From 1f49264ded158e695fa0385d55892da7abca375a Mon Sep 17 00:00:00 2001 From: Jared Males Date: Sat, 21 Sep 2024 23:18:19 -0700 Subject: [PATCH 01/24] fixed bmc segfaults; cleaned up commandDM; adding timing diagnostics --- apps/bmcCtrl/Makefile | 2 +- apps/bmcCtrl/bmcCtrl.hpp | 99 ++++++++++++++++++------------- libMagAOX/app/dev/dm.hpp | 123 ++++++++++++++++++++++++++++++++++++++- 3 files changed, 180 insertions(+), 44 deletions(-) diff --git a/apps/bmcCtrl/Makefile b/apps/bmcCtrl/Makefile index d2f376db5..ae5a22e83 100644 --- a/apps/bmcCtrl/Makefile +++ b/apps/bmcCtrl/Makefile @@ -7,7 +7,7 @@ TARGET=bmcCtrl BMC_PATH=/opt/Boston\ Micromachines LDFLAGS += -L$(BMC_PATH)/lib -Wl,-rpath,$(BMC_PATH)/lib LDLIBS+= -lBMC -lBMC_PCIeAPI -INCLUDES+= -I/$(BMC_PATH)/include +INCLUDES+= -I/$(BMC_PATH)/include -DXWC_DMTIMINGS include ../../Make/magAOXApp.mk diff --git a/apps/bmcCtrl/bmcCtrl.hpp b/apps/bmcCtrl/bmcCtrl.hpp index 9e8fdac73..22e1a7242 100644 --- a/apps/bmcCtrl/bmcCtrl.hpp +++ b/apps/bmcCtrl/bmcCtrl.hpp @@ -23,7 +23,6 @@ Open questions: #ifndef bmcCtrl_hpp #define bmcCtrl_hpp - #include "../../libMagAOX/libMagAOX.hpp" //Note this is included on command line to trigger pch #include "../../magaox_git_version.h" @@ -66,7 +65,9 @@ class bmcCtrl : public MagAOXApp, public dev::dm, public de typedef float realT; ///< This defines the datatype used to signal the DM using the ImageStreamIO library. - + typedef dev::dm dmT; + typedef dev::shmimMonitor shmimMonitorT; + protected: @@ -202,6 +203,8 @@ class bmcCtrl : public MagAOXApp, public dev::dm, public de int get_actuator_mapping(); ///@} + + }; bmcCtrl::bmcCtrl() : MagAOXApp(MAGAOX_CURRENT_SHA1, MAGAOX_REPO_MODIFIED) @@ -261,14 +264,16 @@ int bmcCtrl::appStartup() } dev::dm::appStartup(); + shmimMonitor::appStartup(); - + return 0; } int bmcCtrl::appLogic() { dev::dm::appLogic(); + shmimMonitor::appLogic(); if(state()==stateCodes::POWEROFF) return 0; @@ -276,6 +281,7 @@ int bmcCtrl::appLogic() if(state()==stateCodes::POWERON) { sleep(5); + std::cerr << "initing DM" << std::endl; return initDM(); } @@ -283,6 +289,7 @@ int bmcCtrl::appLogic() { log("Saturated actuators in last second: " + std::to_string(m_nsat), logPrio::LOG_WARNING); } + m_nsat = 0; return 0; @@ -293,6 +300,7 @@ int bmcCtrl::appShutdown() if(m_dmopen) releaseDM(); dev::dm::appShutdown(); + shmimMonitor::appShutdown(); return 0; @@ -437,52 +445,49 @@ int bmcCtrl::commandDM(void * curr_src) /*This loop performs the following steps: 1) converts from float to double 2) convert to volume-normalized displacement - 3) convert to squared fractional voltage (0 to +1) - 4) calculate the mean + 3) convert to squared fractional voltage clamped from 0 to 1. */ + #ifdef XWC_DMTIMINGS + dmT::m_tact0 = mx::sys::get_curr_time(); + #endif - // want to rework the logic here so that we don't have to check - // if every actuator is addressable. - // Loop over addressable only? - //double mean = 0; for (uint32_t idx = 0; idx < m_nbAct; ++idx) { - int address = m_actuator_mapping[idx]; - if(address == -1) - { - m_dminputs[idx] = 0.; // addressable but ignored actuators set to 0 - } - else - { - m_dminputs[idx] = ((double) ((realT *) curr_src)[address]) * m_volume_factor/m_act_gain; - //mean += m_dminputs[idx]; - } - } - //mean /= m_nbAct; - - /*This loop performas the following steps: - 1) remove mean from each actuator input (and add midpoint bias) - 2) clip to fractional values between 0 and 1. - 3) take the square root to approximate the voltage-displacement curve - */ - for (uint32_t idx = 0 ; idx < m_nbAct ; ++idx) - { - //m_dminputs[idx] -= mean - 0.5; - if (m_dminputs[idx] > 1) + int address = m_actuator_mapping[idx]; + if(address == -1) { - ++m_nsat; - m_dminputs[idx] = 1; - } else if (m_dminputs[idx] < 0) + m_dminputs[idx] = 0.; // addressable but ignored actuators set to 0 + } + else { - ++m_nsat; - m_dminputs[idx] = 0; + m_dminputs[idx] = ((double) (static_cast(curr_src)[address])) * m_volume_factor/m_act_gain; + + if (m_dminputs[idx] > 1) + { + m_dminputs[idx] = 1; + } + else if (m_dminputs[idx] < 0) + { + m_dminputs[idx] = 0; + } + else + { + m_dminputs[idx] = sqrt(m_dminputs[idx]); + } } - m_dminputs[idx] = sqrt(m_dminputs[idx]); } - /* Finally, send the command to the DM */ + #ifdef XWC_DMTIMINGS + dmT::m_tact1 = mx::sys::get_curr_time(); + #endif + + /* Send the command to the DM */ BMCRC ret = BMCSetArray(&m_dm, m_dminputs, NULL); + + #ifdef XWC_DMTIMINGS + dmT::m_tact2 = mx::sys::get_curr_time(); + #endif /* Return immediately upon error, logging the error message first and then return the failure code. */ @@ -494,14 +499,22 @@ int bmcCtrl::commandDM(void * curr_src) return -1; } + #ifdef XWC_DMTIMINGS + dmT::m_tact3 = mx::sys::get_curr_time(); + #endif + /* Now update the instantaneous sat map */ for (uint32_t idx = 0; idx < m_nbAct; ++idx) { int address = m_actuator_mapping[idx]; - if(address == -1) continue; - - if(m_dminputs[idx] >= 1 || m_dminputs[idx] <= 0) + + if(address == -1) { + continue; + } + else if(m_dminputs[idx] >= 1 || m_dminputs[idx] <= 0) + { + ++m_nsat; m_instSatMap.data()[address] = 1; } else @@ -510,6 +523,10 @@ int bmcCtrl::commandDM(void * curr_src) } } + #ifdef XWC_DMTIMINGS + dmT::m_tact4 = mx::sys::get_curr_time(); + #endif + return ret; } diff --git a/libMagAOX/app/dev/dm.hpp b/libMagAOX/app/dev/dm.hpp index c93d05b26..7f20253fc 100644 --- a/libMagAOX/app/dev/dm.hpp +++ b/libMagAOX/app/dev/dm.hpp @@ -537,6 +537,32 @@ class dm ///@} +public: + + #ifdef XWC_DMTIMINGS + typedef uint16_t cbIndexT; + + double m_t0 {0}, m_tf {0}, m_tsat0 {0}, m_tsatf {0}; + double m_tact0 {0}, m_tact1 {0}, m_tact2 {0}, m_tact3 {0}, m_tact4 {0}; + + mx::sigproc::circularBufferIndex m_piTimes; + + mx::sigproc::circularBufferIndex m_satSem; + + mx::sigproc::circularBufferIndex m_actProc; + + mx::sigproc::circularBufferIndex m_actCom; + + mx::sigproc::circularBufferIndex m_satUp; + + std::vector m_piTimesD; + std::vector m_satSemD; + std::vector m_actProcD; + std::vector m_actComD; + std::vector m_satUpD; + + #endif + private: derivedT &derived() { @@ -780,7 +806,9 @@ int dm::appStartup() } if (sem_init(&m_satSemaphore, 0, 0) < 0) + { return derivedT::template log({__FILE__, __LINE__, errno, 0, "Initializing sat semaphore"}); + } if (derived().threadStart(m_satThread, m_satThreadInit, m_satThreadID, m_satThreadProp, m_satThreadPrio, "", "saturation", this, satThreadStart) < 0) { @@ -803,6 +831,7 @@ int dm::appLogic() } checkFlats(); + checkTests(); if (m_intervalSatTrip) @@ -811,6 +840,39 @@ int dm::appLogic() m_intervalSatTrip = false; } + #ifdef XWC_DMTIMINGS + static uint64_t lastMono = 0; + + if(m_piTimes.size() >= m_piTimes.maxEntries() && m_piTimes.maxEntries() > 0 && m_piTimes.mono() != lastMono) + { + cbIndexT refEntry = m_piTimes.earliest(); + + m_piTimesD.resize(m_piTimes.maxEntries()); + m_satSemD.resize(m_satSem.maxEntries()); + m_actProcD.resize(m_actProc.maxEntries()); + m_actComD.resize(m_actCom.maxEntries()); + m_satUpD.resize(m_satUp.maxEntries()); + + for(size_t n=0; n <= m_piTimesD.size(); ++n) + { + m_piTimesD[n] = m_piTimes.at(refEntry,n); + m_satSemD[n] = m_satSem.at(refEntry,n); + m_actProcD[n] = m_actProc.at(refEntry,n); + m_actComD[n] = m_actCom.at(refEntry,n); + m_satUpD[n] = m_satUp.at(refEntry,n); + } + + std::cerr << "Act. Process: " << mx::math::vectorMean(m_actProcD) << " +/- " << sqrt(mx::math::vectorVariance(m_actProcD)) << "\n"; + std::cerr << "Act. Command: " << mx::math::vectorMean(m_actComD) << " +/- " << sqrt(mx::math::vectorVariance(m_actComD)) << "\n"; + std::cerr << "Sat. Update: " << mx::math::vectorMean(m_satUpD) << " +/- " << sqrt(mx::math::vectorVariance(m_satUpD)) << "\n"; + std::cerr << "Tot. CommandDM: " << mx::math::vectorMean(m_piTimesD) << " +/- " << sqrt(mx::math::vectorVariance(m_piTimesD)) << "\n"; + std::cerr << "Sat. Semaphore: " << mx::math::vectorMean(m_satSemD) << " +/- " << sqrt(mx::math::vectorVariance(m_satSemD)) << "\n"; + std::cerr << "\n"; + + lastMono = m_piTimes.mono(); + } + #endif //XWC_DMTIMINGS + return 0; } @@ -836,6 +898,7 @@ template int dm::onPowerOff() { releaseDM(); + return 0; } @@ -928,6 +991,14 @@ int dm::allocate(const dev::shmimT &sp) return -1; } + #ifdef XWC_DMTIMINGS + m_piTimes.maxEntries(2000); + m_satSem.maxEntries(2000); + m_actProc.maxEntries(2000); + m_actCom.maxEntries(2000); + m_satUp.maxEntries(2000); + #endif + return 0; } @@ -937,13 +1008,26 @@ int dm::processImage(void *curr_src, { static_cast(sp); // be unused + #ifdef XWC_DMTIMINGS + m_t0 = mx::sys::get_curr_time(); + #endif + int rv = derived().commandDM(curr_src); + #ifdef XWC_DMTIMINGS + m_tf = mx::sys::get_curr_time(); + #endif + if (rv < 0) { derivedT::template log({__FILE__, __LINE__, errno, rv, "Error from commandDM"}); return rv; } + + #ifdef XWC_DMTIMINGS + m_tsat0 = mx::sys::get_curr_time(); + #endif + // Tell the sat thread to get going if (sem_post(&m_satSemaphore) < 0) { @@ -951,6 +1035,21 @@ int dm::processImage(void *curr_src, return -1; } + #ifdef XWC_DMTIMINGS + m_tsatf = mx::sys::get_curr_time(); + #endif + + #ifdef XWC_DMTIMINGS + //Update the latency circ. buffs + if(m_piTimes.maxEntries() > 0) + { + m_piTimes.nextEntry(m_tf-m_t0); + m_satSem.nextEntry(m_tsatf - m_tsat0); + m_actProc.nextEntry(m_tact1 - m_tact0); + m_actCom.nextEntry(m_tact2 - m_tact1); + m_satUp.nextEntry(m_tact4 - m_tact3); + } + #endif return rv; } @@ -972,6 +1071,7 @@ int dm::releaseDM() return 0; } + template int dm::checkFlats() { @@ -1637,7 +1737,9 @@ template int dm::zeroAll(bool nosem) { if (derived().m_shmimName == "") + { return 0; + } IMAGE imageStream; @@ -1712,8 +1814,10 @@ int dm::zeroAll(bool nosem) template int dm::clearSat() { - if (m_shmimSat == "") + if(m_shmimSat == "" || m_dmWidth == 0 || m_dmHeight == 0) + { return 0; + } IMAGE imageStream; @@ -1746,7 +1850,7 @@ int dm::clearSat() } imageStream.md->write = 1; - memset(imageStream.array.raw, 0, m_dmWidth * m_dmHeight * sizeof(realT)); + memset(imageStream.array.raw, 0, m_dmWidth * m_dmHeight * sizeof(uint8_t)); clock_gettime(CLOCK_REALTIME, &imageStream.md->writetime); @@ -1792,8 +1896,11 @@ void dm::satThreadExec() { sleep(1); } + if (derived().shutdown()) + { return; + } imsize[0] = m_dmWidth; imsize[1] = m_dmHeight; @@ -1840,7 +1947,9 @@ void dm::satThreadExec() // If less than avg int --> go back and wait again if (mx::sys::get_curr_time(ts) - t_accumst < m_satAvgInt / 1000.0) + { continue; + } // If greater than avg int --> calc stats, write to streams. m_overSatAct = 0; @@ -1850,7 +1959,9 @@ void dm::satThreadExec() { m_satPercMap(rr, cc) = m_accumSatMap(rr, cc) / naccum; if (m_satPercMap(rr, cc) >= m_percThreshold) + { ++m_overSatAct; + } satmap(rr, cc) = (m_accumSatMap(rr, cc) > 0); // it's 1/0 map } } @@ -1858,13 +1969,19 @@ void dm::satThreadExec() // Check of the number of actuators saturated above the percent threshold is greater than the number threshold // if it is, increment the counter if (m_overSatAct / (m_satPercMap.rows() * m_satPercMap.cols() * 0.75) > m_intervalSatThreshold) + { ++m_intervalSatExceeds; + } else + { m_intervalSatExceeds = 0; + } // If enough consecutive intervals exceed the count threshold, we trigger if (m_intervalSatExceeds >= m_intervalSatCountThreshold) + { m_intervalSatTrip = true; + } m_satImageStream.md->write = 1; m_satPercImageStream.md->write = 1; @@ -1911,7 +2028,9 @@ void dm::satThreadExec() { // Check for why we timed out if (errno == EINTR) + { break; // This indicates signal interrupted us, time to restart or shutdown, loop will exit normally if flags set. + } // ETIMEDOUT just means we should wait more. // Otherwise, report an error. From 617f61238257a34906646f8fea24106283386ad9 Mon Sep 17 00:00:00 2001 From: "Jared R. Males" Date: Sun, 22 Sep 2024 11:34:09 -0700 Subject: [PATCH 02/24] Update dm.hpp to fix OOB loop --- libMagAOX/app/dev/dm.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libMagAOX/app/dev/dm.hpp b/libMagAOX/app/dev/dm.hpp index 7f20253fc..a6a1afd00 100644 --- a/libMagAOX/app/dev/dm.hpp +++ b/libMagAOX/app/dev/dm.hpp @@ -853,7 +853,7 @@ int dm::appLogic() m_actComD.resize(m_actCom.maxEntries()); m_satUpD.resize(m_satUp.maxEntries()); - for(size_t n=0; n <= m_piTimesD.size(); ++n) + for(size_t n=0; n < m_piTimesD.size(); ++n) { m_piTimesD[n] = m_piTimes.at(refEntry,n); m_satSemD[n] = m_satSem.at(refEntry,n); From 83f9bc69cb768b48ab1fa849049da263f64ecfbe Mon Sep 17 00:00:00 2001 From: jrmales Date: Wed, 2 Oct 2024 14:08:15 -0400 Subject: [PATCH 03/24] updated ICC cpusets; updating for multi-picos --- apps/picoMotorCtrl/picoMotorCtrl.hpp | 120 +++++++++- rtSetup/ICC/make_cpusets | 313 ++++++++++++++------------- 2 files changed, 271 insertions(+), 162 deletions(-) diff --git a/apps/picoMotorCtrl/picoMotorCtrl.hpp b/apps/picoMotorCtrl/picoMotorCtrl.hpp index 2fe4de042..45151425b 100644 --- a/apps/picoMotorCtrl/picoMotorCtrl.hpp +++ b/apps/picoMotorCtrl/picoMotorCtrl.hpp @@ -34,6 +34,50 @@ namespace MagAOX namespace app { +int splitResponse( int & address, + std::string & response, + const std::string & fullResponse + ) +{ + size_t carrot = fullResponse.find('>'); + + if(carrot == std::string::npos) + { + address = 1; + response = fullResponse; + return 0; + } + + if(carrot == 0) + { + address = 0; + response = ""; + return -1; + } + + if(carrot == fullResponse.size()-1) + { + address = 0; + response = ""; + return -2; + } + + try + { + address = std::stoi( fullResponse.substr(0,carrot)); + response = fullResponse.substr(carrot+1); + } + catch(...) + { + address = 0; + response = ""; + return -3; + } + + return 0; + +} + /** MagAO-X application to control a multi-channel Newport Picomotor Controller. * * \todo need to recognize signals in tty polls and not return errors, etc. @@ -55,14 +99,16 @@ class picoMotorCtrl : public MagAOXApp<>, public dev::ioDevice, public dev::tele struct motorChannel { picoMotorCtrl * m_parent {nullptr}; ///< A pointer to this for thread starting. - + std::string m_name; ///< The name of this channel, from the config section - + + int m_address {1}; ///< The controller address. + + int m_channel {-1}; ///< The number of this channel, where the motor is plugged in + std::vector m_presetNames; std::vector m_presetPositions; - - int m_channel {-1}; ///< The number of this channel, where the motor is plugged in - + posT m_currCounts {0}; ///< The current counts, the cumulative position bool m_doMove {false}; ///< Flag indicating that a move is requested. @@ -86,8 +132,9 @@ class picoMotorCtrl : public MagAOXApp<>, public dev::ioDevice, public dev::tele motorChannel( picoMotorCtrl * p, ///< [in] The parent point to set const std::string & n, ///< [in] The name of this channel + int add, ///< [in] The controller address int ch ///< [in] The number of this channel - ) : m_parent(p), m_name(n), m_channel(ch) + ) : m_parent(p), m_name(n), m_address(add), m_channel(ch) { m_thread = new std::thread; } @@ -107,6 +154,8 @@ class picoMotorCtrl : public MagAOXApp<>, public dev::ioDevice, public dev::tele ///@} + std::vector m_addresses; ///< The unique controller addresses. + channelMapT m_channels; ///< Map of motor names to channel. tty::telnetConn m_telnetConn; ///< The telnet connection manager @@ -301,13 +350,24 @@ int picoMotorCtrl::loadConfigImpl( mx::app::appConfigurator & _config ) if(channel < 1 || channel > m_nChannels) { - log("Bad channel specificiation: " + sections[i] + " " + std::to_string(channel), logPrio::LOG_CRITICAL); + log("Bad channel specificiation: " + sections[i] + " channel: " + std::to_string(channel), logPrio::LOG_CRITICAL); + + return PICOMOTORCTRL_E_BADCHANNEL; + } + + int address = 1; + _config.configUnused(address, mx::app::iniFile::makeKey(sections[i], "address" ) ); + + if(address < 1) + { + log("Bad channel specificiation: " + sections[i] + " address: " + std::to_string(address), logPrio::LOG_CRITICAL); return PICOMOTORCTRL_E_BADCHANNEL; } + //Ok, valid channel. Insert into map and check for duplicates. - std::pair insert = m_channels.insert(std::pair(sections[i], motorChannel(this,sections[i],channel))); + std::pair insert = m_channels.insert(std::pair(sections[i], motorChannel(this,sections[i], address, channel))); if(insert.second == false) { @@ -320,7 +380,23 @@ int picoMotorCtrl::loadConfigImpl( mx::app::appConfigurator & _config ) _config.configUnused(insert.first->second.m_presetPositions, mx::app::iniFile::makeKey(sections[i], "positions" )); } + ///\todo extend to include address log({sections[i], (uint8_t) channel}); + + bool found = false; + for(size_t n = 0; n < m_addresses.size(); ++n) + { + if(address == m_addresses[n]) + { + found = true; + break; + } + } + + if(!found) + { + m_addresses.push_back(address); + } } return 0; @@ -583,7 +659,7 @@ int picoMotorCtrl::appLogic() { std::unique_lock lock(m_telnetMutex); - std::string query = std::to_string(it->second.m_channel) + "MD?"; + std::string query = std::to_string(it->second.m_address) + ">" + std::to_string(it->second.m_channel) + "MD?"; int rv = m_telnetConn.write(query + "\r\n", m_writeTimeout); if(rv != TTY_E_NOERROR) @@ -603,8 +679,28 @@ int picoMotorCtrl::appLogic() return 0; } + int add; + std::string resp; + + rv = splitResponse(add, resp, m_telnetConn.m_strRead); + if(rv != 0) + { + if(powerState() != 1 || powerStateTarget() != 1) return 0; + log({__FILE__, __LINE__, "splitResponse returned " + std::to_string(rv)}); + state(stateCodes::ERROR); + return 0; + } + + if(add != it->second.m_address) + { + if(powerState() != 1 || powerStateTarget() != 1) return 0; + log({__FILE__, __LINE__, "address did not match in response"}); + state(stateCodes::ERROR); + return 0; + } + //The check for moving here. With power off detection - if(std::stoi(m_telnetConn.m_strRead) == 0) + if(std::stoi(resp) == 0) { anymoving = true; it->second.m_moving = true; @@ -786,8 +882,8 @@ void picoMotorCtrl::channelThreadExec( motorChannel * mc) mc->m_moving = true; log("moving " + mc->m_name + " by " + std::to_string(dr) + " counts"); - std::string comm = std::to_string(mc->m_channel) + "PR" + std::to_string(dr); - + std::string comm = std::to_string(mc->m_address) + ">" + std::to_string(mc->m_channel) + "PR" + std::to_string(dr); + int rv = m_telnetConn.write(comm + "\r\n", m_writeTimeout); if(rv != TTY_E_NOERROR) { diff --git a/rtSetup/ICC/make_cpusets b/rtSetup/ICC/make_cpusets index c365a2d7f..d5fe78134 100644 --- a/rtSetup/ICC/make_cpusets +++ b/rtSetup/ICC/make_cpusets @@ -6,68 +6,28 @@ ## See https://linux.die.net/man/7/cpuset ## ## Run this as sudo at startup of the system -## Then run icc_procset after starting all loop processes +## Then run rtc_procset after starting all loop processes ## #################################################### source /etc/profile.d/cgroups1_cpuset_mountpoint.sh cpusetMount=$CGROUPS1_CPUSET_MOUNTPOINT -# On ICC (v2) we have 2x18 = 36 real cores, which maps to 72 cpus -# To see the list: cat /proc/cpuinfo | egrep 'processor|physical id|core id' -# Each row in this table corresponds to a real core, and two logical processors. -# -# processor physical-id core-id processor physical-id core-id -# 0 0 0 36 0 0 -# 1 0 1 37 0 1 -# 2 0 2 38 0 2 -# 3 0 3 39 0 3 -# 4 0 4 40 0 4 -# 5 0 8 41 0 8 -# 6 0 9 42 0 9 -# 7 0 10 43 0 10 -# 8 0 11 44 0 11 -# 9 0 16 45 0 16 -# 10 0 17 46 0 17 -# 11 0 18 47 0 18 -# 12 0 19 48 0 19 -# 13 0 20 49 0 20 -# 14 0 24 50 0 24 -# 15 0 25 51 0 25 -# 16 0 26 52 0 26 -# 17 0 27 53 0 27 -# 18 1 0 54 1 0 -# 19 1 1 55 1 1 -# 20 1 2 56 1 2 -# 21 1 3 57 1 3 -# 22 1 4 58 1 4 -# 23 1 8 59 1 8 -# 24 1 9 60 1 9 -# 25 1 10 61 1 10 -# 26 1 11 62 1 11 -# 27 1 16 63 1 16 -# 28 1 17 64 1 17 -# 29 1 18 65 1 18 -# 30 1 19 66 1 19 -# 31 1 20 67 1 20 -# 32 1 24 68 1 24 -# 33 1 25 69 1 25 -# 34 1 26 70 1 26 -# 35 1 27 71 1 27 +# RTC w/ AMD Threadripper 64 core / 128 threads set -xeuo pipefail -#First enable everybody -for cpu in {0..71} +# we will use processors 0-31 and 64-95 as the hyperthread system cpus (32 cores, 64 threads), +# so we disable processors 96-127. This leaves us 32-63 (32) as single thread r/t processors. + +#enable everything first just to start from a known state +for cpu in {1..127} do - /bin/echo 1 > /sys/devices/system/cpu/cpu$cpu/online + /bin/echo 1 > /sys/devices/system/cpu/cpu$cpu/online done -# we will use processors 0-13 and 36-49 as the hyperthread system cpus (28), -# so we disable processors 50-71. This leaves us 14-35 (22) as single thread processors. - -# Disable processors 50-71 -for cpu in {50..71} +# Disable processors 96-127, the hardware threads +for cpu in {96..127} do /bin/echo 0 > /sys/devices/system/cpu/cpu$cpu/online done @@ -79,8 +39,8 @@ cd $cpusetMount # ############################ mkdir -p $cpusetMount/system -/bin/echo 0-13,36-49 > $cpusetMount/system/cpuset.cpus -/bin/echo 0-1 > $cpusetMount/system/cpuset.mems +/bin/echo 0-31,64-95 > $cpusetMount/system/cpuset.cpus +/bin/echo 0 > $cpusetMount/system/cpuset.mems # Now move all current tasks to system cpuset # Note that this moves pid=1 (init) so all new process created should live here. @@ -96,148 +56,201 @@ echo 0 > cpuset.sched_load_balance echo 1 > system/cpuset.sched_load_balance ############### -# Now setup cpusets for the ICC R/T processes -# We have cores 14-35 (22 cores) to use. +# Now setup cpusets for the RTC R/T processes ############### -## NCPC DM #dm02comb mkdir -p $cpusetMount/dm02comb -/bin/echo 14 > $cpusetMount/dm02comb/cpuset.cpus +/bin/echo 32 > $cpusetMount/dm02comb/cpuset.cpus /bin/echo 1 > $cpusetMount/dm02comb/cpuset.cpu_exclusive -/bin/echo 0-1 > $cpusetMount/dm02comb/cpuset.mems +/bin/echo 0 > $cpusetMount/dm02comb/cpuset.mems #ncpc mkdir -p $cpusetMount/ncpc -/bin/echo 15 > $cpusetMount/ncpc/cpuset.cpus +/bin/echo 33 > $cpusetMount/ncpc/cpuset.cpus /bin/echo 1 > $cpusetMount/ncpc/cpuset.cpu_exclusive -/bin/echo 0-1 > $cpusetMount/ncpc/cpuset.mems - -## camlowfs - -#camlowfs -mkdir -p $cpusetMount/camlowfs -/bin/echo 16 > $cpusetMount/camlowfs/cpuset.cpus -/bin/echo 1 > $cpusetMount/camlowfs/cpuset.cpu_exclusive -/bin/echo 0-1 > $cpusetMount/camlowfs/cpuset.mems - -#camlowfs_sw -mkdir -p $cpusetMount/camlowfs_sw -/bin/echo 17 > $cpusetMount/camlowfs_sw/cpuset.cpus -/bin/echo 1 > $cpusetMount/camlowfs_sw/cpuset.cpu_exclusive -/bin/echo 0-1 > $cpusetMount/camlowfs_sw/cpuset.mems +/bin/echo 0 > $cpusetMount/ncpc/cpuset.mems + +#camflowfs +mkdir -p $cpusetMount/camflowfs +/bin/echo 34 > $cpusetMount/camflowfs/cpuset.cpus +/bin/echo 1 > $cpusetMount/camflowfs/cpuset.cpu_exclusive +/bin/echo 0 > $cpusetMount/camflowfs/cpuset.mems + +#camflowfs_sw +mkdir -p $cpusetMount/camflowfs_sw +/bin/echo 35 > $cpusetMount/camflowfs_sw/cpuset.cpus +/bin/echo 1 > $cpusetMount/camflowfs_sw/cpuset.cpu_exclusive +/bin/echo 0 > $cpusetMount/camflowfs_sw/cpuset.mems + +#camllowfs +mkdir -p $cpusetMount/camllowfs +/bin/echo 36 > $cpusetMount/camllowfs/cpuset.cpus +/bin/echo 1 > $cpusetMount/camllowfs/cpuset.cpu_exclusive +/bin/echo 0 > $cpusetMount/camllowfs/cpuset.mems + +#camllowfs_sw +mkdir -p $cpusetMount/camllowfs_sw +/bin/echo 37 > $cpusetMount/camllowfs_sw/cpuset.cpus +/bin/echo 1 > $cpusetMount/camllowfs_sw/cpuset.cpu_exclusive +/bin/echo 0 > $cpusetMount/camllowfs_sw/cpuset.mems -## camsci1 #camsci1 mkdir -p $cpusetMount/camsci1 -/bin/echo 18 > $cpusetMount/camsci1/cpuset.cpus +/bin/echo 38 > $cpusetMount/camsci1/cpuset.cpus /bin/echo 1 > $cpusetMount/camsci1/cpuset.cpu_exclusive -/bin/echo 0-1 > $cpusetMount/camsci1/cpuset.mems +/bin/echo 0 > $cpusetMount/camsci1/cpuset.mems #camsci1_sw mkdir -p $cpusetMount/camsci1_sw -/bin/echo 19 > $cpusetMount/camsci1_sw/cpuset.cpus +/bin/echo 39 > $cpusetMount/camsci1_sw/cpuset.cpus /bin/echo 1 > $cpusetMount/camsci1_sw/cpuset.cpu_exclusive -/bin/echo 0-1 > $cpusetMount/camsci1_sw/cpuset.mems +/bin/echo 0 > $cpusetMount/camsci1_sw/cpuset.mems -## camsci2 #camsci2 mkdir -p $cpusetMount/camsci2 -/bin/echo 20 > $cpusetMount/camsci2/cpuset.cpus +/bin/echo 40 > $cpusetMount/camsci2/cpuset.cpus /bin/echo 1 > $cpusetMount/camsci2/cpuset.cpu_exclusive -/bin/echo 0-1 > $cpusetMount/camsci2/cpuset.mems +/bin/echo 0 > $cpusetMount/camsci2/cpuset.mems -#camsci2_sw +#camsci2_sw offload process mkdir -p $cpusetMount/camsci2_sw -/bin/echo 21 > $cpusetMount/camsci2_sw/cpuset.cpus +/bin/echo 41 > $cpusetMount/camsci2_sw/cpuset.cpus /bin/echo 1 > $cpusetMount/camsci2_sw/cpuset.cpu_exclusive -/bin/echo 0-1 > $cpusetMount/camsci2_sw/cpuset.mems - -#spare22 -mkdir -p $cpusetMount/spare22 -/bin/echo 22 > $cpusetMount/spare22/cpuset.cpus -/bin/echo 1 > $cpusetMount/spare22/cpuset.cpu_exclusive -/bin/echo 0-1 > $cpusetMount/spare22/cpuset.mems - -#spare23 -mkdir -p $cpusetMount/spare23 -/bin/echo 23 > $cpusetMount/spare23/cpuset.cpus -/bin/echo 1 > $cpusetMount/spare23/cpuset.cpu_exclusive -/bin/echo 0-1 > $cpusetMount/spare23/cpuset.mems - -## CACAO +/bin/echo 0 > $cpusetMount/camsci2_sw/cpuset.mems + +#camlowfs_fit +mkdir -p $cpusetMount/camlowfs_fit +/bin/echo 42 > $cpusetMount/camlowfs_fit/cpuset.cpus +/bin/echo 1 > $cpusetMount/camlowfs_fit/cpuset.cpu_exclusive +/bin/echo 0 > $cpusetMount/camlowfs_fit/cpuset.mems + +#spare43 +mkdir -p $cpusetMount/spare43 +/bin/echo 43 > $cpusetMount/spare43/cpuset.cpus +/bin/echo 1 > $cpusetMount/spare43/cpuset.cpu_exclusive +/bin/echo 0 > $cpusetMount/spare43/cpuset.mems + +#spare44 +mkdir -p $cpusetMount/spare44 +/bin/echo 44 > $cpusetMount/spare44/cpuset.cpus +/bin/echo 1 > $cpusetMount/spare44/cpuset.cpu_exclusive +/bin/echo 0 > $cpusetMount/spare44/cpuset.mems #acqu_mvm mkdir -p $cpusetMount/acqu_mvm -/bin/echo 24 > $cpusetMount/acqu_mvm/cpuset.cpus +/bin/echo 45 > $cpusetMount/acqu_mvm/cpuset.cpus /bin/echo 1 > $cpusetMount/acqu_mvm/cpuset.cpu_exclusive -/bin/echo 0-1 > $cpusetMount/acqu_mvm/cpuset.mems +/bin/echo 0 > $cpusetMount/acqu_mvm/cpuset.mems #mfilt mkdir -p $cpusetMount/mfilt -/bin/echo 25 > $cpusetMount/mfilt/cpuset.cpus +/bin/echo 46 > $cpusetMount/mfilt/cpuset.cpus /bin/echo 1 > $cpusetMount/mfilt/cpuset.cpu_exclusive -/bin/echo 0-1 > $cpusetMount/mfilt/cpuset.mems +/bin/echo 0 > $cpusetMount/mfilt/cpuset.mems + +#spare47 +mkdir -p $cpusetMount/spare47 +/bin/echo 47 > $cpusetMount/spare47/cpuset.cpus +/bin/echo 1 > $cpusetMount/spare47/cpuset.cpu_exclusive +/bin/echo 0 > $cpusetMount/spare47/cpuset.mems #mlat mkdir -p $cpusetMount/mlat -/bin/echo 26 > $cpusetMount/mlat/cpuset.cpus +/bin/echo 48 > $cpusetMount/mlat/cpuset.cpus /bin/echo 1 > $cpusetMount/mlat/cpuset.cpu_exclusive -/bin/echo 0-1 > $cpusetMount/mlat/cpuset.mems +/bin/echo 0 > $cpusetMount/mlat/cpuset.mems #RTmon mkdir -p $cpusetMount/RTmon -/bin/echo 27 > $cpusetMount/RTmon/cpuset.cpus +/bin/echo 49 > $cpusetMount/RTmon/cpuset.cpus /bin/echo 1 > $cpusetMount/RTmon/cpuset.cpu_exclusive -/bin/echo 0-1 > $cpusetMount/RTmon/cpuset.mems +/bin/echo 0 > $cpusetMount/RTmon/cpuset.mems + +#dm02disp03_sw +mkdir -p $cpusetMount/dm02disp03_sw +/bin/echo 50 > $cpusetMount/dm02disp03_sw/cpuset.cpus +/bin/echo 1 > $cpusetMount/dm02disp03_sw/cpuset.cpu_exclusive +/bin/echo 0 > $cpusetMount/dm02disp03_sw/cpuset.mems + +#dm02disp04_sw +mkdir -p $cpusetMount/dm02disp04_sw +/bin/echo 51 > $cpusetMount/dm02disp04_sw/cpuset.cpus +/bin/echo 1 > $cpusetMount/dm02disp04_sw/cpuset.cpu_exclusive +/bin/echo 0 > $cpusetMount/dm02disp04_sw/cpuset.mems + +#dm02disp08_sw +mkdir -p $cpusetMount/dm02disp08_sw +/bin/echo 52 > $cpusetMount/dm02disp08_sw/cpuset.cpus +/bin/echo 1 > $cpusetMount/dm02disp08_sw/cpuset.cpu_exclusive +/bin/echo 0 > $cpusetMount/dm02disp08_sw/cpuset.mems + +#spare53 +mkdir -p $cpusetMount/spare53 +/bin/echo 53 > $cpusetMount/spare53/cpuset.cpus +/bin/echo 1 > $cpusetMount/spare53/cpuset.cpu_exclusive +/bin/echo 0 > $cpusetMount/spare53/cpuset.mems + +#spare54 +mkdir -p $cpusetMount/spare54 +/bin/echo 54 > $cpusetMount/spare54/cpuset.cpus +/bin/echo 1 > $cpusetMount/spare54/cpuset.cpu_exclusive +/bin/echo 0 > $cpusetMount/spare54/cpuset.mems + +#spare55 +mkdir -p $cpusetMount/spare55 +/bin/echo 55 > $cpusetMount/spare55/cpuset.cpus +/bin/echo 1 > $cpusetMount/spare55/cpuset.cpu_exclusive +/bin/echo 0 > $cpusetMount/spare55/cpuset.mems + +#spare56 +mkdir -p $cpusetMount/spare56 +/bin/echo 56 > $cpusetMount/spare56/cpuset.cpus +/bin/echo 1 > $cpusetMount/spare56/cpuset.cpu_exclusive +/bin/echo 0 > $cpusetMount/spare56/cpuset.mems + +#spare57 +mkdir -p $cpusetMount/spare57 +/bin/echo 57 > $cpusetMount/spare57/cpuset.cpus +/bin/echo 1 > $cpusetMount/spare57/cpuset.cpu_exclusive +/bin/echo 0 > $cpusetMount/spare57/cpuset.mems #shmimTCP mkdir -p $cpusetMount/shmimTCP -/bin/echo 28 > $cpusetMount/shmimTCP/cpuset.cpus +/bin/echo 58 > $cpusetMount/shmimTCP/cpuset.cpus /bin/echo 1 > $cpusetMount/shmimTCP/cpuset.cpu_exclusive -/bin/echo 0-1 > $cpusetMount/shmimTCP/cpuset.mems - -#spare29 -mkdir -p $cpusetMount/spare29 -/bin/echo 29 > $cpusetMount/spare29/cpuset.cpus -/bin/echo 1 > $cpusetMount/spare29/cpuset.cpu_exclusive -/bin/echo 0-1 > $cpusetMount/spare29/cpuset.mems - -#spare30 -mkdir -p $cpusetMount/spare30 -/bin/echo 30 > $cpusetMount/spare30/cpuset.cpus -/bin/echo 1 > $cpusetMount/spare30/cpuset.cpu_exclusive -/bin/echo 0-1 > $cpusetMount/spare30/cpuset.mems - -#spare31 -mkdir -p $cpusetMount/spare31 -/bin/echo 31 > $cpusetMount/spare31/cpuset.cpus -/bin/echo 1 > $cpusetMount/spare31/cpuset.cpu_exclusive -/bin/echo 0-1 > $cpusetMount/spare31/cpuset.mems - -#spare32 -mkdir -p $cpusetMount/spare32 -/bin/echo 32 > $cpusetMount/spare32/cpuset.cpus -/bin/echo 1 > $cpusetMount/spare32/cpuset.cpu_exclusive -/bin/echo 0-1 > $cpusetMount/spare32/cpuset.mems - -#spare33 -mkdir -p $cpusetMount/spare33 -/bin/echo 33 > $cpusetMount/spare33/cpuset.cpus -/bin/echo 1 > $cpusetMount/spare33/cpuset.cpu_exclusive -/bin/echo 0-1 > $cpusetMount/spare33/cpuset.mems - -#spare34 -mkdir -p $cpusetMount/spare34 -/bin/echo 34 > $cpusetMount/spare34/cpuset.cpus -/bin/echo 1 > $cpusetMount/spare34/cpuset.cpu_exclusive -/bin/echo 0-1 > $cpusetMount/spare34/cpuset.mems - -#spare35 -mkdir -p $cpusetMount/spare35 -/bin/echo 35 > $cpusetMount/spare35/cpuset.cpus -/bin/echo 1 > $cpusetMount/spare35/cpuset.cpu_exclusive -/bin/echo 0-1 > $cpusetMount/spare35/cpuset.mems +/bin/echo 0 > $cpusetMount/shmimTCP/cpuset.mems + +#dm02disp09_sw +mkdir -p $cpusetMount/dm02disp09_sw +/bin/echo 59 > $cpusetMount/dm02disp09_sw/cpuset.cpus +/bin/echo 1 > $cpusetMount/dm02disp09_sw/cpuset.cpu_exclusive +/bin/echo 0 > $cpusetMount/dm02disp09_sw/cpuset.mems + +#dm02disp_sw +mkdir -p $cpusetMount/dm02disp_sw +/bin/echo 60 > $cpusetMount/dm02disp_sw/cpuset.cpus +/bin/echo 1 > $cpusetMount/dm02disp_sw/cpuset.cpu_exclusive +/bin/echo 0 > $cpusetMount/dm02disp_sw/cpuset.mems + +#spare61 +mkdir -p $cpusetMount/spare61 +/bin/echo 61 > $cpusetMount/spare61/cpuset.cpus +/bin/echo 1 > $cpusetMount/spare61/cpuset.cpu_exclusive +/bin/echo 0 > $cpusetMount/spare61/cpuset.mems + +#spare62 +mkdir -p $cpusetMount/spare62 +/bin/echo 62 > $cpusetMount/spare62/cpuset.cpus +/bin/echo 1 > $cpusetMount/spare62/cpuset.cpu_exclusive +/bin/echo 0 > $cpusetMount/spare62/cpuset.mems + +#spare63 +mkdir -p $cpusetMount/spare63 +/bin/echo 63 > $cpusetMount/spare63/cpuset.cpus +/bin/echo 1 > $cpusetMount/spare63/cpuset.cpu_exclusive +/bin/echo 0 > $cpusetMount/spare63/cpuset.mems + echo "cpusets configured successfully" From 67d35f51211ecef4bb9e8fee32844e314697b8a1 Mon Sep 17 00:00:00 2001 From: jrmales Date: Wed, 2 Oct 2024 18:34:58 -0400 Subject: [PATCH 04/24] fixed build on ICC --- INDI/liblilxml/Makefile | 4 ++-- Make/common.mk | 1 - 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/INDI/liblilxml/Makefile b/INDI/liblilxml/Makefile index 5dc3cb2d8..4c83da71e 100644 --- a/INDI/liblilxml/Makefile +++ b/INDI/liblilxml/Makefile @@ -10,9 +10,9 @@ SELF_DIR := $(abspath $(dir $(lastword $(MAKEFILE_LIST)))) include $(SELF_DIR)/../../Make/common.mk -CFLAGS= +CFLAGS=-fPIC all: liblilxml.a - $(CC) -shared -Wl,-soname,liblilxml.so -o liblilxml.so lilxml*.o -rdynamic + $(CC) -shared -Wl,-soname,liblilxml.so -o liblilxml.so lilxml*.o -rdynamic install: all sudo install -d $(LIB_PATH) diff --git a/Make/common.mk b/Make/common.mk index 4ea2b7044..9a9f1ad8b 100644 --- a/Make/common.mk +++ b/Make/common.mk @@ -19,7 +19,6 @@ EDT ?= false PYLON ?= false PICAM ?= false ifeq ($(MAGAOX_ROLE),ICC) - EDT = true PYLON = true PICAM = true else From b84cae9e8bd29fe2c0820d2e0acad8f72455f049 Mon Sep 17 00:00:00 2001 From: Jared Males Date: Thu, 3 Oct 2024 09:30:30 -0700 Subject: [PATCH 05/24] make oob protection safer in sat map --- libMagAOX/app/dev/dm.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libMagAOX/app/dev/dm.hpp b/libMagAOX/app/dev/dm.hpp index 7f20253fc..4a10d1581 100644 --- a/libMagAOX/app/dev/dm.hpp +++ b/libMagAOX/app/dev/dm.hpp @@ -1850,7 +1850,7 @@ int dm::clearSat() } imageStream.md->write = 1; - memset(imageStream.array.raw, 0, m_dmWidth * m_dmHeight * sizeof(uint8_t)); + memset(imageStream.array.raw, 0, m_dmWidth * m_dmHeight * ImageStreamIO_typesize(imageStream.md->datatype)); clock_gettime(CLOCK_REALTIME, &imageStream.md->writetime); From 68b9cec3e1b34f94927cfd4f21f9d60ecd17d9ce Mon Sep 17 00:00:00 2001 From: jrmales Date: Thu, 3 Oct 2024 11:30:33 -0400 Subject: [PATCH 06/24] updated RT configs --- rtSetup/ICC/irqbalance | 12 ++++++------ rtSetup/ICC/irqbalance_policyscript | 8 ++++---- rtSetup/ICC/move_irqs | 23 ++++++++++++++++++++++- rtSetup/RTC/irqbalance | 13 ++++++------- rtSetup/RTC/irqbalance_policyscript | 9 +++------ rtSetup/RTC/move_irqs | 16 +++++++++++++++- 6 files changed, 56 insertions(+), 25 deletions(-) diff --git a/rtSetup/ICC/irqbalance b/rtSetup/ICC/irqbalance index d87d60116..9a45e636e 100644 --- a/rtSetup/ICC/irqbalance +++ b/rtSetup/ICC/irqbalance @@ -1,9 +1,9 @@ -####################################### -# MagAO-X irqbalance configuration +############################################ +# MagAO-X irqbalance configuration for ICC # -# Edit the IRQBALANCE_BANNED_CPUS bitmask to match the r/t cpusets created in rtc_cpuset +# Edit the IRQBALANCE_BANNED_CPUS bitmask to match the r/t cpusets created in make_cpusets # -# Edit the IRQBALANCE_ARGS list of args to add a --banirq=x for each irq x you want to prevent being balanced +# Edit the irqbalance_policyscript to include IRQs to ban # # To Install: # @@ -31,8 +31,8 @@ # # IRQBALANCE_BANNED_CPUS # -# For ICC currently bans 8-31 and 40-63 (which are the h/t pairs) -IRQBALANCE_BANNED_CPULIST=8-31,40-63 +# For RTC this is 128 bits. Currently bans 32-63 and 96-127 (which are the h/t pairs) +IRQBALANCE_BANNED_CPULIST=32-63,96-127 # # IRQBALANCE_ARGS diff --git a/rtSetup/ICC/irqbalance_policyscript b/rtSetup/ICC/irqbalance_policyscript index 522309086..eb7de93d6 100755 --- a/rtSetup/ICC/irqbalance_policyscript +++ b/rtSetup/ICC/irqbalance_policyscript @@ -7,14 +7,14 @@ # # Driver names are actually patterns, i.e. enx matches enx2cfda1c6db1a. -#edt: any EDT gramegrabber #nvidia: any NVIDIA GPU #enx503eaa0ceeff: ICC camsci1 #enx503eaa0cf4cd: ICC camsci2 -#enx6cb31152a245: ICC icc-to-rtc -#cp2x73c: ? +#enx98b78501ae64: ICC icc-to-rtc +#pvcamPCIE_0: camflowfs +#pvcamPCIE_1: camllowfs -for driverPattern in edt nvidia enx503eaa0ceeff enx503eaa0cf4cd enx6cb31152a245 cp2x72c; do +for driverPattern in nvidia enx503eaa0ceeff enx503eaa0cf4cd enx98b78501ae64 pvcamPCIE_0 pvcamPCIE_1; do if [[ $(grep -e "^\s*$2" /proc/interrupts) == *"$driverPattern"* ]]; then echo "ban=true" exit 0 diff --git a/rtSetup/ICC/move_irqs b/rtSetup/ICC/move_irqs index 5c82afddc..5a8940913 100644 --- a/rtSetup/ICC/move_irqs +++ b/rtSetup/ICC/move_irqs @@ -10,7 +10,7 @@ irqs=$(awk '{print $1}' /proc/interrupts | grep '[0-9]:' | sed 's/.$//') for irq in $irqs; do if [ "$irq" != "0" ]; then - echo "0-7,32-39" > /proc/irq/$irq/smp_affinity_list || true + echo "0-31,64-95" > /proc/irq/$irq/smp_affinity_list || true fi done @@ -30,6 +30,27 @@ for enx in $enxs; do echo $cpu > /proc/irq/$enx/smp_affinity_list done +enxs=$(grep enx98b78501ae64 /proc/interrupts | awk '{print $1}' | sed 's/.$//') +cpu=$(cat $CGROUPS1_CPUSET_MOUNTPOINT/shmimTCP/cpuset.cpus) +for enx in $enxs; do + echo "shmimTCP enx: " $enx " to " $cpu + echo $cpu > /proc/irq/$enx/smp_affinity_list +done + +kitxs=$(grep pvcamPCIE_0 /proc/interrupts | awk '{print $1}' | sed 's/.$//') +cpu=$(cat $CGROUPS1_CPUSET_MOUNTPOINT/camflowfs/cpuset.cpus) +for kitx in $kitxs; do + echo "camflowfs pvcam: " $kitx " to " $cpu + echo $cpu > /proc/irq/$kitx/smp_affinity_list +done + +kitxs=$(grep pvcamPCIE_1 /proc/interrupts | awk '{print $1}' | sed 's/.$//') +cpu=$(cat $CGROUPS1_CPUSET_MOUNTPOINT/camllowfs/cpuset.cpus) +for kitx in $kitxs; do + echo "camllowfs pvcam: " $kitx " to " $cpu + echo $cpu > /proc/irq/$kitx/smp_affinity_list +done + nvidias=$(grep nvidia /proc/interrupts | awk '{print $1}' | sed 's/.$//') cpu=$(cat $CGROUPS1_CPUSET_MOUNTPOINT/acqu_mvm/cpuset.cpus) for nvidia in $nvidias; do diff --git a/rtSetup/RTC/irqbalance b/rtSetup/RTC/irqbalance index 51f0d580d..65bdd432b 100644 --- a/rtSetup/RTC/irqbalance +++ b/rtSetup/RTC/irqbalance @@ -1,13 +1,13 @@ -####################################### -# MagAO-X irqbalance configuration +############################################ +# MagAO-X irqbalance configuration for RTC # -# Edit the IRQBALANCE_BANNED_CPUS bitmask to match the r/t cpusets created in rtc_cpuset +# Edit the IRQBALANCE_BANNED_CPUS bitmask to match the r/t cpusets created in make_cpusets # -# Edit the IRQBALANCE_ARGS list of args to add a --banirq=x for each irq x you want to prevent being balanced +# Edit the irqbalance_policyscript to include IRQs to ban # -# To install: +# To Install: # -# This should be installed by the configure_irqbalance.sh setup script. You will need to delete the installed version. +# If first time after new installation: $ cp /etc/sysconfig/irqbalance /etc/sysconfig/irqbalance.bup # # $ systemctl stop irqbalance # @@ -16,7 +16,6 @@ # $ systemctl status irqbalance # - # irqbalance is a daemon process that distributes interrupts across # CPUS on SMP systems. The default is to rebalance once every 10 # seconds. This is the environment file that is specified to systemd via the diff --git a/rtSetup/RTC/irqbalance_policyscript b/rtSetup/RTC/irqbalance_policyscript index 0388fab86..4191d7286 100755 --- a/rtSetup/RTC/irqbalance_policyscript +++ b/rtSetup/RTC/irqbalance_policyscript @@ -9,13 +9,10 @@ #edt: any EDT gramegrabber #nvidia: any NVIDIA GPU -#enx503eaa0ceeff: ICC camsci1 -#enx503eaa0cf4cd: ICC camsci2 -#enx6cb31152a245: ICC icc-to-rtc -#enx6cb31152a246: RTC rtc-to-ICC -#cp2x73c: ? +#enx98b78501aebc: shmimTCP NIC +#cp2x72c: ALPAO -> dmwoofer -for driverPattern in edt nvidia enx6cb31152a246 cp2x72c; do +for driverPattern in edt nvidia enx98b78501aebc cp2x72c; do if [[ $(grep -e "^\s*$2" /proc/interrupts) == *"$driverPattern"* ]]; then echo "ban=true" exit 0 diff --git a/rtSetup/RTC/move_irqs b/rtSetup/RTC/move_irqs index 7d28eca6d..2d98cd08c 100644 --- a/rtSetup/RTC/move_irqs +++ b/rtSetup/RTC/move_irqs @@ -10,7 +10,7 @@ irqs=$(awk '{print $1}' /proc/interrupts | grep '[0-9]:' | sed 's/.$//') for irq in $irqs; do if [ "$irq" != "0" ]; then - echo "0-13,36-49" > /proc/irq/$irq/smp_affinity_list || true + echo "0-31,64-49" > /proc/irq/$irq/smp_affinity_list || true fi done @@ -28,6 +28,20 @@ for nvidia in $nvidias; do echo $cpu > /proc/irq/$nvidia/smp_affinity_list done +dmws=$(grep cp2x72c /proc/interrupts | awk '{print $1}' | sed 's/.$//') +cpu=$(cat $CGROUPS1_CPUSET_MOUNTPOINT/dmwoofer/cpuset.cpus) +for dmw in $dmws; do + echo "alpao: " $dmw " to " $cpu + echo $cpu > /proc/irq/$dmw/smp_affinity_list +done + +enxs=$(grep enx98b78501aebc /proc/interrupts | awk '{print $1}' | sed 's/.$//') +cpu=$(cat $CGROUPS1_CPUSET_MOUNTPOINT/shmimTCP/cpuset.cpus) +for enx in $enxs; do + echo "shmimTCP enx: " $enx " to " $cpu + echo $cpu > /proc/irq/$enx/smp_affinity_list +done + echo "done moving IRQs" systemctl start irqbalance From 34f1bc52462157574d6751d1f5150d801948504e Mon Sep 17 00:00:00 2001 From: jrmales Date: Thu, 3 Oct 2024 12:34:16 -0400 Subject: [PATCH 07/24] made kcubeCtrl RTC only --- Makefile | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/Makefile b/Makefile index 91ba6ac43..68bb7ae39 100644 --- a/Makefile +++ b/Makefile @@ -30,7 +30,6 @@ apps_rtcicc = \ hsfwCtrl \ rhusbMon \ cacaoInterface \ - kcubeCtrl \ modalPSDs \ userGainCtrl \ refRMS \ @@ -51,8 +50,8 @@ apps_rtc = \ t2wOffloader \ dmSpeckle \ w2tcsOffloader \ - pwfsSlopeCalc - + pwfsSlopeCalc \ + kcubeCtrl apps_icc = \ dmPokeCenter \ From 6f4431bad6257783777a37f42f05717126867e22 Mon Sep 17 00:00:00 2001 From: Jared Males Date: Thu, 3 Oct 2024 09:39:58 -0700 Subject: [PATCH 08/24] fixd RTC irq bugs --- rtSetup/RTC/move_irqs | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/rtSetup/RTC/move_irqs b/rtSetup/RTC/move_irqs index 2d98cd08c..807e98ecf 100644 --- a/rtSetup/RTC/move_irqs +++ b/rtSetup/RTC/move_irqs @@ -10,7 +10,7 @@ irqs=$(awk '{print $1}' /proc/interrupts | grep '[0-9]:' | sed 's/.$//') for irq in $irqs; do if [ "$irq" != "0" ]; then - echo "0-31,64-49" > /proc/irq/$irq/smp_affinity_list || true + echo "0-31,64-95" > /proc/irq/$irq/smp_affinity_list || true fi done @@ -29,7 +29,7 @@ for nvidia in $nvidias; do done dmws=$(grep cp2x72c /proc/interrupts | awk '{print $1}' | sed 's/.$//') -cpu=$(cat $CGROUPS1_CPUSET_MOUNTPOINT/dmwoofer/cpuset.cpus) +cpu=$(cat $CGROUPS1_CPUSET_MOUNTPOINT/woofer/cpuset.cpus) for dmw in $dmws; do echo "alpao: " $dmw " to " $cpu echo $cpu > /proc/irq/$dmw/smp_affinity_list From 5a5a97bd0c775c1782f57030ffd823a625113ac2 Mon Sep 17 00:00:00 2001 From: Jared Males Date: Thu, 3 Oct 2024 20:56:44 -0300 Subject: [PATCH 09/24] updated coronAlignGui --- apps/zaberLowLevel/zabernotes.txt | 4 + gui/apps/cameraGUI/cameraGUI.pro | 14 +- gui/apps/coronAlignGUI/coronAlignGUI.pro | 34 +- gui/widgets/camera/stageStatus.hpp | 34 +- gui/widgets/coronAlign/coronAlign.hpp | 995 +++++++++++++-- gui/widgets/coronAlign/coronAlign.ui | 1332 ++++++++++++++++++-- gui/widgets/stage/stage.hpp | 110 +- gui/widgets/xWidgets/selectionSwStatus.hpp | 70 +- gui/widgets/xWidgets/stageStatus.hpp | 145 +++ gui/widgets/xWidgets/statusDisplay.hpp | 101 +- 10 files changed, 2495 insertions(+), 344 deletions(-) create mode 100644 gui/widgets/xWidgets/stageStatus.hpp diff --git a/apps/zaberLowLevel/zabernotes.txt b/apps/zaberLowLevel/zabernotes.txt index 7fff4d523..de12c45be 100644 --- a/apps/zaberLowLevel/zabernotes.txt +++ b/apps/zaberLowLevel/zabernotes.txt @@ -139,3 +139,7 @@ set max pos = 384000 set point for out should be 85 degrees +Setup of stagellowfs +serial: 122400 +max: 1066667 + diff --git a/gui/apps/cameraGUI/cameraGUI.pro b/gui/apps/cameraGUI/cameraGUI.pro index dc9e84780..579d30acb 100644 --- a/gui/apps/cameraGUI/cameraGUI.pro +++ b/gui/apps/cameraGUI/cameraGUI.pro @@ -4,8 +4,8 @@ TEMPLATE = app TARGET = cameraGUI -DESTDIR = bin/ -DEPENDPATH += ./ ../../lib +DESTDIR = bin/ +DEPENDPATH += ./ ../../lib CONFIG+=debug @@ -49,9 +49,9 @@ HEADERS += ../../widgets/camera/camera.hpp \ ../../widgets/stage/stage.hpp \ ../../widgets/camera/shutterStatus.hpp \ ../../lib/multiIndiManager.hpp - -SOURCES += cameraGUI_main.cpp - + +SOURCES += cameraGUI_main.cpp + FORMS += ../../widgets/camera/camera.ui \ ../../widgets/xWidgets/fsmDisplay.ui \ ../../widgets/xWidgets/statusEntry.ui \ @@ -61,11 +61,11 @@ FORMS += ../../widgets/camera/camera.ui \ ../../widgets/stage/stage.ui \ ../../widgets/camera/shutterStatus.ui \ ../../widgets/xWidgets/selectionSw.ui - + LIBS += ../../../INDI/libcommon/libcommon.a \ ../../../INDI/liblilxml/liblilxml.a \ -lmxlib -RESOURCES += ../../resources/MagAOXStyleSheets/MagAOXStyle.qrc +RESOURCES += ../../resources/MagAOXStyleSheets/MagAOXStyle.qrc QT += widgets diff --git a/gui/apps/coronAlignGUI/coronAlignGUI.pro b/gui/apps/coronAlignGUI/coronAlignGUI.pro index 7da482297..abd27463a 100644 --- a/gui/apps/coronAlignGUI/coronAlignGUI.pro +++ b/gui/apps/coronAlignGUI/coronAlignGUI.pro @@ -4,8 +4,8 @@ TEMPLATE = app TARGET = coronAlignGUI -DESTDIR = bin/ -DEPENDPATH += ./ ../../lib +DESTDIR = bin/ +DEPENDPATH += ./ ../../lib MOC_DIR = moc/ OBJECTS_DIR = obj/ @@ -28,21 +28,33 @@ exists( $$(CONDA_PREFIX)/lib ) { MAKEFILE = makefile.coronAlignGUI # Input -INCLUDEPATH += ../../lib ../../widgets/coronAlign +INCLUDEPATH += ../../lib ../../widgets/coronAlign ../../widgets/xWidgets HEADERS += ../../widgets/coronAlign/coronAlign.hpp \ ../../widgets/xWidgets/xWidget.hpp \ - ../../lib/multiIndiManager.hpp - -SOURCES += coronAlignGUI_main.cpp - -FORMS += ../../widgets/coronAlign/coronAlign.ui - + ../../lib/multiIndiManager.hpp \ + ../../widgets/xWidgets/selectionSwStatus.hpp \ + ../../widgets/xWidgets/statusDisplay.hpp \ + ../../widgets/xWidgets/statusLabel.hpp \ + ../../widgets/xWidgets/selectionSw.hpp \ + ../../widgets/xWidgets/stageStatus.hpp \ + ../../widgets/stage/stage.hpp \ + ../../widgets/xWidgets/fsmDisplay.hpp \ + ../../widgets/xWidgets/statusLineEdit.hpp \ + +SOURCES += coronAlignGUI_main.cpp + +FORMS += ../../widgets/coronAlign/coronAlign.ui \ + ../../widgets/xWidgets/statusDisplay.ui \ + ../../widgets/xWidgets/selectionSw.ui \ + ../../widgets/stage/stage.ui \ + ../../widgets/xWidgets/fsmDisplay.ui \ + LIBS += ../../../INDI/libcommon/libcommon.a \ ../../../INDI/liblilxml/liblilxml.a -RESOURCES += ../../resources/magaox.qrc +RESOURCES += ../../resources/magaox.qrc -RESOURCES += ../../resources/MagAOXStyleSheets/MagAOXStyle.qrc +RESOURCES += ../../resources/MagAOXStyleSheets/MagAOXStyle.qrc QT += widgets diff --git a/gui/widgets/camera/stageStatus.hpp b/gui/widgets/camera/stageStatus.hpp index f43938968..bfd37f0b8 100644 --- a/gui/widgets/camera/stageStatus.hpp +++ b/gui/widgets/camera/stageStatus.hpp @@ -7,43 +7,43 @@ #include "../xWidgets/statusDisplay.hpp" -namespace xqt +namespace xqt { - + class stageStatus : public statusDisplay { Q_OBJECT - + protected: - + std::string m_presetName; float m_position; public: stageStatus( std::string & stageName, - QWidget * Parent = 0, + QWidget * Parent = 0, Qt::WindowFlags f = Qt::WindowFlags() ); - + ~stageStatus(); - + virtual QString formatValue(); virtual void subscribe(); - + void handleSetProperty( const pcf::IndiProperty & ipRecv /**< [in] the property which has changed*/); - + //void updateGUI(); }; - + stageStatus::stageStatus( std::string & stageName, - QWidget * Parent, + QWidget * Parent, Qt::WindowFlags f) : statusDisplay(stageName, "", "", stageName, "", Parent, f) { m_ctrlWidget = (xWidget *) (new stage(stageName, this, Qt::Dialog)); } - + stageStatus::~stageStatus() { } @@ -65,7 +65,7 @@ QString stageStatus::formatValue() void stageStatus::subscribe() { if(!m_parent) return; - + m_parent->addSubscriberProperty(this, m_device, "presetName"); m_parent->addSubscriberProperty(this, m_device, "filterName"); m_parent->addSubscriberProperty(this, m_device, "position"); @@ -75,9 +75,9 @@ void stageStatus::subscribe() return; } - + void stageStatus::handleSetProperty( const pcf::IndiProperty & ipRecv) -{ +{ if(ipRecv.getDevice() != m_device) return; if(ipRecv.getName() == "presetName" || ipRecv.getName() == "filterName") @@ -93,7 +93,7 @@ void stageStatus::handleSetProperty( const pcf::IndiProperty & ipRecv) m_presetName = it->first; m_valChanged = true; } - + break; } } @@ -115,7 +115,7 @@ void stageStatus::handleSetProperty( const pcf::IndiProperty & ipRecv) } } //namespace xqt - + #include "moc_stageStatus.cpp" #endif diff --git a/gui/widgets/coronAlign/coronAlign.hpp b/gui/widgets/coronAlign/coronAlign.hpp index 40f21022f..d4853fae0 100644 --- a/gui/widgets/coronAlign/coronAlign.hpp +++ b/gui/widgets/coronAlign/coronAlign.hpp @@ -13,83 +13,117 @@ #include "../xWidgets/xWidget.hpp" -namespace xqt +namespace xqt { - + class coronAlign : public xWidget { Q_OBJECT - + enum camera {FLOWFS, LLOWFS, CAMSCIS}; protected: QMutex m_mutex; - - int m_camera {FLOWFS}; + + int m_camera {CAMSCIS}; //Pico Motors std::string m_picoState; - + //Pupil Plane - + std::string m_fwPupilState; - - + + double m_fwPupilPos; long m_picoPupilPos; - + double m_fwPupilStepSize {0.0001}; double m_picoPupilStepSize {100}; - + int m_pupilScale {100}; //Focal Plane - + std::string m_fwFocalState; - - + + double m_fwFocalPos; long m_picoFocalPos; - + double m_fwFocalStepSize {0.0001}; double m_picoFocalStepSize {100}; - + int m_focalScale {100}; - + //Lyot Plane - + std::string m_fwLyotState; - - + + double m_fwLyotPos; long m_picoLyotPos; - + double m_fwLyotStepSize {0.0001}; double m_picoLyotStepSize {100}; - + int m_lyotScale {100}; - + + //PIAA + std::string m_piaaState; + double m_piaaPos; + int m_piaaScale {1}; + double m_piaaStepSize {0.1}; + + //PIAA0; + long m_piaa0xPos; + int m_piaa0Scale {1}; + double m_piaa0StepSize {20}; + + //PIAA1; + long m_piaa1xPos; + long m_piaa1yPos; + int m_piaa1Scale {1}; + double m_piaa1StepSize {20}; + + //iPIAA + std::string m_ipiaaState; + double m_ipiaaPos; + int m_ipiaaScale {1}; + double m_ipiaaStepSize {0.1}; + + //iPIAA0; + long m_ipiaa0xPos; + int m_ipiaa0Scale {1}; + double m_ipiaa0StepSize {20}; + + //iPIAA1; + long m_ipiaa1xPos; + long m_ipiaa1yPos; + int m_ipiaa1Scale {1}; + double m_ipiaa1StepSize {20}; + public: - coronAlign( QWidget * Parent = 0, + coronAlign( QWidget * Parent = 0, Qt::WindowFlags f = Qt::WindowFlags() ); - + ~coronAlign(); - + void subscribe(); - + virtual void onConnect(); virtual void onDisconnect(); - + void handleDefProperty( const pcf::IndiProperty & ipRecv /**< [in] the property which has changed*/); void handleSetProperty( const pcf::IndiProperty & ipRecv /**< [in] the property which has changed*/); - + void enablePicoButtons(); void disablePicoButtons(); - + public slots: void updateGUI(); - + void on_checkCamflowfs_clicked() { ui.checkCamflowfs->setCheckState(Qt::Checked); @@ -116,21 +150,49 @@ public slots: void on_button_pupil_l_pressed(); void on_button_pupil_r_pressed(); void on_button_pupil_scale_pressed(); - + void on_button_focal_u_pressed(); void on_button_focal_d_pressed(); void on_button_focal_l_pressed(); void on_button_focal_r_pressed(); void on_button_focal_scale_pressed(); - + void on_button_lyot_u_pressed(); void on_button_lyot_d_pressed(); void on_button_lyot_l_pressed(); void on_button_lyot_r_pressed(); void on_button_lyot_scale_pressed(); - + + void on_button_piaa_u_pressed(); + void on_button_piaa_d_pressed(); + void on_button_piaa_scale_pressed(); + + void on_button_piaa0_l_pressed(); + void on_button_piaa0_r_pressed(); + void on_button_piaa0_scale_pressed(); + + void on_button_piaa1_l_pressed(); + void on_button_piaa1_r_pressed(); + void on_button_piaa1_u_pressed(); + void on_button_piaa1_d_pressed(); + void on_button_piaa1_scale_pressed(); + + void on_button_ipiaa_u_pressed(); + void on_button_ipiaa_d_pressed(); + void on_button_ipiaa_scale_pressed(); + + void on_button_ipiaa0_l_pressed(); + void on_button_ipiaa0_r_pressed(); + void on_button_ipiaa0_scale_pressed(); + + void on_button_ipiaa1_l_pressed(); + void on_button_ipiaa1_r_pressed(); + void on_button_ipiaa1_u_pressed(); + void on_button_ipiaa1_d_pressed(); + void on_button_ipiaa1_scale_pressed(); + private: - + Ui::coronAlign ui; }; @@ -140,26 +202,56 @@ coronAlign::coronAlign( QWidget * Parent, Qt::WindowFlags f) : xWidget(Parent, f ui.button_pupil_scale->setProperty("isScaleButton", true); ui.button_focal_scale->setProperty("isScaleButton", true); ui.button_lyot_scale->setProperty("isScaleButton", true); - + ui.button_piaa_scale->setProperty("isScaleButton", true); + ui.button_piaa0_scale->setProperty("isScaleButton", true); + ui.button_piaa1_scale->setProperty("isScaleButton", true); + ui.button_ipiaa_scale->setProperty("isScaleButton", true); + ui.button_ipiaa0_scale->setProperty("isScaleButton", true); + ui.button_ipiaa1_scale->setProperty("isScaleButton", true); + QTimer *timer = new QTimer(this); connect(timer, SIGNAL(timeout()), this, SLOT(updateGUI())); timer->start(250); - + char ss[5]; snprintf(ss, 5, "%d", m_pupilScale); ui.button_pupil_scale->setText(ss); - + snprintf(ss, 5, "%d", m_focalScale); ui.button_focal_scale->setText(ss); - + snprintf(ss, 5, "%d", m_lyotScale); ui.button_lyot_scale->setText(ss); - + + snprintf(ss, 5, "%d", m_piaaScale); + ui.button_piaa_scale->setText(ss); + + snprintf(ss, 5, "%d", m_piaa0Scale); + ui.button_piaa0_scale->setText(ss); + + snprintf(ss, 5, "%d", m_piaa1Scale); + ui.button_piaa1_scale->setText(ss); + + snprintf(ss, 5, "%d", m_ipiaaScale); + ui.button_ipiaa_scale->setText(ss); + + snprintf(ss, 5, "%d", m_ipiaa0Scale); + ui.button_ipiaa0_scale->setText(ss); + + snprintf(ss, 5, "%d", m_ipiaa1Scale); + ui.button_ipiaa1_scale->setText(ss); + ui.checkCamllowfs->setEnabled(false); + ui.fwpupil->setup("fwpupil"); + ui.fwfpm->setup("fwfpm"); + ui.fwlyot->setup("fwlyot"); + ui.stagepiaa->setup("stagepiaa"); + ui.stageipiaa->setup("stageipiaa"); + onDisconnect(); } - + coronAlign::~coronAlign() { } @@ -170,45 +262,113 @@ void coronAlign::subscribe() m_parent->addSubscriberProperty(this, "fwpupil", "filter"); m_parent->addSubscriberProperty(this, "fwpupil", "fsm"); - + m_parent->addSubscriberProperty(this, "fwfpm", "filter"); m_parent->addSubscriberProperty(this, "fwfpm", "fsm"); - + m_parent->addSubscriberProperty(this, "fwlyot", "filter"); m_parent->addSubscriberProperty(this, "fwlyot", "fsm"); - + m_parent->addSubscriberProperty(this, "picomotors", "picopupil_pos"); m_parent->addSubscriberProperty(this, "picomotors", "picofpm_pos"); m_parent->addSubscriberProperty(this, "picomotors", "picolyot_pos"); + m_parent->addSubscriberProperty(this, "picomotors", "piaa0x_pos"); + m_parent->addSubscriberProperty(this, "picomotors", "piaa1x_pos"); + m_parent->addSubscriberProperty(this, "picomotors", "piaa1y_pos"); + m_parent->addSubscriberProperty(this, "picomotors", "ipiaa0x_pos"); + m_parent->addSubscriberProperty(this, "picomotors", "ipiaa1x_pos"); + m_parent->addSubscriberProperty(this, "picomotors", "ipiaa1y_pos"); m_parent->addSubscriberProperty(this, "picomotors", "fsm"); - + + m_parent->addSubscriberProperty(this, "stagepiaa", "position"); + m_parent->addSubscriberProperty(this, "stagepiaa", "fsm"); + + m_parent->addSubscriberProperty(this, "stageipiaa", "position"); + m_parent->addSubscriberProperty(this, "stageipiaa", "fsm"); + + m_parent->addSubscriber(ui.fwpupil); + m_parent->addSubscriber(ui.fwfpm); + m_parent->addSubscriber(ui.fwlyot); + m_parent->addSubscriber(ui.stagepiaa); + m_parent->addSubscriber(ui.stageipiaa); + return; } - + void coronAlign::onConnect() { ui.labelPupil->setEnabled(true); ui.labelFocal->setEnabled(true); ui.labelLyot->setEnabled(true); - + ui.button_pupil_u->setEnabled(true); ui.button_pupil_d->setEnabled(true); ui.button_pupil_l->setEnabled(true); ui.button_pupil_r->setEnabled(true); ui.button_pupil_scale->setEnabled(true); - + ui.button_focal_u->setEnabled(true); ui.button_focal_d->setEnabled(true); ui.button_focal_l->setEnabled(true); ui.button_focal_r->setEnabled(true); ui.button_focal_scale->setEnabled(true); - + ui.button_lyot_u->setEnabled(true); ui.button_lyot_d->setEnabled(true); ui.button_lyot_l->setEnabled(true); ui.button_lyot_r->setEnabled(true); ui.button_lyot_scale->setEnabled(true); - + + ui.labelPIAA->setEnabled(true); + ui.button_piaa_u->setEnabled(true); + ui.button_piaa_d->setEnabled(true); + ui.button_piaa_scale->setEnabled(true); + + ui.labelPIAA0->setEnabled(true); + ui.button_piaa0_l->setEnabled(true); + ui.button_piaa0_r->setEnabled(true); + ui.button_piaa0_scale->setEnabled(true); + + ui.labelPIAA1->setEnabled(true); + ui.button_piaa1_l->setEnabled(true); + ui.button_piaa1_r->setEnabled(true); + ui.button_piaa1_u->setEnabled(true); + ui.button_piaa1_d->setEnabled(true); + ui.button_piaa1_scale->setEnabled(true); + + ui.labeliPIAA->setEnabled(true); + ui.button_ipiaa_u->setEnabled(true); + ui.button_ipiaa_d->setEnabled(true); + ui.button_ipiaa_scale->setEnabled(true); + + ui.labeliPIAA0->setEnabled(true); + ui.button_ipiaa0_l->setEnabled(true); + ui.button_ipiaa0_r->setEnabled(true); + ui.button_ipiaa0_scale->setEnabled(true); + + ui.labeliPIAA1->setEnabled(true); + ui.button_ipiaa1_l->setEnabled(true); + ui.button_ipiaa1_r->setEnabled(true); + ui.button_ipiaa1_u->setEnabled(true); + ui.button_ipiaa1_d->setEnabled(true); + ui.button_ipiaa1_scale->setEnabled(true); + + + ui.fwpupil->setEnabled(true); + ui.fwpupil->onConnect(); + + ui.fwfpm->setEnabled(true); + ui.fwfpm->onConnect(); + + ui.fwlyot->setEnabled(true); + ui.fwlyot->onConnect(); + + ui.stagepiaa->setEnabled(true); + ui.stagepiaa->onConnect(); + + ui.stageipiaa->setEnabled(true); + ui.stageipiaa->onConnect(); + setWindowTitle("Coronagraph Alignment"); } @@ -218,50 +378,104 @@ void coronAlign::onDisconnect() m_fwPupilState = ""; m_fwFocalState = ""; m_fwLyotState = ""; - + m_piaaState = ""; + m_ipiaaState = ""; + ui.labelPupil->setEnabled(false); ui.labelFocal->setEnabled(false); ui.labelLyot->setEnabled(false); - + ui.button_pupil_u->setEnabled(false); ui.button_pupil_d->setEnabled(false); ui.button_pupil_l->setEnabled(false); ui.button_pupil_r->setEnabled(false); ui.button_pupil_scale->setEnabled(false); - + ui.button_focal_u->setEnabled(false); ui.button_focal_d->setEnabled(false); ui.button_focal_l->setEnabled(false); ui.button_focal_r->setEnabled(false); ui.button_focal_scale->setEnabled(false); - + ui.button_lyot_u->setEnabled(false); ui.button_lyot_d->setEnabled(false); ui.button_lyot_l->setEnabled(false); ui.button_lyot_r->setEnabled(false); ui.button_lyot_scale->setEnabled(false); - + + ui.labelPIAA->setEnabled(false); + ui.button_piaa_u->setEnabled(false); + ui.button_piaa_d->setEnabled(false); + ui.button_piaa_scale->setEnabled(false); + + ui.labelPIAA0->setEnabled(false); + ui.button_piaa0_l->setEnabled(false); + ui.button_piaa0_r->setEnabled(false); + ui.button_piaa0_scale->setEnabled(false); + + ui.labelPIAA1->setEnabled(false); + ui.button_piaa1_l->setEnabled(false); + ui.button_piaa1_r->setEnabled(false); + ui.button_piaa1_u->setEnabled(false); + ui.button_piaa1_d->setEnabled(false); + ui.button_piaa1_scale->setEnabled(false); + + ui.labeliPIAA->setEnabled(false); + ui.button_ipiaa_u->setEnabled(false); + ui.button_ipiaa_d->setEnabled(false); + ui.button_ipiaa_scale->setEnabled(false); + + ui.labeliPIAA0->setEnabled(false); + ui.button_ipiaa0_l->setEnabled(false); + ui.button_ipiaa0_r->setEnabled(false); + ui.button_ipiaa0_scale->setEnabled(false); + + ui.labeliPIAA1->setEnabled(false); + ui.button_ipiaa1_l->setEnabled(false); + ui.button_ipiaa1_r->setEnabled(false); + ui.button_ipiaa1_u->setEnabled(false); + ui.button_ipiaa1_d->setEnabled(false); + ui.button_ipiaa1_scale->setEnabled(false); + + ui.fwpupil->setEnabled(false); + ui.fwpupil->onDisconnect(); + + ui.fwfpm->setEnabled(true); + ui.fwfpm->onDisconnect(); + + ui.fwlyot->setEnabled(true); + ui.fwlyot->onDisconnect(); + + ui.stagepiaa->setEnabled(true); + ui.stagepiaa->onDisconnect(); + + ui.stageipiaa->setEnabled(true); + ui.stageipiaa->onDisconnect(); + setWindowTitle("Coronagraph Alignment (disconnected)"); } - + void coronAlign::handleDefProperty( const pcf::IndiProperty & ipRecv) -{ +{ std::string dev = ipRecv.getDevice(); - if( dev == "picomotors" || - dev == "fwpupil" || - dev == "fwlyot" || - dev == "fwfpm" ) + if( dev == "picomotors" || + dev == "fwpupil" || + dev == "fwlyot" || + dev == "fwfpm" || + dev == "stagepiaa" || + dev == "stageipiaa" + ) { return handleSetProperty(ipRecv); } - + return; } void coronAlign::handleSetProperty( const pcf::IndiProperty & ipRecv) { std::string dev = ipRecv.getDevice(); - + if(dev == "fwpupil") { if(ipRecv.getName() == "filter") @@ -281,7 +495,7 @@ void coronAlign::handleSetProperty( const pcf::IndiProperty & ipRecv) } } } - if(dev == "fwfpm") + else if(dev == "fwfpm") { if(ipRecv.getName() == "filter") { @@ -300,7 +514,7 @@ void coronAlign::handleSetProperty( const pcf::IndiProperty & ipRecv) } } } - if(dev == "fwlyot") + else if(dev == "fwlyot") { if(ipRecv.getName() == "filter") { @@ -319,6 +533,44 @@ void coronAlign::handleSetProperty( const pcf::IndiProperty & ipRecv) } } } + else if(dev == "stagepiaa") + { + if(ipRecv.getName() == "position") + { + if(ipRecv.find("current")) + { + m_piaaPos = ipRecv["current"].get(); + return; + } + } + else if(ipRecv.getName() == "fsm") + { + if(ipRecv.find("state")) + { + m_piaaState = ipRecv["state"].get(); + return; + } + } + } + else if(dev == "stageipiaa") + { + if(ipRecv.getName() == "position") + { + if(ipRecv.find("current")) + { + m_ipiaaPos = ipRecv["current"].get(); + return; + } + } + else if(ipRecv.getName() == "fsm") + { + if(ipRecv.find("state")) + { + m_ipiaaState = ipRecv["state"].get(); + return; + } + } + } else if(dev == "picomotors") { if(ipRecv.getName() == "picopupil_pos") @@ -345,6 +597,54 @@ void coronAlign::handleSetProperty( const pcf::IndiProperty & ipRecv) return; } } + else if(ipRecv.getName() == "piaa0x_pos") + { + if(ipRecv.find("current")) + { + m_piaa0xPos = ipRecv["current"].get(); + return; + } + } + else if(ipRecv.getName() == "piaa1x_pos") + { + if(ipRecv.find("current")) + { + m_piaa1xPos = ipRecv["current"].get(); + return; + } + } + else if(ipRecv.getName() == "piaa1y_pos") + { + if(ipRecv.find("current")) + { + m_piaa1yPos = ipRecv["current"].get(); + return; + } + } + else if(ipRecv.getName() == "ipiaa0x_pos") + { + if(ipRecv.find("current")) + { + m_ipiaa0xPos = ipRecv["current"].get(); + return; + } + } + else if(ipRecv.getName() == "ipiaa1x_pos") + { + if(ipRecv.find("current")) + { + m_ipiaa1xPos = ipRecv["current"].get(); + return; + } + } + else if(ipRecv.getName() == "ipiaa1y_pos") + { + if(ipRecv.find("current")) + { + m_ipiaa1yPos = ipRecv["current"].get(); + return; + } + } else if(ipRecv.getName() == "fsm") { if(ipRecv.find("state")) @@ -354,14 +654,14 @@ void coronAlign::handleSetProperty( const pcf::IndiProperty & ipRecv) } } } - + return; } void coronAlign::updateGUI() { - + if(m_fwPupilState != "READY") { if(m_camera == FLOWFS) @@ -396,7 +696,7 @@ void coronAlign::updateGUI() ui.labelPupil->setEnabled(true); } } - + if(m_fwFocalState != "READY") { if(m_camera == FLOWFS) @@ -431,7 +731,7 @@ void coronAlign::updateGUI() ui.labelFocal->setEnabled(true); } } - + if(m_fwLyotState != "READY") { if(m_camera == FLOWFS) @@ -466,7 +766,37 @@ void coronAlign::updateGUI() ui.labelLyot->setEnabled(true); } } - + + if(m_piaaState != "READY") + { + ui.button_piaa_u->setEnabled(false); + ui.button_piaa_d->setEnabled(false); + ui.button_piaa_scale->setEnabled(false); + ui.labelPIAA->setEnabled(false); + } + else + { + ui.button_piaa_u->setEnabled(true); + ui.button_piaa_d->setEnabled(true); + ui.button_piaa_scale->setEnabled(true); + ui.labelPIAA->setEnabled(true); + } + + if(m_ipiaaState != "READY") + { + ui.button_ipiaa_u->setEnabled(false); + ui.button_ipiaa_d->setEnabled(false); + ui.button_ipiaa_scale->setEnabled(false); + ui.labeliPIAA->setEnabled(false); + } + else + { + ui.button_ipiaa_u->setEnabled(true); + ui.button_ipiaa_d->setEnabled(true); + ui.button_ipiaa_scale->setEnabled(true); + ui.labeliPIAA->setEnabled(true); + } + if(m_picoState != "READY") { disablePicoButtons(); @@ -475,7 +805,7 @@ void coronAlign::updateGUI() { enablePicoButtons(); } - + if(m_camera == FLOWFS) { @@ -496,10 +826,12 @@ void coronAlign::updateGUI() ui.checkCamsci12->setCheckState(Qt::Checked); } + ui.fwpupil->updateGUI(); + } //updateGUI() void coronAlign::enablePicoButtons() -{ +{ if(m_camera == FLOWFS) { ui.button_pupil_u->setEnabled(true); @@ -518,6 +850,26 @@ void coronAlign::enablePicoButtons() ui.button_lyot_u->setEnabled(true); ui.button_lyot_d->setEnabled(true); } + + ui.button_piaa0_l->setEnabled(true); + ui.button_piaa0_r->setEnabled(true); + ui.button_piaa0_scale->setEnabled(true); + + ui.button_piaa1_l->setEnabled(true); + ui.button_piaa1_r->setEnabled(true); + ui.button_piaa1_u->setEnabled(true); + ui.button_piaa1_d->setEnabled(true); + ui.button_piaa1_scale->setEnabled(true); + + ui.button_ipiaa0_l->setEnabled(true); + ui.button_ipiaa0_r->setEnabled(true); + ui.button_ipiaa0_scale->setEnabled(true); + + ui.button_ipiaa1_l->setEnabled(true); + ui.button_ipiaa1_r->setEnabled(true); + ui.button_ipiaa1_u->setEnabled(true); + ui.button_ipiaa1_d->setEnabled(true); + ui.button_ipiaa1_scale->setEnabled(true); } void coronAlign::disablePicoButtons() @@ -540,12 +892,32 @@ void coronAlign::disablePicoButtons() ui.button_lyot_u->setEnabled(false); ui.button_lyot_d->setEnabled(false); } + + ui.button_piaa0_l->setEnabled(false); + ui.button_piaa0_r->setEnabled(false); + ui.button_piaa0_scale->setEnabled(false); + + ui.button_piaa1_l->setEnabled(false); + ui.button_piaa1_r->setEnabled(false); + ui.button_piaa1_u->setEnabled(false); + ui.button_piaa1_d->setEnabled(false); + ui.button_piaa1_scale->setEnabled(false); + + ui.button_ipiaa0_l->setEnabled(false); + ui.button_ipiaa0_r->setEnabled(false); + ui.button_ipiaa0_scale->setEnabled(false); + + ui.button_ipiaa1_l->setEnabled(false); + ui.button_ipiaa1_r->setEnabled(false); + ui.button_ipiaa1_u->setEnabled(false); + ui.button_ipiaa1_d->setEnabled(false); + ui.button_ipiaa1_scale->setEnabled(false); } void coronAlign::on_button_pupil_u_pressed() { pcf::IndiProperty ip(pcf::IndiProperty::Number); - + if(m_camera == FLOWFS) { ip.setDevice("picomotors"); @@ -555,13 +927,13 @@ void coronAlign::on_button_pupil_u_pressed() disablePicoButtons(); } - else + else { ip.setDevice("fwpupil"); ip.setName("filter"); ip.add(pcf::IndiElement("target")); ip["target"] = m_fwPupilPos + m_pupilScale*m_fwPupilStepSize; - + ui.button_pupil_l->setEnabled(false); ui.button_pupil_r->setEnabled(false); } @@ -572,14 +944,14 @@ void coronAlign::on_button_pupil_u_pressed() void coronAlign::on_button_pupil_d_pressed() { pcf::IndiProperty ip(pcf::IndiProperty::Number); - + if(m_camera == FLOWFS) { ip.setDevice("picomotors"); ip.setName("picopupil_pos"); ip.add(pcf::IndiElement("target")); ip["target"] = m_picoPupilPos - m_pupilScale*m_picoPupilStepSize; - + disablePicoButtons(); } else @@ -588,7 +960,7 @@ void coronAlign::on_button_pupil_d_pressed() ip.setName("filter"); ip.add(pcf::IndiElement("target")); ip["target"] = m_fwPupilPos - m_pupilScale*m_fwPupilStepSize; - + ui.button_pupil_l->setEnabled(false); ui.button_pupil_r->setEnabled(false); } @@ -598,14 +970,14 @@ void coronAlign::on_button_pupil_d_pressed() void coronAlign::on_button_pupil_l_pressed() { pcf::IndiProperty ip(pcf::IndiProperty::Number); - + if(m_camera == FLOWFS) { ip.setDevice("fwpupil"); ip.setName("filter"); ip.add(pcf::IndiElement("target")); ip["target"] = m_fwPupilPos + m_pupilScale*m_fwPupilStepSize; - + ui.button_pupil_l->setEnabled(false); ui.button_pupil_r->setEnabled(false); } @@ -625,14 +997,14 @@ void coronAlign::on_button_pupil_l_pressed() void coronAlign::on_button_pupil_r_pressed() { pcf::IndiProperty ip(pcf::IndiProperty::Number); - + if(m_camera == FLOWFS) { ip.setDevice("fwpupil"); ip.setName("filter"); ip.add(pcf::IndiElement("target")); ip["target"] = m_fwPupilPos - m_pupilScale*m_fwPupilStepSize; - + ui.button_pupil_l->setEnabled(false); ui.button_pupil_r->setEnabled(false); } @@ -642,12 +1014,12 @@ void coronAlign::on_button_pupil_r_pressed() ip.setName("picopupil_pos"); ip.add(pcf::IndiElement("target")); ip["target"] = m_picoPupilPos - m_pupilScale*m_picoPupilStepSize; - + disablePicoButtons(); } - + sendNewProperty(ip); - + } void coronAlign::on_button_pupil_scale_pressed() @@ -672,7 +1044,7 @@ void coronAlign::on_button_pupil_scale_pressed() { m_pupilScale = 1; } - + char ss[5]; snprintf(ss, 5, "%d", m_pupilScale); std::cerr << m_pupilScale << " " << ss << "\n"; @@ -685,7 +1057,7 @@ void coronAlign::on_button_pupil_scale_pressed() void coronAlign::on_button_focal_u_pressed() { pcf::IndiProperty ip(pcf::IndiProperty::Number); - + if(m_camera == FLOWFS) { ip.setDevice("picomotors"); @@ -703,15 +1075,15 @@ void coronAlign::on_button_focal_u_pressed() ui.button_focal_r->setEnabled(false); } disablePicoButtons(); - + sendNewProperty(ip); - + } void coronAlign::on_button_focal_d_pressed() { pcf::IndiProperty ip(pcf::IndiProperty::Number); - + if(m_camera == FLOWFS) { ip.setDevice("picomotors"); @@ -729,15 +1101,15 @@ void coronAlign::on_button_focal_d_pressed() ui.button_focal_r->setEnabled(false); } disablePicoButtons(); - + sendNewProperty(ip); - + } void coronAlign::on_button_focal_l_pressed() { pcf::IndiProperty ip(pcf::IndiProperty::Number); - + if(m_camera == FLOWFS) { ip.setDevice("fwfpm"); @@ -754,14 +1126,14 @@ void coronAlign::on_button_focal_l_pressed() ip.add(pcf::IndiElement("target")); ip["target"] = m_picoFocalPos - m_focalScale*m_picoFocalStepSize; } - + sendNewProperty(ip); } void coronAlign::on_button_focal_r_pressed() { pcf::IndiProperty ip(pcf::IndiProperty::Number); - + if(m_camera == FLOWFS) { ip.setDevice("fwfpm"); @@ -803,7 +1175,7 @@ void coronAlign::on_button_focal_scale_pressed() { m_focalScale = 1; } - + char ss[5]; snprintf(ss, 5, "%d", m_focalScale); ui.button_focal_scale->setText(ss); @@ -814,16 +1186,16 @@ void coronAlign::on_button_focal_scale_pressed() void coronAlign::on_button_lyot_u_pressed() { - + pcf::IndiProperty ip(pcf::IndiProperty::Number); - + if(m_camera == FLOWFS || m_camera == CAMSCIS) { ip.setDevice("fwlyot"); ip.setName("filter"); ip.add(pcf::IndiElement("target")); ip["target"] = m_fwLyotPos - m_lyotScale*m_fwLyotStepSize; - + ui.button_lyot_u->setEnabled(false); ui.button_lyot_d->setEnabled(false); } @@ -833,7 +1205,7 @@ void coronAlign::on_button_lyot_u_pressed() ip.setName("picolyot_pos"); ip.add(pcf::IndiElement("target")); ip["target"] = m_picoLyotPos - m_lyotScale*m_picoLyotStepSize; - + disablePicoButtons(); } @@ -844,14 +1216,14 @@ void coronAlign::on_button_lyot_u_pressed() void coronAlign::on_button_lyot_d_pressed() { pcf::IndiProperty ip(pcf::IndiProperty::Number); - + if(m_camera == FLOWFS || m_camera == CAMSCIS) { ip.setDevice("fwlyot"); ip.setName("filter"); ip.add(pcf::IndiElement("target")); ip["target"] = m_fwLyotPos + m_lyotScale*m_fwLyotStepSize; - + ui.button_lyot_u->setEnabled(false); ui.button_lyot_d->setEnabled(false); } @@ -861,25 +1233,25 @@ void coronAlign::on_button_lyot_d_pressed() ip.setName("picolyot_pos"); ip.add(pcf::IndiElement("target")); ip["target"] = m_picoLyotPos + m_lyotScale*m_picoLyotStepSize; - + disablePicoButtons(); } sendNewProperty(ip); - + } void coronAlign::on_button_lyot_l_pressed() { pcf::IndiProperty ip(pcf::IndiProperty::Number); - + if(m_camera == FLOWFS || m_camera == CAMSCIS) { ip.setDevice("picomotors"); ip.setName("picolyot_pos"); ip.add(pcf::IndiElement("target")); ip["target"] = m_picoLyotPos + m_lyotScale*m_picoLyotStepSize; - + disablePicoButtons(); } else @@ -888,27 +1260,27 @@ void coronAlign::on_button_lyot_l_pressed() ip.setName("filter"); ip.add(pcf::IndiElement("target")); ip["target"] = m_fwLyotPos - m_lyotScale*m_fwLyotStepSize; - + ui.button_lyot_u->setEnabled(false); ui.button_lyot_d->setEnabled(false); } sendNewProperty(ip); - - + + } void coronAlign::on_button_lyot_r_pressed() { pcf::IndiProperty ip(pcf::IndiProperty::Number); - + if(m_camera == FLOWFS || m_camera == CAMSCIS) { ip.setDevice("picomotors"); ip.setName("picolyot_pos"); ip.add(pcf::IndiElement("target")); ip["target"] = m_picoLyotPos - m_lyotScale*m_picoLyotStepSize; - + disablePicoButtons(); } else @@ -917,13 +1289,13 @@ void coronAlign::on_button_lyot_r_pressed() ip.setName("filter"); ip.add(pcf::IndiElement("target")); ip["target"] = m_fwLyotPos + m_lyotScale*m_fwLyotStepSize; - + ui.button_lyot_u->setEnabled(false); ui.button_lyot_d->setEnabled(false); } sendNewProperty(ip); - + } void coronAlign::on_button_lyot_scale_pressed() @@ -948,7 +1320,7 @@ void coronAlign::on_button_lyot_scale_pressed() { m_lyotScale = 1; } - + char ss[5]; snprintf(ss, 5, "%d", m_lyotScale); ui.button_lyot_scale->setText(ss); @@ -956,8 +1328,401 @@ void coronAlign::on_button_lyot_scale_pressed() } +void coronAlign::on_button_piaa_u_pressed() +{ + pcf::IndiProperty ip(pcf::IndiProperty::Number); + + ip.setDevice("stagepiaa"); + ip.setName("position"); + ip.add(pcf::IndiElement("target")); + ip["target"] = m_piaaPos + m_piaaScale*m_piaaStepSize; + + sendNewProperty(ip); + +} + +void coronAlign::on_button_piaa_d_pressed() +{ + pcf::IndiProperty ip(pcf::IndiProperty::Number); + + ip.setDevice("stagepiaa"); + ip.setName("position"); + ip.add(pcf::IndiElement("target")); + ip["target"] = m_piaaPos - m_piaaScale*m_piaaStepSize; + + sendNewProperty(ip); + +} + +void coronAlign::on_button_piaa_scale_pressed() +{ + if( m_piaaScale == 100) + { + m_piaaScale = 10; + } + else if(m_piaaScale == 10) + { + m_piaaScale = 5; + } + else if(m_piaaScale == 5) + { + m_piaaScale = 1; + } + else if(m_piaaScale == 1) + { + m_piaaScale = 100; + } + else + { + m_piaaScale = 1; + } + + char ss[5]; + snprintf(ss, 5, "%d", m_piaaScale); + ui.button_piaa_scale->setText(ss); + +} + +void coronAlign::on_button_piaa0_l_pressed() +{ + pcf::IndiProperty ip(pcf::IndiProperty::Number); + + ip.setDevice("picomotors"); + ip.setName("piaa0x_pos"); + ip.add(pcf::IndiElement("target")); + ip["target"] = m_piaa0xPos + m_piaa0Scale*m_piaa0StepSize; + + disablePicoButtons(); + + sendNewProperty(ip); + +} + +void coronAlign::on_button_piaa0_r_pressed() +{ + pcf::IndiProperty ip(pcf::IndiProperty::Number); + + ip.setDevice("picomotors"); + ip.setName("piaa0x_pos"); + ip.add(pcf::IndiElement("target")); + ip["target"] = m_piaa0xPos - m_piaa0Scale*m_piaa0StepSize; + + disablePicoButtons(); + + sendNewProperty(ip); +} + +void coronAlign::on_button_piaa0_scale_pressed() +{ + if( m_piaa0Scale == 100) + { + m_piaa0Scale = 10; + } + else if(m_piaa0Scale == 10) + { + m_piaa0Scale = 5; + } + else if(m_piaa0Scale == 5) + { + m_piaa0Scale = 1; + } + else if(m_piaa0Scale == 1) + { + m_piaa0Scale = 100; + } + else + { + m_piaa0Scale = 1; + } + + char ss[5]; + snprintf(ss, 5, "%d", m_piaa0Scale); + ui.button_piaa0_scale->setText(ss); + +} + +void coronAlign::on_button_piaa1_l_pressed() +{ + pcf::IndiProperty ip(pcf::IndiProperty::Number); + + ip.setDevice("picomotors"); + ip.setName("piaa1x_pos"); + ip.add(pcf::IndiElement("target")); + ip["target"] = m_piaa1xPos + m_piaa1Scale*m_piaa1StepSize; + + disablePicoButtons(); + + sendNewProperty(ip); +} + +void coronAlign::on_button_piaa1_r_pressed() +{ + pcf::IndiProperty ip(pcf::IndiProperty::Number); + + ip.setDevice("picomotors"); + ip.setName("piaa1x_pos"); + ip.add(pcf::IndiElement("target")); + ip["target"] = m_piaa1xPos - m_piaa1Scale*m_piaa1StepSize; + + disablePicoButtons(); + + sendNewProperty(ip); +} + +void coronAlign::on_button_piaa1_u_pressed() +{ + pcf::IndiProperty ip(pcf::IndiProperty::Number); + + ip.setDevice("picomotors"); + ip.setName("piaa1y_pos"); + ip.add(pcf::IndiElement("target")); + ip["target"] = m_piaa1yPos + m_piaa1Scale*m_piaa1StepSize; + + disablePicoButtons(); + + sendNewProperty(ip); +} + +void coronAlign::on_button_piaa1_d_pressed() +{ + pcf::IndiProperty ip(pcf::IndiProperty::Number); + + ip.setDevice("picomotors"); + ip.setName("piaa1y_pos"); + ip.add(pcf::IndiElement("target")); + ip["target"] = m_piaa1yPos - m_piaa1Scale*m_piaa1StepSize; + + disablePicoButtons(); + + sendNewProperty(ip); +} + +void coronAlign::on_button_piaa1_scale_pressed() +{ + if( m_piaa1Scale == 100) + { + m_piaa1Scale = 10; + } + else if(m_piaa1Scale == 10) + { + m_piaa1Scale = 5; + } + else if(m_piaa1Scale == 5) + { + m_piaa1Scale = 1; + } + else if(m_piaa1Scale == 1) + { + m_piaa1Scale = 100; + } + else + { + m_piaa1Scale = 1; + } + + char ss[5]; + snprintf(ss, 5, "%d", m_piaa1Scale); + ui.button_piaa1_scale->setText(ss); + +} + +void coronAlign::on_button_ipiaa_u_pressed() +{ + pcf::IndiProperty ip(pcf::IndiProperty::Number); + + ip.setDevice("stageipiaa"); + ip.setName("position"); + ip.add(pcf::IndiElement("target")); + ip["target"] = m_ipiaaPos + m_ipiaaScale*m_ipiaaStepSize; + sendNewProperty(ip); +} + +void coronAlign::on_button_ipiaa_d_pressed() +{ + pcf::IndiProperty ip(pcf::IndiProperty::Number); + + ip.setDevice("stageipiaa"); + ip.setName("position"); + ip.add(pcf::IndiElement("target")); + ip["target"] = m_ipiaaPos - m_ipiaaScale*m_ipiaaStepSize; + + sendNewProperty(ip); + +} + +void coronAlign::on_button_ipiaa_scale_pressed() +{ + if( m_ipiaaScale == 100) + { + m_ipiaaScale = 10; + } + else if(m_ipiaaScale == 10) + { + m_ipiaaScale = 5; + } + else if(m_ipiaaScale == 5) + { + m_ipiaaScale = 1; + } + else if(m_ipiaaScale == 1) + { + m_ipiaaScale = 100; + } + else + { + m_ipiaaScale = 1; + } + + char ss[5]; + snprintf(ss, 5, "%d", m_ipiaaScale); + ui.button_ipiaa_scale->setText(ss); + +} + +void coronAlign::on_button_ipiaa0_l_pressed() +{ + pcf::IndiProperty ip(pcf::IndiProperty::Number); + + ip.setDevice("picomotors"); + ip.setName("ipiaa0x_pos"); + ip.add(pcf::IndiElement("target")); + ip["target"] = m_ipiaa0xPos + m_ipiaa0Scale*m_ipiaa0StepSize; + + disablePicoButtons(); + + sendNewProperty(ip); +} + +void coronAlign::on_button_ipiaa0_r_pressed() +{ + pcf::IndiProperty ip(pcf::IndiProperty::Number); + + ip.setDevice("picomotors"); + ip.setName("ipiaa0x_pos"); + ip.add(pcf::IndiElement("target")); + ip["target"] = m_ipiaa0xPos - m_ipiaa0Scale*m_ipiaa0StepSize; + + disablePicoButtons(); + + sendNewProperty(ip); +} + +void coronAlign::on_button_ipiaa0_scale_pressed() +{ + if( m_ipiaa0Scale == 100) + { + m_ipiaa0Scale = 10; + } + else if(m_ipiaa0Scale == 10) + { + m_ipiaa0Scale = 5; + } + else if(m_ipiaa0Scale == 5) + { + m_ipiaa0Scale = 1; + } + else if(m_ipiaa0Scale == 1) + { + m_ipiaa0Scale = 100; + } + else + { + m_ipiaa0Scale = 1; + } + + char ss[5]; + snprintf(ss, 5, "%d", m_ipiaa0Scale); + ui.button_ipiaa0_scale->setText(ss); + +} + +void coronAlign::on_button_ipiaa1_l_pressed() +{ + pcf::IndiProperty ip(pcf::IndiProperty::Number); + + ip.setDevice("picomotors"); + ip.setName("ipiaa1x_pos"); + ip.add(pcf::IndiElement("target")); + ip["target"] = m_ipiaa1xPos + m_ipiaa1Scale*m_ipiaa1StepSize; + + disablePicoButtons(); + + sendNewProperty(ip); +} + +void coronAlign::on_button_ipiaa1_r_pressed() +{ + pcf::IndiProperty ip(pcf::IndiProperty::Number); + + ip.setDevice("picomotors"); + ip.setName("ipiaa1x_pos"); + ip.add(pcf::IndiElement("target")); + ip["target"] = m_ipiaa1xPos - m_ipiaa1Scale*m_ipiaa1StepSize; + + disablePicoButtons(); + + sendNewProperty(ip); +} + +void coronAlign::on_button_ipiaa1_u_pressed() +{ + pcf::IndiProperty ip(pcf::IndiProperty::Number); + + ip.setDevice("picomotors"); + ip.setName("ipiaa1y_pos"); + ip.add(pcf::IndiElement("target")); + ip["target"] = m_ipiaa1yPos + m_ipiaa1Scale*m_ipiaa1StepSize; + + disablePicoButtons(); + + sendNewProperty(ip); +} + +void coronAlign::on_button_ipiaa1_d_pressed() +{ + pcf::IndiProperty ip(pcf::IndiProperty::Number); + + ip.setDevice("picomotors"); + ip.setName("ipiaa1y_pos"); + ip.add(pcf::IndiElement("target")); + ip["target"] = m_ipiaa1yPos - m_ipiaa1Scale*m_ipiaa1StepSize; + + disablePicoButtons(); + + sendNewProperty(ip); +} + +void coronAlign::on_button_ipiaa1_scale_pressed() +{ + if( m_ipiaa1Scale == 100) + { + m_ipiaa1Scale = 10; + } + else if(m_ipiaa1Scale == 10) + { + m_ipiaa1Scale = 5; + } + else if(m_ipiaa1Scale == 5) + { + m_ipiaa1Scale = 1; + } + else if(m_ipiaa1Scale == 1) + { + m_ipiaa1Scale = 100; + } + else + { + m_ipiaa1Scale = 1; + } + + char ss[5]; + snprintf(ss, 5, "%d", m_ipiaa1Scale); + ui.button_ipiaa1_scale->setText(ss); + +} + } //namespace xqt - + #include "moc_coronAlign.cpp" #endif diff --git a/gui/widgets/coronAlign/coronAlign.ui b/gui/widgets/coronAlign/coronAlign.ui index 2688522eb..fda301330 100644 --- a/gui/widgets/coronAlign/coronAlign.ui +++ b/gui/widgets/coronAlign/coronAlign.ui @@ -6,82 +6,560 @@ 0 0 - 729 - 212 + 1619 + 637 Form - + - - - + + + - - - - - Camera - - - Qt::AlignCenter - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - camflowfs - - - false - - - + - - - camllowfs - - + + + + + PIAA + + + Qt::AlignCenter + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + QLayout::SetDefaultConstraint + + + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + + 10 + + + + Qt::NoFocus + + + 0.01 + + + + + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + Qt::NoFocus + + + + + + + :/icons/arrow_up_128.png:/icons/arrow_up_128.png + + + + + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + Qt::NoFocus + + + + + + + :/icons/arrow_down_128.png:/icons/arrow_down_128.png + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + - - - camsci1/2 - - + + + + + PIAA0 + + + Qt::AlignCenter + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + QLayout::SetDefaultConstraint + + + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + Qt::NoFocus + + + + + + + :/icons/arrow_right_128.png:/icons/arrow_right_128.png + + + + + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + Qt::NoFocus + + + + + + + :/icons/arrow_left_128.png:/icons/arrow_left_128.png + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + + 10 + + + + Qt::NoFocus + + + 0.01 + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + - - - Qt::Vertical - - - - 20 - 40 - - - + + + + + PIAA1 + + + Qt::AlignCenter + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + QLayout::SetDefaultConstraint + + + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + Qt::NoFocus + + + + + + + :/icons/arrow_right_128.png:/icons/arrow_right_128.png + + + + + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + Qt::NoFocus + + + + + + + :/icons/arrow_left_128.png:/icons/arrow_left_128.png + + + + + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + + 10 + + + + Qt::NoFocus + + + 0.01 + + + + + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + Qt::NoFocus + + + + + + + :/icons/arrow_up_128.png:/icons/arrow_up_128.png + + + + + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + Qt::NoFocus + + + + + + + :/icons/arrow_down_128.png:/icons/arrow_down_128.png + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + + @@ -538,8 +1016,8 @@ QLayout::SetDefaultConstraint - - + + 1 @@ -566,12 +1044,12 @@ - :/icons/arrow_right_128.png:/icons/arrow_right_128.png + :/icons/arrow_down_128.png:/icons/arrow_down_128.png - - + + 1 @@ -598,12 +1076,12 @@ - :/icons/arrow_left_128.png:/icons/arrow_left_128.png + :/icons/arrow_up_128.png:/icons/arrow_up_128.png - - + + 1 @@ -622,21 +1100,20 @@ 40 - - - 10 - - Qt::NoFocus - 0.01 + + + + + :/icons/arrow_right_128.png:/icons/arrow_right_128.png - - + + 1 @@ -663,12 +1140,12 @@ - :/icons/arrow_up_128.png:/icons/arrow_up_128.png + :/icons/arrow_left_128.png:/icons/arrow_left_128.png - - + + 1 @@ -687,15 +1164,16 @@ 40 + + + 10 + + Qt::NoFocus - - - - - :/icons/arrow_down_128.png:/icons/arrow_down_128.png + 0.01 @@ -720,10 +1198,694 @@ + + + + + + Camera + + + Qt::AlignCenter + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + camflowfs + + + false + + + + + + + camllowfs + + + + + + + camsci1/2 + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + + + + + + + iPIAA + + + Qt::AlignCenter + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + QLayout::SetDefaultConstraint + + + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + + 10 + + + + Qt::NoFocus + + + 0.01 + + + + + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + Qt::NoFocus + + + + + + + :/icons/arrow_up_128.png:/icons/arrow_up_128.png + + + + + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + Qt::NoFocus + + + + + + + :/icons/arrow_down_128.png:/icons/arrow_down_128.png + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + + + + + iPIAA0 + + + Qt::AlignCenter + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + QLayout::SetDefaultConstraint + + + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + Qt::NoFocus + + + + + + + :/icons/arrow_right_128.png:/icons/arrow_right_128.png + + + + + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + Qt::NoFocus + + + + + + + :/icons/arrow_left_128.png:/icons/arrow_left_128.png + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + + 10 + + + + Qt::NoFocus + + + 0.01 + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + + + + + iPIAA1 + + + Qt::AlignCenter + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + QLayout::SetDefaultConstraint + + + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + Qt::NoFocus + + + + + + + :/icons/arrow_right_128.png:/icons/arrow_right_128.png + + + + + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + Qt::NoFocus + + + + + + + :/icons/arrow_left_128.png:/icons/arrow_left_128.png + + + + + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + + 10 + + + + Qt::NoFocus + + + 0.01 + + + + + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + Qt::NoFocus + + + + + + + :/icons/arrow_up_128.png:/icons/arrow_up_128.png + + + + + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + Qt::NoFocus + + + + + + + :/icons/arrow_down_128.png:/icons/arrow_down_128.png + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + + + + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + xqt::stageStatus + QLineEdit +
../xWidgets/stageStatus.hpp
+
+
diff --git a/gui/widgets/stage/stage.hpp b/gui/widgets/stage/stage.hpp index 673d0370c..706de0407 100644 --- a/gui/widgets/stage/stage.hpp +++ b/gui/widgets/stage/stage.hpp @@ -6,19 +6,19 @@ #include "../xWidgets/xWidget.hpp" -namespace xqt +namespace xqt { - + class stage : public xWidget { Q_OBJECT - + enum editchanges{NOTEDITING, STARTED, STOPPED}; protected: - + std::string m_appState; - + std::string m_stageName; std::string m_winTitle; @@ -40,27 +40,27 @@ class stage : public xWidget QTimer * m_setPointEditTimer {nullptr}; public: - explicit stage( std::string & stageName, - QWidget * Parent = 0, + explicit stage( const std::string & stageName, + QWidget * Parent = 0, Qt::WindowFlags f = Qt::WindowFlags() ); - + ~stage(); - + void subscribe(); - + virtual void onConnect(); virtual void onDisconnect(); - + void handleDefProperty( const pcf::IndiProperty & ipRecv /**< [in] the property which has changed*/); - + void handleSetProperty( const pcf::IndiProperty & ipRecv /**< [in] the property which has changed*/); - + void clear_focus(); public slots: void updateGUI(); - + void on_setPoint_activated( int index ); void on_setPointGo_pressed(); @@ -81,7 +81,7 @@ public slots: void on_home_pressed(); void on_stop_pressed(); - + void setPointEditTimerOut(); signals: @@ -93,18 +93,18 @@ public slots: virtual void paintEvent(QPaintEvent * e); private: - + Ui::stage ui; }; - -stage::stage( std::string & stageName, - QWidget * Parent, + +stage::stage( const std::string & stageName, + QWidget * Parent, Qt::WindowFlags f) : xWidget(Parent, f), m_stageName{stageName} { ui.setupUi(this); m_winTitle = m_stageName; - + ui.fsmState->device(m_stageName); QFont qf = ui.stageName->font(); qf.setPixelSize(XW_FONT_SIZE+3); @@ -124,7 +124,7 @@ stage::stage( std::string & stageName, onDisconnect(); } - + stage::~stage() { } @@ -132,7 +132,7 @@ stage::~stage() void stage::subscribe() { if(!m_parent) return; - + m_parent->addSubscriberProperty(this, m_stageName, "fsm"); m_parent->addSubscriberProperty(this, m_stageName, "maxpos"); m_parent->addSubscriberProperty(this, m_stageName, "position"); @@ -143,7 +143,7 @@ void stage::subscribe() return; } - + void stage::onConnect() { setWindowTitle(QString(m_winTitle.c_str())); @@ -178,14 +178,14 @@ void stage::onDisconnect() } void stage::handleDefProperty( const pcf::IndiProperty & ipRecv) -{ +{ return handleSetProperty(ipRecv); } void stage::handleSetProperty( const pcf::IndiProperty & ipRecv) -{ +{ if(ipRecv.getDevice() != m_stageName) return; - + if(ipRecv.getName() == "fsm") { if(ipRecv.find("state")) @@ -242,12 +242,12 @@ void stage::handleSetProperty( const pcf::IndiProperty & ipRecv) { std::cerr << "More than one switch selected in " << ipRecv.getDevice() << "." << ipRecv.getName() << "\n"; } - + newName = it->second.getName(); m_setPoint = newName; ui.setPoint->setCurrentText(m_setPoint.c_str()); //if(newName != m_value) m_valChanged = true; - //m_value = newName; + //m_value = newName; } } @@ -259,8 +259,8 @@ void stage::handleSetProperty( const pcf::IndiProperty & ipRecv) void stage::updateGUI() { - if( m_appState != "READY" && m_appState != "OPERATING" - && m_appState != "CONFIGURING" && m_appState != "NOTHOMED" + if( m_appState != "READY" && m_appState != "OPERATING" + && m_appState != "CONFIGURING" && m_appState != "NOTHOMED" && m_appState != "HOMING") { ui.stageName->setEnabled(false); @@ -271,18 +271,18 @@ void stage::updateGUI() ui.position->setText("---"); ui.position->setEnabled(false); ui.stepSize->setEnabled(false); - + ui.posMinus->setEnabled(false); ui.posPlus->setEnabled(false); ui.posStepMulTen->setEnabled(false); ui.posStepDivTen->setEnabled(false); - + ui.home->setEnabled(false); ui.stop->setEnabled(false); return; } - + if( m_appState == "READY" || m_appState == "OPERATING" || m_appState == "HOMING" || m_appState == "CONFIGURING") { ui.stageName->setEnabled(true); @@ -292,7 +292,7 @@ void stage::updateGUI() ui.posStepMulTen->setEnabled(true); ui.posStepDivTen->setEnabled(true); ui.stop->setEnabled(true); - + if( m_appState == "READY" ) { ui.setPointGo->setEnabled(true); @@ -302,7 +302,7 @@ void stage::updateGUI() ui.posPlus->setEnabled(true); ui.home->setEnabled(true); } - else + else { ui.setPointGo->setEnabled(false); ui.positionSlider->setEnabled(false); @@ -379,14 +379,14 @@ void stage::on_setPointGo_pressed() { ipSend.setName("presetName"); } - ipSend.setPerm(pcf::IndiProperty::ReadWrite); + ipSend.setPerm(pcf::IndiProperty::ReadWrite); ipSend.setState(pcf::IndiProperty::Idle); ipSend.setRule(pcf::IndiProperty::OneOfMany); - + for(int idx = 0; idx < ui.setPoint->count(); ++idx) { std::string elName = ui.setPoint->itemText(idx).toStdString(); - + if(elName == selection) { ipSend.add(pcf::IndiElement(elName, pcf::IndiElement::On)); @@ -396,7 +396,7 @@ void stage::on_setPointGo_pressed() ipSend.add(pcf::IndiElement(elName, pcf::IndiElement::Off)); } } - + sendNewProperty(ipSend); } catch(...) @@ -413,7 +413,7 @@ void stage::on_positionSlider_sliderMoved( double s ) { double epos = s/100.0 * m_maxPos; - ui.position->setEditText(QString::number(epos)); + ui.position->setEditText(QString::number(epos)); } void stage::on_positionSlider_sliderReleased() @@ -430,7 +430,7 @@ void stage::on_positionSlider_sliderReleased() if(newPos == lastPos) return; pcf::IndiProperty ip(pcf::IndiProperty::Number); - + ip.setDevice(m_stageName); if(m_filterWheel) { @@ -458,7 +458,7 @@ void stage::on_position_returnPressed() if(newPos == lastPos) return; pcf::IndiProperty ip(pcf::IndiProperty::Number); - + ip.setDevice(m_stageName); if(m_filterWheel) { @@ -488,7 +488,7 @@ void stage::on_posMinus_pressed() double newPos = m_position - m_step; pcf::IndiProperty ip(pcf::IndiProperty::Number); - + ip.setDevice(m_stageName); if(m_filterWheel) { @@ -500,7 +500,7 @@ void stage::on_posMinus_pressed() } ip.add(pcf::IndiElement("target")); ip["target"] = newPos; - + sendNewProperty(ip); } @@ -509,7 +509,7 @@ void stage::on_posPlus_pressed() double newPos = m_position + m_step; pcf::IndiProperty ip(pcf::IndiProperty::Number); - + ip.setDevice(m_stageName); if(m_filterWheel) { @@ -521,7 +521,7 @@ void stage::on_posPlus_pressed() } ip.add(pcf::IndiElement("target")); ip["target"] = newPos; - + sendNewProperty(ip); } @@ -540,25 +540,25 @@ void stage::on_posStepDivTen_pressed() void stage::on_home_pressed() { pcf::IndiProperty ipFreq(pcf::IndiProperty::Switch); - + ipFreq.setDevice(m_stageName); ipFreq.setName("home"); ipFreq.add(pcf::IndiElement("request")); ipFreq["request"].setSwitchState(pcf::IndiElement::On); - - sendNewProperty(ipFreq); + + sendNewProperty(ipFreq); } void stage::on_stop_pressed() { pcf::IndiProperty ipFreq(pcf::IndiProperty::Switch); - + ipFreq.setDevice(m_stageName); ipFreq.setName("stop"); ipFreq.add(pcf::IndiElement("request")); ipFreq["request"].setSwitchState(pcf::IndiElement::On); - - sendNewProperty(ipFreq); + + sendNewProperty(ipFreq); } void stage::setPointEditTimerOut() @@ -576,18 +576,18 @@ void stage::paintEvent(QPaintEvent * e) ui.setPoint->setProperty("isEditing", true); style()->unpolish(ui.setPoint); } - else + else { ui.setPoint->setProperty("isEditing", false); ui.setPoint->setProperty("isStatus", true); style()->unpolish(ui.setPoint); } - + QWidget::paintEvent(e); } } //namespace xqt - + #include "moc_stage.cpp" #endif diff --git a/gui/widgets/xWidgets/selectionSwStatus.hpp b/gui/widgets/xWidgets/selectionSwStatus.hpp index 8b65bc919..b7987deb2 100644 --- a/gui/widgets/xWidgets/selectionSwStatus.hpp +++ b/gui/widgets/xWidgets/selectionSwStatus.hpp @@ -5,58 +5,86 @@ #include "ui_statusDisplay.h" - #include "../xWidgets/statusDisplay.hpp" #include "../xWidgets/selectionSw.hpp" -namespace xqt +namespace xqt { - + class selectionSwStatus : public statusDisplay { Q_OBJECT - + protected: - + public: + + selectionSwStatus( QWidget * Parent = 0, + Qt::WindowFlags f = Qt::WindowFlags() + ); + selectionSwStatus( const std::string & device, const std::string & property, const std::string & element, const std::string & label, const std::string & units, - QWidget * Parent = 0, + QWidget * Parent = 0, Qt::WindowFlags f = Qt::WindowFlags() ); - + ~selectionSwStatus(); - + + void setup( const std::string & device, + const std::string & property, + const std::string & element, + const std::string & label, + const std::string & units + ); + void handleSetProperty( const pcf::IndiProperty & ipRecv /**< [in] the property which has changed*/); - + }; - + +selectionSwStatus::selectionSwStatus( QWidget * Parent, + Qt::WindowFlags f + ) : statusDisplay(Parent, f) +{ +} + selectionSwStatus::selectionSwStatus( const std::string & device, const std::string & property, const std::string & element, const std::string & label, const std::string & units, - QWidget * Parent, + QWidget * Parent, Qt::WindowFlags f ) : statusDisplay(device, property, element, label, units, Parent, f) { - m_ctrlWidget = (xWidget *) (new selectionSw(device, property, this, Qt::Dialog)); - + setup(device, property, element, label, units); } - + selectionSwStatus::~selectionSwStatus() { } - + +void selectionSwStatus::setup( const std::string & device, + const std::string & property, + const std::string & element, + const std::string & label, + const std::string & units + ) +{ + statusDisplay::setup(device, property, element, label, units); + + m_ctrlWidget = (xWidget *) (new selectionSw(device, property, this, Qt::Dialog)); +} + void selectionSwStatus::handleSetProperty( const pcf::IndiProperty & ipRecv) -{ +{ if(ipRecv.getDevice() != m_device) return; - + if(ipRecv.getName() == m_property) { std::string newName; @@ -68,14 +96,14 @@ void selectionSwStatus::handleSetProperty( const pcf::IndiProperty & ipRecv) { std::cerr << "More than one switch selected in " << ipRecv.getDevice() << "." << ipRecv.getName() << "\n"; } - + newName = it->second.getName(); if(newName != m_value) m_valChanged = true; - m_value = newName; + m_value = newName; } } - + } updateGUI(); @@ -83,7 +111,7 @@ void selectionSwStatus::handleSetProperty( const pcf::IndiProperty & ipRecv) } //namespace xqt - + #include "moc_selectionSwStatus.cpp" #endif diff --git a/gui/widgets/xWidgets/stageStatus.hpp b/gui/widgets/xWidgets/stageStatus.hpp new file mode 100644 index 000000000..bc5626414 --- /dev/null +++ b/gui/widgets/xWidgets/stageStatus.hpp @@ -0,0 +1,145 @@ +#ifndef stageStatus_hpp +#define stageStatus_hpp + +#include + +#include "ui_statusDisplay.h" + +#include "../xWidgets/statusDisplay.hpp" +#include "../stage/stage.hpp" + +namespace xqt +{ + +class stageStatus : public statusDisplay +{ + Q_OBJECT + +protected: + + std::string m_presetName; + float m_position; + +public: + + stageStatus( QWidget * Parent = 0, + Qt::WindowFlags f = Qt::WindowFlags() + ); + + stageStatus( const std::string & stgN, + QWidget * Parent = 0, + Qt::WindowFlags f = Qt::WindowFlags() + ); + + ~stageStatus(); + + void setup(const std::string & stgN); + + virtual QString formatValue(); + + virtual void subscribe(); + + void handleSetProperty( const pcf::IndiProperty & ipRecv /**< [in] the property which has changed*/); + + //void updateGUI(); + +}; + +stageStatus::stageStatus( QWidget * Parent, + Qt::WindowFlags f) : statusDisplay(Parent, f) +{ +} + +stageStatus::stageStatus( const std::string & stageName, + QWidget * Parent, + Qt::WindowFlags f) : statusDisplay(Parent, f) +{ + setup(stageName); +} + +stageStatus::~stageStatus() +{ +} + +void stageStatus::setup(const std::string & stageName) +{ + statusDisplay::setup(stageName, "", "", stageName, ""); + if(m_ctrlWidget) + { + delete m_ctrlWidget; + } + + m_ctrlWidget = (xWidget *) (new stage(stageName, this, Qt::Dialog)); + +} +QString stageStatus::formatValue() +{ + if(m_presetName == "" || m_presetName == "none") + { + char pstr[64]; + snprintf(pstr, sizeof(pstr), "%0.4f", m_position); + return QString(pstr); + } + else + { + return QString(m_presetName.c_str()); + } +} + +void stageStatus::subscribe() +{ + if(!m_parent) return; + + m_parent->addSubscriberProperty(this, m_device, "presetName"); + m_parent->addSubscriberProperty(this, m_device, "filterName"); + m_parent->addSubscriberProperty(this, m_device, "position"); + m_parent->addSubscriberProperty(this, m_device, "filter"); + + statusDisplay::subscribe(); + + return; +} + +void stageStatus::handleSetProperty( const pcf::IndiProperty & ipRecv) +{ + if(ipRecv.getDevice() != m_device) return; + + if(ipRecv.getName() == "presetName" || ipRecv.getName() == "filterName") + { + auto map = ipRecv.getElements(); + + for(auto it = map.begin(); it != map.end(); ++it) + { + if(it->second.getSwitchState() == pcf::IndiElement::On) + { + if(m_presetName != it->first) + { + m_presetName = it->first; + m_valChanged = true; + } + + break; + } + } + } + else if(ipRecv.getName() == "position" || ipRecv.getName() == "filter") + { + if(ipRecv.find("current")) + { + float pos = ipRecv["current"].get(); + if(pos != m_position && (m_presetName == "none" || m_presetName == "")) + { + m_valChanged = true; + m_position = pos; + } + } + } + + statusDisplay::handleSetProperty(ipRecv); +} + +} //namespace xqt + +#include "moc_stageStatus.cpp" + +#endif diff --git a/gui/widgets/xWidgets/statusDisplay.hpp b/gui/widgets/xWidgets/statusDisplay.hpp index 85d4de4d1..24f7ce467 100644 --- a/gui/widgets/xWidgets/statusDisplay.hpp +++ b/gui/widgets/xWidgets/statusDisplay.hpp @@ -6,15 +6,15 @@ #include "xWidget.hpp" #include "../../lib/multiIndiSubscriber.hpp" -namespace xqt +namespace xqt { - + class statusDisplay : public xWidget { Q_OBJECT - + protected: - + xWidget * m_ctrlWidget {nullptr}; std::string m_device; @@ -34,42 +34,54 @@ class statusDisplay : public xWidget bool m_showVal {true}; public: + + statusDisplay( QWidget * Parent = 0, + Qt::WindowFlags f = Qt::WindowFlags() + ); + statusDisplay( const std::string & device, const std::string & property, const std::string & element, const std::string & label, const std::string & units, - QWidget * Parent = 0, + QWidget * Parent = 0, Qt::WindowFlags f = Qt::WindowFlags() ); - + ~statusDisplay(); + void setup( const std::string & device, + const std::string & property, + const std::string & element, + const std::string & label, + const std::string & units + ); + void ctrlWidget (xWidget * cw); xWidget * ctrlWidget(); - + virtual QString formatValue(); virtual void subscribe(); - + virtual void onConnect(); virtual void onDisconnect(); - + virtual void handleDefProperty( const pcf::IndiProperty & ipRecv /**< [in] the property which has changed*/); - + virtual void handleSetProperty( const pcf::IndiProperty & ipRecv /**< [in] the property which has changed*/); - + public: - /// + /// virtual void changeEvent(QEvent * e) { if(e->type() == QEvent::EnabledChange && !isEnabledTo(nullptr)) { if(m_ctrlWidget) m_ctrlWidget->hide(); } - + xWidget::changeEvent(e); } @@ -79,7 +91,7 @@ public slots: void on_button_pressed() { - if(m_ctrlWidget) + if(m_ctrlWidget) { m_ctrlWidget->show(); m_ctrlWidget->onConnect(); @@ -91,18 +103,45 @@ public slots: void doUpdateGUI(); protected: - + Ui::statusDisplay ui; }; - + +statusDisplay::statusDisplay( QWidget * Parent, + Qt::WindowFlags f) : xWidget(Parent, f) +{ +} + statusDisplay::statusDisplay( const std::string & device, const std::string & property, - const std::string & element, + const std::string & element, const std::string & label, const std::string & units, - QWidget * Parent, - Qt::WindowFlags f) : xWidget(Parent, f), m_device{device}, m_property{property}, m_element{element}, m_label{label}, m_units{units} + QWidget * Parent, + Qt::WindowFlags f) : xWidget(Parent, f) { + setup(device, property, element, label, units); +} + + +statusDisplay::~statusDisplay() +{ +} + +void statusDisplay::setup( const std::string & device, + const std::string & property, + const std::string & element, + const std::string & label, + const std::string & units + ) + +{ + m_device = device; + m_property = property; + m_element = element; + m_label = label; + m_units = units; + ui.setupUi(this); std::string lab = m_label; if(m_units != "") lab += " [" + m_units + "]"; @@ -120,17 +159,13 @@ statusDisplay::statusDisplay( const std::string & device, onDisconnect(); } - -statusDisplay::~statusDisplay() -{ -} void statusDisplay::ctrlWidget (xWidget * cw) { if(m_ctrlWidget) m_ctrlWidget->deleteLater(); m_ctrlWidget = cw; } - + xWidget * statusDisplay::ctrlWidget() { return m_ctrlWidget; @@ -144,12 +179,12 @@ QString statusDisplay::formatValue() void statusDisplay::subscribe() { if(!m_parent) return; - + m_parent->addSubscriberProperty(this, m_device, "fsm"); if(m_property != "") m_parent->addSubscriberProperty(this, m_device, m_property); - if(m_ctrlWidget) + if(m_ctrlWidget) { m_ctrlWidget->subscribe(); m_parent->addSubscriber(m_ctrlWidget); @@ -157,7 +192,7 @@ void statusDisplay::subscribe() return; } - + void statusDisplay::onConnect() { m_valChanged = true; @@ -176,15 +211,15 @@ void statusDisplay::handleDefProperty( const pcf::IndiProperty & ipRecv) } void statusDisplay::handleSetProperty( const pcf::IndiProperty & ipRecv) -{ +{ if(ipRecv.getDevice() != m_device) return; - + if(ipRecv.getName() == "fsm") { if(ipRecv.find("state")) { std::string fsmState = ipRecv["state"].get(); - + if(fsmState == "READY" || fsmState == "OPERATING") { if(fsmState != m_fsmState) @@ -240,8 +275,8 @@ void statusDisplay::updateGUI() if(m_valChanged) { QString value = formatValue(); - - ui.status->setTextChanged(value); + + ui.status->setTextChanged(value); m_valChanged = false; } } @@ -259,7 +294,7 @@ void statusDisplay::updateGUI() } //namespace xqt - + #include "moc_statusDisplay.cpp" #endif From 54be47f52c88f410f6680213e4e473d14e490db1 Mon Sep 17 00:00:00 2001 From: Jared Males Date: Thu, 3 Oct 2024 21:13:40 -0300 Subject: [PATCH 10/24] flippe stage piaa axis --- gui/widgets/coronAlign/coronAlign.hpp | 8 ++++---- gui/widgets/coronAlign/coronAlign.ui | 4 ++-- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/gui/widgets/coronAlign/coronAlign.hpp b/gui/widgets/coronAlign/coronAlign.hpp index d4853fae0..02b51ff49 100644 --- a/gui/widgets/coronAlign/coronAlign.hpp +++ b/gui/widgets/coronAlign/coronAlign.hpp @@ -1335,7 +1335,7 @@ void coronAlign::on_button_piaa_u_pressed() ip.setDevice("stagepiaa"); ip.setName("position"); ip.add(pcf::IndiElement("target")); - ip["target"] = m_piaaPos + m_piaaScale*m_piaaStepSize; + ip["target"] = m_piaaPos - m_piaaScale*m_piaaStepSize; sendNewProperty(ip); @@ -1348,7 +1348,7 @@ void coronAlign::on_button_piaa_d_pressed() ip.setDevice("stagepiaa"); ip.setName("position"); ip.add(pcf::IndiElement("target")); - ip["target"] = m_piaaPos - m_piaaScale*m_piaaStepSize; + ip["target"] = m_piaaPos + m_piaaScale*m_piaaStepSize; sendNewProperty(ip); @@ -1533,7 +1533,7 @@ void coronAlign::on_button_ipiaa_u_pressed() ip.setDevice("stageipiaa"); ip.setName("position"); ip.add(pcf::IndiElement("target")); - ip["target"] = m_ipiaaPos + m_ipiaaScale*m_ipiaaStepSize; + ip["target"] = m_ipiaaPos - m_ipiaaScale*m_ipiaaStepSize; sendNewProperty(ip); } @@ -1544,7 +1544,7 @@ void coronAlign::on_button_ipiaa_d_pressed() ip.setDevice("stageipiaa"); ip.setName("position"); ip.add(pcf::IndiElement("target")); - ip["target"] = m_ipiaaPos - m_ipiaaScale*m_ipiaaStepSize; + ip["target"] = m_ipiaaPos + m_ipiaaScale*m_ipiaaStepSize; sendNewProperty(ip); diff --git a/gui/widgets/coronAlign/coronAlign.ui b/gui/widgets/coronAlign/coronAlign.ui index fda301330..b245a05d9 100644 --- a/gui/widgets/coronAlign/coronAlign.ui +++ b/gui/widgets/coronAlign/coronAlign.ui @@ -6,8 +6,8 @@ 0 0 - 1619 - 637 + 1292 + 647 From 1a4638a2652808a8758c97f753b481fdc88e0267 Mon Sep 17 00:00:00 2001 From: jrmales Date: Sat, 5 Oct 2024 07:22:01 -0400 Subject: [PATCH 11/24] updated pico control for multi-controller --- apps/picoMotorCtrl/picoMotorCtrl.hpp | 174 ++++++++++++++++++++++----- 1 file changed, 141 insertions(+), 33 deletions(-) diff --git a/apps/picoMotorCtrl/picoMotorCtrl.hpp b/apps/picoMotorCtrl/picoMotorCtrl.hpp index 45151425b..fbb66c810 100644 --- a/apps/picoMotorCtrl/picoMotorCtrl.hpp +++ b/apps/picoMotorCtrl/picoMotorCtrl.hpp @@ -102,10 +102,12 @@ class picoMotorCtrl : public MagAOXApp<>, public dev::ioDevice, public dev::tele std::string m_name; ///< The name of this channel, from the config section - int m_address {1}; ///< The controller address. + int m_address {1}; ///< The controller address, default is 1 int m_channel {-1}; ///< The number of this channel, where the motor is plugged in + int m_type {3}; ///< The motor type of this channel, default is 3 + std::vector m_presetNames; std::vector m_presetPositions; @@ -133,8 +135,9 @@ class picoMotorCtrl : public MagAOXApp<>, public dev::ioDevice, public dev::tele motorChannel( picoMotorCtrl * p, ///< [in] The parent point to set const std::string & n, ///< [in] The name of this channel int add, ///< [in] The controller address - int ch ///< [in] The number of this channel - ) : m_parent(p), m_name(n), m_address(add), m_channel(ch) + int ch, ///< [in] The number of this channel + int type ///< [in] The motor type of this channel + ) : m_parent(p), m_name(n), m_address(add), m_channel(ch), m_type(type) { m_thread = new std::thread; } @@ -310,7 +313,8 @@ void picoMotorCtrl::setupConfig() dev::ioDevice::setupConfig(config); - telemeterT::setupConfig(config); + TELEMETER_SETUP_CONFIG( config ); + } #define PICOMOTORCTRL_E_NOMOTORS (-5) @@ -365,9 +369,18 @@ int picoMotorCtrl::loadConfigImpl( mx::app::appConfigurator & _config ) return PICOMOTORCTRL_E_BADCHANNEL; } + int type = 3; + _config.configUnused(type, mx::app::iniFile::makeKey(sections[i], "type" ) ); + + if(address < 1) + { + log("Bad motor type specificiation: " + sections[i] + " type: " + std::to_string(type), logPrio::LOG_CRITICAL); + + return PICOMOTORCTRL_E_BADCHANNEL; + } //Ok, valid channel. Insert into map and check for duplicates. - std::pair insert = m_channels.insert(std::pair(sections[i], motorChannel(this,sections[i], address, channel))); + std::pair insert = m_channels.insert(std::pair(sections[i], motorChannel(this,sections[i], address, channel, type))); if(insert.second == false) { @@ -399,6 +412,8 @@ int picoMotorCtrl::loadConfigImpl( mx::app::appConfigurator & _config ) } } + TELEMETER_LOAD_CONFIG( config ); + return 0; } @@ -416,11 +431,8 @@ void picoMotorCtrl::loadConfig() m_shutdown = true; } - if(telemeterT::loadConfig(config) < 0) - { - log("Error during telemeter config", logPrio::LOG_CRITICAL); - m_shutdown = true; - } + + } int picoMotorCtrl::appStartup() @@ -483,10 +495,7 @@ int picoMotorCtrl::appStartup() return -1; } - if(telemeterT::appStartup() < 0) - { - return log({__FILE__,__LINE__}); - } + TELEMETER_APP_STARTUP; return 0; } @@ -527,6 +536,8 @@ int picoMotorCtrl::appLogic() { std::unique_lock lock(m_telnetMutex); + + //First check the address 1 controller int rv = m_telnetConn.write("*IDN?\r\n", m_writeTimeout); if(rv != TTY_E_NOERROR) { @@ -547,18 +558,27 @@ int picoMotorCtrl::appLogic() if(m_telnetConn.m_strRead.find("New_Focus") != std::string::npos) { - log("Connected to " + m_telnetConn.m_strRead); + log("Connected to " + m_telnetConn.m_strRead + " at address 1"); } else { if(powerState() != 1 || powerStateTarget() != 1) return 0; - - log({__FILE__, __LINE__, "wrong response to IDN query"}); + log({__FILE__, __LINE__, "wrong response to IDN query at address 1"}); state(stateCodes::ERROR); return 0; } - - //Do a motor scan + + //Now do a controller scan + rv = m_telnetConn.write("SC1\r\n", m_writeTimeout); //Will adjust addresses. + if(rv != TTY_E_NOERROR) + { + if(powerState() != 1 || powerStateTarget() != 1) return 0; + log({__FILE__, __LINE__, tty::ttyErrorString(rv)}); + state(stateCodes::ERROR); + return 0; + } + + //And now do a motor scan rv = m_telnetConn.write("MC\r\n", m_writeTimeout); if(rv != TTY_E_NOERROR) { @@ -568,12 +588,81 @@ int picoMotorCtrl::appLogic() return 0; } - sleep(1); //wtf is this here? + sleep(2); //Give time for controller scan to finish + + for(size_t n = 0; n < m_addresses.size(); ++n) + { + if(m_addresses[n] == 1) continue; //already done. + + std::string addprefix = std::to_string(m_addresses[n]) + ">"; + + int rv = m_telnetConn.write(addprefix + "*IDN?\r\n", m_writeTimeout); + if(rv != TTY_E_NOERROR) + { + if(powerState() != 1 || powerStateTarget() != 1) return 0; + log({__FILE__, __LINE__, tty::ttyErrorString(rv)}); + state(stateCodes::ERROR); + return 0; + } + + rv = m_telnetConn.read("\r\n", m_readTimeout, true); + if(rv != TTY_E_NOERROR) + { + if(powerState() != 1 || powerStateTarget() != 1) return 0; + log({__FILE__, __LINE__, tty::ttyErrorString(rv)}); + state(stateCodes::ERROR); + return 0; + } + + int add; + std::string resp; + + rv = splitResponse(add, resp, m_telnetConn.m_strRead); + if(rv != 0) + { + if(powerState() != 1 || powerStateTarget() != 1) return 0; + log({__FILE__, __LINE__, "splitResponse returned " + std::to_string(rv)}); + state(stateCodes::ERROR); + return 0; + } + + if(add != m_addresses[n]) + { + if(powerState() != 1 || powerStateTarget() != 1) return 0; + log({__FILE__, __LINE__, "address did not match in response"}); + state(stateCodes::ERROR); + return 0; + } + + if(resp.find("New_Focus") != std::string::npos) + { + log("Connected to " + resp + " at address " + std::to_string(m_addresses[n])); + } + else + { + if(powerState() != 1 || powerStateTarget() != 1) return 0; + log({__FILE__, __LINE__, "wrong response to IDN query at address " + std::to_string(m_addresses[n])}); + state(stateCodes::ERROR); + return 0; + } + + //Now do a motor scan + rv = m_telnetConn.write(addprefix + "MC\r\n", m_writeTimeout); + if(rv != TTY_E_NOERROR) + { + if(powerState() != 1 || powerStateTarget() != 1) return 0; + log({__FILE__, __LINE__, tty::ttyErrorString(rv)}); + state(stateCodes::ERROR); + return 0; + } + } + sleep(2); //This is to give time for motor scans to finish + //Now check for each motor attached for(auto it=m_channels.begin(); it!=m_channels.end();++it) { - std::string query = std::to_string(it->second.m_channel) + "QM?"; + std::string query = std::to_string(it->second.m_address) + ">" + std::to_string(it->second.m_channel) + "QM?"; rv = m_telnetConn.write(query + "\r\n", m_writeTimeout); if(rv != TTY_E_NOERROR) @@ -593,27 +682,50 @@ int picoMotorCtrl::appLogic() return 0; } - int moType = std::stoi(m_telnetConn.m_strRead); + int add; + std::string resp; + + rv = splitResponse(add, resp, m_telnetConn.m_strRead); + if(rv != 0) + { + if(powerState() != 1 || powerStateTarget() != 1) return 0; + log({__FILE__, __LINE__, "splitResponse returned " + std::to_string(rv)}); + state(stateCodes::ERROR); + return 0; + } + + if(add != it->second.m_address) + { + if(powerState() != 1 || powerStateTarget() != 1) return 0; + log({__FILE__, __LINE__, "address did not match in response"}); + state(stateCodes::ERROR); + return 0; + } + + int moType = std::stoi(resp); if(moType == 0) { if(powerState() != 1 || powerStateTarget() != 1) return 0; - log("No motor connected on channel " + std::to_string(it->second.m_channel) + " [" + it->second.m_name + "]", logPrio::LOG_CRITICAL); + log("No motor connected on channel " + std::to_string(it->second.m_address) + "." + std::to_string(it->second.m_channel) + " [" + it->second.m_name + "]", logPrio::LOG_CRITICAL); state(stateCodes::FAILURE); return -1; } - else if (moType != 3) + else if (moType != it->second.m_type) { if(powerState() != 1 || powerStateTarget() != 1) return 0; - log("Wrong motor type connected on channel " + std::to_string(it->second.m_channel) + " [" + it->second.m_name + "]", logPrio::LOG_CRITICAL); + std::string msg = "Wrong motor type connected on channel " + std::to_string(it->second.m_address) + "."; + msg += std::to_string(it->second.m_channel) + " [" + it->second.m_name + "] "; + msg += "expected " + std::to_string(it->second.m_type) + " "; + msg += "got " + std::to_string(moType); + + log(msg, logPrio::LOG_CRITICAL); state(stateCodes::FAILURE); return -1; } } - state(stateCodes::READY); - return 0; } @@ -751,11 +863,7 @@ int picoMotorCtrl::appLogic() } } - if(telemeterT::appLogic() < 0) - { - log({__FILE__, __LINE__}); - return 0; - } + TELEMETER_APP_LOGIC; return 0; } @@ -792,7 +900,7 @@ int picoMotorCtrl::appShutdown() } } - telemeterT::appShutdown(); + TELEMETER_APP_SHUTDOWN; return 0; } From df0622f5f7cbe782c40d81ebff29bbbc5aee937b Mon Sep 17 00:00:00 2001 From: Jared Males Date: Sat, 5 Oct 2024 10:15:10 -0300 Subject: [PATCH 12/24] updated gui launch scripts --- gui/scripts/magaox_guis.sh | 8 +++++--- gui/scripts/magaox_rtimvs.sh | 8 ++++++-- 2 files changed, 11 insertions(+), 5 deletions(-) mode change 100755 => 100644 gui/scripts/magaox_guis.sh mode change 100755 => 100644 gui/scripts/magaox_rtimvs.sh diff --git a/gui/scripts/magaox_guis.sh b/gui/scripts/magaox_guis.sh old mode 100755 new mode 100644 index eefa091da..5718cb571 --- a/gui/scripts/magaox_guis.sh +++ b/gui/scripts/magaox_guis.sh @@ -1,15 +1,16 @@ #!/bin/bash +magaox_rtimvs.sh pwrGUI & dmCtrlGUI dmwoofer & dmCtrlGUI dmtweeter & dmCtrlGUI dmncpc & -magaox_rtimvs.sh cameraGUI camwfs & cameraGUI camtip & -cameraGUI camlowfs & +cameraGUI camflowfs & +cameraGUI camllowfs & cameraGUI camacq & cameraGUI camsci1 & cameraGUI camsci2 & @@ -25,7 +26,8 @@ dmModeGUI wooferModes & dmModeGUI ncpcModes & coronAlignGUI & -sleep 6 + +sleep 10 dmnorm.sh woofer dmnorm.sh tweeter diff --git a/gui/scripts/magaox_rtimvs.sh b/gui/scripts/magaox_rtimvs.sh old mode 100755 new mode 100644 index 5a74d14bd..61da907bf --- a/gui/scripts/magaox_rtimvs.sh +++ b/gui/scripts/magaox_rtimvs.sh @@ -4,12 +4,16 @@ dmdisp.sh woofer dmdisp.sh tweeter dmdisp.sh ncpc +sleep 2 + rtimv -c rtimv_camacq.conf & rtimv -c rtimv_camwfs.conf & rtimv -c rtimv_camwfs_avg.conf & rtimv -c rtimv_camtip.conf & -rtimv -c rtimv_camlowfs.conf & -rtimv -c rtimv_camlowfs_avg.conf & +rtimv -c rtimv_camflowfs.conf & +rtimv -c rtimv_camflowfs_avg.conf & +rtimv -c rtimv_camllowfs.conf & +rtimv -c rtimv_camllowfs_avg.conf & rtimv -c rtimv_camsci1.conf & rtimv -c rtimv_camsci1_avg.conf & rtimv -c rtimv_camsci2.conf & From 15eb84b3eac810a877dcdd0c47c46420470557c4 Mon Sep 17 00:00:00 2001 From: Jared Males Date: Mon, 14 Oct 2024 14:29:04 -0700 Subject: [PATCH 13/24] removed test exec --- apps/sysMonitor/tests/sysMonitor_test | Bin 0 -> 2047784 bytes setup/steps/configure_etc_hosts.sh | 14 +++++++++++--- 2 files changed, 11 insertions(+), 3 deletions(-) create mode 100755 apps/sysMonitor/tests/sysMonitor_test diff --git a/apps/sysMonitor/tests/sysMonitor_test b/apps/sysMonitor/tests/sysMonitor_test new file mode 100755 index 0000000000000000000000000000000000000000..4d20136771de7f00686ac94927d9691067c1b67b GIT binary patch literal 2047784 zcmeF)dw`o&nLqHiIn!5~mF(_5-gUJ3&#g%Udz!Zq()o1t@gnVGgJDu!|~ z-eX-ct}cYC7+uBKRd!qzUn}CQx|prXjz3wAb!Dfki`lx1@dEtLdCzm^eexv-THHT( zw9Gu8oSgT0&pGdTZ@Ijq>*_1!&zpCUML!2wE3J9r@BH5>vdL$coJoIKmTe`hqs4#E zwPMzxLJt=IY9T!#GV z{?(+v=C~Xk>*eU*dU+{&-aYR<-meFLFQInPzxDFoES@LZWq*IdRB#}DSw{ZI^3>&i ze75-SjiP{T&%>qIYUFf9<)87;F8io?kB2uV!(s8Pc~&@L<>y7i+Z11 z;mE=BoJ;5BUt`Vhd~aUXB{!Ly#Xr4C^ozgc&w%(nDE?)|zajDOHt}zx_@{q{#or?o zkBZ-8;@>32o5b%s#J{(Se{U22-Y)*-#lO46zq`dh`EwurmVXz--|rUx-Xs3~^T3lM zpB|n#^`fyS|8U1wPdat&kw0>Kj$2ubyz>*QAN|;x=Sq)%>U9(MUVZAfBe!00(%YZ@ z;AtQK+=oa0<;z=d**M?%%=7=T^x6k6`16mu%Xfcx#hX6!i=S>-a{c@6Fa74B+t=4> z;V*va_A5J|dvMKjANc;$4}9R;C)_@moj7&-{Ey!B*x*;ocl`BdkKfz;)ANUXZ|sf_ z^?vy^n>KH_&NE~ z-gC_jAA9iehm+68zq57g#y{d{bhWvLmb_0e~q-rg@c zp}ij@hGV;WzVKShdQEH9e)JYmxLx@zOWXS)=eGCF3)}nihJ40PY+wE>OWOOrC$;z2 zis`W3dMz{LbBm#!KXrcl`hRy`d+%P{-hXKDhYaoTSwlX*HIzTe&^{N4$)sI7+$46G z?fQ4f(7*p?$R{DT!*=!jQD8g&nwYrS`l;>x2}3&{W61OShVA05hV3Hs`u58`$k3ii zgP$qJZM$|}xV(M+s|UN^?d2%_VpaSsJ;JFXM67wJEC^&f1RO!pD>KuK12P@ z3)<)3Cw55fmisnC|2`__rFP{Pp3~mHXvpV1hH>%@!+I?=w8I+1I2k&t{raA5$p11! z{l~nn{dygLVf*@jXBdYC!~FK5VIKIyDeag0JHz&JwV~bKXK0^|hWa;(^=j9@Hyg(D zZw<>$#@g32YbZb8;D2oxSDl7-E*kplazp*L*e=?w@0eknJa1^v)5UmeSI<@A0J@!D zV`%3!9qr3MEh=eO&x7JXvYlUL7|#zI>Uq|%+^dzztq!Z42=ZfKux8n%mwVf;L87>D079Cs};?B5gOxTsw}t}yi1xrX`e zY0=K@+W&OJ{w{84|DA^RSuFM!?dt!Ap`IfQ?f(nI@yRKM{=L)Czte{HmnYNh+VgFq zAKT^sO+!6@GWa~he$z3Ozy6H&`Fuc}1h&i5Huyb;@%b^saxWG0nAjv=@^g*h`20J^ zx6kKEk$<~(>l5>BJMR!H)z1IQFwSd+dE>{1^?IWr&$6NXe;LNlv4;77xoEd``Cn<+ ze%BlJ7hf}s6LI=tMPJe@mi5by_U(U;Vf(tsu$>MVwxe%}m1;NMjx~(W#|-ty4fD*~ z4egUR^vhzy{_*?Awa?QsjGsFU?Q@6W{AIIYKHp(D&OgsEe(p2mdH#{@^Z%@2xvLEM zZ!wIY3k>b~0mE^~Wnz18H=e(3=-)+#arnza+OO9WhWrPPZC}1($n)!l{pL>$`H0;} z+wJIh!+QP9kmvsxw%-+o{yNuiT$(o2-)pF6m6*@l^~*v-dCxEo*BZvd<%V`}4dpi- z*1o^~XqX=kThKoL`wYwV#H1&l@{*qi4D-gLhIaVD8`{@%vSEIB*s#9W8}_G<8}bKV^N68e3Wj-a z$dLc{4ExQ$JE8q}_=BN6e`)Bial`giG+YPxjG>;xk80m9A24h$=NQJxC5Cpp*Dx=A z%+Nkh8s_~U+|IqgB_FKbsgEI`r2}=y?b%~+f zYKA=jY#4{%Hubw_-ka^vgvepLWaruHpE0T8#5{OhzO;pRvhj7usGh8KW9aiH%?IXtN&Woe}}02 zXO)O)*8iCj&y)4UhsA&tKS`?pSK@C!f2ik=;&JJAMN}w$9`gSyUJIk^KSbrzE#`gs z^Pu>BmbeJy^@|Ba{HXt0)?;EdWj*d1wZ3ZYENiP_`}%}#x0EWc^Z(irs-Dy}%Jmq# z%5Z#jiAc|1ubWhP-OhK3;~(io%12b||NOJaUwZZTs(tRI_PI$MZ%B`CR4x|h|NK$3 zr(E9>t*=Pi|GAag&7u0$vn=bw0tyqDUiDt`Ox1 z3}=SK@_S?rsgdrEOjpxwLO`t2?l|uPf0%mf14YKQP+W z_tM&z^$$$;3=Ma7ZWtIH7$54(v@UGPXwS$%*Jk;=&XL^W9@p*Y5dRq-64?xmjdsL` z$9noN8yg)Q+Mr6c=B{h+P^)6D{3XqKd8c3B`s>!VG={FwkZzYwR4lI}J~A{sJk&ir zFyMCGCLZXX>{yn`h{o77Iy5>onduvIx2{f!2AmXqBDPxg%V_l)-^ z2Zmj>R;$~#rp$i*>h>$#z6JgD4ccx{q&H|BisF%19*TplLoukkPpx{}VJ@5G6$g1= zYt5|#1qb=EK`|%?`qf|#l6Wo{I2#<3c?oBYkNZ&+@|L+jRO8JcM2+?Gjkvg{zu%vf4!r%uW+eVUq<;0PUvh&m%>eCJd~PMg46tm&z+~6x=2w{y z@6VPwZ-w6)dZT{j$*;40rn-x|hEjbaVqx8r1Gk%}oZgokltXNYz=OZ6^iw0}tM3ffOaG>y+qcer6J7G1RZ)og8YYYOHCF%OHa{8G^X z>(+E9GUAbr#hb)#R_^HgGb26jYN7s~va`?MS*`CGmxH5wa!IylA}b#ie<#F_RqU51 z$5bq8oLu7e42`eu?#gs0Mdh%LuO@Fj8~O8S|G;3+rs2tq*x&|6`@7^Qm}@CM!mOeW1=?Q*)NVMtZFnZeo6uz1=#gWM_#u?;aFqdUVp=^-3q(>I`RO-I_r;p9J-p zXKwS<)v`Co{fjshk>?!;zK3B+(Ms;exy!3bU-z=uABnb*2ThqwcA&@2ObiT*iyNz7 zsVQI0GJ^&edsW$fa^Kq3C1=m2nar3w(XlkMTAb2khQ%3-e~m=6pg6v}LjGSI=BiFJ zoUw1gGxja=jD3qZC60?x(myoej!g{c3k$;JX@5`e(B_WLj!b6r$WW$lxJN8iUN{lM zX>iP+MZ`4%|H4W4kY9_K#>aa^%`a96L)Uw)D87h9&fTaiyS7T+^YR z?w%Z;5Qm?5`9YKyoun>OjESoh13e?F`__wN*QFVmV)taHSf|PC_}CWFe4`sCv+A@^ zuYjm;cx;2d$a7i8t3Pa8zn=H~iXbC#-9+d0()2}N$V&yUuEAD_9u%E3v|&^pYQx(=$PN0D(7Y5?}46vF+{JS%Y+KV$wNn6 zTvob$(?G_Z92aLanPnMqhB!GOA6cRgL;A&LH94@_zYvnTV)JIz60O5(m<_A$NpaLL zJ~A{aD)O(vbq|eCbglD`UPQf1=dMP%oEi2FiP*Sj;bdTc`elMSI7aQ|{%;r90QZIqXQ)P;-dWFxAT z9U3$bFSWJGl*Corft(rK}lq_~ninHdwu$6~a~;VP4#OZGq- zTpaZdY#bXL>>8fywr(N)L*pV|?04g};uLj6TwfN|iqqmgF^?R`0#pD9+>7uj9wQu9%QCjp`(dIPQitdyf zvglORO=H6o!FcQJ9~%~L+x#`H3G3-~{Z0Bk&@96YLqu6V<3`DW&;(|uo z)8ux$F#puJt9x1NuCQe;$6@jp?7Mht@8?Fhe0)IM(AhlTU!sv)SqBUcaUju?*|14m zmGZxhYO-Ht_^m2`!x_(Ok~Hli1YKUeR>+2>)piM zo?}1u*LoUz6~klM#3nKD$GiO5NgSQ5$gJxXH&X`W(UrVImJwGE#7(o_p5dO+zJcD9 zXjpOej*5(m*~Xum#i8Lky-(LiKjMggz_iN~dmw$7_iD!U(s4PayZi%ywcWf6#VMEW z!qF|_3_|QG=CcOuOZ4H_(5SdWHzY>G_=Zg*VzX3-V4?}cL9RML>+KP<_@>c5 zc?Ch-+#4SDCm~TM4D}^jvOSY8>B0RRxXb9$qFOv3`N0qpL%`6IY8#g~HYc`@_Q}gI zhDp0a?tv0+|Ue4ALy$4=N{t&?r=|^n1io^+Epubi;LP`5Cr+;X|9V>(&W27fi6Ck;F5CsnUO8g?~uXTCY6g zooIXF{%Yp_j%C5|3>{q4et?}7u(Jp8dIJCT6XJ~UYB5B`0XglnoJ2tNNZA<#Z zRdiYvchmSlX7kYaq_|%umL|p#?6fZHq&-4QC+z<`uvi{7sNU`#^IJ>4b|V-Ked2&q zx2rnr8W-o*;xtZWGdD$xJY+4cqikz1%H$RxY8B`7biN++?SXD&J>B{UP25$R+pv}n ziurodpI79Z%PzkJy8_w)izlirN@II{7c@vY);Y{+lV4Y^##9T=Y&8x=<{lUp;J<6^05eOj7HuTbm2W2>Y} zFS%`Oh^8%Ad(km!Wz{jme(X9$BBBm43dYoqNgr3Y*_XZSIfl4JzBr>tZOdUirQhF^ zQey^=^8ND>(X$6SFl1Ya1HS|xzhaltvo$k1ps&->0_Uneu<4dE%e>_EOPv|9u3e^c z&iy-56Bm%gVS~7Uc zPG7$g?Z1C%FC7w>#0KOb)B8BJ{meD-ejajm$omU)+?DCsloQ8ZBkFRnyuj7Eqox7m zPsz*h48Y%zU@MR*i3G*apqJsrGpTWTF>`!CzAho-j)_;=ZS_+a9T2Z%P%Kl>wFOh^ zD;;c)Egc*dN6*x(`*&4fZi8;UM(Lji4XyLfWe@yHwK`Q;+dU*-{NZn^`?V6X(ZyMp zY%+1)r6xf!kF`6N?OHnCFXl$^GQGBgMZ8c()v})>X_LNgmFeFqj^M+)m9u@1V1Cv4-NsrE15>u6p{LiHgMwUc|Mh(Mj=wNOc=r-rdj* zupjd-E$CHDeDWAboKVTD;OpoLK!>=JqLQ7vOy#GV33hYx0(!^dxrb#avi0|g^jy`Z za~sV|j=kgwtAFH`5?2lmq^FmOoB#f}p{eeGr~0|=C3q%{kFotbaHa~x?qcprf_SNo zxW=0q?-|`NkQp42R}$naA^cPAmtN?8h2gkdzUWm{BIm_U**0SQ1Xo;w^ItJ3F`qlC zRgHO|Q>YvVBb)rYA#*3L{ti)J>6yC%lo=E+bQZ6Qo)|D(3JR_RiR&mWV+4i_oi6*w zgz7-jziP)DQ?86y&jVeXHm3;kWSmayIxMKgMBgiZ$+RVBD88k&X?eZb9mrPhPif*ZIXfj}+g$&^D_)E0 zo*Zwx`%{O4y|8l^>fcwf@pQ_4g4`pGZ|a-unmdwug{@h3iFjr4_`smt zmi>kslvk1GW&mqc+?MYd6n9I5zr^c1-ZHvH-Yi=;Fd;6&T7%+vqt9~HsY#}1a&la} z&|z|-FFVk$4zw(hR-e1o8toY!n~?7tu*5U6V(OOff)Ee(4~@<}eeRh(+Jr+ z@)p$G(kZ?1ewn2uZmWyeG>9wFmfsw5ff@1QyD^d1R`L4ToHf`tIyr3hiq@1Vy1nBY ztwH~I(h|vxjBS?9Gd?-yKRP)!C>u^@JT}F8J3zGw*a;T`L@*87IpXk$3Yr}}&l(L~^I3c#cxeCQzO58WrUA9HM z=>r~`9N+4<*ND6~I`^30lkymjt&D69ah93ctY5|G=b#6lIxMpKH@Tg%sobG{eQZBqb|vS~PSvjry7CRU+Lo zPWh@qAzF8G%o^60%9kORGM#1&hDyu0LYF~gJo1}Gnq+vU($pV&skW;-fgJT+I5-ptiJ zmtk2nq*A0Hi) zqu+l|mOpifE>ts)J1MtmT5B;j^rCfEJ%ggDn zEb2(KhAUda&K1^W>GY+mR%bdEEnd{IxaGl)B`x9NPF_|lO)i<10<|t{d9btPiLi{0 zmZBZ4)po}DB6+U-S^V!som8P{5?z`6lU7CixtJP6{@JOXDhn*1`*U$nHu#IOmQP}T zE)wtgmY?o_kod64L&U#>{Qn+m9p?WP5+eO@|G!6wztsPf9wOe5dyx2duyrKWAj`^H z4iT>Yca(Vi5bJ31zk{t~tYgK04;Jq%Rka)>zGdQ2@%L-|XB;D*v4H+MPW*kms8iN- zwD?;-Ti1E0h-ID!`!yeIo#6jg`Riq?-}1l5`Tz8za#>Pk-bahS=2<6-{~ltUB;G|T zRr(c>QPHoxhj#pD4#2PL_YIOzodMgd_SziEY?-Fo6PB8D=PlY^Pi=%R&653my8egduzV`m(0cVKh=}!zos&+ zZYrzZfGo>)iO*7y?^}aC#Wsj%M*(%;aeS$SH_xJ*989g2s z@5RnGKO){a9kt#{Hsr@=TJNTKs~?|keU#$go%FnTNAqb`h2nny@l&ivDPHBrCt2U7 zc+)?BK`j4x>qiv7>mBEcO%8w&fk>Z_xe4_O+ia+AVVe4UvzvRb9 zTVJI3_@N>3j`X9fuTgxQA0J^oLGj=D8G>GO51*>a+u(6q zl}~~@lxG@Tx3dH8$`AAqKUr|=x5{1cFs*M6yg}=m2lr@w3*auTZxK97>staZ)B2Xd zt?#LRuY&9KodT~m)p~j0_J1m`f!Aq#&VW~+Q|0U6(fO)hX2JFNY=Gf0!YG(&LDvlid zaSN`;rwgvfXAWGC&pfyup9OF|K8xUbe3roV_^g2I^{s+?4Yj^g;L#V9PlM}vYT({~ ztMW78@jok{1&=IOD4!g7lk&-fyHtMxJVp5w!ShtU1m4)C+Mx`d|5xQz@bC)Ne^cNos^0^* zDW7R@hsxK$>y*z7c%1T?1&>ia4e&VC-$bW;tn*sOp-tsO;5Eu83|^=490j*2pBQ+U z>W_m*DW3#7mAAn?$|nh4qP@rce?tVw;K3ihbymxcgQc`6F&{`6T-@^^ION& zspMhsv&f_1uP2X#UrlaK@*KELaREFBsGbnGN97~nWhx&9*X85jbt<0#*X5Jo(ba0b(%^aWEVy3Z96H5C@H*8~ z0#8v~0gqm#@~MIsDE7b|DnAXb%g=z9seBz=mv4aAseBV$mk)Kc_HT5J%0CRQ*Eb68 zQ297`k=zEalBdCI!9S1GQe zQ~6nRikskdDsOeR_Lr_d3?9BlwL=syLxmR6YS7rZ@@iQ27+NuHOMKQ~4~oO>qv~qw;xhU4IeWN~!fNfx8q}z@t=t3fv+0 zz{?cZ(5d_kc$MN=@EVnGf>-tN%97T8FVglE1#eJ2aq#GyRXZfW%T#|7oyw=d>*Nl& zO|c6eU8k0t1J~sX;0~29f@di%gO{m%1w2m2byMITmG{6)6xYD5Zk7KGxGp~nZd3UN z_%y}V($;>=Q~5BsM;-xBQ9UtmYrV=d4zAnTMyK*g@F>M;@H~}wz?+nh3+_?*9C(W2 z0(hOu7s0Dke;M3LGCr&Vxkv8sOxT$i5)cc^>~T$itd zTT4{^v*5aX6WpQl7TvGV{iw@_!L6mL{s_1(9|JE_`8c>PZ-d**RQ*YCT|Nz7r}7TC zF7JZpm#g}7;JSPPJepADi{P^~Zp+{vm9K#7@>AgD6{>y@T$itb+wzOB#m@}5EwL1{amvR9&%a5%E+r3M zp?nJ9Wy+@r9;bXt;5wf&xXz~n?jEM{nF9AH9}m1p`AmaHDW4iTwZja!&ZiDuUa0bE zfX`4qP4GPBW4)<$9EK^M5V&riFu2Yq0-irpRm-0z~Ta=FtuJcKP>wHq+ z)_E!)2RuacV;0<@d|dDb-QUcC>wNOyI-df#b-K!@1RkY)%HS!=rvhH5e5&9&pDA#i zj|W~nMdeciPf$KH;5Ow`2d_~+v*0?P2Dr|r30{4j$|rPD>-bDjK4I`UV{lkQ7hc)Aomw}jc8h}N$>ZP--QTytts7N6NpO8$mIk+}yaTR}^IdR{ z%ICm~)L#Yg=uIl0BDgMJ2G3LZ3b-ym1zxA}9=I-F1CQRU@|gkG>pKhXQ27S9E^l4Z z+K*)_9|G6qBj9x^9|hOP)p2m=7L|VjT$fLRTeqt6DR5oh0nbzUEVwS81Gh4&{yexY zUj%okdETgOA5%7?*q z`6#&6tLl$|>+%V3kILKNx_k=U=~MNm!FBm8xYe)9yWqNf9^9ky1#n%y1fCyI^_RhQ z`6_sHP?eto*X5_d%T&GwuFKcKqZ?HHv*5aX6TD32txH?`U6&7oN3*K_2)HgE120qg z1h_S%>Pdn-*OVHd!wqS0$wJc0=I@$`Dt*6dlGpJI(ZnpK^_4wUZU!Wf~PK39z(xd9a+Y~og0)V!D~xYJt^?;yOgKFGYQ$A5}>-VaB3_R+p zeB$7CUX@RP*EcG+!K?o+-fk^^lHe}olLFW6p9a_M@1oN{vx(vC;?QC7qI^J|U zhrwfX-#-E#->Ak(6g;0+9s@6vC&2SmzYX5#RP`jm<9dGwZY@;h9q>BUp9Qy1QRQ9m zGQFNW2d=M=<-u**t_$EP@)CH6UMElncNeRCD&SS}DtJ-9-X1(k_0NJQ$Q$7KPpaiM z!RzGKl`u}Iox|W+sy_nmjH>#h;Pr9kG4LX_TO8bZSd~wJ*Qk6FJWu(gz~j{KY4AL? zrvtA0Jqxa{i@M--YM(rKmGUWp>-DXGTQpxyflpIC9=JvAISuZT*TD61XTbAuHJ{hP zbv_Mn{koS>vUQy3`Xk_B+JD8+>2)1(@c4G>ckn8?4c>^W@=0*_^=iFR;5r`%JVyCs z!Q&rN^}FCz@*KF%Cl9XkDS+#IO5ir-QwEPtsC+8m)}-<(c(qIU6u9$U$Kc3c!N9w9{#?1KVuaA%gSTm zMe;a!lso|*C%3`NaDKw@QP%bbrVJFMd$Hjv@cCJu+M!{?PcoN*XLFFF@58t5fOWNQb)t^K^TIHVtw~tYt2Cp5i+yVD!xh}ZA zFIE9h==){h@z<*LngUOed+2&RgGZ?TCU}+ZGghx|ZGZhfk>WM29;NGbQ{Z#=Rl)V^ zKVxfK>(Q_O%!9}EeJ=3o&(%C!1kcx%m%(kSrvmQHsPa|t=ueb;;3=wS8a)5Es^4qi zsn02|gF95uEc%btavR`fa_idGc5|to5V%L>!{F9as{SZ=p6W@0>+2E~aDARw1=r_^ z9(a-JZ-AG{W2x5l((ju{f$RI=Iq>)*_52FBeWCIic!_)lym5=#zUttqTb0j(muIQJ z&}sZwZ*E;Lz1$GEMW5FZ0dG>CQE=~Ol}`-3P96t$zM|&61bCk2ha|XOZVEj7PilP~ z^tf8jEVx7YxZrv69C-X-m1iE@d8_gwc$k)30x!N@m9K!usC*UNqI{;nqvRgA`wmtA zG`L6YIRmbjTL({3dp5x5-lw^)b^J6=R`W>&T$hi7muYFn$cx}Q&k}g?Vzt}~xL$4*yg_+-;5Eu~8r-Ay ztf5nT&VcJY>)_FqD$fSEUTzaSZ>#d5?$&WKOL>ODJ(|ZN;C8QS=P0<&GX`FzJQLu0 zxi)zCQk7>4-0Dzyr@^B%4?Ey_@+^2`RMqc-*N;-`l?T_$Er8cfP~}VDae7@*8T|pZ z+zPn+pz)?&QQ9cVEr{y-lQ{+u>hum7< zI^K%pA@DGrr-Z@t^t#yyc<~B#9VQCy-lX!6ftP8yaq#G6YJN_DH=a@T*x)t#Jg6kN zKAuT|$LYK&4Q`V=;0}2fJWrkjcd38#;C1T90(h9lVG%q<^_Re1@-nzbUIni&R{cE% z?tNUfvj?7fkoJ$@jdkjCO>5v@QI($ox0WiegS(e1p9Rl%DsO;C&rmOG2M8K=G{YJs=sl_1oYnYR@Ei_Zya*sNH74t8|^S39jD{7`?7_9M-7*7ROvf!z8s@+`hI(ZH}PyL$*kN$`1_aeA{eX<8`Q9je) z&KFcW)WFN+GvHy`kJQ1dKT-3*EO_Jf%A4R3%E!9CwI8E;{|H{aN#z*^uaQT=_2(E= z!S(B|r@-yJs^0@o-K~5YTpthA!1eLK47ffXsDta{fmv{UJkS8w#{*4p=ksbDTItsI z)W-uMaD6-w2G_>}5paDx5CzxA12J%YJP;9^N z+cY1}fO~o#0I%u$Q{eh@cp^8nj!%!yYog$dA=SSzaQimparDPjzuVw5RDTk@O!cI| z>*Q(hBAusX!5dV+3mzU*dFH^q+m+|R8`Pdf@G{k30*}+{8Oq=d@(OtVYpQ*wz^6M^ ze|X^D`&6FO;Kicy8hGtAq4X8`gNf(aQ(W_IQqL)`y{~i>q2dCecd<-uD8=Pc$50k0e5$(%f|b*c$;+8%B2`fJp2U=m#SV+uS!td^SwPaUV+0k1!# z+93<>T&0%lf``{A&w&@I-SXhN9}D2RA4}kA>c=v8?K3LR3V4dnr>f|b&lI?BHxFFj zhnfbD9;Mo?25xVp@eJ;CE3c!|>tkopDbEIYah{s@n&A5NvDVG4<2?R4)h{9N@bSvS z;QIBk5pb9CiGu5XjDhQZjDzRjrP{#;57GPXlHm4TYJF4Sse6<=;1Q}P3vNBA%Dd=g z<$3TJ)l&eE((9Ls;MQhUPZ@mnBGn%ia5tvPSHT-^P(B47r~Ro1Zj(=gm&t43)<3BE zY6jdPuY-H!v*6LMs(KpWdGaQBo!q*mb$r@iQ}u+v%j98j>+7m~1l%Eyf_vmKa6NA0 z;QDyp1~2IIDe!Vdjpr12mFA^1c$Bsy2VBoTS@1ZOcfmdJooMnW2cFuc=A}G%?JQNk z0B(hq7r}KtCGhf7s{S%~akugccyyogDtKd$@+t88&y{=NHnqbvxbDXqxSoGz(CKww zv)~EZ-W%XidR=Z4yhyLdwr*`5&-!(_A#hvYj{vWqsw$YWsywH`>*O`?Fs<(lxHY2cnFX(|RLgCEyHtM@yhv_k z)brF@T9!l04T0OV+z9wIEjJ2ooucxLfjczb;^2DxC&2Z1v%!nMQt!t}f!8UYGpZ=ln7Zh~8sPpGeTeC8;hFnE>niGYVGpD4IR<&y?)oUZD3z*E#;S@8Nrs(cQ-LiyyuiT4s@Bs1Pf4Dsr)RsF5d*NQTfn7>-eb* zsW<{&py$WI8&ppMT)&Sj2_C*fwNDCMmv_M9R6Yx?%jduyDxU|}<%{4Rl`nzo@)hvt zTd9A+b$Jimrt;I^y8H~dL**Ob9(ic6wZELVseHoV`g63R;1%k}7C2R(Y1d zQ+H8eHdJ1K0V_fX9cA^82@rzESxsxX!-`uIH1`hSqVY z^9+OQJR{&b<Ev`NY9>J~nuR+A|66-Eg$OzA5nhEy~m2)rPu`zAJf_dcugse!w@l+S=y_p0@(gBO3U@|guM zlQ+R*G#^>n)_$+wptg$;xJTPX7`#p%1-GgG7W_nm*D6nd$H|l6X{tX3UcXM& zlLk-GJm!GAbRl| z9v@ZPe-*q+<)^`G-}aNT<-@j7_CpnMj*IIKK8+}aLR+Al}IJ@Od%4CNmOclW6AmH;pRQn?M@xJZq+q`_0* z9*yTTc+%tBo61MQQ{*vl`{%0t6W}45Uu^IiwNDbfq33yY+P)m{DAk`ur~Y-pZSov= zjp{Fe*Y8vNsS>#LPTDVnJGZO;sDkGyo&qmksJ2HByh>gJFH$@UUZed{!{AMWhiE^q zkL&a}jDp*=z6o%L+y>Wqroi=aOB&qnqTIU(3UwIh3M$eCcdzY&6 zQSj6%?%x#pdX-NaT+fq^!LtT;4W2W2-rz;>Xo2P*@B+mZ z@KjE%R~5XmRrwTn{0`;Q;0`T!2Hc~#4sL%{)iVq3kT=20RDalQ9d90a6ud#tkAc_E zUf>`9$HA?0lqbOBnzdE;{ zI#ziIynLkcFnE#jiGX`YtMXBB$5I{x4~LY;!Rs%meo25g4pHT8aPLJ`J_(*WOqEZ8 zN2&fac%16bf*0OR;|*LNpXAXy)p85qb@C#3_&im-sg_#< zFOpZ^);e$G&sO&tr@(D`z1B2%onCKT2lrm5>X`+1->OYYP}NZG=5Ux`npOQ+@|`o;4bx-3mzsffa~`qmC>nu1>C++wSN`dqI{;n zqZg?1)8N*d)pg?;@FIObP8~c?{WS}&-w)LQudYq{l@8m(^?y!={qpKc0VUni-7 zTl6~ZP`PWSpih-{skAtrxPk>)XZiC-Qo&>*@JO$oMo(8}BY?Y@2K1k)W z;CGR`;4XO%JV%}fzn8oK{sHnL_=Dsn@Ezo3@K2Ffz&}G?1^+zx6!;g(J@7A+PlJDj zyaxVt@)_`NlGnk%O+E|$kK_&T?~^ydYvk5lt>gAbXc@+FM@)-EP zk;lRRhdcp(@KI`f+TdaGB=~9MDe!a2)8LEA9q^UpS@3JgUGN_A9QbYIdGJZ{0{9)| zMew`GOW@}nt=gvyUZC<7@b&Xl`6~GPsQeW82gyC~kC0D;f1JDq{t)>L_@~J0;D1X# z3;sp&2KYaaH^Cnzx3;y8e~&x_{sZzb_)p0r;QvV;1^*Ly4E%8FuQ>PxG!G}hchh!Z zgMT}u`Y{RqX)2!rzw=a8J`H}9p8vs9R8JQC6XY)Vk+fbp@UK$&Jox9Rd;$EsRK5uQ z9r6sVC7Bl2YDF$3i1f}o5`c#H z@&x!%7pU?!_;b|$N$_t_Jt^>eXq=?MABw2@9q^$elxM-eK=r%eL$tm*@NLJadh+0B zQvC(+>uKB;!6#_BCGh*n%i!NRUoE!+zLD~*f)}WsDew+ze-Hc*RDK$KgzB$>-$m;? z1AZ9QQwLu}J`4W$v|bJHuhV#Ff{#%?);+D`e;auSyht7f|0Hp2PV z@Z-vp;0f|HxI>-=FOcWJtK@m`sdLo&7r=|;MexWHRlWp1bCL2IxV|16zCb-bPh5q) zSo~9WwJl43Pdj?tP~JAU{(d2>C%UNpa`pEEV0rzyo9IPDJ^J<3SiWi~ufOjC%j@sE zK-b@=fv&$#16_Z=0eb4f_U%wLxE*g_UVl#r)~~;}1YLhm4!Zt62Xy^8aOnDT_0aX_ zfTHW~2|?H2`+=^%#{*q|F9*8*o(**Uy&35G`!3M+_g%ci>2poc_4bEu({_p8G|~ZKko-!e|`^o^wReA#|>^9JY{gl;I6^*1}_@CZ1AeVJ%iT_ zUN?Bd;MS`4?HM+>exD8Yi+-(taA-XSyuJ0eB>-%-+`u-2P zzTbkLV*8hvcu?=BvIe)=JkQJP_rb{ex$EzHLD%1}g08>M1U<&)XI{Vl-VZFVzkdT= zf8PbV{(cE`{e2GT`uh{m6CJ@g~Kz`g2dQy#BmWbp8E-=vDe$Np$_W zq3Cr(dHwm6SYCh6HoE>CM0EXq(dhc~_Rw9nzu@hxKOYOr>(7TqpElH^zt+kQy`t|qdqU-O!Mc3bdi=JBAemv{%v&HiIdu7o}hI;h( zzG8X(J+A0=Lp}O?RF+Pa^7?y3(X)nn@&=DAZ{KclgC`B{7(8e2qQNT$ z_Y6K`@P@%diT3LoHF(0{DT8MXo;P^O;8lZ98@z7troqE2+P6c@;I_fj26qjvzaJ9E zt^Qs|bp3gd==%Ev(Dmo~qwDVlLf7AufUZB^4qboF9J>CzH}w3<_U)`cFAdA<&oe{U zpEriCKlck=fBqJ_{v0fH{drXA`g5Vs_2)C8>(5C-*PmB}u0J;jU4MQLy8av;bp3fY z==yVI(DmoLpzF_BLD!#mg04Sz1YLjr2fF?o4s`u_80h+QDbV%jL!j%=X+YPXmw>L{ z|BbHSSB#WiB^*{9ZX#4p}zn&V)>({-a>+i9V z{(W{`(PQUj+#Pnki@Rs=6g$u2<@NU(;c`pt_@|}3!S(kiV?Fx&zR>me6rtO zW6W#JZ(}~g{A}iR=I>%Y%X}@%zrp-=Pqwwf8OA;26wvJ*W(#{+Tb%+w6CXpWqS`N+xzV5_TDgf)8Nso+Sd~^ zc--I#gWCpA8oXxk(3$IFgNF?sF?iJAF@whq zo-nv=@T9?022UH@F?iPCuEBE#&l|jA@S4G!2DjE4`q$uLgGUT*8$4<7l)=*mcMP62 zxNGplwe8!%Hh9Y5X@ffk&l=n{c+TK?gBJ{5G1}_^t zbVK|0wCMA)#)E>^!S!@W^dJ z{k(kK;4W*on_2y{tUUKJYX|OmR?i{qyt2va;a+9+a4)cWnk*lSmFGTX@FJ_{1eQ;T zmFMmmyu|7`ht(5i<+)EAyv*vklGPJo<+;}k?y-9AVeOM(<+(QuK1H9KB2#f#JvEcF zemt1vUtslfpJC-sXZ06ZdG0Yb{y)IV&(izv&)NFJVfualkNFo<`L!}WgcVx5c4?mPcpZef0lWY`QI{knExH~9P_U+ z&ojS~wP%s}w^;cS^T(Nc%zwhX#=OqF$$TGki{5AFe+w4NC(Qgf<}v1{GLJLg$lPXr zA@elzCCpvsE12h)U&K7md?oWT^DOfU^Q)M9%&%oW&HT;GXP95dyw3av=4Cc-ypOei zmHA<;{1o%Wth~qkY38%cA7kENeiZX2^F?gA@kuq0$#;b^wi3+evwCdi>YM4*gGuHG zv+^nC{+Of3(#+L6Qq=S^`h z4D(Z1`8xAcna?smjd_Fl8O)o^&tz_G3dUQMd5HO0%)`tVGLJBSE%PYzbC}1Nzn*!V z`MJy!%-_J=W_~{NB=ZZHrIUT1z8^I7Iy%p1(F zVBTbYC39P}td4%~I=27NXGmkO9hIyR%TILDn*D|-6rd6D^z%uCE~VqRu`3-b!|TbWmx zXP8eh?`Q5YA7DPse2{sK`3B}Q%(Kkv%!ioIGT+F&!F-r`llcg9YfCWxN12D1yUfGP zCzwZ=Pcn}(-^4t|d<*k9^BnU8^R3Kn=65hpGJh-c6!W(+PcwfzbBFmmm}i;inY+xl zG0!o-n|Yr3z03>D?_*wM{!Zp4=I>`-W?p1oVg5npRp#57Pci=xbC3C7F`s6BKl2*% zk1(HMUSeKn{@2WBnSYFVgZamqH<|wpb1N5&{|A_dm_Nuo%)HDz!h8qwDDzJ+k1_ug z^EmT|nJ1Wknz_xq!aT|RGt5)WKgT@H{PWBm=8rJXGXDZ|mwA|kNGU~ zZ!&K%-^IMi{M*c}t-<(zf_aGfcbJEnPcx4&|3~Ig=HF!=WBxtnapwQTJi+`)<~H*h z^Ca_sW}afcn|Ye~51Bj6f5be?{Kw2)=1(!tG5;6ldFC_B3(Wr?^CI(~GA}Xz8S^sp zpEIv8{{{0Z^F7R`nE#Tw$Nb-zPc#1&^BVJKn9nf(cjk5Gv&?6i?`7U#{vXVn%zw?? zx+56>zhNF?{-4al%%5c*Vg6g@QRWTiG3NipJkI=g%oEK2o4L*Wf0!qkKgT@9{P)b$ z%>TgLVg5(vS>}IY?lS)~^BnW%ndh0mz`VfxMdn53^VkKl67%`Y%ghgAUSWPH^D6TY z^C{+sGxwMu!F-zek<4q%k77Q<{AlKN=EpFfWqvI42JM$C#hYJkIZyn7@vBp846#3(Q~7yvY1q<|XEDU|wc^9`g$G^O;wfU%-5dIlo@*F^{wI)66@V z*O+%QpJBe3d7b%E=CjO~F>f$m&b-My!Q7(zdWVTQ=8eol%-_U3%=}{J5$2aLk21HJ z$CzKrJkER-^91wDnA^-RXP#u<#XQCQ3g&6%N#+jo)y%WZ*D!aPU(Gzn{2JzY=IfXj zn0GTTGGEWU#QZJH%gnE5USXbQ&UQ8b_vin$!2h+t|Fyu&w!rU>J>!qbyMGf(zUPo{ zo^g_uyw{tY|6(n9_v4{&`OkZC=^u|f$$IhZKa2k!d!}v4^8WSRy?b7K@x{TSAIte? z@9rR;FXLT7e2|QH2C=-MyLU$rA0p%JL42r;w*|4>x$PYf;*gAcgZOY6uM6TMWV|Yf zkCbs|5FaJug+Y9@j28s)F*2SX#K+2b-wSi=8<7B)uh>w@? zjvzik#@mDVL>X@j;*(@N9>nsHcW-YHpDg2bL41mgR|WB@GVToG(`39bh)twtmh|iYs_8>k-#@mAU^)en0 z;+TwkgZNw-uM6Tg$aqx{pC{waAUazb)fEL42u%VfMWh%cA%jv(%m z@%A9TLdM&I_(~a%2XRuyy+OQM#_NLkDjBZ|;x#hv4C1S0yfBEbk@12cUMu7IL42)@ z_x*8h{ZlgD6U1+p@$MjAC*xf~+%4msLA+kZJA(KvGTt7<*U5NW5MM9j@gPpixHpJz zkny@8zEQ@jg7_vGcLwpzGF}+Ox5#)w5Z@}}`9YkK@xDLIt-mAVJwea<9+`#xBg`r?+N0EWV}0wcgT2G5Pw3(JA?R>GTsrypOW$RAbwcJ+k*Jh zG9C}&ii~@M_%kwI7sQ{H@v0#HTN!r-@#kc`Fo-`d;{`$dh>Yh4@fT#g@4x5PzbfNB zLHtD-?+)UfGTs%$e<$OeLHs2d?+D^A%XoVbKPuyGLHzeJ9uMLv8TSV9S7f{{i2p&x ztAhBeGVToGugQ2}5Px093xfDD8P5;mZ^(Gx@8;IulkuJ){-%s~2k|Z$?+W5?$#`cF zKQ7}PLHunQZx7-pWV|hiza!)EAfA?SZxH{ZjMoM6cV)aPh`%S}&LIB2j28y+KgoDO z5I-s7`9b^x8SmRSxBfL5?+N06mhtW&-Yw%@LHt7*?+oG}$#_Q)|5(P`gZL>KZwumo zk@0vC&&aqph<_sEbwT|9WV|Yfe=6h7AbwiL3xoJyWxODWel# zPZ0k?#=C=fkBoN(@h@e(Gl>69#yf)eS2Ern#LvihTM+-djK_m`R>r+SyjRBSg7`mV zyef!)E#uB0{*8#Y;@``7Jcyez?hWEU$aq~4|53)Pg7{A|?hN8T%XncBKQH42 zLHvS@=LhkNGT!&wx%HQ??B2U4h~YJ z5XACE)!z9*EN@Wl-S@0s{}<05JnAHC@YpjixBTlNFP^>Z=+^ith?gDH`uL;sTjNI{ zei-5hAif{s_d|Ri#CJlx8RAih2O+){;_Dz@3-J{YuY`CR#ET$42jVjzJ`v($AU+i0 z7v{CL_j3?G3-L1${|w@%Abt|!Cm?RF<6yir9ei-5hAif{s_d|Ri#CJlx z8RAih2O+){;_Dz@3-J{YuY`CR#ET$42jVjzJ`v($AU+i07hZt=hxl2DpMm&i5I+U+ zlMp`v@naA_3h^TlKMe5$5Z@2+`ysv$;yWSU4Dl$$gAm^e@pTZdh4>1HS3MOABOk=i0_B^{Se;= z@tqKFhIka>L5OdK_&SK!LVN|pDMOABOk=i0_B^{Se;=@tqKF{{M`9d4P^p8}}5Gk!41r(K>3< zNJ&IP(a83wq3JE9sA!S$hPP&7*pD{p{SHZDaoFlN=i!WC^6UL!O%9AnD6(y z&UHV_{fzJX{+Q=%ziTt()mQG|E4T5LoBPU5 zeC0EJ<%Yg;U0?YGU-{@^-}w8=dwu1dzVa`=^0&V7Mqhc2ue{V(p6@Ha=PSSID^Ky2 zpZArY@Rc9;l^^w$hxy8bedPhZ@~yt|4ZdMIZPl?VIE1AOIMedQZ`<(|HBS6{h9q}=iPUf1Oo-<=W&9u5>=)V=NQ{ER^H$fQ6? zm$X3JwfS`d#mJNlJx<2r_$4rQbyoPtK=EaPqRRZVK=A`qM42ZH4?4JWoNXIpuam9tnb?wpx*XP{a2bF*-mRRH1370PcJsWc;#0bmj+8Id7N2!skBX<9CI&8B2e7Aj0uES;)qip01Cp6 z<&w9@Pn4f5#T*AN0>nB zE%6#Yy1NPuLu$2BdCjo@Z>zlk3a8;n+~kW|?Hb(js6wX{crUE>2^EJ<>oM3dRy(mO zoqCy0b)eIvz}U+(lk#=E?t^V8AtgF4s4tZr;3*j-8hfaEew)Y6L|QGikT(XAJ1(`5 zw-As!KDCgCzj7{xmb4BHJ4sbq)8qK0aGIpDHdq=6u8|K>BTwQMcIeK+w2-@$_HolH8ntNiE`mEpZ*F=0k83nGvP}*I^VPu70364^NP_2pso^)an9Niacg@ zs$j;uPh_?qo+W*i&wn$)s9e5O4~g?ywc6d3cszeDBpfbYoK%_TWUrC+xyL7k((tsF z3LX1MW*XS9boM@i5tZ?D!}!T?0Tmbu1w2LXOvKb7CYMT%gI#3|e@60WIDT@26|za) zyHv7>d1hB-<(E0s6VF2BMySZm58+k~}9M4v=%!;M=S+QZ+<+a6sK z@g>Q@s&%>2bZKYQUvuhIq06b%rI*L^-D9Bs;%Hvvp&ma5Y9moKJygGApk@-a9VTbz zFFOWkEI~^Fq6MA@OOC=|R5Crmh_d6RWx4buQ4mBJvvO$xN8?VhRVQ(kyTKVG=*`g| zEBL7kWTjOS*uk5Dl3o}p zE#QMBGLL-`$T zDNzS^c>aG3)MTPID~i@>dJK{OBkWzk7@t;$cUINcT!O}t7g4`(G^?;k6QcTis0GJB zB@uNQQ0!uT^p(aAd!srAp%Quf`@8`FNhWWS^)*zyhr+*zD*avcER!}wf%&Z)oj=9% zgnfyAA84{{^e{n%nFHa-zOm~`T+rjX4be|kz0V@*4x+jjk4%%A?VQkbA2a%|Tu!05 zwrIginq=wmOR_q=zdKuC9Z4fgFM?Q!AVaT|iVM7$2^1?@%Df@dxFMql=DIMe>KWAiOO6>J+D26 zo)0m=$^Q*ML-6BFHq)8wHCXOd&sOgP7oH+l5m~Se1}pkK|HSUa)ibeLAbORH(eCwT zhXx|$^2I+e8)R?c(CZcDAojClM2fW3rgB+`CPtqh)ILEiycOf*^RyQLk*{eBcv^;x zH)MLEgWpHwOd=t)A8?%Iy$wIpk1v<@#1A*lS<;+HgbDp5(`dH(X-cIgX*wHCx^s_S zKPKz;@aizk6^KlRk*b>fU(gd$K+6@jMaOD7SyFu6ok`GkSXd*X6OVx!L(~$7s*sZ{ z^7|>r@f;ZC*^UZb4>Ya38}SSG;tvyXh^0&A0>iBW4zctt;7_uTSX|58EasM|W-^+qmq4=(uBs#j@!T+D*SuvDH_uP&EE z9oz`VEU{|C`_V45f5Fd8{Lt!2;KUw}$3DfLj!*RE_9Pk(d;l{mMK)rmqj&Ink6zQ$ zDATcyMjh%Rs#6V=-Ag*-LKh=Fl;=48`9I2I zuh%hNs$%C(BkF1ob-(e7(LIAQcENu*yZ@8Wp1)1%keXw2iM7V`NvYpe>T>C9Iz-z+ z{pC+eT`5hpl_PdKbKrL}QX7uNnbY9!fnZ_gB>Md!j3FidVPm-tl~F@#NOviO%Kc!@ zvEQIL@?LI~3y@aLdkV4O{k+l?W>&%bM|xyK@Fs4sa_SoEGks7+b6saFCda9FIxRYx z{t4<9fP|Mb$M`HfUzYvo8ctCj<&w(ksjzRQR7ckN^dW>P6z~U9J(k6coCYBg1AVW6 za`}n?Op_`)(U6_E7SgbXb&A#gRila5`ZDVH8-|*8f0z)Y_p6u+xwlFZb=Wx|kzGIF zX9s>JIsMxyU8S@{8X1LA+JVlQL*+EG1N-{MmTR4FczcuWGvr9i>|&s*vwfR}tmQHg z8ye0@_P>iW8yH7<>wzZuF9L|>o2O)jnOSj5fx6EDjIOkz+P7}SPY7{F=(0(iY4oCd zVY}|dT_sRl8<9eOW?mqeTRjhFzF0DP#oqc^2LTp7k`a&Hu+h{5Yp1*YgnawaX09d zpP7;yT%5_LKm)-Kt23o~g_$X=DNfGvYnTMVGR9eL(JW`RZII{nU=wAJ(Qu3L%5V$3 zQV_uUhGq%$kpr+A{5%j0OAjN;mQKjgeGY#ML%cu(Wy?icS0?8n4gV(l&?F2lg|w*=qO2r1*RhaX@?sa)yOrE2~yV9ilK z!((*4$LMO0(bo?;MyGm=E;dF7?^lM7(L`hP4cvna|4XYu(>s~!INa>)_`o~Pj>}{0 z$ZG*-r2+O6$__HR z6clZColTdRU0yj%B!{&y>e7M6;CwI$e@@NPK(n+rs=4XcCtvVC%qbAxsU{rm zPGF=;(8+dw{O&DwX>Qnhg-v&C4@s%@YE} zH7a?Kp9tS!5IC!L^jr1lTXgqWT#tHSh&bVHobjT=?i7#1+azhmdRd3FdUs5j)87Y^gRxZ{nk+a;YcB>lgINV z@~pxgeuF2-8AKKSn13Rp#0(j1*m#cRGN0J}=$FP{>6f^^#Q01W4LiwvE6cdVwCnac zlw4+ki@b>+QXEBKL&kl|nz-c5Z5Bgf$$fHZVRWfiOnK9Z1z zJJ3gc*`4gQ1_5AGaMT?o=>DwV^;^l z-|1yXExoX1SAMmy>U*Sgj;~lo*RtS~J}+trRpi>QoemG}Or|T-i>D|l?iWL?(4E>J z+eeE(%uM4X(vux5kA<7ad~xPB>RD2lxsNGskk_L`El}564Yi!D@Tv3&gj=e1=Q4v# zGl<@1S1#Nw6q2qGe@FDNv9tI2HRCHuK1xuTJpY`tnV_TP$L@VreUv#q^sBC=4BN zy=A=Sf2_QoteV$&@4L&VM2lk~$6g=CptX%q%#2OiS^N79senH=B@D;bd`rP@#~6(3P*nUtb|>4TI8!cx@x zTnkQ6Djx$Ue{6Kpu2L0oUZ^Vi$E{o@5WE^-^_bHQl@&FNvb>Y1sYFrmo2{U6$zq*o z64FqtLViU`8^j-rwW2~zRPl0I>Uy3V+!nyCkb-k%3OOiGa zWD95b1?dgYs71Rl{gd)93lvx531$XL1J-uV%)uNDmgg4t8z}oH!x|;InK^-ydHuLn z1b0Dp$I5T0ac9O{QxT(tpL2}MdB49oYlEl_HOFG(N!+9J_sY9C!xn8Kr=rT#B7Thx zW!=h)=PhSR7o*f7e%~&)c+oUXrcXxFqitDg5kJER0+s{C^Jo>1fd6;}1bLcF4_ypwLl^-oxpfyQ5LJHmx*Bzt7X2tm0NsAfXAury2F=y^D1v3 zSH8O4Id64M>--t7R&Wu(#(*_qj|q%jbDW%qMtXTFEJN@9Zjf`(N;OGbq;@`y+YOEl zTyDt&De@yCq3{NIb`2K9FSsE7umR@%nYn%#N6O5g%oY)aTBt(v0PBuG%UzOs%3}Y) zGX4VF#;zI~nn5-}GF*ZjrUGj7WZ~6tPg_FWu zJ{KPir<29nb)0{q8=PvjkrGeyM)A$))Yk$}Nbpj}G9IFHzd2dn1D0|pemG;+fscHw z5uKeQzM}=)@sMfA(cF_+1DPop$*4@7hChD+Ug^ebD|rnvUR=!NR^yc;*DJ4b$u(Z- ziM*a7ug_tzh+bzIFB(TqGF~l&@fkasWW1`-s|$IJisiMLQ4l(;yw+%eeO!zjd40&5 zs{445Yr-Y5yvD`ydN{(1@fqzk@YuX&lb5WA`;_36h}Xo`GbL~<-5K$y(#7q}xNt9% z;Ut;|B5c3EzvWI7dPg^4_6|${I?Cx(tbzj^nW`^>OZa6u8wydohk2C&_xq!!>%|83h7rA`KN>h|Z_>0( zu03w>HJ=32(T?LP#D^5Hrstu{!hQofR+V^LMrA#({Hr(o8DMA0~=Nttfc zrE(E@a3+z*@rgV-v(xRUUjauR43}_liZ96QUfe};gM(6f1TU`+0Zmlp3MXJ}5;)3O z$OwJO^{OpsbqAWnj)2L5*$LacMv$A#BL)J82=X}4F(z4WaQ_zm8sPF1w5FCb43r)n z1s%^v2>KWx)!@-%pl%@QDWa&K&^&NgzrYqm4f0ScfTHB{jc3fbs^sH|Zto;l$g|Gm zJi`ha;b=|E_ zS!Zy(Z>P5bcL=czdmC-XNqUhd^CxTd+ai;)Zu3y{H6ALH_YCdV>>muJT!e@sEP{5fqV9M;k(>ZN;amsKjG=23z_0a(w9)8y7uF?mWfB9T8% z)VO03tj@!bWa;=luG@-7Sm%!1zJ-V?Nx7X;1JZ@A>bbzt)fQ{rz}o zYivJGi|a?7xPB~Kk{}MQi}e-aWXwt$fG5FOIKd2?1y5(b(AB5u$>t*6sSDH8ntF|? z*1SV`FPauH?|)cPvS<`4WI!s=B_jsPeLT@B8IdRXJbx$|ku9g`EoPj^ey#l)VJ1I0 zQB`kIC;m@vkJ(Fv`0Rc9Ls<1^|L2T3jBhj6IwY#DwQ;s;>roeDhl?q+&d>Td4q zvD3RV=^rDh&YuRPKrTf-tCB{qiqk+t_VNwQg7-73gsOTw=r0*m?=+{LJWwTA4~!Q$ zzhV!107Vf+Dxy@{S4jo$Dwi=7v1BQJ7Vu{teh>px$cf6ri_gmB5aJtpYfIC5m&Q!~ zD=J(UB3=SZvRJDm<+4oEGWpn8lyAo3xJUvJMc6chO*YshgRKLM8tU~0oS2ssQ9oBn ztKkG>af`9&Wh{Caiy|lKmnF^-+8Aug3`~6-#t!XK^iTc`oFH7B1I6#^gORx<15eYKHL?0 zNk=M&g=;uE5-7QZAAL%aS0E+4*yHz$#vq7aQL7Kr(<~2FsYtTyXUMS|%F-|=+kK$R zp^lRkN zCW9f}U@Mgp_m94E55CURa;1b(rfK4%Ii0rq;1_hG@#LET(SyP-=&C7EDYsDWO!tt7%ZPZ~8k<|=^RK%LmNQWf4XBLn5p{?@&Cp4P9%$%&2w!Ny44iLy)BPu{ ztMb~tF?H=5)$Dyh!|Q3dx0qXIQeHxV``Ooc)|ZVF*f`l5N3u|Cg`p_ejT^*&uVEJ- z4ArgiI%QKPR}*wYwEi-!FPG`SlYKL`w~4l&X6<9Gy%x&sWDDu24tfm+?x8 z=btpKkm1H*T_T4i#-W$vu=f+kL9h3Ciy2zt<3}LcT&8UN85W4lA@8>nEPM4VO~RTmoh? z_olVgg`BXyYxbX>U0Owm?}-qfg}U&k6xKlTWik@NINy`m5@gF^jnK-Z71=j1_IiDhU=>~8n!({^ zzydc8OO3b**oL;kLCEoKtE|V$+l=G0s0_^qLieD@6@u$?gAPNgOJ#HjRM=8@j2!$} z=P$1Rh{C|kMD0>;8Z2Br-;u^#CuLEKvFdE4^5gq1GL321u)Qpclf4Q`PAgVmR%JymDUtpVZ zxfiV*qT7iA`uvZe+2>wIiB`~(~{M|yG3pOMtE$wF^ zaOpfUj5`>~pn|99bSRY}bNs%Bql9)~NqhcLO1qZJE_eZZ^Bc;v$HOYAQhs~cEoAqi zoVX(CbeKbT-Sr{q%j8Pp+@AOrNZrCw0#o@W(j^pLK+0_&VBYYGfi?B5FTPkd!27I0lUbP`i;=sz4(gm#Shwp`Z!DY2%@M_x_q{sHsPT4 zU*~cuG7c213rG*E>n#sxU14S*ZXw2-fu*v5etM2_{4buU!M*dkFeGBP3~5i*@EpF6 z4jQaP|77Vh{Dj_zw6=JGIKNq-xG&!$hCOz%BU^D`hXYzX{t^C#LsBZPd)+8-3}`(I zv_Zamafj~3!@MqTm9N1z{1p`83CEVrpe$LG4dru7rf1OK?_cYl)R{o0#f$Wq5ic=Z zfUEoz`5RBrP>)FND(*?Hj7tJrN2fU2mO$S>0HQ{YYomn zQA2OvhBTbxILwH0Sg!=&Fv&P9h;Vq+IJ{{brf7=iaSu47$M;B${v-XgVMNo*qjLIt za=$WO866X-R2pzKapK=0Nez%l&RqNqdXIz9H#0rA?RL)FQatjK zAw>XT-s1V0^w{TT(&Z7rr3PBPskg`l*fP)gWtm)sMw}!LlzQw~N%Ggv;BdcWB<^(b z9s4dx(nuGna@qf!TMJX7E1X*V9&nNwbFdcjw2r;3p*kWGcE_7D-{xpRHCKF5i*Z|S zBlfv5_z;#&*mAiau<$2xH5luD`Z^Vl->FsnF1qHqM5%mE^>MS^Y#0I(>T|b|4)ke0 zhorlxEQqdDF!pOrE2O0o6=tr(phxL+Qa(uc0?A`Lv88?{Gil?^?@|`NpMd8fAzq$g zJhT**)EN&bt%Qg-it~tQj16=ti-KqMO=R@~S;00#iMq;|ZDL`zlJIp`s5H&!Ilm$*H8Yiv$~94ysvDP4X&4 z0@D$x%!;z?XDo&OvC;_lu`pi?+%duOZEM+v7O&fzj3ra)9c5X^SWY6Bp+-23g*&V; znS~pyFbV~4B=RmqLmj>E^hoAFS^2u_?@Z#GC>}8#^=V|p<2_<{?j{g($}^R9iy~GV z2`-^kDQJXEay|c=W4?|KxL&WE5VO*li>)w?g*jH3i~=Q3weqA`<8nFVV#7tO zXH;@EO8(`L8;yZ@cFsvY-6W64)v{dU@nhjiD+H)hYb)fSK*{G?c@&V5F(6a+8L51; zFw*CsiO3<>-5S&^&J3_nYK1I{_}U5?CSrw^vtvZ$(PHczQu$w0L=zLSjf{ducz`B* z#0vXZ7-9u6``u>cZ87%SWFnYK-KdC_(_p{e*sFBpoc&S@GZ}|&orRwo0%)S_E!uv06!ga3kA%6;=&o2~n*gJQiEwz9C; z3d>oTV}-dayl#bQEIen0Ni2-F!cfW|VTFM#47Nf)7W!MEHw)KWA&-S_RtT`r&I&m! zTxf+BEM!y*0FF43mAxARym%P#gky$TemQ9icMzW90W?7*H zTc%hcC5G81GV5i`29jBdF$<7nkdYi9vsXZ^U+Gm6t}5BG$_oA1^05^JEfJeFCcQDs zBS~XpHk>4dMuJO9jJFkrvgKYY?2BQxiOd=sv)&~6<`t*rD3V-iBpGZu-wNq0oMD9n zG0gJLCjCc_K8vVv#%wDKyKv<|Z`j7d&sNyV(b!~#O(<}YUG9}V=G<7oTo+ji8A2g$ zJI*u_>r|c*E+^NAt+0TF`>Ze*1&X-E$}>^+*73Y^oCu~;J1XMSmvI4lhpusF1Hm=! zJg#xyzl1gJ3~%{kAj+n5{zlVMHZ?*{=YmIdJ*lR%=_-$kB6TO6h-!itupi6xa&d9y zauzmh?&4jUn3kvuGd&$I11!? zg_S4AaLvnfT$#$=c@eJKpAQaLS3N6?`U_oM@FKc83^}zOV^A9CG8*VrHeKu)$ZHzP zrZH?9U`+!VX_D#
spm%SziXly#;A2j8%sXlUQaj)q*HeJl7?$$Jr0TZc;+0>9t zqdh9GX(gKuPe#)xUK7I_9jD(>&5Oa_a;jbo^0F|Exsv4n-Oop07iZ4J66p?23Nwc? zk6o`HpW@cHWtOvs4{Psw#VI?*_f(ab5k_Z@8|;HGhkw zd_Lzv+oenL8`KE7?qe&DPc14&Z+P&r_a$8GBfX(Nj=~7+UR(pRc#Y498((G7D~mN! z@b7Wx{!z+*hsS5|9K`Z_19&4N4|YwGJBQPVYnPtL!YNaos!z^kIE3d*p_iP5pTOAa zIB_Yip4q+an$)6!JF4T~)NF^k!PT^Fzkhikw}_WG@REXF9LU|D&_p;9AB)usYo&yL zIu0QJ%RIQA!u?ga3eQx!2iLGzPo@7&1=>)7r{2P0#tX9RIV^)SWF^dJ2QcBEyo{Y& ztqv7nn7reen?UDYP79WsAMB97UPR@8IhZg7Pxw*`JE9~L!98>->q{1;pd+#f)X3{K z(HxgwM;lEi*Rx4-4_M^}|DnoLkd>xrVb@0!T|AOOWC{Xw?>HaVikDOBTi zZN&XJ^oUGWpqBA{KEh@dSac@NK*T;xWv4$ixaC9cK>^hqNoLogc zpMXT3#`k#7c~Ai$bdmOlc&o2mw&1oKy?~dck>kD8q980wUEjol<8|^Sb$#d10lZc? zjTn8;CclGRh)#tsm7OnuecQkDuf@St_pxg-BpLE>{tQWnNnXO|A%0y?S9FZz!`V); zpOm{_k-`T#u>Ewrd~F3H0i|)r$*F}G658t-xXn3q8@N*oX`(k_;vS&Aoc-F!)khK4 z6_KBrp|d*BbPfMgwH{{PjJ~k4cf>CFt7HrMDM{MPJ^A%u!S171>oL+JD`D+j@%VyG z^2Us)0dGQ{09^6l*78vAYg^BUU!*GOcs`qB5qJKr%XecgP<`n&FxpJ|{2X#}13N>R zlDwUg7gqJzj8ZI5aw<7EqAT8|(JSQA130I~a|`Ms8y>~2Bkzdz3`LYl7qAcGMKDFA zSY-=VE{kZ>7{$Ru?thQ`uAtM#y z-ieiIR-GmTP#qd%?qV-Kob;3%hWO*|QhAA!dCT*9f?kT3ZhHiG%Rlb`3+>J{4N~NH ztwH-XzNwd5R8Bpv1 zy%siqljS}zKh|4h*RpNws_gIz8df)IO#d8i*lzkKOLIUdB8?*O{#;{9eXk(Y1~ zTyYiBQ0Qh-g6lw6yxNLbT>0^V(5F1IC~^ABt=~H1QD1!D*?CF2)POpnw+IBEe&CZ@ zI6+Iw;jx&8SQR)WDf21$?g@DQ1dYPLII?aOoF})yU%iF&S{?4v1X%v}G7RRSJ&a{) zVJ*m%QD7T7j?&?3^*?iSg=b$;3A#`mfOASKu)uxg3Yh>goO5HGIQapstiK=S@XkO9 z-^PFZFFuLxe~3_-%_6g%&(LW2#sOKw8`5E^DZ*E^w;d=Gc5T-!ihyvQ* zsulR|IVf-v6~G>F?^G&^Ue$k;9tFhN0y~S!|UWt%+TE6PE1x# z=XG3!@E+9^#`z7}y~>xLN`r&oajo04&V7tr_G3gW2BO@vDHr2%73F+12|qbg;Na6! zQj+lQ!;}m z%owA4SW~s-5Y6KHQOTVx`?$QSaSigJIY*;BIw%3YPo}BzXr@^_FN4$@k5gRU^&k1r zAo6hCJgnDluAAj9uie~^JT3mCre(4jX($+_Tj{XM^JAA+x><_H`GKZo@-ouUwNbia zhgG`ATwduOP&}R&(6mhMKpJWkrMu2ym9Cr1E8S&^$NHivo_|Fe`t?ZEMyF~6o+onv z`fLr&R!XIYTh7jZy1eo)Lq60khR3%$zwo^mP1Vl4zMy>;A@%G$$K{pBbmT+Tz(ejS z!Sy9pMfJ*8P>}P`=B>IvY9LW6o8cOhq3bgioQ#TszE993)s%|&e<3fynv!52z1hHFhQTI6_Ul^pdkrj<_ucXT3t z4&ul2fY}I^Lqnk;^_s>NE;^d~AE%o5e+?fvH5va$)zpCg=t^U9gc2KuV|48W@JsnKFVUS4Z#wwwz zW_?QTNj1Bh_}8igYY?-Ov$Zk7r{gD3g8OZZ$A^G|q0rr$;{8&(iB7#<?c zjH{&RxTO~9KhHqFf<~1g%jQyTJYNF>d>E0R=y+6q81IW_~L+L=MXOl4_m%0(&carxqOu+D$=KJBDUZ%_`^6Q)v z-MO~Zi0RUG)O%-AT$k`57`v2Hj;7C=d0lE8>Cy|}JZrfYGC^~GMtYH4iE)>9 z92|EAei0brYuZ_;F-7DjM!n#j6aTfm0%*qxcZ)7Pe&+hArq{uokajfDEf_1=guyUL zt7pSE0;nV+oe1s#SoQFICNy#SA8)LAZX8|x`f`EkMt{Yq3TN97rXlt}i_q5vsWbM$ zI7)rrwT^oFq2ux!xqn{c)|w;XVbTi9Npt?(R7CErPl7*ixZ54Af%M?QKb@Pryqnc! za!%7)nvQ6a!gTCsSpVL2LmGe{G96a}p&p}B^ncv|fa`bp(g5cXFa`kjeiv`#bfJB= z6{_H`_Bg?x9&v)Xj6k2WP4GKePVn&%?EPb#)!~_Lz*dLfVkZ2A{_2d>vl)Ku>sm;s z_1=bH4rw;_bL>dSwZMMva#`5VnJe@?rl=#jDe5W7;1ymdM`5Z344pbI#(ln|?oI7k zx!wGxS<$0%v?rp3=e-7Qiw| z;jwu7jRA;k8;j-WGq7fF@0jI!y9hL)I%wt{F?{Zbzy|^B(ROG4Sy;^Vxbb;_!h1Y1 z<4MvEzy#&-j9x7?$_ePV9ETtLFD3jBq$2)mjUcMkW37Go)@zKeZJk{)+lBn*Id%xi`ZPAr{cXwx^6TTW-W{nD9acP%|uE zf#4RY7t!x-AY}#V^w`Lj+=5T!%rQ~Lx244@elipfT}k6_fSF7-xQ1uP65wB(>Av>m3W5%jQsqhj&>YozSwQVbCXk&Y6x zhLA%wT1N-(Oz@OD!4THIFwD7!=l7v*ZgBs?Rc_4Q6jql@^K&`(@I8dHIqA#g=uFP| z3b_ID--(<^E@#@}GniQIkAF~*0v=nOrK@s>=-_(Eg+hA}?EsHHc4 zINs$?VZ6b)V2FG)O4WVTxIS-OzjjDxt_<$^by*+2mcK{ViibL674+*+6;Z@l50C0h{s4qsx+#$T(%lr;QF_dZzf-vsOlu0qL z>PllY!_6^(n?qDPOFCFCTQ1R@{}FC|H~ww)Pi6bd3~rMq<0}*>p(z-L-;fnBQTO04 zJisr*_SL=ZFVWX8P9Q{In;MUCiOz>)nTP;J#(~uH?8_L@Xusjvc@fY41}r(0i_uJ> zA0pMAn$NWJUc#q4lI@?cTtNScm(!g7^DD*}|373S$qPUp+Iy6Pz9)kYe?t0k?0OvzBpQiaRPm?smt?nPaR|2<+>)jQUI*6X-24$MDI)HeNk=Sxj z;omg4#<6IO+;$qq!c#JYKJn5B8nZmLa1@qbkm3KqWXMNg5e|7atDylRhL)>APQ+%@ zK4uWk!rNDgdqq2iA~ggSLpnU>q!^(k;?JDvXZ{UuJtI ztp^$5_h9jtomroisQ_7bpMBk#bvI)$40pQxh8%YkUN7qR{tS7qAy=^eVGJ2TAF;52 z*TK@1>~RZm!Dd+OvkN4`h%LjcM!n}hkrj(l7yJX>C=)bx1>Jq%(TX+RF1qX zOF#}KgA}UOiOM+m*2f%tQUYAhj=p!!&ExO)3^^bHsr{Wp|J(I2es=I@8-ISp4|U=7 z1%)?DAZ?Qc#k`pN8ZExAtwJF@v*gS*&qQ#KbGo7Mj2)S~m?p_FtY*>rJi z*ry*Jb-jPuPvTC_esn%as8Z)>8VXf(>O{q-)IIW(6r%T zd>r+qiH7X#N2V6_#?nD_kP=o6cjI`vA6IZ52k9=yQI2Tr6W1{|cO{F_U?GnfpKlU? zIw{VGYWBw?uHWw@Ao1@m@O>pZYjekqgT2z=BmD5xq9t4cL9(1AhaW^oY*8tH)lKSd zi8N1`6RZCke7V8X{qTbO*vbC%QG-5b&^>yM6>E?7gtm!+-fPem3DDCCtwp7~LTTy9 zpUe4kDSukxhrODRK&LZnv-1WSa zm@H4{&nfuP7{0><_W($f>uN%sxVHtfXuJ17$Ec&LvW;tR&GskAcYOgZg!ey#j@kGB zNnob4w?DzJ04y&U#WJIKE0IF~f$l{nek~)gIQ3GC3e9P2k!x3DI2a6<@)j-knb#ih zQx#~ZzK3J5Q~yigTA+GzA+p;skWUi1fymYP(bKNQFLCGeKTf9`Y=4zo zCNEYAQPCa9@F6nHSJC+Y994pqUp?d3y-LVHj?Z3>c2i^3m^k$2Ax2~gD(dfBCrJf<{jWDsS=g%tqkaDq6o?InmHkG=`ggj-?ki}IA_fJZtIfdLq{&yPx zzDD%nv55}S#V!FpP=W(|EYdPg!8}YKi5y3?fHlzN=bQN83Es{>H8w2AJpEyn8E|<7I3Kz27T5ZYwZ0x{oy^vc10{(uG)gD zL*E=tq^xI@>xVeX{g;C>mz1AwO~IqY@p85&^Z6Ep>@OL71>t89{_?kp@DCNvC(7vjHPOizwr;IO&@3k>er2(EwXBfN-;k=#-UG#Y({8A6T_deI*hJ^o* z@WbG)M%@{s=Z$Q6|6eor=P@nq+46$d61{`6TFzn1NVNDJWnncs3i~$Hq)%=K>5P9u zk8X&#r2NK;%RSaNLMUg*KCTaUgEv{UkXw*rbl;0LSRa=3a_d9-X))_VYS9>-%=rHb zm>}e$M?Z~~woDosw{%H$T)1N7gHiY_Z=h~qeB-Wr7aggo*EZGg>W0%Hc)eRnvZY)< zRfPv$W2L)I>SRckYcM);6^97QXUH^gr8iF|chscI6YMkoA|CRy#UEXqRBAQ>Lc&Fk z!>z_a^-~VHBPSKqddACMqI?Txbgb zsOA#_-?MxhIO^L4Zt0oErDxM|Zs{362&5RCxp<;cY7u?*zQ{PU;qHHHx;vGA4o?_| zuEt?7Ijlzn5jqs*5c)AX$H=V_x$(==er`F&?ZCZGpA2#vL2h6E5z!}H+Z%MoKjgRm zF!=EyLa!k}lFsO`8DJ~Rw^kwW%Oq!jaVBuir4V=`(LMHaR`L_=x>BpTUIUsI?kzVO z{xRZzK-dr}3{|1vahWS0DXkKyg(Bikvrlalw)hu~@ptJ6Kts%XpO2-yz?(-tcXH{XFNk-pW zx*Gjp(ldS!)%Y#3v;7R8BMlATf%q4Rf1oM{dW^9RoTcmloaI&P8xJQ@x0!XpDtdM3 zi0f63%)Q%@Z^i$cl2(-R+V;qhN9R!^lQNndFZC?=MiuTjRawKCZZOV|lJob7heNmi zp4i`^5lxyHz9;c-6Q2b8c!N5b6=gQ4+=$1q;(|kwVP}80S3tWLqjhpSL4Q;+s}I^^ z=s7ZHfHS~%_|I3;lK8)OM#P4D`Tb$J5~6z#8r@XV9YW+A3QLr(o2U0Swwxaw7WtAv zGIYI^y6!m`(O>2h*(SzY-!NnyB3A+#D8Zw61h+LmdRblt%dYq&TY-hdq7x8q5H>Ke4ERC zh&)>^HL8muROccW>I#FoUNtm8-3XvM0p~^lf8)A>{o?h7>-Ki!Le(RHZw&Bx1h9gD z?dm^~NSQB{$tQ>SE?JrU?@rZRUc4Ay@E78PP}h{2p3_>Fdi;&?MLH%9^OKbnnXVaE&b?eKs$|YF#My$e~&AdQ0?l8_@RbR zktT-kN&MTyKlLxyi+IE5MEL)6yX*0p#6Lv*eMb}VX%YMy!|%Na`0m8#R=Nor%8S_v zE@I1-RuO6w)6#$~SyhbVy9ZpKQ{;A&F@Z96;G!sWKKkt0{2Nx3*)|;d(K0mtLbiON zt7&|9uQk@arG~M-h^!|N-}7K%cN<6W-}QIqsca7X&BV7jWZmr_BRPjH*LgZIzVNhd z!j`sP%Y`v5wb^nOD*S^py}}#(n@sv>O8*Jba%lA5iP}D3_!Mbs_-l!Om-svWF>U9? zEc#EgAjWy$aqjdxyzRl@h zpZLMVk3C}6D~Q>8u4l{L-sasWrllQQdU!1zV_GuU(#mT&FQ(-Lwlwlu>cq6{{x4c8 zu?+{XKf;z|Po;xLqHEagYzd>nZ<&L5JI<*zr?0ckcTFLqCGk(5 zl&I2r#Y3f02A@fIHNx+#Zz_$75zM_dbiY-E2E?>{$(G(#s5HP-%9hhjMrX>HO8ifC z6IE*CskEn$>p=s;hZ6o>s;RUG%buF+cgt|I=|RZ1F%_4yVl^uKR@!WD=VeRKWW0~B z2}o_?vuh=)G+ptq(#-}RL-^0QkO`d~A1kO|czA?%$90iOU2=+2lQi02o?UmRp4t(^nh%ceY3OQmh&LJ1@TwcaMEe5vsf|HIEG$9 zCQxFl+6*)~7B3;k#pY?&V4@wmvZ__>F0N`{-s*_b za7XW;``VH!7^fD!#AntZ_kJ*!*?nAZu{1>!i?Cr#okf z#Sc?FRJzdMy$GL6_*rMz=s%1_%`}nc+2U1%usBCr9$^bB{3_M=L~Q8odi@9fhm`an z{DZSi#3?b1TCs%{enuPidVL#ZoMw_!HRA6%GqGF>lpzU%3 z4>mZrxH5vtCT2TVALY|Dia9faIhmMc5lnIvbBLjo4&6Q~^)fJi1D1th5lsK7y(qm@ z)}9T6oK5u5W{LLuglI4f$PmN7K>Q!LNC|bzOvDF`dq+dxL-Z=5>w13p1eEgT`a5j# zDnj`&EtA;dRfKMiX&J^AR^To>o=;+r(Vc#_xEw$$%Xutgr*RAi~>^&)Rmq9ywD;OS&i3rq-|4rq8Yb1yQtURuJNVwmCi5@YrdQ`}9@ zigG%eoIa&z98(?n4d#mBS0NW0zov=&aEBQ8*TIhuHPl2q{@vE=G zYdj{hj!&%0m}79+06&pr72YjvZMXCx_qWRke3Ez19YZpD49TZ~g4e)BPxl6lrm1Zn zS}qrmD|F3N?tTwdqufIQGp=KwD&*hWT%Z188gD^7)KD&$a}7ME6GjF@t~Y+~8owFG z;I~`7?pSjy%CEZeE0@0D!y&ug_~shlKyjOrh}#r1nXQa+7bE@f6z%9_P8+!$}N>UFGElP$HH z`K(csy=yfySfeI;$!eZP8ZlXsRgPq(XR@JIIgpiCn(6vj<#nvQ&?>uHWe23}VjHGa zbn#L1qK1aAi_~?oy4C#K7d4CJxjbi!Jt)!#cCcEz_@mWqW{q}nz14im8tvl8R>SMX zNEctX%9mK_b+N=Mi&*J(aky0uWhJ}F(YXT!cC8OnY&A3Ewi^Av&eP!B^5ZpV*VXM} zWm7Iqjk2*)#yOcT$@hTFQB?MEy{ zl~R0Y6z?Jht1b~%FI&SiY?$Z3zitnJX=^U%dKVs($ENK%F0<* zIh~cbUen6wt?~(0!ZEaRv{gRD%FC_tzgBrCE6=ma8?EvhR-S}PHxF`9^z~Ogc03$M zR$lF-==BBks&C+|sC(;kgM9$ziuWf>ji_*3|9_Bj zG_PVB@3ZRYPs2Io3+%X#>>R+tYvC5Wgl@>f3fFKV^Y6L*QA9W7{STuY@ZQTbo_BA0 zRvYkk6rUT#Dx}_IUSM^+UgTuvGBLyIUSZt~S2xM(#+){pfwCZ>ee~Pyj?5H z}2HW-P9SaaZ$003-42QpDns3~|+no66ilgihh-m@8+l zn7JLyjb`pgFp_LU%SZHE}Q7kk=t7g%*Bt95BQ)oM;+jV?_oR+GdUU7G&U zP^e7yB6UmC?^g2@(#X>ErB$wFCEQ3AUucydu+rPo->}M8S$Ux$Ct2lqR;F9!2&;Sm zDf>N$X%+pR2XCRBczr=TbwY}M|J2P@Ut-l4uv+_lw$+@<8tr$Q)ugaS`+Zd7BRpS> z)b)F})%=b$((muA@=I2F{a(R>7vO$mh}o=cjjqvkrfDU@g_-N(qahmZX>$3ZtFz9zz=c;t9G+J?C!vZ4JW6`Rp3MXZ-{MR;1S@+&TK}JjVU2ooncNBpjt(liP!>+4dK!}q>1??yX=iLE$Gst^hJ6fdWFd$nhHw_H zp(NmU6nhcYLUijdG$j1h$q`tZNlR?4py1bwe* znS6!RXA&K(Mj$8teNt|etH=m@K$=W5!pS6rxh5qtaQ+W(k@_GbmqAK|_}_^8D3SkD zfGT*JIy?UVBOv&)iHyr`7*uF8seh(1<`&kM5Otx;>XyO;6IdO2mAr^lFa(J`Az+@py6(e*y(|GX~jMYR1S| z!oVXAfPd{M(3;v$GndV#BCuURmSS_{#p2f3wIH?VbL;L95Ogo@f_LFz=!?J34f5Yf z1|O-8pX>4c(&FS>d$@P#Q@j`1^?OST7-{&q7Cc53&Y%j#$y2U!@4(NcAbkhEGyWyb zG*v$N*IdUmBib?y8h0=5ri!%44c=KjuX}M<$qn+`0nn#kM9HX%JdMQ#sQ&9`*~zi^ zRgIT?c9pU-o$R|3WgkL|CmSCGIHqje!1ByvveD7@#xLGLFH~jrf*WX{f8ldpZ_*M> z9)6d8F<>i8=6u+M9L3AM31Yj z;0md(X{G#Ys;A(&`{=fei+lY4XV8)4dxdc4x((`uKb3*1Kq+^(C1|4#A8A@C?QQdX zBSQ1C=I{()oB&m98)x5XsumKIx?D;n1k}f;2?a*s8Z24T*o8&rl zI_$`vOJ~b;<%+oluYpVFSI5im$#nsPCf;nC23B&fjd6nbQu&f@eWHrT=G>p6pwvw& z(l@CK^wS+vbP5358kq3cvavl#N?On57a_(3VnToDa;R%nbM#-;Cb@lgH%IN`8JxXe zgQb2s19K#^UoNL5xLgh(q9d5$jNJb}+q!w+*oMi7-gG`d5;(8fv52NjpKO_(jB&kDD0f>@L{OQ1-w*0w-KNs=meEyuvpA7tf zh!c(R8TsF5{O?NOpIU^s0kk`BN8O@>k+m_h<_Tm4+LK{Xl3GSm%}5Sw1QR=@`LJKP zbOMPynvI`_@MCIj1ej{BArZ{5G?7^4oe-7xvXQv!i&800BvE;r;SN%l@@huq-D<=) zkO=a6CJ?696dj{4JiMs}8wosvN2{OPtR$zQm5V9$0VrKI1P#(8{d(c>m5i>lsn zDSj9#$GgZ#MjA;$0!eC7OB?S`=qrD(|m(N7x|Ju8}MVMImwNPt4Wbzn!`~DhCCXDs;EWqGx_HdYUKW_fOH2KC!AoPBJGb&IEI8vK*(sZf#MJ- z)iwgDA1mo*I>5CcAeJYWVO$(lN-1;enA^fY3o3u%1zfA>NZQwhsN#9i2ijDKCsSiM z=f5fKOogXC(x4LTCCw8p$;C&LS~$28a@Qc*>e}ALZ2Xdu7jg|nUb-l=dd?Eo(-s8gif8p4e1WQp%(uUME~Ox%9VNC;8K_FlNWVcT-&?P zEup1Y=R02C>$>FFKuP=QLlL7- z!Ia^r-SC-Ae3pGVy&+gV6OWb##vVu=hN0WZ+ne~Fq)xSJkbuTc7}sinu}6+8Na;A? zoit8P7vO_7?Q@WO6zk=$G$5k zElY#eaywRaJi}SiH!}ktAe1{8+LW}u>UVy%x0Fx2*5?2R_fnt7)dV~6Pf|E3)~R-I z=rXyGj8XN521cdwDpN=gL^_{Z^fGN!+~9RON^$G!F4IdSxdY~QihPg7Hb#*jD66FP zr`scn=>Pt3iX736)>Gt)s3J33I7Lo3MNUpoq~J6tafVZ3V>_qBFBky{f>a9e;|_)J z{a@`Z-bX;nP98w2^Mio!4*f0jz_ScI-N2s_{5(7|793pdy1EzR&o_j3(Bk{qmy*`I ze`7~cxl&#`!cO25cI9%iHezhl=B08ySH$2iROge6m@SoyRWk1XGmW!(K|6G{B@7LF zZ*S|m`X@)KWRd=7&9z~y;PDi?vs^)QJPh_yfFE|CyL)+b4Ya{ONT*_pG+QRysbD-0 z+^;E>!;s@_voiWA>y45LhH3-;m-#f=!DynSb%%NUuqGZ&UM+l+N8K6rZ|>}#XCksA z&Q#DI9lHsGhmM_yj!~ggqXJpHI+5s1>U9TTG6kHeoXT7&<(LBD4KiNkmCH7UN4m{? ziyTe8ku@dBw`EZx4=Z(n8>>eA&xH=1CI@z=;yuMh`i$&Enzm$7I#;1dO1+2=4N4*N zP~-F6c-9a*z+_ZLy5;^g2(@1VH*~JD5*tout`n{n7YMzOqggJTL9E75*I*ux6_bSNHuS7vZ*!D=a+V;Im=``iCl)i9} z(SHi6(8*X7A{JaNvy~Hf=IO|hi zr11EM|6DO4MoRyuBzz9cZQn2RCe#; z_{PaRg#-ILq{vyO;DZ2%XG>7E&&91k8q3vL()za;t*$(%IG$d9hsl@QAlT^r^+E+aPU_sG0WD!5T z=^sDCXqbCXw5G8tWC{jRx*O?hD%DMcB8i$Q=<0PEjAS0uV0FluDY{P-TjUEO57+fRoh{IrurDFy6pc$S@@}rmeAB+>*9Y01xuGsf*g4b z^#p}5%y@nT|6f9>aS63U{ts(!9&b|>{*OzPN~VwoQ;4FZI;ELXE|F$aGLMl4iiBjm zj#C;WQHBsvDpV4gE)|ub62&#&=O%8Yx*G6(zn^FAb@smJ-rx88`usls?6uE1Ydz0< zz2DEX*4o3_d)A|TURbX5!B@~6kE}e2GyId~r8cd7h>5M_hr_wL$!@k6Sdgq^u=4UF z239dI!mNCS4&a&Dc+o*q`K>1W#VeM%vV5UW&gPt(h<*B#4H;m3A;Vnnh04KeFaeTp zJUh-c4<4Ah`7hXN2&dWC?JrSC-ZD#{Uja*XouzklI+orv19Q{R;@}1&c(q%vWXf@b zLh#-1I%8$Z&-jilI_*L~K*x6djQbrvB8RxYgWn_4LhB{H+wB9?lS5!b8Qn-mTM!pa zOvF!M6z>zE4PGd%0qht8nx+4WmDEZ7F2J^Mzivufbf6uMkJ6H+S6v8WiDfF){U0h8 zyv3n{zVP#j{j{6+B3#q7VQV;Ua~0LFUBd?(w$DBjos$mOT>*VM7V&nM0PUHSTWCg!J;J*LbeSaIirxrV5 zj3eoVyO0a;JqN5OV-Alf%aQZc1fKVeDl|3E`HxoBrNFNUPN}V$W%A;|dk-UP*ULHh zhMLMF&fCYC1$ui2CJ1N(s?ggF1$%pz-j-1c#`ZzE*}ToeH|njh^VYOrZ#Ow_HJ!I_ zxIj;#LHkyg-dZHRecMO-c0=IpWu1R9p6)ELZ<`PT?AsDlVc$9y>}@s&h21rL-@2K% zZ}5%w?Lsz%iHDsxKF>d-8@+U9z@f_R>g|N+dJuh!R@J`Mr?;cMWmgF8PRmfiNiKl4N`m4TiY$aOJ z_7awkha1?)@lcQZfPdO{<6#)%lZhl7=|OD_b~gHlZ2YYYKI8I`o6a(}nT;FFMwS%m zWl6a~r_H=0;myjw1~BfY+m7_uLM5iEHQY~+Z&Jq%J-zi4be6L(z@`i~FvFp0Vo#%_ zy>k}LNp&_8?MTKrbw>A>J7-ThXVFGFh4!Vhx2s|^3mb5gC3Vyl?*C!%rwncC>Kf;& zs_)l2R)+JE1^0{bD>u>Awb;0Reb&SJHQG6gLR4oPTx>1cMiSYtHqO}$d_#oMM%u55 zXe67fVDl9=+OK=nRgRoraKAb_S54Fv$;iPHiv7CUxr)wVs#hJl>P}akupz!r(1?u- z=i5l<$XrOvDw#i65RImv6tZ=!-M~;d)l4%K#&y@R_D>8&+OMbanK9icUlU4Ux&{*d z?*(rbhiAKfwZ}K9ezjls((m)|B4e?khdmgb3Ho9-!si)ZS>yVrga-_qkIK~eWs}Tq z1eYssq3OZ(Y2@7ZPf z)K>Q@>ef0TO&RmeKc0uqw~5TKTEIH3oRj zaQ^(+)$yn&UD4U>5+~fjJ&$;04@O;%%sf0hfS&`FFeRP)ITzcj<@uwbuhVzR2~Ldh zDaxNaFLb?%ucwTrSG3y7ZdtDA0^U#64|$m!@h;Eh#?i{oINSw5jcii7-{GMt;2E<{ z4W92|Mm_?5Ft-lWvn{cU zYjSSQlxq=7z9%@zbEf(EYqkzcyL1`{}jyvlUjhuOE zJBXbBpK)X7<$1CQk+X>%)`)OntdYa@b9Q+kPevbaE1Kz^iWS7)%Nlu;BHkaAguNqHrX-~88*awfRUBjs+;pbD_kqcvi|BF% zXGsI^47HRaSD?(^4pIb{BKjy2Tp`_hl^zkWzzvMtVwqT5~A-*~JX z&STI_jq`(!WMr?#c`@yaryxVhg)JAu2R6D4W%h)ic6vrYL596%C_C;X$?hNQ_$Lh9 zk8hFzcx$~Cc_XkHm|+}e{|);*CgEiESqC@&lbw{Q+~$8q7O*YCy3fu3Zdo-0-=sFO z`5%pBa|LX^!sdT^Oj5cfj!BAhEbv!kE~Pr@`5lw=Q=I>M$0TI|Jb6swt`G1mXchSa zs{wr}lzhV#3*NH0-k$?4je)?O1N|K%e-mE+(bJ$;A|Tvp&`D==H&;qy5TNX*aXp7a znB=*(k|SquV2_t8QB9-jv#NF~^c!^FvLfT)+1!B{PEYHAgO)zi67K_7TuTK;WS;GR z&i$#jKZpA-*}lg4Xx$&wLx$K+n)J7wTGHEgib-egL{RoCEr&7iIY9b{D@Mv|Ns#vP zahz|vlXGmna^wcjS4Raqvuu10gv9BYJf}RAlVu{dWQF5%wXEbg#mg#K@94TUxU{tI zT>hZfxS9Y2?XE;?R$M|W5u_zYzHWRj2a(9qzEzCRp%6K^^mC*VRdtts{-Uo$>~a8s zWe(Hz4G8_5!zq-Jpwi-eFrYLuD9h1BLb!?$P+pn>1$SP=%Ux|Sq_V*{ihz(e$xdP^ zM<==Z3{IBeh_HKLZemJ3g^JQ28w&tMw^q5q^#DS{GVcICM-Av|_BcG5UXhDGHJvp= z9;7C4|EDuG8KrcC_-q$kTyvx~N#8F^F~D0ktmG;=5i5kn5jbF6@+m(q8}@OsO7wH2 zwPBFQFI}u=zD{Ws{s>OY@sG{G2rL%1(O-k5K zEh%a{#pFLgjr#9@CS`5}Z!#3qi#&ymg*uG#K;;Yej_Xq3Z=QZ!mhdy&?M9j1@r2a| zBL_3t3~&#+6;&Y&Twx9i(RU(t6P8tu!<&!NlyX>&6Ih7D&XCP<_&FBtSS8z=J{E5Ix{;Q|a`jk@PhJ51dWeuk&nDD}_61~5!ra^@-}pK<=+>menB%a25? z$ZDUxr{)s0UJVsa5E%O`dvm3h4tRP=G*OZcbET+re2jJ?N#e7&@Od`=o#Vzo9|k(& ztwBQ~|5Qu-UrYg6_Rg_=jms&vue^@ey12hgzXPvBZ6{5hu$@}c$99TI7w$xWS@zCn zNM_;4S@vKNXlD%~# z7@hx&b|N4>duu=&g0FuCV{arPf?&~_W8WxeV2GAkGMk3n*w@SUmAwaTU)j4`>*DXFA>j&We7hv!x0^y+F;_{|nh7Y#Y*}2C7tqUw!vS!fWVi>{=G1*)2o6)*Ddn@*n z*;_?UB79vwooetKe(2+`$q@q5?7bN9aXCV#4!mzjhZ3ynGiB2m^pPb^)EEB$py0!+ zwvr>K*wk^`*@`~59165N73l4tb})tlJ*b8K3>m6S#g;B64!!!Y@^|9E`WN#tC#}%3 zbB_)kxcv*yM^Yq+f3#=Sk7x(smOP@+W#xBGPr)xuQ`1%g)bP z@nlq#}tIN*OKDZ;x&iA}EoX=NNIQ~X2Nl|rtmK-oj^@3%m zoBPu+b0kS?$`*;(!ykLn#{EVcN?ISzQX$gb(Gf#QD+BKwG{)*;AWNR5od{|E*0|AR zEFP<0mh$CDT95{6S(acx;_-BbdSkPT8RMBTjL5Fh=pevh}G2NVKkMV*pMYEzl{Bb&Be5VatBJ811`ffT4hx*q4l$5 zq^ti9%cyTvFazG$42MGDyT%R|bAfD3EI?*kMlD8X!Nk^NM&;%Zk!I8n&<_V%Ivn8s zFa!sFpy)$kj;M3dn!U)Ol?WO?p8r7_;;~s}$OiHqVg^TY9AAh+Z{n+CK<)$(Smu%3 z!wN*t$hH8GaCAHmVcn73AEz3G-fRyjT~eT^D18h@CBPv4mjZ@tLsR({n-I@6oSBL! zS@G6XbINl&mlAn+9_6eN$##N9xmj7n^Gi`m26PKc93JP+!H{KLugoTiSVJ9OKnCt< zI?V2=DmNpHld6p1xL~SepTb>S|8|aB(@OrTJV-g>v67`tmCA_BK$Vv;TzOSqp|3>j zlSN*Y9}dxpsT#zcmF#y=)nU4N~ zjCp#mrH1JGUz7~?bUwsOs&W{Fs$5xe51dn#^<)d>YFdd<;dAA4@BlgnmNYuj5ln$9 z$B=wpl|lxjI)K13bLD0OLO<0w@r6dx&Vb@_5Ms<*|e89;THXDbFAM2-Zr6Ee+6RCmRJZ=lBwo1*md4B$n-_lnic65PPrMv>s5iA$_g;lv)hb;||DJL0(vV;IA#Z#cDD&-8u z+A}OTzNa9=&{UqrCZx(&+GYGd6D3tS#LtnQ^;cDj`lN`ca;dXMB+sge9C=DjX37kd z(g)HMq{>Q+0H(@1^cQ4gzw1>wP1rqEJ;yBL7VG~m2YG*%{YED(@>ysj)%B#*Ak^Dl?DEBFg znNl34WGk2|NR`?cjI8VR*d!6V2X}_T0%!Zj53qZx%Do8Y4Rb?9tuvwlp zSYc<4NX0RCrakg9p$NKh;#3j9>~>Dd|wCDrF4FRRDr6F<0(YAgW3XK*Fl@ zhqg|Y?f;o7ce6d9G);k`s@!8RiU0=5F3U9e3{B+|Y(lD>;mn+jk`-&Gnp0J7@ktTM zmEO)8k*pwSlpiaLnX(I|%!4!qsd54%fOWknn?kZMjN;#-pkSaYf0@xa?FZv5IUYO%lSuOAHRx;Sr7j-5H za^+hPs!4?BPry0D;eE1&axSezsPMV+F6F@e4@HcQz6hp3mAyzlKY|^guSD#00CB3+ zG9dJG8h#9`(gaYPD)0Vns$572s9GrnimFo6VEk~h!N3@d=U<_zJcmt4l}zn&j%=kz zsB(gzBR#X({%oHVkz8rutP#n}Y6ABwI#Y{K%1}sCkSbd^y6aWiZHQNp@$YP}%6Yrk zJzW|9r!z^Q%8fc~>B8sDqo&Gv&hc3&qu9MF6(9#x`J%AVu?>0#sx&8xU|zY?fb;_p zr^<_&3WObeobyO1R~CX3r%DAtVPK4Bdz52XMrq`K5nq5DfN`^faW`PdF`R6aqu7L0 zY2wT@L`hY8rkc}S8RnBBqRQLO8j&0)Xq10xnI)BAO0vOJM3sPy1{jGz20B@a*B}~_ z`b4bjEKkSqot};^2xrn^*C29arj8e?%xM5Xr^DDD&H)s+_!#n+1<7AT3n+(a zCjzB^11OUV|9~;45DF|=K8Bu65})dwJraMRIDQMG@2?LbI+^)&BkapH++2wbNmc!w zw`b@L_U53J$3cCV^^oALv>x71pzX3`06#}vs^H^+%X~xxU-IYi6XOF7pXNl6)NrtJ z6Px~~*YLBS2ug?lY0x{Y;VyK^h4ihkNy3(~J<7!_BaljtbQ*p_*5a{;PL$IrU=Y*~ zY4{5=)-?Q`^IRfU7EoZB%f~AfifUL+e?;Ip4etXKr{O1mn1+`F0wG zUQRXq1A2H3*FB%VhBpDLJO%sGpPNUp2{c?oZs6@x0)vM8P|5-bQ-FpqYdwsA+79mv z1!1W|20t?Nc7gi47tpp z+^bOZa>8Q)6r4ZeEEO6bU(!(k%bFZHinp+m%SRMUmh?ygqqEkd2IK+<|R<*~dV(N7TFCcB|YhJy#wtDr(=mZj|_a%sT>eYpB zvicTTMLCsLB7OI3j+x*KwB7fQ(bg3~7pS)lY3kMciM|rC3IGDjJZh?BKuP> zkN->YbA$pL=k__#^DN}gbk+#DBbt)M)>`8K&nTrCBn&5CNWJM8QB1wJzzay*{i;_l z`#Z1RmpXL>>J>*6IrSbr%w7CHm#m`PO)C-TUcCe03+hcgYP7ut-2?T`BZ?sRDjASA z00PTYuY&=hpN5=HL%BB$oI3Rm95M(GvOTKap8`eIYi}@0IT%#{L)N2dpkDjE`K#BR z6=$HLypBysy~D~4{trrM$h{J&el_jbY}pUqyqJ9MTCa&J5b8m`f^$S0q0HxA zFYpER&im8UtBsfo)SHTA_Ug@`uS9I;%U->Go4k4%oaaL76$KQhUN1nQdV3Tr=0BDZ zD5~CG_y>%a|1cOcA)K^eFPwUNGxJyPAS+&oic%Guka~|ff4xwWk{46`s(Nq3KtAei z$qv5Gk(z1(^Pe--7^RefgaxSAowJXs*9W|Sw6|XJ>Mhvl)f=xfU7+4(5bxBx8osIC z0v#9W}>ZX~l;Zy$XnVpRYHmN{}>Xh7)aRL*lD^%?_; zQ*XW)gzAKVs^_ObQT1vVjPHLp7ze1w3uqdsS7T@X>RrOL>w${W8Jm!LiJ2ySV;|)>JQ>RwB^7dWXRm)SLR7(Y64(2kKQLieTit(13IT5Ll*q zJq!r_G~qlKQZF5xI`s}8FbLh)9#tPqfuiblHy9Nhj9P#pThKI6ulrB=tJjwm-$q55 zg-uAkzmyvs{}US2E1&9DbMI0ZV6!~xwRF}9d7hfU{O3%qM=7sB!UEJg$k`{8M{>V$ zGE2m2kN4_b@s(GvEPhNL$=#1Aa(_%;y5AsQ;r!M{nO8k`BzGD3f_l4iPyp#~(7j>$ z8eKt27r;o~b1_vce(mB(G^!oy&KtGziRKei-H`^cPK;$eml@i#5WNGirw4@oBADU`TWtj*A`N*;Yj~y~=xE`RUaQ)Mnx)PoR%0*X3!Q!-6q!IfoF-s%mgf%#+C$%9m&*LWR$& zSII*>*5t5dRcl03kX2tHO?_5vq_0G*IDo)1v#N{%p`RlVFs#ZIfa0?1)x8Fx6d|B$ zu@oq(N@;_!>X5tsSLm-q{*r*))IxZ;Y)S0lF4i;7@iAJ7 zVE5-e3PTR4vhWwnmetVHXUkQ9k<6C*2Bn`u(QJ9@3!g1*IX8u}WinWC*-}Ws;Q73i z4xk=M0i(JMgdhNNu>*1~fXM#c*zCe4q)R<#<|3K_xp$?S(`@PK(jw0w_M*3j|MTdC znjFRcH@`fS;^PJysP8Ju%MsuTqjmo2>jMc03d z73)8i5h$w4Uib%$mwz@GGohulKvO)wD5A<_XXYi86nSZ?IaOr~43OPCs{EH3e2w$J zY6ACzI#Z9JlRgTi1G3K8AS7mBBwC)Tz=Q&dJtRvW4;+ zT8U8M$FOg~1Lzo;ZFEdPFa@fdMijxyptu1^0}xo|7sw>u3& zGqy+7Mk!EqWzgJU92bL8f@!h@O@oy|^KbKC8QjN;<55xK*o2bmC*>wbz9lrs_a8q; zD6qkxMO`HdG2HJ|ahI*yPc=gW7@ap}e zb54*`*CULadee7s7ylo0eoLc_Lig&Ghip)9U6#?d6}kuN-A)vNdUqI*v7^0ul1~unDPG$@wdflIq=<>Q|HRei&f0Jn9W~)(CkEdxvtpmUv$tN?8s{3s8^i8B^~Z z)P#E1VIYD5hJ4%AUcKuvHzjj#hz^5#M7;M${*WVWo!@(CB|@23uNC+LZKoYD_0B=e z1?nX*)_e8F(^n$4D4BbkS9$doa$X9lcLbC;^;!W6yS`De;(4zuBT#fi+ywuC@$7zs z@gg*r8_-nhV-pf3-I*DNlA_E_HK(Gign@iS`FVTrb&lMqCh-4PXX-(eauGxhixOVd zaXn+I3`c)K#;jycWvuk7%+{GH$SGU~fE21qb2z6e8DtCPGFpjH;Z<1$9ze(A`;3m^ zh^0W4TqLPiDs=#bfiY9D=ExM5kpNLuW7(> zDNtoS#v!lD*YuT${XW90Qp$kP&u^S>LaNjQ6sO87- zqr0vOR-(TkWAAXU%E`;TD*JRM2~@dIhb_&O_;*IZ$3 z$~h)bWd?oWPp-qfD*Hb1s$_5;3FS&rKyj+{0u=Urk7C8~56cJ?Rb?;y1IEic48}}o zDJ{@cnqm`DWwJB#5=yGFG}WA{vIPd%EKjcdw>kJ4$3JQU$3M>0BPiuMNK=q1&tn8I zRVJXnAmgKFyeeClcvU{unIy=Se?X{Hr9GT89JZ1zl;6-wgbJT4-+~9wG4dy)V*-LH zP~|kD2vjLuR&RWDmOw7sFJhY=r{pA163X;ia?bo z49IIkyec1mb=aEpZYy&4wl^X$tf$^bY#s7a;Mgl}t`3Q0VMh^#L0ANTpG?hx& zgmR^?Gt(U{r87nVQ>7>R3svHS zy(;rQ^s0>0nIy=SuXWf`Rjz<@I-W#PyUb7}&|zs}UVC}kj|DM*#CIJ#@DY(cz& zj6Vl?Rmv^)s{ExhNuWx79k!H;*S|6f$~nhpqKsnqs+55oP-XR2qhky73{+`M6oD#D z4ama);#3*8$mdEQ&Lg2*c?X=hTqy%642-dCkMdcTQ5ty{Y#ed`#`O+HGr*AC4cPpS zO-PknoSExTQkBlB<}_CZ`J{-bGSgWjlA}8L;r*;yW=RE@lD%Lmq6+Ww`&xOW{7A-d<4J zuX=sH|7B5;@wgSw9z%(zdhjun(|B(leqiaI!-i)a@gZ!i8Z=2ue_3BF0aqiOEBAs& zdn}#owcru5u=ru_D$DarMj)|d9Wmj_b+ z8iO0YgZxL1|N`*_hN zNoPI020AaHRFG#$u-$l@^+nK~cBBi@eIJeH6-VFD(Uug%W5vHE6BzHAD(ldmJ#wtC zmh#R_37SEztMWCc`Et8YjMe^m{&+}xKbQ=L1CB5DAe9^0okXnDlT>M7rBw>PU^ZOJP_@gW43l!pa|`NQnU-N>yVdRs|bZ}Kkgp~XOy(g*}=(gvx! zWoqpJ^pB)%&ZgQ#NWe zH2=n;p&bIjUuE5hVIg^ybu+vHN(qIcyDU$(R&hJgG^j^lue~J!{78}cpBU2D5Fx7~XUgoA#%Lwilk(1U@-J5XZ^qPFnUuz38`o1{ z{D0NyA?nq5o&P{yUU~aIo|i<-?cqk+VB^S>cL@p1&87v^`WmH70)5JadsAMJ--=xh zB2$s%?Axy#2k{S}}jyF!>%+JhwONXWftwhEepR4y$!+5MHI!6J@p>x4< zEgi}4kKV@77v2!x#~;1jY(Ut{1qi(GD4L@Ip}}@9ppcLaiZw^pu#7;_T>XmV#$!Xi zFc{A;Ek+H>SuHG%72&Qu$eQUiL0 zV=k=9K#V}9%24zdWK8evRf!$-s?30R$@5S9G>4UnCU8!+R+250OK2rRg;!-ccmN%J zKQ}stB0d6Djv!mTDu2-zp7ReNuuOvH=PD5T;rb%1N^3xI$JEQ08HB3{0aY(efugEh zZ7^h=!8l4m-b7P*1DlX4Iof5suY?|s!aXMt5Tdl`m=&}AUs^IEd10csO=nALs@_-wIByn*|yf` z$cCPQD(#2@0_cC^I~b4=y}T;r4G23poby;{#jzTkI8|x^3Ik)BV#WRcEF%G;s!WF* zfN{5j(Fri*Of;2Z*o0JR?abVTlBx_$HK(e);FBUU9euLYtPykxHG%72&eWwS-m zkSfhF7?~>fpubS1e^0NFGrtky2$|BxuD%3gks^vu?Q|2i@A|+1;!1_z|zlE}cmNRW8tBOGmKLON@dOWD5XtX(fW)tMVUs zfGY2-HaeC;&p?%WL=oi5l?J30fS^kp!G8YTtI`rc!m3P!woaA*J~jyb*d9=Nr$A9v z`WuW39gM30Lw2L7{De(Nl}ntN8Yrns^Hg)1D_wn3L~`XhXN^eq5H!l|TH^gaFeP6> znu1iRiowWKsY&7!u_oQTDm#Ajsx(C~Cr7Yx2oIMlzkOsB^mL9p(n|iSbOR4io;WdZU!9 zAx%N5#4!SxDleeFAY)+{uS(-zy()`zCJA!oFA(ZfX$$9MYYW*zxt>-cRQO!k2p&Mk zuoXtf3kaq_m7+uus8Y;;)BzA!X09yH@wrkPK*Fj#1Sn3Gjf)LJ8ruU(gA^#LN)vo;WzDFt3Ax%N5 z{K?T>N3eepuTZ68XRpfphrKG5_@kfgJLs^bBUr{Fqu>VTIEJzSRj!2`Q03rqqvK!b z8K}~iC<0X;Ga#>Y@~YG_Anf1-&Lg2*`3{^oRjvgT2F3@970eZ^lOm$ZhJ|L0psT0}T>o;W8laRjpmIT~w8scw zs&qwvp~~ovUX}9>c~!>fOcLbEmpW{zDs|zUj^83%D5ug&gbJT4Gry zJ1Iyyn#u@lLaKbHUCxoOP*RmY`8m=vo9)l^NfA-yDrb#I#;OTi|8l0@Mk)OvO+l)B z!O>lF7Vyaw& zU(EqIVG~m2ENA8nlvL%4RCB7z?LH|Yxzf*BBa+Vv8s!QtvqVtJLP%4PDyMSJ z)vlk3s!*kFTc-;C$8~^YfPB1<48fetmB)10!a3_q**f1SXyF_;rj`6vX$Bsk%CQeo zpyinera+ZpoMQr2M$lIxHm8kOl($1=l`&bKv7jP zK2jJ@00zk(g|L!(XexEE38^yJndy&`6<<#^r>ZQ50XEB%D?8@}U*r6jn!xjq)MTdI zjZ!K?<$_ds6eEDC@+A5TGA6b5s$8<)tMZ!8BtfqH1VSMfxorsN42LCT3+4N?5~0H9 z%7>IA9_zl?RCyA?6sU5Lb4;MhVfw-=m;uD)%FKN}S4!i@uqt-}ic{sow++Ijga9ZP zra)0u>Kcq)i%gYYDad3rl~=F{sgk8#&XG)dges?|np0IO`=p5EN}97qBvaG`o`0t% zGv!m1G8)npq{@#R-8ENsBVIwq$*sI96Zd*mittCjGQLfREmdXST%(|xb9^2h=dVf? z$`OxkT4<{5hMs{c_c;`L9;}rCc^dD>bE=e3Aet+KIFE#KWhppus#F0K2F9z371uvl zMxdxFlOP9RGzAQj-3BnED4I$kY(lEs<;*le$%>Drnp0KMeNseJ`CyJ&qbjGU2|Uk9 z=VRPIg3t0Bm?}t>TQL}!Dz~#qBG%`AugXb#yebdtOcLbEdx$TWE9KyvjuT`H^eH(N`jN;6AU)fZaY<_H!NysZs+_oGN4AG6;pW z?>X`h?L?rcDkmF^Memy`YbZ!xG?iZ1gj89oUCxn(D5=VispeFbBTmdbBiQ-Q8p(M? zP2@-qHJK^nQA%4#Q;;ePIJ#@DEJlAp#@2hiDi7`Qs{EicNubKPI&5jK44sWuaGXoF zQ0CA|gbJ_9AK(G1%zDpMSqwb`RW5QUG*{{vkUIecmO0z+$@HqU0FbaM&qG_M${(`~ zLT|PQlrAYyRFyskqY_|{>`MVdwxOwfi%m$C8qQ2bl&pAbsyS7qollBLu8eZlh-5oK zqui`4;{6XOB?HnFq{=xMjI8UG*#z%@xW}vV-A=E{%?Re?2sQ%Y;c_K=rcuz*Ic`lW z`K$6E<-q$N7MLoP5ln$9FL90ua^)5J!uucY_Np{fAUc9A;XD$`mA}D>Q{_QGVc)-3 ztU2;E%Lo)zWh?#T{SWV&Dz74}`8tyXxpEkUI#uq0bB4ou zvW0RrtwgBsx$-%9038G0F;&tLOo1xLIL8F46fz*y0mS9XhslReRs)c*DxCqvsq*;@ zgV2EO0i}Kl6ji06!T5c?sZy9}@(!BH9Be|W{Ho9Qy@d{PS-RV`C`=ig5^8C@y_N{c-(h+RgbfX~V z9A84m`Kxj{<-q$N=9wx-pl6^;cZWhpuwDk_xfWiPDhfn%CBb6Q|1MfWp9d zTe0H(4=f{4RF!#<127%{43ga&Fyw4Bl``0bRO#%@v_;8^!&A+vDwBOuL{wQb&8$(C z3TguHe^8T|QXi$943!H~r6mR7iJaJ>KF4zJ2t`bbMXUU^1mk|0-B>9D1$)P!?7 zo~pAh?th|{2o*k8rce&N|KV*@r5%DPP-PS6m>^far7yhyp}ALO>^48IPfsdBXr zTY5k{WvZ!CmJk4`cnTC%rJTW7JJ(eCo`MWRQ+XPjkSbqkm+}8slvL#qKSz3I=fR5l zq==|;sk25T&#DQ$|3OXS{SPRm52Ptbm6aUbHCNW5zaS&KnO9}7KGITE`B`U@K$SW= zY^f?QykQia<{Y0y#}Vval~X7O-v2PiR9Oc-168hbC^T1YG$5S-1YP26|3~uaj2!_a ztjct7;&SB_Kw+*7VSAKMu#7-aRfa+iz_<)BNOl9jkb|#da{!x=Dpxx*by2cn%T#lk zD}8-ZL{xdzStF8P2pZ)+WfAXxfGODurV3J}HU=Z>dObG5`yX!is$_ldN3eSl%*he# z6~vdDSN@&CT|7VAIev&%B2;))9-$m~|HE6RN<9Qqpvo-HF+r}(p)b7up{ZBpK?R~C z*m}+*pSj;s$|nY-v2P$RCya(%6(`mcVZJ#Wx6vn2_;oo znQBf|*#-k_mS?sv?5vTT`_%;A|DY!E{s)xO5Yn)nzf;iPoL5CAU<5E#CZoR~V_6fg z%3b;hO3jt!I+FysQb>m_&6Tc`(F%@tkS&zo(Mp60ugZ4t06OBcOqIz9ra+aF4u$4Q z83S?^fWR_y<#T(iBmKkxB&VHIz7XgITr7X$n&11V{Hw-s)DA zP4NDQG^fgHS!$1#q`g`Q=Hz{~y>zV58z#S*WSAQ}$2ZYR9#!14z8X;uy#L`%s)GC1 z5KO^+cQODllK0g<1#f`zMq@(Jo8K-Apx}HIXOd91>;Nm!g(h!SF!=wUE&;OS1KNpz z(I>JjovA>2J0MRZu%srM;x2r>ar5>o?FPf-lc(+Zz^hsD_^a6bjZH|vrq18Z^amWh zQvIrc&%ywkh~-WuL#pz|b-|4`CYWtftmL26h)%_=@WzKYz0v4UrpGvrpbNW{9| z=7ag)pNQ+z_NZ~yF^x@GO!+?bcd)k&0C{{qX`tT@i zJ*B%Lh$N*({}hlT%XQe$p`{x96E)Xotojn|MEhD9eVu|%qOZ-TTVLBDG6K=gmlLl9 zpEPyvbf(g@#QB0$lX_F;n2?cg5Y8vt_YrYnI+RW zH9+_V?grakAlC)|tuRU^m!Um-x0rU&yB^6~dmEv5%h4_LuJ1Gys67<=^N$k6WTg5v zEt}LcEkkW_i!JWYKyCSN0yeqWn3l>znseHKMo_Uwit~~qx43(spLXHSELa~f`=y^L z8puN!UTjQyl#?=^b9aj$lWKmWOH6k3Wdwy|jjtbj%CSXu6ZvuhsPIDN;^nQ)WIAlzr0Lm`2UC2&Xwy~+YKd! zF3U?~$&tLykB8Lpd=2O*U1UAUpz9mSNZ-3RPtVeI;W1ZuF`=VUK{MpS{p8 ztV%UNaVyF(;|)R~?K}SeOFI!Ls>(?Qt7@Am|du zq+Rv^NOrI}r_fNYB%rNR<@e_dLNB&Q)lMl;RF#Je#`z9L9l(&SXeyhr38_-enK=(7 zdwNT%IaQ^tPm0Joe}uC}BtPi9kLRChnI%V2%4$eckSb?mFfvstqAFBrS>LO&#U4UQ zvKt_nlezLN!o#VOl`sn0JI5_)C4W^O01r^*%vVj7iU_7al@~A$c~xGfuS9I))n1jR z$){m{#F-(aN-j8YsyqNF#LD@eTx?(&fugJY@8BOWMolyruOO_XA$#Gb=I@@(|H*wj zSg`^s%30Wi_TUAiO}fgfS1$R~%x87R336%;hnu>94l%)D!ZigF(|A@yb}H#zbKN~*V(pCc65X~LaO^gQaF>Z}oR zTQ!j*_c&97P|9tPumJTYbGFdC<)(udkoM!1UcHv~uu6)uMrWo#y;F1;)DiKau}0Ni zoyBwHM_P$M_v-BeUr_IbmyNdR&^=JE98m=7RWKm;0*F)ZYkL4B`*$7ZrI31qz^PMj zSGuX!itSPL&J-xBUTcGKx`S~pU`Pg<2I{pQn!kD-S#b&~%0z5J>WOlL^IwDp^@^qX z)!eHB18kN@y(Z2YA-}FBaR00`wG5?9PSF`G zP%jNpMa8$PQ42Ng;-xxtT>)w83`m+Z}LkDqnU&80AR?e?1dXSClAhFy*F8L=V)xUVG~mC zV(0GylvJ;2s$W&F6Aa{|UffxudYL*qV?D1W&X=H+FF|Pm>Q(0Kqw3W_O{mwto>%Y3 zeWEZ1?o*gGJEx=&==ke zc$ru4ZUaI;pK+cGsdoaDIQ6;!3f22bv10yX8G)ke?SOy4cy7GGcmu*o6ZXQXw_{NL z>g{L6DyS&uVG~lXxAWHpCDj|3>Q~j92?P14_tnVY>l~@7CNTdwQw>o{aYRD_>UHGo zqv~}BFCcAtU9Von&-|Hyu{zTQ>TLk=PQ7~YO;+cURg}|dB|@23Z#MV>Z7rWS+PWj= z0`-1GGJExQ(ii?02_Ue{dGF=r{;JnWoaaL7H3Sr=-s}+up%NhgO8FEhx|XbLFg8AC zFm_RoIGV~RY(k=J)h_4AH}nWma``#ZGn>vz`rL`ECF?tDL^4iIr>kSg=QiBqK%pfE7T=xm!K&#;Wr$g>XV zkOMHTbugL&hWz;~HosyMQl+6Ya}7$W(lOPXrpiE{6A@KrIBO*5FP(Jp{tqqjydap8 z-C(L9Rbm*lOqJ_MJpLD1$E)&N@_COB>dX}6$}|oPrb>kv$VDhn`Pc~w53FZ?gEwpXQx0imDoI4^}%DF-M{m8XW8D!(h%9Qm1L1d8U$ z5%>p;nQ?=$2wF;eG?g~kgjAX5%)E(`s;o~nr>g9Q0XECCcqs0y5p)MNkt3~~sb^5i z?U1G*Ri<(l&=G7F`U^5LFZQamwTE9a{yx_kCs5^d9kz7s*Y_E;LWL}{g));?B2;)) z_JIe`F=4FHF$;PIs+>aht8xc;fGQ`( zm?|X^Oo1xHImZO5jG{06FS3?b<$43c4$kE~63UfqaN<H-g;)=VWUs*+RLHRw7jRT=^J0 zK$V`OO_hNNra+ZLoMQr2ex>5H2GGK&h1i zMb~Qe491>O2IF@M@;aIZYqffh<-bo^&WpDfAt2j;)kdx?_(2Eudws? zk4}YIazUzJO}=YkfX(u#*V$PkLbL#m>woR3XNls?W( zSCmYtM5;LzWflzNBg)qUg0FMr0yU8%=Q>k2qm(lta#)mLrTsLn33lXcp&E2Yf1yhH zg;WKkXGldp!;(w46Ec>o*w8h>FOkO0(s4~NQ|iJ!FB85+zEE{4?SPErm0fp1GG1;b zn1C+#J&OV@yCRx2y_=-(mmip?iP-bDq->JDM&5WI?&J3rON;ksoXCfC6vA*DFrYL0v@9544bF~(zW53>;Z z1d26uF{Buz7VtJAa~X08%_L%X>1d=EB=_zwH+I`27-Ug=6P* zgr1AvzOYDWSvt33e5IW{L7^AaB3EiE#AN(-$Il29#_xuH+{N{Og^26_T4Mc^4^$Vw*BI2Fhgkgn z16`x>+XKUyi{Cz$dUGq0IgQ_Hgl_RWo|9H6tu|`9Yy8F>tapeU49=pR2y+_0?~<-~ ztUaJG9QrcO&P7uxhYiKm;bygTb7mf-8B`pVYEI+#4IiVC<@&nEVR98VLEwbr_jG5w zu$K7$k50vy|LDV=wz{yVO{U3#%i{M^=Z{@nrR{Kk9ZJUU9+dJ9WC)!8-{Q9_0EWlk z-JF|r{LQieI<2aY-`D5+_&pszhGVCxj%YgmE_lq?uj!ywCbWnOe*CRY3F5Kup0@bi z5B`1pwgM1DV@X>OGkz=4eQ5l>3edwC)`Azb_(dm-TSYY~QRUp8uw0mUN;I7r%d`PLSx@p=;_AaoW9&e{OEj*^DDFy zQNhP=7fOKh-%nAAOsRpe^6~pB#wECKQJwB{7{3qFeJFmP0Q4}1Q-A?2>SznBUpOU% z0ws&#ZsTt=g^2SDI(O&Fr&?nD$DGLn)y3};VvNUn4Yc@u3c5z)SCGLjehj}g62FaU@@8i;Z~TsRwx87!|9{XjOJ>lQi{IIu^B;fT1z>}jD>rMq z6LKxvAp|<1luHmX|F7{oy-zZJd3S3^3Evae$huvo+5D(+WZ&d9zc=kq2x^Ihz9D{Qr{{z1TQggiSIYKGpF7 zHyLJ1RoG)ZOwtJ&@BgBe2zNdnULkRK|5tyDhn9#Wi-)g};ua5WyZ=AN!$0S1Je-XB zQUZoT@h}wDEFMMzGXK1ydd-Nkf{d<*fCSy~?Y>Zpz94|O-pN5~cc9Hf;975-W6zk&zQG5t}h zg8LnzXK-h-R0oXYe@ZSiC`}cLrq@r?e0nwE5;&wwx{ee2pOVAf3`92tlO+$PfKgq# z8;}YPNG$-7EodrVV-wP)vNLlw%>eODspeFdmN39(d31TkTf_bC1Pv1#P}0;NDCIMV z6VZiX{PLd8li!alvO%t z6?^f=i0XeRh|}7pd^7HNw_qBMeib&QLwa_BFG!_oB z92Qkr&_k<0DyIjAPvQ=EyeK~hB}Z;oteJ8x%m%@+&hOyOA9MS_FWwBYf)#a%GNSqb z?8_W>I9@cHxbSa}R*@eEskcTrH-}erqy=vVQDTsFm+{;BY3U=XKSHbV29lOOu88e7 z!i0ohYw=gBZ@+Ti-VxG6+Z27(IleP+yo;!QhjiJ+j#HPw5??NqYKt!kp{0Y1Yz}UM z!NN3e!KewSOvHMYR_&$G>ogiLyiQ(F9dh`*KrKbN}Ln?g!-<}VO+WXO^X&<}Y7 zkpCGO@~|pgmrO&cn-Gceb0^y1yM7v=UG_zI>w!rOvzLa=R^1(MS9gS|TmNE)aO>X(b-jb$h1b8y6EY=7cB9%@|CY7& zFX~Gr7w?2|frD`_VE_(~N90U|rp)PRT;Rws`z2&W!}PW4UHc_%0HG1jePu{{PTq;w z+1)mvHS7ZT@M)x z9T^;GwXJq3^vnJm_4@rO2SR7EbF)xac6Gq!M{Fo5{4u-hIG5Gw62_XPy4E4T3k+!3 zMBm+zaMrR{AyN2y_Dbx?6Zo1#?bloveWAqW%1V5oi}VMNpU^kLFxWrE2X?hW@{eFe zS}wRGL}H9|;EL&fnlyz$~B5ij3IB1Y)jr@ZNsBi}*{kdFyym^`TN zQvFVO2}8F#sD72+@La&tyo`5D@-i-k+?4SVC*!{$#>v>By~+54PS9DhQBkL0n8txM zUT$+QRdYCw!wCK*#DI$`7?&b|W9fCep=qRORI?SY`t;)Zm|=*s<(gi76pg0WW-!aH zHdQo;=lsy<@*vHS{N2NloCYMa2(4uSHWn*ca!3UUjP z!Towy{|L*xg7mM<7$^pZYzd{quh6PT2z9Ut(Q*jGhtYC`^I#%&Nijd_%$?|IDUTn+ zwA`;ljncBTo#DDd@#RSEd~tCwtw&|zu{}62qCmexU3nd?3At-6gc=6bVrj$HHQ;Pf z{hoZ{t^Y-2;35~u++RjuFt%7{ar|E#rOY9fx4^PeX#?(_&}(e&l)t#7$m9_7AL0Vt zu79eJ%@1Dju~`{EhGVlmh;^~K<^gkjy#mORD+wSUIpXE6Wf>2Z##YDv_^M{gY`m(C0;#`(P(In>-@rw1YhLcAj$ z--NPoJt&=2O1?^S__```FTZNxzAC0)HRM;}UUtNT+nk0r)kt+Ojo_-oy zMauBgnXFD1Mfm9ixk(JFB7bo?^&37lN#IR}lEsgElsNub{Rey`_-XgKg${eV1s~YM zT7EUs|3pB{rq7A*Ucm)-bT5=Iao{d>5yzGcC1_ zzMEd5N*v008yVDT{x)lAubuSxaTffC4xNC(c61S^q|eb|vqlJr!_#-*tq8xmD{ zc(h}Z`RWDN^WeoV3g5zqJg$n$1@usnC@WxNtUc^nUlnfMGqrVD*@sLqv96_^7?ExS zy+LnB;P>n^G2V~YX`ACaQE7#m za!<(lsjg{X)Ml$w_Z!urR;SAaY*i7hq(Z3a2F`#{2dev`P;AUet)se+XArGNpJXjI zm}u zYhj+`4BNr23VL8*(4TVUEAkJdx1v2ec0;}ZxZ1m=y$*1HwBx*)D@7P+3((qF!Pth# zm*eyl?_IrC_V@012WztI?VV}sZGSg5ZLlG!Tw)Bjopsq=ka_OQ?9R+Wy-0PAnRXD3*KyIKU;(kyaC$6uKpJmNmBoyO6@UiZd z4rh-LizAH1Yd{}Z{JAX)1nu803Lv7(1?jds$<@zv|G}AD4X|=KHlzfo8GOZL7@P8#1NfVxOOL7v0DKiY*&RKD z>kjTTD%T#|Wjr=XKOhS+CMPw=;rY-_>BaSj zJGqPX589K$-)IM22u<}&q<@sR*t|AOB;4;z&AXwg?@NY!R0 zf5-oa&eg@Mp0FLnx{SidY$r{6+D@it6Xfw2{ZHTF`zwQQ%DROU_;nex`%h2sA=Z^P~gc+;h(G{hKYYxTw;2N5^ysHO*(BF9F%wJGjj zMqnn_>hmFyTdS9bJ*G-JsRfV2XeEL!dHoBdfxD}5*hZZjBiurlF+avQU_h30-I0j> zlS?3aouyv@BujQf>F^@CszTB0ETftmgyU#WNPp2z1WNylAmIu6$Mr894id%+s3#Ah zDR{3UtI$T4fnjNduS`{4GS78Jr_(5!eUWNh52tp!V92u;KHXcx^&d5b=ifO~Lr_W+ z_@ukwB#j$eXCSk~k9L~DSu+va`IqOW)hH)YmSk`~!u(`IE1r*rh;RoGy_y*}dq^L+ z*-ks)CN#3~4fK0SN<8-R{l?8qh->Syw^3haL0f46OFH77`jf`8o>*Dm&<-e)=1PwI zi32s5`UXZUjaSoi2YSZWV^R>59Qm#`$&@L{CI`2KM5vB72S0IZ5A;)pV<}>%NYl}G z5VQJE7rhyB(@2;1xPKe56+XZHizYkHG-b+Nw;Lf}=vP@Tp!aZH9Y3yoT^Qmg{>b8@3j*Tt0^Yq{!28G z4A5)c(3|W&Bx_LWT`jZZdo{a^>r6R)JH=nN3s&VhexF#T?~nhzEC;h?Ite_X-w*B~ zeQYO9y4X%FX=^*h@MT}9eqjIg1lGbjYVQ;+!cIcK;}pHT>=aQdu;$S!?q0}-isQzu%y@0oTY zQQ}9rX`mL7a@ReULLCtrp@7|tlr$(mz#E{HQ7AgZJol`Z`d>~=p$jtCDHJ_5It|^V z=sdn4q*5tR^mOq#2II@S4aRnah>S#2c?O#xR=;JBVPgZap!@@+d1qelPoZ2mf$YgArIJavIbzHE$5 z1~%ha;e6-6A1iXPC8y&Xra)mu^fZnFj)Fq|Rz(i$9`{p3F*(c7xSI{gRwMA(oA?KAt26q%jfPCN%T_1w`;_(pN zuD1nne?&&`%w&|35w9?h+M|{^sG$z-t=@wj?f@pLhfQA{HhsD`{Y-wQ`_Banqu71S z|92V-jhU}1UUM|b{@op)WuFLkc(L1na6ZVVr~AJQ^>og$P)`Tl8rc2~376W_k>xpZ z#LFEa7X1IWg+W>bJgIb z7)6$vEHCNeBNUM@ejb88>)#Oc0k;Iu4{I3bg+5{@pvz;Zr9Og;Tgl4ExNMZkd_>ay zY}8K2_Z%`O@%OqKMI3*|y04$**Jt>^-HXvbAHo-{3!%>WCxm*{%>nBAu#`{WHnqUL zmQ3UNPcsXKf1#6x(UtgFcbZteGFET3tG6YnS3Ia!6+13ExSmOihsceEVWx#)p66k{ zpox-~+>xJJT)fm=VK#E^@Acu-2F*z0-E1Dj$E|9M@o}Bot0MJuFOU8H9T*=^z?y}{ z(>f2N4BY+KhG-u1cZlY;4Fj4tX-ed=->MhzEy*=-$J8UY-Zr?3&wuR)o8L-1=d zNS@~RHSj&scKrWg@6Ds5Dz-P!1QLk|o`|4PQFAqF5YeDS6A?`q%xUQ;3J6|Aa6(j6 z)U=|=WD=oo(~9EkRZ(#suLB4wCJYH6GAW8E1Vx~lMhTz{3g&&^t~x_^;vIg=wca1^ zu@*T~)vj+3wfC+%b*jmGB)_<~*3`wu;NtI+dVI0As@|wTar9utz3>229`&&QV z-+H>+`sk)xXNm}sjM1&1YFa-Rt?RblmyqCVtFOPUn%zE5pE%Fq)M~0NSV*K@JKauA zKy&$(qf)1@ucE<2>ifm;IWIcToaL%n<}6#iEoVuREIV4A1q8-I;?<(emz>MjXr5o2 z=JX^+e6wb8g`^BV7VY^yWp3EzV{yj04vQRLG~o;G(#jM$M)K=y&E_^}LAP~na$DET z^R;!SzpV@0wyLBrC9!K&a@HLpol99_{=>9IdlSQX#fe(`os&nMlelZnt0XM=c%Sdb zv-wva@3Xr(yyrEIXAGzU&*>V^h7!&DPS+~-!fcrkZpSfptb=8UizOgf8o7)k=lUen z-;XHQMf8mHh(;2MOZaU!jiN#RZxCJSBD&5X8bU;mp|A+<7UyKXRA($Xmjy=PQfu*9 z$t)Tnt*Z7Ref<}o?8cts$nF>EPmPckOH=K35n?3&<@2@dX2Jw?i=CQo@kD=%h5i;> zxh>w?bc@UOiMA?qi}|L-UT9H-a04F8$*0cAK!N$_YShxJuHIlQpbCx<(_ zI&#=59ifpN3PBq-^fTe$`>$SF4sS!z0_IDsERd59C}(11o2Ee=v9T3+w z4Z>tl*J}_*8W1PD)|SU=PJ}#OXfQ$^Va~FZ)f8QwLG?4NaL`~fD8`?JAm0blHGyq` zx_XCCerLMS-;mCdEI*w=<)IX%3~IS9H^G#9&?(nc z2K9@i6+Q>I^AjJ;1N<<*DR5w3)HF51*lSX) zY_(0!lEk1hs4k$UJJ;EQypfpC@Z&$f-Y4cGT>K9-MIRZ|;V2=7fk~T28Pwld3Fz;| zv8fE|Y~D8+)P>|7``;96O+Om z^pqsIxf#@~?gHut1L|&AotRG(8Pqxn0sV4DaRP+%3DS5O7bh-I+ka-`U9hYezdv*) z+s3=1b4=5#kuUjXEPlmWcKEAvb<^95v^*L_6R33nYvHZXNVU(T=UHlpIm=W^&MI<} zXg)`p$W}Ul0c{GWCBZ%IBg)Fa?e2qnm;*Q3H0kp-+y^M4NPdxl+s82r3In-xA65qQ zqi{^L1jl%Ck$Pxo4@;KfNpi$&AGDW$@+3Jr-$-(Y*mWbWU+3IUq}?yXgx^0rPfPLx z=w6gK)JcQOB9$>^V1!Xl?)vG^%ZG0O1Ys0(F=V(3UO+(3MRClF$Ak z?XK2<+8RJP4xnXD0<*zwdXhv4PZrbsvUqB%CyQI0rZ-7nXe0~s+bW7}M)IFHSIgp6 zC|3*p*rbMTndKAu>Ar>za2guZR70V&A@FkDNEg#cPc$L|-{xdN%^gP9I(N3?M16LK zDOls&UV{^?0)c8Qv_{pmkXE@&XTQn0vXssTlUNSjK!YzZZNmn2r>RA)_#Dl1M@eWr z;dcDc$Md;yPq=LWOi+ZS&7_vfZcvAyfTsDixNeW;+cSMMw`}of&NK^e-0+{0xa&7x3bFSd3cA5e>CJ?6aFtq`7uaE*Zgy_Mzk(XtzAAdK=L zlo|*N#Ojk-odAV>MuA20?>Sq`Z8Fp>db-hAQEW6$Q0@g?uAeD)jZ?0NQ?9RzZJ~rM zuRBb8-`5?!-RyOTw@)+O;l!rkS(S6NYIAkd-xO+yG1!Bcay@L9x>aJs)a^QRmZ`p! zvt))5m+RCKjwQdtGNRmv20bEse}!b z9^U^JXdzBFb|UD*)bOm*m#<~Y)A`oZdv5pMC!u+ZFpQIa5^&8Atrus(ClH{Nx!!f35 zH!{45vQA_;M3NrQY!7+YXSO-ABv4Cy&nbrOTbgPKkzqFqXidrKH$a<=4EIUY^ThVmJ3g^JvB4AD zO-|cCip@4^`&I2hHnGu2{$u%CbT2!0`xa_(Xz`NNW`glgbC#tZYKmfL5IxA(sIT?A zR+0n{=-Rh^KC7{l_kv`PW?I%uZ^=_BV2duaOo`BV(It#HwTrK!_Nx8|rKtDn>)b!D%mBgxax3 zOkWq@f{53VB%y-7IL5zDaES45c^TiPMRJ?CZOUUmp{shJ3^QQI2x)8dOLKEaw?pH zlPSzaiiihJt3Yu17jcBz(yYeQn7Q^(9flI|FV)+*cq?w!1xqTMrz9UlnM}1q`bhFu zF*lRYS<)*w;rKZU(ZCnr7_ZfW>>%;8A3obf>X3)flJX`cDet8hsIFZ9hX?W&{9pi( zC#s^U*2>zdR&I%_P$D)!%j6CUBa(m8=~}jD!G1)u&h-45qy|`5u+H&DP?E12{^j{* zbufxgA0Vh6JPFc~_)j|)nXD6wPLhdPo(s7gi)va1Cm;}Tu1w1Sv&j&{-q#@p zM7Y8_W^nSOX$PYTPBq`x6x|R%_nAx<@&3QF=Cl;HC!Fe`N1h6zW^9PzknOA%x~E{Q4By&mQRs310$0TXm`kjjPch0;z0MD_IJ6 z7n{-r?sP+_4O?%6(k%BHp2xpZJy=ic`f*dkTj8vwz8<<(M``*EO83W}IX=3AVm3?t zdIIH33+zo|(Tbc`=!vn8Hj}rrR2OL@z1?XPAIw>Q`rR{Us5(+V83c(!2;Ti2a=#*n zZ<;(-jvAxO4PJ;PEcy$gB|!0wcM zz}|UfF#JLR=M}<}o9p9Lu5!UQ^K0`oethA=J%7qSq#G}waYgmA(4e6>9Tah|3KJ)) zK(O4Clc(k&2*$qzoz|yxB`*$ zRWSUXE!ajtsKCn$kCh}w_!)jVS&8Mr%mR^Kpw}-aI~aalv-z-) zsFgfH${h!S;pv9^5}bb|+`EkT!mUJRT$WD-%Q~BUnd6Y?$2rqrTIxv|lo0n6bC#{{ zle3DP3~=n(o=i4;2HP<`-kFGBDDD?oI~E*?*+*M1c$qHteQAL{W)&CNnRxZ;aTEup zJF=T<#i}@kHZvWCwClQ|G4=D3sNd9m)wXmuV^8RhnOjZ<==QhnEp4@=uxDL z^-Bq&wkm(uLHlS8b!kTpb=~ofRQfe;?&6mco4eB2T)xxX8ZMWM+z>?#{$rL5b-hebU!C0dai?lb6oCOok7s zvEQ}R6YaO14=LZliv13iF-#*_zE5>W+FhkF9cnNg@7U$ZtmSmRqlE-J-=XF#TOHUG z+0d2r*B63_mTo@@0SSHX;v~#ha($xdbNLSDH>5WuW3E_)j;``h$aL-4-{CB@T5tFc zYVD0n-SD?`>>Q$dYVBhhcI;ezTGj3#7Ruvqfl052!Z!sTSRumd;xjU+ak z)e0PAZ|iQdk=#Y{A2sw|a_DifpwvFuIZ1O)vT)*jljp>=vC=abxzlt!X9!foc^4w8 z5~E5lJ`rs-j^*8@ZhAS8B*pS9h(gEmGVZ0*L@YlA?^E9Qhw`$VTsM@zuYJTB<6K&RuJMtsaSbJp{Xb2O6Wkh4=^7)v8ev`IbX{Y^3A&A)FdW^+^}0q& zuf_mfBSqKvm#I;W8q_VbNJN_*Tx-PB|TtnWvKp( zXu=puHuon0lJ71?Gb)`3U;=|tBR-2~$Fl}9(UEpIEhqjGZ)GOjnhFQTk2;^+Xr;vO zE@BGLpuzFLUW;Jb%uRx~|73Ev|m2P25`n1BzTU_{&9u|Tlhd5H0Uz^0lVjz9Yk zb5e#{JG|U3SE+i>P}R1bk*jPqIZsU&&DX)FLYWPHGJ*Z!r7reY#M%V=XAqzt`#~Od zi8s;oyADm1?KjM!IkTehwl?m>*NQBN95%t1ajpyD6#BvxQx#@wWU^HEdOSpfwUfk1^FQEwcFodBTtBAwfV%(|;#a^wploA2=Ya@}XOEbH49~^52a+5F*{2ad zR^=Poxbx?U63(==5)OmyxX{9I?!~ZdB8!T7<{#xDi(=`TLG})8$d9ZZax%zXWPpgK zUy+1t4#@%83?36DO|yP>uArKButqf=#;iKF#h(-LCsF5Rpa7kd*!4K2y*wzyX)oID zUu167zKzEjZRHKP2KX7j-M_+5Pqf(I`ORhS3&_^b+@T(G3rQoIK0z$l6Z`klrLZ3x zj|t3Km3$Wm2Io`@gP*q63_k0c5_@Z`SAvztvdv|Dn-~}4qcJyhlvqn#7W*9%t!gPc zr=z-+VjTHHxxPSiw{ow`-LKG(pSye*fKlBR`ub@43t}1`cg+oVzmseNclfd@+V00H z;cR0o&DjEKZ6stb(0joZ%E@tthuB%p2`534$fc{@tbICat4@Z5>9%9pI8=TIl>?PO zgQHqRTT4VF-S%I`XxLHLs11j>e#X~r^-2JWZYl%M-%W>nRLnO&hl>%k>>l0Y%5D~; zi*GZXz0jhO-CH06**z)%Y2E4XQVc4FMG}mX*ZVD3SwXBY8|mAiQt2ZaI$|2=_`+T@CIt1ZqXjzzpAr%BuWacgJ=g ziwqCTpbRk|Z#mAxORKorQGIfdW6lIlgYJ!>B?i5~O|1UTPfaxRi+*vT-^PIAgZ?gL zWT0P18qxIZBsAJUqj4(e207ZmVgBC zRURPPcJXbLP>cP(NHzhV1k#$Bf~~f>#`ZG2hPvcH{3*pBZTX&K;ctGZYg%~1Wl#GB z-T`ifLvv@m))F7h7}@UG=3+l83HuFjV_&3=z{TFdVE>RJP)YuO)*yF}v zq&u#nPGU4lsO}Kf57+(Y@!E%|(DZoi51M3Q2L5!x9}31qn@Vy;{hPL4#8EA$tt1Lt zyv&ClL?nJ&AW1D^f3y*M{x$=h302q(Sniw-9Nk1f12^fXW46^ zX(RoIKmwN28}>=2#+`*n~bXD>8j#;RPXgVCf9#CpQ1+Ip_{Yz7W7P`(vod_|kd zOZQ;YW~$&gl5A!jK5j9n=l|rQ-ptVBLw%Bm`a9ByrauDh`%(W&K7sltnpC0+?uN~L z^}ZnfIz=O%NsV50fM27?9MwCT2ttv1k#t}~pUbf>cB0?ue-;16C=mR{S0}ZXt`?Gf zbC6emKmtCixkxvlN(}W|a8ysSCnZ7_tGU-$93%&;dEZdtm6xNao1i7J3_9p+?e#8$ zcQCeb1!?1V&0ce*e8pB*$`crHAmt*-Rj?ln^k{734v>J9PivMav$>d;$Fn~-g|p!942^jrj>`u4kHGbF>cj7Z9O!Oe7s} z_qH7CV*J$DwTLFH!`EKAdX3~af_=3fe|*-_SvR0M80r_}sP3V?CqfqMxW-towvI;) zr9|uSr6s)(eLg)5g6AZPEqy5eE53f#(ca!7(j`wfGPXdvI)mM&UWW!@6%^l45P@`$ zKrb@VmFbKQUdE%D>jnr2!G-qWEFKMGLQ2rB~3s<xQ$#n!T<)TbK0fX~hZqfa_mW05 zy(=u&&)rk(3gB)kk5GheHJ?{v2WAhD2~aTMRM})XO(>OlSCt3J&7u6 zRVw~0#~+_P{LQp{1T_K~6yvBy(83d8h&}Z48iu#H&rtePd&oyfa%UF`q}Sxv@a?;{ zhXUnFY!H<0m)KL#pOIJ}5P`%FM8EM%?0S-e#I9@v)vA0`dx`Vk7O9o|uBCR8;|z3a z`Zzi?92iZN`8^z1M-ST5n_XyC3=2MGrg+dk00}_5S&Ysbf-faGK&#;~QHsn;-+oJA zz4M!fH3gQby28%XnfRkSxR(}5h%5bLzc2fzDSivLon(sby(zD{O)mOoN$9&ngGR8s zNdx)67?p=U)1c32jGl?n_BRFnj=dWFO3wyhisX7ZTZAF)p{47@sI%X5txBHAeijAY z#K>p(>1reGHM?Oy*1zG8&uB*oZLH@vZB52e&7`3uid&5KSq~zNb_Haqh3pS;yz?g$ z*{*-fR@X8;9d7*FaIwq$UGkb%&&Y3d#U5d_z|S}8sJB~v1|?&4Bjqw4L?HG;u}WEK zCI0ORl7sjjG+cPz+^RHD?~XS_^mp#jq94$NxvZqqI%c2GT(W5{Z@>X1nal6;*^1zP z=SLU!7qAIG?n6D?3rPd>zhbr??(f+LfcqOBA$<>b=qi}Y+}8#3yxkh}3smNX`yFL+ zVJ6H*{nHS6m|}yBK9=h`Ce@63Np#cI5|U{FGOAeuE!Ec$>TL+!j-z^phMovb4C6jy zRP(YL@1Ao#-Gv)m3E#>{=d+A|L5s#R zhJgeme5`aWPr~C!4idhzF&mtN9{QR{_{v>c!o{#}we|P?Ai7)il&W<$(?+-37FEXzAT;oOv)HoN$8}QOsY}Iov?~xpM zVZ2Z5tFG6c@~ZIj;IEpWTcKcA%$e#3IB_H9&0>)Gp=qv|H-GO!YncS?0uNdPNC4W0 zVv-)TECVgG5i}Xh?tMjI{q~E7wFcIrDu2VD@%W?dCdq3*hIiT?a(2TL*m7b5QNhn$ zbU5tbp${^~_yju{N;QHl*64o|b$jUlPGLZ>m++YA1nITAYV_wA^zA)cH(vWl$_qWO zyU?j)&-?dYI|hhNd+pOGnj7}w&$akN(J*d<{TZ}xV0??*p{=iQRH?j~2v|C23?}S! z$2ICGLy2A08<>doHa(nm1&{q^;Qw8({jS($e$g|o*x#*ljb;^OOR;OOy-l@)?HREz z1`!xdxmcwq_6;NlmcHc?b5O%G66RG`=tSg`m&A7F?9jIJ3@ipBQ7=j5I`mHc>TWZg z_m#VRRwK@P8$3jk)eP{a&~~nK;UAU+|57Nzz&}XCpD+6N;O7|l?VExhx)X-eOha#O zpl_gB@5fGR6up;Ae}|S$F1>;vpxnJUn(%*&aWv)ygN4gRvI^n-7ipgk+NzUjz}U@L zA%*u}hV(Nyszr!Qjj4#~yyY{Nuhn`8)G;J)zSZ1e`h30%PqOLra4FWK?tstW>kL># zHq*pA*km+6?Vqmg+_Bab{u7X}-*&zcCCiBBe$avKlkDhaxjBuo8;tJ2)}Z= z*v)z+*!1bzinGd_ll3+NQz33Y}`P9t)BX1KPv8iTNs9BYW#f z7g@H4tVa^Ea;Vmrbb&^;eS4x*FE+>mjgW~OKV73b!=O5p<~HXS{F#M6iALQ56pT^t zlOVlW3v^S^avem#uBFY{NST*KKFq!CR& zJc+YA#Sd¢%C^U!TDmVwWUyf6D%%e&AudxoW05Vnz2DP2{fjH=pctg0D`___sG z8u>2w8!K~O{HaN%p6R6D(8ysCE65l7KaMJgHxr>s4{hawW9D_Pp_J&{)o$=97URye zZ$wNmb52`C`}w0Dcjs=ld?T`D+pY1CvW5G^?}K4}2wH}039lJ^B4qoK=wIyF=KC>@ zFIe+X1K4(F7u=clJ<~+Kd$;QOn{Qw*$usS}JbV{ue5)UG@m=8Iy9o;R<9ie0F!-(l z3E(>_3EyaP1bnxXEClM|6RW;lV;gL+b)!KmZ1kWu;Ez_Kmz>B<`)}AG!VxZG^FPq# zVYmL7_DpX+@BY=UZ2!fe;*;(6UtR1kkw!Fqh*+Q}+fT_Yu+OAfCt_!6GVNKB>vM4} z*9o36z&W$tIM##eUY29sf1YXQ_`*$1e3D964}-W`R*yf6@rQyj)_WAHi2hAmU2#;y zXe)_;#d)F(U;Ma_0XNra9Kl6xdIhkL((mw;{ z;g|mH(6q6fT#$hDzlRN&C?l3#OnpI$g^ieTE&G^fL<7fe(Hdxg%_Lj)jqpwe-$=30 z{68Lc@s0e-#W$6a!)F~|KvV|bB#;2U;v{^}kt5)Hf@Bkg&B>B`pB8N8F^%nN8uh`j zU3DP-G-=t{KY7BXWxs>YpJdr*;>#Vh$*1qHaj6h@F;Q^H0HEt2FkPJwq{;{UYnZvOkw&-G8?1G8AmuvS-t%e+BER9)En6U5qNC zf78~LII79Cl|;Z|*<~I?SoTYX(*I!DJ)lLgYzgn$woik1Gefp6Vx#$UA95pNmoG*B zl)?Z;K*-;j6MhW3hV2l15F{Y~bXcg7zs#9%e8HN74LjcCkySZUr{3M45*_r|tfS)b zG#%#O$sqp$H)cRSAcmTMvGbR{Y7uAL`M|vhM%|laR1KQZQ46c%7S&@RvT-G5AW!OhoVKvf(Nm4`R*I$M51rz2w{nHc-LH&Q zKJM~i4MureKmy#oAa>&Axy=oCzmseNcY6KbPIiHNukILyBBoK&UvEs7^tJE?Ns?}X**7EU>zBHco(wzi zOL_@ZYD{DTX++b{mM-H-`bp{rCh|~Y>>VNL(T|9v@A+O!`f^xD5{E6-Ox#pEHsQ}t z_~R22#}}l1CTT_0CUN{K?6;!lsH2dN9-N=)auNIF6O+K4Ne zi#~THa~p%2&j#OxPK;!(0|`hb8{NP-SV`c~$y~KwOQt)G6@$)iH+R z`8cXuX`hK`rSn|o;e%a745cKyP(7d|9i74(b!_SkCu3sMnPU3+^TTdzI`cD;FWI?_ zu?X^Y#;i|3k&rJne<4UfzAa$<{>XbB$)V;DgV-DCSd|~>?5F2LBI91`bbLC2onsof zOoVtpLWY4jRctW-Zyv;{i(QB_pl3hCT@ZOAvKPI_Jm6Uf3PisGrw6?$00D+;k^TJq_O_qFbPz7sJiZyU+MM z+^MDLq~k4M*ut&?ePkX9-wEKlk>Fcv#Gusu_{`CV4&Spie0noFFc)15Dbd9gI#&@v6_p{TdWPPq00(?e#*GSLE-%;VByQapK-b98rpY&>> zB!liAkbv~^lh8dvejvRl$>MEFlJxj#6Qp-bRHQfZ8!f#)#%?fm1$Pm92ZHkn^Iddf z19qlZdwwqu?92r&*fk7iKCnl6V3&aez)li-_e8149>A_A*~Vb&G}yV51?;@l8te*M5Duk*04=*H0rg5RMHZ+0$Q7*t=OC*vv1#E$fWWJctS)Za8d z^{DFzzMStmg58WL(djw$LKG9Dn^hNBo>^oaBe7`u^P+QaHFz^}2L!*-o|3r?T?Tcm zj|hj~f2}#Ju0uZ^vDWE#LoteJX0J4u%9^(jDB*_JQLz z>Iuguaa0RvMvXv;M|cf{bd&Sqwdy;_&$*JHmY}1k5{Gr0#75;Ii}90;tDOT{}#7s#JE!A-V0%o9~nFF^($ z=+l`BnGCZr$yPB)Ku^DEgK`(t{+-H2%}Yci39}5$61)CGlyuHlI@xN!4&2p#>j)(& zOI-I298e~#g#A5}(jNiG;7Eav~% z%i!95(<96h?+pv^@>Lr6)vjSRHN@(#X)#N@faGW|a%?(F^fi^P?xNAXzXpHa#vkg~ z1fmp8RPE8dO=aU+_2xw)S~0sbJbVa5*BVN+HgAZ9`Cll>6L2I;wSu>i?ycHLH_V?l z&NYiR)vk2&8Gn4z4MB}Yx+jAIq`LtMHaUt69(qt8FpI8&w<2etKORXm|Jx)H@Nr*i z0XL)FzX=1--NmyES%^0OYd>&W#wG9|NtSUYCeBQ+y|l{3eivht5Bn@g%3!~lG@|Jz zC1IZ^(H8Unw0QLLMC_bky>_BtANGaDe!gqaO&LdlCP(AwM2awu{&K8~IeW~5A+EK? z_&d3^bafestA|(P&ja}5vyb%>bT_Nj(nq$b6cAM%dC`c9m`J9F5?=##H^gWn-rH&J z%##9DsdAyitxqUFy-~(3=4_y1yl2tz=&Nd=+^)#sPF!xvp|_BGnr6Kkx+8%;>Qt7b zxy9A-hE|@s{yuDo@eFq6;y!UpaKZIM{ct23kE4MkngP&uIyf;JTp?eDpSJPQ7{sJ{l_=1`Zk=`y5_Re`6a!qJA2# z@RPIr*>1*L_|DTXyh1PK+wVDu93}z}Kq6y)^Bci=w|Wdr%gV3@wQm(qcdIgq*Z5wD zbQ1DltCC;lVUw6!IYko5KTbwsm`{X#6^G}Gw;`D4;W7Y*5$I*K2QV`y2^epId&02As5Ac`{**#F*)?_Y)7*lWNv`g)IL z(q(n{Dql$ZE%>q#nQ?So>rqi1g*Me;_@g_XZ0LBMX@3aY2abu2arCFgo;58)fRuQi zsg^6p2F3g_cD;$~?1ryv*EcWznwkzw26X&0=VY;p; zE!qQ^uVrW>W2%ew{t8su7KRQVn3FXa%JG3OG?*3!OatjO)^COeG7BRh)>>qgqxF0B z=Z*9`aAhMhqTdv7pt_<>bteA!^gEIA0_AaRAIFy);}HFR>X`-g+s9P1<%s!s9REze z^MT1xt53gg;`S6+>C;QVMf9WP>{)t8M6uNSS7<=zqhT1>oINz(*m8ZdGj5ul_RoZ; z=U{dtVHHB)&_)*wcU`W0Df7hWUsrQ;&m)aU(yfL2w5; zVY!knJeqGiqpEo-zSj-<6|hD>U-Kax6ZAWP9Qk^VtOLXoq?5px`wPI&fGO~H5e8tC zzz~>8c!3LLIg%Cn(i-&@S_707`LkP+osRZI&_RBx*k_+po2zUO^9s;lave+10C%2ZS}{Ue_Ma@HTr`LT~R&)>?^w z5_`NA1SzZ->*M%6k4O?;TP4OCCY9 zAgS~lEWH`>5Snk9Qpq&$W2tJEqC&HX7unxH^$b%SP(MKKRODn~D^#}utMUg*1Qkk9 z-PsH`gPYoYoHIopO-|Fthb3>cBk7%>64|X$oM=T(CR5u zej3jSI~gx`<<*(4?ANDW5hLKHn128%0gP0?n6pvpZf1~>(GPM5!v(*LLYGoLC&4te zd}MRqk8>oBgda}hkvoh%EWaHE4qF=z&3?=kIkFA$bx=e6DK?y|MpIaos;yv3@6XXN zB$fv`Izo~0SwBIO{s`t`Sg%jQ!;?guJt0TzHf(EgXfQOPJiReDM6e$4oTohha~?!u z%sXXg8}j@GO$XExO|4EH1Oe!;A61@0m=$U;VW|90VU@t&o$fF z5|D;6jSs`Rnl=<#C{%ZeY136*Ho&Pjz?bYHuC7|_7y&5hPU5FUBOs;t`_iu;rd0vZ zKy@TMF74}Hxznf*t`$7n)I1o3-atB-lS%S#{8=A-l{UlOMg4s+4LGF_Hs=r;qOB)g ze;;fn?WgyU+R1%zl|1zNAUl}uep-0JoGedxlSSq(*kq`_?#In8REI^zdyS`!h)fO; z7mgp0gNS|p=q)3QnJ_PCq+q3HrOIWcXU-^fwopkQO%npKY|SK}WP%9|mo6kcB5kPN z&|7|>tt@S10OpL5VOdUQFnkSuwLM&xHk4qo8i4vY1kG0Dy7#CznnD^nnF>7wC{=JF z+jQtsZw_TUj9)v9zobq^3DH08K)BC9fM=ln6Ygih(17Rc6-{w}j!;P-LoFwA-v)B| zzjNQu5KQF$t)`G_?hge@bz$v);{Ftr7)8#uQy5Fs^--PeR&oCKuxaE*$Z-+*a@fWuQvN5-`F!4Swgha z0+=9or!26eM{kEOzQ(^vWiIjI_W@5Nly0-BFK&6a#SU*!U8uxp{s$z3GU+UXhtY1E zKt=6ZlqR=trhJjyT&_#io#2%El%?MJOqa5Csap-LS#GJvS!(t|UFtYp>S9xBs$1$- zmMUAUOYLJ06FoW|_lT?XT4GP|@>u|R$B(#OJ|COuf|+%g2e}q~SPfm^$ZA2XyO9;9 zA7W?v&QJE8AA|Ga0pRbt9OUuQZs%W>nNoadFq+@)5}fo8MmxQP2Quq4Ve2HQHbJ_h zAYCS|oVqT8&g|&rnDJ`$PfTWq|6uBrDyKi-4Ieq#iBE-re965n@SL+9*uy3lG;xJI znO9kDaitn}~KREd6sR6A5K_lTeCd6eCzQ3=UaqlJECXfS zry`ZrEkr7NIZDC4rv}Qq=-H6UjRwjWPqaHqk=EhAW-jhtTQeqdSmnDeIk>z&)xEYOpJw4X zUIjD^&73mKYYe#Ao;9PS6)=b#cpWL}S-w8i!-wk?O77@K)c)B?Y*Ni-8M4ZL!c@jL>j2lx~8(ZqFvJtaSHxGp0>Uy+ibiN3j9ix) zEZk7m-tohcu6Fr6B#}Q$t671-5{FF?~!i{&n;RHl{!D zucSY;G5w)`CH>)z=@0)a>5ptof8<|De^g`oqyChBvOoO)uM^|L|JUSUM=nJm+f&=U z6$3Gb)SD|2eVv59d@hswEIdJSkCEsAgt!5jH6_`|@O8f27Yl*Zp|VqS-5ibr2E`uv z7v_MS{7de|?!_%#USHqlUhDdJEr(I8so&pUU!HGBc%JWnjy*#0BI7uh-kfY+w@JEg zmUO-29T$(3{~_smWzzNBr0aK+uAfi3ekkes-lXf>ylcUKRnqk(N!Q(zu1`<8J}&9H zP11F#~3Om=l5Daw|VV}{I5#7z9i|od(!pkN!Q0EUAIZPZkBYt<1Lqet^cI! zm2z!IyEhbHisjycaD8$A;_za8;87f2RNN0MLyF5cr3R|Ep4UH+I=^pV#lB$SrhD3O zHZH~UCwj{9%x1ypKumVDZE-=g{jt`Jme!1pMFpRa%?QWr@S0$F^`us31q$bnTTxoM zt89cF9f_{6-L8(EXQytrSL_WIR*lPzpT+)EH0g9ZdNCd^x2qK%FSl1lKe$VzGR^FFy!TGYWZDd?;&A1z@5#-Leop#}>+s`kWGzNy=E0s^cKU!#& zW6cOj{Z}y!9-q^*p!%K(05qn!*QB(Z@b2PCw>C&I{3**xjg5e~0^y&6;T^&7QcfDz zVU=EKhmDlV*l|?#Nr7-Iwi|bgC!Ld1G$~J4bZFew5bHoigntc02mfKO_&uIxm&a3! ztvRjQ<3$JNyErZWcPw1DvF!0j8=Id_LEW?*YfdSAb-eSgV22GT!UvOjVUBQ(>cqn3 zzo(A-+BFGZ@5Fe|F8r#jFGfDwv33%E_X|D#DM5UgYj;><7tSj?#xDOYb?jMoco_hw zt*>L&6*K9PUQUtJ6?S2DS(+U##k(b$rlkBacpML9rG)CN8OcDVN<)@0;QqeB z$jul79%Dz&1Dlzp;jMuV-`O4Z1Pj+&_x^~Yb_A?K!yW#B2e@r;Y2}Y&&#^yz{WbkB zhgW>Kf80k@uV|`C+Mvpx`Cv`^) zKc|M)1PT|FJz?gvZh;@KMun;@>yTmq>H~jr@g9^2ZHV0l^V8#K`$NuN;@>#1ecRPE zyhGlF>LVen)fj{Bjal)zfx@+A$LsPtty{n-m;@N>kPFBt=w1N2YeO6C%7(HGh)do4 zD!vU&{UsO<;kC`Rcuni$TK(;PM3(;E7#zRa_HC$TyqDm{`@2ZrY&+5;t8j~LUDPAf zdbS!dCxrE}>naw7aynP>erdgJ1y|Dy;TY`j4$PT5b`c$tVHXa`DwCzbHE0SIBYlwD z%!{K8y3aaR>-?=-(Z~VNJ2D}$BcrnvHd05uIy*8bb51TSK|TEn2m$8zgUoy!awIPp zfG)b$=cvBZhBJh_;_O1BF8WDGkfL8$JzADeh-?*nuA()N&O6*!Y(W5s<*0b!T_F46qsM zY~Z)Y>prqM7;M7E@FF(Ddw0K)mtf=``+B^Asbrat#^iJ6fQ1?c&!rO4Jhxi5g^fjkurr?Dir-0#8id4_Yh!$DuSLw$1 zY+|^wQ`bg%WtFf0pmjzOI{zo%qk2lXR~9y(EbClTxgJ-{8}Rcub#`r0CaJ5JL@KBb zdf^exv)o{h`0znJN-+88Q#^hwUM{w-sU*qN_l__hdeuIoNK4I7t$>mY0VR`&J_3Vp@)(1Og&iuLXDm}(YD7xMAHr_OSDrSwJ zL4;*TiqN%BSReS^zA?4z(D7pc`ABO<<>SCyTreN= z(%S#X@(<(>NV774U(>`V9$nj|f`Jc*pm^D`IXs|9!^-$PwS79!(qGU&?BRoGyTROl zJM!sjUj3i^1L+kHaFU1UEt#A_&I(4x;s1$Pqm+Z0LI|%YuQ(5KPKqdC8i9b^cd$2bqD$xNP?M4D<#Bi6ep?b_NUMW7^pgD$rdU;KIg! z5?)Ysa2TZM_nSS`f=?3tL zRj;Lyn@r5@@Ep~RM<^KjIvBY@-?zhGtAp`~)vrgo9DmP_+~_>Q`jKg|B3C$scB|_QA*=&g7hA?pd9c(gLoy1yd&pEJ=6Opye0fer>?u>iG{h1o z_)BEQu40Mu`MExAx_M7YCdae8E{Jw%#-SQIXK8poI_E0MYQim?i66ehRiD$5(7gEX zJiB8Lq$}z+WB?dH?t;frtr`_zet061Uin&}PQ~8<1!sL0l3C0hlyv~*sW0GuwA*l= zPsF(dZY(bPox^m`gUi@khLjv~FM+3&Tt}5r=_Ut}u(g26OHB_hiD`a8wCscwbx0#< z9(Gwm)Q8X#nDej;bEh@N{$Vcge*L^)e}m_r;oQM~5wQECulTQ@pp|Mr!vFt*K~LG#;+TvhVtPN@$1D*#d>5E*Yr%+9nhCR;C23d zHube$!o;A&m~;un9PkNMbl!xV-ETJ8~!7RIOcJlNx*QpRk66?8(%p4XgLi zpA#@g`M;t+Tcu0R~iZ7VpmyF03kvRflPwo`qIc9 z_)dLP5yMKBI-9v4%n$1nM`f#1s?$?+@Vi1)f#{eb5X)2tp#UzjRWqDO zA$}r}uFF{!(@~52Fy3cJM;9?5s5Kn2MMr0=6*!R!^lM)}iMt37-5DNE1uo-11K4Q- zU=bwLb12WtZ1tE^lQH8-Q}Y?dj8xPNM8}~9ob*VkFfLnN=at8P>r(#Pvfhj$GvT=P z_!ct_Hh9u9I1?3cm908CHJRt+v8G6dy1EKYadqZDK_bZb;kLU6g92P+t8F+jBEf!J zPmsfJ%S=$|DAl^;1fpYs_KHk3S89#TROOy4nX#!d3zZa}w7)X;|9Ob(aN+8m{)M;u(H;dDqn5SCpuYf9q^T;8R3oFYQm#i9 zpB!pOZqFJdeXkuJi5xKw_kxMP|4kKf)y)|XgBTRs__*nR9OL%YQ3hl4cyp*pT(0?|8zUQC1=HE1(`iTz7EIYxDjD-gBzqk&ew{Uk^yYc6pTy}(N z3nyDy^&v!(Vq3jdGXsDiu-=CgDi~8b@k#XEHUH>F^vV3%`8@*1A=uJ(e_a#!I|AF7N&nNTSBavRk|3)v`h~Ca?6Zq}&ztQW~ zh~5i{^nOG-@;~tV({suE_D!Vs@c%~d=|=RLC(`TrztJmgMDM+866E&_(v$y|U#!1s zRyGW)rZ~2@Bjbwbq%P(7G}`Vv@k>R+k$r@EOTlhQ1v}Z1!|li=C^0wGSxOw0R01xIcMEy!w-r6v%gGVpuazOT&D5RTQNCsT5@LV#it$^HEzSSGD?liRPEt_ zYI^3hI7z0mz)g{|%kOECnNpT-Q#vyl|wdkK2>a@0)9&W_d@?mW+>&pCQBPT+2JH1r^gx^6+HwoOGOh;Ux<3|`*D%kVrqqM=3JXwK;p zW&))$^>C~;C)9&p{&qAe4jzmQjy>|Ui8rJ%=@C4_oQB?MLeHYyg9UA6aKYOemSf9_ z_$TUi!7B3)Snu}9&29N%1Se;Mk(Z~jNk+cNvybyM+ycux%CLs52&hIQFX)lY_;WiV zVKye&ZHYn0J%lKaRcLGN$kS2_vAvBQ`9LQ3FgMfz@!~-O8#5I1zavcm!wEy_M*XA+ zPx|l)<_SW57=9$0*5au%enfL<#j3m=h8KT$iiD`7_rH?g9&h5S0t16$m7pN;LnaTn z!!u{V@KO+=7Rm@9hsaXvQ6&(;S0AO!uQ-j~D&E6s*Tmt=_x!s!d<>d#Baf^d%+I%U*xoh;#hHLJZ~FlkoGWOJ7d){W0Y&i?`K`2Obkyr5ZPR^s~JVA2tVB~h# zWmn7s;(#S|7`1M3W`ho8TUlz~qf{x*Fd=k2a%cYb;dr})!fV_yN7=K$#yI@P#Lz

CS)_CsH>zQuGe zjhNA=4}@Zk2p5bYNp>&4Q? zFmAL}t;WG;cP|zi#3w;M4;EMxYzu3m6$h)^}lhCst$pQ@f;v4 zlVp9crF#*GMWRuY+1nh$o6$=bB%cc@3IUX9tpf_PI8?HYw@)G6-eSYdlEnIm-fz^n$}vyK^xBJx1sO6e1!5BM_59e;6uD zda<2J)(3QP;Hp?C1lu*uPi@pK#D#lsc6CGT>aJ&Xlw`$&7O@|5D$tXiGOd~79iat@ z@%CUyy0_t!xT5^MUh5`K7)7B)lmweH%);PM-Kp7XDfCneOB)v!9E;K;Ul$*$uX((I zzzJock*ex*PA_grR01n^?i&{(9zFz8l3L)?`ztX~Rq`$Xw&ekU=63aXV}MrxurmrU zwlP3C0Pcta3~2;llwo;}#^r8~0%ZfpQAcu|hX5aHcEmS8UmA~(myHuqy7v-&cBeO& zb8$^Y5EPJxY%=9bvcYzBLL->sEf&uD5SOcTaWA7djyIVfbv%&u@xc*XlVnJTaShL4 zlmx~d800CpLj>b6)tl%){*8h!NP8amavkLNAwUP0;|9VRl-j?u?BCh^MZAwS_U}gg zswFeEJJBlEq~{{AZhLSLSs9TgP&vh8duJVq`>n;L8uogAS@HusbO0V&$pRn`&cWpd zT;4|Gfp}02mPyfgAU?j!NjG&lbR6uIvq6Yb5YTHO)`mk_hzBx4HhLHw0sHd!U+=ct zQ4yq-b~F&S5czX6XWK>VXdrAT{1;|QJQV~Jl4u|mHpmE~5RDPR{&M$|#FgCI-i`|L z_%|?#|9VuAY!>NJ3$F#?-KV}GeADA1Z(=UdkzEHCQ5U9bK{T?fv>9h5^&WL(2LUuc zxMqEEADFs|3ad6+M)&ul(yFhppIa#sTB2 ziLr=*boJS22%|GtnuDmsAIXl7Kl1TF0yIFhI8QyjA*RFIW`UJ8^PG{0^8t3_7sm%8 zd5yy><1_uOTdV)YH+4rjn(Z1bIMe7-DZ|2tg8v?z$e_a%HZ2hmnor$C&3pnNqGq0j z2}#tFus}z@yg=)hhIKg<}eVghI}I) zC9iyoLV%wa%TVjjGAuk!JKXwZCD@Z1&^uU2X~J({8IJNR>Lm#;YNH?vXzGn~zGNG4 ziJPdGm9}~bMHsR++9<$fY#}1t4p*zshA|GmuR~%oJQx(r9}q8#3TCZ(0*Tg6s4j{7 z`$XW$Z%+rFx`ox>(03G^C_EWu)u?tkV@AAoIUQw-b~y(4g+*x2=d**=L| zEk*S3O;*!3vRfPMC>kLuf!N%|uHqhhS24D8%2xOP0LRdVVk7hkdwljf^iZ5U zfm`M;jT1kGn$$hp(F`YDq*ce56e^hqfO~s50K*#tJPLq+MFDy@0x-(%)|%nXQJ~HM za;Bjcq7d%kAPGRFi^th0JCEOjWV1d(UL-ekr^v!jTvt4u(eRTbUELTB`YJ$4%UVnq z@sPzY%e}_&iAGr^r`t&G^~6^6=^~UM>-xm{BTq6yWoaB$iy8tCG}|g9H6mDy-x1Z3 z2lJ_V@vngzNp+}HlH=7P=Rz3fueI~H;8&GQ(`w|YGWE$y1RA7hlJROJ9Jp-#@r-!= z@l1Y+J~|m@WYHgIqg;CDc<_4!{n7Z;r9bLOao z6s3#qDC%E_VN6|;Ia{Yb>IBXz;%5~|WJiqv$kUly>^Dq7I<6Kw_edQ_ee%|g)F-hM z1)~R|bY&no7k)=$&v*PFqr%(W#U5*HT+dtWJhw z!4P2Tn5&}*!i)6w_sEk=GFd%$PbHH`VEaG~WF~}RkxJRhq9;OTIzFf)2ym`^t#71o zX$>3s{nS-t%OmNh7Uf`^Hl-){+hveJKOK`3r=Ri^3+K0Re&vSt;D^_QiV(#kGYz$O zJ@9PorE;|v#EyGMRHbb>3WE4SBH(mZB9%4=c0;PP97EBz6<@C2Nz~>NrA~i8rs}@r zh!!U{LA0h9;}zXMQ?Oj{VZ1+v`15@ljog`RU$`K_YOjY$w}%{u?+vZdG69cwwwK&Kds0}0g`YB=5( zct}3S`Hl~1NWgX?PIEnpG6LX(v;mQl^qNVt{N@R`{M&C1P3JWx{>bIoc*aE~V>1Sr zV|V$h`?L38)oFnWFNZ%W?xoH9$p{@nA^@3?f!}O|`o!6($-DgKxNd>GeZ`pKTKFQP zlhu3gP~o}CgPp=`95?m^7>%|ikno$IqPBFui7=s8?FyjKGTJeSg)cHDIe0kD2wn`; z%ComB#VGp;PrN_(8i2sy(z(0?(xEh5f_HPT*O))}_lF@Aa}M)+D;KHude^_a0x$TR z!ac0NV)8<-;exwf>;y0r`i8yT#h;8V{CagND9OhABU3U|I$qdmW&fr)2dm*gQ-!By z5bXeLurD$>Iam)o88pGOw;Fh+5KmlqN?!=$?Vg_U9Hax!FYs>G1I-JGW**QS+eNNA z^G7c6Fg{4=I1)DtRv6sImb|j&y6AcxTfwb;CU4!nG#y=<9fuJ;h=FDMrpHx@)mn5(GniqHQ#}ey`c5sQ3Yl}`@`0aNOJVaK;)8S zFR!Q%ZYAIBtw1rHR0;|Q>sl1U07nbCN4Y-So%A&d{lJ^N%a`?|7d1$qOdE}F`Q{Wn zP#4^xAg^l7PU{cI^@V%-%p90$!v#IDKUI)}F*&Z6FSxA^1tovz%X&Asy^c&b&4gx) zXM|xh*90rm28P=<8)&v|k+&Z>(hWuL4`6T)Fn9UP4hRn%p4b`0p4b6JPJyHJb`-fk z`2&B}8kElQHf=xDNId7PH`fJMAj(Nw?7y@%@_rgqYw=_l`;q%h#i2z&mD(f^b3WgJhnAR#%Aef^aKvL4n!6 zZ#a;AkZf?!Dnz5bW=mhNb^!n6zunS~s0E^7g#xl6f|6==}Yjp~GJtYS05imWe zWRy>y8;#R@&@b{U*KuCE1EGVEounu1wg@ z$rR{yPauD`B%*yUBxUe)D!$|woa&)09qwC|(hXpb>SA#f z7BlJG4M~SU+w1BFVg0#XWnk9jQl$%LUk)C)-E(~H(~Xu!p0Xy|$ows9*}(gYqK!;f z`Tv$iisLvBNZ4&WKr|CHN7}2~bZ@jx$#$F4V{LL8ByB0c@{binus_wXQP4P}?Qw2v zQ$CUM`;>=E6|TRxt3shwG2;W^JOEw-2n7`AeXj>6*HFC}?e?kPAcO8LT$~@rFM|Dg zdHBU%nPs=DAMi^hcN>2>i>fc=sX@?Pqf9n{+|hsSO+(5tqby&#M_C0J@V1<1dMFj5 z55-%PK`uxBgB82+K*n};IwhW|6?%9okYe5VKAV(>WJKG(S2N#b+vHS;hO{#CYA51jD5>JuwZpPRBq#K}LHBD1xRw@OB=0_y{jVGa7Dq^DZ7lDxKEy~a5e zJof^Abq_uzPYu2(zDb>dFQ~q4MDwER8`QM>n2t_rh0b!cw3D2N7o3N4SlPvPWz^3a z7xfHPw~4EXPp#@Cpxaejg5o^|zj6_!U7&S2Y10rLqihJ1Bf0NqIIG*qJ)-MU3HRlE zUoW)&uk5ccfM*U3pPaW{hR^8!`jt>G<5hLF8ocBfKHupINtZPtJ1%qabTWq%#$ z%KrMx2%{R?U%y*0<;UC@2@|Jw5ImgPqgto zJ%(re{(6j0qZUwZlm4gs>#q#O>avObb(8tOy1#zYDlJ%UKf`735VtgNYe|^O>5Wh|BudllbcsH@X{!iu~aew_0<~sZ9{jpS|#0deTsPXgP zc(JXOqeR-*s=H1HYcVcQ@*>)BDOhiZXPw?W{}GBDI-}v{`Pr=Kc!*WItds1r&R|)x zd468p=J^}c2W>ALsS33i%hFY|Xhr356-D>QD~Dizd@jdWY?s>zrGNq0QbkgjRNEXz?sc{ZR`6oJqxWI zCQ|N~ZrWVwv2{0B^UBbPnBO+5&@!^;cID`IF&J!p%l>#I_ZnT?YbY+dUqFoX{QxZe^>s$WWV&T zItKgYYbzZ4<*OHQe7WL2LxY4N!gUcPM8Dn+zu13d`=wYRC*ywaMkYC<>?QPYyty&T zZ&B%zN5wLMz3~??vh0U9J2lSU*h=eLjrYUfMFd0HE$8@^jr&B#L)`w_7*p(r&s-2Q z5+3V*c>3Z-`{DnS>(P4_X`$t;M{`!jtw$eTitPW@>(N;v>G!E}YWN^dqV?#^h0#Xl z4+4)iSdYF=!A(PQOMPJff5m!q!3xUSed)PYqU0|DE;dLl_Fbx*k0Uo(TsK+)X12=edPZFzw6Kl0D9=4+Pu z5lS@tzkk&~XQ77I+jmRwk-a{Ry0XL^!2f~s1&)7CS9^g9mltd>(hI|L8)kQC2T_NK z>o3*o)Oi0KKXzou(tpE*)RceD>A;IaAqyxSlYdScv5flX?8NSacqvN*qm82f_Yxu^ z{yAM+YX6*ez$xmVGrF1f&#A+t(u9A`1PocWXKE)D2Q?={-LkxC|D5eN#jj3}%0Fi- zeGT2cn+$C$fq%}ThH#sFfcsVdoVP?E)~dzFxz?-up_n=TISkhp=buCWaJJX>&-oX~ zdL;jxKQphPe@+KDX}kS%URfCDpR-luY9s%gmDCjz`{(Ss1PyikbDoDEE8JUeiYkz| zLBY3|l+`Gjob_Qx*k9oQC5uz8hOWb!Q9N(zv1GJ?pR$3U1F);PD?ww7uFqquPnLv2 zxc2Pqlrvwl-7a~>XDZ)6DE{4v@T++qiOzDbJr;srT`Cfx2QHNn`7a7X+&A;Nj$87k z{;a0j`S`R3MbAQEuj<0Ko}?FsXEiFU_$}*Zt_ejr7BStC>10D*kA& zOtgMp{05PLzs`zwaqDMHF4&ubsLk&HQZ(?_>Ccaj-d|^EUkK*k5CMlciI&`7!#35( zH~@d06NN$zdI5^}JxF(i-m&@X%=mkpzfSbrx#Nc3y0}ZQu2u2v@VpB$*cGIwLajrE2y2>|Es4ysr5QsRgQb18AhgzafF2 z_33uGStvJWZ_O(Lr|#c@Z{|krBdX>A-d~8mi+!%adFlq|H*+d4x?zUYWn zU#H%=9~hrt?{DI$e;;+i_~g)aSG9i00;Ht=aW=4nx{a@Xx4KXPnGzk#kh@AV;)`jS)a}sGh-y zpNxy2d}>23#?yNA?xuuAB%wmN8BEgz1Xuzf3_ot@=7Wil07byA&hAhvR@m zpb|T(;pS}ME%*?moP#S9=CX`^(^1BaQeQx~FA(`VkBGvT3VKu^a#NbR7bQ`Jx*w(Z z!i#x(u$ltRJ)oaaob7D2I$$CQ?$v}{U)t3T^&K=@aXwj3+MB-QG5SGm>vHCCW+^~LZn4^B`=>1{{lmvA<)Ejmg^H~Ot7D6_A)TPfeFy&yxcZd`)e!4V` z7nAs#AQU9TT*8P*W05Z89Z{I z;fthrG)29=0w%(X<$Y>|KEda36ozrzXI@@sbQr1}Jn$VvYV?TBXRI!`YBZ&j1bG|} zk&LCsNZVsY7zR$5@Q?=}9(nJyVxjQ zZOXyuABQ5u9}8Wv@iwh|^1^#|%^G9ZjV!kQM5L3J>o!dvVSA&nU%X?&4cEWwv5-!^ap6 zxqyx22;!YbvBPHQQk)$=NzkXfbnps^Ae8%qegV!;rLLijQ z?{V|()E#MPfQ#|9<^tZ|f{~(S-f_i<)7n6zG0Nt#{cgQZoQ52^-4DT6U&yRLoig}* z5%JTc)01`{qkC#ZRvtbR&X5t2IOK3V4dN&8SEaKWp1Rplfgy*NyvTmWB3`X%j!wW6 zhQwED$Y0SD=4Lv{dQ>;y%^VEGuT*d5XdxJY)6od^l)>BpqvC9%oJ3u#FN>s1fy+Fm za{KZ?v<$(WNdqrrrWT=QQ5xXJ8l5pB9Qyc>DBk&R;sXPRUFo@ogqhMvJUp5?n>ksI z|Nczr5hF```m6l*6mZ)STuJ?eSZ`e9e~(|bw;OL@9Pf-Id!jY<0Ro;a9IZ-m-IYxr zqii^M!ulBhQAoaIm-SaEs{!G_BV+#>8XnJux9KFG7L7YLO;*N>b0f0Q(k0^ED4n|rJJdvK>-e||fRsR&)wKb`;i)Cn@Th~r%V2*QxU z(dCs#gnq48{W-d|XI^i4tW`modl5tp@sR+?-_iDTT!dfvkmF=WZ3S371I!dK-{L4+ z?m@*6Qb~A*BueK`b+8M5_*W&MOv$!W@YoBFbcZ)O1U-1f&mjFnF^0F%_)%jq#G#83 z7RB=GsQBNuM4Hky7*t=B7dH8)S^+>Fpml zTR}sm5`i<^IH#^XRXO|!Z)9mVR#gSn7GsUW?ta|oN3lOh-Ge6z0*nVexni6L%+Zum z^i*@CSh}kB%hqYonyzvM2 zs%bxq+ptu8nWm>>&H~A6g1uT7e-myN@zn?SCy&hw*0n4?A14%GXW3A)I04;dj?;In zx>kXsP=4QZls%zS4X*DkAj?R7OdJ1(O#d?L@S@Mw#anBhZd7zhUX)}!IpEBo?Emy9 z5mWHre~DlB*|&{ReG&p6S|N)y*E+l(wSOeAZ&-hkUg8;pQhcPW z{T#)%&h>*m>{E~vH|(3k`CLz1Jb;On2()(fk5z{$`k_whxs0ka)R5SkmiCBV>Jl8{ zfJntMpbzM*$6;eT*%b}&x*`!?T=B=@b$bf*FzlDv>(~VC-4D*CaCF+czmDw{u`1IR zRNf!#_Lug$i*p%-7_wTUSZ9+{bO1R0O8oF0Gg5}y%ji=xr$C7Go_+URhR zJWHcHOy)`27o_Dzhf&Zi3O!I-a6Ayd(JRaS=M-YnS?#Mll!B|MzxU-QUF1(PW~@hP zzTnQ}pf0#g@f1#1>Cgr+GBhWOSnk`)TYC5|D*aq`VS%Dq78Tp!rXH*bxpZYtDyOuG_l7dJpi!wM*JEjrHWC3etNT$? zzAW%%eT5&!xq^!!M_IeIQ|)J4Qq#Ai(4m5OtKT}P#qgn$|2XVF~t|F z@v~TcJMXquNsIhvqPj@#+%C8cFOom*Y@9>$KNw??ISvoJ;XM46wB3vT*Xw*HgJ`?t zGBTRbcu=jA1PkOM6&(Xx;|apiSpP-4w4@a*P*58;Ub9kJs4uFIu{<6>J~n>%lr3Vk z;V3`60PeH-!H;f;4ahregyg=iNLw6DuQaCZpamb0@EdRVxHKhg)=qE(m! zp+y9%u^70dPPJHlsD41+&kSzL>&kZF#xgGMWxp{E2b#5Lfk?rU09=i;%3&W&upSJH zOY8i3t4cQdB7aQBeM7~4fG3W}Wo_|Ae7jI#rGbZFb0Rt%hV z9%Bv2+8#*$WkA_p#Ip|LLJ|Z;1b%_6z3SvJhzz_2;J!yj%=VkO?lI`x7GfXc^CbC} z?t+xS-xNp+uG!EqT(go-&I{v)6-ZlS?03-C1Ctr@&n?6*M-!<)%4_+D0<=@eKEQNj>fs4vI_DsmN5aKlrc)8egSoe4NiP{qo{XY12xWiiU+-V?BcT+vtET zZXITvCZahgAHgi8Q$_4&Gyb?b@tggaGof9<)O=?V-1o$A!?4wm$ov`3h3asc6Z`4t z?sE0ONbInL=aqwXXt+o(?>8RzZjCoOTQntSxSu5<1{7A()8vHQ#Fez zkD6uhvbqR+z?U@m+Vt8 zFmTrchE-JxeGB5Iu)dtaWD|vQ02{*_YEGKvGq>feSHDGraTfr-#IaY%5wj3dfj3vF zr!m<%<<`8UcB02-jfxGAS>7Rm$ld9Q?+1bcWcKheti&_yF=$GNXm9?khMBC5)vU&4 zD8{(UcqK|nF3u`-$}GPUHTO%yRhw9;G-$w(n4E~M&!Ay^P?H&zN75d0!W%>}O6o>x*$t7?^`CIK?Oy|KLr$Z}jz@4@BLxCCUa zF|8kX99K+%d4CDyZ8fHyhxe?t1>tcpy6hTrT0!r7yBNWIB*vOyi#ym=a4%0c3Bmn| zoM1l04hs*3F#XgQ?w1h=ALldr{xl#mF}2>eZ=*kXpZ|2k)40DI?vpY?TL5hC9Dprp z9XAA_7{bFc0=-Wi`Y@b)%KVrz2IL(wf?KE#;)-Hi&^APJxDO3;ae$KbOiYOZNLIgD zi51X*EC}qMc#&!vg!W~TKA1&td1~@D6~=7mgYm@f%87X8ovo1Lm43#6;DxQ8E~sMb zELOe)xN%NDe+J=r|LU56d08)ivc=i2dB1K2;d`@@;sez^)WnANIv~S(_a#Bj( z(YoSJsKCbmv4>draw)vt+^KE`n*xKH+0xK`I$d3kRB7K&fh=$y8n(-y2d>ypH2p@u z4+B|s1G4r6l0UpGa(;JTa;175XtH&1w!P4p`8{^d; zt7)ZEMkIwV8Dx|($Q_n#WwrPX56#9-ZjqNU$8lK~HsGsQL)g~)vOe)e?m^dG0z$3z zoxaB?hoIT-3ZE za%0L^4*h*!`pumL$4O!MYtUk%c)k)0?+NzHPVq$sA!N^$o&s~k!K!{YBvWMCOPQDe zLOIp_ip1IyEwA`Z+65p3F1Jf7NWMKgkfnm(H6xc*VIq5gl~j3>8TO%hNvVEomSo*4 zZU?ddn|5`Z1AMAoP+ zKxd&}4<#2LFY{jbN>5b^LeD_2;a!il;VVI*%Zfk+YqI7R|97Cb4(6Bp44y&nnK&-5 za;6EltYEfDVnuQ%>+BG-JL>E<%zi>=U$3*TV)pK-lzbB3V+g+7!7TGTC)DVbzR0z+ zvG6V8hvrhobHO?)#a>4huJM_5Ab>A*kmQ$DAYZN9Pv$NxMQNQ;1LqpEj3Zvnmz)Tr z)!+imG-SewLT<>4tY!Y=$PYx8ddP^8+*=Ih*Q=?L`eKHV1b#Bx)!mZvdXk2_Sm0{a z)l&Lnyv|07#U1gFmE#2wl2ktOaJ$S>A~=A9`s@06M9I5=EG2_^?`=u-^8}3~_E>l+ z3-U$ExQ79j%s?Z?^AQe=P=RzZBQy0Z6=;o2Svqkt%NDpGC5ez}8j=k`x!D?WwhK~{ z2>I0%Dbu4N2WiMRU67JQ$hjJFgoYfgA?LUtC5e!K639s)OChv@vL|d9IAh|S0Jmy@ z*#LMG0NAsT#uDI70q_wZlDq#KvdCs-?E^q~DZ3G={Z9omeTpPdw%2JOdw3~36O>RD z1cdiI4kh*7ua z7>Kc0H~!a%@$AdG8dyhOlA?xfb57>^T36Jw^%xk++r)g(J7MvU8$a?~T^cfv_p zqBSuxZn^(giBX_Inj*&O8l)*=9KKH~YKj=23&;_Ou}o(sCdS{G8OeQjvnEDg>^qbA1RbpQO? z$oOo+uM%Uv25E{Ik7|&nh;fewX^I#F1>^|C$kCaJiP1?i%Vt5IdlzVXe!FWxgPgs- z@GK8J`FxQDz4&7;Ed`94E4poNUw}{umHj9^f4RJFS7Y%C!ujNtG*BZ65Swa-=vRAA zIx|DBj)#;Sc|WBBOx}mdCTzmD53n1(;X) zcd_rB!Z~tzWhdbDvzbJ7;X)0Pq(K(AK++wM69^K?oeiTciMgPbpXN@J*X`;Ryn>j| z%Bv9baRS7MS*~AgVh&3MF-s)rKPKjMa#v$w-qxleF_#7#0%~HO4oHWX-yN@s`4C`_ zjhN3$*G-C!7+Xt;XE2oc$GwSuTLP0%+qcvA$OsX>||=&c&0DT4MVNF;YR#uW*= zeWwugpYpn0ZNw`G`m?+WL8}N5Bj|knY7=xua}e|eNjesS;&zzW=$uDYy)i+rfuxBa zojb71i3bEhTN~3m0&)?E3OST}ArR;2tN`q>5%dG;x+VzPu9!qTf&krhFEg7QvhQn< zrYQWX25E}IGc-t36dp;CNbbCit%SmPlJNYr==w{8TeDZCe63J!(G;5a`i%=Oi=QFw=RT@w^OXG{|m zZZDZlQn=rMu4DjJ7fA+Si>)(2O*j@ zH(gWsAT-`%qi}0Yz#|J~|L7(t++8x8q;M+@(iDZa-7QSe6opr6kfta+n;?5&+UiUVlB7WvuupBfP*hvJRfB9{p1nwJ zXgcaIAcbpU+n8tjA~$cm#yi}5E%$h?#Wt@y7dQ6hx8I8{J{PQ~o{*k!=kGxN4||Z` zPFT~OwGLSyG3zH8@b0X)k+pzX8yaQ(1zFE9Ye}Q5Qe;hI*54Xt8D)s^03OS~iP_T{ zXZO|F1;~}$KFuQBx?C*rX^SA$u>=uo);mpdf*D!lKc#S)+ zesh&ow<*zcm38uGPI{GfbM$$YwIvE)Wqs{RUlUDVWp)4D`F54n?Fi3LMB%F}D_TyK z^_}Z^wd?ti>p9CV(`T-<(p}F_xysCs)>~!W>Vg^MdcMsCU+98=$gYd!4|Bm^Xu~u8 zXBUk7xswatdB!;e>vY$*-J|ucvevquLmQobtFj)7rdL^!=<_OTrt7&p`dno#b@h+? zd0{ktm9@b2JU78J+jXIhL&IkWH>Q`mV1Dbuc~Z2@D$98${DBRzcHL>iF#UU1`Vd!J zp0(2nQ)H*}d66qU#g*=U&UB?a&*bw?QQTHpr?~1}2V1)y3ssi;`Tc16Dr;2~w^de! z>v?Vzrpg-YDznnnKM%QZj<}w$IEv>1fN}4pJO14b_SD-4!lTmsdG8q^`i}U_Lw@sv z!kqe?&ub>mGJ32rW>iC`3xv;Idr$kMMW<=~?$P)3!elsPDVCr($k7*~Q+EF`%X!p* z@RHPB0F@B&ccWNu=@eeG%l&CYP#xC~A9=+~MdeZ9Gpp4NP>6A@MoMsHGJL6ud&7fj zJ=|;3Tj1fH-NxCEt$}?CzmfOwYxKZI=k<_iMvqGU5c{+QZVs!u6qt36cez|S7edX_ zj8<&Msd&b0enktdeLsc?MK|Mqiav%Flx84KL^ItCgfpkX%3C_AS5ooSXhKOppSeLz zq!th4UqI^%%XCbH0%KsE)swh!f4W|k7olO{mU2QKeUpvN`blH3pB}1%Oa(ywT4UKR zs|GKlW&sKDi&R(2M{p70X21K>zWB5_1UTHu$UJ^K29@dka?s6!k8iy?^Oop-BD`qe z8>8D#R&_QNwSSy1d|DuU7wC^mJ7ibWJcL4^u&jHxRZ`8}w*QUr!5h+nUDw=g^MP%a z9dh-l>P_?J~Bbe=7I{y>eoOFSz9ZHoRLQQdo;N$`5ibrxP?prs{(iU-l<3*lWww?-UNsxNM(uD=3hWLAK*rcJ9aj?f%|$tE<1?!wdR*-i-l~Yl= zxDHKjHbt%%>=j*n8D)2Ihy_>q5L(EdFCf1wph@J^N3ZLWI3f&zm9Aa}y(tkgd}bv) zoHI(=ned!sN;f=Uu?BI)V;kuUNqe4K*~4Hn1;K}-9~4eR z+^yqxY#m%xuesK`50@3h5v6*f{ozPYnmqR`-GF)kK(Vo&mWnanbrY) z`7Nd;&S;~Zv)6&V+Tsp8O;F0-<3`m(!`ZOh=YIhsqMV*6ho4ic(}gKRgdYoO^zmT* z@mTxgJs<0jsS4U3ua}XW@Z%Ho$Cuh4FR(wRZef4?*pWZ}>>5G)RQu!m?T@LD*dGr& z^2g8MV}E#VrjKr@@IA&IMuYI^t-@88D8S>7-~cNOYIG4FP2Y19rxc4m0<*`gZ+VE4 zXoNoF_9aNgxhf0W0PMnNSuxIujKE<5us)8WqnJUyFwX=a3Q-#CWB`lsAk5A<3CP1X zd>H1d_8=3xuby;(q`4|P2Y&9b^`#ioU*={Ue9s3hf&rMd-X%Q%Co&9Nl_^yRFfmKD z2$#WX5qt(tqw5DO>ZdQO9J|zq40!4r7`PBp!#;13L|(#&Ji-j)PkTOj zgo`fwqh_>0KJbX7qxImf^X&8lywinQFi9WKjJI$-x>r1Ezf!M%p{q*p)z+(7QJ+lm zXc1_p{w8P_+Mbj35;|U1Lm-1Il zqoj#Z867`9kXL6+`#?59i+QE;0TOu;$9_B<2!svoX|6rcrFFV(5duSB0-51XzE2&J zMkE{*%_NK64_Dvg^hao}`fL-sgy}r0&qFVfb|c{po3mFvJ91yW({iV+Krz07XgrM0 zDVfoRKH0bd($Hr)g2Ly+O;_5vo)V-{J7IJl3^>Q=e4pLU7e(B}+Ijqu+j-J3c8PAM z5&D!f6*>sKC81$BUXp)Odp;yjkoOV!We{$tOeR4wlfd&Ii^0k|c(Mj?-URc`12=%L z1Cc&cd5XnjESr?9E`faEjPx=_3KE*B-`fc<>4fI0tDW#75`4kcDFOJ0hvw+qB-K)K zi{J9)bS9m%M4aYd57AOqQPS3UI{-w3tCPzI zVEJ5~9LVdFiStBg%pe|k$g1=;XS;xY7hhfqO3Y*VaEZ2i-~(UQ_v$hBr(9Gn9bkmG zS~QmBs!2OFnQ>{npY6%`P#@Ucs&)*txk8>WH1h(h1Fb z!bX5Jr@ext>JP?4%#jOjQ6bW>v}8G8!==J+4n41+3xI{=u%0xXJm8Ge(m zBHjsyUvLO#hNDNhjk+QMGDO*oLpjW)O@oHX4tqbMZ11pdgcX-4Uk6~K3_l(RVs!4zhQNEdM z9A%8I37}*T^kjfJd!TRb*1cQ@b(bj5jiKCCG~k4caod%eXA;hS1DJ^`zwMHL__tPr zDqsO2A1^(U-MGOGL;Oh($;gi7UMZ zF7;xcz>!Eq=}|uOUAgJD5Mnl`o_F0Aw+>(EHG9b|LcHU)xIOM#ZF}LULbENd0j+Kp z+?H&Fz}dK7w$p{)@=m=hj2Rj|D1m?&%EjHGoOE@`Cm&nMrn}^cd~wc`txmRPB0x{< zy_q#J?!CEnhwGgJGwXYt{=zk{2L!PL5L%z>Cp6&~K83qyTA$I57uE0KRlf+t;p};X zNKBb^QZmie>K-mX!niwYG7g`jANx!(%6j0}>L{J6+wV1h#KlCoebw9$T!C|}DL5EZ zke^h5L!UbXk%HrKVDViGQ4*YXxZrtADBb>OfSGb3zp(~HQabXJh4P6f$y0iGFk%Iv zp(1IQdVs6ifVGA70vo?%c(G0l{mfNL59V-^Rpl&h zP_zn+kR(;iG%wR|7R?CZI<@-J3CRPD&~HFrObvf9%95jBa22Tf@(UxHhDj_*{f=qB zI2G|S(Ij;e)3!&`pt)f`i)kMTs;up0q#18tkz9Hp#|S-zm(l}0izfh+X2$d|ph^$) zHA2JXp|GSiu<37vamRMdhXT@!=wT5EuOvjHH@5`%Ey0HlH-o3BXF9~ey<pY6a6MlUeO_sO6@6Z9<++}3a6Mn|dLH3= zcEjB0O25hVJks@iv+Mc&<*~L@x}N8`p51MH#+5$F^<0K$Z6|NAzkx$_Q+F)D=-F+g zKR6tQih}SP!|)Sl;NZ-cQ(^RI_xY&y0GK~W;Fb@@&u*hbATzC`<0!9j*B+xs?mR#k zq4^m2us5YXh-(O#vw=pg43r{Kc)IaHV!hJ{#)v}0#2N;e>?DXSqsLmp_X5XG;lm*3 z!y@NlwDTYx6H3T=rfEvTnE~brKI6|QdmKWKcpa7?5=M_Y#H#^7IWj3W zB~{M<@$mIitH98hVMlP~vn-AIW^I8v`XJ8(7DR4H5z|3|i8wXtE*rMUyO4lE#NSLV zFf*`skOup^@8BpbA&TL)U65HcuB~?gVR)x{W-&W}7=3B<*jUoORL818Pj*F5`Vduz zs5Kwg){SKW0{#s0@B6|V{1yismjLl7%G*~aM7byt%8PB-qUBH~<1seJYlKrZ!mXDP zVie30#o(5anF!no^7Yu_#`jS`92LIrVa|%;dqE<6QO6xLbLvh8qXB&yX>?DgIA|{< z#o{{J>1RY`M?V|WPefI4;|D3HjBJ*q5Bis_#w@m&CZ>yx2g|`Nn3=9Xq=cM$b@pYP zs%q84qnmM51UV{Dd+Jw+Hp6!g55B)^zjHM3{cZc*9u}$3;hj^-9N_2DCabhI$uXBx zkwBk>xhg|P@>x zFSj=};H#i!;6=9LQ}6V(mMd001I(MTafh9{NUHZD5DtMd@S3z>_!Sfts4p4yrtzUU z9@_GurM*#SOn(CmWN+3P(`kf6xPZ(y^~NJK?eqdMfe8q`&1BZ#-_OX+>2<^?LkgGA1vbV8AZ}t8$p6uA{LDv`Dz3Y zv|j*qk}0)Dk8{^cN>`+KLVKZ@;lVm3T8>TlJC~F3jzsu22?)PWlzDW4FwVJ6et$Ax z8!}Ey{k@h*kVe>5MlIGjN%khOKF>AArcK3EvXPTqBhH!WnB+NBD$Uu${m(C zpICxT%xr6Um>pfO?2-<)ox(40$OYtZ>OFD zV8(TS4-kQH>Zy2zi|od9vUb@P`N>a0A|n0x5Lh7#CQOXu{mp!ND@txhV(~ZIn`jGjWlJCur3R-;=`rIg63P1`~;^7jiS8JhK zfz+5##S&fUpZ)Gn{vVBL4?})1E=F)NRpI1nKa9yCI)?bn{Of>-H44v&=a=in3%a8( ze=u-f4ai6gbtY&e|1YN}1J&9J?C!4_M2H`Ztklkc^;M^yj354~t9*JC{{w^7`qIr` z+$O@lz3wS2j1Jz>EU9#Cb+ zq*#B{B4rc$I1qlUPK3xayW}VL3uM9%;eGrJFhBNZec>~A4KTk$fB7p9AtZM=BI_6)+o;!832s3^JtLO zHo%yGf!o|H%q!_yzD$D*LZ~u?7lEJ%ByW{VC2ptCFpobCxLDWYc@{helJR1mkA0KP zY9Qo9K^TF5BJFm=RS2Uagb0=tGv}YG#Z18b0Fvgq02W?QIdIcr+f2xtDgZ;?{2M>~ zQ``D!QE?FlKmqj=iS;sH813%Vw0vxb5>dkPp$i{4sn5QZtk zoQDz4Ly_|^T0iLJm$S^`QiXq9*!lcGR2z1<)VC;vRTCjfO-UbkGY4no?jE9Yod$t_TJpwwT8#y9eJvxtWf&*729(9)uJ51CnjL#9#<)1l7wC<6zDj7DewFLAS1)7dDzhY~@ z8OpT@pDdXAeUYULc;e3kl&H-Oc@Lr>k~?s?%nUOwqMWN&wKvJkphwDMGEy4N3_WCQ zw|f+xI(laKo+7o;%#evx?f=ktUf2O??(0^5W2O z7B1t!8=*Dvi0UWSA6kQo#I>ag(xE6qxWDcy4vG24aOHPYV-B5?hQ2LoO5L zu@rruRG72V`bJ(udgEBLpGk03L5!DY%d68ipbb zc)x#>gfDw&zj~QM8~ox&W-5S zI9+@V5@42lJ9YGxdg9DR6Y!d6zrMqP9?tKJSLoX3;Rgrzd%;=(WzvJ6Ksdj@B%XQ! ze{i8l7IgJB&^Wpg=$v^O_`&fif7T}G%_Xe@c^?>|J7kuFI(;%8m@@4oRD(q|$l&2b z=&w8|D(SRE>`=y`<9sf(egqG|7B9GA3lGxFN|vnpb^RL`|*&F+QisPE0u;5J$gZsfg-`&t&dN}#F>93a_x0Vb^+HVhoL82 z#80YI`{9RwYFTfsCv=8dXKlfFp+1shms@$UE_b1fqx=<@9fJ1W_2gK&8~d@`Z78>e zF1L+S?kKz5WzZC@3HUzRKV0v4e38e5?;^rdY{QF~xuVOSZtVL=Zq5)+Zm4n&*Hw}H zsrXS(UmzIge6E^ZE0diRlqU>qgf7*h4RR1%E6jmCrpoQ9zU0IH=J3_|pbyzVD#rl> zGSgGk-k-2X0JtHU8aLfn@>Y&nY#q?3vpneKz~Rv4=)efwxXi=;tdAisG0mx=IGACN zr9k*ajwOHAdt`j86ABPLA1kv|f93vEG-nga2xNW0g~?ad{4oCwmfBz}rasI>^8iL5 z#-a5pL>uR0;)c;B8b9A->$7Z1zAhvyHMtBm2Ao6TmhE1j!9D~_I)=q5Twx&KI(Ewz zdhiX`XIs{SXJhNLf9C7;*{jI5O-_1!HVnNe?xPu8pJBIK+(%_dKf|KJsgp03^;vPh z*xGF6`9R0DHfxU3*#*}?A+g#==|;u}zZ+%Wputv4bf0To(~T>Z`x+Fq2-ry7?*O>w zHLhFiLF-z#?8$}jU5hVSLazoTj7JGp7+*V!njUi;$-LS+8PBfs12Or0BW+>YUgDe& zvL!RC{|Wmi6<`GXKE4LOagurg0CFluVFzW%`K<}^>{<=_@<#pp#uohICZWk6@V^a! zn6K=VFY&T`7r_dQ^ci&m-yt)TZx1GQWQ84ICddDeqY;WA%lSNw z&&;y-V>YXwU!@X*MFbR?5l$+)4)=gTPp`v14f|+x9d*djRMtnRO8b-X-UaB#q@cz= zs<0QB9%$@KGDFDgKvVhnaqX59aFnSNrSvX#?`muLY-B_Cc^LoGLjDAPTN=}M0bQ

-{@5e}q;%mN=xT{BEQj2x<2sgf0*`JJG#EGa8 zzFZpVK5b{?doC&jz9aP}6Y$l$Og6sGE|cBAv#~gj$M-d)MDg7;$HCXtzr!=r;`?`) z8{e1gPsY1Y^)8{c7&ZfL<&B79j4&@?4P$z9R0)hvLFiu@Zh9NfM))N($Hfriz~Au* z2ays*xLXwAcwR;*+gShl-1zQ&SvPUKSN3vTSljr2A%Aa0#hDxkWK}r z8-VFrH>M-e?XI3Z7qIb|<{>4D=?5=4tl;X|fH}U-=~x%0&)Kl!W!tkMqOLI}+oQnq zNhos;o}V_vGc3Fl6$$MC8;|FSNQvV4+bEu~9vyvz9zF1)O?z!~XduPJ?4ZY%SRR1q z1jt+Nhi+DPU!wOzH>(n|oXh5bHMshE6_gc3V1(@n*68DYCyJQ5|4OPbjV$oHzz|TB z*Pxkk1~QkFwnaZAk*KkKZMnIgzh1^o5wA-cxRNWa7M?xu)~sZK=OMB{h>&PB3OwONH;V6Ss7!D1DA(#~Ra zv@BL{24KU*>J>;EHOn^pgajL_B&r8V)$ZxdnJYrup{UrE8ckM;JLMZy`YO^yA6g`9S@8B3y^=Pu*a}qGs2~s@zS)cJVZN93cE#X(_+Z`}=d*}bHsrEJp zV8iy-il->*T}TBa%2!WvPw`jkO#zHu@5N2l`#A!;HmtWAX;MDqD|EshdsrVgeY@%> zWrR-FPrHmz2mOR?zLtC{FnUxNp@WD=%EvWE=tn%tUbe!6brv{e)GSVi@1sa$m!og3 zy=c6wyO4eu=_srMw6?PGpSrsnWTH!~S)ZZ|XHn7d>DZzo3(vY=V(W>2?Ph&^kDfQT zuV$E<_@Y>`^|bYBTTge4E7*FLdi3j3C>VIX%YGfGU(d2%H)HVQ(!nAu9(b-{ zx_*yLpUF!H{>~I5WI+ev>R?kQwhJP`Qi7RVCAv7xDsW7}#$|9e3xUc52LxQf7EFUi z99=Rny-VXIMRWo2f3SD}mqoSzCKnG}wWzU`oTMHpC$8bQ*b-n{K=njjqqFAdEZrJp z-GMBR&Pqp<@D*DoU%^vDbw!rrl_f(NGhiuDGRkn{lWaR2hPl2flqm}x&H-iXF`*aY zvWYU<;b25H$|~>yPRJW&4^m6f4i7snc3hHvnvFpiSsXR{^TP1 zMmpJu!9uIKNSmarOrV*Oz@yl{(Bc8VS}9jeLVkuCREu8FaYGA&4hW9&}bGP z#-kYtX7QN+gEKAK&S=!YQ}B;2ABbP>-}jX_xDD=Tlfa(dNMSu~#H;aat}Q^k`-&8= zS>>K|f1nA=)-$mUK)*pmxA*V+Qb+AyiT9|JSjT55q~ce2ErN(@N$!7lUx zbKRXlJDjT%I!Y(Ry7Dx4C$vMuxWbi=u+_!dg2+87NX&o|D=u=Q;Q`0Zml5i#zu5ht zeGOv@Q?|V>Xryh=_ye$so3zQgp+cluNp5OsXGDko0dq@S+q(j3SDOxlM_?xCPF9H$ z)N3P01+crcg)M{Ap>9WQuu_v08xa}!H$tU5tzl#1S2{Q$sTXFA7CJM=L+5Cq4RBb7 zZbiCvE}A6sNfg=mc4@wjapbjVmp5{W&~zuBNz=NzPrizD%MdmDCq16|+d>saG$U4O=(F(JjPoFSyZ{|Q#euP?-2dfB(d$7w0A zzJ_?=25KGVJ#4lA3E95hB14U`ZzWAj(s2GQ%!1v$oqFB=W|jV?v;Ky{)hK&Ye&-(F|)K-t2t?*je)c zO$+0G%*xzJZ_TnIsh6^laDMOZ_=z0f>0JC&r)D9Mf3Ugl@|mff@miJo8z!o!GPR-d zr?X)ttdi-!05f5vYX@Yr{3q@5|AIV}e>Rd){^#dN`EyxKb!saX6)S&lFP2}A|C7{( zcKHvp{GqP$e?&IR&$G*?f`;;2>+}^Em3$OD4$Z0$gjFg{>ql3; z+8;Sr%ErVX9V8MyYlT^zTqzBp^uxVUv0d1n(Oua3yfsGfCQMQ0nu4q?dUomVo?S>G zmnb?5puT;Zf?q>IK#CfnJAsQ2P9~5dH|5l-u2PO&MBJXV6e1i` ztkH=pWrU!^@ya-nwd%`9*`#PW`vO@%7BGr{jf_kLgV93`vB4HwRI?|`S#q&Oq+RNi z*yeKOWZ5dNUWmQmAtyrxi?kbvBxkGmIi39^vwx3l@fYED* zmDX=(#hy>Xb4>q;tsho2T0i*BgSY~&qH|Ib0#%sw-&_FH<8~tEAR(thT~*Q&bI)cU z4q#ozN5&oKJtWNtl_B4WPyxmBA2?U;Grytt-t!N0AXtkIpgZ_!BsX~~u%5XTx+qLZ z-!38>ZC1m*@Uj5-TnL#3*e8hce?vc6qwE^8;?z~d(Y3Scj2GTS8kV#7?bIb1dS<#2 zY4^c{ve6p1}|c_8*YGWxvQI>+^V0-mG(3DNbb&-{cgd}&Z$;<%~~OC4XhKXfph z9-O`(oh&gi0+AOox1fQzM3n59w>DtDkhzw<8@>ovUBc(C0#dD0&U$kl@9TW~e8XFQ ze%pe)6=NU+LYW%@SrtlQ30S?(mG=P1#S;9%!>PuM6MzWr^fW^4@xai$2qrwA#Hm-E zPSY&&Gf?vfe@LZ1oFdDytw@1a;DsoK3|j-u0(e8)r=>W6P#Mem=`0ke-jC+K1#J%( zUE%t4;2MOcTS7V$QF47}lsfB}(ClLyWch`h_dJOAX8 zP!6#!NFbv!otK6}uHv;9UXzWiP$n-uS6xm=VTf)L{)5_Eke-oR+=E%aAAAN-MVUqp`t66}5;7{DWc_0ZxU@eY4U#N3gJJhg)86-Q%J!~GN>sJQP zAa$>xmt7aHDP&byXTvcAEPe$>KQq$QC1*h8vqwfvCt1%_7bYcDOjw0QR|;eUTuQcs zDll4Xk@`Vq@K(r9Owr zfcc5{>mhj0OiT$85EM>$ix|}hdGFuH2}Q@qVfefO^Y!%c;#@s_oZ6eyN4+WmOEqYM zbrRYE|NO?xyrwhS@hi-{HUTrQNW{#SL2$U4*(hrzsQ>@Kyn{BlnD<`Hc|3k_JAYx^ z(acNflRq0YG^RHLTK@0@oYDP}=}Z$QwR;z)pL^=nSNNDLk}g>`wB)QhV$Q2a%$bE8 zVPGlJAO17zc5(7(8jWzNk7ms~UX{{NYK?=#N>n6LSMzwdke z$(=jL{IGK;IB`F zrmspGJ_FmF6ARX$I4eE{OYVSo(hAQ^VFi8~jEvw(BO)`OMfI#-UUKjSxHm3a;pIl$ zDC*+n?FujBkf!71mtQEnjQ9-O%)2C#=b>^8tQyW{ZI&5wm<|UYjqEIbKT;SCISWB_ zmL=4Jwf9viMgE+I8-xnQcah9G*&#{Wqvbnz0fi}TkD0LVVRm&PGEb^D^CX!WOAF{N zq1erQ7cx82z<(zA!&9|zxfWjLhC!{R)=Kxa$TBB7#br_l_qE7+P0Q9_3op|0baCTl z@o%*x50bR6`BuG;cic|7gn-vaQV@(H)5OXi1px{(+-g?cK*5A-3IMfzB2WTmdFjJBsT_qG2XR8jv<*)tHGG*+dmxocnOCS%B73(rQ?V1OBH+c4ov%eF_eZ7y#)e3BRPCQqQ%B)s#-0l~=%OBH*V z!DTiF(c-z+&*Yk3&<|1v(TS0`_SA@1qOB+YQQ|UaB%}SNq%_`LOIcj4R=%gD#77B`b3v^j^qf$}lM4V? zsybLUOYvHgc&s&J0Uk~e_IdRQ$)3Sfd?C=}HQ<1@U_9)@PNK36A>$&b}2wUA`v2>ujpVUJdQ%0&L!J&@8ZNtDX-?ggLSor z#@t3$BaaJ^#%RO_1ejfY-a3Xo7)Djj{+TJ%|AKAeth5aXr|CKEffUdOw_hq6v~jHc z6ARR8d&NiU`7S;U?c#J5G(J*Kv9BC7#X03ZiWg}?IRG!ou$1`qp4@zJK-^PCGF-3~ z?w6&8FCDkBL>XS2NP*v+J^l=HOe91%k_r4fDTvCABJdTTEmPT~d_18Wz&s~XmWaFU zL%Hb^%PI6!%^$zPGky<&D!&rW?bKVy2y0eEJ$#uE^rwyi8RpdJ>8udILys8bk72H5 z{4qR>0W{7qx2NdZlMEBX_+wb8pbQhW_+vb!b^aKZ7;1+dWMX_IhmQXYH)R+4;#?3=^ruf!t~`OG@BYJt*@MnOV_|ja0PzU0j!T zzwYaRxvja%mZL=nb3F~Z!=+_ZSOoHT8YIGtY*bhS6+ZtT5IL_U)&~snEc+b=}4hEb=G_4VmKdy?j^9I|;0}3a&@gm6up&64G!dQ(l z1}hZ>g`XlPxc`|*gxW&Z#RZv9CX{Cye4f6FQ@QaD;Mf zN~SfiHzh}A00*87sTJahSpo(W7Je<{?@jwX{TJ-_^b0%Qy)KXW_F(75H|JA03VS4y zc9OYL;B#d9t85qPsvTYs3jx(>2-Aax8p%d|VV|%nZB23d!J?v;oKd)6O9X3ETi%I` z3nmC*oNPs`cY`L**?QP-Q8dIl05Vqc9a)2H&5Vm5A?aD-g2;P}guijl@5B=Cb_nBJ zLAGM#yWG!j7sc>g<1+y=2=Mb;Fjx39phwm{iqEp!#1{U562!<5%Y;-R&ceJpl-c`n ze>hPKkI=%my5SOQ9K!#wpV&aKb3b9|`w7?%Fob&k+mTeF7O8J zz_~l34Byp;d96B;bfMf_;Ds1k843(U?w<_vWOgx9NjC{&;E%hQ&g^Gw;4bF-=hZIe zoWNZSc}Fba;qGQu0Fw+KHZD}%Wss;_{REQELEX^Yv2^Z^90P)1UTwT2eMgjXYH>C` zJ3Jh;5#Jx%pS)kCsPF9TZpA^d3Il)wbj}?M==hYFK)0K_p+eBa1eY7h4iYfGhbS@O z4R#Rl8x8Xb#hGPjq9$=>mo=I_wAX*m$Eoj+&XmOi_8j;U%jw!5c?4~ z{R#F5*jZHBA0W=Z9!Pt7nOK{}@hjoY-oN}oS2=C}Qqd!HXO;a+JIE;3gWCQD%K^@3 zLCUuT{_uNDazB$L>;K37$M(Of_IC~9{Qa%E|4?^r&%t2?uC-6!DTNNv=yfSbh!Im2 ziT-v8Y+-T@AS3TAYBx|Ctypn1QiWo~9vOld49aph44(X^q(7YT#Ut4(G!e+&$ar(G zk?D#hVNQ|iL%7|C*h^I(#D4$|U?XILxG(NfbeK7Yua36CnzKd~T`^d7zt3x`=tn3@ z4$}hNCsjU?km~0g~G? z`35A5ul~ZHPw{6G_E)bA@Nd6%A&i{Ay^NgW(2jT-nH;t86;9G9(#RbfekL=ON+}1%(KVh{ zxRHLs3lK+Ayvto1^GY!hvzp=qwZU>6X5{{jOLG5|0?e*3!+cuG(~dT~mk)lu@x}B| ziGhI-MuHFR%^rM?P!wiki<&985P0$@f}_JA*E0+jIj$n9ykPo6sZvTY`$jIV9Rmwd z9T?teMTN9M!5wbzD4!bthbJ#eN-Lx60=}DY9MFftymG zKr&L}4|wukLkolqH^uh;$~ORVyBc(=ZzS5M@SFP==3U1>td3%m5t0RlGc-C8J!jZ{HUL2;GZ zN{?c@NLTInx5~01d#kL%VR@_yC}5x}{+xcWs94W^55Pi#*A|M=AU7@)hz;5*Ct^C_ zCH)u{N@xr$e(uTMKZ87bgn&E=Ve4jWqh0@|OyHHTYc$N9osVF2ptN%K16oOdJcI9Y zRw%IT7Bh|!07L~_;<3VIT_HJ-om+XWVLpgc1+5Wd_%4jL&A?@%T+)nERXdTG;Yv{= z6Vz%AX9Hit1kQ*V_uFKy9~GgPB=`o(srNls3QH|?A@DBAIv=}Kd};FbCHp-6BA&-* z9rk(JF7S?H4q3uCj$i%3M>m=vQz0^iWvNVsUYXK<6Gtpw26(OSArZ^{XK|E7wlnZ< zJ%c}v9cjBIKZ5LCNo#Nhz|`Qd0+V7$elU@W@#TRO^Pw>DI9Ln6aV6ozjMfe;+|=X7 z|B-p+e$Oc7(V`gL!=N<9T^;TV25L18l1C;hV)w42$8!?Q-5|hMFjL;r+@s-RdK_F> z8?OF%hbvPv&sUQrQz>Zh9=x&+AU4J4p*69o>?0fxm!x?6hA*y-&kA88We49w2l*n0 zVUEQbu^nd~L%q1vq<0uXy+iS530&`tR)^tC8M-I8{4g%_dvFGxaGhG0E3dt8pX#mM z37%6GJ50}4sjp}mL+kN{>QvyuQLi=|GMi+`l23IDXh*JCE^Ad~Qx*^Ay> zWy@*#r(E%H*h+pkg^Z^h$iW{L8rH=pR|@G>Rf>REC{fwJ;(78j&^k37A?PI)u4$}? zFZ{{#SzJqqYP=7R?r>j7vk?SKE-B$097+)D_(O}#%V!LqqLfY#VB5@yO^nSQ90$&S6{%4!;-)pz$X?&u-vX<`WQ^<9T{H!knB{%v0l(+=yi?U`it7VB_w4 z22-+Es3{rOMomdmPKh;Kt#b+^@|iCl#Dq0wsKSB#6E^q@fDq8&R8E^2chp2hId+4Q zc7rjp!9!ewT>F}}|31j>#I^}{BfYK4_NGa5ylG^4z$RVRQ%6a)(7aB&i;K=&>DtN2baLSgW^%-5`9kt}a0jY3;XlK+ z4HNgo5%qJ}Hh$!FllUaO_%So2O=kjr9H~J*ok&&mXxg}#RU|&9RMDfk7X!{R5?7KL zP(ilC_#jM@QK~56J zKZo-=B>_dclO@ekZYN|?Ar&DH9Uq@YHeOm5BLylh7ueF^7AJDSL}*+bU`gw>y~A)p zbkiT?Aai9K?F(^)G1-$`j?I}TFAG~e4pDa05%i;wUCLh9VO(s&5GyK=$xxywvO}H4 zH!`HGSQ;bw533xvi1?K3E!Wg0${$o6Zyg}#SNSVbk5vx9`Tc=>Zh3djPEkX4o3;3Xv_RHlUa2mDF(4Im77#eJR)h>E)e_3aH_( zrZLw8s1!Wf)^JydbE-BXy?`o!n&HXzsY!YQVX3nRJ?A+zLWdx>DjL>tP8t`0fVt4c z(h(BR_uysh;8j(+JGz}nrKp4KjiiynkJ&lyKWja?>*dDh4@&p0etWp`|4|rDa^$S> zXP8;_u(S|s;s3*(U4Xut+2H?kmS@5M!U$D5UuBzA0H*ytIZV|8`~(?K0mv@!Gi1Mu zHKk3KQTAH%a%P=*T`=H?mkOAzFO$8b60@ne|c8h;EE6P<9l z7M4h8=W&pU`J>(M6{e!g3 zO0!*2W9G#&vmyGth62qst@|?3Nb_0_YZu_lXnDT3hv)Fj?Z#=Um~Ar1O0P)gx~d`YKj{Sim&K^=V~)zMy+eXO1RjruBk zKV;vrQmo#l=r$YZ<+5$5CXR+9j<{A-mrONr7?Y!sES^Ob;wk*m#$!g@bDdvb{2jt5 z^2K-*x%oHLXhvMmWcz&EYbx1fat9Ir2-9^_&)-qJ?K@;YnKf0WJKB7LIho zCDvRwTx6|4*x!HlAV3}xV6v1LVgn=}>UbdeD5o2_(qXk<0!Y#Wh6@Z2G*Q&xmJTbt zScJVQg!guPB5=5<{Xxno!@!2$W9<;~DRaz{Evagdb>Z#^2u*p>g@{h|Wk6cMcY(nU zrsJJI-U|x#@7s2BsgMG^PuG@hBNw@(%Jmp>g;t6p;4*6cahKW>47bzS-`VUh%8a(- z7$#Qmht8p1wP>RF6uWqilZ>ndPB^zPky!}_WIew^wKU0}44G2#b;?FBGaEsKt)e)f z_C6DKqKxmpaMU{8DdxK%6<%}iF*g9^){ws`t1gvl`7u%t4IxZvzpo_HOYL_kLY}YA zfO3rkO!Y!d0&+rdzvqeG(c$fvwqH#RI3>z()(&FJ;1dD_Ta)^IkeS_=Z~#N;@F5C| zDHJxjnnCw=4@7lv$06`CM-}AyN~l9YvT**OqQi>DR-9e6)Lcu(d{kED-^VM>HIw*5 zv8F6$n2=0)G%5;joFG2=W4Ajq&U_3KuR0CYnbIz6;D}@F0(uC!@Ghnd7L1raDy7j4CWK&|hw2~a7R&1k;M5qohif3s+h+2Ul6rVPS-)_<^6 z+VhrT_B@8mT)5?rM@uQWesow1N3l_Xr{O5MEQb!ymGnA zc|6EptpMpf|I!=y0X~w!>}K3RWTRtaDWc^@K9Pe8JQg#Ai@CSRFo!2924WwJku72u zV91tni9neFHv)MwW))nf;YSAL-xoHcoh+RtQ_V3^hWFYin)$KnJzfBa~L4yR8+-LEeC4Hs@j8NyTn?IN4zam%1p~73VBa?dX*FGEd%2l;e3e zIGRaLU>}4~9%nOdArQV$B>~PDj?BBA+5-t;z-he9;%xr8p-JSW1U5K8dsQKE(@zI0 z<&_4!IEguB$GHD*EF+Y{Lb}9JqY{Pe>}q~ruwX?+T-jnpNrln^#E9?gP-pSE4B_+# zdI}b$v|FD1d{#Ve5wS9mMLBjZ-seyz`p8LF7N^h;$2LRIa1;Tp zYw$h;JFIVn78{3t$=!x)uGRq+Tt~MDga0+N1h4v6RMLTjS_p-}k=#4<4+)X%ADJyt#6 ztR#cBiOmrXTq65(JxMVyItP8H7C@@pgAM_0$MPT#0d04c0O>&f7#FLt{BhR!gOghX zBox*kB3>eI4%pMn$;~~C4_Q$MHzz`thnLlIf&*Q2GUgkI1 zv1(g+vL=ibPSNCnw_-w+Eo#y;b zBsJp-uO>XpgptjSdzqL{CptWv9t*_>TF@0P9O7O`YSs|$_qVBHUc1<*$j0pVpxBNQ zv30GY&;kJ8l_9h4fw0mM&ST=%4M;X4KJ4V*yoYo~`)0zS2a!DaN11Fg+1|WwK^V!U zOwM95@G!7)Y75rGV@wk+zTnUeyT3$g;aj7<#$jw{;pJz68IP@WG*qy_np8!QUJ)cl=ubQ9hLJYD?=V#otvt3L;Mh=~8 z!yhY&=2N92ZjR)dW?V~BhB_lUOZ7|c-TrTAh&ga~|Ig6^I5CXG&#xg?P6Of@d_9t@ zu>=cbBH}6fP1{I0@{9YCo@^_4>A>$(O0m&eNnU`-=8h;EsOOjhjQF*l@#n~G7%yaq&x}s@=ms-2>!z4?9}=*!HPcfguih>}S$;&aC5e#bj;aqm?eD#05sjIHa*n}`-t z%jod6V<`HAB1N+P6D zmp)^M#2a#76j#SCxfP6tj*jR|8k-;>io}Ir>?yt}95^r`#rLHI6fCh##o$s|fMjcv zhuFOa%tLv6UrN+76OI7{bDoeR+AJ!1BM$h~_W(XgM0%9_H(XsKW+22qO_MR1*yfuF zgQ0a1ZRM)P3lGeMNJd;BBbs&H6ajd)xRFOreN%GK0M!W4&6kO#aD+tMbS-Wl+*b1o zF$VFWN-PXcT*Aa>RbqK?BEQBW9#n}TfQ{3Xtd^f>5q(r*RB&QB6FaL!PHaF)!Ndzx zVn%QxKj|WlFOfsZ2~Ol^Uc?q8${z4DFZg8abmRh7@@`CV029&vAUE;f;!b=O8vF`E zn`lI?vsLZi!o}ZP7=je>rwq`F{D%yw)ycc6(t<`9aNgXDHERrz-jTt z;>aqgh0N~-2@v<3zKP_Nt0e_MmxVZo2yp+XED1l_`yh&n1*%-$K)hJ|$TZhw&`t&> z%b4A%XQ!UA?PJ>;@$mfn6yhIJ-b0GbN0Me!b0j@zJLBA>$OQXw1_v;;QD-T|>Sn9LXWJ^QHPRS&1P?~A|$*ITx0zOs{T2Q z_9g6CC+lCtW=g_dVO9S6C*XB)*t3ij*W2~K3BtCLo%-ios%CR;tiq4qASkf0srLf7 zn*d=)&*)REdrtcfoi2~XKO;WUlRpU6u98Gft+5kFmsUs^J+-dhMn6`)&09KXcn~=Pc$-9?V zmwXM9XEAvtl0}zg)#afm{WSB;WS%C-BO35eeg3I~KaNlxhR;zuD#zMxxY+9KhKsCD zZn)S=(8Ar^aFKO^7G89NQ)h|QR*N^Z@Q+&fb1huxhKsGuZaqa-i5p*J`STZBQ{DJt zYmOHF*bNt1ZMAyz_{WiFl6IN{dSHU059Yr0J;bAJH0`B$kMn3pFY}#re2d{$!<;sn z_%UwhaFC$k{qAK>vA0aK_w`uPzOW>J7UD^BCHWsBg!xD4J%qp*L&V$Hpiu5kcnlvR z8!=@{s%f$i)}>Ta7E1M+@>|MY+>@7|jU>aHpM%G}u+QUibHn!?yOQKB?uQz35FALQ zCj@)>BDI;m#nj>L@)W!ci8a;yE)BV$Q|~jJxDBO7r8o~=QGTSN+p04$BHZY=UA)k{ zj>PImm!FA@C=%BaMMPUL2kezuZc8_}+?oDzci82wRprEApmxAB1GvaSANmWeDs>xc zX%{-%F0@z`ntit<=6?WXKU4`w$Y~%%eG+E(LZ@nj?59-o-3@RgH+&|6N7d(-UxkHu z^CwA&mZje=`k+CddPdseyw z>|qyZXBXIpT@#>k{mlw0FZv68>n{{(7dpI5wK7W;`e@k6K;>FgSrsY{OcW#}=1l}g z$4uM6SPay9`O7eTgmqEU?ZE1!J48I1o3Y{s4ISzEiWZ zSv0ss0r|*MM$2MOs=rMCxH{<53_1C}FG(zN3+gSQ(W@ z&hfRRPboXu%eyQtdUl72> zN$CV|Kd}LVu_V#Mkhnpc+lEN2pq1-!)Na$}n=4#wI+Ug$Q-;g46m5QoB4QHiv9Yj+ zzudk4a`WwS@2YZQ5G8VKNK|_w(qAafU+5{j(1UiN)~e88yU?aCZVyBJh5Fcq66`_; zuxMjE7_ayM1#BMk`jwo#j}(h5F%+E>OE~oB@eya{pCgN^?@RfM4na|DIasH^m>6i6 znLruAjQdO;o-7lc{N>tKTdt*D?nYHE-!4}f?{@Xi4%M}{`zqDPCaPRtRjy`!h4~E; z@3U4gs$MvP0oJcLmra=Wx@cm)8w0_dys9qtZNQd+g9wcef3R`odCJ$gQUYg3$ya-$ zQX5gmg2&hZ{sA9uVX3bcD-Lo$N~2JbU8uRgP_nm!yV^Fa@z?Z=f?E&uUr3SdRSPjsmJY~k! zvI}+d7rM(|XtrHwx?Lz;721fiv;<{cf1%6$g>vme_o+f4)A_wXa~Gnljo7O?v4?Wi zSj?a~BNl5ddgGH7Zx^!=YcsMGFK)~@!Ve{wvv|R_MCF6xcv%>_uw5*M(8jLJqx{GD zlkW#@<_j@=D86?~uG_323_F5(v+jiBaGkZZ-`Iyuh4~RIkV)0Bha}pWrElKJtUYG<_&&6#YUdS7ZM6}(r3-OeT zLpfVj9N0$b*_Q&_+piwxm7G_++3-xdK>7MC(ae3DWM7AFxFe~5(txCaNrMK!L>yOf znM5`5q524^8>2Z-hs5B)3I^W{B-{^)_S=-m@BRLux+;9f^T_>{UDuU? zbv>f$GVQt=+jWgZT{}KQu@QE$V{rjp$Wp~_vx{xU5gImq6^dEeYT4*ums}WF@>x~# zLc8SKcFAJ{P_mmUdAOw-c0pjt@v7w3OVzONwM#B!$=WRGn??>gXPU}42l2+!8yzt_qx)8e;k@msX`Kecen z?plAe@Bl45S_?mIhuKe`7XO+SKTV6Dqs4!t#jn%i*J|-Xi{Gxr*S^--O%+*ZXyGVVwgs^3a~s2Oo)+$<<;l>(k89ycc9>&)R*QdE3;$3U z@C0ircF(6c06$nWE#te9_wZV$k%IwzeBQ}4;H+ar;hBbKqT%yRg1|A%I~g#fc5?H%bzDb$Q6*#B=y9#^JGx6FX!hGDbySiF;zxMh+d!dv3;yt9&Q@T~GIxJg z4gM^Y_=DTofkH-Z`7t6D{AzNypK&VKlz9_TXdHT20}35dDAb@D6xyRusKJR)NMR4~ z=m!mje#bI&iYPRbMQs$4NRc#$h-9Ns(zgpb7YP$dZTWF(NqHL4jYSCsu}Lg5|L&n^bKZlaMr97l8Z+3TJw*;O z%_hU7Z`9jpc*E`n?SUvwV>Iq=jWx#YJ|6K`LqugbV(%^ z8t*~O;IZkmX&lXv%Dj1>$@l;+HzMSCtzWvatFR-dHs0v>%&ZVttm?!e{Le6|s z^c$)YH0NmrldJf64l$@VT_H!IOH{2mC?FXz7;w`R0E@^#=XS7Q4G~7Ov_m@c#*7`4 zIdtTpOk@6oBgYIHHEh@z8x<6L)OhhXLo>;VF;6zEyg-S0BL6 zk(|BodUEzI059$|Y|PM1&bo@a8WWnG7C7nl1Y-)my zDzE+YU}es?@&h|rcVbRMr9!g;ZVoijhKMz-xC_~v>V*$t8Ayz~x+M9jJh7xDH>VY1 z&pbjC!hmZC@Z_uSc<;>df8@HzwwJ`cE|r6_1=@PV1J$-5lZK&%9aCvP;({8p2x39G z_0C~@-$HxecobF;q{aL=n?1JLBVB)|PmtJ&VcO;ZIWN|VtNqgF7A^dd7T&Fe8+G;P zkJZAxv~Y?RzSAF84Zg2cHYzxA9uiL|e~sH&h_Pw1mpX?B@k=eD6S<^j)-k*?V3;#y zG`)^@i}KeiVVKJ9YWtKW8S=Fq2{AGkUn0s|3B537vAl~Qi>XhZ*S`-N#xa`x5^lwl z&;ww|&F66=Rw0Yy`&Hb9S#yd2dY}`M8#aOZVA?I*KyDWY;J?P_$aUCC!Baw2p`03A zKj!JOUU*D={V@?Kmr|y2buQ&fjz|W8c`_OszQHrue^0>{$Q-J(pWM&QtmOXqN^cA( zzE}M2%r2?k1Md3I!xn~fPU0GrG;mJBy~?K>8cvDdm9;U|`#FoF6LLklIyVt-vJ(sd ztc*@IXGZaj(1o|oZc(NndZi8Ea`hT5Vfz+@6baid2&nERW&yVMqHD>l(uHfkrV_4V za7zW!T`oxHHv&knhk28rd=svAe4fAdWI#IPBl0R=y6pW6z3pzBpL0PJbrzr{^Yi{H z79TnLsOZ@$fAVZ4fWC7hfu7k@>+j1qss4W2LiP6y6hg;<0v`7F)il-L zeZ5qF@BNYc_6o5O+!N|Qe5Y3c>Qd(SDJiu4DZ6+@=zultNt+RE@bM~eV+8+kOR-i+(N8_NZz&2)Bk%IdlR4(VxAbh zFLG+l2v@oLZ$rr~^845m>7Ro9e}5mr;+veT>ESFL#r9Fd&&abuKf7;3B zAENR{EIY~imjem@oBBJd{EyrHVXx75Pro%B4d0rg|7+0yRp@`IXW~xM9_F|HK1?D^ z3v}Jm*!bm;`r++Rh}Zy54wV_tYvS11TQKlj#rRVNpFeG^@Z-5l6@DCb@wuV_@Z*si z6@IL~LE*>ss}+8{IUD9>FBCt)^ikKYFUhWNrCZdD>?d%^_r5)p>+R47K+BQ704bVUh3}wesg@-kzTiuC6 zlWHt)&B5fKD80i!q<;WlvpiQC^8M$@_sxWvi=dUn1cBxLE{@~N157&;G+{+R-a&qu zxtK&?COpB++`u#Qf*6%~;}6JuHiad~SN{4tsQPcvi@b*Vcf6+Z$$CesdRyw9xCiy_ zct?zX&y}>S&#v?fO-r@#A6huHqd!kGEu5@{Bed{9Eu61~AJD=fTKGjR+*%7igs@+} zp==m%-Z_LqNN)XTu)m!Y!2?9E!{?J9x_(JO%dXEI1^=8IT?imM_b^N`z?O19q)cNc zbVn-I$FC!ia4!;gSSu1-Lt1?*#C3NbLDXDz0vbs<$es$p8$OZ+2-YUUgZs{zpBD?>$W7o}moef&M&5D0)xwj}s%AcO6C&0@>ObBI3Sc+|F5)JMz@kBi_x_ z2Xb#Ch74AnjKWyB1B;X+Q6q51S)bzsHWv&)US54!AwF8iG340?`D9&9MK-p2%r~05 zM{F%4#W032njfC#Xez{2sDYz_G)lNn^l-nrT~uC(70JYqWbG({&+g)Uo0Nx;j&QoT zfK{1sl|9uW_A|b?jdl1iU%^^440sC@>MR(W^bH9S4X0uSk>Z5RiU=?tlSG9BPwHe9Qeq= zEBFKghwzBh;UVgNbrf5)NK6Y(vd$_G4Zo|i$OL2UcFo;}L6$Te}Rxns}yMn>;4s?dA5RKNV_pYEH zjRxLH1`PNuZY2ugbq&2hRN0>J(F!Kk19 z;%Ptb#a~^c1mDt#E+N%p{=st`7oG zzfO0=ZA6@o`u*-W0qUPm)SuYbMg0#;*$7d8Jl9Py@kivdQas277Tx%1f-?i%zd3%Y!_Ln?W_q&pr^rSA{`u}(JYDi5p#bE5Aj@)8r|Q4KoI8lm+e)D`Hwt*S}^~D@2kS#vJMIc zD|;&#tZ%C@zd1MsVRGF>JpGveX*Xc`{&xc~KmHoTl_5^Y{6Xm_!2FAe`DSky^FLd` zMu_sDkd&HBb$)GTjlEipfX z-34S;KX|H`-$Dn6IR7Jw`HdH@C+7FA5%ceq?Nx{QInSOJ%)fX^RT#9pLcw6|%?bv; zv{IPg0-S;<*DDWCKjwdpqqgG6+X0y0w=3edAx_8qp?yw(`Di0Vyl}IN`Lma?5n}!` z?6=~(8(c^^muXtv--5;+v zc$pU7t%dho>Xa?E{?fubv^?Y7aFG>jhj%=0TfeMEZfdc$Kns^>;cK+;KrP(U4qG@m zWSi59t%goyTP@Pf39-w~xm@e;YAsyqhKsDY7HWX7$6Djvri-j*TD&tTtDn1>FUQ0DH>n%M`ic`|GW34s)bp0Q7ID~Kiq;=SPe*pL zN9d=xabC<-`fYhBfOO}V`l-%h)gp8a4edd#;_d0= z^oPV$`K%O^@gx-$m#on;+U^CKFxu2FqhHPPvHq0yL@I#ebw8K`^Sxu zoy{Sqz2+Y>;~^;J#97dNU-CrYkH>pDlKM&yi}FlOI2T#vleS5=C? zi#Vn{b$OH0eMN~Sud7w85KpzPeZ>$)caa=jrI>&kI67Vtho0Syp0VPa&f+?j8l7pF zy>ZF1{2ELubUWFi&va)U8zJstWpK*qsF-!@d*u?=Q@)mwBTq*^iHecr$x;i1xy(VN zqrY+%6Ps^RH_#FHHrf_S%<{{~yaxXrO`WU95~*)vBcB>Qg5!b{THN|8>xQ5}4l?tX zzZA@Tv3T(w%5z^tzmF)48_LYd6I^+YJ%akGCsZT0ffz#^!IxRgjy_M4#lEn=-YPX% zv{x~SJ!95FJjG4($<|qsRANnM+#M|yTR$TOGXs#h9cxr3fb>96P` z=Ku^#oUOmI0pUQ8UKKV>enbmwJ%>-k72rwOh`6`xjs0kRGBxbi6`apQXm%!aq=qlz z#pmSrQMs>z;gA8Ug%XP2UI>F;SPxWK6=IIBfC7`} z`8<096u1muZK?ZO!VWi@R~2+oEfnaMT&F-++MFw5rD(cPy(a>D9o~Ymeb62>w)0iu zxP9S_8MpQ?(AWmV5yqe)=)Mk#bTR}0QJN}(iE2H2GvPXyqGlGd5iY;urYbTTE1!qN z19);qH$FrbQ7Mv8h(t795z!-PnnZL~9S{*JfXAXvNx-pearQJn8C}Ba%(yc#3L?g@ z!z3A1szb3ZR{U!+`U&IHQAKW#MA#cr73`AHBs8m&5w*aJ#ZBl_AQ|<_{U4A~_}r?v z(CAWy3v+v@xnBhB2B7u21W$$da_GMyqfLZKb!4>rb(@SbNk#?B95Nb06{RoYre|s( zqn7LrG}Yt(OENkx@A?mBJpTn5t(a34bQ>>Lpc|L0KcaIMbkRXR4~fQ~~BQ8Vf{eT~C?!DKW!ItO)$GHJAnoAu;>Nk(5k#mWB{WHbSmvEYUL`HK|j zx+E#kbw5v$(No{5_s@X88p&MP24pmFasU}+GwyoC>14D_5=jlK(KdqNFg`3{%XiH{ z--?X(Pf=vFLp~3QU-2Xv-7s2_(dQ_{)u@=BG-lkL@Qx!HJr<%=6Sy1*OOh1kP_Fb@x{s;6m_{*wDGV(%&B#p08NYM=T767fi4Yae- zGa3US8ij*dMv<4QcGh!sbB;$D&Mn7H%lc;1n zhX-M$`sh)q($j>zrnXbul28?UL)YJO{1(;(A3NW={m;+#9 zIH8bs4!~f3ih%ip%~uDQ_Ag7oG~T#SDLON&1&n7h5j_j-t1k0QHLII0N2O$c&sT&Q zrp#~zVdl`c00mE1Bic@OK`2Gs_As^ugC*g71(t32el4kYS0f3Qi(?d6Hupbeuu(Ui+f#rv*66h|nwE$n;_e=n54Kc6sfmKx4&gCr(nl_DT6X zBp$|--6*?P@!IQ9NaM9pdz8o$i4W@072@Q0ZLR10ytWA&Fys1TT%?Zmu&RUm?T_Yb z+36Ev_7X=h{RMdXx70@_W87vKkMjOAukDJiIeY|t11stB@c)3<9{8jxl7ybCkmUV% zg%qDQkhD`Qp@j2a{Z5&7_SHl?n_rN$(_+Fr($0|R6Y$zgW%IqO;k8K*1@l@zqnOT? z{~KQWGi+MHOhq(SfSJ@;0p?}+y8xT!%Hzcq!V4?lDe~I=H36phc?p8 z*VaY*CuS=Dp4S$`$Q2BhRgDx_#&%L*83(s0faS|e6p=j$`~4|`<g${SYVhAqyBwnd2a

Pzc^~k zGDjmvX&{F<0L`m>QWE8tX96{tN0~)qw^UPyi>IE&(9MX8WJ8BwmDLlGB_Ux2I{$n+Pr7xWRz*ZtEzb06qRSbrS zBl0g2Q*SvDS2>|f>p(3KNBq!}LT!J19yu6ShINL_TvB@G&M z+rn$p0gz2w7!WnJUt6fu`LU#OS8o=f?U?yOYjx%(F$-ZZ}+P&9lQhephDLV$0N0!|FMuimiHD z_);y;y2?Jl+i#TR&;xj#_x77G7(I15CTsWiY(O)&{NMuXX*MU#-P& z*TVC)JiWB|ceVI9E&dfZTx5N0hiMT0%nn$68r#a*-9Ig}>HnOSit!-V&`%PAz9f*d1wZ2c){my4ZxqE3?M|kKXFF(tqG#DJR!0Q>*`D1w*q%+2Q}*maN#kW=Ij%OP zG(_90W6y4JF2tX69#tZdOt_J`&A4Z`LT!HZ5ePImRFO!t5Die+&%x7+Chl@ZA&K@y z`@99Y9-Zv5f~Bmr?b+a#k3}cay@VNs1xFFuvw7bzZt#LukLNAYMCd!{8fp!}Q9|+K zIEqn~V!3=)h(&l(jB4ATV$^mq8I^F$`uTaRq*8Pw1A_P>&qqkR_6XXs$=0N|Jd%{x zy!|~ibOfxDxiKhS4f6RwKVUHQW;~5M=t)0J5Ldbd;J5*C(!7tN%Dm6f#fqXU)Tq+r zsFY*6{mEc^F?gO}LD#J|TtDRTjI(EO$a(g?>hgF-XR$FyNsz1Lvr;U@lS6OMV+8g% zFbk^NPouKDLMK|rdGhSL;0*Ma4H`QrTiO5syH2Dzd<3pMmKsNBg;Z5ZV;!M#xah++ z&A52`=wK6A93f10;48cu>Bqz}Q4}jVr;bDkT>;lPA^{uB;Zu3a<6_f5AN?szqu-O- zxM$)NN@BjWg%3wdr8o&Ig#hKCz-p9oR2sxfL_Q4ubZ~q{wonE~r`)@_ZAUejR<`dR z=wSb-#TZUpn9djUFo#d{NG^ryOov>UkyId))aoe`rgJsC&asF~{7tE&R>QrmFdvwg zBcW0}NU&k`M+%aC5;%SxDGNG~ajfDtJlJOf6GvTC<1exU4rD|ddJLM4ciRAg4S1cX z^A2y_c2%R^5|M>Q{qUev0Fa1b0EyZ7a};%e!jJWE%+6^S2^@45)dmB{7FB{F(gr5Q zV2E@&Q$eIGMnPnIh=fQt_8IJA0}O5d3L-BBK;%5Q?Mk!$2pH~5Kax)Wqnk5}A0#~U zGgvk&Z2<&`10De8$)QrV*3iUp^00j+Tnwom2pkONOl?KPd9PK4NQ*E9krkIIh^(z7 z?N^9qZ>skmx8rHEVbIwp4Zv;og3)Smo^ufQ3z;t^EZdW4faD$8u@^akHiLN;Fc7}W zT<$Up$V(#XEG9grSjrRfSt%aElc>A-HgeMn(G!KpP3;fFcEU*tG7isnwJC)?klqJm z9g=IvvoD5-#Cd#V1MUtN(X7#o3&%h><=c8<{AO4vUr!Umn5H8EKNb=xJmaL*pA6%5 z91X0VVW=Y(TdslI~yR9VXS*2m|-NNQ9nFvhVk{Cl3|QT(bLB;j>7a643RTyDTsU=tswFh zwu*pA7xo$0^Daz^|B7L}9sm*XgvK!5dS5XNNJha7BUUzB9mBYB@abe20v4}ei2NC% zATsq*1(CP^QVe4!Eb^q(Mxa!UIXn>o=1}-h0K?dPHsU@+oX#-XN_J2K!*~-g5Vv3I zGK?pIyozD;$yN-bmwZ-=9(b}FAHlbu45Kj$X$<44jf!Dx-g-iYQ8wDoF!nzz8OC~? zu;Y|}(H-N*y3g0s#4u*)NT3+T=EtOe1HP;X8>}N*$YXPZ&@ePH&at@|aVa|FClD^D z7Z3VhFpNzwX9Xj}_Tz^ow4c3LP5w(qBzd&Pq!U&JN&k{O-q9f=mOhGB%*LAtdcZ|8 zj2Y8{8OAwi)DI7vVN4h(8OC%JJ$(#g>5Ek%vi5HUk;kJHMDh6?Gz91%38UG7)5$Qto>CPeMaL9G?rW|fG6pJX zQs%c{E~M07c>={RVf3mC=J4!;0Sx1P#yyHSonicS3E4pn4C4d9K(uP^GK?ExqE-we zI#V%>3+1y?G{TeJcnqfj*sb5-eL{vYLEaM+_X2#KDPerH`GgGPV|;tXkuVmHkqjdo zo#vG1c9RU_^>DnNCWi5mjs%Kfe3Xp=nqf(7g**f5?cqFZ0Y(;Z*f2)yPtfUu{9^Cz z{|kOG6DGW1e)08Dg$sk4sky)VfTWIQHmK6kwSPq&AM1b-uRN?K9e1V0eZLP|;_O#~ znZ@s2bztlUF!BftZ<)g-)Ce4D`@h(KU^4omO;`Ay3d3D6INm#=z>#*L0!KRRTj=Zg zoJ3$w3Oe_%!0|}{IG%b)V;0TcP|V^y+>R2&ELOwFUOltelYTmx#Z$1^1w-V;!wMqZ zE>IBZ2}3BU@)9D{?1 zt?am%c6ks{XK`qhVipzhSt+*T$!^?qybh@SxjM# zFrw5}Q+`_)$t)h^>uF*ZU+PGpm_<$|255#gVk;+R7K>q9^e?7l7K?8CUoeX&V4DlZ zg{KZGT;?rcsPnWY~$anFGj#37Yvc?0}3KhO%+69_DG2QafU*k^U%3}1(B}USs^S0t31C$3$9|1*&{_Sc)P-Qz6A%zpv4Z5E&?p)Q{XiKF7eteTt!JA z4n=V0XxmeYPBof>DU0R5V4A?rr0S0T^%+#UsxUm7ZaY=c)T1&nrJE^-dV8Nlz9wbBkS(&>gZM=LeL?GFvV2b^**Ie}-i3a)l% zfO+q*->m!G>TscvmFYzHcB;4`ApO}x3IJ9|H@e9BeXj!*);!p$qJf)*(T`}&hg+pi zrkw#JXmr4?er-T>J12Uc9c_K-rWaXv+s#|k-AFe0kWiN4T{F0y{ugUex0-~D`3d0GT3eIeMCV=q3y(^S9q zSIfOjNFft5K*_w(I~(y$kw2X7#GrV+gJF?Ah54pPK7@II+} zKVPg^#am=hD^FF6x9_5eP${O$XN8!ICq)GM>r>G%1eH)k=!ZMmnXfjPkhBx`mgk+n zNc4{rBe{q}%oyw+BI24bE|qa+)%*Dt!M}{1l=f#ha=|==^Un4XV6*x=I8O9ML?Ev+ z07u9%1l`ZK;Z7y)l;TO287USsgwb3sM^hnQL=7B`{Nkh;_tGM@K^nAz0#EPg-nLg_ zrMf~Gl17@yWfeFYeMl`)$-J?`49nmvc0?Imf(Y%ZvW>Eb;^GPA3a;PFH;@Ie3I*NE zmwmUiioOGGiu_uK%{RR9CSidB@t4N%SZ@uhLWcFdI!v7Eaq zAPm_CXDnvf&Z;i*#s@4?IcP^rveY8gxjyC^&`kVIV(mGYSFYOa>6ak8>1I-HpyekA0sOy98QUA-{#ObHR%BW;$dY4+-jg>_>{LK zP2S>m7|}HOpVf(BLP6^6dJ0laepSo)Kv?Jrxe35Shbv%Yd!Wq|9R?Cx-RsN*<1RuR zK?-V+xAwh8Qr4A=Y|XKI-^rGjpXJiVUf6kwLQO@s2oleg1CE# zv{SkSv2VXd5XwIJMXO+f_^jt?C5SOF3kFZ~lfSEJzO1gA)+@G1_+5BF5kwUFbjk!V zOb3M+dY4NOKi%vQ#AaNyRUJW;B8N^8FULrN*xREjL41U)r<)*BU@i=XRG)1MQh(P` zkP0hT1knp@hM1TIOw^FSY%h@iV#uso+Yxz4GhBjLdZR-SE1-j`jv!VdhfWX^ zTS$T^?_QN4K19~jO%R=7APk07@>T_@owXID{`^@HL|1wr027A*6E)=j0ZKd(nI1q8 ztt$|BtZyJeJQjWef*4JL_@K5+5Gx;NBP56!{S-k=lg~;q1y6S4Z#cD+Acmq43BtbI zvJq}gB>h~zNNI?A%Vh#&W_zo37K^Y;Lk=lA8LZ5Vdxknp)KxcH5=INYo-$#K(Xqi# z7zy-3G{aWyLfse`?M-Ri=LcVInJ98$fe)0R#wDIs`shBk>a5>bu4esUEj7!>aT^C9 z(;PEN$W*{~7^EpZp#;ToEAc5)2Z!i1K&m<#mrYcz@Vy-fQ1g)}0V8?Dld?VB`ljS0 z2OQLYTq9ManxLd~Qk0Q$*cOCE2$BCJ8+C*EFBtQ$FHuJIK zp4^T(Ls|ozo9xHwvn`DTh8LGx_Dl!l%!r@1vu2tB{7hdn10;%PngLQ~!b@G8gR zAJ6{S00Zo(<(7H{hYz@yTXyX$382Mq<46EQsLF8HKgs>2mU{x*G!wp#KPfnX*LS8a zhTGkMO>(shfJlLXE*J)VHYynW{g;A4*pIgS4^|;%2eAg9`d}zl#LKvox!m&EWJiZt zY(4s`6E3n!-Egrr!w&nk+L>DFb}hV13!klp&(p%awD1jXxX2o&g@@ST0Il{#ZiZrO zk`{i^$*gO&tII&G_Drqd$4}2WWX2EfsGAH(8H@3(+(~jg)W?0RCvo*NKw>U#V z!FVTDxUogn3bzvAr#05eQtW0y!55s^Puy61fH?&^ir$~4T2|@bfyW#7WYAXFPm8?0)u6^GHUsk04c;j?(PhKNQ#wsbE8O2ySzu=V8 zXn8W{ICz%f9RWMka}SW|+WO-my||cEivIFhA$sG<#boYf$OJAIjY_zfG-%AGE5#y` zyVM`6@4IBS_Ky=w#^x;;Nz@JgAtG)aOyUzPDN;<3F=b+ROSLrKh8j2;`}-~>vlJ_D{Edcu1(6?v;c9vergyA~P4Rl_BH_gxn6ni4MZ(ydr5-sQ^%s_- zehej?I|1Yd90JY*WuY66_>XD9+A!wI6U&5w>QYCaEVqEwERv$*2(>6+%+4M{B(715 zf;gZSg*_|KFB}~MdJ{BT8Y3EOPn7?%q?6nYU82K7v`VuLzx=+7ctmMRS~E+aH|hhj zy;R;Di+yaF0}jCA*$$^gCXBtWDh#@=RxtSOPX&XW%hkfzkv4qLPk+*ne>b#vGiV^( zAYQtf;(3hw^SVHpFcb7fL4iZ52sWg&z~IH3(nm#7LCHuqLOsB=6ovXz@Fba<^1VzP zfLlH3WdI6kGU3@DE5vX4g@gF0MeQbS)bB4pnx{}dk(HTo(daMdH?)yN{bqPQb<~g1 zr`nJDad4Z36^W={jKet9qrTD{KXOhm>SxEER@9Hbr|Pu#C{@$GYoD6-1Ir}pUtXp_ z^E(WFr-u5iba;r%dugb@_hE(l?W&^wL$bZ%naES)->4^~0cAI!roel-7n6VN=OM*!*?#U+K>8OZjid+YCdiBEwpyj`#8K`Jc+9-95$!8{^RXVE9!TH9WQv= zuV102eP4x|_M;^d^{@F^fo2CUk2oc+AFIPdTnS%TdCHMo|7fN{eOi!%xc;NEz3Nc^ zmA0n^^}7tM3WJ`@6%2OoRxmh-E6j;w-M}h{`ok^`K>gAUK=X#(15m#$jtq(8Nr9;U z1YFH(MExs?`XBCQ%M$fh!OX0<{=3&I)PEgMqW(+ry-ZX#Q>cG83K8{f?Qav9%SkD* zAJ>HX!TxAkeo{A3vHf-ygBnVR*(JJqa*6idv%**^TWxBjVOekUCqBK|rJ^OrxM zFuxjy`f;+o>M;NHR;LB?6Ys1FgVd!827m5QFgRAEFh3cbf|x(zq5#ZahdU5N(`y1S zf8aXA)kd7I1Iw#80p@oh=6|-s#r*ZKCo9bVC{bbl3_OYX)8u=Z2!o?P334O~X_)^7 zF$>XG&8!LYNAOE`Hq%dIWoF!q7y~iC0c@4P&UU=k;gq$%3Hns~F~3I-iTN9U{7209 z!PXy$`QFP;E9PGh%Um$#-&Ue#{kWxO{mg|D^ZQ~Z37JE6PZjgK>EOV9(;DWlzQ0Dy zpD5d_4)bTUJS~{tb5Kxj`>gRJOSn>5%XtDZxqS%e}UmxVgBa{3iD^;Nz8vszT^7@aN;NCk3k^~^OqB| z5Z(2?nlS%Ce(27|{M%TW88;PU;QXEoqa-l@O1z#r<|pe@?Z^BZx=YM2TlJ5a{~V0^ zftden^l8QXG??9jF~9#JHS4vvt68rPe`P>s0A`Yq`TNXM#rz&RI7E*m4f8kLS0m<| zvc2jsf99p91@lw;SA{`(k%B?U?+OOt^AzT%fm0Ckvw3dBkNI0y0?VW012BJlDdHj# zr(-_-(Q1@-3}XH~>2@M9|5sXuk9L` z&!`FWv-zPrh55?v(U&!vanmpmPI6ONCV~DP5y(g7hHm#rEcmdB-6L4LQ;kZ;@M%tPePDMBM*YDH)U?uwNAnBED6q-v_LM*w|TYYM|^Mi6TkHos8Y%r8bUo zy4dQsQiZ9QA8m(eD;TSVn`q&SweZnZ{(5Gw@rS$F@z!EHGb{hn%}hQ0*IM?bb}s8B zw{B?AdpNP<+}I*(kQ-(t`A(LBZZrzM?!+2;>`o`PgBx39MY>^D*Ra$X0^d5?Z&s+A zsmLn(L1nRa+5y9h7N2vnu5)9HtS_|idv2IDuXeJ(>qZw@`EHn5%G|Edmf(Q%VLOj? zzY`ehmO{QuT?iLh8&^1EDY81anPAni$R$FSpB+YMTt-gelEvyD{DaHgA~$ht}E@T%qZ+=Sbi ztxE0O#Y0Y29Z)3DKflQTD(x-7@A(HkQwocQx%a<;7iYlJzR1%&5$<9*bz+94>+kJX zd-otQ2fW8gzeZ0tyhoA2Ute&0?PX(mEUwD?`i2`mUV^p0vfSTSe}Dcl{mDopzcTZj zd9c8QSan+h0G{Tmeywe{zIoxywzY+0f11~n@2i8}7rO68{=rO-;XP!{zw97x$;&}* z0!Ka-?i{i@#xlu;*OUt(Ipr2&NOi2bFS+3okwg#%~*D1Pwud;L(_Ww zW>_<=zHgA%9iLs_-xmbdHzlCHL(u{C;Y(NEb%uAD)jSS0UG9L&g^!zF*|FMm;KNX~ z=Zx=_IftwCr$+Zn*puQI8`|C@oroJ$w>+ot3P~W*#>ihdVe|<;3 zsoK9^kgnIa7J2;rE4efPUg%#ht$*)VQ(wEF{^bYM_i&Z^KGOQvubTSIp#H@L)OT5x z`tr5<>Q+^x$pCw8Ad5U*!Qtv*u8o4{08u80Kx$=%GUmbq3COpMk znd1G^@P6OR`-9<2j5MwedkdQEtigtNr5Foo$u=Pt;}T(`)f%JKI>UUdSx9Q=?_vkI z7cTf#hBEOB-cry#Ut&|#aT7GaS?wsS&cKWtxr>?_UZEYUBwV~dRF*om@0dObW_45r z@w2jY#}5$AKYSrPWDboE*bjtH=KeR~WuEd{6vY82hV+rFYFkooiEZO{mLhAaH=q8h zsa_K|GGHr`d8wyWK5tC%wCa`PY1LoI=d0LGu^t8$<^|X4tT>B1ZerM$6 zwWU4JHF!zoLZd~<9&AxsEiiJo?lIz*XErt*M}()N4|~|V_~ltU#%--c*l6`5P{ETg zuiG?-M0*Ug2c~K7oLb12lKa~p!1syEP{= z7$;#B@5*~H6zPkL&jLm73j9vMcjdLti9CSCgzuUfcLGIhyL(0MPF>gvRgBgrtM$r? z`CsQo?o{Qlo{RRbE2P;yfL!J;1Rf)@Zt**2z zC%iLu4JrY76IyA^6zHbBb92Jwv6g^xeMkD5eIV_H_&&l~h%J+-ys4q^mod0}(a?=% zLkEo8bwiL#n`7%>#B!^bEYyY2p>eT>*A0cQ$NRg_=o-2s)@bRhks7;&H42xuijzGB zU{*p_znt(_S$%WD`?C7vgx5em!sx;`F4LL=OTDsWsVxgdFHBv2VJak6%}b(rEfb8z ztx;tjaOb~np*Bzf8OE^AAxbbFkzgcvD&%Ht8Fof)_|+LKv*F&{(WeS&-8&Z`}w40|aE zvdG1)av_OY>p(1;ocX0enG#z`+(qZ7>X1D}u}DEE+88W4m!H zS%LLqSIui;>^aG#y{zIh#e}j7pj2*5!thx3=uy&-sAhuEN8DLLzuafbeHHZce3q){ zKcPDM1?VIy-$OqPajvXeX^?y92meg6UG!ri|4-?Uv^QRbt3{8#P=ArQPW-8#&pekZ zs9)H$8tSJBuv+T>jjb4|ABbNM^?SiRf9jvY>UQjZj&l4-Kl7c{?8n_?x$~!f!LLR%FIwbT#6HjdN}!mo$=U%@?p>Zf2;#M#?NNxxeE@H0DSKsH~0i1_nh9uHut zVg@WYz8W69Ai!#QFc@1ing96p@L&&k=+A>mSQ+v2pTaNv^?VBT+~{4YFwmys(jf|! z3zlXbkM7Nunb$^?^h>A+I~u+fqaEk0Xz%bcY(xShFXMJ3KO-wJr*YcYD`Cf7n4Gmd zyB3wbYS0#K*M>$fWuKNrH|_q_6=z!G#om+CKcfsgmC`X>GY36k;p4?bkw&6Ewiy#e ziK93-(xxJ8{3M)o_h>*#^y~{IaS>`OeNA@Bd^k#ebdb5|;m66G#s5eAXh>;U6+eoo z(8(snk1vnotsg%+_W?i7Lv05??EK-vor7{C54Cbk3*?lhmr^@s@+$!C#VoswR$KTG zb|JaZ!D;Pt!uyTJ900`#*w6<9fia(Ps4+PL#oVo8f;1V6@8>|dvs%Yc^m=@+J-mB) zlH}^0z_r>HSnk9~XY zG1UykcOydKjreGS@taod*ev%+YagS_kt95aEd}e^J?7nRv})`w%&)-Aef$cH)Ht+* z^7kHY_pGIq_L`J9Fco4r%b6xq{;%xT+>G+d|e=`0| zUho_LhUASNf2mW&`0uJ>{N?$o#$SNW(a1lV@#h)?$^PT7mAiZVX*PSt|5$gS8vouL zf3)*A#-Gh{{5{R<@t4uT_~SQz{H?LC&OV0!wpOHeC=oV(F#0~jmF32Su?$xR$Ld>= zKLh##WXQo9t=A7M?3gs7eqe59(m?F=iicwpo)i9Yeh9KdoHe0H@BqDn(fWVRRuQ}2 zdt`U{nqwZ|ALGOZ6kIGcw;*Un;n;Ng?d1yP$WvJf^mqooiil}ex} zo4ZYb%7Xlx)GZThH$W2r2z?iYM(N83p0qlhwjE|xyTE9IW zHOB51I@V56blkyac;wt3<84{#)sT>{N%)D+aNFR*{_X}W2lnxZ_hWH1SYIQ4fWpU( zcyeIO9?{Fe0ys0>h>x5F#MkW-#E;X6&lCkLi0>0gSqXa7 zP3T?buOH%d17rFr#8<#;>PCFwdqDhnh4}T86~_;VrWC}L{I3S_F&s<`_HcIX!|^{; zd=dYV#rUoc$J4wuc4fBBi2VzCQ_^fVd~Zp0f0#$2NiKg$R4 zQ;GP!G2!^4i3;&+#TF5czaX->8pO}gh=0Xrd=S5}4$D1LbZ zWmAPqkuhUA!eEzLLC3k7wW(i=?)ts5k_S=MN{IExr30QUaGV2T!hes4*A@74HXKKG zJD*Px_<4U?&$q#)qx}W~UuVOY#=}zuJ_rY4YW!~CnV34h4Ex|%fhQia;QQm@jRpR+ z4Sx)mj^~dT__=Ul>h@dV(uC`xhYw&VVRzZ?vwUnpx}NwrhB*U*g~~Y*9lcAKk`HmPS%6Igl zhbT9%U(?qrm!x8gS^ff_1;c;V&s8iZq+*TyRoA6*{kHs-txtvX`bjC5SYL(XI`$tR zO;Bu@c|k|Ll;A@Jm=l?HeB$rgy8(F*r`&ky0kL=M>D!4^7H*kxBzyOmRIzvKy`dyw z{~yW2;H%&v=Uo<>blSV4h3(Y{8PndKCyJ{Id$)6vmNY*0?kR*tgBJiF3iwj$5jRb? zy_*y8%E?T8t;d-BgV3@0QANkSY)09;3q?LxLxO4V?h_T}wRaz=sj-i@cL%Z<5iImh z#E zJ-Rt=+q+-a_aeUbH6VV5LVR#kar_t?@m!Hj)o|RjcMC=LdO2RtAMxK31@TrI@kvyG zZp3YSx494E#}VWmoE-d!!a*NgZS#L#OCbXJIuK=0)E zx7={J5x4E#+fuw7zy4JqK6{HG{zpV1K8ejJ#5dMH0^+8<+pr46rzH3y{xFN9!KLV( zh@b9`; z`v3NB=KrF-dsYdCIR}D;_HILrFYS&xGS1~jB7fs-WNq(`^^B6(yWbU~vA<*~IY&_J z-Nl3{`49)Az55DbOTEw0-VGBr-2=1i-8%>$>jT&JZVusteBj#NZB2N{2d?eiI)u0K zfopp=Rs?u5;4~_k27fg6Zi0U9|J2^KGap9pWCo2Rw4**afry{ezdHn{v`~o58U}ke z-p5*auuh=l9C#?_*JW%c8tkL%o=@HF7C1?PG3Ue6BZ(D~+x0;Ko?6I1$mB|s!(f!( z)YyJ-pUlK{e?m$ioh-iF47hf0MXxHU%UDgd6%66EJxibpbjtP`}LfSEY#Hp>u>3b?mH%>4yuXW(G`8i*l zp4zYY^w95B@o5=4)HvP8eth`!5OLCcnudP3C@%HG3D)B_xWG(4UE+^ZO^s6p=9T{( zuK-~hr)|`?Zk#a3ZzAn_jvuFSn$Nm!KEW^?=D=wVK4auFcK7U4e7dSioIXY)8mBA# zaHfZbtho7vb+?xN zXdzWwfi?h*Re!aqq|!3<2@m>?VVTM&t&qhjtCFpOYuBAAC0g5vw5bh-n> zLbA`+dnd-4-HBkcKo=wO)4?e#+#D!w%|}NsrDWC)KDhR>6B5k0S_tm%kaW&%oamwE}+J=va zhbw>IJ{!Ix9Z(HwP}-wci6!$@!cu-YOrfD(AAw75-JGt179i za<+e!VpV0={iu@SU*#56Wi_kBu+n{S>87f@#wyGGt29$pidf|(|0?*>EQ!9ERSNv8 ze5I;fz$!QRSDB@%oWv@f{Hu&tRSy0KRhsx!$sYcS$rPpmKZLMh@0w2Z^Q`1QmzpWbYW^303KDuB}o?(GYH1K?u`PWJ^z z0RHtpfR6>3Rv%w6%hhg0UWaf^Gx{{Z2adPm=~X71GRgUiItd8~s7Kr4e{cwbe?~Uu zyOvIPO@p!Xz?c>cl*LP%!hcKs!-eUWkXuwb``M-O>$KMHjSzwAMK3R`6#E z9<5&_k)%DwhILq8b~hPFA_^2eMdKzKtP94>$E<`Bz$st*jb7-679C>gA*6B-!8g>9 zHyesT+N};0T}FhF#EgR8NCiXU3oekjg^lC#Ok@VH$fS-(%!ND2Fr=w}9Df9Ak)|zw zaX7`(qjQ2(2!GHXmNSHpybdcsjtn29^yCs|6T_tA!h=bHlJ7y!e4t03HAd`@?H90p zH_u@8v;uDt7rN$;6f@eq$BggyMl8sfzSf6fb=ZO8)PC-+PDkSwb2PJrN%yh!f6k-_ zblmzw+NVBDx^TBJJb}{`6#+8S%Lf*Y zs-2K`31-euAdj4Rl7^+KwNRKQOSbliMp`}R)eR*YSQOE`)Fjp)i26FG{W?DCGXOUO zUvmHobvNa9H+E7D%*_?l6OrJ&1Kt66hY_t~*7yv->)@+%03H^c^y+m^(0gHD{TC+a zP#MQ^<3tkSGXO7Eu$-}5ou8v7Xhe#gPJ=-45H{r#0?kfHz}O@u1d6_dX@v1P`w2BZ z`>CZpOAJ+rx>SN7LSwv?R^;F2c?Dtnl9S&$0@)9t?k7xCF_u zNg2JuNnNrtRu9|VE1J|el(;%J1MIf)kN-yfHAh*0=TX*Afk6@PheK9kwClfzVP!{m za?v55sY z+lQjL+TN}h<^Gtk9i9c8Pp{uQgst_$==GaG*n1wB<@Fm*_!B;G?e)8o@L@i1?e#mC z@GE@a+UwVd@N<0N+Uxi05WtTG-1PdDVMxtu9NQxH>uG#G8hjBkIb+04hbtpVEiri$ z0`<&_CHkR?UszI6CVxMYzY-d+cvr5!a3*LvWy!sM_OkRrNKis;!15p~r?{c*2jCVgS1K<~A=z%xKu+6?2J9=WiQg#8f z3w`oCd;Y{}OXJX+-+4A+Lb6QlG)ezw%9mCxB9(I;cxQo*~a#(T0MRYELHby`pIzsdN z=btS^gGWLX?pWdNU=pXabzIu)Z$J1V`W=g1h{8fVPa)dG2hj#ZbYPiq^iv(%yVyo_ zoJgH&INC%bTE=I55bf!YXa^reTLi|uMJq89{P%7zM{gSoL_b<0i2h3>`aE|RYUqD3 z*nc&M-mVcnu?j?A{GJVXa@Qg(js{D?CeHP??9s7Gn+3+4K%Aq&>3SX4Wet1;LqG5* z4SdG~Cyuxu>-0n#J;MWYl4|00@4LFdG)TKtCXaI*Q8f>Q@Ux3Feu5pN^4j3tuArUph)&Xo-YOQ3 zm!ms3`y%=!i(QDG78ui9AsX;Ov^EjFaiMT@9k@$GyV-~qiDIaRqqAjuwa55Sw5Au) z3;hvo%i?J8X7tGM_=I}FAuXC~e>jq7wLo}NG)J6$SbVOvAB#V&B3t~{YQOa6LGj-v z)r?KUm1SRJ#jE`iz7J3TF5qY3$_ZEdrH?H5EEl{5?Tw;~)P4-lcfpnO`DOy&h|+>C zHL*8bk1LSe8w@AO8=+xhAEV6lvmZ;bBG0@9nWb=gNu-yeNBN^Wsr?)JYmX~ue=7g9 z%z}U5f;W}6bCtgv&v(a_^ZC;R{-p)~*adGcaQed)J+LiFPeGxgr!MKa7G*+@LVx&v z>4Nx+$PX0#3ng6=^I&xZyXyx(g$9eYL^<;!0c#7`85;IJVPh2In&`4=EQ6C%>Z5Mu z!wP{g%kg@wS-we^4`un&cKtG4ehtfi#h~hQF<#N-SuDTPt{>Iqtyx}%`tci|K=BNi z*VsMuy$vfVPXtK(G##hlLBjiZ;Q2%F>={))Jh=8 zjoYLJiZ%ilquaM`fFx2(WMi{ry*deyM2b;_J>`XQOLaYA|M9}OrOG7i zCJ)ToQnetw8{ph?@U!RVV%KS2pRKPewqcn6EI`dyu5fK=D!w)=*F|M+Bu~?gRj4h^ zo3fcvTN-u!ij+){zft)+#=ee?(tX-VyaUaWJIsqd<^}hCd^Xk{7Y<`3?)(v+4pzl} zDFofj7_T(c`FGpR zG#Gw}tF_$NBwGvDi+V_js7V_x61?>X=u{F5WKE~{b&QS8np*{xuhH?XsceBxNaYzs zR%zT1zawhZ5O}dB@E6f|UPX4_*P6EYEz$rMM}wO%2qY`Xk1Xu%a%mw&g3<52WJ#Fq z+c{N`)eQVF$;#0qeHlAZWc?^hxf-&1lb=BBq$2|Vhag7#s zf?}pbf^)Wd$$E>itXfr(C2nRtTEox@M{5*2QDoIW5?Lo`va)5H4#n7nek)!p{R@}PDg6HK-MOLy8S(W#KtgB{MK~_%(SxYgl zBx^N0QDoh;kyuqT2`j{!MZAK~_-tgF`;&EyB5N3WBw5pCyWpCH$S@hAtlRW*?`X9m zSp~DIAZsG{VUE@=j4R3dm7OTE#%?$QS<3b;Hx|kE#yeUUf6fLxqt%|pco7dhlB`du z+TEjtjpYX_x^nGiFIkt50$H!W=SLP|Xy1V!W(X%olhw>7>s=Aj)r^+B=>^0Lu{peC z4f)KMtZSs$X*mRnyOIW4w7g0F|e3f+SjZLZ}zV@1dG_wejD7DHJ$2Cq|u*Ky1%dKlwqOz?13Y&GLr%z$G=$T=SpTWt+t z6|$t_V6@d{61L6@qpdcPuvs3MWvk^8KEVf0GYHT3A$+(G{CoxPK=_qD@Foi0nDBFb z;M)ED+ckhU@_~OXJCUwm5dN#IIVatL;<*YwoAA$l;7=*|M8aqJz(*>09^n&w;8!Vl zAHs+Gz|U9k4uoIn18<_>jR`*&aGI1%>iry($-G{tuk}l8JH=$(WY6)=wU~rX^VaeHn$9oj=*Z{IPHQE} zyn&)xu&FHjwhS*>89!cR*|$2sWMmg0J_|4|gJq&g(10T~Esv_caA`;Pi>C#!4ox|d z_hG^P&{27_(biqMt$W#)lB;G2oyS1PYpTUxP$NZy7vHS|g)OX|}Yhz7Is6bh@UZKA@onL2XK3_u!-gD^#~edi{#$4@U~D#sI`ltY z?uIp>DdR3A?0iO@3aL--_PI)t_JT#rj-0}!NukzD0&|ZgC4rKI9Eb1@DeA5~GC#3M z(iRfeM^dAWC!sO4mYtfEld&{Vd=4l>+b<7SZBL*!^W{^D@Cj1hhfk@9wEay!ZTu>p zPv^W@1)r|gd{X+=pHIP$O+KxrlGc1`+fUIl(xN4vPbqWZE!CL+!uVlYs2D$E=#lDiNvCivel6k;!kC8YC3941Li)`gqMDRUEu zOSJ35S3qP>!`gPkx5$$0dJEyBec+`E-ktE9ec)3S{4~O|eBcENUW4#cJ@EWnf!nsr z0juSOg#cSkSPW||9`Ag(7Q4Pp*e6_vI6ia|EhsQ3sx2v-2YJ~>(^Z}Zn0atF8yJTM zs2`!GD;Am;Z|Mt4_s(ds;$C5lH^)WhRVx+q^m&O^{^s9(Km0{B zPf7~W1A1F{x4O-vx#8YiI795ip`zW1ncF{2VbW#AT~utyx7=%VeHC*A{w4X>Eu?ZY zo8S!qb7|fIrqHgPjsB`m%sgIvEdMyC?qP{$mm6w-B^#8u#LRWeIB;}Bc@r~d5f%+j z7_9iyhvv1LKX5}m3u^*|OTH@TGF@(;tWQZW+P~t%jJJT3$&BlJD`vcg#(i@OZxrvv zKjy}lnh$2MU!}IqWHBPO7+%hp%RlvD0bEv$mHDt>^*XSi-OD~K zV77+If@>~QEO?oXhnHwBK&D)RblqWaDXt6@O&4bekHd>}N185AFyo2txM*e1wdLJ; zly6;?qr0LzD28MbUxOUv3;U$0=0XO$QqG0A*|4~b<=lnGCHTF;Vtk?MPQ`_u>v8Lz z2=H)y4lV1$g{5o3g)?9B;ldr5<0cobyi{@Fc{J`j5%!7s^N%OOm)aY49*OW_!NMiJ zEO?E@(cnW5?uZ<6oi(J zP;nw1jT5GV57l`A-;v2)Zj5ISKKL~i{NlInhxm-gfh75`>b#+=U>)iAb8^M^Q$z{D zeWCIXb%J%H;b-I0%x48$?KWD#p`+n+1v%i#%C3o>wT2&zhb#ZkHXFVPmyYL^RksRz zd;R=ET$*rQ^e|%5D$gW7zxEKAeH8htbJ&cTZ~8iJ-1(~y99?_=rkBlZ?`GWC?X8sj zU%Ch_{5pE`e>=wK|KbbRXfLT_*4U(uu_m~&+f(_(cRSlVaz63b(w@#IUhUIfucK@4 z5zY*g-Uo2w#;@Jcwbzw1#cYpp`oEL^dp)LywV(JK`M=*{y2aHmmHgrrg{6-C;+2wL zoD@o28OuG&_6Hwj{c%TGe+KHi!qdeKz-O4)buWUg+}cMR?56gQcHPkf@H#&5wF@iyB_BnUIPf<*&N_My}Szx zx*dNjmWt!=;~S~hw;L^{_!t0Z;yKd>$_3w8@hNoX47#5w!&glt<~(iM-bgG(VqXWFA#R+!WaimK&pGwnR_S9(7o4PhqdYLHnK^D3V5ggv;tI92&k{%x}xa%S+OE#NE3U zIYp5a&?J>|XW}LaTakIRg(AV6CEiiWydES?e$t1eufYd%9xlyNBn51eUKZ(6%_vRK zByEyil$WFdb9_n4WpOlk5taxUvWq(nH%Zu9)KVmkSnMU~?(0C(vPmE*8my-gf0fOs zv8ecv{Z@l`Cyn@NRUrPx`)t6oEu6sOXmBFt2odk#hd4F_gK4ryf*+N75ueR4RtgcH zr~D=O=!|lhjB$)b$4oUAg*Hh|k3`a$+Q7ez&nN>rZpC~(+n1zL7Dt0CF-J(!&D`?1 z#{vfa2XskBf;$#@N!rTDRK`RflKNl(&FOVpH$~D+cA!S7$9!T`%_#jQTc2{{e%YRR zr&p3cNxNnVNtKu*B;jj-^GHU;-NJJ-ikRu4QKoWVT2l=R*?0 zuR~ZXFN_x4u1X>r2mX|Te@ghzvh-Z^EBL#FulIpp zrQnYfKGO$&zJd=Wd_3T$-TEu$kC>?PG982VvAB|ojRKWGeZ^Y2RwYa1T9wS0QJXgj1` zpd=B0M;{8D$?GIshb!hmBcbSpl0+0S&^G!|x9$O4|AypB?MY0rJ47+iF*UB5koZZdDDV7U!yW_+Vf_kzRBdxclxF`Z?@>0{=E4?-wff+ zHn}NED*zVGdmc*Syr1g2=P^1KykSw=2e_}OO*s;-2;K4dDa93+BgnpZN6Wi@xwZAr z;oadcv%}vfmPSV{DzgfA))<@AaP(oaePrqA!!i_OQZOuq z%i3p-ZOwy5IDYoNvG`#M^3hATpcKJ;^D8p=Y~97Fh0ALQPw_!xW8O@~(}FkRdCGey zPkC?gv{2s&PfPSoCW#H}8{z3Vebb+i$MlWx^a;7Kd1~I9JT>p90((Ae-kUs?d(Bfj zCna%LvFPiMYN%}{uQC z@aE_f7F`q6piFp-`-k{S$$^r~F$)57FNa!25ImbxB5`A+6B@u)qARfMk-iHN?b?V{ z7Ip&u#}nl+?*ntYD>J61 zNkt?nH78?P;Nc22pU}_;x}g)e#fj%S5;bT+-v(bSjBaq@gH8gTGjcnq#Lm~C<$=kBCP za7rJ2c>UNa_&ypfk!_pA;PB6CxoNtK@9f^>dod;$8+e)xkX@SZpy7Fm<7&PuN+K*G zC2qdE5)=|yPm;nc`G&6%*zy2FfCDx#1Yg2HG$%eh9bGUYY6$8hFy)x|zsbbc{BLXW zAH)6FIST)cv^pHGsNpc5&8UVkkPizLeM&|-$AE84IL1KD`*H7?BM?9Dzb&bP{~w79 zXpeE77(M>{FMrj={}ei(^t`WyNG$n(qTp}yANV&X%I3URRMa!6aPmJkUW{_iPh_59 zAFwJ=BnDaHhDdrOB|RghQ=q6WWKxgxANlRlXmDmvs1O{ZiYXR*5u6Q-G25wTpD<|Gel%eZEiFln1P3Pkg>rDIr(sflMmA`5k8E@ zT#LP-7I_hV&~`LbdHB)KS|>`z-1{%k*#sg-=09$@5VyjhaMFi`I0>!U z^WSXRRG=?_gIam^ismO;^Z#u{U-tAQNb?Iq;H-XE%6Rl)7o8`+Li+H1cM=y3PSb`% zKNl)EmbI=zMQ!#EfwSh+%Zm1^?3@}X456%hU`}4EBsMtlS65H7URFJIMo*ffKfg_a zZH|KAm(fVC@IH&FYSBGvc4rEo(%u&%ljIgcx|0kY_&poc5-ZpU)%wW$|Jxk{3XO%X+zxc44&Z>8%0pjsbSV zPgn4ogrDXEuc_cav;w?_5Bvu~qiY%A--BRx`(+CL65&gH;4dk7A>l9jzzY?80O1dN z;Q6zk;CSy{o~I5y^;X^a4G zmG8vy;c*o*+(|Vz2M<*&rgJU@y@_+>JNYYb4Ogs`>m?Ylr3}u7j&~$y3h1@C6ivRK zJQQYtfX2z+68T%ezp;@3+3|RLzgPA5-ks;24+aKAwCp&EPyVKFXJbp_aS%J>lZ7;n zaImKH#o#liGk>#d8;M{caQeIP!2Ot`b~vJq^=|M*u%pda;C4t558p%LHmb_QHBY1Z z{pa~wkBjYzd{q+YlMGbvS(Y=Z={-Mb&ohAG%u$3@$+Gb<@;p3(t-l_E-+t%8%Hgc@ z8j`jK|HqFZ(0_e_mwDWFOf#fhtVo|D3I|eE|8rhU6Z^B=7)e5Wcv1PZ=7kyfRe78S zi=)Awz>;hT!?x3GNZ+sDU8gi~J#49pq|GvF zQ>19N_-9F*7l?^jZWOUAACgo2N!~X_NFIQhO_HC4`Q{=S&W+TX9QQrOL4K*wCRtB< zSRef`h0Q})o2x}){K=-Op!t;l4$VB?Nna0-H> zq;(FANf)hfqYMElB%>)m=;$}TPhh;v@x4Ietb2@;!~*tN!{5_}_~&c*0TBiGUIkJ1 zA-MBXz67U9aeS=eWKOpu#o6 z-~(@>;FTu<-rNU%0Kg14;lKJa+SA?>XvL6}nj2~N*fYqR)O!^;i6e+8;VlBNTV5c@ z4evI-ya$8I@DClhMElk!Kn2EQr=n(BM@7wZ+#Q&VQrP_gTh_vEmvZ0wVpm(R0~K-D z;cW(W+|X_lA0y;O=Ih55GB+t?PSD7tdXc%?i42l2=`cy(?_pH(h!iji3j4FXnvo88 z2MY0he&Er`fm?K^JJ?G!`1<*Z1J7^|6wiT!%4@8~r$Tv+eLAfxox&QhJ6&7u>U7t5 zMQOh3G(&fKhPTr~XQv~o>@-C>g&W20^cr`kqjaYUs?#;de&rN+ms^2&N*g#kO{}uh z2GS|)7Q53QH@hgUsXL9RJ>|5fs?#oNZ`E7l(9XhvQ_6chzzr~WF~Q%S95=z=Kc8+Y#p!yg|824+wi^p*^b65;hjryV0x{!?zlFKUH*nl@cA~re({=lADuSZA z{p)?&Pm%V;)m3c1|LAVNgS-8*M-~1(Rr?)u`+w1pcj4ba+7~mjcra{SKm5PA%f+7o zy8Q|ZVM~7DHEIT1AR1F4zk1P*j|S%>vdUTW9}59BTB!UD`ha$WHvmS3>y9 zFCT87;l}p;sNzOfwPy=zWOh@FGq~f@+ZY+u~}(c;XzR0LIsE1nb};;L@?{(>&437LUO%PF;@n_PX*7^fJ~LG|53_x%$Uc|0S! zJNph+*|(f}afL`NSKkfYeYe+r&vO#0R2~@r8Rkh~ZV0mg(W+&fG>qPb68DA%q=#DX z9axxw?eqqeL-`&XDES%NX0S#j5B@;Er;hQ42BfN)l{DgRrJV<2`W48M-){Uxi^M@F zTDnF$)-B~q$KQzR_NWE$6K{7df!D*J3Tq=Be2JY5YnJ#G7b@!ZPngG~ho|Q${xDvkjcjVx`5@r$w?k6|WGbzrmiz z6`!c{xSJ!_lMjCi6EAiys3(64yQEg;wL-j#XMf!W3=0n?28!=esGhE+$P0YpDpl4_ zqaR_}g)9Th7XlwPJ%@P31q}j4g_wIr*D>aXpiF0F?i1^MkNl0v-yh_!GhXnilzc3I zm&xBn^4BL}vn+PM>|cUkA!KRnK6EJlI}8;i+~1AF4Edj)_i(dBlgo_>Xd0tLf&NbY6A6n3KRHWb{vqu$cV;}C`lr*{iv+VDLuPyk3m3Sn!x^IW zJ2PB1VSv!Fp@E_!Pt3dJ+*NMJ(ax3RrqEIX@ard*`44f7cv zHaGOg_K(qm-do@mX?=!vp?iM7IXr-V*hnxf>Sgmucqh*oezPF{L5f1WkC>Oj<|&W~ z)gnGr`?S~d86U*2CWhYmk);s-R8Q>hX_dJV$Llw%X#+-rca8HRe#;p^e13mHJV7J= zj2L%<_?D6*Abz#>O*g3m@fQkw5g*H9Y#21+t^E+kOE&U7mq_rvh!^qK5m+)372>bz zJ>>UdoeAP+9trWO8u1(1wGYR)J>-k{Iu=KRw?ZCpstjR|(O`_xW!&D(+xUr%H*O-Z zJShju)(e}b)K&ANgN^OI#q6w_iG7yFb|#iZ+U|9;XF=MXNwPMN${yN*XR{dDUOTIWwJ!=;&z4%1G>iSB?osSl&L zkx>`>dvYr0B>?j>!f;V-+L`}yz*RhGJc{-6#kh39)jqp5%xw*Cj!OqzZK?P@7Y&~q z4_EJF4MMa*`o9Smas8|B9mG(qpWlp2NBin~2M@y})bNqGbiny7nn2M>Fg!IpRcz2A z*oW}TlH{%UD1n>ZI{}2-c~C7(fHAV5n(feejp!ZS@#mozA z^a@21SHs7vHG1zssg>2MxZUx?Qy50jbkxVtTcM#TS`6B)w7Dt0w8u4a+h+{MGvNHBwdB}_S zvnK%Y->wwIJ88tft$3INr=g{N{VvZ#7e8jyCot^BEt+TlgbhM18Ud6{h= zX2;uy%KkKL_;>MeWq&>dqfzi5feRadDY^m%cRWwU4r}}8F$o6c1MRRz7*>jSvF9*8 zH9dA+py(}(gYk%GfW!_f{{xL3mNn}fJUK<6jIi&$Fxp|S5w_e5qa79@>$I_IM&;dlDLbzt2zgrDUD*Et^*IC{va3pnjG+KC^6_hPfDPue;T z$FGo_4%T@rt`1A0x&+r8i7+&Mj7e?M(i-`zvOJV+_@tDKm%qw3bevVC?MGdQ7V6Vj zzV>|JQw0xoO2|JR=^zNi91cYu$_z!0sq8%jD=fLp`RXF`M_AusQ{tWB@UM7tU%luJ zXMZbh6T(GlEAg9N%53daq>_ZU=kgf%*=bWzoEx2yR)F777^l0B12(zgtqV^eAbcPc zJ+6e2?&!;DJYL=S1bR9<(vz?Bq?dkxyp)9b5LyWfd6gTjHINc;)!i~vbHjtvh8Q!3 zKwQu_U&O@H5Oz| z`wu@cH)A(Gv?ro`L0SPC3T3Pa6pmpZ^I)g*U$@-WrE;!)KJ-a$7`owl(DN6yPqY_O zFqVYEy|C@aChtCdRPDh)QCAV+Jy6b*YJ1>+K1k>kTG1Uoh1; z$?x=4(~||<7T`xtK#hdaPSp%24 zzYLfxM=>QI@_72B^^SEwt12%_xSjqPf)S8)2WSI_C4k%v(k=FZjaMk5CPFBj8s3-_ z$vysHD4d&mFcb~pqh?zVhFY&oEX!%VyzqyEz-8D({HB+Nm*D8boJfb`L*Wh$Grk$N zCw4E!TlE{5+okTnaF+(5!o@YnB7UJg_Kn?Nq;9wY4?HFxi{_!6Q7Wv%@QU=$3b!8& ze_FVNO{e69^XeyL{4s2IPBia0oC)x~NQ{BVuf$|7c?zv^3Kl=W=EDws5sF@vh*2AU zF~@5@`l0V(4lB$VmYO*>KXrPIydmLIWY!*Ycwjg$5%OVJa%>VRDEt=%I6D8b?g38C z2}Ahhr^0-SWS@U9H=Lb*FgMzxX-?smgSo92C$7wCy&9M3b=dLvO<#qhJr*bTilm&= zE1c3kWAU&((nmVm9Ix3O-V{#Fiu7szSGZ5pzheA$O?XpQU~Zr0K&nsE!?9K|4l)& zCH5pRqa1{M7C^KR_yWO@Pgg25?q6`mk7< zgXWzqEkW~67Dg3Ug_U(NOk|m2?|+SzugM7QG3tqVRTV3v10AgNu<#y2JuJkjL1WSQ zeB_^!g*{Uh3t!|m#>GN-ULsULG9y(}DF4=nt+hd&GPk+3)xUMPl*Jqw*IRN;aD zIt!nYjVQjiDi(QFEWG5l>R8y8P!9{SjBh~W<}z-CU_58xP3*|ULU@M;iINRw4DqtC zJ;GPU*lfz7iL#uzy13xoeR6fx(exY?MX%S7XVCAvmGtz1xPer|N&WYyB^$Lxn%_?u zm7SIeTPv>twSJ~7v>bT=MiGJiEnt5Ew$;EPp=eQB0TIK)@fK1Ysp2`@Xo<3rDBaBz zADTyIzRPLYCI;qos2MxKy|~nrWlIP>Z^c6fiHbFog|5Y&x!+a$)d)18 z{rm&C6F8)HN~|X|hqkM%_czr07T*C|>-~}=pKtvM8#3QlDaDQZ{f&=~uDzAQ6#f3j zhq!UK_uSF7_aWJ4;`cUg{?7X#e+lPIeU0}uK9lpRzlLR%8%fIO6;A4sow0h@?q1QP z#-YU3v1ZD6)B63$^}C>cDB_tfPk=O-7juyiZG0tb(p4pYIKYz$p6d%{Smj=VCld_4 zLWyi#2klL*cqO$setU{Gzdx<1k)^Lvjq~No)m@;d4c4vk;VoQFE|?fX_1Txm2M>4^ zP}#i$;QGFpz5(z$f_M8Zo%{&EGYMYj2M!buA_JpcqpUK+zY2shtK7*dVgD+psVWz< z%0T}rm6!==C5=@sL=|P$mBnVG+`OKuuPc6`IoZom%iN;#b!;BUWj-<1d_skOzF>KU zdMQJNc$V1Pac8`y+P$^57dtxbMa0sy%u=RY3*%BbWng03Sk5&_+5-M!Qf$L8!Enq4 zp)SL5jm#y;McZ&}Wi-j;4DORQh$6N>8+ZlPOoPEPP{+&QTZZGQ6o@Xvk^At>`P?&v zR=_QUUsMTxoGgCs<*-+g7K-!WWIvak)|7^Crg4zcJpP=HmYAwY;p3|ufug3=H;Ef_ zu>`0}?C)Sj>cUX1i&IF(rA=i|;oP+37>`=F84gwd_#H@&r`ixxDq4RWVnOz6>&T(( zkzjn;l^mFuHXRSkcj$mT87j?ESMkL1S>uZ^V~^aA7YvZ-3Jm=jhzFy zyzl2N`D1bv2 z(pN2v3+2kyM_xzcW00j+YDJlOF;mv4xa+W*D?YNaSj`I4xcGac8ifbYY@6{ zS%i4^i}5aT+Z0lz>Sy8yLL5#UOlVEYY_Sj zaXhvgJ$&&3(|A6k$+Tqj#L7*5kit%6E99pz4M?qqO!7f$?bV7|bFQnBSu@3m7Nll+ zwnv&-cMvJ;Ux3YiA~c2-U0i})Kg5C1Mg9nN)d;n$8X>;Ipt*F4FGAqb7zdYPI=K7` zwTlZW#CrdPG&H&NGOGG;Y5G-)OXIJtl1n3PE zsEJ0XQs$KJ9M|8A2{0QR~72d1-RPZJcm-`GXXxq1y}L7W1#~S zJQ-Kc=hgm(-?LWmdtGo9k2`3=ce~&!9(M<QDoR+;W!g~we1 z-GQu9>|fL3 z|702a;B|1q@;jwB(Do9cY`y&m<$D;F@G2Vw!>YV?c#RD;BZRH`R+82*K@jQxyvkQ`54s^Y4I+=G67EuQxy}OeMSjy??>UrCSUW8gM8+ryGv~B3`Xg9cQXa+|xzQN0pEr8MI+ACQJ8`@>NIMXLf z&2K=R~t8W_t!)N*2Nx_m8c$6Q(kwqH<0X>1J~JHW*^pQfk_TL^*Ap-_FWExHESZg2PZuzg8m zdlkDtfQQ59FJyv*ZT>6#urSF>kS0o?+d2K^#X!#@B>>O*OOSKlYbTMaXt72sx(0rE$U;x zf|KU;9(`T0jU^RZs0B{ab=3hj^p$QjYl(l9C5vP<3cwsc`)nnO~ZFXzBTTlN5%ai-cfV;LYaqfPz50DNj2)qrj5J&$S*1wo4{*$DGl zTSaW7kZ`F8cses7@CP#@1$&UGOYLc_btK797%r;>Ce>e9yz(}GplGjL{sB8_yDH=< zIp1<|M}sw)tbi$a9MzP310YM=EQ;J&BGRoMA!d zY!F3qkU)0lj)B6Rxa%Hm{E>bvHA$Z#5MpXphcsi?CFEU)G&F!r3zbDc_v$a~7j*4{ z4UwC1Yg)%ZQ7MYls6~S_K38O~1sGa$(UmFqYysX;Gu@QY`g3=&MiLrcVJp~QvjW%F zHhw=-N&Cq_%IXxpT~Rme{AbojC)yU*6M_h9# zI%c`A!PrLwhY;}s;$k8$H$*&Ls;DdrTSgVjr%OjK<*IWCWNUs7IoTnV9DfU-}`ak9Mux4WZH9uekTOexKK%5J z$wofi+@xw_NCkbA1OO-Ipr$2zm51#m7U@G?eBwS5-?Tyi74={;!5+fNs!DD&HTLGH z6_QC4RpbUF1@OxNeq1^IIS<@cS~CGEW09gm2}PX}AvbJde|I+Fa>uBALO;(T@DjU< zUy8Q&r8#sL1d8w(T=ks>XvXxU7(O%PZCOG?53a#leC{HjjwLj76TuG(m#Fz=%_2RZeLrB9dH~OJn6Y?Q1DmIz7;t>-$;I>{{Q= z0P(Ev+nc-B_dbX+&-&gXvi(Tw`)aMfE!CY&afLm~yzBCAyL-s+8(MJN(_0y{I&Wb_ z>-1d%3-3$9qtN;erR>ba2oygkO7yUDDnkP`HF^n3FcMrkYEqYK=I|&19%&9=A+XL`Iifbr;GpjIGe8PY}7G6CpcPv;@g|NV0LC&`U#q zh`wrN4AfUGjO*pf)k|Iv<3~JiX=Zb2TmES|D2pCxc`u(A&*?fm06EjBjaDlrQuALA zG;Qw(K>BddTH)<@vwj z<5nqCwz&;^ykRz0LbU#I2$(Sfac5JI;c!K3|G(^{-)47uC;cTNl&rt82brW3t#y_) zbJq(v3w8ScSKOK)XI+)4oOLl?b^5>9Q?B%XDO2hH@|Xi9zM4VDKmyPq#a96Z+yAT6 z|D}Dg|Ib&@sR>xHQCAwXn(8p2XR(&65BXN)L3-fP5qK2rgQdU@w^8c5SPZwpB8r$u zu(Z3CczwW>DRaNYA`0L=Mn@k=|DTR_@m?0Yz_aXPKSq&kEu_kEu+f>n{x$pg@3Zqv z8Kpf&GO4rN>27vDa-M^oW@x}-<6wb0-PeC;)zO0Mr9HQ2viE5(d!MdSotshsds{%Y zF>0ZK{Rwn$jA{zdC1?W0tH>I!I&r>#tafvI>0Y)Df0VBuaKC2xx7Dj@rvLg32wvIG ziQK&!&-&+c(;s&f`P_f8Av0fk4{qY~uZIskinc1bnKRq^#q`Jjjq~_(;VZH9?cb;` z>A(>e=ku?GBDrfJCix>BF+Z@(3cw1Z7YsSh<{mT@v2ePI!3eie2f3g=IZLiw%>{}U z@bR~UoNF$aBts{#t5evO2TVuN){g*A@CDN~zl7keA{X3^(>4DR!AtzWmTSI%RbD_9 zt*2rz`K;?hRM=2f?`XK~YyTM#K2f0$nJVAXI^qsV|kfUP4RPffsgY{H)@`Swn$~Sf z11>XC`K0ZS^2ycqvZqzg(IjO3aNT4ZyU7+-RjbKlIowtbNzK+_pk#kn5%XM#oDu$DT2A`M#@z7o<*`qYE~hAU(`Tf>02y7 zSIjI>{2mGO1P__#!(*Xq%CXR~KQPO!`7QF4`Nx(YO6RlnLM=yr#09uzJC=Mdh=&j5 zZMZxXt}r%q~NL#>MHZ=_(g7Gvxy;^Lgi5%iMg`w5;M4 zS*TWu@>C@UmdV%NIJUF!5ZFQ=@jNT7LHWeHoGw zrfFS7+vC>nHscY2U{G~x^2UIA)?T`UP(v?WwZfMfeMQh(X6f_(uH^QzpTyEdf(18W zYUyIkJ+5S#_M&Ku`FY!{c}?+`uXiJ$4O{cn4Pa}-PVRZSu7et}7S`+X%1UVRFIDbq zCH&D&0e$D`cLFR*Ba1E9L!dZ|h9lB-Q0mxpa(=0En5hyWRwjHyv9iaw{S|Ne2t>dT zm~C8!1)vRP->Qz<>;r)-Kck^2=NYUJ6VPac)5WZ{t`|4ke&%e2ezI{Yw^%sCTX*^y zrK!utMBaoP1i+10oDJU#eWTmU(XH`%ihob(R!?)u`Dk$E*NVJBR!@*y*h%B-q;G*F zEH#z-IaTOuRx?!iC*I|h^Ck=b91tjx9NE!-ZU-9zCGT*`jQ%rlCT}K-CAo1S_?r+~ z)bpB>j$bXiyF*1Y#Pdi0{?Ll?Y!Cm;Xx!o*^-%YP zlEj1&XW^n-_dvqPCD9?ZDw^4L*zLC5kgn1<$$B?MBOLEI38Mfw7(an_=H0!8qd&3G zWpAMeA<$Yy5($1D;Ap6lMYL#H^bCr4U+TJF@4DaOy8qdAp8#Gs+e>xbw{YF_5Ort$ zOxJyH=Y7MXG@g=y0U9vkuF#^geXXv4Y{|Y>Jl`R_5v;5c3a7shu6osw|Av=sq^7 zc4+h;9OscQMlWp7NinkZ*xKgY<^tE8H5Ros=XMX6VzB@W+)&~sG}?@fkG&|7mu$ac zkr~g#q*M9GO)<8%eO}kJXD#_(h{kMqJ`HKw@6jQ(V+W*i5!&VbF|qBqUx*o&5aUTb zqQ+x*siKl!H%N%B!j)1JQ=ulgBqz&nr7>Q94;W)beY%85-dV^;*jFj@E>?^-lmaNL zm}OopFfZPuK6nX|hy^NAQSqe-d|nE_G3ocw7t=Aaar$C13jR*KqLs0hukf1&hG|iN z!hu*0N^Kxpa~4Gv-ho+WTt*22)6Wr%Y+*cIhiy266|Edkhs~!Mun6$^NX@{U-t}^$ zgHj6qI5gr|oXmlv3rZUo{DHFzdaTR|f07mHk)U2RgTa~^3gg@LW<)Y45hpreBbX!S zSuvUi8Jfuepa>?|eJ~=-2xYp6-(Vf&9vH7cbL0%@0cjm`C0xMzTTcO{-!GMrWl1UI ze{Oh(g#5d!{oq?HN;D)@g3-M%IeUOis>-aGjy7^4wR6Ht!Kj?YJG+Grd>0CYj8Ner z$iyi`rSK4BqFjwWq-5e$7LPupWMY^%;T<1h@Df4`Et%L(`}35D3zYn+cBrueHw-$--)Pt@aK*tM zv%KlHJKTT2VSvCm{Xqx0BVVsY75RFP&r+-$MOF^sKJx6=+;jvdf#$eP$A05DKtyue zPJ>jVe@)eZov*jMm9_IQ(^!&?4JdTD4G^`$eD^=^ru8S(RpJt#^|ae1&hu`dA=cG` zGZp{QNU(;gZ=6TP5ArbzMs`q?8x$TbX6u56XeG;@8pn8F7lWNizw`ba0? zOlK{dT*xc37H^<5Cu@_1xZqnK%TO4bxWjU>7JH*SYOYA|{Wg{>-1;2HjAd9dNeTWe zeb&X&`_X)E*k+;A4L*~7{P$173CRfUF%o6(SQRS^PjRr)bc2@)Z@}o=2=%ZKI~{&a z(G1wMLO7XYHkoF!i-p+fF+ucD7;X~rs@{i?{(EQekJxS21QN3(1u_z>424CC?W)F`F; zf@5$Vl@-?AO#Whery8&7tER@Ya^pXJYD)n2tNgyXq|L-=A6Noq+@rq`paT{K5v&}Fv`&SH<)|HGG zU?XL0k+HL!j+ayJ`Y8SuP~@Rymg1j}H&5b4E8n7rc49Qx)J~_W`bJk;W+Gb69psoR zC=TPqB%jAijD>t2AHD(-!9OK!Vvlj?3_S0tjLzu$GdtU%E3ao|mmG&GOhf>J=77XAoq70PDZyj5zaY!`s znsRL%DGTOO)^hbFXITsYzNT7yxlF0W(d^JMc2J46MJ1Y{4X)*9wW7f!@kW=+n-D4P zZvb>hmzQW@e*)e6n^y$riVX&ePbOPE(PbT%P=17IBBt>X!NY+fCgOCd3>5MF)uPfs z5#2=mupm>By5Ka_7jcitHf@O_c+2Tko^wQpnDewnJgGGxK`CCr|K932iz$Y3Ut;<)jd?d;#dshM% z$5v8*73G%~AYdDw$kBFH$-f)&_j7`OIl&KnDZsM{{+wWF3Sw_O3D$6_J&Iq>{Svva zG#=zVCRDPKCs(e{^6oSKI^M4rzS?jpd%4>e3F?Tm3BJ@9%!qX=!Dj<(YKz`34Z-bV zHw~}YVb`K17C5gilmb$q*~qywBuC8 zHe&~dNnX9uZ{c^^=T;RfQ9}znGd}gcjIE_AB%jEoDkPwcX)}0{Y})wR?_=Z4xQ&+n z3`_OKI>qNr%P`K=P_43fBn;w{kS2(rBr~r6|G0be@F=S6eLR5#0t73_Vn#)yMonD9 zXfzSfH0eM!b|A_kDk>^QR1^j}fC3We4p6qOxbGv5Gj8KP3Wy6~OAtkHLtGGCsU~c) z1rW&heb24xu3pH zf~$+OK{#=?C|g{ZtJHOs5pDTgc0rSQ{C0FLyitIrd`)3)Fzak@nc0Syie&7Fy;4nV zukNIX2z!#y6qv(7<`61;PBPqJzDDqm8*nj76rp;kOff2Bxq@s`6%4g6K+VjVze%-j zw5oNJ3?V~l$GVPE^rB#YVs(CF&mjDERDzZH8-Bxd1EBC<@m1g}ewe$wx<|WIUoZRx z%m)b3p~CLKGdAllu>Ty#U4sxK{1j4Ret`R2XGd`q>7K>~E~fioW_-HoH%nnw$#hc{ zPPK6#f?%b4F)^L2uvs&ynjOd_oFhe+kTcZ$h^F(Ey_Prd6wxmu^Q-+xpu)G~NrB=u zpd=}Cnfz`r`^)cEvyc2Xnit_W0im$~R^K6lYYp`lTs3?`THgv5us=LuKPa>N%9y`$ z%qr&id2IB)BzX2HxHM+{OH>=06q%&(EDLpZ>cLs&!?WY@>|EeFRNu!RkHfPq=Fvoa z2y)DMnHzA>Cr?A59gZE@D}BhoBXm=fx(A9z{oLGo)Pjo|j#yo`Psat``@m~Vf7PUjs zd4<)Ux`e#!To##S(f(gl92~tGhG`qYB{a1Q^gT9pYJ8k4A=rX94~pNvggC`36&GIF#!Y~E29SyN1c7^@$iTxnEqz$_$<3<*Dq-^`IiRaxY zt`7NyEfnjpOa&!^#&(>-i}mCumGDNFoyQ+3!n^k21mV3(La@Sxb!#@}71&{64@0-1 zF=Gt#-4Vl{eOdF?JbZG^ zEH|1KYr3>5gv-&CIQvL<2DCM{xpiE67{CzARnhdS?5iAQpZlUp`;m;Ew)Gvd%wF^_ zWdTk(tozbAvViDntG*Wqdd96T=30U1V>eLR-kO5QV0E>%1Uil4Xf?9>nP7ouR%ARA z+p;m_{2PEfY=W^MaacJ9;}nr5(YX-E7Z?U(IT9&1?)^7xW< z!S@6FjcvzUBva?iXm$~eqYnFLQik%U!yC*+UUdM$o2v(EedlZWSVz$Ey}84*{DHZn zwfrY@t3d~DVsj-#%U63pTE1G1*YcIKffy2JcdOMyf!y_okHa_~1G~~ZCsw}@943lH zj)-G@T5dL?;ABKv0e%@N%REa&39=jQmJDk>VzD_jV^@=SAsS$8(~Zw{gBp~v5H5Wl zezP^40hu{0z*uvo!>5qM2Pf#pmt=;5n40FHrWjr;bmJr4zcz9n41gqBemgU$o#k!nE-XIb9Ze@@f0ti@pinTQ$%#V49ADOXbU=ku>iFu zd24Z9iGx!1VqJR`=*!t-mhtHaq%}LJ^L1|s8+${yWSKlb7bxp7KDOBf zY#3QqM$N!tD`bv@S^HLZFb@z=&$^_zn!ZBBT)o)z4Gnhm?>o`gv%KbKUu!+z^cZQm zHJ|w~twsh>p12Og%62L`c75E&=?$O9MK0u0%?@@kx7)BI4&G+`>7i6-29*4eoL?%L{#l>dC2yIGV$$4CW-AI;4!v) zgT29dzw5yxbOW7vX-0XdFIJwM;Vs4jL`&!bp5k6vW4m}m{V~*kq6OBY>%GDL zS)SsBW3P!SAGV*Zzaxd$_{w}t1Ie-WTJFcJX#C@EKC;Mn^0xB4mK9a^n}3 zfTf-is!^QSAO`RZxXrW0<^l>sd`?yKxi$%}U8(-23~k!C%ocf~P0ZHV2Pa8g=p?BF zoFtV-oFuKJlcWuMkYr2^e!G1po}S<&sV$r&Wx&zX*6_`cqgk$Z!~xS^MDnmMOH9zF zLG$s!z}m#X3+c3}7@nlCWcwmMf*M8>Xb~KEA^bZP!*LS=W+4Em@aSDYg}LAq zYd_R=nK!h62fiYB04)N1F||G$AK{5^8GAK&@{)F$PNf|uCh#4=8caVCAs(Pp2~GuO zRqEPp%lT(jr8aW8mYTa-}4bC8LcfwVPna!xtDY`wt>BkC|OtR)4#xg!7<-r`!XR*GQ{ zKkh|jDo_40^G0YFdhlJ7Wrc!!q)3cuoG8GA`${cvC$lOxl}AQ42N|k(hM%dlE~tps z!M}}3**P~e0nX)twY^aPG0JnWPpN|rO-)&k)s&BF+S%m6pvw9EvANu4nZ=Bt5)|j^}#!at9PqS%7Y?>-b)zj=E>ROX|+b#}8 zia8?S4-@*N&eSDjCC3soz7+cO!lutr(nSOznasbTXdypbB z-_$Yq9IgBJrNU6EvBg}AELFE!-EBO;KC4SRN_9;55-F|(X9LlrGoeSwOh;Iw;WJ~Y zsKvr?<|2$G##ZigE~AzoDon!+3Du@zyt~R$j2q1cGA!8~tB>UL(}CC4q<$9qi=Q%t zT8(Ckuwfjvd;`pxh^K&jaYGyX0XjmX%rBV3V5o+ij2zsNgx*yjP|IkUYL5ns8$O1D z{hv0XU=PoL0ZiyUzLaS2k#-p!><20&=Cx=h3%y)^vECq)oA~NJ5RScXm^k0hfZ#h6 zi$LxkvV&~`SWWpIMu4F=n7`i5b`7K}NXxTY0Dys`Y8$7=P5F15H%kZzZtXwJ|1N&Y zuOo&v3Nc_AeIXPGQekB4%%Ep7uPuzscMPLaWJnbWPo9 zi}X$69^xGdirZ;-;Ut7CKGd84jwFvPg<+MArYy16--=mcd&8F*?9@?q4R!4_m^HKR zR9%Ev!L*hL_;3dTmhI54UI_CCwJh#gU<`_|mjdqM*^7%GFmx=^aDKQN&s-@G)LYLNE*5;VS5U8AYvh0~spWS;J+)+I zJ`UMH33j-Y5C?ptqrhk1VJ9Nq-Kmtz3=;v{J?#&>GeGu%w?} zvadCkY+>4K`cIhnkd4Cc$O<9!3*jA$ZNf{U>xPQ0YROhGBY8#bcJ1=?6yy`88%g3b z*G;~X&E0BL0bTKy^f*~>85$qvE&^YU0d0sP&k7F0ADz5!Fk1@E;@acuVFp128-~8J zA0qn!5vY3E4tj!x%mK_dh!2s>{W~2RZ&G^_Cg3LqkJbntrT@?Z{p;XS58g3AFT?*; zHjl0WAKVAt1&d-1U7N+Vg90-3dVKkUiwHS-&2C?MuoYl~{JaXZ5qoWrMOtgqIXY*U z>7+vN z#uF?vxiDFQfjg~&oH~SAmA9OX&%gpqAkFr`y>i*{3}Mj&Wg3~eo|gR(fqTKmN_b$! zmZ+gojmb9G0WZqI#n2iG7pGF*9?YGMELH7>qvhHt8HB%L?m3=dA7nHfWruo;t06v& zu&bx#kK{57R5@F=`8x~QnSH<;C}K?tslnnx>M{Zef^e!*$O*LYQ8)5JR{;_6WErEg zR7b>0sZ$rbQp{XJ9nRq6J|zB3z9~7NE{#e5|x2 z1=L!M7~nS#$O1xh{Ti_PI#c*-v$cHbF`k17rk_H}`D-JzrW#xlfzDbcA#^^yQ=oGd zyApKHAqNX7%^T1I>^?m>ly=t92hx$AU~ii>hNcZ8gE0cM1L3lv=;>hkOU%t?HkG5| zM>9qG00-#MZU6RV#AC072|4bdd_^uH1d z=`M@7GQNYE;)qLcRaF1d8h17|ypRmpkN!@5vRpjFg%+)r_Lv2n?oQ5k!u3h z0m0{=lI213SZ3+iYDpVcXz$*f5#2r$^SVA5Jq+z&4e-SEP-Bs~mSjH)Ry$lWjZx3;?lhZeB2!bVAW_8b?j(gq zG&D6FDJ3mnrAz+{i?)Uie$MczODKm7Zr5*F7isBWv!TpKqds@oF#OGI^h z!T$0H3;G?P-S9La>yqs|vHq4gf6Nx@MHZ$5xm0!qudMSPKvaTNUiAFhb9WM~oOfK^ zBJ(G|G$9VAel<^%5HN$-S7%v9(}EJ=^PG&PigRlS-HV<{kwzRN?r~E}li1=|TwS z@xsNwu|ib3Y?vt!jA$nfA^ZSlDk2->3WK(6REdTq!=O(kP>F*BUA|^rrY@n>IMBt$ z3kzR{0bhK?7n%$P2DG-=V=^H_nGp_1tHi}JeT7Bt&tTrC4jET70`X=&eksbU(8TZo ziHq-rrwFcWHS?J#&a5Ge5`J$fShm&d!0)5+ooRPseB(56ll(TBKXbeTV^Y>5jq|z9 zksz0iAJL6o`%AX{VBghe){jY6JmPXZw7rJMh&8`#-ihj9{+k4E4y7N-c`e`!)Nt#Z zEPDlG2oQmDx^8zU(1{K$D@EK-F7zdU&f5}#xs#h70^y%!xdI(vm~|ZW0mQJS+yb3y zd~&Ee$?jL!_Y$mitJ^@Wh^Es~x~uTZ2Nm4^mAToPPPfnGqzbV^j=k6X47x`S)OEuC zLT)EQ|K@AcATu_wlDZ9BP|q}#b!%)cpsrja{Q{q3b9ZVumBC3=4^4_A>~yb*6|VKIjRy0AudRj1=;v zv4-HkRV06GFsxAl0nJn;adO&~fR~D54`osvv@b3L?#4RIipWFdia5lE64+M5}p>^-9#S zaDJ#$%P@|y*mx%I9i#7}PsQA?Q2G>ka~qlvK1$}7>u8v&1Wlz-6v=O+Sqs&d!ki~0 zAmAJ)PjQv=<(SW*xi(ZqEQds=nk=j|9F6jlio3L7y8U2n3oLDDkGQPMTTq@Frdcn~ z<3+YJt@9JMPQ@c3dDT;fVM6^A`P)Bb1T5J8?lN|1(|4frg0~dF42H+pH)CYHEUCl+{(?ND}7arj|kiTMV4(rv7F=bJs7;CoSUzJi{S|Lpf zT#V@6;KZVGZu8M)UwLt(<}buomo|5?H&~iiZtUX#knIY#@M0{;r*B|yYEz}V`|(;0 z2}HoedKfNyVUy7fEh`giSXf}`lxwaX%vZoTRRPzFMd3_&x+D&nEeIOm7P%p`dZHKCkcc)%o;LTs}{{_Z}N=xd{L4kFU z8}dY5NotD6zaK2KBJ!n0O1Ks;9{-}Wa%}%kQ#;xbe!{w=`TCWTvmVUMC51^#*oXDk zrn!t2C_@j!NFkJy_60*QelB6Rg$my*!w?hdS#~)Vfhv9kE`-{5VDLLC_$d{feh-4X zso?FGA(-o`NPVXYzO5R;N2*{yQ@_vV<77UL%pmihLI~dRgJk}59|Y4lA%d$_@NZKQ z{DlfWz|@3Y1YfIyUuEjI5sX7lVHgQ>EJtHqfC3!RIU@2H>{FrD3~QB=!bQbm{093J z)b$yb>M;&NIE~MZ6=lW}a8G6#TsqWbV{M?U=I5$*uIf8SqZ|Av-{Ze?L`!Y@$zag3 z;GG4Y#&up}kAFS7gjWYeim6`pyy5^BqI#FO{Jjh4T=9bpse8qKk1-e%pke#Vf|Uj4 zQ7V@1n%@?|ZX-wJ#cfpVN4kpCN|*o6fo(iSZ+(0_*E@`YJ7oO^)@+W{=oIjiRio2E zd1mTq{I1;C;PP)kmCnJpNR?i?yqPK)Blf$3w-vzuszlOV^H^a6H#{N0ZllCeq1IBN zwhI`c(q-H^u;$yU)*^grU7{~ zb=pe%#$$Y?n2-0RT%k*viWh1AOh}Tk$c>{xivT)bMfmsc07~JR@fp!dufYPJ|3{RK zhDF)8VQ@3->oz7pqV6m(m#SF0+bD7^$V5L|3_QWXHtonZ+KdxXw(DKSfmB^RFnlE5 zqx*SrwIV~}$dumrt!}LK|ANZBi-fMwAZZ>&-&pF--|SzS7HQiAL1mytv~9*>WZ*Hr zQ^WpWoDz}QT=PUaArTt}DT$DIfGrVDu)twQHthhKA_EenqW8e?7QEJcs|9GvCww{n za9>f~iGE1sSmH{BwC0=spKKQQb+P#XwwhX2W!S9k3id7trvYs(K7gMd@RXa|SZe31 z)XI^AaTZ0#jWIVH^5g$8F>jB*DL!wSl|%h7D3Vuq4UFa0Nd2_H!U$*DgW_wEFW^<$ zsgQQAMn0l9sQNuCIrf93p?(y%Y**@FwEa_$(XXT~HRT1I_?i(BEehK{^mbL`3$h-8 z7mSC+7h+6$6rG4MDTHT?Xo1@?CY|uDjA%zQ_+b@%n+m>)!7Wtq0}SR>L!|Dnf(J49 zr*Al8R^!)Tb#8R0Iw}ToO#g0YQ}x7Q=)I*-#WVp`4rNk|f1;AeQUSGKDeaA>r+OOK zmK$4K{$J6GufVfnc#rzV;{zg!CVU)M0FDL#OPZkU0Yndo=pe&!y{SwJLjK|c<5%@V zS{YN!%cB`YG*xga3bvIa$AM|)qSvdcMRW7LDQDT&neDB-+^M$!lT2c*rTzHsjcPt% z#Hs2Hz2J)(@|EIiF1^%NqQ)YhZK$!Gj}~Y_EhnNy9RxjSRXUR2Pk4#SKjec%s*?OB zmY`bd;IN*rl;} z^c9{bKQO=>ym11L`JU(D9-vIEaWk>A@?rKFCA=m_^6{!Bs!V>1)p3 zPvMu~WSpvQ@|~!|UZ5Tvl!rrkK5%-59`t1E-P^zUQ@fO^BC{R%ta>u8yw#T#A+r=; zS0qH|H~Bi@oHu(A%P$#C>n%Cw2c8#|^Xv6ZpEfx9HhSK-TkSh3U}=xh=n~#_8DDh! zOmVM&lQ{4mxVm*pT^|<94P*TD$)f#<`aap{ohkKw3aqa>f9w0m|pn%Cx6p_;f($f&Zz5iZ3lEbCjP=mVCVW|)*EwC8O zVpG_fdClra;*v<1c^N-)Xw1hhBPi5rt-@O^FpFB{Ed`#1`&%F@&f(BKI++4j!I&jc zvjz_l&bUBwEiFMRfow2^J9I0!Vi+K@Lb1gy1)A(a62mo=z*<6yt-4*@qpUNZ+iG*n z%jB~N$1I+OTpjhW8J#RKkuaywYi@aRt{IYqYuxxo`Hme$%8gBK!vtU}m1PbZ7#h@) zD&2|fR%3}Pe^XW4>WQ2l=`1)lx!$-2b0f%~(w8E%IZi4D+FV?qW=59K+$7{7Z6JH* z9xtn3s*AegFRe(m<|CLNRr)6mM82g^c0L6gDrE<23gN|gQ|sSn?%mQZC7foxTV4Gx z$@1b73{qId@M7Mdx}I}>qqG1sJy;kaWj-@j!>UJJTDKIOSKkqChi|i>tdq%ako1Xi zNGFEz@^J*dVRU%uyy!q*iD!%sBmV~Y-}jk}4m%2?gGV0~d>(_pRl#2{*cv?YRPgZ( zeoqBo)fd6y&O21tMg{L3jo_yc?2ygB?^Uunc(n{UZguX$bs6x=C5Wxy+D2;K8@v-2 zVDwgi?FU=8#OCz6oi_gf_0$ouWg}FR4bPRs+pQVrF3(@OoXl=Of@D#^mrLpc2m4gnBpO zqJaM#$Tbw^0sUOHp9l9eggJf zfTXf=`V|V!V=j5rdji>DP)y!(jLkd@m;*gh3)Bly(R$oq?B4n6Z`!43HJvfL_Y{Aw z`QOHx5VXcD+z=cpAq5CAyNObYBM#hi%YqusfgWmf{uVv8-kZAHoc$%WRvc`E(n2kE zmb{}DdXU*cX-z+{h6Sx4-J#s|U&#d6#elGRjq8grbHze!9*LX^QAU>=*X!W|P${Bc z+xXwxf&h!!>xJ5-9Bzc#tDwZFJ4?X-jFjT-!2kE~Z5EWTtS~2-Hr=6ALs7Pyd+XP% z-z({8Zm+L!#>ZHKnWYd8KVjM&;#9N1lfQ%#!s=;((}dxnL2w|~reBT5ImDq7uMyD2w4JgrreSq2L%R)95#`9q#V5`2c39Q>A*IT>|H_cGH zht=SVYKTg`MMJ`N$WvTUIXY7<&)X-()Vt%k;G2`?|; zm({2Cbv7u*POP~Od8+DF{%Y$_Bm01Y{w2CYli?+c);I*d7Bmmz&*Wb?VWWSy>}C+1*^J;zboj zdnr9uQ#4WQsHXT$VjDch7NAq(_iD9-RdI#NTEdv0|2;OxSY4LC#csm=c5-cc7iq#b zShMsPUurcx%oAbha}%17pmeyY>t9zJMX74N+qf9Z-B1lW z;!Aim>8V(Lu}d*UaBKnOKYwE?#&L{YV+(3F`!r`i?isT~Z~PwXLe{{wD=P77BXCb7 z&rw#M@r+iED9$W7`z)4ZqAV9lGAP>vFtly;=7-&>n7BgO9ssaawW*VdD->VsSs^HN*5o}F%j#a^#41Qe&e|Rc_ zl?mL!o~rDxuSf8GD)>Z}ZE)xb6@IURe`fF)72LfD!DpzNKZ0je?bMqQJOIItnbg2d zO8J}@ zT(I(op3H%gfJ-i+WAVSRmQ%a!J<#{|c_N-B(q^0ubVBeT1ha0dR)L!HpmXrwMf&Mw z*zDbd%We;2q_gj7OtIn){1kB|H?DuFs~4~riVS(gX%*-pr<0&{@m5WS`4;D$!St@E zd$%Us&fvW{xX5^&twRg!3pDm+6hxi23aXKPg@(t45taYE!C}}{n3Rhlad_@9Y~*`` z6SBO_h74v~@NN*MtJO)yO+?<7E&@ z5lsJe1&_KnT8EXh5Q7Jo=i!(CSaJJ83$@=7I00A8?~Xx-eyp_mZ@1)PDNA(f;$ zhTE^Nfk${36*?GhkML;9Rpj?z`fVt8hju5s7iX%}I-)veZz6OiLebkRRI?ZfMUmvx z6^q1NO5|9QREI~eN*77aKJpQ$m&M9UrOh_zN)J+61eG338-{X5Gp4X+Ti&KvxIJqqd8?6B7&CKRN1U6>q=l!pxNm@I zOUTy}y6;x=dr`v@E@>z~GD&X0@Vtt3w{r<`EyljleN^Ax!)LB5*oS-roAJRNJfmg! zXFQ1g)qc0Cx?an|rLH*BTZBfXC^>@lr|HxT&`TNS%U}pFN0E9vVmUj};+1Yo_>z9d zN5b!NHY>s_V0WIfv-rY1Pl?8OFiu?OXQHQ)cK%q#b$0$|AG5ef=Yx6`U@0=~nn*)b z12SQ;4vK~J4lLGD#|RZ3J5aUy7G~3Y53R8*>#~P>FnXx4_th%(nRpHNMUM9V2f}vV zqQW{va*m}ZtZ{V_5G6f_Lgb?K{9qZ|WYO~nB_XFR7kcuTXUIuUxej9q!mlhUn11TV z3G{pqv`9+NlNi@Y&uJeq4<|iSAQ+_QOx5O%m#TIZGonzeTazMi#`q%hCw_&dX4IM4 zd<+$yc$JFZCK4a9Az$IQg(m~#F!CksP5KrDd$eqrFZ`_RPp$<~ajBHZ73R{YHD5)1 zWvA;_s0McUwRlGJmn}n+qBOGLWI2n+`A4v29IwqryPUL{ltz?ki-^G37}`{l&q0Yh zC9in-49rAB%oYn+PF$E+haZSDLFQPZOhPa%{}wWMAcJAq^d>y7DLjziD?NN2#y~ZG zFK(#dL&GllD+Vxm;p_T{s-C^ruDPv z=ApHJ+x`5pZH(PJv@G}Bw8c1R-hNa8bPO2 zT2JaC!^qiht!6v52~3saFAY{Re+xH#Z}5OSOnbdZyWICG{o|4m$Z_mBP)~4A4bSX( zHziY;o};*`jPr!DTQm&}@-Y_P=hT6hLTAn&CP%2@oXpI8LLJ<;7m>D_kH1eT+W>XG zXK$2y3=}faj-mgsQE_ED9m>`Mm64~Eh#cloA;Gm+7Ya51`FMOee^up}^CK-$;>bZw zn?4kISp%CE=&!~);AWY8uE1FJnL0VC&0VOce#4t>SitF#5p3b^PD|!AjPAxd11x;r zC1p9Epa!s%ZOJ^?sR?HF)n)k`PAkrMPWc<>0Dbgz5C^tWS zEWSzCfZw>#wgKf>G<%W?OAI(=N|7?!Mv7!{Cngk^5mVfC3B_%DR~0vb%?cF`2jh`7 z@L+R>wg8kDrZICUquYjPv#R^euhot@JOlP z2D6b(0_C^zH%97x=bLxDV^4GzH+(|~5m+%=b4$BV2Ea$eznukw4X;IEGX?A%^Fa>m|4pfwepA_TnIr`Bfi|htXRXTg@s8f9T9_T>x%@3EsMZfq^aNl?c({ zO@h6I%Oxc13y+YkVvpqW+jpt7bmmqbOpEY3j`(jeMew?sx$TBcK71>$%Xp& zd7#57#B!m-{3Fpy3wh9ezoVpCMH&b0fJ z5wy{4ilAUEEZ zj5JN=);S5J`3|4-U`K6E-*$SaS7!Cz1LHJ2z-92FPStzqGI$YY->Iwg>oc$mtmiMs zr5qS0ntU|mXzr!r$|EouFN|VQ81Z=whpuq$$xBY*N|YMD4~I!+fxfFDdpAH(lMwY{ z<{Ur7gmpN^wDo}`iK>z&I_cSFDV~dy2(i4l2;u;W=UtFM@fRp4u|xK*dy`XqGNQ&Y z)a|yl-dy(>ujl|5$LTBp?#=dv()HvQ9L!?dP}Hr zba4VT9!E$VH8#M+Um~hEnWGRjjv7Om`f#byrvk`q2AlTvh$rBqZwdhq;@nsq0q;ae905PNJ2`I*K-4$_mN50<67cjlk`r*p z8z3P3pCHEsYP0|@A4*cLydr6mr5F$nmE?uNNs~O&Op;y0o2B{m?(sCwMRR~ockx(X zEYr3{NF2>C3nr)ey4MqE{xLosHqD>MY%>|tPC;hjmn@r?aXN(o4dGA(Y<*2q0?uqE z$%8j0P2!3saiHI+l3$BY2xp!r9x#*lU@{vJk zVRQ1ht()Um0>Ko5OCVpIr`Q2!mauce_3be)3(eMW?K*;3OE@hYA|bHoqwbQuIGydW zH$u1oaXunAD8&*o%oFhuM-H_)IyBb`TXU^|=2~lMuB&jtTNY?Sg^ywHgv&FbV_TSe zyUNOPWrch)Hxe)7R(aFL9ceF6w~4HX+4^nF3iH6%x#!V-2+mJ)O7RMOjaf%a?swp@ zZ1-+8SH8q5$8*94^Qh57}#d7Zz(~>vsM+jY9(^gUr z54UOG9Fx3h(~w#C6%0G}`qR<97{k57g&CBcq-Qru_4H=@A8efe~nLv-RifFNZ#tZky&_dn62hGhskP!w!Mx=`4cAf|GAcFnp=RI zS`bf><53tWQiJsz=}B1>7Zgipn_?+)X?1dneDkjaiqzxNVN;~n^T{c42Qmx)%e43) z2|eEBHGu?r?11-g&_g@q!t0o`S)B#x|}oqVwx>fY>;L9i@%67jO4NT24%Nlg|2(OJTH{jn z58Ro&{+WmwSO2}wvhk7npV&p!e|zWT^JYO?w`g**7BrcC5jCy_=QH);;?j}0!j=qjH~s_d>uk3#2|r@ND+xaim?8X_ zB>vmjAWP)m0dHFT3k{K$JENOq>K48E<{657IyJ-+YKRr68T)3<1q!gcka7noa z(X1m$=F1#1LWSq3#O70cRr|{k1Jt&GM_(F^^F=rjdfwKC#4e&9*!n5tg7AA~sEyYb zo6J+6Vfa>a6vsi(<3{;yG_S#L_|l)T)_<10KH3cbb~`H^^gkpTt5hXWxF~s6FbR^izdc8yOU1sAR2!UobMo6_W&oE120(dL{vtl ze{ZXC<>J2qz8g-|<}N}sWMQZ0co3f;W8ATrBFNdPj;`uSxId!R__41P8TS(Bnxmga z_dM~V$VD^#@>qU+znqVR5R9izO6Zra2#M>Ln{Q9vFWdi~&@b!oDXw2MbdcRIUaibz zr$jm74YZPR* zny*7F(G6WrbasP`uMbmTEp{!+WPEz3R8i+rE&2F#8lr~> zt^e=i(BPr2&IZa5g~3r!Ns=H^7qb6O*=}$$SY><67_tQy=#D^mkS-QA+wE zvvAcqt9`)MzxPrEaRJc7A7i6P?&;b90b8iKD*S{aa75*vUyy64aEO(rJ=2WF?x*?F z!#kVI@A>Cz{`rD`R`Sns{#nXDwfyrg|IFc^H~8me{&}8%{=q*_@z10D^8o+c!#@W9 z1o&qP|J=bpRs1s=e|UO@rvp3L4;=|DMuYhu4o|@Ff8&=J{w&`UmF2$^3?VB&KiW)Q zH(GgJW94;Ovb?IUWIj(i@(~NqxQS=g=maa5zgW3+kl#kLP14+sWN!VCn`u0RKLP%k zfW$+Q&;1c zZTv(AzPK4sm5{C@Qknf8#2*j;xberXLjteNu(F+EWvj;1_-uuA??rho{BR8EetaNO z&GW7N&bIP9mGALgq1Di^6dO3g%9GuCf<>`#5OlSv*USF+vLZIS<#UcqAjL-O$t9f&483K4qnP$VwGTnuGfh_&7Y9D-mce=bxokG|(-KtKGIJhH;zHeoln& zZ5;N{0u#UN-}N#K#`iBS{;V@kMqS7!%%68J?dNRA^T}5A80Q35ufS2M&n#JHAPn9| zGAP8@W@pyT@qDHuV;pmd#98Nv^R44~Xf#ekS1ZGYWBDMi2havG!@(z1i+AIfE#AWS zcqXVSWQ)(SSdtZ{pDMeOG&0I(2uk=Z2S7b#y6%nAh_{~Y6k8qDY;Zh36MatXn}JqM zy;e=#Noy*QX;@s!ntoyBNilxgeC?hn^W29+7FN9*?18f(;((8%y1D*wp$-Z4B_2tj z75tPyAYsoV9mR&M%vlA)dJbQ1Jv7{Ho?=x5;fYPXNfm2eYn6F<(lRSp!@oy4DlwlE ztbG1r<Y3s`|4BzjLtU@4F*44)1e3yKw@>YDu^R z&*p}pB1L$v6^m5%o2#tPf7GY!=!e?H9<=7&037QMrhoEayJmgLjzfph%)-ApCBy|s zx!X7u9mLb)B|5ecOSZeTtXB4IO8WHGgQMY9_MpEXyvj~TtN)-^+5d1{M6Scc3Vd^3 zWjk=pZO*G~HM62uSsHQX4O^HvY1XUkNG8DbRvduiElgZH%SJ;ELwJ?F1KFSp{*BJz<*RDuVcq4_&7RavgXynYfpTXk z#<=|9dzHPJc|~s2SvT02u~~~TpQ=Ij6wd6F2Rz3q(p*w!>XK#niJq8<*sBXg{mK?W zR>WBt*1zdj_H;#iBhi&Fyl-WRqhUy57zc}BUj+*|4u7&CWW|+2+|W?&gX8_lUWP<+ zKl8u(lN|%RR{mrsP)iCGzJ=X?UQ{y{o6j}v2N>XtU8DH~MtWg!?D=w0^ILE^c7zEL zCFm)BnkRH>G+$>v@pSSHFpCh+MxqE7;!1O)=x5A<`W`9$>f|JpR{muFb5}GI`jfr> z0d!liu+#m#UAMu^bp%H|{X~W{6b64ERyEtm?*_A5((1x*1H9TK&F>cqzX2-r~1s<3S5-!Dm+KEOaMv zM0tC7ih=xG4|wntf3MZ>)_%ARB0KH%n0eb;GMYDdlDQc%nZaVj(fzNGZBq%WH%Qwi zX47uvIkbSIhc3(T7Vpu-o;)Pzy;<#2s*6w+&U+9J3y;QS8FJBxUy#QKIrud<1ymoO zi-O9FfAvlA8b5hM*8>r@!f1lovr`)F&CKk|@`IBn&>3~j5R5#qo0C;tl&;-7056CM zXOjksWLLFW(WDk!z;oAkP=^*y26Tt9K-Dx4|C_dH3tO-%HC1>qKb*1;+va$ZbrO&# zBO?v_NHrv?x4WWf4ehwVpG=Lo84rfGu?@IP9l$0TIC(i;4rS@{23+yP?6c>&Q}l%! z+vtry;s--AO$yxfS<3RqyTjTokuDpoPa?h!p7QTOgSsOVvlj$`Rt0L##9PC6k#$jA zCd7FL`<`JFefID@*t)4ATQox1cd4rp_92qzMKGl56x=5)a)1X#o57t<&O-yLS{wD| zG1D>j??x}E^X}xw@Qu(Wt@0Ir(oCIwhlsW${R`$HeM;R7(g<|q{a}l4z1@XpXCXvXWsT7gz`YU3^X80zHt9mU<`Yo7RI~Q!N^DklBYk}Y|q>K8!&Y1F?Mxpf=O&_Gi8}~qe4s$fm^6A4CiPyboGt{LuvS!&4WW_!N~=3 zsnHES%ydm{I)F0A9qE~hW}=wC)aw5A`!IsG@q{L|Zf8z3b~Y`@Mif{jGH=5RO~3}z z2Tp69;+lDEZn;sJ1!LLhvh@53Kv;~29;4N~zajyQX1jA!Q7lZAyK`IOA%hRCQ4)*P zrjyz5auCJBp9fxCaPrlzX#tKQrj)aC-qa1Q>dDu_82cdHT{&4;t*S(B?4FMo^ED3r zp{HsQpZt&o`6IYpfUpHQ_~;D@W14ei;28#*V6k^J#=`W?K?}~FL^L=F$VlZuth1+* zOT&-YC^E^hB&w=Cm>75sV8%lx6M_4o^cr8o=&gASmN&eif7PNEq{E~ciYGh9 z^W;guX(+y46eZYa)N37du~H3#(dp%e#h(G><1bb0Ig2#4*pqp$LKgAOBNMQBU>3!m z;kLK$a}bbht~>IHO<#30(;{yx?QK#?^7S@WLTbt!S~+rHO?tB?G>wnj0Zri%=sJEa zkowVJVNDYjvSK>IS7=@$ECPF^(E+Rh%ytEM&|-`Rc!yWp2d|r@69D$_QU<<8heYuB z&*z8Jq}qR&AD+MxmxCWh)*ON#I?9lJD1PWUBMCoLPm1M-T4WJRWvwQWANGxl=Z7Lk zKC$WJ`Qhq_UJ=U=yC=rhZx_#U2!yTBaxAunI9n#A4clHnU$l0NFNb7)^*OZ%J$@I=HfC1cn zr*9<#UW3|F^$2Fd$m!;)VY*QcSeT5vWLLrB(30%v5CSBkoaygk1&;rwfYo&aE|>Ok zPzrX+CH$l=ZkT4pGgiv13RVu@xg8OVg(!N8OAl6Y?!tn-`CH7Z8HBPMW<>M_7>XP7 zxc-hRr0ICQc$sc|q-(v`=nH>p(Qp@?R;&7}Q^sB?9YzHj{uwcag+vQ=t`OcyLe53RqoO?4@jFaFG7;Ni5Un~8G!LKqniT(q+sFA2y{in*Q z|KKIAf|mY61)cg27}Xlx%+{9D?r2R^|A7d{$rF%93($^(J+bf@`{D6o*8tu4oF4PM zL71Qn_Q`_d4jba8y@x48xzPwCI&jjp%aac?bbC}FY|tN1{Db%-f+v5S?*BbayT=dp zRX4s-erW)3(0R=MXcP?=WzZH6J;LqdVX%A{BBn;<--l#pAQ@C+7|~Q|^!%^PY$Q`D zpe%I-pl;CuPt#U`zX4XqzQL@z1+Lq|@bm8(<1W#SPqjQ?63{u^LaX}_75f3kN_*t{ zf5?LO%upF@q8w&7dVw%vEc`jzv#n~I4rfsQ_4{cPHIz2pmxHSw zX`n3H@|CY6UeFaCO3;k2eCd43@NjVf?tsu0Uvse;U1WEKIcqGt58+n#r2@+soBctr z326rJ+$ic-OS{a6Q5{JcmAe83)j>?_vFK< z^6wu1LB#tF>?B<(7U=!J5pU`aXdzq~!BPQN1fe2ym(-Boa-&DC2hJWdJgN1ZeN#Vi zx@WZXjt?T514O@g8}xuWiv*O8e4dOyss6(V}dMNE}GPtM}VVs>*^JT5Z zge_T+xLicA-~R9#yhrI()t1_pM)5oXaulZRT9Nyjp0Y*CbXo^34D&qJcbX7Ger5dL zGTa7lDn3_dm=^+&S!>xvW{xj`O`yCy+!grW&*ubNrjz-_f7M?~(6H#7^Z%m1d~9{c z|7`u{T?~j3{pD4>DE;NZ(Fyv?O_fpo<%&!G4E<%RjK&fDr2@ljQvIb7@nZFtGw(>I zzl<6MNpR>duTdF@)e>rw>o33D^yla=T~Q+pC1w@Mi>sN^UwW_!q4sZo9@SrN|5Ox| z6OI6bw!ck+4>H)&Umjm2!R;8l0>F~$@G`g5icsvvVMaFJl~DfUFa^9YdNC3V0NYluThFi@FG1Q6B2kg zfhQ)nzVMfHJ$0>`AB9S>HltQ);rlp8H%iynm2Sg$*iiM8$GDn9xN}xzkKd8;1FO2< zd-D$pY9oJ+9~-r4F9TCO?^)2+5_&^A{O0~ruJ!%}8*pPfdqcS?k?BuMPw^73)@QwE z;m@!pj@2Kmb+C$N1<-?s`7yg&2)Lu4l399aH0oO-OGyNN-59;Tu7ve9QQzWqzH#3C z-#wx6ST$Xyr+(CMVq`t~!g2$n`2+-DRA)+mU5=-CjjzlTnt(B?_a2V{7qtB_jC@k{ zDY8z*m^60u3)pa21~kGEVhv}kySQf_1y6i6|G+0t(6y)G4J&`R2loBN6C8(O0NsiC z9cW^neG41F7dn?XLSOhJ=)T;W`UBi&qAva7r>q#4y+KTOk8&A{`UQt}+0)M$deokB z_!0LQJ3Rg$_jvQaO5Nkh|J}cS4{E1PyB!q9GnT6l`0HV{xYOw#qtj`{^<%cm3a3#E zU&aGl9fbR-fvpdQFGg&4unWE#N4bLoTftuaz}EZ2xbaB9KCLwv{wc^ql)F%$KO3)) zh0sut|7UpJZj1x34?=hpUjGam+Hv#EcZNmrdeWbQ*B5bcimtcMMpcvIbsxlw#p}tw zWO%*cCgkV9>n7&^hw!>^_@9H{VF&hXvx7S4HJ%@}DA4TRF%^<*5Q= ze^PmBM7&seI`ePIuBegdKPWG*W|scLCP4pzkl6cI zw=YxrPdWsq{S6X)kioY8Q?K+N25%Y81}Ex25Dvxr&B@bm*E{4XS8|FK5s{}Sh*8vk zz^Jx75%1z!6Is7G9r2ozr;O?;!{GmH6#SoYdMvKDYdJ;5#NYVcLyMSSa&*UiB7XJ9 zxQiB_vZ?eI6Y*945k~rmN3?_A;apCzw8URpkm#FMwg>5aW?V0Nv}s(6y?DAOtm=!U zXE7IVeh^JB4rA!3L!8F=<9u$4XQHT294jZ^9LrJ0I4d9V44J<^>P^=7AgiamfA4Qu zHC?^ID=jqz&cCq!#66$FNCp!NEFa>~{FD!I+{BhfMtz9y$5bzp6PaK!D_N8RHoWmV;nHCYepCg& zrGo#>U>(8sdc5c>gOd37#NJ@~DA;&ZPF|IFSKFN@4v!2$H{%!@uB!f5r?347Mmz@& zui13S^^nOB`;L($Ew*N>$G4A|7zIBXPXL8m?SK>ishK zuJz(5V_k`7@ZF^cTfzSMHNto1q9|MTP{F4&c$EsimZ=TJmR(iwNeq4i!4^tV4<}5ymYhiG|(ilI?VoRG_ogCb(gG=}!j(DL3iwl>M zbr!tfMAKEIl+P0GI;lko5A zc>e8E8|B|8@C^RF|95cU*;fhw<}uiU)k!M&76xaj;Aa?Y@$XeC_<9EaHZ+ERxBC_U zz63@|;NMy}$?Eo*Yaq^jVD({z_-=Kw@~$h$%5;$}2zwYT9Cfj6vv70nwGW_43KYo2 z>u^{dp2o2TQiYCP$I;#V2;bb|R=c*_hi+pd@Pg7g{0^IqzhT!$+1Me$+omZBya2(r z`G>*b4RDxctpkWWNA-K-_XYFGG@&)nGvG@rmZIdp(Gq6Pu$-E zL#cmT7N}P2--915K>Ny(b)0i^yM2ZgA}_omrpNRz4X>|8@fg5txw&1Q7;WqTOu`Hrab&8Ug*aPFHP%r zrEAmM@P*pxr+VWCW1GJ&P0qzm-TUp|$3<)ir>gp`fS zy$k}TjcWhoV75Dq$Ij2-5x-qu#4jCB4NC>;BWfEJ^<*pjOoroo;Tsa~?%ee#gz-mP z@xv;-rxm|Fpcte&5P1kl*)mOXTG5EaRaMtcuNfFzpA{Z%!a>J$`%7?4*^!-Gj?- zw&*o8P1C3DV+W6aCgdv6{d?Pt>!PQAh{%~tG_y}CADM1uYw`~%5n0WIUo*u?dQkNn zPsB|71t&6igln=)gA{SR#apof3rezAv96hFHVp;`+Z#R6jQo4DwdpXsl`+4w9x2t4V2Ew0n^xCG+;2l0%0XjJCEFwcXpL-Q4?Ea)7j@D?|z@?V$O zD1Qpe4~o#~rz;WkFHKe3+Do-*)!f+$!q;`E(1V;!-Uaf)(S+>&*`jVcAbplv)2jcy%o>v*S`>&^re(21vPBWJg@ znl%6y>;6Z~DdZ1{1Az2P?hzy*gaAnhDDZ^BG$F`+6oGUDu8}SDfqx3L=MeakdIhOt z;mf(=ZYn9hL#CtGzJ-XeAFNO;5%=qYK zg)2`At{_?03nW<}*T$Ed@gBvOe3t!%{@Z~)VUmmpZ<;nm5;LE2i6uxw& z7H@%XBECF*DMAl{FRvm88(-RER!y{8=|Bq`U%thFGoS83fC67PwX*P~45&kVDTg+5 zXnZ-I<^Lgk8HJq9_1hu$q4YL52j&IrSO|ml3rm^UwuVU4WDda;L=C~Ao+FVEC|HPE z8cQ+LzDFH9^yMBqAF_nnLS2CO0jLZ2lT`ja@Y_<2S9_F2tDeDP7}wNJSiT?d#^Zax z&Hsdg7%IGT9)oZ{9(JGkd-Zli!SCt`f_dgyBp9G)P7sLqA}&YHBHld?+>GK|tMFYh z@2$gk;9YPuRJa}!N0$8yEXc;fYD;Nsqj?L8YIwp?-FvMhV?JbEew)8cRrT|^s;cM^ zsp5Zr+utM(zlBoa=YZWGpvzOjPx6Vh3E$5rfJI7pW+e1`V6RH?1)n5zIiDm&Es>dU zN)Qc~a9$FR(^cnUHgY14jG3;1?0vXFdSN``fl9OPB0$IEdf=a^ff=}jk>kR|``T)p zFEe)yNES@*YjYXAI%)7r2!52oa}jLm_3G}mj{B=cQnyUhjU6zYb0gGolaZ{BHAA`d z0e*i<3PPK{z&ZYgPwY(JvL2Yz(K033U>=FzhL;)8pmuFh=2P;zf`7xKkfoK(;ni&^ zv-k?!Eb@ro@FGyzir28wPVh?P<6`@|^U?-GT66(wmOx3Z2L8mPf!{(Vqw1>EEPOsp zY{$%Jy499Jj~MJSK9QLnHkqT-J+HCCIn!%b4z&LhW_lefoHM;$un-wP)B6G6WTt2A zaT~uyr+T-Kw5NJoAu`dap6hDYHH$5Rvg=cE`;C444pfq<|8igCN|$QhPuN_eFL4 zxG&Q6GHXAGy>8zZ8RkVztnDC*<7@%6*ybhP5BR2c{QZDzM?SISiN7CkAxcp5oY?yT zt1phNNf*{6;eJ4h)bEh@15RKypwGtL4>+yd2FJzD`yw6D40S)?MRZ7vf z0IYVb2iam)JJ#R>uJ%W60r{v3ggSS1VUN%lfeSylA4=oeIO~CH&l|W}fYT9+vUCGy z20Kr$BPZf&XQ=bHCmw7vyMQA(JmP*&ldqNB^~6CH`wk`aevB(TpJ>P@UWyGojS2*7 z_Tw*(<9FLFs}cPn*)C%V7vw*~+@kt@&Q()f@A1N%FT0^P)&s3?RTsGYo3Llp9}&Pc z?FYd=BOM{5esWbc9Tmb=)v8tI6Hu6OP1X0SmC{#7iv|zok^qs5Io1`#sY}-5Yee*j zDj)ZOEj1lqp=}Jqx-)=?M8o8TN;9tV%LOZZ$>tYX{7Au2%!fP-AXE5IVh0VeABNcv zBkYIK_QM1=nRXJY`2{b0p2=tY<1uC3d=wTS=d(Q2>E_*1CwFjoZizVs0dAacDJkoQ z#kBd)Ahore*7-&oT!L_9JpWE6R)*}}rOE(weHP#Gu^xt;|@Dmc7D?gbG)3brf~qum=Qj zv}prY%lUofZAy7K6=gBo+Z-gK3TLyZKy->5 zSdCZncHI`prQrwg!5;jtwjWMY4~xUqk$TxiJ0>JzotZBc*lJEqR%X>K z4taHbrMl+9ThTCRVKLS6t(6;TDo?25s~Y-QOwXiWwi&fIUnyg+0UPKamh$nk8>8-r5GfLKU~Y+$72_@C4Ixx`#)4K3 zIS~}WpX?-pf26HyuH z03R%BfSs{0RtDyRe@K9*p^2DR013lWAr)q=n_Or~1132^xi=jueBlG(S>0G{hTez9 zBF>l0X#g(=&ng53@#ll8WLyzRYt_FCa$tdHVM^j;+_S8TbU{Vfakrr^?6^w&nhQ}t z*aU0a+#_b$l$&BG%wagnvw{|fkBI7@;Zq&oPjWoB#xpDNA`}mEI5JP*EG;kvab*2R zVS2a$?@{eEavseaTEL}4o_O4C-Co7E+0^=M%Bfmwhrxra{)e(Jb6daW?aOq5a==j` z#=gu6y;)_ztB%{LB?^ZzK><(DybKOOUxAS*YGdX^i0vP=G4mR$jhu)5R~s|0h%%&1 zkA#%%7^K7TMVcfjUa18pF)P}bc@__U#KsJF1$Bc%DI_3=5YY4I@pNkuC5Vp}gPEu|)pF>?p<$mWU zp|Y|sGXUUcXF~fjEz8km!NRvLRz^#fltzOOVPEDAwgiQ~D8C!bPw|^D@%1IOFB8F& z=<(?!cv9Qp@bsgndwN@DP2CPX28 z!(rnITt+6~$y#LP#0Wj!Uey)N;R$w*9DuSA$bdCo4E<&uVJcME!i*rw&bK0n66U}c zf>Ab{r67Fd1MGn))GO~nNAXiDAycDyP~a{RQKloF4F<6mt3E~w<}k1if1AwxIA@zc zXoV=LCDBZXC~xS3DA)DD4{{iDQ8f4vh;oe-)@WYFY9h&$q}5f360=_BF&e2KSU2Ty z;?PZC!OJjs!Xgwtz#PgDPmn2f1Gm}#jRY=jPM~?mzfH_UdE%Fv` zP~Ua=zPFg)L7K=!sA?is=_c6oWUSITR6>k{dEs2lDAYQM&hw2Msb*ehz-(1d1eklM zxRE-)m?2@CMzaRLda%159Gj)%@(QhH-OmQb6srX|4>tFro{AakqpQX9)t99W@0e{+ zUvKbqFQ{5xe86``xv|Lus!>hKqT!??c*Pe>7uaAu4pBY+B{}8A8>+tb8n=kq6GuBA zFz-fPnKe$jg?YZtY$yU4U?w39coyWs(e}9ebeQu+ujPnA7r6oC4W6$XYt-dsTmXW7 zhEus>U~KmoIJ~{fo4=j5&H`_8{-x|QXwwP_RJ75s4$FD-a@f0@yM2huE9Jp7v<&)% zTzvJ0`eK}K>nYx*1^$8bUZX`h8|yWCft~Ka9hY-+JpjrKWFXdvvTzM(m#@NuyPV~? zaYv`NY6aXauu&m* zD(>;D)dH!gvp2uN6B>k@n~P~K%gyu!dhoBfC4@SaV2#Mi2bWp{Uo-pQ800V^%Ny*q zM>mS};_X!{Jm@L^!3@pM(+4HH>u>{TGTMeqR`229KwI}r4If+hUNd&%c8&M1yj|lx z|6s$@s=W7MNuU3wfa7!n_9pHE&P41@z~e+oj%Ags8s$S7ty6{h@uCVlRTb6&g=Lk^ z?7+gbntb+7aQvP~3qT1^F{UW+%F-164S#I@#|}iQSld$Drb3vxFEHp-00vkw&My?)}H>x&<=aNq5sF;dxu9=d~xFmBoG2} zLsLXlz@S7$39>?HCXnDpHc|vd1q4yVg0zI9Ac0MQbzKD&d%=#1ilU$(5C|k97Oa4X zU;*wDF%+ej_wzY3clYk@1@-ImzQ2Edc^=rgbEcd*bLPxBXW9)7bG^SF%uCyt9sfmM z+GpPF2T7u-yr_s`2H!d9*j@2ymUl%`cYi|t?!JV2Ss8mq<2Ev^40S;=g`dZt?C}{{ zzCBm_`y}IhQy&9`yK%nh>s;^8IN$VT{PEnh!&dQbv< zjQ%5dG21*7^oTd6;)TBxp*uLL@(vE8+b7tE#$#l`F^V`vBsT=>mGN0T+0{8~e+hc_ zH^k*YH7m-4rI}+agdEJC(K`jeDn?NT<9sFE)FG-XeSPAO2b&`fdVU@yrpMPiB}X6C z(sb&LrpQsPytJ=!;y=ktTbqRgTCCBSx)bYsvJHw+*r<{X!of_>_N~nFmf-YOLcLsH zLS4`+E2Cs|kg^B|$36`%K(=guGT6;$z|+tg$F@9ekBa%7?N9OT&+*m4X|7gBb9{Z$ zj|SHRKjF+it&R_6)N#2kIfwY7E!jZ18_#~RHAjQj5v32wulNJu)IB6Ce#Sw(&x7qz z6#Q)ma3Inwf*6WEzl&=U+`a=4G*fgN+33vXM%fyml~JeBe;j}Zj5M5hB zw*y3^Q8bXL1J^>%ola~Ad8kTHV5ASe0%Uai&{hP7A%Ihf=}OhyjFTS4*OLy+*@K(PHQ zAO_B(%*Az;1uS>r#MF_QGww^-zXCE~2x5F|vW!I&Pdh%;H!=Bmuoq%N{EBy|K<*Wu zv_rhzbL#IRre)x2GPm!|Z4hrosxpjxmYSx0f92Yd(IQ_2#O&|A!jX1Nvb zK^xmK_b4u!2(#6d?B{5p8bBw^C$R(m1KymWVrQjFT(;~z)I9hAo(T0sc$ca0# z=kK_=fvk%Znmc)epsoKzj_)uRz%?4?A6|(c=AYXx1^+BT6dUPVgH~qwC!Tf`+;BA5 zRggumh52esKjEpTK|k`;cw|IxPl^li6n#aJJk4XbwYPAyzZ$nvGC@ZQhUr^vj z^Fu*8kr2Pa}Oi?GK+SC;wqVX{iXyuxN?@|V5} zS+?YILMspUPPrwTBGdnJYEOKCmpR+aOYMgbOunfec1x3psqP@g3=E(u@#PqXC>Ba@ zKL$*{3)lu4)JmlvYY@z}TPWa$rOK@#VV;eD*y`njK~$u1zK%4xnv^%KNe~G%}CBAbvxCtK$7eF^^1gLT!n1QlKdblr}fNV$F-#BX6%H}JSu zz%>{#tYofCwQ`PX7YfStZOF!A=kPYj?S%oKcbTZ1{ETzKyCZZ@7vo3DCuR!`M~L0~{keinVG(%dNDJf(u6I|w2u z&b;=k1Z;_<4y@J!r+t@z8t~rE2K=IjfzcLo4@8j#pQYdrO5i+K;TSm}mi z`!osAkP2lJK3K=2B`uqO4-;k<+MuiH7Ov(_do{~GP}RH&wVBlnw6bh5>miH1*;QE+ z6jjX99&_ROs_QOM>6tEtUdn-ga`zzS3b%KB61Jana?pgptUgcnE}O64ghUXRDGJDe z7Dom`K5*asVd!zUf96R3Ko{Kf9GlA`1Fm;}Vn1$i``wtHQp}QM^+uquA4Uj?Pb`ws z*m>A*Nr4`4o&6n0S*4jJQ_ROwnQZaIzS(1tHyr+$S7zXv98`>XkjQPt{I(eXU_d9f z{F>FOO}NYGu7nNiukjH><^#=92YW*R<^as&;#5Qw#Lh~yF&Rnq7Nn?|*Mgr|!veDv z7lRv^&a4jgfr1j^5%@mwt&$2q*AOW=Q-4ln(PYU=v-~2KLYhFb%2Ht~vmQ%U96Og_ zHU2i2%J^H@1>+B55p>vYzCKTlzdCuU6K^M7Q0ib>n;3`J%WtLGOXx)vW<7fh^|dNv z+o=O_`VZ+qMlp5}Q-h|WVbh>#KeO#JA)|7ciur54IsjAgV0KT$RGf~3Q#*6gcbTtV z3=nf-D!u`gV=DF)90a;RBGa0LIUoBD_<1>bJM%YKGMtTbITe4Lx)rss8+Y>;Di2i5 zF%TZ;S4KeioA~7)#5>c(nPW)a2${_!klEFZX?F={pp?aQ?4gVN;0W^tSXmA^cz@hL zD+8}5gcErzld`Lkcja@)`vLgQ8W8L?tzwW(cY=Fy?V29B9hm!893TRE6comIcy767rBW8m{{vE zj1G01^_T=U41}8-PNT&eF$ZO1P9%PuSzgNGZWD&id|qh;D@xUG##M^1XOUJQsE@S9 z?-YKs6U=cEbHE&d-{9HU`yKW%bKea!wV|@FhST*JS;31BQN_+w{G1IZNk8-F8^FZR zuxGOb(!t92aVS0`Ii1#6gmnY;W`;)VLNgr{xz;~7W+VH&AN``x@7Caw#t6~TC3r$9DV`2T|tQqx_f}{CC zKj?C*7QqC3DmyjHcNjJ&u2RbKt%F%~wZB%it9`ZNvopRPjWdb3bvS-+#rF^ud8b%)lyZB}pTUpNZMo19MWxruG~|eAJKTa*q?DjQK?6t* z#tMUzf%#{)WN9B_Eb&jYdzqZ5Bql**ie4_W{VgpW6M7HUH>UAy>SCTkMOWV(H8IQ7j&^58BUg%F8JT`~!Ua_$Vc>fY0NHAQZ0z=c>!&9nqvF3-W#6vL{+TpK*%>T*1*~n_lzJjaXx;+& z8pSIF>rTyHNB*qyfO2e-=TwptbCKj6rz8cFVWn&(_(U^@5^xE2pwkM1w*qXw35o;h zJl|0>Qz3{KW6ar{K+wAZ{Blk!mS4zEYhp30Uat;1L^h!4S`fuNaIRCmChE;)y~7;Q z;$e&n3C?u{^DstDf-iIg`vLy_HGpe6fsNu};3p(m!z5-?2lR~M9F^o%CRvRn){0#d z?N|uzL!VjUC(#RJoLb1mPQ67`ikSZ7LJR5m3d&>h&DoNiPxQ4GEu+%B5WggGGyIy9 zE_6ig4Jl@eIZzk#m{rUXvw}HL!>{<|c-$lyY$1W$Q@{89}g^y~UQN$&l;AmuL zy+c*KB>NIk4-S|MM9Ibb$NY`WPKR;uvJiTu6>C|0un~Af0_7UXieKgPL;XowHjtQ= z;k-c{3}ds+$xRdDg7a)iWv@c;aU>;p5W(~|vH-T;kHN%n#a=1$0}ToewUwP@OaG^i z$K|=f?{rw_&9D$}Wd$zR34(KMB_sh;*2U%IJ=kNa!sWpqbQoA+cY@lr6~sgDARS!j zcApb_7am;f$SvlAsd-i-@MXYq`@m7pO{!X12irqf9{GeKy3|ZRjt9pBuEY4`c=-B! zbd1*PwBBxj&!Cu-Bi|RO<*g~xZZe#|qUeE~UjR9eo=17TAH{esUaA;j^I|3E`$GF6 z$=|ww$uU0h%SxZcuXzw<2Y3Hr^#ivo2e}8CoYWW@gL|>b)$DR+7{9Rb;gQBvnztO2 z#`M;oi6=p~lScQ$5V|it0(8IsSk-okM)%cBh3;_{19bP}*X%_!b2XYA4%e}_K*@^1 zs@qlvXN9_Obw!qj1|JIdWyKX%k}Q^yi%3xmnqb6@D7{YtIG1uMJ6OG_(5mEVpx7%6xxcVV4$V_ zWF9?T%1u$_Ch2l75Bcxx<$nTk5>ftgWVXs@R;&Dm;qsqB63|Yr*U(LhBNR=VqCgu` zm{GOXWEh~K1O=A%gEDP4Dw8hVa2mq3Rk$DAuVxh;508<#e>Kw-e^>+Ay-PO;X^h6Ta?A-ox?vdHOxH6XpjE_>S1Nd^hfK%k!sVz4<124(%sgvygjdbE&iqLfB+ih=8xt#3A1N& zP@lrRJC569w-Ovs_LtH69<5@nLziN=%8y3zHxSoB3V3CgkVho`EC}IXNBpPb{q@Kh z<@z19-WUjsIMKUd&;YVnKNa$7TAI(IqdXakpvCX7D87koK9*{oBjfnxW;F9MHHR(B zYzQAku(&>#_hB!o@eLCRFWSkgP(EHqg)K_9mlgZL=YiFWR`h*|_0xjNE*ea!oymP_ zt;}y5k|2HP^r3!Fi)wH^SXAi#R_>27hTNR)a<##}q&}&c`dXIW0(LjS)d^@MlL6SS zEFmRsG5gwlaSs*LiCCktwu@!T;_j#Q$eUi_HRY5_G0%S#oe=O!_mq2Ep~v{=_IcTd zAKp3|4soB?BmL&ZzdAJf5Ge}k|l9OQcc+I zDkrx2QQ+Zo7z^Sj)@1_T4frbaUXA~eu^h!b!65$1yc`HHle}~Ji)RnZyz>#NR_=X2 zl;lH(Q0932;%5eaSTus4An5jCW8dD7ImWykdzLfK{7K^8CEc418N1nhE&Qs;yi#bE#5Bp0|v&>ic zD)aJ^rucHXq={g2B=WigOE~|Tw=fK@?Pps@--ARD1;cDEKyF#xSON^d$PL}zC3-R( zLJO}%^EL6SlCKV49WEnyDZ=K1P|w1?t?2zsYA2JpB_?utwGVeRC=XjU z936bB#3l!^?2M!kgtP!^wpLSd0nsI(C^0kF@&vXZR$un>hoiZw(IrG&8udLd!B%}lEzm^t@0Lg z2a?=Qw413p#|;)};^H%F0^P6x#Bm`&}qXb(&Hw_rG^&^ zIdO&1O`y3RB8OmuubHV4!(pgOoPQn4RYHMbOG)~EI(LWRlfUB`9U=qJLgoDsrz*Fw zdsG_4PALQ+0>P@tgB7i-F{|eJZ*4*Yj7?16FU_}F?up-xRA3d%y4A@kP0Yr~fe5Sv z^p&H-=($_C0Rd|~*tvFQOzmb&J|&1Ya{OVf0eZY@%)u0US6%%8Yek`&3ZKD(FB z&`grsY9BbPr+mu_Q9JW?8dm6-@v6~#YvtLO9{6PH>W(~OyQ4GOkRN)bz+LL7u zVk9z!e2ZD4ofioq*aHxtgwH@aSx@HS8T9l>Py8NOsXRop&$uDs3DcKC6VgPKsl?(?LM$4+`a52^1K zgS(Q+I4USS^tmFOyLNYYRM0hwQ>o7Bp)2oM@xlYy4F4r%*bLS(5|Wv&Pkx{ovr$Lz zcNli!#|HsOVY6mkSfL&WOQnA*o|k8u)cz#u%{-QzzDe&_+MrvuHPIbkX8wLJTPFMW zMuO^ih35&=T}B^r+gvU2(xl-t$RT5HsZK0f#@U)~;F==h@iNM_+I?`Uikpczw0r-Pe1R$=kLYsbncv(T(e5^^Pq%x7B!;wFZJy2az71?hWV;gtz&5p_|EVwP zGUu>iQ?=U->Pc{QIBa@JglMibikBe?)sQpOe8P=f(019N=;mtM8Xr-=a!64 z|C$?2WbwkEcqs@eB2`b9g=mm@KkXr3WzZ)zRhr4)U|8XMLI^pjr9>-QxxVi!8Y&h> z&wm^2t&;`Qm>=(j*FhbSQzCxt({dMSV4}Akagcf2HfJ{wdsrqJ4sb!Op++WMG z`5@wZq=D}XZWRY3Qn0mROMxk52jVypKFBnY_!eUq6KJTBYZ!stxj@c3?;~yjb7=v| zfuZ+@IeHcI-6fki%+(tq^Hq{YqnV`A?6Qv204{PPu@grzQkFD#{#G?ESXVd#{tM8e zVFr3%VP(uNCk=}~rYGc6{D<~Q{|I_;(cy|GG>Km%?&PW%&^IH>Tn4Jcy>ZK?T7$u#)1GQtNH^(%>AB!n~D)iXD}N5ruAvc7I*S-!3O@ zz=9l(|IR+8O-cJSPkR3B{WU4HPb&v;|Gj;B7s{f2%4|_oqak{gv>v-PdnB4Tl=(; zB>5Ni=^E(sP;_p9Q&*HJOx`p=G3EEe&;M?pzCd|`F;2w>Qu1$X)4fJY!Ul5}q~3qC zP1jP`q1Jz7n+_C_7ipVbcsHlkux+q6ZrZEAobQMRd?4~Kmv%W!;o5RYweW;H z8uPriOB2AD)|}g~Kuwst<7Cdgwm5Rm-H7OrUHUP)O=~1gQKhAk48$P~((o;$rApS% zysR&&7t%={1;CnhzkG#>#V(!1^iFo^Edro&vV0Dv-w!Z>#@MBE5UHl$E-hwyC%g160kGXqpc~Ak&`r%G5c;HcX$6S@`4GuL zA-nXm5EK0eyYz7oQbeiUF5L^%(B&b!bo8qKWS72K1$6`*?9w-+fr%9fq50Zomrf$v zV|r~t6XySlT^e?^EB}~xGJM95mXyv^a!b9950)CAJGq9x zayjM*w+|<}x`*C)EvpWlhi^++?@A%_S(2Gnm@TibL&aLT&uVjici4k?KbtG;ElmG$ zjujv*M-lrbl_i{kiaS(1r`M}}URXS;eRbiac1V3B|7>GfL02lpFVG?&?ig1Cf~6Rk#1BH`!-GUACvF)R zO;JuOcZbAzV2}JYfSy=qEZbeN+kv3UxzQssvS>Y4nVWHCjiMqHg!Q4AeTa8n(Zga)>kx|>Go~M;psB= zvM&cYF#}=E#+QQ*!nx+{X2)a1U6ot$su|e7@5InB3rYWf@AhrW>cd5QoLyXpCVG6u zgFr%$FTh=pxM}4)Bdu77nwD2+r1hO?qz#y3q}@8-NE=>aq!p|)(k5-SHL|!JvZ0xQ zZfCfCKjTz}yLsGhOton%@N~v*cgAP=4Ny~D3W(`_AoZX)Ju*HksF?E0354Bg-_k!I z_oZ;bAIHSlnmuwlB-i`fZnv+v1@;6-D+JARNR7ZXI6K4RPHta4_mFkg-Um%AErCbh}?=wH{6)je?Y0* z>#2V*E;xjxW&XAAL{?uw3Dz(_L_W8V-L#t9 z)yH+m|M3MboZ+pXI)g*2Yf@HOHmsm12Ivb0&~GJ!1vJ0o;ovVSQf>SXejqn506$`< z0H;^sh^{;^B>SPan-?4*Q{Y(&|3wwE%n5(;D}vQ3u=Vwq){ys`F==3*ew=e>u4?$uTaApO`RD+Te+VGI<=>L)$2CoE$hG@$(HjDAu)QnrI{@F6pN5m& zs0Ih2%sYT0SRoIKz00_-#tiOe{{w`C1?xTjJ5;>ex8D2$AZEWE2Q4cWxczrpAn+G+ z0n`$kbAxnqDfvu1R3a|;Kd2MI3-f#MdL#n!7W9NUQlOjiFU$392{s3ma?Rh@ssr3g ze6M0EqDPT82R>EVRGaG`XcdI}V0A&ba^|Ptm*^?+B1-GlC^o zrr1`=)@;g`6e+=*nZmoOh0S%T{fhcZ&|Kf=@(%iUA~tmuJcrvz*J|EXfYv1l1Ccpr~6p%F_ zYhWn`Y1#yEo_inS1D(!hxFf>ac^KUNBu)wA3e)ei`obH{$J0K;bSS!k*(MTSilQ*S zR|WE$$C+Qn;1fnz&QzqtBnTsnLp@u}O3Il?gvXBul8^5dgzsY5kFbSs4hg)C#a-f+1J`D9}n_cNlw$!IVxUBQRj4`&_jhQV`Yaw)nzXEvDrA?vxJVd_IY zH`I$CvCj>i&2eu%T~<#r=%>qSONMpMPnV5tq#r*Uw-T?QRMZlESRFLombLrd9)i*yf3H%X2e)QzW7X2}ZAHV32k^I;u zA4RE!Ad3BaX4LnbsBg+}d-{^7?{)TXZ1j*j#rRO!ZSLjPLuGoMd?#LYtHO7f4(tG@ z=OQ5Ql$m&^Y^B@&P8sCQ>MR_AlXuEI2~Ba;YeJK5Gip`K4rHD12Khi)HS2-0xq+Nk z?B8)0%)o_0~SH}Kaf4f zqLiWD!wJT;?}6G-FZLf8MQbH^xSBC-g^C2f6)i*%V{sez_8+FUIE1==P(5M_J=$1Q z2L)9dThCaO3$m@jycHkxr{f}*^n~1xF_ZG|ik$TQ!5%0{^ex{`ciKv0Q5Qw!F03Hl z^y4zdPy9)NS^HD)Iz|4o;)-U2DhhzSOkzBtFy$Q|nWDLPRG}@{Y|hL zIDrH(YTEQyh?f?j$)lhyw1{@LSp#=Vnl*yNDk2&6?SZ4v*^|JxQ7~+s>(qs?!LhIf zfSpfRPAu$kz>*0|BP?)Q@BW}7Goge7AkjzaQ66bL-US!GJY|pUWV_qb=m%Lt>7^jeNJ|VF%1o`-1QVPTjU8G zkyjr7h!&o-U!cxGzch-E5iedcn(@8c-?fPco6wCed-DPl6HnkB>fHDPxlOV6#GHFo3J6e9oHs4 zf+@k{uaC=<$8x@pW&P8z1Cdl2yC5$o7wEg%~%VLl5%eDJ37F zV7tHC89a&zp$}S@Umq1{{1XNLqJ6tgtYabaQa0Yl zz7njd*7{xdA`I4?hadCH--L6`ZUBqAfu&&u<`y1vz5-9U4&aMH0x2qX8cK7eNd zJX4=CfM=_4@}M~Xm3SllBX9u}nBq$O`mckNuE($}ZV@>G?#2bVt1;uiSMi-YFbbr* z5*@Y9-SjV`xIMYad#I{0jgzwbzz?~;@4&uU-fdO!RwSab0)0}k$;Tpu1D-&VDtC*+GvTjsN<3=E&??b<5A9q6eaOdoW#tm|NGQVqY+ zeu-u8qnz@tSO_2nR(bjJwSmw>mzEuWXDd&d>D>l>plfCs^wI}eNm*umT(0+6)q+Cx zh2z&_q!+WLJyyZCb`^=EMeUQ=%heK;5?eU#9<&t><%(Zb;{07(1x<^exdUUqE&W$ozcz4F?f=d52=%Mbzc&6??6b3=|Q4ae1G4@8lbsAU$ z{e83${r$o(!Y!@IEj|VQ14#k?li;Zed@pl9p}=1%a2dfv00uwXB=Pux;)Nsql=m`AI1B{c2>kp1IyUaI=FXp8cG1G(Aqb$2(iLxu+M_HR@sIr2T zNcO6#jXlj$pNiiHYas0+SxVSqE)Ay*n;}V(UevMTc}Q;=BC0F=u2#RxwA*HyI`h7f z&*F&gr!A3&zjErt`&4XHz_oU|!mAhSf*VDn*+r^WdJ7JQ04+;zNfx~YRzz5DxdnO) zFYf8IyckPDOTm@=yCV2F@`*eo_K-qa4LIQTyY8<@jtgl6(D7SaX!5d5Djt?Luz~g) z`d}~-I*B&0Z3~)|aVNBrPm$WvN`AaUwd{gWQ+DQhSB2F8m_#@Dx$2;GD`gm6$tdVn zRF?cHf%>!22J}gG3UsSgMsaI23}m`kQ|+wZ*_%#eswHHq~u=rsk<|pPAQsB8N}!$bXxk8MW>aR?JYXJf4id732GYBmPk6)GN!e@-$p02 z2?pf3jQU$T)dUx^_x4e%RApyrc7i&aJk)!rHtE#6Hndc#!8`q};Wcip*=Z!Uxc);r zwGT$p=@;`PbixbXf>9mOxtz7j*_$mo?S-hZ==8ua)t2?)wuJaeT4GE~_K{A1xYNpv zMc1-TM$v&8q|;7+dw2X{fBQhkrHY^WvFE4_Yk8O)q=RsD(sjF z9jt3o!DCVrohU*LeO=z?(1j}=h1?Y}XB1^|iog+X*_ph>JWgd~F5>JY+iN z$aE4ZQ#lVq;MW}rk(|Djd>je?P{H@!3V0m{I0q8)e@*xv$b`uJ1rq^VNZ5C=ut9)5 zMc7BNux!BYBkb8&815+QbTeU7Vqvua>qgkEfSK!l3~TBY)54m1_37d8CR=GVewP>lEst%B@Mj&G9OKV=WSbsNBA285ps?9I zTKX)3;!NqojjkztLfmGvUGW28ky*V5VL4BxEW(L+be-!-NJh$wF)Sw@2`6bN?)FSa7tpg^9j^Abhj!~8QV&iWt;ieGh5`K$gb8AcO~tU zlc-(Yz9UXmNhw7bW7@Y`ls zA%emM7XkJSVSCA7fzuYaVJ~U7(G|HMQJ~Xq?1?rn14?G+?=5C34SGGPXyRq{No`_+gZZNyM~)bCd;aa%T!N$SuDdXsaF0oO zX7v$wgGI2+hRamr%DSF~`yhWNWw^d$TW7(%#HT%@?V5gD#IEU&buyYS@mtUv;n@Vc z`oR%i3Pt?mRI(XlV8RxxLtRL~`&xMiD~}Ptd781uC{oTwoDapJ4XoXB+Yhd0_2(m^ z+;%@}xFXsna5S|LCmLNhl-;XD8JUPo)+08p#7*h>hCSr0WVRAmcB(t%Z#0TuWO?3I z@G!_aVQGkMDSL)mFGI$#v z4$qcX@%|E@pM<>%8Mp}#H|6$Bl0(?m`l#=#^fg(y7u@$HUh44p6FPf**`4CDGuH6_ zyX@28b>36)q?!0Fn`K8`q}L7bQJNFLR8cTWug-)G2r=C1VBN_U!>tY;y)PWDg7}cW z7}9s#K8p)+n%w5XkK#htelRyX+WzJL_l96Bb#d+~;|OHno!au2&$4N#Ac^A;r)P`We?l!kR{_zZvlTu@8ep$rP#1bMMLqgK#KN1PosY)Yivk?wNdhAP0q)1I{GNYsE zlW0u44aF^%D?kFSu2>W&eHK93kD(8gMA?5W$C&)C=|6y%^cpXw5H-nM_ydR}oqUoW z-YhiOV)kMU4#;o(g7NmTX%zE$K8TfmkxLn{+d}fCexyE@7_E=Bh?GBPYWaiwN*|-A z(WY;miBHbce7`6U%QU`E<;f(jQ>CBaJ4O&v?JXfC?%Y?-TNluOL9)W#su1I%e|~guFmPeY|L8 z9d<4P>i;PHFf=`q{smMEJHxeY4)`j%ZwjauHX|$xFmql^=ZRpAXM!fNnJHMeT?<%3 zER2gwYX~!C$lDpBfQw6S5%yUO%qSkm1_U|<2%qNwzfQr26aE0;mO5HEAuPmi)?r>O z7qG?mv4tP7g~uW+`Y3M|`lqtK-dHu(+HQ!DD@xX5T<)L{*5h)IY)ao^o<)_(LDt_0 zF+_y}LpkoFO#HWu|6xz!a%6-Sp$6yYpHeXGFhBSlrC@P2QW#MFCSV(h+Ma06rv?_8 zLZ%>GeuaWt4oAV3%ETQbQNO7EH;@*(}rMtCnq!A>tjyFU& zD|s85Umgs@@rD;*b}g%SQsaj z&k6e-J!xJCHj6}9CY5gy8kEo~K+m@^u= zFQR|M+W*Lzk&j!D%1?@_LN}*2OweiA(9>)c88K$}=6vSDQwfq;`;2VwyW(WAMSk{$ z>=_fgEH%~K3TZ~N2M3EXS_tgJawv|2T--o`{FDT<5A__Izz6c2tEX>-EOEf95zz^B zx+4$V>_asndsX(e0fG2U=3t2*k(jmuebp7W_0&&g4>chLnUd@h5Z{hnb9Ra zc!o&FsD2VHw!a6|xVH=fXM3qNz)OR*M_O88Y4Grfh{67k*XtXhjDN5{Pxc14q%;d} z;WCP6v#%T+(uHWc+Qpau*E2waG_W+Dy9> zk%xNyt`|RxT$jA+GjbF+Dn+exe}w{QIZhB0z}aPVtOOIZtaDFCYRhc?v%AuRuLvO? zxqb^JVej2^H|lk6+JNvkz64XeB;D zHrmK&DIS8AwrGcRIWAj;i+%0QVj-F%KanDb0)N_w@hFl{Gd96#d1?Y#5Q?XC>=dC2 zqBdUCC%W!%oei$D)la=D|J{*~Rqs2kuWlhM;93F3V>yLTJ!0AfgYpTeJrGPafW6+2 zqpVvrB@Rt7=gK2wuII2-kL}1{F{%moNsrM1c@p0g?#Gp?KVTl^n~K1`lZAbxW9@u} zxS+cXR zWoH8Mt|vi!?P5p7-)D5d^)~vOx%;xlXo|yz{T%i;DE`yxSj4}(35ZWxEfgP(x|<$7{r&VKEBvpCS8CiTFD#8i+SM3F31;bVS_8=z!~KSzp~^Ug(5)U1NF` zh4_NfSj68L0K|Kj3ahxgDvJL~>@K=!;S1 zD}TuHNcj9PT24=m z0o@_{uRxzP5aAF3qdVjW!Vby!i-6G`vW&3JfSIxVA?}c8nc(Bt%yfrLA#6@8jP8(I z2`h?)(H)XY*svH_$Q_bKxZ44)ee5*|ZvnWa8qXXOR)gNRg_qmHt8L*Kw(!Z)thJ?? zVhg`%3#Zt^b8X>wZQo2D#Et)UHE*wzdJ4N8bxdc_4~Tr%dV^k zl}qnEflmjr7=yd|hkdVx^(A{xY&$>3U7z(K6D;O`@=hI8oYN_ciYer6o*o!>4~rPE zvyD+)K*1x+X7=4GYMk_hUifwXbH>72^@`TyKURo`+vQYvVaIxS7M^>$j72KV>ximq z6!F{whHpY)$Epbhvmuz4L!Q$ilJv1i#`pE-nhBQ# zI`!yBaf;I&*2z=cce_-I8?JXh+=JrmYUpB-@*y3L^?!gA_?=1P5(?i8PTjc3RO6H3 zfDe>0?(^b~Zb8Ji-@?GWLsfqWWM*MUDBP8t&y1=0!S_|or|X()<2N`?Btyu*D>O8U z22(&R`n0fP&G`KG_`ix#{0gFg=QlE=R+=jo<1?~P??H+nj~#~mGf000FeBM##iXBh zlu}Cdno-n=nJ>YA>~G|&rSn}Mn{Somlas_oabxCtk1=+6&D#@rhga1gpOOmU6O#8$ zLvT7+%$MJ@#(Zh;hC$Z&DGgq03-`8#AFzdIAZ+=^ZR6{o?Vsp`RXxs@zbd9|r$5^) zb(lQu_R$#Z53u-B7NszyzP3c2|Ldz*q306muWlXG=g(03?Tp!UA*wjlJbMLwEV+#97?=e;O(WZ9@1dV@Osi!>*MB;ujF{FFz8*S7#{12eBB1_$wHQr$qcmZ6Ez8c97^e5s2UN zHVdGAq|GLUcpjqzE<+>!2dC|5#9<#@s}LXeQ7pypz6OY&t`M)K5r2)vD8zqXzM^~|cb{149b3h~SS4)JN)u)9N4omh(Ro#%-7CPu@sL+wO-B5RDMIP9ZTg?OR^;zzmO z^ztG>{HeAIaaS1edmx!kN%3Nh_`A&Gz~dRth&NM+$7{q(Iax#_4*SSY>&x%*EQ+Og zS0Y}qP!Rw5a)tOr7NaP>;@!VN+@mehgECLWQoQg@77)WKw=)`jjM_=@WGBR7AMI84 z(IX3E5x<{{VyzY8Ei~e#G#V7*Nq>j3%wzTzZ^m%rhN_Nz0r7@JyySgBd|?}fcrO;CDE^p;;Zq>~E{jIhpUa#Ti+EpR z7|SZ1B|1{a(_%2wC4AaJ(zGf1V0oBSN7nuVfe!c z+VU%V@NyW4dVTyNu@yu0D|_(EFnm=cT-k%eU?A%J1H@Jg0N*nvQM`Vtkr?Vkj>*-|I~9iHvJ| zugDU3fUtS7Fxq^h2%8xTqs`Zsu>2TU$mVkq-p2v1ZN3JCw{d{CRr{{~Y6W>Q< zb5@L&L4T(oPsh7%ut@z_5TmKoYQ7YCKKh5BoUiQqalCZ-DTI=xAGebknnKAzKVI^( zmP`)%@$-ZQT+4tDg?MtTq?);%(Xh}o;?r4UG~!|XIK=_+>O}mVw*~Q6E>VbQh7m6o@o@^o zE&cdonet*0&vr(;e@hVmy`@5YI*U;h|7ibZ@jmY2*<3h~P{;$P5QP>9$2 zJH##h_$ryJV=4ai3yz2{VKg4TLG47mKWmJpcvwH)HZKKIuYFSxUvZH_yg!Rk z6o28>zd_v6k2i?P6ie|zb67wOtK>2|;CdLflj1w6=SL$R){n=$8B6gyu)Ji}Rfs2P z#9v}D3UTul)_V$yTl(?2CqewR=UG4u;xic?aBW5HL_FOI@vwfp_>EY^-^D78dHowg z@g5f{itnTtSBPKwcZgg1@laOnz$$+{=ZN@vMh9G%XvD{}#%PL%_2YO4#1CSX#+>uI zApTgILOeZ;_*j`lPC;=?KYmN*tXNiYIU|0KL`P~Z|G$1L`tSc0{rHXZ(amcxKFu~U zlo$Qj#{_d_T-$p^^yA@#JrE0{e%y<&k+Cr9$1cM9#K1!OaRb8JIKZ`j{8w|p>pQ@; ze*7Kbf69=y<7^ab{rCgIzjc6X{dhLv?*ne>$E`hKUGr*N_$phtr!Aap3-_>v^K9X3 zY~fnAaJns=YYU&~9>yWf7T?|$?rIB zWNZINg~+vx|KT7+KC)usRmUINKB*Qi&V2^uIG)PLK&^Ufe6!ICzj|0HJ~HdDV$zTbQ;UF(R6~2cpSbmi%z4F)`3nJX`Jev6sJjHoN7Da zgmL!;>(N5$T8+~$w0NR%g8FyAxB|C{``=pldK*u;!?1r3D@0srylxI;Arw?~VL&7e zxHG;px`iw|S=(B;g9jIjN8Wc?7470ibc$TtdGX_D47SHpGKY?gpPQ`~nniE;IPCX( zmwrF%yiKRDKd*J9KTnw|BIVy>lNnUhL zGD#&F#3YlQliZ+^bYhbJ&Pm#;B#oFP!#PQPmE=HUBstwV$sUn5oxWv~eUKLpE&4(w zd6!AnIVX8jC3%oZ-f~VdLnXPBN$z(_QgAyc>mm3~NAOhuw+PF*Cm^RCrBT@TiSpuvye|Z+d{-n1T)S?{v z?+5dbN-(yt z_ccsl&J5eKqdJG}$QNwkA-3>jTlgA;ZC6Hx?~@Lnw-{zK3A0oCMcIROvARm#=8-2b zdf=0Sg~89?sGda+K>K>h0$L(G(ifpv^?h7q*!5TxolPO0R zZ}Y2x$UD?|;fmfF(?oz*5g2e?*jhEbf>U>N!y$R9ij}h`auY=b|zJUB`zo`GrvN&Q|mlw+uqQJHIj5LY^ADH*Y&Ap&AeZghHX?4EgH{w?2SPu zkThpHwFm}jFUVZV(ugfoe%HgZ(W0E$4!!mitz9iko9Y(bC7Os-+-TIO?Z(W{IPxUR>_8(VZGwT|dMf;s!VSXePFDtQzw8uO?_i%iLHCeZ4kj@p|tLAj)7Oi7^z|}>Myit!jvAcy_F;z>4WxFYdv!ux z)uL4>+_6`?qjb*syv^x9^r~ed_GcqR4n>aD-=;a!;4{YKNEjB_$P~k=D@XS#jD6}o z*ebJs7VK8a537fjFYEDHpu(vni6M>LVlER^JeKFW33iwqY?kW*R_R?eEb2-kORv}+ zwp-QNh9amCV%IAB^u@4!`nZ#Q+9zy(=0@6|%06uetwL`eX(>8QsC;Fg(x}w%Es=0# zpHlD9@KVuvRDK=RMYiB%vxU5`2=}x7Pxl`kVaqI?88_EgWE)v3CW@xqHHNwjr;Ci)T zI^nN6!1ZdwZG=yAfa}$UD+wR!0N1Mx7ZBdf0lpqw1^lZMe!c^Ik%I521$Z?F_~Qy* zPWX0=KWjB(RhzH|xYHKiWeZo>!a-a3h%H>z6)tC^E&eWB_;*`)jV(OP7JkGQJ_li& zw#oYexc(p~Lt>xdziWK ziNl=Qgs+0~RnxKrygFtb9ni1*j7uelCfOv`J4#|fipyybc?Z#0&@H&*LaxU^a=hNu%%E{RvR0@qe9i<@<$?Fb(ys)%_X69 z*0t%pzy#&}g4R;6z0iw-A{RYyd4*g>g&M{AT4^>XJ^|OA*sj3JhlUEp@e);ek}<6o zhxsBm~@&gy_{Ofu60y;e!b#NQb8b%=YZ19Uv*f$9n89IgEy`NS6)OWy|j{^nURp-+|M~ zJfLITk4nNG4&{Luz-1&jiO?cZN{|qjvzwQJ1SfabG(ctl#S@`946g-C+sd>76n)v` z)%TJ5&hDDlgoPW!>tfXHXtV-=9tX=|G+g-Afp*ZxcTi*YyE1*Dofn~#n{CfSr)-(w zK(9KMl>sV|sL3eX(OZ+n{`(K!8cn0C#U`mVU)0uAG>tBtq-kUsS;|{ekI~WOfj4U< zO$uN}^8AcOk~~+k=qT2Ls=k$48TLQVh$T@Y!1O&cm zngfBGq4VqnzF%s^B6qYsDDN=-cmBIx`l-@v#x_8=k0$UN_b{HDpR|#$`0o*kwtK3K z;+t8Nm$!&U9*4{p`OVkx_+|v?*0!nYfa9EgqdOphZ(OKXH={b>OC}GvnkTBxaTYAL-Q=jf^+#PiZhpRcF%b;Q>|DCDmLT-sQXms+3Eie(l^FbAL_4vkp7u}Sw7VsstDn0xaGRO2jek< z-=dg_gbjjHKANyuu`r%bzm~9qSQve|?FqX+7Diw0IfQir%$z$urczo*$KsHnacpK< zM?Vu57Yn0xw3@KrVurKa0sA^(pTxjI){&3!xqw@G(&K5C)?XT&Z3{24g-dPWw`}3z zw(#e+@FH9Ic7$yffO`Ke>}z&X$80yy%i0+i#^CEvYiCJKAxl2IaZLW;+is0oJF7#* zS@}ZL%mAJ3bBs^>tSh&MLp8n@l5cSh794PW*@WT=_kT=9e%lN!X|WllHq#0cIO46- zzQVN8eitb5Z=t^Eb-Gc7qVyFsQc7Q=LWfC&ul33#0(|zLNEGcb3w3CXPhE4br)_o3 z{k?1%ZnwuY^FLg3zg==~F*l1k9XpBKnopK>zOyWsuxL8rF4ebD=3*#Er0JY<6-_6x ze0!fHjXet@oGzdIy10xAbk`HM`C=ifv=3YBjX&Ep*Wvr~&xcgNi?)ez9gpYV&=GI3 z(|#(##h<4E&=F_%cjCJvPL-$O8yFouM`6?f)dcxYt(qTzj9T~VCQ+gLHQM4+pA&yh z=Zt60O_Y$ZD|k=8+=KmJ?&;^u74pMG-_x(|tzI*l_g2^9E&WexeClg_Mok7j-7S0q zt~xsYdd6Rdc=J-}MLS8wSSmW27-zmTHk#bB33M1?(_>*2JRZXCjD^uH(~7VjF|d%} zNg@1Fz%94MtIaLJvpV>)Ej$Ndo4^RIx9cY>oCJnZlzYCi-}t_`>#v58aeq!iuSXA1 z2m~BlmSgSh!5x-Wwr-*f&~Np^(u9e^Fz=%n+T+QvYwX8%t{O+eono(aOT7#;MT{km zEr(+}38PpFEveXJ?dC|ppmYHN$|WByhv=q2*1S$l+wZCi?4z&!s=;N#ckhi5G#9De z09A}>TWK*tsBxfvfz?R1@>^D-cCp_sy?BZS7KsJ4#hfFSj(vr!m8_7pApW9(Mw}h5 zqnhPIjcnF?Gz6lXg=MC_(5KO?4)?}3t2Gvp%pdNN?rESAzmvr%#OD{V-cum{j@Tw! z%pGEb#3DXogd^hp7#(oE1)>u1L!6eQ5r_49y+VBIJ+X*Sz*>>nl!)8pW~e{-e4f=G zoi!6?hnuxgM)4_{^$aTpVkswS))RL-Hfsu_u^$9PW$tE9&4ShWB8>#U>&*$V&3X~b zKju{vPSUKeZOyt(FaHf^C91co{9UuQ>tkUQ+T(xzxx>Fg7?k(7Q z70Q_Y7H+EO(X$q7K<1e7Cu!DYwr0)LYk-fj64k7W#t^Gh^wxUP6ZF1Ww6xe}?YxTx z(0+>;J>M`o;OdMTnLB?1KBJq3g`YO6S;xl3HtSD#O3Y`*$>>?H7w%fJ7=`%g(X96r zh_7bRsQPv0QHE#4l@aOAh&NJ*2T&t(FQGCVjX1V~K243p@5**SyaN&cb*v!XOCz4o zVie*Zi6}h<;w?4eyG0L=rTF+e*`OGT50+^A>}eFsTODFC%X2?m0#J-y=&sg<>E71YtwhDpZzDM{Ei}fB8jN)RzJ26 z@WwH4G1h)2EG`yCV{J8IzscaYmn$1@UMK96SQw490AcfDVKml85jGPr^T-`!hKPb` zto3Aq5wV$RthFKRnphZhriO&IjfGKXI=UCIvtnQ&o#{uyk6`#%I@9Zo!#dOFw(wS4 zc(yJ4wJp5C7JkweUT6!K*}^Mr;ZJPgCv4%Rw(v8ya1C3yqb*F_Y`Pu!Dx}|O|Gd-Y zBco_FGKT!~pK?{Pem?k4JWDbe_2&FyOJU!P)D5N|lCFlJXVMEo zNjWksw_+W!4G_U`U0fAeV)rl29xeNqp2VUYv?%Uh>M&a5R5xHjz3MYe2h<+1MM*A= zttH*F*P&f%*zxFt86Gen>)<69T0~KwH^wZwc?LtmY!>l z!VZY1M+ts!Vi}SpT+Hc8p*Bk7_bE`@tWldQQ=IGy&=Y{dsui%}!~ln5HtbSv$O>(G zZz6ctW(w((FrlG2;Rvh~zU_!_#Yn-oipF;$XDNm63X#vJ!1rR=>s4tUl$k9S-@;oh zd@;Uy2KauMS@jWV7U zi$(2|TVhdbVoc9+Ms4p1p!UiLp<)>p_}J^0hf%v% z7%ts*2y21tw#h6(an!0|2tr$n-3+MZ$Zc#3IOz!TkfXe449mDTMA0x7IQ5e6jKv4T zfyFR|#dwXyAx_H*i_U+CgsQLaB5>wdgLO+E$_3Tcaxa zh$7f&e}}4Cq^vZvPlD=agHD0!I|N3d+RT`K5URBUsvGYFst?>LRDG+uqUzb4o)oG# zi!?t4hjH5+IqXT~A%`^u%H*&!iF&{_5JeLFDW?_Na5=}AKApOLz|~C;^0_kcMDFI1 zg9BdfCbKV1$$h$NzgS}^)@re*u4vq$`z7^z!Sh1!7o*@xPi_mvTIFvk8hJQ>6Vc<} z3&H0`!5a(Q4Y`1uKe0yE86mW$XEoK{A0X?486q{ZWq(^;4m8Qr0Lr$iv!)MaO3` ze&=7I_<)X2WBf(L1*6}##f^{4U%vw?_;?Wy5wJmkbt0^PER2grO$p14h0zX4BrG)+ zMmr?99k3+8%rOHoY$6e&9r6hi><}Rkfe`JGd4#Qvh0zX~Ntnoo$TDe%iM7T#n_bEPf*R$KUPTX>u;{J1Ue4qJGaEnHy>|7i;! zvxQ%>g*Vv3Rc&?EvW1gu;R&|%%MiBw^w+rq_1n6A$Fr`Lr>%I$ajeY({a2kGuns18 ze3)I#5x1T=;ql*<+R%g32`P9lrhDMxOWZ3CR&m3^c#vCy^8%^UJidJuZtJ|hvFzS> z^R}DzouCae8FLOIs+ia6i2GDTRWnCN@GPv`Tbkg>_|+&X6le#tg#h#4cV}!iiZ0@0 z5Ev5g$=GHTor4dx4w7Xo>zJD5J7yjM-xZe>RL`Dq5ekauL)u7Mu!X#cr?EEYrmc2Y z%}#CT&RDJ9>*gyom^-n>_z!p559V5`1m20Mcv>7SO<6J-e&+lM#6-#quEU)H z<5DVmh2`6_iDzR!2oa#`oxiXCDL zOWZ>ern%#HcRsOI#<{Oj4)~_;Hz%OElHXT4bfzccSbiPi4tu0hY>@k}j~-Y?@zp}M zRm0RH%^|N2JrM_G0h@Oa8NSf;_>c z#{<5r1Ye5yt{QyA_6_bx`+<1px4{2ZaUKQD#601v2)@cfmvt~_^jGZNAK6$w#0Aer5lhhUxL`emJieVAJhPU-WQhyLBL<|o(kR}BkW{|Ca8lLQ zA95|%$leg#in67R!S5Mjbnr8TIwH#vWHEct1|%;hj%^|wC0Pq6CAMbv7ntcjW_lbU z#qCn@41Agk`i14?(pon8p#_KbceIN*Y}G;zTNy1pgw9FyDGI3h)Yh9M1Dw%hT8WtSWm^DhuDvj+$n&oz?@w zUVNziSn=z!JG3yoTX6tC*Si|eoBu|Q2zQOc-`i(!a@@Wy#tjK`BfRkDpMywJc~xt- zdU~!+s%(PAmBP~2^H@Ecw&d~Xv-Pj_r6#KK$&t~Qk;&R*_xUk}|1URdV*TJwTRGI* z9{9ILGu=LZ8;iOqHFIfA-3os~N-jj+)Cw?$vIl*-pdhF6NUGN|rd^|`4rLQm?`ESq zJXPx=_v6&1FAG)Fy+fgotElv=~W)~#uN7hE zKhWxdNWMQh;3V|_Ks&Q855=TJ=@0zRmcG^WSFKo` z9@Y0q_>oXw)5i z5pf3W=qR;;vE||Er9t9UvZqGhi)* z=zw(@&|x7B2s<5m+vzZVztEu^J%fF9L;RP=aZKqNgNkgh=OA%WW3LdBxT zLlE8$^oZ{tLyuQ)jH1Uj;gm{qIEbL>(M+lj(*xC)RI|}T$-}o86+@3d?DW7o6X?+x ztP(+whwbzj21gzEA`4?Lh93KWQ1qCE>E6yC5EPf9_K>h^W}#xygE#az&|}XHG4y!s zhA4V`*Guuo01!dbqpnmRrU$B@pJ=0pl2gwzDuy1{hQ^7KF}Y|`@C*nN;eXw}cW;br z9|mF%losZHt7uD@^SG*>Jo5qt@ge@#?aQ8<0BK$ut8O7_{`U1z?cCLq?b~4%uyFy` zD5w@39_L4)f@`5xB?u~NbJQYySTZduaP5f>DTX%_)b3&|%x{sv0&jW#n3}Jx5$Dx4 z)kIC2q9xGsqa@Ej6rAV#D{9cWt?H~vw+xeRu-*aeM^*GZw82KtGJLQRgQfWJE+)himCV z3L{47*~y{j>sSG|<#QZ9NY7JUNT36}gNp3__o7v+C7+d0Y*FYr`bM3e_x!5S^OPH1 z^vvn5==l}f4th73Hp3Jc(>gs*@k~ikpr}plGc-^vdh)Ixhn}mRb0d*v)9EdG-U@o612$eBAG1X6Zwh*!M;Hq%J-7+{=ykxsWxbpY z7?FP9OQbgjgWc&z#q_x13#RV}Y24}Gs`P&|ePfjL4^;YNOn)y*`ZFqhEYly2NYB3? zu-(YCagk|5kk*-LH$|p(Lt1mDT^X6y25GgK_BW;l8@=?QL#~ksBRQG--b1d%BG^5k znYHNjuSzHUffoKy3oq5eOSJG}Exb?*&)355Y2kTV_-%wkdZBZ*L^c?Dihmx*AD(Zt z-nadeKF;0{kfmQtS1bYO-eKZ>3_aW&)}wXpT*(%d_kzA4o${fWo=Bq7dqHSV%HyYz= zk^9if@7)+rcSx+0*_++iNXA3rTbSk`(?%!*f8&;@)ABcd2U>;oH)8#6?;@D{zeBlV z-t*H9wp)~avTW-fNL%p@VboUy+XviDO3Bfwd6?edWTxqc4N1Kg8%ATWal97uY7n1` zELbPF8V5>wCrRMy1O{3;u&=%v$5Q?E)nlt`uI7S+EP1u^5h)(=yj94(&B$a^QRwvP zHH@dLQrO|1g^YHS2>0GyOAIi%0<7N0_9+tm3{yCQMD)9)E(&-{ua6|rl5&vfw(Fyi zDBeY)AS$_R`K6ce;hbMuTX-VDQ@Bj8uVcEu z<8laGOxnTKwen8M@GNTBF*noSu%oYVO|8P8u+Tb9h!EE?eOg?{(0%xD*Y{k_>Ki~R zEHvxuj*mZc9_pA-(%fI;`KFTe!XFO%*A$i{WC!9pDZl=;W9Zi(=Zjq%Y9^HZ^ZC0V zf4F?e6YXz*f=;URgDyLAQ^TW7dlyQ=Xci${awK3hGt3a>5>}YoN`07?7n#OwrA|!i z7n#OwrE{3pB_hqlF@0&2 z^h00}>Yv2)XOV8X*VQ@fg!dhC!oO(Y9a{K%Equrf^RhrI?DLm}4kKQ3d5d=6RbXgrktv z73pkLco=&ONnCk^rsc>n7aNweD(2B-uF_J#(OT%g-YFOX|D*H6<_I`M)}mk!5y2?h z@#Cu)PfH>4;KVyj3wmqgnkK68p4m}o1Y=-5bO>L%Bx!(`rN`G@3x9}-xEm#sAQ&eu z;8Gx$_tC)XCPDs%2BMy&&c({iUqB1K!AL|p5RoXfSbn8Ri*Q%**BBl2HUN|?oyCbq zxV4DkUfnKSVZ4FYnKXoz<#Q7nhM!2dt_J zoSXkOICqqu19@drQP{k>3*%|ggq;Xj!RVm3GXN#dw`JiooXzl8>;l7qIIjwZ;jGyF zEpWBA7ntdDR#646g@28Ki}RBL?d@zT3a)!PGd=>>uNVy%yqyZyaXx&8)V@VkQTy-?G1LBQebz%%!8T(oL5_m((aWPEyi=mX$Gr-& zAi@Z=)}hUFj4j0av+cMhw6JtLFF{Ns+KDG1^ z7D9TuT7oI0K`7<#)$Je6WV{D{SdKlW?$0_7mes&soQo=Kd-1s__3`%R8q}AIb!)r6 z{`hdK;H&p%L?k3W(BJ6+!XggqT`U%<)iZ#O(A$v@qlf1}v< zn+jKI_Weg<-#6iHYrG#JioJfK1m@>CqVDu=F82Bkro|%77}1gHAuI#kz*aEB_6Qvz zM|kHjZB=9%?R7uXUW-hly?!^-rbndN_IeJ}M?^_C?e%s{&yJFA+Ut#&-Zo0QX|M0a zVyV$EO1f#Uf6DYdo!s>B6mKGdgIB!8^iPm(+4Ix(IN`Uo@RwS6z7}4sh4r#iwD@bZ z@cUZ$d@cN>7M`euZ$Maie`NWO^`Ylj`>5U@?;xLj+T|YXmKx`$14C;+L0!lNbA>+J zxFjboCJ)!IdwU=wcVccz2ZbcBc1aF=MQXvKXZqz#4|->STKsHdXU9UKsv6ernW}1D z#YLZNs&VlkrSx0(db_sI8*9_`upY^*&Da$FBDc!7A8FU+a(HVi7m4 zv1ic@*jU||SI-<6;u5n1?Rs2=6%=!>f)&c^u*?a6Wh|zMX%5FSW7n1JL*|PM1S91# zG=s7JO@+;^CUk=$p&M7OK{p&9RY6xrpaT|R(BZ;cHBb1(g2(9R2Ifhx0;ahFW(({p z!nmH(5sPbb$=j6B&l)h_;RC>=9*iJV!nlSY6g_tGY6mXGdSZo9y9h>&PJzFfjm{;? zLGN(0(E*W-=IM>zQDvj`rBPS|PNNSMx*C1!QiZ8kHF^YFnZ)!b&N#v`tqf_H?#D-T zOdCq0*j8~GJ=5K2N3+oqHNBf|Haa@8(FgTLCso<#DbgtH7N^mdA8=t>dWpjHI@Rc{ zOBJTa)I=lEgkdi~1#!x=>Jj=SaG%2ZgMi=DB}~BY{5nFw6NM)*si%GUJM~*1<|Ba25=QUA`%UGTRs>wm)r*w$Z(o+)&`fND&H{>q^p zAN2mi1fa7GfZ`T1_ueg{s?NW5!$(ybBD(&HLhZ}k(B`KqY9Ci~w%@VEN@~2#;a}@F z0A|fk8Zb-nQ57(MT3x-~$wfM&y#i*G0%o)c%z2T(T&@GtP5~2DUEu~WrLO9y9xUjR z7?b9ixtdxl=YChW8ez8m8ygFH+nPH#b`+`>N^d#3Ee zG68y>Iu!jQ*9_$DISzPH5LGp;#RqDVp*vz& zkek-j_=%g=)|)ryP>_bQ+MsvuS4yt>Mz(SQGX)!7x&Ft7*BPMeuqWQYA<$F&sOmR! z%_?iF7G|5DztJw$@Mt1^SdOw34?|M`W|En89kT|#W6aMbu98iqq#SZ7{$8!UTyJK5 zSe3lS{48*lOd3}Y81eW^{sc5|wwbLzv%zH6-303rnZi}=v;Er#3`!qJ4{u!enn6b_ znJVKNxha@l<<4-vo4USV!E{bfZzCB}ZQtJ|iw177G;?*qROU79(sS4Vap5)0V- zGF%iX4L7n?KjLy{1maq}V=|k4ubuYAR(3}2m zMdt5dtLe8THM3qEC;+h|BmhLuooaGgw9~@r7NC zl4L<2zJ4340H3^G0sbNlJ~!Z4sQ(97OatCFQ2_rN0skmf0B>&g{Q+V(3gENbo&@lh z&BgXjEE5IrTh3>E#A2+E(QwZCTmc@UB^LDF_P+Z3hM(c0gMkzJP_#*x@ggpb-&JIO zORPA7c0amhwPe1?gtm1R(7xM}6+}S$G^2yw9MFn#-`N4rkq;~$_X2<*^Q!id^6|k( zAoGy+LgxPS6yU#!K_`HBIvL>o%{A{)Y&r^=52r*0{0BzEN7EGS2iT%pK5*j?{ks8p zgD8O4BH(i`7Qkn}qX6&h0A6q*+pXr}93N={nk_;ZF05ZA2t-i0qXKj>COgc%g(jXG zP#knmRe;`haU_NNW24E4Re<(2C$f)T9Xu>AD;$&$U}izRH#ScMIqPjj)}3No3bd_H2JJx-0)!gO2BJV~ z{4FZ98yFq*7J*hQJ%%m1$&6ES^uLEZ9Bmg#=KX6x=BL|L`GBBH%x?6~H&WsQ@3tYSdBn zMWSG<0o+5Hpy^*^G?HD#FbzHKJR%e!AGa_%=-q~H#L_X*06)t!bu;bVfY;wPlHvuc z0eC9~_#|@%`o7q4A}S|D!BzwKc-pOK+FJ$S%aWr4{)$BFtHz$<3zP|r%bvrouCmtc zwjY-Bd5D05uou3aO+N}S3F+PiE7jsIa z&d+20$4bW#rMJ)9Mm$Al!vHnQCyFhq%1e{K;t+cHBE6^ByaX%hbqGKQQ9t4AFfYM6 z{2J2Fh)9=9u)bs3QR!29+5Ev+>@H#2w#YOdK7W~MrIBeod_Ik7uSTZv@c9U)1(0SO zY)-KXYm~bV*D=GLk%j3cbTQMqN2YPt;WVcGJu;2E4u@VvT2rK1tM+$%?Su=p@cml& zK`lH(3s2O-4`^XM&l6hwlUjJ37B2tFf#E(aUa$XBEq<~V9;}6L)xvjb;an}eLu+fU z7QPYT+?x9fb%(~G#yEge!q8pUnx7dQl$6r71~c8Dp99;Gy!=4NZVKClGIAl-=^R>NJfp=(?qH{UN zo^bGBwD&R1-5dp83lqE#nOT8X`()s?HR*VH72vHrD=K(zFdC2fnc!tdf(K8SuQ8C5 zxo_jbcVsS_qo~*10q=GhL8_r19Ii#qo?#hf3xrXxMRf2QD)35674_cY02od^Ocri5 z!Sg8acD<~?D_~|ty)scy)qr=F3EnXoVI!GabSA;(h#$t>yBQtywl={##Q`sDvhcOC zv7Stc9PuB*83yCB6zP0zO~BW13ZejScrw7h0`Ba;U8?~6Q zD1i4Tgps0hwF1163HXm3!`*;mzR*AcKH_hY6d!^;C8L1?Jk|vKSyrO}|3P$QHGn^8 z8iz?$06x2ERKWd=hA$Pi<0&c^I)Gav17;ConkoT7!tYWW*z@$oE&NX{d_)WH z(!#S4R(^pI>%)`xOvAJ%%Q5)!VlMi#Djp$h27 zb4xwh*LQrj>4j#O&Q z67J{6EXMU4xcjDWgMvSfk2|&Cj}wbeLBx_K_~Y|ruJqv=Rd|%hzT#KCRJ}=r3H}k= zj9yZSefemoHR|Q#WHC3NIF*`^_u$BlI96hsB;IQ#0{x7X!S;=%m}S9G9Vm$zDHH5F zC-NKnCa)q5t&ODgTS|?x#+D$JhDLwvgzwhE!x7f)dAx$?Kj53ZXEW;3_)(OymI%`U zC@-ZWSdnb8qN6WZlv2P%_1tx`@iy+D@dX}FAvnIkd^54axCZhL2EF-=&Y&_fs4aU6 z@yy_Zit=i9D`U|)ikibn&B5Gbibu9EF5!|DW1nc1vpoyDHt2HPGvz!EKfzwO(5JLX zmlHlu#y5f56r;2y9)g1lg?#u$7H^v+GAiS;p`O?#EoJ+VBVHnfKWRokj?m#ZQt_pO4$WxTW;Ue~%?BLQAo~zAThFvrMyDCs0GEpC=-lwO`W=nVuB_Z@SLXN(K&G744 zaJ~TZ6T}h>lV57)YNi1vqFy|Iu{=H_f5 zG1z1#U;-60@TeIspeeo(nCtlUCZu_|=Lsk#8ri3#Fhcm0OS;T%0NI8xKYWTxglK1^ zjIt$tlq8Ok#HA?((ppi<4F0002!`^(DzYV)l2NBi3`Uor7;9a^xgV-wXeS0Z(usoY z6yizXBTqs*C!zC1CUZplhRH|J1&!N5S*5{CLp|0y;Z9n3tQNjR3#TG%ttV;v(CUBe zJX-%lU$^z4|EDl*7?)ynG0){&%CN%t<}~SRX|p2wT8X4M%CM&hnWGFVjOUTV5)$c+ zWkvu|zJT4y+D7eUJo)oR_uqK}EKV-bc`H{Af3ttEb@d-3(J)GJO zmwq6p^>FGZRLk%l#Dt3Fm+>>aJiHA*ROR7!urBZ1@bc3m3*efAAPT^@A|WQPGb%sB z1a7dMSMz+tWc)C4v+*=L-F6kKKQ0sX;HA% zwD4+#quCpaAr_jxE0RG^RNh1k{?I2$+5Sr1?npAO;e7%SamPT|3Gv7dw!8K*oh7g^ zelb4c2tl+R3nRhkbGo9RIaI;IcnR4|zQD5$~rOCz(MwNK)nN=P(cep>c^J!IL0dt61 z3mp&sreX{7ky2R8Cg#i_K>%&li1?Z?& zCwslb3D42OtF`cxcDO8b55jCeioNj~xDnR>W+CFw*!!)F4`*r&hk2?5p~C2kfkkP? zpmz~KH#^i-9B)8<&Dc*iKElh};e9ztD}Aq38rGvxDWgtp&%&M!vV+4Ka$45d7xcm6 zFKL45875_Gv;3c?2Qp)nX%CYm&F9D6bm(+q`)9?LiD+cW!kAbbPz*G%%}YzBfVrw4 zdWurHHW~CD!H&8y6Dm4uNG7BW~qBco-{DFbBsa`sEyG|Gz`l|09_GEc|*}7p25N&X{$v zif_sE?AkA<%tqy&*3(l;NAWRF3;!5zFKCR28 z!LgNv<+X56#HGH;e~_W$=L9p`ll$Y6e6f3xwJnRJ<8ItoeyDPBDb^%WJ2D+HS1csl zSTHv3mjSJ+$zp6QdZ(kcaU>Vh#$2eXyKbm4zZYep-@@~{4Hi?gV?%*djPj{*p=S7`wo-;e zs0k*&>b_r|HdJ>2f58woA7Vo57(%y<2`!gmE=cn^e&IkDH@awNsE zhqpFR{U#BjvQBs zQSIUHBr$A?63rgYtlV!i>$&$GMm(j3XCkcI!@pzw?I_mYs+s?*$+c@ev=grn2;;{l z$P4&!#k2^1ERz(6A362i{CEaAT>O}Zs2cL)^hs`hbd^e~SPz|YtQvj{Hxr}sBU=(r z%8vzLo7H))UhMGWN-caj!hZ!nUgvTDFn)BaCH#16N(4XJNs7adWeIM6G(Zj)KMqq- z*KEF+`MsMT|CUOs;K#u~s^P~LGchVZmP+DD`Oy+=v-q)lp~H_KweU8C{|bJb8F2Gs z5mYJq$2r9j{CG}M9DcN`>*mLO$l>D0FhtdmA44QkG7I{ zQhv+?+bn)eU*Pa#nieiXSm(z{)+@O;qx97wee#}Q`2FGhzZqFIk3Y!npPYFh6Jo19k*P2JYhUJ%vQh z5|R=yTFbn>>&Sa@hu?8|GUx3wS@&-?Ckf-)n}=5NF2Dp2yA$TQCu05oWR-^`_KjAi}oj`B0y2;%4oNn@v7G9)<|B0}6 z+gA8`zX3RpA zw(cd<9#{WCS4kewr&lJIzTi*?wS|}#nKxivE4CD!>w*|1-&_z=9Sh!LG4?F`YkZiU z$WyeADY2W;y{(RP0mmjd4`I8Ioj!@5T6e)})lyc#^IE#mS7CfFyaP1$!Vvm5)_%_a ztr}6TXC_7!F8Bb+h`cGz7h)g? zwG?qCeq3MT4IjpSfN9Czpm~n$P1eFWS~v?~%U?6g|9g6G-0)DfeMvQ_^fh``_A8&O$UwBfoA)^t2m z)V-G4x=zLlSvLv4yP>VQA)D8N*E&!JE%}*xLba-91Lfz)`8^0K1T#4XlT%wL!7C`# zZN@8ym3$;dn=FKWtwwl0F%zQ-&pVPBre=~Og-6M8VM)Ufb(>Ki5@+#w{@V_p-_ycx zBOEcGv-HUx3`wkxwLC9r3;gw@ih$)H!jB-gEP!U*6hSM zpZ{~&ayQ2BC&#e)p1LvhV3xmxO5^~Qnlm_KfW`Yihq3I{f`cSZM6uWY{H*G=eK{mr z?Rgd@`ZFY*T(iB~l9vt`%qOBDUcOV4LzPY87k1#rZ<>fjz$8 z1mu4+)$QvjD+?R;czTPBr!Jsmd1BoJjEV-xZS>mbi0!3sI%3;V3-{2%NeBaeO8R2> z#>SK?d5-$cB@{i~^<6r{(ZA_8E+#K|txcByczW+F|CfFIpYm>-q>R9r_60}&>B+z% z9sG(GgYPjp{zK`LPaH>RT;nXR!Gp|amiP*{|A95-dRf7Vbs891VDj=LWPwkS(M33Z zddmtt(h``2lj{BO2-zSc^-S;uPd~V`9^BUP;%VW^M4vy=S6rD_&*&dI4D~iBW-%Ry z(x$b^^>@X4V!Y%pfO1`Hqg?@@Hv%UBz_`w1<-lh#$q|RpsNeTjqNs9H%FXcK*RXtL#0e3jEg0x* zdVeB=^XUurMy2-UG$nIX!bvRC+hv5ry9O{`CJ6y=OqrR8Q~j z5L!#V8!Lh?c@PAB+Le>&5P9km--|buvJg*??GdW-Y;egL9gY4^<^QU_XQAni{7QzN%Eyk zJ_E@Xy+3~?oZd833-@5)Y&SZtzHZ0hJ;2nGw1N}=6b0|eT-~wwFbFW|9O_a$Th}J8 zWh;DpiupPrG-DbyBSwvi65MV^vnM&Vl2d%n@MHX?p4Qm@GulxwP#&ZC3g3!Qa(*LB z_o0|!9Uy>7BL)gFE&XsJ+F|^HodI8PSqW+|#(+9}1e0&1El*}lGKN6x7iD9{6BtNm z!Zn^#eHaA3&Fk+A#9w=$UQ9tp+-KoO-oma4vA*Df*(~NaNGz$;S6Dm`QL#oDs&eDS za>NS;D^Ux@{&*PsEoLPdti&uGUNFD66jBXH!C|P}+OOOvkO;VDO@Hi;1m`k>Q~a%` zh`ZJyJpET`3}J(`>_Pb^Lizl1{~BY2&DzpX+c}OI&;()Ge|Gr$Zted)e{%%NKh57$ zxJ_g7_fc44;rvber8@rJ`D+#Yef_6Mg6=|9;cW60yZL+G4;p`OXC;4z0O!UUK+50%76rUvGb{!(eIa%cUGS1E=1fSWwJ@{7MVit$C*4H z$=3LEXts;q>c&hNrEsGY?la=3!&TxW*YG5Mo|DdJH&4=rr@yP=sg+~6WAqXrq*vdw`Z9qnZM2cyb0+5TZzTZtdPM^s+kP3eW139(#nT=oNCx6~9CR*s`g zI05p#=s2x#7Q?|m)Zx3s=sN{y5HB@WW~Lqt!95Q#SpV85RhPeH9AM4RMkD|^qa=}ExKwn+7oOI=VLf0r7LOAWSfvOSiGK>$M0*OQCc;+$G( z`2vj&;0NAwYvApL=J=1MN)BH)_65@uQ`dRmal$!ju77&UJp5)6c}A`!cz)Fkmdy-q zUZAPoaXo3?^kY>ywI?AOj{GQMJOzg4$cjZUJ7qB11P+N=wYwvSoUZsh3ri)fe0~oT z+8cLDc1Rn5?EW)J@Oa8>8$2xS!Nj>8DEl{w?{-$88!EaTjR(`^`~(BTEciUFZ%-La zQ)`q54nGB`hQC}$F*b^3X*49nCgzK?54YqorRL!Q|9tZlLpsQj2S-nka2Sb&qB0jp zcrn8Kx4KA5<2`wiHY@~M>p693-LIo^m9-F3*xJP56_w(dRUC^6EL%=ADj-Z&(Ty-v z!9TW}XiTxIKymw0S_+P=zo1&)-PthEXY`Fi)I#Vzc>*kqatoqPTS7#>1iJrvkfBu z@otF{K{wci(;)3-WaVJ4XUQpy5>~_Y_0`|8bH*PcFG0y<_7LHiF&$i{h|nU&6I9|U z24TqxTw{sfz_`JbVlkObQ630s3dC<%naB@?*w%TBFM|VLM{J{PVi3jAKEd z<@u;8bsbbn;Pe(!D>{Oyu0)erI?NZmI?+;HqQ@-#Ae`59VD-8z(fD+iTbDIVsY;b4 z8UK>pqRPC5yFi^Ns%%75Rd$V~%C52dgs1h0s#IBBPMHGUSy=rO5$6Fg_6=QM1+TFb zSvJ)hw3&~TqR2*5Wjm>H;In5v@sd*v1yQ*Tk=Cj%_Ko!$Gn8IH0nv^@Zwd>1W)}dD z#KpDFI1e;aoz#Q8M5egAC=+-F#-jtDRQ2?$q3S6R9OCPNERaE-f6!Eqr?m_|^wSQ+ z|Acish@(ww(KnH5=9bN(W@eC;;cBKOIAEz6SSHo08QJc~h^f@fovbaYnkf(p6}{+O$UmuTUITDUvHVfy1g^)K6E9=Y$wZ4Z!bn=u}0jr)JM!hD8IsBu#5 z|4E9o-@Nz7i2Xn02-_UO{vV=h=s&XyhwQ}~Bup4;aQ;PxAdKSCw(!pXnk`h}?^n-E zgyCWiZl_TG2Fu8{=PQ;B+ro?H@7HIO!>GYeI*b~qh5I2K&3`5d_D7gLPY{CyN1(&c zzqIn1N1$>3CD*-QxAR-Fq~*1Pb(Ubi?kD3TNr6q3!Gj`)jGJ~SmiS0IXrc<^HRLc^ zqR!x!88Z>3xd8k`h+HlJrmSV#4~gI5BNUSG{BMR{4eNLOEZ zXo0yJqEFB+qF537hIT1Sf6;K0BNWAnC}X_|HhYq4<-2cCJ_uU_lNoL&!cwJPD-kFM zLf50GbHb*KsdI@JlBtGGV~R#4ykepoQ*TqB2I4zxqXJr*vK@JS!JZf^9#1Jy;bBl? z_6R)nd*nkJ9o?-Fc&!gJgnh`20e6LE4BM)X2_koSUr0-HumJ1}E|n<-Yv8y!3wex7 zX+H+yt#oN2fIX;y4_fvH17k~*0@fAinT)trgkpw#t27nHyJ&$l2YM-2WR{D+flXs* znucQhXEo2Jj5$IGeJgax76LR86z;T5c@ec2MBdn_;?vl>+-GtgG7|?g(R~1Tv?La# zusdj09?w%l1+&+LnRrV7%KgW+@&h?J!mgKdps_XyJb#tho?HnZI@v`q&E*MJcUBs^z?X5?nbPy+JCY$IGN9!HB(0 zDG^5z{7brT%lLs2N~Bm)u!e3bk<-6dN(6PATj4{H!|JutM48bOQJNCD9vfF~CBic# zvxU6$f-$ZHp|XQ7OMhH)8sb6DITK0F-9|0eW*I-J8(rqlPT)+SZt|rA^pI6AnIo zr48#mB5Ut$4l2kPDcMhcPQolTfqho>Omv&@qwS-Si@Iw&Ve~(%a%&wD(_VICrOD!i z=jPgjnig(G8VC?wlkKFQ48-4!1w29``oq*@vr!IOEliUw+oCjCvRjiSBEr&S^H|WD z8!|x@z}(NIrEjq`OHHepY zlBhbVt<~}eL8GxBYZ^`YLwFW7sU3RI(MR%qn)5CCYCg6ttose1ugFYFehE+rok2Tt zA$VXZprH>t3MgF*U!jFN+2OKKV>?_L>ZOIRM>x#BwET~%(nsv;1tdSZPDiXx>0ZGd zjj^~q-Q7*ehX$e&yrXY)>7;|kuN)sh;la+q-ehCq7NwYmQ85i>1s^e+zYMRQ6l|if z$N&0uJ&*^>U=>-xK55ptypprvwW7h4JmYeOhh+q^y_WV#=MTSN#I%BD6ECG$lZ*+V zwyniXf50{4l@{y5DlPRQI?QXX6y>#bj*I&Ihqw&Z%6Lnp1tI7ZJX>TO->|>3{0z(& zEX{SVS?^9HnCcgAgYP!J#JAp#uEY*QJ}kRwSe}CGW#)%s>j}H5r`Sztj_w(VQ3H09 z4@fF)bC8`Is%bqUOuI>Gn=0(4anOcY!OSE~1DmAS`UbYlY*c^*nfOW1hjB#B;c5N2 znj1%`lK~$A&_Mij@-mt_Ia}-yJNj^Lq!C8h8CK^~X zdvu+OA50l`+dlb{X!RGR=xx64FT0Jwz%10#n!kD%ngjLwtYe-ONduhT$KWGIk$i#i zvk-4w03KTEsC~duM`vl_&RY2JgHE2E2uHJrOy^dvm`m4T2c&e-$sf;b><*h@y~bRD z_~u`LlUN3|R?IeSl$DBz6|?4FG2U4*lclunh{1|klN4jI@I3xJ$yHI3dXP(9)7S*Y zIfiEmP)gcUu|kH`TLr*Bzf__$0iXQm3k<`XeWPHOPr?93z+>?&atGsUQAF`06?{!n zxb{eON=e|7EVWn~SMS<$f-svkiBM4^#icMuPg%J&27w1a{Fe<>fxAT$qhsS;A_Z)= z-xN8lPj%Fdf6LY|vIP>%p)kM%+8cu)0@;`zLx{U#y}GNpUR`^2S97`gOV*4GJw;7q zc z3o$XR^XJ83f)t;xI4|=llFRr~T34Gf&aiwDx{;Eousf=or-8oKY4>eLKPc%CUc{?3 zy05VWyDap`G)rj9LX+%pY3Kzlyai!Rn4#Ch?fc1ls#@&5eLYYO`nU@>nNoqlYn?d1 z5_f*Bhj@O(ZfOsg+oa zggoa$_PEbwbs9x?HO2tTUdYP6w3b<@ea$YD9T=RD1@+2JsFcCku@J`zSm3+Lcu|b( z_|Bh;JPk}qWFzbaqf}?15s%J7&^RTh6qqA8R>fU=Rp*luf%rwAvD+Lnb-#2PglWa{ z9|5?C1D9<^&u8uD$fG~TzV-6I|Jk6xhBY|Hpn1{OmK0oOYS`lT#7CIyp%4OZg$}k zUR_*x&(%-I$ejbGGNm0Eqjl_P7{x2Vz&Q0uLg(LaM??ajVhB@DN#weZ0Cw#UJ%Y&RZP9d_ff6(T`AhLRRR@0#AK z%BFUe@ZpnvjD+!CL*VyUpfef2eck((Uzrf@Y zBwJ?BS%ucsbn}%nIl#>DzwK+Pw_^M z9)+uX?!DIn6em5o+n)C>7wC#g@?PiTWDl$HCiO1VIAjfmqo9{z3R}v@76+-e6)^f7 zCPPM++p*Pe-<*gYxF^;@K?mDCJwz-{T-IWAS*PZM7${|uIx|;(ORH*knG-`Z_o}h0?R2Yp_JI2#CCcr}Z4%GKd z8Hl<}eda0Zfe$J&&y-Aw?#U;}JVl&Hdls$0$qvp86EXr_5(2d{I(Mn%DLw~D8UDi{ z*m-vf!D#0h6`T(U0#-MvKkighlJgQ+Nk?Don)JeoSe)H4M#r20<~BOO5MfXlu5IR5luFfCPm5GO|rRK5zQHE^yVI=06?iZoLc{(YOWvo67*(3 z@F*JfWYz=!sGtuMdz|u-gR(_E)l>2IJ{#T|-XTVO?mdYI!7B^%tu`+|Q5z4Z43-?ql1r%}%M68n##5r{JWvDDF8 z{qA?PR)!YtsD;~V;bbk`L<=V%9C3c_Ki!|~be&qqcJ?PXvFqXfi%fmZNcJa}Ns6;S znPUoFN2&)*Ft!=bAcwV(BKBaZF%3~Q+@H*k*q`hwl~l1mIpuw}P{sb_a5E9h2ApVF zYmI|t2_Rb%Pr5(3V2Q)T#giN+&ey{85Vpq;z6g%{ih5ObABksCzu4T#M~k|9rcS1T zHu-3C1nEzJ;8}5=qDz`Vc}*=7Aa&&KzZPvfcijyCZW zy>ym@{to|rOfRrDh_zH0?Xu?y+b03Mp_Q6oT$`oXt@H#J77TX6V7u;J9d>8YNAVZq zGf9!-sIn?{bD8SEirqXG_$G3g>{izYtTvuP)SqN`PxJccYxXNcMu{K|nBJ&F&d)(% z%_@^#Ys|neMQj>>VP{X!2G8#2U@VEa$2oUK@UiXh(ti8ncF$Cw43~{kOXD#tZ1fFj z@`x|?qbnP&(t-F%{wmg6fI368&?A|G<`a9oZVD{85etsXK|3Knvs*c zxf$7<>Mhu=I6Z=q@si>&awgOh2MdRhKSE8p7`Yx%HDu)R95*8as3de5j6bEXfMuw* zr>G_AFvUY@o_zFYL=>Ga!SdRk;uk<2?z%-6-@r9)tXrc6VEu5Kjy0a+`o-`_3b0mJ zJkDMjj`Shpmk%P4{uWW@VQz2V+tdg!euXONi01<23JvB6F!|_L?L9^D!q@v1KK;PP zCW?(;wpZ6_Rl~+5nQnyop>iPf;Z-_9(jTvs6o-wUnSeQLY=#^zHr7K_4cWMQvzv{p zpa4T7o$+x=V;XNk??CvlP=~yXbo_c29Wah8M0;2{bM?^uXWBg!<>rE0&Sp)h43?3H z{>q@|bj-9`q5~orjLCnZYEdY_Lky0^LnzKA6v1{ySL&1#QHYZiTNGxNxJBVd3@T)1qBQo-judV6h29(H7YSJpbdDhFSV?inTKmIriL5lPM-CTRuS8T0$vU9F zo2=}gp_j3AP>q1JjKHK6rO>rnM`H52q&S##TIR-NDss3m$wO2PFOhzSs<9)a(M(#wn>VE$;hQ{OqL;s3zNBssv#z?4t4WnC@KjhR*%UeSGh5{ zSm13pvr_~nr%Q^1$(#?|m>ifNfys76)ew`tKe&1F3@Qm-g9j9=k*+mYx-l7wQjo5X zJ4Rq~ouoLJe7nSrNo(YA@uVrDYKY0d8@qY3;orbyBHmH229x7gxG{MKrGQCnBqoz3 z#lhs%2uyB44i_fbh^iqb_i|$bww+_G)I}ws_kN4ib(t7w%yB3}H@*nnSPka2BQSsA zJ;A(ghX@`{l@tf_Gv0Uea42%PFuws&HN<>mxf}CFs3f%bK(&~3>f+|%rgsICD=v$` zWSOKmnB**WWAY4gxGNsHN@m>)6#OJ@m^FCN~s=`IhVUJ=_>HHd;QV~Oj=8dgUR~~-I&xx z4i_fBy;EaMe*MWUUGJch&`rNa_Nzm9=qS>@OM~^`woYb8&H2PjkvX4_nsZ?Fy>w6~ zHyw|@EwX*svydu78i9PN}3g)af zvI3=m$pw*^yecUUCLQLvxmS!FE=L+M$xr=AR?E=f|#OB=>H9MO%kE ztB0p(D^_u^WRTJW?~qmBFHgI~&DnQf6MCG{E`qa9N{T~|3*K?lBOf_j^tcUCHKfP= zBi!^j2bF}@hPV_`1k|csKTXFDPWbZCwpRtCOsw??a9G7M7sAUV#lfi0+ir|rLJk*3 zGZ0lnj2eC9meuP}N$8+q@y%^N@VIp(pRZY0RsPGP=0C_aY+1jmdbO=_s+(N%UJ-IN zZKIP*R@Z@9_P1-U}Icay;dEhOl)|^zv+gz3>jSTzK19a-tW&)@OF=YcRF%~IymrFGhV!V zu^ZqX0#>^Pt#yE9QO+wVjy#r`4R@4%IBv|Gh8!-4V-QtCdCW221#rfT4_*dBxj$L* z;+Dq{_gLKfFrlVc+f(x8&R-rif8S56{MFEF@=V~WiGqLsfIdR^bnO|Oa< zgv*K9=9kY3BqbZhVds3cTpr-e_|{riEoZgi3b z=yp@i*U=GuR7X1i zNtg1^BK~=gf8OGs*ZAip{&}8%p5mX!`R8H&d60jK`KN$??&F_v{4<(=M)1!a{Bs-s z48kAf(p46E?PhCVy)3jw3s-94b8m6-^wq-oTKFw3{D~Hh8|;*Ap@j!%;eTl1_q6Z^ zEnM$br=C_?_-qZ%8Ctu`weZtgo^@LIO0E98weZnFPFojh`TwQW`I#1eUCXms3+HHc zPSnC{%`omi3dNcAFkH`Um*GxYovEzfX`4rN;YEn1$@#wpL4i?;_|P=GA!Q9};*DXgToporRfS={x z0M3NRa>MmG@HoFWD{!VSa9vt?b6?;RUiJmg>+WeRx5ejQ%c7k&;hs(ZfvirS z<$vc3^hxw}?vk856>S2<8%ibZkOauy1VP9|>bSA6yydDV~T_ zG<~jT;dP1Aa*__Ntd-Z;ztOWOJMlzrx<9+g37IeD_;-ieNfm0o2`m$R!AZ$kxO}c~ z_hFwuCkgKX2J#XPXZiCQ9?tgv;A?#(_M@!U>k4-qMq^_>#Bb_4|7V3O5^@4@sld2H zrwwB&%3nc6{*5Re$WA=Q_KuZ5W?TezSsu_FN^)oLE474|d#m>UlW$+(Mi3Xi%l=K3 z+nuYa1wU!+BFW34`Zykj4&6P&5|}b8*65Eo_Wc(iOu{cz(Kb#9hZVvVC1yaVE^0LA<03D?_;y--_eQC&k*mHwVf8I~*j?Woe^~pz!15Vf$iV&Z zb$o%kmAts)gISCT7QV(GIC(N5~}|Izfb?m`s1zopN(Gs z-T!6%a~=}-jVn++>0SaP2ZSC*tb>dr-@*8Nh=s>bw)g2Ey}jm*^25o<^6*!U=J3220=?LC`x7Tk1wO zRDYEZ$#y_SQx4(riC3X{qyl4@{*LT&M#Wb7j_k9TU*jEFIbc?XS4i!5Wc@fpByY+7 z!Wp={B`YE8E!lFJn453OiYI8~Te7WjUdeh#c8KIR-;vE#AL+T;7P^Mp^hZUy$vtqR#1yUpdOheD~tR z7ifq>u_IgNFkBml9_3;?>l`0*4UruwgT_Q{^5Q% z_BfoMV@ohM&xlLqpY|Ek;yMNIlp%+P0sD2Pb&4 z0`6t<@2ade7;n^(7#`QF1tF*Z;mxzqO?fDgM{MOri)696etHn`PGP(*mf$IBib67j zhiq>=UAa-7g9;*FhQ-35rC)h^ie1Vc>paElNFrS5BQR`t*=u~S^&=^+>;t~nx+Lto zZfGvQt@m0>;p3^j*UGCg)B~+W$fX`={RcznMlo_b&j;w$F(F*21_%LCAw#ycqN(wCP0QqKA^tVY`V*6p--{JLu*4fQ1+w2vBL$b)&!u$OL` z@y38B0RNCoq*CqV7G4fDR2QrINUJ-UFT#aK6o^3)%n0}LO(d{vzKQ|C3U zt8l-he4zF;PPUv=mGUamxLd6kh`QpOTA&sLpjI6F#{oc#8%rFm;cJ8Q=zH0u=L?!^3|=6OO)-!dqM>RR2RTfh;yFa<3pN{f>z3;rL>H=kI2 zUG$1Y*0<^|iu1JvHkhBgKdAu3qL!2GMX8SJSQsd)@bIVTN%APDJ811@u?k^pMC$`*3GXw!du( zK2MVu`xHy@nGp6!-@D+GP41W39r#G!A?uN~2T0tYcRhB`D7s_$X$c1|w!wQ@PqGZg z9o3~lqN}6}bV;!vnpB;5S`msuxdPh^9Kx~=IJK7^ewQSIQrd_ygB2I9>S^^lZNg@~ zzt;(VBLr)D1Xxqxn&!N}H&Da~^f+X_zc&}=M<|ndC~xY1B}|Z6+2^Q?vb~0tV#emc zly{DCL$TF8OUpO1pO*h_>GzK*7yG9|E@tpWs^6>$P&8TKl6^AdiL&qxp4%V+HCZ_3 zcVuDEDW)ux8oLmk1;fgILT?pG6g=4zdabP|^pg36o`1K++iM;+buyK4c{AxBI6ez$ zN|g8WprI))XamBC_rKA4RT}z@2dZK2Lz1WyGQWexSk>Qg?LfoO)npRr-ou>vb>nY1 z{m(Eq7CQ9*#-cp##Mov`n8GezL}+o3!nuF+f!Ovw9tY5Oarn#*PMV$GC%re#|9C?BJYamf`}{ZezK`ycMIeCv;&w&`(lH za68IKwRrR{2tmOc0G}B_q@~}O9SE{UC__vhDi;tYUtk%5PG1}cBB0ovF};j=Lj7e@ zQEBGN2#3H|FY|pDCSI;oRh$h%o%`iwwb3977u5L zDoIuuW+THqWSFI8m?s%3?+2zqZ@;5)AW@}}hIcoCxR5XCZ2+$)qaCAy-rJ?;Z8OeQ zIY?~8c1NtyK;_s0!-y(1CwSEyAHdaa7i2ZYoPMJ4Y4lOi@{4 zRF``DNA7`dgKyI$AGQS*oM;OlAps zuRdGR`s=Ae>lpcjeZfzg)?E;5%vU+uBTQP)Q8`Rne^n1T9z|5RG=tWaXR(1wVdgDK;q4feutd`b~sw~yfdZfxy9j&ufmg;ETnpuM0e{7>xuQ2YMBDDS$ zDuD`m06%S7|4c>UQ#rmzn6&Psa+tIpo`4+ZBPxQ{Z%K`n#u4;`n$h|K5twS^I``gc zXq_dA)zbQWm8Cjb*H&4oqxJR)ghCktRSYc4m?h|aJ4wm)i6Wu(%BG6e75ubm{US0M z->Do=AWT|+s&bgLK3)eomLMvE)mk?8d`6a#A<21L}jUt z)=#P|)zLanWr?XqUtiBGm=VHvk8=HJq0oA%N$Wy>+O+P4OvWgcqnkMUZ8L6FIZRsD z;$*iwq9SPBR2qQ23k6d%TK5ovsYb3J8dnXiM@wS0wC=95R7dMJDob^=PEc8@qxG(Q z0$L1dt1MVNi__%%mKfpJYLn8#u&jN-p_>P!4@@7FeslUQgZS}GADnXEF3ZE z-2^M9#`lbZ8Iz)<|8so8s#(fU#X4Fw@2gC2B9;nkuKN6;wqpA;{Io5~smNqZLsaz^ zB_{zWv=->lqI^{mU|_&^JV@b~<5F#TMmevVXPTB1G=)l!(gt1=6eIDn5##`B1( z5vI$8kIMcgrpG5MOn;YOyjPE36CmRUhJoo86(^W}D)}mnGREQF@Ct=#Qw5rdX(ul9 z)>goufbT0S`R)ENOn31!=soZ^h3VJovyqAE8kO0^^fP2K<|C>`n0}Ebm`EMO^fZAS z_bJQoZlg9aP^32waYg|kE7Z(FF#Qo>S`ObbF6ixIV%k=LW@6f-F+e+00pA&5vXc5L zhh>u={ik4hhKcDO_1Pj;@pLOcZRy>QX|(YXqH2U`Xlyv9tp)N5<2?D@ZJbFAOiUXw z3?SoGoM3tc7CbTim6m+a``#~#r&lY`OiU}O9xqnF50%;eHX~W(urNIppXj~mNQLyW z=T=S<+%Jn!$nL`@qO$`suj7K!_lT(i*U0I5Eb#;@Suj&zt}w2U-`$3nu$wrxW*9i0 zr{V<1(Zk4~=evv%2zT8PX&~}D0y%iP-Tt?FtcA}ULERYW&>fu!d>n7RkF?{b>b3pMU^ss zmVYdN6>T<2xIq3s&%dEz769mY3KBcO@k;WHvjTRK9mukh?7$6HOqvz2lkC80R+1fP zX2sOE0-sxf16E+Q6*$F$`G^&>(+b$7W>_&esi?4k0iptS9vneeF>|bdUFv!(Cf^G9 ztbm>8J}V~I3fQF@TQR)*M`&2j3fOtNSTPq^0lU-}*iV#FhpYg1F(t;%!>2?f#;^h` zGA$j%I}I~i;&>yPV(n(D{orJ<%Yv!((kqgGS>aZRi%7aRCu%L19O0rTSH zShKQ+!8zM(%qbVTeU7w5rd^CQ3ZTzlR{kRQu(~6{C4X2Lx3()1tW5 zljQDD?g98rFBmvh`4)E_c~9=}J1$SgE;cR`wPb}a9eAcTM^S5!c1~Tzj&jaoRKD!M zkOXzpXTrFvOhV*cCPcs%7B~4SjAx0eE>PL6w~IV=5P8BKZrhAmtkNygv7RZ%0IT)j z=G`Z_{=dx_5v}?9u+F6L_B(aO_VjeN4G=jY=#M1? z=G#ZJyO92F=I!F8av!a{N?PiZdDRsKSjHZmYtv3@5Ab@B0yMqQW7D6A-q<C}3UV(#TJFLO zLGPoWGXZJmd1H{d9cpIg7$00N9w_XiMYKn%`74|aK;n1r`rmh!_p0Yz>EETzC?8@qV@fK-m@8Hf4>>__pvvd<==%Z*`$$U zpnAE#k1g88J%)F5HH0KmE1wVZ-@JI(dS}!#^?k|1w`0JwFBhnu=%ZUhn!955#Y4!> zy1o&Mh3}=n8^C>K{Gi*(db2~5AA2Ypa1P4ubVxa@K~rEa&@1^Sra)Olx)dZyVn)g^ zyGQ3wKyMypyA!B!Sjp+-6kI+Mmx=)VANd{%RwP9LwF){w)|T#ttbI#4RI`rRz=Rmh zB1ZU~A(-jy=3Q-^J(LLOks`OFSl7d-ODWz`M{Z@-QNG8De}&Y20vX}*oT2u&u}D|A zCP6f9;huhB^5{z~F@^&S96C6gt@<1iOauw~DH4?WOPAAn%<}Ivu7mQYNm*uGKMIfr zy<>&vyD_;jnvaAm`@bh2@?bg8&mwFyfBku);VK&Rpsh`&3cuKf8VNHOwT)vd7ttHD=>15?|> z`%n27@Y}O!>NFLRW~NWaXRv2%amoF4rDLX+_@884srZ|F7Ea|7AZ{_g-WPZ>8KWJ~ zcw7}&)C$4kgA=^IA)om??>yWJCE)+IZokiS;W}UOx(Q?G4acvQC@|qtzA^py5IVVD zymnku1&S1!oxr@JZcHos^9Pi&%mDs z>mWM)J0j(OLjPVvs-XWz=$a1woBb*H2UiJyzyB5dkKI-U{Pn}&A9%~3p?^V@@K5+( z!T$vWJG%VKfMdzevo}Y=|KIAz|MooBe_LKtpa0Q$E;@r@&Ku?N4A`nE$$V%CM;X_7 zidI1(`uy;}`qYR69cgA^GFJ*a$umBeuM*_<^epTXGp#oZ?O<}!YCP0wdf4yQJ?x7H zuvh30YUJMzJ?AqAWJkYY_%HLJvz4&(WFd0rUa*+KF@~F%`b%QbB$>5;;4d$js z5B5naQ<_kTp}U~;jb{c%G)%iW?itu0mFNQ)vCB&wi#rOyZy)#A$DnpMn4XV7wec1s09|-%vB!@VEU_@c$o-moGuEqr!hy82lq{45z<#{>FO$ z_BBk9vjZ&~-&#+%xzsC=Tn>mIHMkxgJ;hNpI5*2%ed_I5yxE2a;bE&<$8}0YxpQ`p z;RE}bAf4sjK0)?R4;gz&bc5I$|OhPAiQe036H1fHA)2o|Ljpbfr& zDc+azkTzpvF`!j%N??3{FoXvW2b1iqq?Pdtjl4koEs~<1)5JT|7#@A?ee%9^b`wlr zdL|>Hl@G74A;6cVvzs7bJvoh$RK;d6Z~WP;iz_i`9czSaNdak$7Dc4wz@Bz{ih0Ze z$KNP5=1CXjKBDG>=6m*Oc(1iL-)rU86-d3wBy|pyLx^$q{0Gtk3RM`TkmnE{j4;;) zP^KwX+{vCZS!SS=Nh8}1h}Xd(BbMSPv0f%ICNG#w=i|O+?f)sj~E|_OVK_x)sLEO1q?5`qHI17v(G|?knEk@TWq4N^x41Qap+* zLk>JIyV8g29B|`A6;eEogKHqZav)>_2VDl^dG#cpzX^`Cg+H_2ml^zzrxXxr$POR! zT+1b_QA#;*8P7T%GfHGT`+BK)(#=Y?ds?!cWHc6Wi!YRvrK-v>*>2cG7j09BmB8a8 zO#vwK9*3OqSFEy~wAM*UG? zBte2g@Ew9s<8Tv}-danTZ9x>wXT5)9CN4@VI~XEzSsdlN!svvNG<3BTNu%hTX1ZUT z$M_2oPx+?3&c&$dl$3xAcF1=T=xWLL=T_h|%J+qke8(Q<`Y-GsN5Z!Q-7pE?j0j!A zDc(Ifkr+&1vu}WmpC*WTKM={=Z6x&tOqNoYhahzszZ@$L9244;6sP1uE1kk#{l!|` z3IempkHUaw|9xa)#O)vi62VI^V24NzM$DaAR2w zj|x*fMd@nig%@^LiGYzE$P(E!5!t7Z$hXCn=B{FdxSenyQvu*NUl^Z8RI2J>O*ni9 z;-Bl!9%eq0DxIu1hoSIZwy&S+W$Rg?)61;G-5iC@hqh!KDPcA)DsRt`HclPDzP2=F zwppA*$uQ$3+HZmQCT6149oF5loAlKC+hA)bLBJVGkc9(G2J^#e8_knzvb^!fPU*~WiKt?Wo7@D zIuB>QG!}6-5+@_IXT~lB0J!Rv&x~=a06{)8mWNk)JX7ysS|OhqdmK9xo~h@ekKntZ zr)VO^Vb7F>=mzSUv7LAw1tB~$b~&sTK2GKTk?>{oSKBfe`!7w&;`Ic^BkY=}7|izW z|JvS``3Iu^iKrs$iks2qV6N5b3dteLkPJ;d(*p;eew*jt_;qQSZsay-( zxy<_c9@yO=r)TO_iZy%>>=+&n@=SS~^jGhJ4S{k)kne#(hiDYvcw+>`n?vbZ6fgM7 zrg(ykarrTexo_oJ*tbE!AIHa?TJXn-#kf*FW(l5Jit%|eSE^k$MRD&AeV2_CFNFYx zaJt7FF94Ff<0axTRl(19yjCf2`Ht6_Vc@oi1a}mww7}i)r44R>L@QW=-Y*X_8vEaU z-0)mNc<=zE0}tQfdJD~io{D^Yhbu)rB*k~Q{DQqDu#fePAm8>L4m{}&JnIl$LxG)g zw_9L~P)VqVqc?D#KGAwZD+x%F#DkFszkEY$!F3dAc|%K=<`xhaN;7)YaPXIlTcHQT z##8V`-p^9ckE!>wER<)PMAZ7|UT7hU1>L`}S@1Q-AK8rxdM{j|STLryn+5ZbD|DZ{ z2}Tj+yI1*&+QlQ$;6rik@Kw^h>x=Y#1nXq)8S>mNC@U2mqms; z4g?P&x`w>`7*2}ex;~2#Gzo*?>l-3y&_aWtXuVB?hBb#E^nsfOYtS1*kMbchd%Wu% z3Be13z`@EOdf`k+|P0%mZgE1;=%q;LOggJ$u;D`HJ?Yf#ulWYP6P$3 zZ;au=i8c!I!W107zQz=sD#vi_qsu%X2|j_F!NNSqiKXCaKv_K4`*DZ|kJg-m7b>Hr zkVy&>A}CniK86Pl8wCTx6dbs&#ysd^tfjC8J_|^Kk7M8s^B^mhf&ic_9{jR4#DhUK zr(ht@f<(*#nvsITxZ5jC!4g*t501A{&_7JUukC8ggArSzHE}wS1Rsr{pk*utK0sMK z`01k%4<4>L1!HGKQ_z$Y9Kc;#VIC~FA%+LX+9>E9reJqYjd`$cTC^0V0!a{Fsx}Im z$5P-0l*NM|*MxZRK+P#QeP%QTO-RA7d+Zd<{bvjhYTGF28Kz)Y+ZyxW%VE({cn3&= z4@XdNMJxp)0A=xDM{$S;eQQoZg}Ik9+#1g(1-p0KdGG}v%|mf#LBz5fxW<56tkMfDlQfVFz=#$h^U zAi0JdxxaffNBWVDE920yw`~j^ZESQD%Cd|&x;L&l9p_JvrekMI(D6QQ5{u?X-&i{4 z0oLM2YM72fBwMRSj-3=&xoU}xq{zncC<|(bf@J+R%=cQc<#e!>GovUhf0k3T8TD`f zimvazYbbx*6c%0IM-9cv;g#%Sz*_Zf9HwIil50rEk>%0s=tnxPj6=uX>{$8R=qOwo z;z#3})8X9~&5xZ|Q~sfQ#=>&x8%xJLz*_uB4bxGGSpF?mjtP8<~>-7vy=SH>jk{025W#PP$IY_bw$u+Fk zDmmJ2pEJ6FBzPk(0*ltS<6`OPYNKQR;t(BKHK*hD8PWQ7s5$6Z9lF0O%#SD9#PH)& zz*=(72-7hi$yPi6ehSGeSDjl&7xWAZx*Y{Ywe!iXL3l3N)>QfoGVv9P(6gAzzy%PiH@NP9l zm0f|NE~v7o{su+Q7!Dq8n|&Wa1Jj+ z-cweeLnD-<%A&d$6zyYB=%Sv(=VV}019yH5oWq-Eit59n-oCUd2L8m+2({WFqmrF5 zx~PAcqLv%D1u<|AZ$5f?*6JuULba%}sNn|1BQYp+QA_bTYt_}jb%=q(j*uzpSr)ba zlB#Oe$e^efgF+Y8*%Y;lV<2k(y^MwS+B>|@VN7DJ8ndW-sx0bVgW}B?6uPJ&q|924 zFmOX+;2ho+rl`e$RR@~JsTKV3%2jKF;>s8lx~RuZQ70R?6Jp>T-c1;NS*x2_R3Kha z(%o+2;04BfEQ6SxF}kP|O;J+~+=Li7hj*tbsuUWb&b1ZgFg-i#)Yl-mI|e~MLZl=9 z6F>gpV*J_8KVS3D7XJB+e?H-#V*Xis=SrI z5%x*Gz@?Fr?kwvT{<(>NT>NuA|6I#It@x)o|6Gng7CH6ILvTBG#aPlHQ_=&mB}tv< zLfO=wi^3ShMBsKF5{o3wmLMjxG=+TVSvHay9!)0h^y=$VJ@t-FzmvPipAW> z%AH|wHj2f0CM$PaSPO$+VJqCilBAwML1gY%S8Dcb02r)4jw2^wO?HOyup`s^o$H<(wWyy?b&)bvycghWajvD1WQF zE~Q&2PSWKDx@OVydToRsZ)48f{YfV_1C((Z-QWz2OogQa=j^rgcH)@=UObedPJ$*N zijVhpSkkCFPC>M#BRd>--%c;YFHf2TJn3opnD?=mkJHrsG%o#3*Jsp4oPC5b@h5$Z zN1op91-I}7A@qJkZ}Oxk3pwpmNekb_Sr11Ih%(pT4slUD=?C!4e=grNQ|g#Hg?MM) zWM<%Bu74ODPF-+fPei;B40SGlei~TszfQS)#y2#usLl+4BH$&uJp^6BF-6rDph&*u$su?Kc{a|dIHgcB`jh-)2K}@|9t9-(?6M| zwf9!$*M+J%ycq=c^-u4{)8~#+TM2^`=nl_ZKKTv^&@b{lOoi8;(+u|6 zQlcRO&V=}^TM@*2S&KUQ zR#ACo^9y`Q%?r8SI=s|4c=}RnLy?0RZxrsKh!^IVd+cbBa0V3!GP<1hGle^MH}Z@O z!twao=YuNnNcg24^}6w$ER}=uN7Xs#8=QV}2Q&~a_!~NbI0W%}PaGNj45!Z2C+Pbn zc7$q(p}<#8P8Bd8;UZF~GJ(v?#J8v%)|=XPF(V@WNS<8|28dU@1dxD#IhwmA+UUdyn6>>E#AAB1ZCcF5q@A< zKX9I=mKyLdH2}5iE59Y`8T_i-p$x2!szI{{WgRZ<~FW|Rd1nK zaC^1*5S5ev1K+Sn!%1JV zGXBgb|4|nmO}Tpc+>iu<8zB-S4a-S3Cf(lz-`HegX{PE=W?==Jj-;xb8VELZ zmGW`>mUBcg6;z$PFs>rfotE^DG9(0Nn^6n3*G3N?Ql!0^svRaH@JV|7Dsq%11(~5r zttcy!U`4ig7};H1f$7^35hQ#NL_(jG;0Sq4_!a87zDUL8OAlY8qV_#qixEYJ>o1k( zsakSxPnwCRk^@r#SD+wQ^|^pch*iY4X?Z3^#UtMC1GOBU`cymjf!g_}IQ@0fdyQz` zp_jwc9EsNWUF>Ca4=9pZ*L4NnOF#nZ%%bi9QH-tw!Uh?_$^wyuO%+Q+2-|ReHH1w# z!y=4Vd4agR+k~(adW~p9qTEmw_=y&K8BN4S4@Px4SdtBTZ8|)VKU1SaeG|&&=zh?!;Q@y?5vAzrGe3yEKE(Ga7+$NF!#hZ_ND2Q1AHl1U zcfnxhuZCXfPbI&Y4FUQ(U3yIW+5jTkTn&lnHn5@$r|?Tu@N66)viQ%O;5=yA->pv* z#zyGV6=NdB_AAUvqfe)%S0lDvr&(hAJM`%U5EZ3QulOSg>mDYo;Jj)G>l7mF-_fV~ z2Frh^KHUi`l8re`9rWoZkQ|{;FG0bo*QdW|pYKk!+2=d)QmuXdFzEX8_W5|AtJ*$q z*X*Nq%{FE)q}8EM*k$`Z!6CcNCJ<^e!;?9Dv-xOm;N5K8;4L(|-#L+$-_g zTs5411j6Wo_k4DbIsSeb>gcQ^l?6k4B;eWKwj(UI+6Vvz%PoN4)optu(#T|t!FGJ$ zLEmqqJmAs1c4`x(^uwpsogGM2FOK{+_QR+$s%lbAEQ z2O4artQ;T89jW1*ayr)Cwqs(BuQ7(xwZ#f#`!F!m#=N-vW>cbEN&~zlc>Vzk4a_iN0Kpr=?xYq_&a6f`nKd&Y|D24 zh$AvQXO$gjSBdy-?l1W4+tRMdFWK(Zb@Gp6Eghbgs9F>bXT?|U9kp|PoAvkDr<97S znU|W%57m{=2|QQ_wLhHW8*rG6uqyA*2$t?un0XSKuo1}R~M2Mx{^>>=7tvS^DC%;B8CkUE+?3T9}A`uP&6gEMl;7NdhhWz3<%I6PN?_~0jm87CL} zBEFfFgF^j7Gjb48yvg2ni8$D=sc44)0uDqCTjnlGTwUk5gciFW-UlJ&v^d~!H={P< zQlm&I-3HuJamPqbwsR{=vfZUP4Rsg=BWM6etrM*h6ItR>R}+}nowC|_D;=IKfQl+k zPM(wB<~pX$P05!VvY(zqp$Gq)Y$V;aQ|VwO2Mcne{O$8@vRZ#4)+I9;uVC;6SY=n+2P~Xk$=XLfMI(s#<`|0e%%=YQ*`8sG+PuULnkZ;RSs2`_COmYSW*5cv;);B!qYmmTy ztM#NkLCwH4!XD{SgTU%TEZ$w{o2^*9-%Zkc|9I7yZNn9Ebx+na7B`Qi+<48ruL}Ep|Je*on<(b3Pl5t3-_> z4Cei55~Hy~^_YI7QhGF=7a#Z!Hth=aN^=ftrphr@{W(QfwUDLDw4z0^!!wG_3-iGl zLKEt|8eoihZwH)kS|Dpzz8nWa_E;L=K9)3uvKMrf02FA+dWj}kAsjE6}<9KEsB(C80z z=1l1WSWiolLi*DxTn*--zGpZ_{!|P@mVQ(;3p99T> zT5kn$xh=5dh+nJ);;%E{N>6Lo41`#Hj0-bt^Qqv&MVnx&bJ>n0+@$LA55SsZ^D3Hr zdPrJhPX~AA>yZKByu*$DJjcilD0V?QD~eFkPimnptP?)%SF+$w3UmQCa7dUQ@qA zYTX2fcNvks4N3Fs6f7;&&BYbSzKTi)-l?i1>WLylvOyc8Y;xVJ5^<-ubJ_1nxh*z3 zo)`?_M(7u0$&u8yb}Dxy>$~P{MlkGL#@2Zpl8`!(d@onmBt)LbSM95hg{j++X6!Tx zrBwNu)FF5k(%B(Km9`T#g_-g8b1)QEILNaYkRlB-f*^(QLAb67EO!uOSUiyY$C2HJ z*>}Xvz7yGL%x)7mI}6!~%uZvr4qf~MM^AK0-^wV;?rM`fMbq!O1pHN9MIWN_(#)KSHrjGW*@Q*;A0+kJ(Sg&GsYP#q56ZvK?MtiUN=(1aZa(;T_KaIffwT z1H_ndWoMh&b?^}M$x3WSeNR^RH=})5qE?*}SDJhA1=)5C(6OPk*5C|@@hrXw;_Q!n z{v(u$n9JUlzt8Y5*29DFy42|fR=LXrU?=|u?*zf}`lHE}6<|sETmY;)X3ADYtOwZk zyGHEV3T<+s=Nc!!v(pRk8)18{K|-@4u5&Z1SYjnZ$e1~M(nsT$|ImZ+`vmtmtQV;ZfOcyLw3UHSL*&PyBU3YdT` zC}A>k7}bH@y9^8Hs0#Q#KW$*2`yRNfe_D9i+LJE(H1lzAiT~QTu>VsCSWveFKNw$N z+#Lo{T<~>saE|CZSri6Hhht;~U>2nCHIP{`PX{yTB!l^xpPyJabZ^64XbOctSoCSU zvG8U~nN07&bcFx(V-&>>n15RB-NZ@jd^Sob7}gxa39n0XEWy1W_@Kjy{GeDp(vZJ9 z&34C!*!W-aIKKqQCuv$^e!WBwvxP`^wWy35H?KPu2+(&HNUpJ0DIr-jZ7jLk`nL6j z-!gy1N-9J|Us!+yh>wdW+=JBOTQL{nn+`gIy!0k)uTk6Q*JbJL5|$i?Pf+y?=QT;w zz&D5I6o>^7l^YyOb_b8c%eZK~j}mWJ;{6`uG~&U?#5r7UC+1(p{FNNXb$FT5rbp1c zN>v-E6PwvpqE=BA%zI2NjaPB$ml})%+Kl5!chqP3?3ebAMRtR@*;CY)z^WVIin0;r zA$UJ3r=M2^Z;@K#eg+_rv_R5(=W@g6GpBDaX4B9QUvcnm7#zJMK5h1Y+x)Pr!)`(S zkIfIqQSBp|=o&uSV73vS};b0J{a)r_z{n`29Mj1^?)U9Hbm8+Xc0Y*a^w$N({ z%eg*mmMM(>R6jpFGh7Wtk;Tjp7thf8(;1~l>reFjFoQ5Q{YiKuG|RyJFjec%HI1v& zpFl#S{`|rG@D70g+w;RAxS%e)`t{#DKYS2oVq}MBgcdbFyz?WLTNC8=cpx%AJe%3A<7VH90uq>g zcHHbNWPdjj*$K?n^TSmfJz@GSmQj@R!&&kaO~0NWUM2bvl_z$Xk9a3bClH-YJFG9W zeQ~onKfHn2edA_xet0pnZ-|#2njh9BNaOe*W`6ji7a&OhG3H&h^TYP%>G|PAF^Qw9 z0#22CY;cDcwxc`slheL1>Pu+M78^M2Mes~WD=ZL;j2HKeU z;TP}f`Qhahi5~b*vw85wTh}B=7(>@tGM(_dqx0l%3;zS^_k2MH!^#V zR4Y1riuw>(bzkuZ^TX{xVCILzFkP-@ewckru5W*K7wnmfi`lwPPQ8%h^moOY=~Z#o zZ|ESAupjyu;00{(kjzik|5M)N~|9 zxLEW@;>$?HUS%P_^&_F3|4PV&lsLSO&auxp*E6P~vmZ16vK)V9q}Q z7=#!^h$SA>&xtK6(puXwvXUekH-J?R@A3FLwDW&D=E78h0)FO7A7J@q$hJSd69Rp3 zG3a>7&w(%T02Mqze=!WppgMJE&(n$!s0W^mP^=jw+K7XM0*eFi1JT`7` z09=8ly&BX_C|G=eA2`N7jXJT(e|HAC6{UX;Z*%Tu##z?!;Om5h54F$17%3e^<^@80 zc%&Z1M3!LhS6Bo$(%gz~v)w=^Y1R<5uLNuLXk)Zcb*rM>DFp{pF8-(=BA77Q9np+?Y&5VYlopp&R>p49-4_JsI= z>spss{(e>QChUh&jG(_zzz`s=-oz_fWId7|;+nhO(Msy0#kr7P!X*Xi^~gC(FMUop z(ctC;bt69F2V`9K0xs8uIcK@4(1S>`u5Orh)3I2U{UJYqpOmFMsBj_DLzG5}n{6x? zH(45A67LSwB0JDU^oLULEzfE4lY4ocY~N^MhnoKret(grt_&QRsf5eWo8Ja5NvO`v>$ilIO zob)ucb{|I(-a_eH=3Ev`%dd}JN*sp4AqqU4!B61a0e4<$n%HkvjZXkm1B;7*Le;|< z!5(fRD!ep}DGM;Xpm)cHq|4tEyKlZ?M*}DJ@8BmioqFR>+I~1Wp`dv}-sRcu9BfHB z19J-b;W>Ljh(_yld)XT%s@s33AzG^D-~?gt9aLqv{zjuVAF4gEAEx6&l$pOg_z=Fb z>9?&530@D?H-4?+<#Q@PgC3lAw83l7v^jMtLfw+6)j7UOco^j*9t^2465(tleofj- z=rZvVqVw4rhnv?1`_?p3?xH$iYCXF`{YuYiOQ9SiXF$JleV6r=*HoK-7HX?Eo zp(mD~lhwkp&-oa@qg!}yq*?9Tp!y-1^%;|104}p3NPQ0GBpz_0^)L}svOW$^kO(*W zwz!wWR|}p`zr*usvmhiGwl3sK>E~kbmAje*a}re~KD5YgU~e?O9HbdJ81I;Ng3s#A z(5L3W^S=qMD6^^xZR$=;kzQoM>jhH|)J)6m2+oLEa;u7Eo#U`9OKM0wM#ntmu{u^% zfhl!EiqEc82)_X}uD|J~u)o%YH`CB*b#ee!*}`8!h}3W(;5vkCQF~W{og6pcJt^L} z>6wmf6%aD&4z6azID<{q*)y5lhS|{KH9&=pmPY3{#zX!T zSnyqTYg3P#e0{@P1>v)txn|FxUR>h5_egfRdJj!eB?r-1FGC7j?kh+MHz%{7(5xui z_vweUyo}}8-nS}rOV=*mrIWO?td4lk@`i_I8;!3l{9nbDwtAmg-}RjV*bQ|q3prz-m6BhUn;lAq5X`Iw!Z{^KAF`Ff6Xdw;>1E_mZej@GETgy)$ra zA;E)a2;o# z!@4AX4}`+e&JnxjgS8R!jLAr7R#dR`NsLSh`4`fxV3KWvQQT=qtmKzGn<3}ZR*w>R z-p>wSs+T!oKE$H){ATZgFBLeN!QaXTpbMMB1;F48%;F`zs_Y)#b7G}wyAO^;4$XED z!I^<zbzIwu`B*aGoh*peLVFBO+EocBV=PgaCLbgeAlujNh1 z7pX-5;GW8Y$ABXL1o%Vw$!mxASo~mC&=GU!+`ydP82h+|PKwC2y8XzZ=SGtc*dOrE zDG-i$(t8Nf`frW~*U_VP!z=$eeRa}l;qZHGof9fSU2%{q0pB;=7*?uQgNhKXF*L4G zy4xc{-h_Oj41(pVun!3tF9o4Rq0_z?p0nIhu2emx_L@kG!ur!l8CW&%fW7eCY74(X z3ZE^7@aDAhNGGeJzJr#xd>l^9cxgG@;rR}~qrC@MW5b-zS*-S_ zg4>8FrrMvCvf5Eqc*LS~)VpDN~QRdxLNM_rWYmLGazx$J3Og6rqUga~BrgaZ*dSZ^QZ^?^CO`r7FE zKdYs73_gcq%Z1bVce91E`Pe!UFEQ!s(QN&0$iF3fwU-@AVsMvO6cBBzbN1p)NFejH z_85_y!sZo^f?zFlc|6Y$$h=3Bnj3hp5L0D!>s~D>c$I^<->^EqlJX=6N?q*eaok!JsfFCW5dpTEoM9f3QXH{@*@ z$ed&xSnksWrzMAkG!cCz#rHG#l{;cFb5h`j;~3c&Y(qiqO+o9tCq@YQLRae_%2gnCpLzOa_MKC>w_?FkL~~_>Jc8cUY>c?3I00NeGFJeOi z95WboAE*PSHG)tC!w+T(v*ZJ|42@h}BQ+sL7tZphsIOsp8MGw~x7j0i2>mMaH5%qXc-jwcsN)PrCFzrRm@E7YB23GCNY)x|ues2j{vvdWgH zmg%ZF9)fV`7hE61TmdeZZ>LH_I?<)dZ-q*c4~Xs<^OT|vvo0tiS?!f4pbN@FR71?` ztseS5WW$y{N4o%qT-kVSMyx1%-g=NMp0f>Qy<7Go#F+hnCz1Fc+z&XO78F{30Tlkv?FW3hUw<(g zU;MTGfO!Wjjc-pq3^X0|J68Cj_X9qwqsv)?a%=|F|8@HT@6slS%i*f_10FG7ki-9L z`vJA2P-_Y8KfWI@@Yf?X-w$YwkH~5=?*EO!}|dXzNYC= zll_3y{V)^Fe!yXjk&*iWQ@+C>QSE-fhVSF<2Q>H!ghcHJw3i{cR89Q6n*D&SU&eme z2p|59`vDU%L$TJC|6}_BX*MFNTHOAV`vIGGvp#>{et$OH1z_ry5F+&;5X9~WymaI+Qlt0L z^?txGA)|gTBIm*cW`PUv4CFKOfc!>5UcZFdW_X7?e zjz?T*Kj1YqMRj0!wg81Ws+_5Iomod?eQ`Bre769>RCQ3rwq^_5f_JD>Lb zPI#%{q#z2#zBCS)IBWWCMRMZp)xju{br|=xCeYoaYR;c65v@q znBBUD!6~0s*ceDW>hmz3$nW#}@>}3G-=2UHF!jT})@~9ZloG=v8wOJHBPs*Z9iFFP z_)Dk_rfy&=r~5cjncq6Hq`XYEhe$99qIAsGQW>_Een&0!++l^D@pA4xL+xB&QCYT- zvxyPIq%?gRhR_|Xr4t_qiKEspV80lEa=f*W12nv?UCPIEL z10Bvp2kG>?`AxxmNk_zM4UayMUxpOd;Vq=A0)iMK)xNAdj^WYL(92FQ&~BEuJ!IC) z$fl);PRifX3U-PMS&~}lW~utQ!|>2ENX$FN=|7f-ii?FNkeje{LmlpwOp|biY5+Q6 zZbk;&F9MS@FkW25a{N=-C(6nrsxw-$tTX51(+h#d>7T((7pH&R0RH$8&oYIh>ru}vWY}J<2Q{unS#MOZUTN)cj*MQ zW`~D8&ru*&!#}l}QgK;7)26Jdmi^Nt1g8NsIy2qMd_f4TP~%Yyt2IV`E0srzg*1jr zLg^A}rh0rGB#18iO8y2iU(i)n^S-2N7+zKYBl2bs)ABhqK&ssHCmSzMftLm=y!2OH z;ZsnCdKkS)a0-QmoQWpqh;%X0wf8a>9_eWPnZy^3&66V`$#Q^_d|-N(I;$NrnO*A z-=9#~5g`IIXW%FdWQ&5-h^^p^4*^#z)E2aKOK@z8nwRD31azTPqejqAl!xzc$M@N_L>w_DTs(G(6^6mq+nZF z=q*>De_<0bZ=MG&pAFR_PSxa$P&RU|069Sfy0A(l{*B?+Ahu+ztYEV38EZtL^aMPU z%P;QLHm2#KwT0;L971*wD^C`DSwmBos8E{!!sk@&nP9T2hd(r?qi{_pu4x9BSfe9$ z6`__9gUfuWcG5>H+1_=JOUECiqHTa7({#{aY*nWrO^rb7gax2a!r@_zbl-RwFI_Gk zUX^%7cz9cSRXpgkat_2xCV@zpEkl8$!I*RoMM%(5g&hsXqfdt+)ZkUwS#~sdJH5BO zPfH&xzq8Xv%kLuDuvF>L0Jzckep%`Ot;P5cilK!4*Ngo!dL&b6TH#DJq4=men9Nqd zWY5H)lAta#nalA4=YQx!4<~ocN|duNx@7EJ$;;Fo+(Rl+n|2?@vNC5IWTS1Q?TJ^6 zwB$BN+7;wu0Y468K6pJ5;(n3MSUb8#4WQ-DpgOD7L=05^<56s`FNm%C1!H6s%p5&L zQ_zbGvw>FSKNyWfGgEINfH?{ICkP?Zw}4G|;EbeUE47a)^}EldRNAkm)JvmEeM^_x z(3HA+h?F|SUh2gtwQRHv`=;x3o!lDxt6}V)!4S3A=>?5__F!G7XEgTH?bz2N;Ck>v z(-}Tgt}FHtQ9{KHpLKJ|>#lD4$m%Rt>88T{vDIude31RCONb)+(|lx=t4-(^2wV1% z{9Pe`h#$OC?Ji-;@$G%zQRhmvd>R3o4BGpMNPp+@bxLg5k*tdB?!L3G+U&pZ#rAXY|FZF$L^y3qH?ycq~F- zd=#V%J(LZCH}?`+h^lJ6Bpz8fC?tMYvyCsMxGeMb3eyf*oc<%WM8`CbSnl2g+; zBMD^YVcmt&=mF~i@;y}sS&{FJOtIwqyO!@2fTj!^B5oM^lvlp9$@fNt_F&%rGA-X5 zfhtnI-Bugwla6AfH(_~Pa(RDEZ21eIz15eWYAZh- zEkR-)(sX^}ekm6QA8=@o|lN@+e3-!mBpz1 zW2k(kWAuGe`MmVg<&si(3ZI^!hN43zW1a4JuUZRfu@9X(yr?+e+JXL|0J2FrE&G~~+Rq%7nJYx!3DhS2@dUS+1X!fF9_VP!kK-b)qpQ;rowr+f|yVr?>uZYJt4RXeVBFb z1&(-W+5URzu0WEy2HQ0gbm8~+m%`P`_4qu{>P$Pz4Yvj2lP}5)vvn%P0?ZB8;o7YEOyf8cph-YG%c1SGeKu{Kxzv7TcmqS@_ zDH8|Cvh^AO9a1jFopvauYz&hK_mt$V<6m^p!H3M;rvP0I)2#8uiaMQ)CK)l9aObaC zQI-cmJ3Zu?|BYmH0|s8#tNYF3K-@P;zEuTwtzHvBn+!=9B;yI5kUAU-|LT0$BGv%S1xpZoH>4?!=jG~H$+e#wwGIKCJ(5HE;&?RF5=7Uob?4GR{9 zYIwfn#@6t50kPNcw_ZTD|6fwWJ2%;C*wEB)!MD1G4NVP?3)L`zHSCU(f>&U^6f1f! z4voWM z0FeRTT%m!Z$=1l9VP!e3hmO`mH|wE?^}xkZ!81S)_=xeqEROcg)fXMHoPd+ja;-;E zvyT=WQxCxCB_G&iIX32P5DC8aS*Xk1raFGd?zKc6z`(DKeXKt~t3&ITZ(JeuWEVWX z2;XCFk*G1F*5CAmVtk8X4?X#HcC-h#YqW0yEk8Yo89~__ENHArDV5n>)OohN3)F*i z!kxD)7SWcMj+wpi3DkzN-)QR}GhccW)tU&=r5Ks%Nl5-Ymbw%Dgtgw&734kza?LiZ zSqSI`mPROs6A91(Oil~ITAZzy9taXs&o5;)Gta>o%tl?h6vYQJuLnxLZsn_gmfo^_ zR<{q2(xz?wc>+wT=V;C%qOe>n6XW{Fro}wY7umJ{>614gx4m}z|)*9esOqCW)cP#p#_Ke+|OarA{>p!)uc#b zxxQCd`ZYBV72-5gnn%EiX)@w%``*^maCEUP);c`A>&PT+1J^Td0gLoZ>vz)4e@d?5!ywy={AEYvfk{pyPaU_Zzg z2q4K2NP5Ls$E75NbDvjdQWko}z^a1WTuC+2^#Rl%14aIE{uFt`KsS@S9l5c$6I?C1 z5z_XVs|Te2<^2x}NpIvjEu^}mx0Y)2WwBDNQkoxQtdEkWp10YgS%EGtR+>k#3_$e^ z%BU5Vo)M@>5huE9EJeKqf7@LU-8KvtGJIC3^Ehe+7LqoMqALAEo5=ieMYU(TO;o&G zG(tq1Om2J;%`v(0Mf8H?Rx6^q{~RllD})Lcy3tThn!YBN}j)fdSN`=S)7phq@3ZC3huC=P63Hpk02r#k{4XGk@` z_aev-;qwbW?f3>}*8tbf12$Y+_`?0HY~LPS#OD6)fbR?Ua$IUrr$u{Tot8N*);|18 z`#_yW&cwB4uW(=MkKuyp=vl`73Akx6@}S&m*$k|dwa2K8l^d)ExdQc{?T&?;987L7 zG#|N@wqLn=Wer3XXw?%=PqKQ9?E%%bF**k1E&UAUS0J-5KI3c34cIb3KPN8(S8(6F zd@+csRL=u2xB~oBu9!m4Vxf2FLPwiIFVKaSueKGs<3e5NKXsuEO`)&+(^lxwJtuKn?yRGtfqx{t=3*=e+rOTd_XAl3%J#2iSsSm>u_w#37FVFi`M8RFd>fnjpfEY9|MWrGe~_jbIB zWsW&MeG;)(q)lfvb0%y65ELwd-o7n@(qAt*VjFl?s6LZ9qztL+z6RqC?l{MQLtKH( zyGpk;hghz=Lp>+&IjmTHaG%khp|2B-~-mMap?L@7fBFmTfHLC>5@}Gb6Ot`Q5TOGm=3djwhCaf{(eZPMyJ0wcW5!4Y^Qj4lduTKu~Gh* zI+|ZeEeQ`{^rl=5r*YS^-g_ky^&~k14mMXA5M=O0=pf@x_>&T)Mmbypo0i^<<;<~YhtX6ie3I5s6ZBE@L0Oy zgjm-A+d7o8?^yMe7`#cJz7H0IGpq#K4$29!7+7Z_7fHfs7O9$3pLq);_FsX(YFH_# zKF5s~LVc`8wSd||qfUDZ`U9^yVB(4_qKqPq+z%{nSi;zLhmKMq- z4hT+NAmSY(?b@0gT-%AG`ln9c$Ep+r8l1F#*GvU2U-1HTb!>VkbVlP^$+ln`4EMS* z)y3C>K2;S9`rFbwawib1zeTwMU#fTN1tnQ zGQ>7;@;;=Jx%8bV!uy4k7lbOl6xxkKE4Io9lc=j3sK4{24JN%yIUuc&`fD_d5>w5g zVY&XCbj7RcGeU9(JvR_d`+uBcdbq!X&jmtY!`N6UT~n0wS$gB z%R+_&j$p7i9I=w4S?s(3j&%VrP}^x;&w(lPAT>OY*@f}Zz`T7+#FSaIIAk(yQ`66) z$yB0ku!d`3gYkkSu{-^bq`BAEQQy9SCPWADko}EXW~l4l1clTVdQO6|&y)TB^G}hV zRz+mHwB;-rGO-7nbQ{y86YwVuHqXhrb0J1HFKS$Ks?Z5DXtS zzmE62F^@6ttN7m8I2-7$X)wETlRb&qb7ejNImYIXWd4o#9P=;J)WC%_XYIktVCYGR zw?rBRLR}SbEeZF#%oYTWZF(@Iv)~L?DUjJ3b!Eqq!zPAdB*Ioe`o&1Mu3kFafv{+k zh|hv#xQ=a;mMk8r_rTh;#(Os4!DtEoi_qru$X`bq5Hzs8?;w;AE5VJm{%yWd>))&n z(6vCTmJ4nAcPS(2LN{MnCHr@(9L2E$kG#95Qj{{d7Cf{}9p=0yTA(eN1?jqq*=Ol0 z-X+a8wu-q(x2kw*xQdq{8C5()D_T3<7NFQ_s(22So{cP2#glXu_af2}tFZwd=&0hq zFxH!?&^F~d9kF>*Vf?xv;8gasU!h4cIN1hT1&wqSRv9L}4!uSf=pwc!Xyb@=vIx0q zr*xpx%o^pZ>09x+iD@%h`it@DsnQsYACbS+OOumvKQ3DePN|KbL{{VcgH(4LA8!&~ zqCS|ivA|_lhh|EMXFf;wxrZ?;BXDPmAJl(?v7N?6j=Wc>!><58s@7aBmrGJE6UE3SJ?}u2kIGo16`{6lsX`YyGY>`>VDSmGjtQyM?YB)x%y#M*@ya}xU8%7aJzw#X&i-m zAA}KSKnq!2>?u(!BNU6tCj;8K5K{0K6s?j`OZ6;Y8M0Izd zPh=j9tgG%t(eyv>zG5loi)s$a61$6-|9ACg3V9{A)SuFyS70LA^k)}(uDJU1EDV#X z^=I*$ar7tQ1yEwspDd1)f2co?J{_$;^PdmniTplVf3^vcTxX5cpFuVZ)StP4i`Ab( zrdF*#%ZMaaf7YUwar9@_I7@$Wp$ifEQ@uW5zV^4C7k^pE{?q+Q+2ja)_y&VSQ83O?Qu-+;O_8l9o50hoErn)e|s7=7Z|-;Sl~=d-gz&wu8;courz+`sR<_?}l_I&ecQ zkok2sOwwj(&NTmvs8ag8_yb^l^m*}lfaOH~t=F*pi;2*7f(J4OrRh~yKaKLZ2{tA?TEwY#S0ATt!Ve07Hq(; zx=1ys*RV{dGWDWG9WKY(UGWY@h5a%Jm2K3lP)H@_M!9Q zCp>F0Ao{%c6$Zf=qArz5TNIYR8!so@m53q5?o)<4@O}5B+@ta-- zXY_gTNoeWxW6~Sj;q&6#P`}9Y;!W|rdIUNTH7a`7##8IO_%(*4XHjP=k)PATAA$c* zo)^DJ2sfkzGIzBStyXWpWD~JDFaD(EXIZAwg{=9e-d`>MJ z0Vb$##K?`oRg?4LACBj=OdmqQdfH?dv|Li-Dtj7NB(Su{Uv(2&CoDqkJ%@+?=y~y9 zQTcf1#aoUO`z8K)@v}`PS3P6Si`O!l%UO3hFP?Fnp0}o6j4l~dStOUJSFotZ-w7Yo z{JeOZx_YJS!WZP^b`~vny>yk2fy#ci+ME~fc8#Xs%9f&$Z%neyoUQZXr-2Zz@H`A` zx&yxty*Q;;K#~KQEljC1pO;c;znW4jVJg~7HRr{5T&+tjx<*QEVlOr3y!eD0qd^Wq+Z{cer@cYLM4uNw$8U9(Rh}0=IzzX#h)?x- z@d@Y`XvSA{Ufhj*%fFQIo}9jF&x`j2_lv=AEUJdiix(ga@LxMG{>!m4*su#N1WL7k zJkJxyoEL9X1YN|U@MOT)&x?QYB>T#8btk6+fy{J-RHGG<0!tMurXS&lV>tYXj>4o3 zohLTu#lLT^1-cwgLFkk(dOIYa@Okk`xX+3hj{=p}xzng~C~}O+`5rkG+8U4+8s>4H zxWCU5T9xO;-^Hi;JaHu?Yn1W>-=|AJb?eudGRe?J*xcC zdGRHvy|ur(BU87dC!xgQ^Wy!VV!Jpqa~!wRcwT(MSng70E+F(DoEOgmrvJ6`;8r`bX||Q$7Ed^WqbU%Ad4_Y=fyH zcBNU&W)Gw8eI_Db+{ORi^Wtt64fAL|isL_PEuBTFEto(2_4DH0&@v~SBbo%6{ zIWK-XUVH)|32}%dp!4B)$qqmIy!cQ^&RQ;uJTHFENHYTe z(RuOankb$Z4{)M}QoZt9qN+JBz8r0q1%qW(oEQIl&+|QV=YP|AzB-1QD$n!ne20>* zP}iVClKH=MO!QuCf+yvnI57i+MCmsb8p1J6p~6obVM!I+&DEagn>w6`qR#Uj^EDTa zqR;bfudEF%CJB?qVQj)m98bGV=XPV4F;sMY;9k~t%GEQFFI1PbUnRM*r`;YD5c_Gj zV>5s(nYV@qTHW+Yr~w>Roqy8j`97JX*^-X>6ZILQ)}*N+p49y)Df&F$M~}y;Vft6` zYIyXhRl}8I!!=xYK8PB~&ONe*Gd!Uhc9GoJ8U_T!Uc>V*1+oj!S)+yzzHF=E!#Lp0 z&BC81>Ka~4rlE#c<5zgCGVrAQD5=`>e0`s=ME|#)=acnN%iq(t&l#APip4Z@M{|Vd zCp&w(GQTZ$G5ejV>%eFX2?fYu7_C?M4x4y1-{ChU>DOo*+2Oez%Igexq=RkOY`?Pw z?x>Z(!_aefy69VE=*k=h=3rneWSWsmE}ShJu|cr6nvvCV^U0h zh8|_e1~f?>#n$1S%38(5GLZc!S0FS05^Zdvn}2__89GYTJwKyJI2If#3>WQN5nJ*_ zDA|3eR{lup$|X-zhe|nO+#{$;)gc)4!CtWb^*&yRY2J;vPZeYu$G6$g8gG%s`fSH| zR1#N3d$8pigfU_BPqLU^)v1e@heBTinNKv8T4AQHwvJ-0zFUwLI=h&5F&e=+XGYI1n+`ZUCjm5C59)xb;9){y zZD5qaUV>qmfJR((By@CMuDTCAwZ_C${jf?$IxE{{y)LD4za9@k{!*5)Q+l0p^)-I^ zP1y&b{l_4>b}+O6+?V-M_4`loL-||xpH4&NxJ#4v=k~J?;g&hue&lU17vku z&rT8gs@%_RMlxdepRR`HS;{0gHql>VhB^<`(6g)$A&`jur!Htd_eOlU$HKh_t-Rl1q-9^E@oh!f`; z*a-!Z>I^)$9p4D{FPy&TQt*=N+oIMXuanC!2+<|Dd_QG(b@~^R*6jIQ)x;Nl6DsEj zHM<9sp^F7kV9sv9U?(z-cSyo#!Yl9Wdz(BWV44bV3W@P~vj~k7VT6<LAqQy4#x_VvBIF2x99G~Av>OKs(+o^~ zxML%%4FGy*fI^MzGP2ANK7(18YY>r;-y2snDH=pX6bsYpMDHuV`VX;1$dv|Do9GQvzuT@wG^Q z^P5AIj{R+&TB|N2BWzLH%3^R$$5{c{WOqlTdkW_NM=1C+AM2N$|+*_{ph+XtQ^ zjBZD4L@ZWK6($S|RRS$2QmK9#SPcu-N#^3}SU5$4R40g08YGRft3sSTHAsR6iQ9U! z2@=R$+fZ}-iQ&TWY4TdC2J%(28bHgDs(R=ovIysZB zUT4WG;+^s}#Oue9s(u|NNru;bnDiZ!0-34Utz!4I5w9`4ZUaE_dLpiktQoI2X;xOP z*A1nXRW$A21_%p!XmyL*HEh%%)$w||2C0tMV>C#0yzWB~tT1k_EnV=G$AoRoQph&k zf6mtsum6EmHCiVbUZ29GeErch%wNgtUU-e+_0Q;M$m5PSYUO@%qRE!s}m*Q%38d!s}Y~HLow_Ylzo70Hn^)Nru;- zGO4cqDC>yk_3w|y;q^oSlGp3dQfkKQLsE%q`s=G%g{pXcres#j>)-F^_lv9J^%okX zI$qD#Al32uX@UeY-xcQK{)ZvL>%;XluUGIj#Or4Pq-N+O!|MVjy{12Em!$iUr|=r1 z*S7$WyuJ$^OwD*bRG1L{z zf01h!`RBuIToYaw^xnn8Ie~k(cF(>o`*sFXqi+a4%Ku640qOajr^9XB5lY^O=s(8sp(|NuT+IhLrq`gFJ>G+=$Z!e zrKTsEntsLCP)*mL4N8l3l2z0B`h(S}x~A{y*X@X^Luy{uz^0~e0!WQQQjKalsc&RW zf5b$JxVOnK?kAF&m)PlQt$vo8E|L67HJ53q>HGY}#M#ue5{DM>+5|2Zl<981hH82| zDg9O_Sv6g+Kln+ezwY0!YdS*%o0_fyka`VCHLB^NK9My&4D+8g{Z)QT)h<0J z5}9t-&r;LRCBIUA!Zg%$C4U2%-tVvewj&fr(-5kV(VJP+Q8?%K_6EG@L{UZj`$byTdI;tyB=E9 zVKK>NQVjW!7dW57G}LiBeuG* z*}QCZG3c^ZduCY=A6O4_tcUr0K;*e z@Txq&A%EYJzZ2!}Ok0Y;@EFvMOk{zVpk~xCwFA>BXhwVAZ|VzqELETCNf;~J9$`j` z^sDH{Yym-Xg?g9CAoEShwpHKZR&wo)2dDZF!tBn5X{S(#Q!Pb=k9bMPq` z`(T}wqA=?Up7Ze)gek-B90bP+-e;llS`Wut57-RQg+FaQVCJh+Zm#;_Dl4m%g(vhd z#7eosdbr4XxWxLZii z``IIvt9QRd>$pOum$nEU+PMfVRUN#COW<+hjXXhn;|AF8HHp^8-SOj%Tp^Wk{6V~t^|TPM9oGYfk`)#q88(v`gb2H! z&Xk#9mGMT7_JD6qmGMRj*lj`A>7 z1DT(2t)~IzALLtIQwecOfs6ECjyF;OI%49DoGugm*ys=@-pJuQ`3?3ALPs+DV$u;C zZ{%$f3FUL$gmWe>UF8DhQ6d zwi0h7nW+6q2Z4xb@#BrSWiFMp%K-h^cq5+>9$T(e#~V3K>~WreE`oe*@kXBJr#ONc z8*k)Tp#?cLj5jj8pC%@QI*xyT7;oe(u`84A>4efzQ>QL{fM{(ng%oXuQ#v9ovOBNDu z(4WADVo8|g|V=1KlgypdIh4p%PWRfsek4&-SU z?F28q)6h25Eix0~5%q6q*ZGs`_u-ixsC$@gNUcD`4kU%*jm*=WjT3Jq=?+q0;*B_2 zTYpjuLL)6E-pCr19_M&AD61ykh#QjQXwiK$N8xJYjf}pHS7Frp2r51~Vc?>Uu{G8c4~Km*{vS_pnGv zV-29xB#KM+q>=I>QY`O14m_%{w6cFI-pFRCusz<$y|?1s7H^~r->Z%{awW5?i8pdG z^Q(SP#*_WJima9E7bjDWkOQc&>d{?NEDlSJds_5?p!u6qz zl9q%WFObi9!+hDn!@CKGR@ zA#EJ7PF%=U1Em9v8*e0)guz6JiZ{}vC*qBK!L3*qdQm!uDKpc!WaxZdXu$g!x!EV+RIwIakEl{BX z;M(63Z^ZMs=EFA>14XIshJ3itwiYQg8=ttv;)IiulL|e6v_BJXedC{M8q3$ZNU&`;*FduekCPXUyvcJ&qKEMwd*V0g?#@Q0*SmqlI}3`L3CqQ z_?d9Lk;McXOt5S-*#ygjTq!r~|BLZP?gifeP`r^xMelO{tbbP7y%GLdi_mY!_0QsX zTeW{y;LbSySsOY-h&KPM6pjfPrK^uO^3M*@{#m1Kcp|@#_Ro4>h>Z2my3U4yZFD4i z$Qb{u0n%@xEys^H@-&ge`e(fiRkhlx%|FY1qvfAY34=W@tK!T+9#Z+h`zmPEldl=9R3s+ z_fo(e5g0CO39Ma?eH(=F> zFcStJuFQ7KtCL>r9>WkGg27D@6)b!be-rbLFM!*4g2UTP>Nb^uEb$>DR;H*f&=oYJ z@vvtd9$7Ge{k|1AZ1#ISPJKqKr1T@Ah!-G1GfOij#4AwsUZ40J>V4F`tQMIh3_?uK zdibBE9yj3Kz|eY2;B&3{glipyO#?KWl7vlzZli4SPbkp7)`%VSDY`^RBg?%#(Ft}A zPIQbsA9bajpNlN*K?|Z%EutWVtVB>zxjL&7ynv{JX#iyW>knCYFA&wU>_xt>b_)|l zC$Ql1AslMR^#CqMUP5W{B?SwT{7roXohg?{vERsLka5DFS(F7E^T9P_*CKsLCXm^< z7ObO*-N`2_4bx11Vg-1Y7dp&c+JP+cfHE!816~rvMLV$C$VqQmtgUAvAoLRpu|D6 z1ESF2LMRNMlWvwSCrA4SJN?HLG*5cG4)<%bJ7ZpU_N~bYa^MwoIk9nZ;d4hT<%&H> zV$WCHOv3$;(%aQ8XkKf0YIkQ~4!MoG3K*`*4qlGni>!FWg{@iIAK9$8{w5dspo??w zN_D!2r#5=zA*cV&6m-0KS3CU=Bs*~*RtIN`ekpmUg!)H)IaMC6J?WQ{zZdsdCFlBw zq2Qm?&C;auw_(=?(XO_JnT~2@VSdR=t@3s_-9u9n^7oW|Y29n*A0!wS9NWiHtnL7Z zUH*FzfEODIxfQ=U{k2{GmK$l6)4*K+rA~kQtg?TE4=p&*{G*i=Ux^ zufdnOEjHx0b^5-|ZLvQ8>s)`AWal+qQu04@aT@FNZp=H`i8#L`UA^3iWg^*Ils_}q ze|GR1^t7S+Hv2kwk^Ps#(#g&i-a@=PJl_D=M!-KQU3GFC>u#~^7rbW^7`<3F2V(aD z+)Ge^)Evj$p6RJe()cBs*uH=A#0IMS0lM*U8lRVwFd(I1ubu+MV&%3Ohd zh|pK=!a#HGSJIV^?kg0uO>z122Rr8C^56XqFYXDi1P8|Q7qBjW)BYfk%SDf2W5{Z% z*L|V)eUop3{mL-wXx}0FI)T0rS>8U-v1|!trs?r&N8@t!%{uUVu9tFUI98}}pb*av z@5#XDK~H}X$Xo3dhLQgs?qld~Y}p5x%FZV+8r@w6q zdKAZ4?mguO=CV_f+Hmgj-G1P!C)LPGkV6~09m{Hw|K0+mlB?TtDk_5m@e*o3xfmUj zK?5XQCmkS_9TDBxJf&)p1)YM^LnvES^3x-2NrzVs3L#dNt!o(v4a)l>8n6dN20)Y- zh7C4Dr#lX=wYyP_6XDT4K`|xPavqcBoZsozR|+qkpOfHR_ETMF#SZ)+=wWB%^x2rO z_T_7wO+I5wYb-HCaX%sk9mWQC7~up*0vY71zJ@jFZeAz9v}|)USs$U`rRU*~I_3uQ zI?~eSO^%`gNeQ)I3#EWBd;oI#qcfS)U$8we)-NC< zGA*7>I*;}zXNX)xz7QBFvyFuL_4(K_Bfo{mC#~o$sN!;NBR&m$29gI0zbL)5U{Byi zaGGl_6iyR-*Gu8SciF+T^RQ)j4Wx~A+aFz6K^S6Tk#=ak?vLs)mw+JJ0|nw$FR%1* z+bT{*mcwL*@QWwy;KLCAFe`LKb9ts+;$3g7n4qdGHhVhqsb5QQvA96OzVPRmH}+=y zQMK}MmS7FW^FhBrny9S7D<#o00d(QOSeNZq6t9cc1Yp$8W z>Ys_1KEWK_9Y^p=EjpPui_lBZnY^dnU`4)A$6}yMBb$KS-4MDW>*G&r{Pzb=QELPX zR}^2g)D1rLAqz2|6*=W22q?(XEo&)+^lo4D@N$oI!;ttRNTiuFba-_AlA=hE8 zJ1>XXj_1}t2guYs(HFi>F9P|A6@YZJ*aApW75#2!s8hhSq&`S)nU-S&u*8p7_#&er zk-!6c!P3B`R%8gIMZUr}BvZhP3;_+}^79u^vic)we)9}p5#Qk}qPrXHw2N}^;a8}% zt|%X)1dr-!8Z=(m;N{qU5Utb}`*XWcbNU@;6z;0;7#s&t_pimicdd*8RsKvwwGT{= zG(+)Fn!gvD?b37h#w*WjOyA zHusC&4GDTB`1O0e5)jcH^>xZ_Dzm>ko#Gofm+C=hE%?8AHIzzk4?$JR^Jx%lL-LR) zgw@5wS>#uXPR+hkH&1B?fi^gn)n0`+av}1B_b^BFnKhIw!NQNxbfw?-?E;G#dEWO- zG-O`V{gS(|bZOTB?F(O|H}`}F@}6v!6NF+vFwwbB3tL!L$8GH7Z^8*Qb%FWJz9Wo$3ePA%UTGd|tOBiF*S?fzi9*onNux{gL&HtmWM zlhy%*j^1K3YX}-L9zU6$5h1p2QHSpoQ4D;*S9u$Xs!zZLnH$-fA7(bZf6}BnLR=}0 z;_(Ia2N@{URu*%ZC8rggDM(zMDDY3L=~grs$Wj}yT-zDQ%+mKr^=NvBeq#4|AXc4q zF51Mk?FyibXChHq;UYZ7fPIs?3)MoGLpa7swfQRW6hK3X=`7)RCdeC(4l>ulcz_jq z-)z|0@@G9KEi651r20AvryW6ZICE$4WeQjHKiTL9d~q;-UQX_?KT*Y6LQOc&sQdz( z^H{%aml@qO%Btx%u}jU$8mTWQPsh%U6;6|HlbS61x+Yb{Zwr#Dtijl-E`{z~ut{>{ zuW{$yC$L3(1=zS=dvL0?#&*omh$Sq8A-=E(J@UW2OoL>{cO3)l>~^0aYB$g_2=&b>n^xwuWs7wua+@aA0dO z^b*D@e6JdFqsG=@*J*5x;h+FpH_8|L34GN;v|5(EAbsUAI z*Xnu?GxZ*5>fMj^UWa;HR27(Kk8`nG8(*r?T$}JRUE{n(}x8C3k7MpU8Q*~|p{sg<%_L1~|M|BVmW}+Qs)up}%l9;n<25!Si zg+KC@72)&ErLk9Wiy%#9Jm|9fPFv9|L_<6{BJ6)QL=cE7?aWU+ZULwYA;H%KKpA|_ zqIr$>?Q5Qvg-pp1_cl)!wCG{a#K=JuX;dTG-=tn*!}u*Q;}HHQ?DKT6I7Ybs5&pye z8aekRN5?;OZAXQ%d}MMt0E1}wFs zIUswnqbizmAMErr({Z-0LQJM{E-8-D)of!%agYG+#XcP6BT7X8f! zK_vCJ5hI<#k3V)5w?BAJ4Lt*`&jIK==bh{d3^P}Z+a90&^8h3BhmJK3r42CYoHGXRkzD%z1%H>)vXfLA5 zZuJvZ7}3?(Bfz*>3EspBn@pc^`2nWayhvuZd%7qlShJrTC7+cs|ALa=k ztm`a|Y*VM1Y9BDwj%ST*QEAC-5&EkN{=i5_a*O3fMQRln&98Ixw2S5rz=Jc^zz2{) z#@P>)MSQGx@v$D#ocicv!N<8nJowmomBzw zvz=QJkkstXiK^p?`#OmQmStK@-Ax!qcb=O0*xFQ%>~?0Udh!0mR0h7>+3cCROZv7p zb$KAqnZ$qY^xgIJznQ*0&LB4a-SlnhCDZrBR;TY$G>GZD2_I)iT5Bfn#}isk-k;wB z9o{ON5^k+Hc_#zsB#4JyV$JyinNGywi_OBLgFFOL{6|f!+eT=DD26afV(o{op1hYP zChrQ9Da&Na#8=$`0jb6K2YRc&025~56XrvZ&l}ZdlwcbhTPqpFjB8Lwfxqd(oB;7` zQxQ49X`Zm*2AD(%jb=k2-Ox5{;vN8A)oHnmNw9(n;0GX4@Av|# zL9>EAkP{Ltu{Ssou{y=Y>e@}f>OcP}SnXTp!D`dx8mmuStg+gJ;bD&(@m1&HkBw!Z zS^iPEx6MnB5+KMv8n4Ev;U3 zd9+a98Hi6?oJsT#76GS6elCp{MnQQ8ojde3u^!!yhedN}DPl6TT3K%5VWiZ!)6gQ$ zy}P>B6R#jfiUdrozI^ENUHZD`4b+KZd z_MSjX?uC2`16vt%j|$=Dz&=*Ab2B@>a2it73h6+T8vScp+M*if#cs9sRP?GoBqAu_ zS-Syc|gbUi_)`jjNqgcs|+c@11H z29-D{f4JpxpzX?UJl(!|AvmBrZCs*G(5zlaP69M+Ws;|r$!;r`vy~HcD?3U&t$aBH zwS!bIKr8Xt3>8UxdUbZS0KUrZq^;wC4X*J?q!UzNASZ(^9iC>M4y?7m$51#dkt!A) zu8*I}fW8q6&O)W#DcEap@yg~V6pCq?h9{iF9}TMEM1H>(+yP^oUWLtV7~KROUx!%` zfiA_xS|G58w`=L9Yomw2nD%7wM0+i8j0#8FPIxRYAiO%+lz!Y^7uN+%r(c$Reb+LwuK_sw1-bqXT}VGte28vlZV1Xdw+h_TuY%;5@)k z1QV70n-}wy)3Qh)yGv=i#-fUQuZ9K8uv}jyxdWanFT{bGuW~qkXn7;{ObzmLI39-l zM>cW^(u9rR$Y46s)L8^O+9jLJWEq(WILk_hqlj$;u?Ma)>`Y^Kvkt#QMd?r&ZCBHB zP}^1Wbi@8WJ~Vq`H+{JPk4(NH3N2RmgSkET+H zs`5z`QT^C-tm{!R%rttC#Z0S?V5Z?+20UP*x}88gde0q$?|}!LzYI(_>}mlIk0-4@1{0E3*g4g& z1}SU#W4O^UP1wrae=DMgqbJ0PEWwHV>MZIwVgt7+jm@S)K{W)aci9b{np*cUF=7-5 zJWC3pptIX)sZIzV2VnIf(^FCjw2ZseUwL26R8krpjf4HB0Bi-!l1^P>8Oq`83CH~+ zC=@m0wAwi~63L+ywH3`h3f-a}0Z8rhcg^Ux*x5uDb>`0o8^*u1UsRo*3?oRU4A zBPOS|Q?&IdPwV7qnfu_33rMyi+A(qU;W!*m-988C>9sNJ+n#DRDu}OXq zmF-zqGV*)@?>-L5`{*T&yuXpQxD_B*?l=w-Bs73puUZE(y}DjHzpBvF`7-L; z(D~zFhRtQ_UT_%FVh~@sIAewC+Lb{nimVFlO}}GEujayCbsd8R_}e~scxVgkQ10SH zf46(@qN?us_Kh;@VdsG3?Jm7BL%ZOS-1_$M^^QCe?OhbfU)&Krj?d>gFOIEytt|>| z-V^yav^2dm+OeQ4GN51DfPz(Hww1*O^hmSXt%^qo+84r=Qg9m>q;3SBoR#P}2HO`F=`_+$WMUORv59l_uNnH+2K|e2&D?e%!;ulO(Lz3&7{cNv11bFG@>^E| zn}+(5avdJQ@Ms+#i}1wB4C7y&G|8A*Is!3lmN9GG7&eWBZ}1luG81>;i)ORfY-C~v zKe360`d6<0RiS^C>t9^7*)9F61|Q!66F1<)s}=*YxCflLLg!&3YRjSAP%lD-ZaWR} zjLGB||LUZ9#^k#(g(lAkd`<8wlZbqyOt609XbDxEi^#Ew^om4qGJ^bt4AT;^(@n5` z;tUB%1+x)$Jc{2pXxywV^H2tee|C+0R&CtI#=wB=JuRZ#g z(!Vmf{f$ga=O;F?T>mQ6zeeFxC&R-Il%oLu)d?Jo8STc5We72o-I!@6W|kW>*Tk%G zV>XzW9d67X6O)0K`LAvw;bYA?{K5dVeqydkL!{+qBj7;aRZbeu@v-4sb`p2Op&f|U zS9#=W3bLZlAuhH^%mG`&FP_!mm!*H@^Aih=(!WONUsd|oSp91nKZ$LRg(mAma~%Nc zLn{!}V;@?Rh}~d<^`T7?B4LG8BAuWLeDxvTIWiTbBWPkXOt3zbDIuu<)5=NDF~PbJ z^eqBmp&MhFn5*2FQ6{Fsjj3YDcR*+w0KsPlJ`}0bl~oVjYAhsg5)i!DmHnp78Q_ z_-SAmCpq%yRP3?7(p%ggcsm~<^}{h-b{f=7*fpZm`6yKv;)HHjw3sRmD>7m%;$QE} zwqWX-mR4AaYg}g`Kp~Ax6+kz?*CDOY_wF`sEYAeYd{Z+wVwXmC(i|LXMx4)KhSR*}ii}=PAIYoNtaDWNqJgY5EJ~)9WGp~fi@;-TA zOB-_$jYsJt--vp-QEh-p6I#6;tyZ%$Y`42^SG{+hZf}+}(bmPFgV`>mtJa~~a~M-o zA5ID1M1)URmX41jRTW+7$W?WrDDV#Kk_cswU`6{qK{a74PdyE3=mo6up%0qX{t)?z zx}F4-CRabGvDhRK#iO}dfNm#8owbUm0lXr8xrxhE7s^&*KFLv?ufrr%)!XFAP-&)A zy4tmp#4?}rT^*+Lj$pW(4(Bu6UWfOPT+V`zEpsZUPGT6(@~X|;oW$mnrKyu6U*gtsNa`nU-9f@G`cWZ(l99F8f4xPwN~(n)X}bU|Nf z-)`dL=GNA7`zyq__OF;o!w!IwkVY2KHzor|T6y|27eDBNZ}q5KyMQEMuZ{sgsfQ2z zO?7Kj)U9y2IRjKqfgL*(9j3f~VJ6Ynq`qnNXkq&?GS+E$9tm&0<|>6_L6U4Phq3ki zk*3y>|3&9(?i9)(`_T>PFdO*x5RS`yVSHGLKx*BRufU(wH*R1=n)`wE-Uisy-nMMBkPQFw`2p`X17;Q7jP) zjpfIXfrN?T7j+gg6J#m(WRWnlOwd`#V~{1&lSRVJ@<*LTfqftgWiF>72{TI{on?j2 zLP5>RB4K99)LCZeEOR|sB+M*7beA4g=`7PcStQIXYju`UI?Gs376~)U8#;@nvyAX$ zkubANViv7`vTKfDnELJlZ0fYWo9u|2HuacR8!VcOBe%=!VJPPEAFcoNN8ab1gI~ae zaBXA4Rtox7q&uEhzZs8;LwR|GFHFbM5B zod7*o+Yai&ce16&FvNxWdNjI3JNPV`mK<{wR&TNWQjd=#cR_qqpTjqqF0S)$tKtAXcisz-OV1zmGRI^KyCbE6JY)qm$KE=>empU zLosb!e!(I|7neoqi-wm)Ru>J!u`t#JXv}0(BC9bl`9N9{{&NtK{3zBgT$+Pa!`gYL zO5_Cs5Sy)$-=O|*52FPkHvl2xF04UqmmqOU0gN(`x(qmlk{ADn@l?As@=o@2#B;z# zA38?QkvVD; zI-i~#pSN2p5nRpY_h7Oz%T=6BEh_yi{xXRMS|pfvJ8IloniF*6I7Z_1!1}}4x(8)! z1>`93;q?zO6?hTYRUI;zk}wq*wp4^?9ypKXIO~Jd_l3nc1{gjp2}C75x1lYFs(%MD zs2OhyDi1i-gUV&HQ)o~(8$g!Hm^7&c_^Lzj$9~lno(Q~LsM7NXx53tn9kaU92NK=9338WrcU6=(ii-*q{`G4nMiI21?F9!_u) zwAE(%UwJo!oc`)72?~F>1gwJXu|}8G1^e>cAsv%az!B<5OilYbsP8#MGZ(f}7Ph$8 zVI&;{f6Vr}V`BUl{kP!#QzhYnSL|?4xiwsDn(gAEhcL)S)s^rixZ+WFy12M#tc!~c z5)@pN{h9sI3(yjv=s(3v*+&{LQ@KW_;uLr(>z0C-Uob5b8eHeRQq~7dcdie~t9BcU z19!#K$wV>t?*>Vjb++3)2AkAA07nnJV|Jzv!oi1LAe>VdRR~IvLzdkt?{dO#EJwj< zv6fe%diOwt_U{MNohT(aS>%Q_%MhLlZ-@c6n zy* z1{*;BE=x4d@9WzTpW6)E)E!? zMEyxtX{DgOJX3#+^(xtaqzt&Pl4hs&KWOQ4nsa*P@C)GO={Y#Y!9i_l?2U3TOh?q8 zuyuv7bq{FBv>UO-s^j98fs`lLfh0e}^^@|sltbPu>Kz$^xsWMZt5_aG0F z6%p@W0|qA^W-nk2FHh}&Juj_OHVXnYln#hpPn6?f$k$1Y*GcsTS1lS}u@4)6$27hx z(35CoSJWS0{k6I8cwgm@_|f-1U*+fcR)zNv8wNdY!>9jEQ}=wCkDpkvU?IC*`kO5e zl9p4tu)nG4cDJUhSkqF&hGo24^r2&GHGL|_y$$LFr>5CE06HrR{$^!!IuRi$V7+B3 z`$Q%-Iyn0mQ(2Ce5?eraqf};yOZI)xEr=RfQxi5HCCn1byYd~4!m0zfa=nwCBP*8> z`||w=QCkDp8Rbdc`eB^QIp;ZvTw%$_C*QdKaIPh!B;E%v0=bH(D|;*V?6{BH?>T7G z0L@c3fm_bR@;{e4YP%C=H}WIl%eMv0GR`@u!_>wML+5-8yA)-=d{`R7AEy`m19tjVG`1U#( z9@jAIb1^KyBT>=AH2x7@4dRILM8tr3kStjZ>M}I$pRhoZGGK<|d*BLS5@oARTfNy9 z*%I4$<_O)^@{^#><~2**SnC8HoEGSEd+B1ipAm=`qrtky5P zph?-ek^|Do2mZ)v6*847)PtU|N)8(7Ay?ILBw~}Y%XJatM=4d#T4Q-9V_ifE=FC@H zAu-5axmooxHKqfptd1i~zIV3_EA7{*6)IQzvKlQ(oiiP{9B*(rQqp&a#%31z8GCX}f@l28g)2wb85*xr%umd78} z`=RB$+`C&1Ft9w`T1j3WXi}Ro4$OKev!=3~;0r|gB4jbu+7L;dEtd^x#|@w13Fmsk zK#H5^6i@i1L^xi-%Ee)f1N;FJL-Sp>|9Mx9v5)X=0iv&xVA#7c%be2xU_d*wi#M4_ z+c|@=8%$1Zuo_=2ndQM2dzneH=R1Kb447ga%$#x;!Pv`t?OUFF^Z)Ey{^#~B*W$Ip z|Fdst)xM?IuFn5w-?9fHK4kWZ8C+@c?|*9F@>OTB_W!eQG02o-NuIX-SN1KVUW5W6 z#lB^zj^i0?!oFo2E-(DA*|!|KkBp$mi&(OyY9k>_n$P4+ziy-oB+r z^A1^{e!ZOnL#Ojmsx|wTMeVqbwQ1jS^eYMbmWw*IV&8J>CfY^xYwYgYxBLsX)R19Z z`LkX=(HFYG)T>F-v&^!f!4T$#Ix9q_}N&6PG>e{zltJ_su zkJjz!gO|4KTh3y;Z9(ui0I1V+ zm}mX!SRJPNQtkST7?tyG^$o+cZ)vA96f(mPl!;^WdG@Sq9ai9Y>N6c)!SIJVJcHro zI$Xu@JRKgz@Jt=H7=Dgn2vPQ44n_*PVc&8LhQX1MTC;Ci@>3%He{A3K&XNBk`<7Fi zI{!ZVmZ2aC*S_WK9i1`EZC)q*ZTprnKX8gSsr_I);odU5f|0OqIe>(hYTuI2*m_~9 z>U;9P-?nc#fOY-0earUmB@1a140a7asrD`Z&{;^T$Rai^CX0l5#y^8ujD5@H!k4vu zOSy(|EOiTQ*tguGYbS9d%P4+K?Gk3~19cYCJhE7xED~mx6C}%jZr{@M-44ewO_TZp zKYrW3Wwb`992opZ_AL`p^?zgEGS~~>c^>#yU>>)$Z&{-;g)>HCY6m~R&%UK`r;x!Y zU2rTvW)vh$6fe_R$V^bT*tD1|5@wd?bQba$WXbf@B4K73ud^ty4`iXt{}A|qcsLk9nv*D*^Xil0MK?6qeV|5CaQhL0Et)% zB?|h6P2dk|%MSKUM;1kvyQ*mnS+Ztv8#3~NgQ|Z*i8lbxs!?aDP5}0b3YPoA_s}p8 zEdI`zzM0*XTma@QnPfux4*CA*G_S|4FLms2U^~|1{di|c1OO0s`T3MbY#?qR^=O^} z6(aI3!8P*?T&G)#xSLk~)a*L|_M^K9GL}s5g>2WY?GQGM)J!WPo^It{_<4XX8rE9Y zoxOIUp-lC!-2gpO$6I~RAh}|psN#Yb6fNQqRV#G3G~Qo z*XaKqePg>lvOyc21Ms`(OWVf)wbaMPAmM05;a?X+Sd7B_3K_dp^WrYeZSX0L2C{RC zPGEox^!ALd++9#C zB@>_Z6uWJpsTzZHU*+k5p-7}}H}3#?^Hzr=v*{zcnH-LAKLM+Q6|I<#s^PX`3Y0RwO1XDS zUvnfv5O1^iAfg?L*x}32jTHMtQ1{i-G~q@ors+CzP)D%0L94HFCEC^~jXzK%hc?d8 z*UQBW6iS2tT(YZ!QB|B8blq|zO2+3D&4cXa^0lNgV4UiUCsLY!`3E$Ao1rE94Pe8W zuy@5YJ%xxRnE9lh0TQE$A+@gv8biDE`Z_1F^-)g6EU3~zE9;j)y z)3phyhWSjwe7{pe5LXmfXxoFH8b+gr_=4)^Fq%knJTBbLtg)_}p8#nbmEP=V;$a}t zq*f2*?zl;vk2dY;xXCW{&x7+oOgV>%5E<(qXK(WkHO=1XZT82sz0LM{D1w{NpK;ZT z<;Bn#xH)~lzWM{rzi=ensM3(gW9J&6-JE&!1FI{G{8${>(Q9S(OaP9;EB>PU_U2RW zv4H@4i~;t^4A$7JzGZc&*2dTVat|EeG=LMcJ9n8JADA5E$Ld)8k!_t`MU08yb!y-@ zj89oz#I-{?hE;F)YU9T`fi8wKtF>5Sc$Ha>503k4m%wuBG%kDCJ9--l{)No?`K`LP z_$*ds%m)uQ)!IGKcZMC`v9<9hQl$s<%=NlUXZfn85s-VVL}p!Wu)bX7eNP;TK=mM` zXfM`9tO5F#ZqulzV~%PvXrR9ADUJHGo=isl-{97ih&{@uQGX|P4n+N}_^Op?znxsM5aMsrNf4@Qn$`f#jOFPj>{`x;4@-?R@TG(!heR ziD{fn%bZGB40XJLNZ!pEc;ZfiBCe9TU-8lc$Y4H*yfpG-_3@CV062)?qQ}80hDMSp z;6+&8vR_A-eg%Lh$|E=9tLjm$eIyoYEAq3A`R*V-1;LxTXq@Dmvbii9W!WX3GGCif zi+`1{PoyDDs^uL;o&U;S-XEig36|2J#y`TKv6sJn%5U4tf4iL;GATE*jMJRrWwO2e ztzU7JwYlQ`gB=?`*IvFkDT=F)x_L;dz5GdoSa%D1`H(c3YS7-Mz5F`vNHPzlRffL5 z0Erp;xF`ofygzIgN8t^;zfi6=Kk6Ni2A<$M_ZJFj4uADFj)(R)b%7p_LU%l1-GJTf z=U+JEficEiNVN@E6vN9V4hoobnz|AA)=>mHi}5ltYu&*rja)17xz_~8jNx`M2fMd4 ze9s(n-K_x_Y@LnyvW?Uzz`TsDD~an7g(yuVjowQYegHN1x&Wt}SpGY;2d*A-J>|SV zNE4Wjv;{jWP5rplt$L8D`m8pp-oAMU-cCu}zQB7zf|(R*YEpR;U75|HaLFThHnvk7 z#+2I^4XUn@(C${_xibNkBozysq4xRGp{nKa4>Wl#kFO>Yj^GSSEkQH;CiRF*ip%5s zuuyy@OI(V!5{L7~1^4o}xL(-1y|wn=vhTs7qvhxXeU?R*J4SbMzlJb7{34e_eG1{? z38EM<8xnvmGo1Kf=bc2ciCyYBcwR8Q*mVm#)TBQD8siL-&Gd)v!(E+&b?d4GObROqRwK2wvmQ@kBtbZ2 zLwZ(wcH*qC3_=FcoRmG#N3BOUHJ#KZR!}i8;0oH4MK1&_EsAP0+lxVN%(58XZCYdr zd={Ucu*h`i0VX(HLVnd+Dc-jtp*!>des!&T-)al0P8xmPGnX;!JCVqeb>N(+;7#+Z zUVz3QH8*}R_*0X()!WJ)` zP(ij320)kFS(59Kf$h@f-h3TrE?zCc=n2mw8I|HqOftIMz-`yJ%5rvn>ypN&H%S*& zEjGA@n>Bg4**%|;<&4)CzT_&y4br_7meZh?p3h#V@Q$`vPLsL_?NQ3#pL?s+Vu1nb zF(AvKAj5KMwTTKT$o1SWq*N~=ernST$ZfiSW0I5tlUjier1V6Bl#=wD|BLiAuaX!R zdfHwk$TsUAh^uXSx@L<@Pa6gh_LlUt>C@Ke=^Kng3O!wq5lch~J*~66Q9@5e5|tpO z+%ebP9wbeAN$Sktb$0~ZHBzsQGn!m#irpX`RKd-yQ`4ycIhmRcFJ|XjP*XtqoI0d! zEMQHl6WSv+EmW;jQ}MrkKQ-OmS{*^5rbV2=pr+&DiN7V$f||r03fGIirVLdYTbPBN z1iW!w1$m!7e{dZXP+kP?Gzwaq$m}VQiy@K6aXG?@Os&E%4`V7`K?CXVXq2s!zsM6F z%@UC?E41pvqwv9eN7omwK!Q4oL=$_akgbvjPLDZAnRz?LhRG*8y zsBkXp)h8r6isIFM8}%lj1SNU(ga-?JuxBw8gv?Xe2tD(6Fs5 z&^+3Pmp@!emB8x5sSv1Zi> z$we%A8`L-%@z2@&Dzu@-@#PeBY^cE1tV;1E0Fw;>%!G6pwx3Nf?p(&e* zGU!K7WFXDn@RjV}SnFv(s6p33%xusV4Y!J?O&=!)GTQnGE<_fNeRvbm=L;VR$u<>V zbn9xcy}I%D;VYll15KG~?umG*r$G(oS^-S05F~uA2BTHRpFn&XifaSV?gUiV=)ecK zoFOHe&LC{Dyfj#M^XFqCBS^CwFu8$b_Vcp_-QsN7sA(E+qs8YxLaA84`QP#6XO{|H z?2>om0C2eh;1B;EfMWmvv88}5k=KB|-$udd8iIWc1e3Y@ z(U@P)r9h+Llg~8@-U57t^A&vA49`*6Om8#;Jg$Vwn#plaB+V;kF-2E0)l_nespLBO z!oN4-K}VIdv3+5sGXT5FF_DE3o@owWjs*iP%o{?XA8M<%{65Ud>m~f~rHC>nL zhFW#0=}i2EBpI7p;grH<$*D7#@Ffy1Dve6rMRU1EvVZJKv*u>e7;6VNVLdk@wnl!= zmeN102kN2=8HNYTER`o4(}m2cPSjz6?MNNgJqqt2h=%D(nA~r_by5{;SKRM8^Xv=Z z2xvO!bt3=9ZpQ~mNOyR27{HrV3IwQlvS>=nI8X?Pii z1E8?9Q%|ng%%QFiqrc4)OM19GdtDG!&FCAC< ziM)*aDN{ia*QAc?Ljgeuhd+n+!_U}kHo~7D%TH+?Kc%N(A&+y;ZKn?`s8YOL4)$aj zEW*z03m~N!?!~L_Ccn_E5`B3Yw)vdLJprbf$20yVxMEAcUa3L*`eSwo_p^yv2plLx zh_`>nzU6H)bu{p&9wfwmf>`yQL`^03{E-b%Bmy$xfX-o{fL8C}rT~g?3S%Z`$Z%`N zI1(m77kr2|f1CRs%q)OsFIU@GkBI}Naw6eo9PjZk=_~S-=)$WwW1?CLG82dLk!-C$ zT*G#XSGe0&Uzj^ID|X$6%Ze^9x}xZhMOR+o_=iIOUYmgajoXNmk$mW(opZui-n0jei})x{tYrCaoNh8LyHjegp5xB-7?24bdS@HT$liz4$4Q>W@4!t&6MOP zJWAh>Ze1ZOmCUT?nW{yTQR*d-H@k8#mjJV{-_G?2wcdcQoef8!)Yqbee(7L?dJ|I- zbjXhIQpks#;jz3Q?$h-6-5Ase{|{R`C!Uz|{lX)#W;JKm&(fNYHTS~!B{pHG;ZRfm zkmUL|>iVae`XAHv{{q7ebN6JgdgEtZ|HY>MH_%(VE~$R9N6Ow@33D-&_F3ZJ*+VtK za{%@PtX*n4(aDqcFV#!yg#3s~bqQ*vtTBYROrp2SJ{SnK@q?83;8xUlI%^yx1LSS& zLnL))(wRu&ewX)F&viDwlNgBqfDxI&mK$Wlr&pDK>adVey$)9}&wL#gI(b8f1?m?V z)}5J#pxqlXu+;v9)0ph3ai9=~D*~Y*vvE#qt}?aRUzh+C0Zz-;p=JAe6CYpT)N_s#BfeXc zudbLpT9sfwgq#LF{&9E?)9Y-)RW|T3QbFeMPdLPSG7d!8-U=dPg>iWSFusyudzNV( zIJGyLu>BVYBwO-Ka^kxpz!`WMxR|8yfXlgWY+khC#xb8P4f+ycZLomAX;dlAjIe|D z>>c%GX1v)92g)!Tg3(QyKk_}^1m=z7EWCou>&Vlw%2|;=WWzBATE(>HdMr2%t}Fb}IkL>-LVNTHLg95%Fq3b^kUKW2WB-7%(FM{~p+KFebg!DlXgOMTVLLM48-;nCrXD<-?F3rSQZwyU3D2;;|l)|d^apEFckx-{3;zYMK%L5Q z^eR)G@rdP(xmOlvIjvBo9}%G&t1rQh3rq*>aSE)vOEGHdkz0hr{pd_~9fpx10m8eA<8dkRw3D7%OgfQy;_~ia zrg7Y1I@(b>$|u&FRP24>I_kO)h|konSMWLv?%8AXE!dL47u?g?xuio)+Mp?pEze$trmFc-MAZD6(6esmfQw=- z*h}aN1=TAUI1+pf#tFL;zZ|rRP*<~#2!Abm6H{2ON%i|DfsiU59nRXC)Sp+gtHuff zyCGTwQOFlVM)^UZD0>AL5h`urWCQQLAd|X^_3O%J7qGH=^ui%ub;b|6UbapH$sOK$ zY49hcr;Q-3+EB87y4MKW=d$``m_d$8%Q@0Z=YvN<^?=Db9$&RlfWv#xceaABK(_i3C??r* zr8Y~09ERc0QqHU2T+Km|a>t)a(rKx&KW!OCM(hX7d3C?j$#=l2nlR7x z;ZL<2m3&@(tgt9#ZTLOs)i06@X<&XFLSBORt;9xGj2e>8tDmg>&(5p;iK?G9RX@;1 z)#spU@7X2Z!x79Rt(HV|7+k1@LcOiSqXu;_+T#>nEnB{nQv#e<4+owd%1S=3z8TNM zv}|ZKVc1-kDC9Y>eq}}5=hcH+ZU6uIdG*CNa)f0Snsh6J=DhkokZ*!wTb@@p|3laa zi6d|l@q(N8?wMtwY^ujCaVWMyO~xPzu~MeuvXQ2`VmK2~B0m24G&Jh5QD{*4C$sJr z=hcs(N$+{}xBno?N-xfbZ3c(rw0ev)ph`Kfe&P(aip8^D^|eumiyFXj7d3G+sZVvi zA{HuqW;MH$k{##O$1QcnzRmOM=j&Q)N!&vHozoh%`)Iz=qW1s4&#NyPMPv!y9=ciZ zrq35A+{V#w>%6+dDtGM1<`C?b+^S-+JNBOQ>IXS&$>-IbF~Er^p@M+W$`+88%h)y} z*ME6leSSjBI=M``s191r;Sg??bYA_BMPxbN^Xhrhy%d(ypbnJi6yDJm%V|- zR#I9{B^6Cg-D)&7-FZ_h(9!xK>AafG%w|r;{;OzcY3!wP2wB``WnyDsMHZ$b9-@0> zHcl%k%Ab8Jcd1jU7We2K%$YUMUh2a9i#%agiNoq?{K-XQtUN^Y%xE;A2VR{8IYC6* z&!PXUK)mX{4CEADD0yH-Lr?3Bmo-UMGk2p}BYUVOHKUe?705vtt=L=(MC1$altb$6 zY9MD+EblR~$!}CY*HKSS#-wVHqFYrjp^CPeyW2E(wP~(Env~N`(8cCf zvBK|{whi!#c_fI196;#gui_^XPGi$XWiC%nNRxf0$Ffo@?Jlq#s?&5g_We9y#(vKAY^*zu(_Oq*eo7C4!^m)@T zoKGikxmhj`VH25z%M$_6@4;nXA%I48DC9bW%h$0uIMoX-R}hyo(0E&eKW;8dXk12H zN8%-t#SmZDQ(J{O2(=-Q(;q&_*zJ!*U=TI@;RHz|CyQ_ZIeWPA`|UQro`Wp0exLtS zt}Uv%d@tHw!7U-Ql7hCKGVAh|->5;jC;`GWFdH)uo`K%DEmYjjHh&weLC9k02?`Q_ zY>^^`4L>;Yc6f{Y zCT}@!wvdYkEWC-?4EvEVvmC9nNIyDo;G+w5@55Qb5cNT#gqeNEJCY?=^R+_F*I3x8 zSfZG-PUjR3*v71VfmuLOQCS4ItyY_a_+?3p>SZpn(R5yQhaiCPXf({fdVDc&`xEpw&ozXjK0Z%LycqFR<%w@Bu0oo+=f$4`uf9)!FaiQTQ< zV5X>uMshg5880zeu{rW^$~8C`CkQ7C)W5laWU}ctXzQ0Zg@LKBL<;bn9QwkCbEK0G zx8d(HmbdOt5K3OG#`$%pq;u_>YY{(*@lPerwH<`gWNmc1x|efXaEHUc49r;-MFAq@ z8Uhf@>z+rn?^Z)Ebgz-_Rv)i`uO37;Y``g;AEgrKxefsvL&I3tu3*v$rk6s>gTRvz zHA|B+`K?2+LrD|z!lkmotO3dAFb5+2J}AqC5bOs`;gR2U*(S>KnaCbe9$ zc>oIhQ4Imef?vi~`5itG_ z|DT@E-XI4}a%B1JrNZCb^Vx^4;1>Ni&S$&M<*bmh_aDqXVO!_3l`~0$=6v>vOzgB< zp3i0+$_+S<#^lsiw(0jC=8eL1N>kq;*MD+8d+8GI`RwKEG3zwIy=YTKH|jW_?SaRe zf9LsZwe&M-!_I*}2+{xD`Rv*&Wr@(|v#$w4z2~#vUrxS+^Vx3)1J|*Bz2TPD@s6tc z9imr-+5gn%vt6;bl*Kx6KKqnO+9|7V>XGR{^=FI>3DNr9=d)uk;|QeGq|ax!y+MxI zpq9T$e5Pc9g5YbRT^eTq&&v(FpY-=Rl&xE_m z+Iw?$27c}e+|72z5=uVqlp$CCsl>ZYGy?;&%i&?Sa8WwbBTaBwFnX^QE8jaHc0+rf zQI`+Eb)7f&QcA%NZh`aU^^Hg3XycVy8 zp`8F^00||Rx+eoG8B+Rx_;YiSZ%)T-?GXY^;4NVBK~XUu zCe>-}0{d6s*cgfvzx3_ZX^2EY3&3TlA6^q5C{u7w>kBL3MHfmdT0n#adl`2YBSU+R z!jPf@-^0D}w`c*8g4phXZuonsFHExs+L4iEO-34A%8*R3M^n!oi*HOnlZ5qs&1G8B z7&seUibi4RFWx(Pz;hQRzT(Ixyg*5rdfykAVS#=|8wcYxtkyYjmmk~`ygh>q4Iam( z(aP-U-dys7xnh#5GMg0Y9w+$1VtqJa83`LGNt`LzGqJ{sy@_YwU0Oh&ZV}Z&O9~jZ zH?*WZi9iSd7Cc?>zfhfHvX214bXf!wOHBt6ysbqt7_G^mlaPV$0d|G-7wiUK=@s|^ z4;*nwUpQ(h3~g#>fn>(E^F6Q`2{56oybei=I9w!$b+Xq1U?8+Yc%~_Dt}CRn4&-R} zMMmev12TmaWWbb^1_MM!0uzp1h?KY?_v_7>gn z<2&oILqG>9zOzmruYG4-|0==7*^S3{mf!WAHC%LnJoNMU&gur}inQ}A?5K_NtiOUQ zMQTCY;ZvCG_{thQzdJyVA3{FkM)nTHVFOz!u$4a%hjF6PJ$83f@B zBc^o$&8l5j3TrwG#3(gnJOv;9TLo|(#r@IwBDh>cs<6rZmU6Szte(G!qE@3CxM{EP zq*VdXTlJ(xdv?rN(wS$*vhc4P_BI#6kU_e)))zhwlZQvCVujv_4(Z+;%-%RXu0S$P zvL8XdBCrQ3i!rbv53|mB0d2DV37T_XaVP@0F{3X$5JNz(Qq{;laui^f*jW108pG-2xW(}Z~-mZsa) z#vk1B(@-&-MP1DD;Xj#?6E|hP%41Q1Gw}9!03{D&3&PncKE=&{;y#LGc0a0(FD508 z#s(T1)fnu?<33{-6sm0(`uV89WyPQek`f)6MIJ}_Vngl4aEKSiHE846Y``q|;WK0x zuDQF0;Yk=q5c)$THF!5el|^_Hhq0(S_!5@0Klaqi+4)6S&JZul*~|0va`s{U&yII9 zFVU=mV#o_s)s5(D;Km|ZIbHf1fF(3bJ&U}~%(0;;hrc$Uf)D_AnEfLCtt>RE7%o(& zn8t^qaj~8@Bjl_40>og`+*m7notBbtJAe#a<)BqF;AX)7_9|RsUG75C50K1toJb|6 z!;bIJ!aZolEDw3UV>NnCAcUCqf}RKGYV^ES2lSxp&Gta}!E(XugYxmIP7SvV(KUR1 zuBQeIH5flw=(6Jn>vm*?AFPd~m<|Uo+^hXy3F4d74PT!Z)pwtMCU zE}*1I9c$WL1>u}R$gyaTeETqb?Q-5apr@uq8jarh^72lm<;6_B-<;#=dKp9>_rdMa zs98*U>j^EYUM%ZsigzksWlx}9_5Uj@`kr<7jzi362_EChp=4mSP8DJ9U7}2!ma=6XROFu+V3YCnCy$so$+xKSm#mmek zZ?Ong*?U^>^8ln{wmRqq91=w~%4j<7s-7LJQ9E%^GHUDL8jizx+cJZII>=ybV-ddU zQ2eo*p!y_;@L1#v!*N5J8uN5AluM6hX?ZTR*htK0B0oK6qf5kk%m<BZYlK-82}^tpkzt!U@w@^t$KPxfplySRoZ6(HF5^U`yG^Q3A2 z5q#CwzZ13=Ke5WUThbPJ8ANGvHccPYR<32WPYhN;8*zhIh-65pA#U+dncHg zSk)L(YVu%Njm}@5$dp9&QzRE2`mCPA*ZqW`PZ|h)?3=P@O(`Q&q>`ujS**Ajg8|>N_0^Lq{kO|wTI|00PEUEVK2qZ)mk#|_i z)jmzwx&}y0+C!~CM6a5P#oUELPeEW9=BIHOaLIQ{M+JjQ@&U63owd@L3>*_^lR6h$bT#lyWtL{Dk$yy;&8hKITAQUjm9f7L@kn7$-@H#54 zW*`93pHKKfd5==?etM?SpAcrUQo+n5?TED=J5#e_((yS+GDD`&yaInz?jil=5Lt95!Sjefn&Gpa;^m^E6i@-{; z9U5yr&NyX%A6Dz3lsa^*>oRPS1wZsbT@%biBB03;62k-Q~J1nhgC=6&LJDDY? zu48*=n22}0($+V-m`MK#=ag#bWWCD3!`yDKyPYnN6WxHvL!n`5W7!DL-p!>Ki@RTD zK(q0QBPV12@rqX_#XEA2%b#L>nAiN7C9Fljhsu=O5hw^(arH)vnS6jaOAc>1iSNLA zoD4|dbhWnybip{!#MZY@Q-4A|7}NL+Gm+!-xS&h|LrV-tvi?Kgh`{eXK)5BN1*fUCkD`$n)E|s>m%vzF?}RjY?q4x!v@|K}70-iVFCoMCZS~F2 z0Rf}v?d|=saE-zH;-Jk>-!R87r1ggu>&5G=YAusLG@Tu5RuAB-HUs5$1#trWfAz=q zX?7YHXCS2>WbZ(Kvz^GiK*sXR`V3A!6NCF_{=H#FN_bvMHiRG7Eebvi-to@ z!E0^$LGsYne9s&J3!(p?i8aVrH<25@c5t_Z7d0R)``(?X5DkYoT}ulVPDjvJ`2lj2 zMzgc=CWNn&rzypia3W1DJ_mj%*dkd43>HCd&#(xiw}Bp{R)0Z*FZ?B9?Q2j^V#d+gDh3sOQWY=0@ye;Z}>Pdug*M@^QuYx01C08OKW!F>JPXaaKd;M zskumW?}Q^fR_LlpeQ*#4?%gnlvb2vLM)65R(=(1mU04uAd{^Fw-&{hdGQE?GIVZsm zDxXK9y84kF&68zEy~DSpJ@FM@BNMq%9UO&M`C9y#?1x4-9l2daT6u<}QY+8YsFe#^ zuKeSI5X??)HTV$BzVef}5A;tM>A=Uy8GT`%1Yk6h^V_#$-opMOwu3$6vU`qf99B`U zoZ-=$E%|0&E1@#Wux?nJw(6-q)`=g|uOn7s+_-8`Q>JQ_na|+U-UOn>d{c*mcTw-v z7+;?X7O%D~?n%_057ecmzQ$CL1^nBzlFIwyI(0uu9V+9|U9P@DBZX9`7@9x>Tva(# zPSP-)v`&(eMlsx*bqYN1wvvjMR85Q1kZO2}9N7i1xHqcjVWE)P2PGJ7Q2T(lChpVP zcR}=S<^G&@o*3GS)2799(Q&XHk|yW~XXRK_=S;`1(mwJr@63Yq=>t8XygvXr{n44s z=`YwG80!}#5smR|%7xMXoY9esIG+OpWwvmh_K0EkkNlQDvek;-f+~2n5dJjq873lb z_+FG=TCgW@BRIrkP#5A^h2XnhO6OsAgUYSi)f|6K_tPI;SV0(KVOdXTdFYSoFlE)3 zCShbk%jg$6LBaN4GcX^IW;skX9JV%C_5EeCP_LmK_?KtO^PCC!D<-HaGfz95`VbUE z1+%B424DDdjF`O{f7J2NJtXk&?pH!vbE$Fb(t_)AHdLSvY&PWD{(8uv>N!X@SQyol zv-oYmt0C$kj88PJxFDDo+@}B)1qK-#xS-BU7WWf|lAb2TZS}n{Dnul)wf0BEWBh)) z7y<}H#x9KHQyns+n$+_*BbdZzg2w}8xemT+)htTGNjZF#KLcv@F|ex%wBGUlxtvWs z%%<>de2@iCO@9JQ^MUMUEN}feTEX!eW>YmbIE;J4#7$!yNeFR2LMg&3DiOD+k#YDz zd8{;c>fazK072~Za`5A7ZhcUs{n@(65KdI|apTvB);En=xVNYF;8{`wHCH_m?Z@0r z_eZtA=L4m<)P6l`S8s8<^C?ExOhtPu!mR&E(11%HI&qJMtNW3UC~-%tCU-#l*b#KG zn=m~My*cNn%rEi*jR;9737@9C@urO{JoKVZXDKL{XY9};1%b?RC8^KV2L6WHdm8Xj z8hueqSbe5sbB;sV56oIIeIO2T#9y$?SNSgEu(zAe5@6h%GGihfv`HcwQ~s`DTEXT( zcV^@dS}QZ79~ouIdYrWgv0*RD9CRqjEh`8(4NN7LZZltzlvp1pH(9i9I5fb$HCN6B$!ed#@K$B_eFR0QVjX8sSumxc!!`N3-@^4l@ zf?<;I4xr3%E|x~}MF+DM-{}#ZYh*Psk0mZ$)q|pB6Bouf>rpB4O{wEhg}I*CH{*}y zFAmC>Pf+EY0m}~#&npvASuF2Su~>(+jKx-Md5n0ls|&jj2@Oa-EgvHE>3AU=BJ{Ku zT@m_ob-_Cnp&Qh9uVV|2UR;2MS6H!qCxC$csewR7;vKS2EOCuoOjQ$e~WUCH>ugJmE<$e4eBQ_AE)r648)hn z-}&-)c0%-Z^-K2kB1=?Yctw8q%{kbL>=_yQsi*H@8n_^|b=>ixrQH!Y`>rEtrTt`w zG~b-H)-~N9vD&RVr}+z)AHdQgqrNa>*q{prSrLQ|8Z`LgK~{ZXx)6WiA!)|%f)%?s zqrN2L{33s;6*;87QABF%~n&ambovebWR@c|KLG`oMxFFgbWNEkpw5eL1xK`a;9x&#-%G{J`}Kmes%vfoTYg zF;v7*YyHu9LY?RPONL#Tz|)2PK_$P1r=iy1G6(ai^`ies1=0_x9#p~;&x^YgN-PL~ z@?dtU5G?Rw7Avvl4K6Rf5T0cn7+dKN>btPGh{Fu}xP%!J^f7Y6PZ=lp!n6%a?)pX6 zu%QD;o1U&u*7_SOS^^PqPiLHOlgozobPDD`5kDcHROqY3rSr52`D`(GYQ@-&msC@v z4IUdmPT&sh=^8xNs&=U|+Sw||@Kp{)q3T01&mwDd|3Z8A5B9dIT?#b$;My+Ds&?^R zkP%!tVQgn&yP8HH!TIq;GH(G@x-Ts7MLSnxl6tALAU!b6n&%Lq*xOl%tF-1h177W8 ziGp-rC4F59g~@^zsR123G#f#M1IY|$6yp}>T( z9Z1;npp`GoJ*Le+BPXLXoMIyG_`>kt(rkaDnY-3UqaZm!HIEI0Gwsz#ll}tH7gj^t zj_oT|81`&QC!;S*7)Vr+Uz^-)sCVXT9HTz-he0o6EhNDD5v z@w`#9&;Wqi2NyU=lO!un21wKRIda0-ju`1frLy-CVe`+(1kVwp}(&(if~^`w?LxOEu_sQ zqEgE5<9nctBl~XAK7G#*_#L>&4-#;3lA%BHmY=7*9MgM$lSXRia<0^h8ENfYPLA5S z9AuQ|B51`*GOBO89!LSJpipB)I?p`~-;oh;rdSCy$0b?#me-f$j=lM|>ya&oMq=8K$&b?t96Jf0| zN8O_S48W}@8jkjfKd#=p51WAmxoG^#7P~%6y%Bc%=;&LB|CarO0>QNlO!RMLmfJx~ zI(Wvv>EIA=2aUXl{(ab5|9alvM*p4y&`$rJP+P~h*}p>dLFMo4pVfN*3jcrXU;hbh z^sgE~C;Hc=wf;r!x(a+_GS@SiFVT{#YA0)a>fiT`qMGg?P-nV23={x@Bq4+Euv`mz zhs9MZpD|%0%73*J4L(i^Il$6WHXyrZZz&)6u{d1j^TuFIDQu-hv zg9!)094_NB3zl#8RHO(Wyv#e>0I$#^eAyc)Phwx91Kb*Y*e_*!gtkHd_d??4hZ@QDwQXc_lJlU#z0Ag{pxZ}KBq{%AIjRdV+ zOJkk(J-tKPA|^oaFUL$C!9UmX&uIP`SB@=46_R1P#UM``2E?jvMvc8{)c1Fz1!yz4 zY1lB12*Xi!X=F3Z2F*^{AE{A;FqfgfPKWlJ8|*cxf}PmJFHPfdYUT&@P|FOE4 zR%Q%f-snY;yY9&HlsQ?K5nlplfTgqALy?sSE7T=}48SkT(bEOmfm{?0BER)jzSMzv zCz&`4qcch8kK}T5!hX~hW_T}_M)0B@Vy%LuzRH8x67aGE5e}eNVsywHfuk(-IPr*) z%W^=7ETJBNJ7#!?v!aE7VyCYXSHe+diisZrD5mHl)j$aUoohvKg#V7FvHBu`%Q|ss zT@gToYJ$|pp~z&t1*?4bH)HJ~VA2qeI|ZH`wU5B_8Z6(L4wMj{*Rpd{;6WDz9v!dY zks=;=Dzo!h3UC>C1Q_^osQl10&e9H6x@Wss$yF8Lq&$zj$_vFi+I_kQD{`^|Oq2_B z8VV`mf#Uxo?@geiDzZP|1QH1dc2Jf$qDGAxT!|xN0^%gBFWQkfsDQZOC>RtWLN~+_ zG1!UFw(Z0b_hoS0aBx9!K@bdt5YQ0;bwp9YWu%@U;093;zTfXwz1OchO+fJfo$s74 z=Rnu1_13Lhw{G3Kbt_L=?YbD`Q0M?+Mb5K`jUg;YY&?xcn%IzvTx{g4MshrmcP-JU zv0(ulv-#yB54;Uy8z7f3@Uh~ zexi*@&6HGQj*!hhFm=-eU6!QAi`Y_gij%s+q^=aud8X~CKh`sb70i+>HwlAIS4V;k zs76`QoI~I4D^6;e(tzyH9*38x9XF%Fa3ACcJAxpIzV#_*V%}O;*HW-W!%>T9X{5h_ zqlOU?ayti(8BUhtB#UO8t_b3*-bEx&SwjA*1rhDH8cRnNN+K<^IJE?C9*4gR{gUAe z-Hd#BySFV)3$%$86ovEUnbmEJTLccl#jCajBm0Hh=3AkL7NIXv0~x+oI}{X6>yS?d zU>~c`M{uzO^{uzU-*dwhib{PmSzQmOx|yc79&T+jrLwdhMbpwySy6^P43!yqLh4ga zeUI#4eGetnx7Dfd$o;EtRa||=uwIn@j=v#q_iyfNJMK76bH<}6yee;bQRwr=@VlW! zSSQlXDG8_jxo^Spahpq`X+A6UJNr`aey1qBC~vjo|1h*z^83Smd!_U(cx&9Z{%GHh zDR@Ur9BLZ*vuS?Re>StT{tnFTZ@zxyKgY@6iTU5yTYd+g5(ge0OyK}@$Su$V<_Q6J z|IcCeXY-I&Q0pQ;fqvVJ>tp20=65`-oc@Kpa0_4H4!4&yc}Ik$W+}DMT%%q_ZDOobPAStY9R8N zB7IpTTNkM?MOId@V_NUdRcy9ta4zGyG<~Mpp;+kc-S%VD5jVxb7OAk;mpg#47Reci zu-|B}T4q@nWP?pG`A@0EtcuZI_aG}VnX6t%mOnTKD&QMfT}{&Dp&S&la%4N#RMkyg zoiy)R%)3>0;wY0hTje9KdVC!IdzAk@!2hQ6zrXXp+xcHL{u9v}cf~L0^_?5;=?S;@ zgs<>~kMV>r_Jn^rJ66v+gk5=_?=<~*(E_RvMckD=<~bg5SGHijR|gz?_OBD#pS=rW zD!UXJ&~^d$)mCafWbtwx?rCwJKshP)2 zp0f)+xW%1X+&(li0DDbX8LhLzu$CSH6MZa5(^g8u=am(M5;y)6^1AOeKye6SZQ9XV zks}|!DK;%S{{(W69zR*84&EOG1v#_h6S>I%`ya-cxf}h3gt1O#A#UMCYzZGbK&+BM zP8u834h-JBW0@H3zTrn*U;_vAUm)d3zM3U-y&lUaltVaQx$XuMJLFw-WU*Sn(rnJ0 zTRw+xeVV{Gym{stsZdtxy2!-r(27)b`55>fcvnp<=WeAE#p3rTbXS&=N#wQ7!793` z5zDn_*s5S>U`5{lGu2UBXJ5B#<1+GCM4|gN{W0(S= z6BZ2?<3qKm)ok7(=_i|F6f>QySxz`qTga@^?MV7;0MA+}gi2QQk;z-}!I2RAM2($7 z6~VdyGleb_Q6}TiRsd4sL`VO*rN!k1zM zLpv~hZ*x}>+JWJFks;>z4u=p{L<&D_wlvQQaCyt~RxeG!N{kmZnA># z8YWK6TapT~R;(8&3l$(uTgftLp^DRhJC#Z#+FU+deVA|IpguH9;%RD)EZo@6{Y7o- zo0$!5GcR7ylp~|KCyp6?RkR}^R;Hl}D|!>K2sPasIhFjxJ#%#NS9FoXKz)|4Y8MlD z-~Kp88LeG0t}JI{?-AD5U{S!^e!lAAR8x`a(wVgaRLVQMg+Vvh9i*zg9aIFjx&#cG^n6uaLE8{VK{ zOP?OpEzF1|3vVdLH&G%!j5I2SsIkOTBt2z(9B-KI6iwg_P8G{o6?j7_Q8JewE^p|8 zdFkN|F#I*V;bw-&8;-+FCvQOEhjVIC*yRae@zMf#11lwp@k7SI!R`QoOBN$ar5o_! z=)=JxG?p}rDCJO*=)cJ{)2=ENQDh5ZQoURK4U4s?5nQfNfegiw%fJ*a15aqf8WMTJ z6FHRvh|3e&GMDg#?==Q|)v)#fs9KX>9O{>mZC@d?h9y&!?60BJAd`j|l0$+BKbx~2 zpIiztGz_BGTsOv!>yd4Rsm5Pt&Hc-WE3eKTftSF6Zej7rq>xFDl&j>@Jp5~wvA)ID zT-KI zPcusU5phLUi1>af)2ec~-r1I1f&@Raz%#f$fz>`cig(WJb%O9*KbsN~1 z%>dl?&p0519PO|%=!bD*Lp@1L7_3wp#p`@k3q?FN_@!QH(AC(#(xTqzK`@89U4y>F zuRF)zz;)*fs3YRn9r^c;{rtZUglL;4@1Tr|OMDiuxqVyAFJ< zwg|^I>wxG$Y9O|TB{uz}vE)K;XpWM=|Ckid=lo+N3Z!QGEIh^0Y6*)X7D}#Sm(wSg zv+hYbL!cxxk`4(`9U@$X`Y>Ec!G#m(+*zT^P{Mbl>2UhhtN{~`Gk||iHDtT$HCd0- z%Lo&CAfipYbXTImEoALOKq7$Y_UmIk5K>1E$z$d!XFpH@3 zWnuNg54PcvnE?NK0vkzxg5?e4K#U7Nfl=GJas%)gk{3H~S3NkJF$5z`z%Zf_AhnRi zR}}y`km_rkY@c2Us=Hi>MC%9D$pq0TbE$G)iLB&*M41+6a3(`h)7#CIF3p*PpEl;WO2aLO+Tc@j?flT_Lar^K?tk*Y;`*A|c{l|i~5JH4&g&v9bdlc3dd^o248L@a;ttTWfturtTBp<=7bM%Gft|eFh1-_K>4WjzL?ayf8q#`yvf)=dKrP%M-!33?cdA<^)fIWG z%XievvFh?&1+!Fl97Wz&)AFfhwmTVq%TczXR%+;H!1ojeV%s7}-iKhQ#ovZN(6eyb zi@+nyy*;zQxP#r`vr*kG+FkQ+j^R3MuMmyO$u23uOG z%WT^CK=My)(27omgpDP!>n~_7^{vnsjXXoR^)U1UVW_dg%R-AX&X2Thd49NUtAbVI zHrw05S}@D0jtH;iQVMg_$c2aR#P(&UT?cSLg#oS9`W|G8uW~gMe1y@eR0k%B>j$-3 zr&p)~6Ro--;E!CF;XnE0;zhrv7l-Oo{ZP#>QfK?BH(?ZDja&lrgdupjttHjQrI1T- zXB85E7*8resZy_^mve4FOEd`2v@Nz4{gPh2dh&^(Z&IyAU!+@6e`dBT7r<7eHroo- zgE?H(Xca69ZYqwPL*rc|B&tPVxoQ&@N3hGED26!f(nyVDl#uVhgk14aHaTfIY8x1V z%Q`$xE?bx;sv+lGFI8#LQW)k1>`NlURLn)uaxNu$-v5DUIY6K@ zq9r#Mj#LS;1r|Dyfw(P!)2g=Ibh;c92?%THazKn@4lvTCKimoiIlwwurbw4(V$hTE z%rm9h1fGdkH90fGllLlJo-~Z32utYg>SzS*hrqa0@LJ;AmDVSaS+){;6fT|~3cMeOSoNzQ+Qs`W%*fw>_uZFy@V5&=+C{+{suF6nl^@m@U*+%vY2(nU7c(kG5iSW6!?3zEB*{$&V|S`}AV zN?w~-@^d4^xh1n$5>GM7ASGkBxUua&cHDJ)-Ppd3 zHkxj1Bb?l343<-5*$eIW6lSnj+IRM|dXI}aP^@YHbBblKl$YI`(f1U51eK?VYZ;sm zg1s=ZAgozWsiA#)Hy5p*;pJFxBa;r^iG_cso%S8Ykwvi7fs(COq=!O^BdZ}l1X@Qj z!=1zo7*c~iI?sfg&bFO!+TJ4cIYgV~kh36*WKK)#WG@hztI39V6K0nx!BEB^;*nnT z+|(bQurHC(HB2%(AQgx0bqMazQ4(!jyf&d;0)x#eYig=>AU`CCG6@weDz zKh9*@sWzp|Hb=sv_mx<~6T93Kj8%HP&L3V17^>t<5pNHkp9yo9NZ*4ghqP(5qUS>_ z_#9%vTd6B4hpca;DZs7W&?Lf;Zo(^ZRBgn9)Pltj3pyZ8eRnau@2$wI4Sn4hUJO~J zB+?dl%-SASuyq`+m7LkqpIU1_EVJYeGeUTm;4?r3So(YBiFWJFN%rS1=*qo7l^5*g z6i+yCrW@UpPn7E^#YTHA`wUx;4KfN%M(A9fxI~24I^BGcrwQ zxq`J!PF@S|`~j9y)^c9*T10;k?R7Y7$xmJjUkXMos~r-@I9!Xdi}+ja1WoL; z{|@mh34B-UVsCzmVxJ98+Jz#Wb2Ri6Vb~(;R&8_AQpD`k{yl3*)Ms* z_jtm0dBVLt;cZ99+I-Lx-|?7Od>c>vy`Jz(p0eM2;(zdj@Ac&QrzgI@r~VH-@wO-I z_vB$c#vYPpo#9^=f(~}Sc>`uW%n3UV0-{4O@gyo?;py6ki2WqqReHg~Dy9#Xd8SN* z0r(>E98O}3k9wZNO2`wr>yG;lV>`csOCKyrhZaZL=D?DD7u28&!7e0BC%O@RCs#ssTTNT&*tAr2;GLDd@4vLT5Bd)Z3!~ zNE3V2aHDIFB>lVaB6Ch&7}ueEK)I=H3%DupRnK6Dq8H+pX>`un!o~S89963DAJ!Si z#()*x4^B>#8`L=Z3N0y=^KW%K`WcT;Hm2^Dii53&0Tl2>D#B_G(Z|pCXR^Ne(+u)H z&D*AeL{>wHQT$^e-G9Pw4?tZW`(1cfph^jOw0*Dd)q|$#7;PUPIVe1}95rE_#h&{j zd65`)v7ig41=w)pO=s{9v3ky@EEq^v&jXCm%_*rt=)OW)J`71Vkj}8n&|perzLbu3 zpPGgXc#jSQ*kNxL8J8&yR9f5RX6iPv7k{4TpK(Lsn8ZKDf>zj=#rGDg@lzb#qN7ab zSkNB9jKz5v3#`Q2ES~o8A11RG|A8|gnLYfq!h^Iu{3Gg((j@lcQyQ`Wuss6{N*p~k z82kR`dGeaPKP>ov(x2n@)Sm|drDGrdh}wh^YBE2jGz@2d3Lj0?_6c&0_a_)gywswl zFoE|$GVeIHC5atdI+aR7tn`7LG^=5%L$eJ+b4V~AD{n2~oX1|66Df@)Kq;gtRfZMQ zT=M4i7-L%T4>Emy^?NWl*U}Ja9P{6)fxcwak*!;#yh*nl4I$1_vN-k8MKDO;Hjj_D zEkz^Iid27e2J>(O-j);^nO}&^R%A{of5Nl)W6eNp=kP718~-fgHJFYU`+m&hB6q! zu)s$1)WfJ~6&?9#l*R;#N;1Y$rfM{lD?JMdp+`f~&xTO8sS65-rIG{6<`5Chzoj7| zAYc1Xp_IjTl3LyhCPS<>0FD!^Kw)D!2SAlbm;K??^Dq$6^bEibWs3k8DkM{jhPaHG zqung^0tO6sv$K{UBaHb)45-`;ViBnU3`?+S{d0|eWZ1OX&8Zmx6$GaQdnddJ} zgK>CNPC%hs1{J6>kswid!dtgB=aT-Q2z7mO4HtA&nD``^x=fNZ1;jY!p*R>LkvN2l z*VI)Va4O6@TyLL#q$AtZ8^{2beM~IYJ_YEE*`t~J7scWKfNy*t@!f z#Gx5+8@~b%!3unBOCiKz{q{_Vba~2Q_G2`Fv}S2=ZXT&5MuB@JKMY{LP#$n!sCGWU zxhS|d&$bo{jyn_!$=%ZzK6awBNM(6|3PKW1ZG`w#5im$ny9RiYDaCU=&;iWq3_(!{ zh+u2N!G~<+EMPuN_A>8SoP|+y#^Ny#)>DXe4>vdbC2sx$I)nKp(i<5-HvNHhQ$M8& z(!cJrXQY4ac269k{_aR8-+-9~rh%GzzeajCr@9=~==(tb93V)~29#EGzDBwiJ+%zosc7P7?K-CZ(juy04$D_^?(RlB$b>%t3b zK;x+42-N4$;*}`aJpE1CbU(!ZxW#80BIw~#c&4wK=NJ~8-WvIq%5fMsmBLP6kTQ=8 zHw5AfiL@_gpt29%O&x`@UaJ6BJ)pe@?bK3JVAwoflWv2Cw(MD(e=V zU-gIFVb0O90cQ{0*$jg?4$G7!M1*Hj8$EyJe8EGo!NMBU1-z#V!BIc8Xn`X+sej|6 zVn?O>u6ANoi3c5kTE_v(U|Ul_`)G~K;bJQ23%{%Gxj=Z)os_$9%#c$k3>cHG3kZ%G z9X3J#9o+YHq1hsCo8e&YJFaQ@fGPz}(h5`5GZB!i(S2{6WbT43c?FT!oB402ws(mP z;}(CUB3JzZF`_d00s~vL`$I0arDQ$BVLKoV?DB`NHtVQqWq69JtI|9Gi`xdx1BMIZ zeW(uz0S(Q$Ll$HeK|VMp^;M0>7zn2p(TVdwI7gwB8i7&{dd>q;Ymp<>EFba* z6ks3NZ~j5AcE#a(_|mlh5&LB7y|GWGPQs^$1IzxZ@|=`lEBkw_+VIa16Nup(kFv29 z{ux3_w4*o@!b4rZfLAo(H@t}XBA0zkK6-gI9tr{9O8YW4>C6|IiqZ6T=a4Nmz=VYB z&wxfdjU6`oL9nfFd$rQG;n7>%JZgP!qH>+wNgQVP#+Tk77G1=uM1D-R=N~2OTJQ+s z*~3&P#h7YcxbDqN3}tcnD|Mb9Jb4{O?+YjpMZ4#3;~j<#IF(YV?Xk($k7WfQ)lweF z7E;-wUdDVkq;)vD0yQ@rKL+7-z!mB2p$g8CtU%Log$i4Yr1BU{LTq?9(I2z7X*N zWrbJlUa#Zt)$ygwuRQrD>-ZszH-0Om{*gK!MjI=GbGU>%)W$+RvS3nnedna> zS8V+|pLj9r-%7yC_3zIPWz^eql9$)=7p(O$g{<(ewDRYUi_$%KD;>p!KZ{=yk(yVF z{$!!O-OAdGR>juDjp~Oeym3yPaSC*LOYo7!@Hg+U_uN!x2{zjNnwnA)xfwXZDkf~+ z3iIt3ylznfZ;@3OklVwp(?5U+?l16cO})0X7coNoFn$Jrpk?Vi&Ep?fq;-pWz3^vZ zXU|(8n3rrA*;CZ#4Se7Q2c;X-ZJ-8D*%gEh(sQ=EL(ziVe|zbveCJxiPBUUGEm?T) z=hOJUoU>EE8Pkc>B^V*V>cnrUCD@>LFN=%LMzqEC7tq8=;0mt2h>2T!p{1-1j=};Y z&xv4O^RNiUzBsJ@7*m;e$>!7si^FI^CKcb)yHpAIf{sM*v+Xard^~Ut;}V-yP=)WF z1cmi4SY7C6c!8b@!or{K=qxcyio^f4!||Wv@ag66yvvTY#!=g0sn#-eY8}amlADQZ+UG+(b>G7nnjluIV(xMeP$r%fxQgj`1Wvv$qMgsrpsK=dE5+{i3n;e z;1-ZGh=PfFk<$e7T3hL=sAr)PN>O$t#Tgik388nsJvo&9fIQw@@<+R{Y(-=@O4WzzF&7mSp&Q z?+J~+o}p&&x2vED{^n2E7yQ+uAo2I>5Bq|@6M=0#o9gYBE^g}W-G{|++24(?v)g#W z2mNmN%Y#p&1pL9$Bt?yyoD6?=Kd$k&V@fmlTbSPje>Vm91%K5jNc=7MeqZpn0oZo% zm*>IRsh)7a4db<2PxwrPe;@k$?wcm~gT+dU>UwiB{0;h-#@~F*?mf=m$!9geU(dk4 z;IAJF5`Q;;w=ej68rXL5cg3MGnj7W`|H}>6*&{vSzapH7KgVAQC52_eIU;Ftu0#tc zG7fl_w+i}a_^PlOmW90w+-!nn^3^b`P8oT)i_LpcV2y>EugXHaTSaZ+_`>TcA&6Z$ z?95sfx9pIERlAE|d;U$V5xzo%TjB{$xF_DC{x?Hoy9B&I7H~2>u|D>wV>16lm!thq zw_K0pO(jSgYWX;njigad0Gr;ulI06o9^$BBnx(>RS9Zr}g|`$%$H0DgE4B+*Z8M5b zPRl7qg|E;0xBjyhHMX*RFD$YO>V3EJy*Kh#y+AnpmHJEK&9lU-mKafv5#_wD*k?H5 z<4u^$&}cVYXLs|2PeIu1&si){UQhgnb4AG5RiIsczf=3#iGAaIj>4m>pO^DFiP8Hl zq_1j{E-^Yixs(i5>6^d?#A4Zrc@DsirqC;DjbX6-3*9YS=&y-kwl75>`m;Fp_lJt=}UG_CI z;?m7w(gc5efE!WCt8B9rts_O=`t}7{IiLg{|oq!+Y|f`icI3b zzv+yo@JFV;&*65@FL*w;M&R6`9^OqxxMmpUywE@Sf%ujZa){27eAL#2z9Oeh|LW9M zIM14a(kQkC=MEf7{&6?EG*qh-K=YCZM+GvVQAxm;pr;{3{P9oS41KLX`uJ9Sb9owr zPbie>4^zGLF)QVc+ZF4{>;7~ z{jv_<(fMpr-HH7d!tA8FmEp*IfzZGUc1~S0J0%Q#_vs{+`8D#bJ7}^HA(G`2X2GW9 z3B20@-(5mK1VmlMnF(doG^|R)>{pP@9gn#43@ni}pYzO)s+=LBQr1fp&5J>A>Py_| z(2I_a$x^E%=2W!+36Z;rV!m7kRh;fq*j7Hsl}lyzG6@cb^R_JwtwcsVwRtxO5_#D< z^)=>1Lx@x}1K6XDTMb5w3m#U|S_GGd-a{hB4E2$d^Wq-kFCH;&JUutf)=_o%89!?5 z7~Z^@i!f}aV;-efeMXAX7w6@y7A9v{w#&K6krkW2bOeRH3TNyVHSm1`Ge<^LTP&Zt zmU*_QRFQyO8VcsFwMe+6Ad-5gS^90+}I2 zz5W0@>O{#F?1YCHwLx8uvpk)o4trQf_56hs3X;KYRf`TT95IgZkUOAh)_CF7{3UEJ za%PS}TiM1VynK|les zXb8_=&*kFGoYzN;cc8T9mW~@+K4M$|+5_Wr3PM^ffEkIKzRU3I07`8P0DTKTu-_|i z0X^IRn%XR&b57YSpf$)sEI0D-4nh{RF<+~bLFM1$HJ{LFc#ZG+5yS=k!EfOOX2B|y z`?(J22E7-R2Szzid(rznUy#pL%Z_$ozYGToL~_3~Sn-~ay!~Vi*uX}P^*S|REv->& z35o30w_t{r&z%6^5&*gKs=%m`K&Jp|=7bj@70q=)S^c^Og&uzP49aMLLfmAj#oNih zfF(6oLYi&FR%i;5>T|(`z%V&Jl-2e(8IGV|XMgPpAKE$=e~2f1uqW(|Z{vw? z?+Lf_ggbk}S)Oo*SlHnVocnfKEZ!dEf$ai>J*N}S`LOnm=vl#3{im{eop9psx_Z5d z#nZET&6dwuWKY!JeD@v)aGg3FtB!+o(H3zT8)kZedo%W#o^Ureyu?1;gx&WkVA7^n zWEET|{kiyr-?cwmplJ5=XT5y7{W-?;rx=&Gn)K)0R?bqq)Sl@HKjDU#*pHiVqVGzq zA92f_R)(oXP{vo)22bUFC{EwxtLC~AuXA$bO|3%XLUpy)qFsl%DOwD12fG1Wy{&Nd z$FD~fT+L)(NKdhx_wW3Jn!XLHJM2g~nUZSJ8c*b$gD6Q|uqe@9y_&_SQ)^C%R?Bi| zr15hYqwxtobxzmV{9AZXY@Yqw6JF~HFYtutBW%vIWPdICc(~Gmc7G4MY{>H0L%+!b z-B#!|wze6?1^rTdRX-D**uZwdep@!$dEbhV5x3vQ0=Qcp`7yECWWRk;3isQB*Yiee zyvFahgLi38`RQ1V*K94!IQwPj9I^J!IDz|ZF76u@Z#sB#KOEETX}irqAbC+(iszJx+wJKXJBL$FNq0u7-oDm^Ij0|W*8a#{(e;ME@T)L;r%; z^F}45e|X;ETJR}n2k19B{U4W{{)g`?{iD1~|DXQO^pCM~MrUYCXQb-w-X=`?pWw#V z*+V?>7bCns^bh_0??C?_G@*YH;UB*yDgEDJ=>NLr=>M1|^ndw2(Lc+P{;_E>^p6p9 zusWuNgVj3w5>Ghd319CCUx%=ve>p$<&F4!Oyl*fQJ6{4DOi|&HkYAddFU_G<3@G>r z@{K*MjGtu_GjZoj4_(G`RJt~|G(L%fTz5a^ray7L43wK~>8TfO~2s)M$A`yNmD z6E|FE&+vpFMmSMF4g5KWk61hR#EH5<#v! ztxm?EI79H{?pSz_MO^?)->2t%#VQbq@kzl5P?hmDe$Y(&s+>v$RBcrE zI+8vT`$p&x3rAYMF}3g}vjY1r*t##nzm?Q2GJXx>J9TCJ=(ib1i^@_atS^q%K% zxA`NzmgEAmNV|IcpjUUuHC%R}0%$IYTm$*7D3jmQ@Le1k2xAZ30MDY7>+>CGplX1B z@aL8$EhCOl^RJ}kXlBOk0C)*fqad`EM8;-Y(dpuXk!N%l=2*ooFG8MYCCUnaSR5IQ zn*n&H33epvPa@e5#M^y?yAgWe4R;T;lSw~r5JcLg0i(=|Bev*KUB9zlG+v6u;_r*{!uZ;&>v84vqkJB@!%9OfG-XYB|wF zB;Y#>9cIls4Hui42Wb`fWCzkQ3rf?B_?Pc7_!{Jy@6^H$>p!LG|xN5EJdS*TFBIC>}Rw<6}j093J+-v#gb zs!l+ic-Yfd1@$>5{B6un5?)*!kwU&s8iFEU``e@t4X!#75a;~@kYHjjmJ;!%lTAFt zKbuA5rKf{ugD8021X%^;p<0ap%Z8lH_(#$|IS#djYH`a#)3F6QE_bX<7 zVJo?C!U&{-)GE**b5gGe1tc}g!qy_1|DnTAupX%ySshkKOpqlyEKmJ+8i#wS6|Lly z_b@5-EPy3*3j9Jysa^a=$US`!MvOd2rn6x@#HV%|X*iI>d7RM_{n%KCI`-mM|Hf$-?J0=T;Hjv}6nn^js2|7&fF~0C)o5?;# z((gKkK5*aA6eiTBIS7F@S;j~fJ;z9OWGZ|k#!iB;jj?0j;m0&u#N}0((EJa7)XHjmv!9GL2&=p(ZV_|O=KMpC$f&mkdcGv z5aS+L#~*aH=V9nI)p%LQr`UP09Ow(z2T1SPq%>R~c3FpBKI2)(^kl5VCBzIi1?q5? zTZcMoND#whOJ!Kc3Q&iU7Am$Al4e;)>0!tM)-hLsb$}GX0r6hwdh(HV>h5)nY$ByC zBXy%k6-HD8%ZW*A_EGRrW9)CZN{ANGGt`O8gF}$c+6E1x{RLfu(H>RPoE3dp6aF9n z0H-U{ValoNcjJ#>d=Uz{?FM>!$!lNQdAUL82b3jG4d zA`fyNgmRSRI z624dUB0H^B0stG|*<+HpS_LDt7t%Ntzc-;GweC=7|4?r~{X;DLlPCPJC;X}#uCrhN z$;n@5&+~+T@Pr@O7Rz&;3EKlfn0f)Hs*Xr3 z4*$J8wKoBcDp={VrJn6KU<1-FZR0`OV892Y z;UvrpxUc$l5GYJ!O2N+;79#9$YWrf?&4=sdj*?tDQcre9#1;&ynnlJI?fwm3kCGi- zy&7t>J5Y__J_EQ^G0(A9&VdBKEbDn>-SxHt>3uXY2-yGFdN9N z0s@@(Ctg1ux*hMa>6A_R5H)bW|M>35K!boSpBLrW7f=w1rr+BdvP5`b*3tog!0Va$ z+)`gNg#T5*7azQs5Z%~FGz{p*ws?6bIsjYh0oYUy$j5Ikeuv-}BRGIXC@W%VA3)I# zs2G!hv@+h475jbq<_$f zq&cewC1JzEr!%AaA}y2@Fv^;ZcsA+iD~>{TbmQ^4jKl95{(AHmOU1bXAPuebl%z(Z zF9r|MTM^AauX2M8Wv~^-Q_lgTFE#)(ubKRbhIBL3dW4qgm_|v*bxTAkiAo>Wiefkg zDG{_nnW$1#gY@)G=O@xxl@^F8N6e5KpcR>v14)jSP(x*DJ#}7Zp|<(>fvW>58KC4z z!I=3YBcKN9pJ_!(vhucZOOk3@ls$Cf*ybs_xnr+yE0h!wdg*Qi5qzeft(oB@brkAg{()={Kb zTo5dd3{b4M8#OUAPyt{EjTxJ!Xn)Yp%X-Hi-tGWzg|UaFwuB9GlTvGbSDN4T_*Ipi zIJY{s??6O}CIqhLk${eIT(a=bio%gE6eJu3BEuP9HpHx)IUsN#78$U&V7?SZeoI+W zx(leN>Hw=M^{0LZ{YQ%EJm!EUQRlHq3ifvg1*a`Zopie|l`KnGv)uQ6CA`xQ25GKV+ zwvP+;TNz752P9`C8@Ux*UZxXCP8W=#qmt2%4-d)1eSBRj;wZh#VKUAEZ1o`l6N?~w zQFP2^F=v<~=|3EbQ8K#~(kBrL`(L9Tknv%)qjj~9m@zezNDr1e9Rn`p3Pk}2@ zhp?PIinJ^Qfn7L1Tph;@f$8Nm`HiGs!B)`WnTY0}p0RrVsFyHhIYwlq?peC88aMf< z_9gpumM5rvU4G5iM5<1PC%la(Y5QyF_A7W%twH4-j0(dc88p4cufXU1Y?m+lZdNm} z-dGXxOE{N8wEZP4Z5;oym?Xq57o0U9J^Ndc)H&vXo_f4B2TB}hLw*$bWbDFQ>@1j4 zJL`)TjVLr#T(BZ=bxg!B!1}4$3pj?#BAWQZcW*^*XUkAYAm8F1Cw7Sz!am#4!oKuX z7u^UGaqKIA2>X7NU_Z(Q!{B>r8&*Sbd|{P;qnC!LG^fsIj_CYls8IFR;h7Bo$&?(f zPLbG~%G7Z>V5vXoK(1=90~soVfhHqa)f(tjcO2xd@pc)kC!7^{mJv4en>4CBBo-}i z^n@@3dE;-dQ{Di>s#o@U#8BSYt}cgU1!05yeFoqxrYWn~x0b29+fZ8AMZuvlo$#>V zV^A5(jbx=wAgsPz%sD!iwU?FP@Juatbj^r?Os-)-whuyo9Psm<$PJzhII(du*q?jC z6`%*oB!#FLQ+m-MXbvlrnar48X8P5#caii|0f&18S>R0K-RMGWZW>n487Znr$8L~Q z)t!+{$xK|9XveE(B$`@?E^F3qnj+^=S)dkqn0@11r<-qsq%=y85aD*aI!t~ysGj(> zpCygP?7;^&BTxMg&wlJtp6U;a-~Z3ZQ?@Hlz1u{ds%{6w?Ylg+qV4|5Q$Lbe{!itp zV|N|YRG#XN*`(#E>3fx@T9dg%PQ8|pMmk=HALv-Y^&3G;{G)88Wvbqpa2#UfDM#9( zl$BJrN+ewGLJ}`eWnd5Ro8+kvu~PUW9(f894Ee4cGi6iyg4mKou!^*cVsGlmO*jL> zLab#ccOmA96XqA^5z|(pR{pNXuj+<%1xHtlxK+b)BWto=MgtU*^a8|_C8o|r35PQf znfT0N6vB>><;qj7xblI$apse0dgQ4{H<6~&TeHXeDNV^{2Zh<0eUYZtfOxRPa@`|T zmGT=WP2q-+mZpx}cWLTlmf2rvD!6M4KuTZ1{Th#r3il#SJ&BC_AWa>ms~t#<1x7NS zV}A~^)Erw*jpV@;k*21n%>YW0NK+o(9ix6%nrhEh_9RVREjVu?O}#;+HIb&MPo*67 z$E0$Uor>XWPL3KP>#IkO+L&C9s!7Ar@B@|xwg)-tkH1llI*RM&p5>=isNR**_bflH z;o9_@J{_!71g4S1C0c`KgCo6W8+7A!UbdZ*xY)lGAZunj0r)SN<`^<^1DIpz;B}bP5F}4 zrMYobJEg>~5ZVpnpc0$H!9NqRvJEg=7;YSyh2tm3%4g~j4#>nT42%T_O&P#;|B>v=&uynb=Eqy0$pl)U&P}N zhj^m^e4^3J9AN#devl(rG|qvc$R*+jNl-M z1vh0B&BcmI0V~?>m`CAFWpqoBQ}p=bZsV1wLEX#^zMFF4S5cKB4UwfNXBEvwds6Py zWpHbbyL>87Czm6+%uPo8;Szs$4f3NpRK(U~!>o3-V2yWE&Onq911|;Y(rUd$7|<8!tdH?Ri-=Z+_Ab&?0+H+>Ozo7KVh z#a4811;C`;rrh#Lra^z}2TY#uV9@4$La*WbG$r3B1RlOmdKvVdFN8AJTeT8Z-Tbh_geaAcs9{d_#(>?{Hqulo+@oQ`rn4B90UF>ol1~UU@B41 zk+j11Ez>bXH)Bv*V2e&|WP)KF;Q=e5r#|O<^sQk4(}iU$9k8C?91GM0X3-Bko5=pM zDY6r$#Qbern%KkQ{LLSIjp*{CxQy!aZLM2+Z3U^5il$!yaGFt>JL+=oNgbVdOm)6T ztOCn8h1N=P^i{B=Rp=|JCC4OnHRtk7t&Z5P&8fvd#u(d5z~J5Q^XQ~F`~l6P zqc4yS%q*(_33UIVRRRfMiltu)6nRKsB2P^w#!gLsKN9dqMxuKI;AP=zm|Zv|a87Y( zCtfN(4Mc(vj!e=J0tvJ-CnlN#;QYDK zVGie*ckB&`#D*O(u!fRI5dW^vpwC{sBgS`=8I2I2xeXyebI>%iMyKDr`5{o)zKME3GZoHC2Mw#ygO*f(<*WJ?lU@>r$jmeeua*3L4Y<4-LQK4BSgEQqbE_Xt8axB4C!%$ zx>47o(dxJula7m%v299$VEv#+*27%3(Bm23YkK6#^GNiOi!Q@G5RNUmjOBfKxE0ga z2%FI7se{s!(B~W9#?j|k(&yO!*Xi?5E`7FbhCcn8G=)r)(x-12# zDI{LMq0j1VzN+46l`LbzcO2@z9^ZIhv2X~l&{yAz5NNg2w7VM_7uM$=`gjp*?$R_$ z>*;T76qe|+HS%`D+Lmv3X*FkEQ(DChkEXPWV;<1yPcb@${i?6(mZWrg_z!!b(`i`J z;^_2|q;$Fp1P7R9mg@5b(mOkilRZPKy-*b=TbAFD>LyebKl_4sLZjDDr$Tny3c^>{ zZHbZby3b-{JO^RppQ326Klh_eUa61(%8IQmUImHz$st2w1k zSYrRAkEA!t*pZ{b6NBMs_cQK*R@frk81j&G*f@7iA7UTmo>~htj3aJ2#6~d@dH{o2 zYa2qGTKse9u>ixOm)cdIYI5`}wZjvZTG6ANnq-~btsdK&NOy7T>^7B&6*X?1{U3-$ zUGi;gojn0WkYxYRJUxU`lF-8@_5UM!;D}-lSR3|>9$X$}_)}N#4^0odKRFP3xNGxX z=pls+#w<J)FBSMh_Q)Ad}I9F5#}U=3vc%P}sSqYin-u6T z8o4-=7VArW7!eRB1B6B*GB8_0YV&V>#>S4=FV zc3s6AI6Bc1*5X(d`KSV=`dCgCrKn;Es<2Rn#VVk70f4%SpIs=fh*dEJRiIR#GN+1i zR8fH{%1}j_tW};Wwz*ZD604#DRiKm{7@Jz2q__u3Pk59gD?Ufo%NnyiHFj}poTpdj ze#Y3w$c(6WCW<-r&erwLm6~MZ?2kOh46GNMb+@zdkZSPtmsq_lhI&~E+}SL{k5lhT zRsn}Z{0WN!2lX<8r%FD?r-xt*67(pFVh2^SJj4fuAE(N#2peJ7h^nZP89Y_?cdNv; zJEzJ<$@4hNi;N1HIa1BZgxaX>0DskA=`VZ^4JR`w&+})PAmrmI=oi1?{O*JKBSI{u1m_AQ;mzsYR-Du{t%23+d7-%}5B z86ABkf*31-2L;vVw(zT&jE%vgX;JDa_0+>$_7LDD9v;^7fUaj+d_5dXgPjadJX>^WQBdA|X!=h$x2AuH`=3Eqyu0y@3J|Xc$gSq&~RqyH#3m=wR ztUs`M$7#kZ^6`p{snHGoOGl9qFyZ;5{;s2z=_vlFNjggDDE_EXjEV@Spe9sv33V8@ z9D3Dljb2lP_Goqwp#so6X$BY0>V&TxWY^o9kv(Dmr}chGRIGxW?=Z1l=>{ z@H2q;i44l@m-m&`^PT1d6s~*mj z$e?nawcJ-d(37_i3fTfXp zW=pXR;6((9#b$DJBbo-@-k>#$4NQ;Ry%I^f7(>2lvSOzg2?WLXqo$i;HM-bVw-`gd z>Ki@9NJJ>cA9a~2HdKn~)u%v~og&}#C3bH_YrRzwPexPhK8R52^DQpF5PbpY#UFi| zYnG^sp`=KvpRfEuAkG20Xc(HE(D-kBVGc%ab{^oTD(tag|k4p20AeHO!x74LZWlH4s}5| z-l%h$LBVK%;GqD0pJ!jk-?aZJG=92$VI3b~J<%xWX;h!hw7==o{cpb#!^i&r0ByK# zf2Q=`ZU2I%rzwd;F!})6PciMc{!-eH%;LUReGD;2(|;LG!xAVUk^Vo4>%DVcwvYI) z#MrU_M}OsQ{}Q+T$$+c*_Qxb|A8Iat^m+1MapZ59Fb_$G$1A$v^=bzYNFbgD5XBMw ztU5##Xcv2y;QlLD1%3Jh75l`YJnsqgfzl>8+IcONtNBw{+ce31i)sk7N9A(~c-C-N z*eJRjYk8s8W%bG2__{~l#rX=aq&x$(SjKa3UmiOd*TLJ=(O_6+gWuDhgmqS3zt$04 z>g=Dx)PJCm{lD&i2hx8mo4WrmqM8HkKSpE^{RhKJ=>NyD{x3k&p8lH?a(H!z zubmI5@T7FuA{SwEu>o&+$@mwn!aGsE-is_>?^WS`De68j z4i5VZUprIfJJW3sr${*Wtow+(((otu{GQOoKx-m=t4EAH^3n!?2KkyENpHloW$Srv z>jyJ6Uc!w#;vRsu9h-t5k++FIqJ4&^oq=b)5_q6__*&VZSHklcL|)A}3YgjqJg=>Z z!E>yAAn@D_9B}9k`9|Qe2+vRhPkR@hYtTk>@SNy@rxZ2qKYqSNn}p}=jRH>@;aLuP zCVr-1lcDi*520-aKlgnY!_Q>YwEys2X5hJY6XDV4*8u5H2Bgi905wRp1h^TH(mWtN zgUX!!v6grDnSR~@4v3%ozZH16-V#Mmfe8^sm%H$6Ccw?W6ZmfoMIWNF{e-8NfoJJv zfrsla;pt@HSpkNt@zaGFnt|u54`T47Z`mU}j@vJEHtCk&IU|z)h$_Ud*%q^%?dw8P zilhWcj8Nc;#e)G%jpuwlW-qiiesij6zwLLp_#fdjR}KJm;Jq3Z*KBP9KpeOE=zX-l zhw<2J|BXm~?Dw($i&WCrZGJL9+gtw$!T$B%wBO?gPyYpgI`DimdjVSl0P+2QZ_oYT z8~&d&B6%q;vSYq-^&vgp1_sXgagGbbQvk3zAT9(D4$J>LDvKKrTHAV0OKy6RD zK4ux9Zp2l5Y{6wOEySrUy9lJp5stE5J&eUkqiHd_5IneXl&{tHd}$I+`(X#Q+(`yJf&ClR`4QINZz?biZz?0>;7 zX@8}+{ppaYb^rfC=$dVR=8FC7ziEFU+zm$L7~VtwZu>I{U9;`y?q~b8z#IEN0-h*= zfAYoH_+w+D`@ay-HQ)ZscjEhRMR=f!hlBor|62r4u_CQTPRSp5oo{+AoNlGoVgm_< zW#_rr-=<9IQGE625y4!?{t6}1gJ+_|l>DO6cvazO$raj~x@dh1mdmT1(xZ29{Eet9 znpRj>Q(2J~2(Hbm-S`P#S45u=*<)g{C0;_w!po3yfobgk|TD&*vGEHW2QxOaUYE76DFJVZy?FV()mtE zwB7WfCh?uPM8NOX|I95W%fI8YX!~YVk#mhnzdbJ9Sra)b&U#}-1_R%}vR3<6~TmLzt*y-+^}-i;;mt9K-^veN$2@D_V>UZUP>^^=PAvJ|qsGKqOHL6dH8G z2r5vFaSr4_lYf}${}8ADkmO>>k^bY@kocS9;P2mYS&HW3V43NoZglz|m+tg`1!jfY z|JN@XbKRJ+6UWf}GB)y7cpxm2k4R}4(D}j}%SVLHX=8{0jx|#zo-Rai{JMA|!1%P* z?OzV~<}oKopj8|Qg0G^vt#rOZPrh|n&^P{9(ls9L7#yo)F%w^R%e{JYEa_<`;aP8t zL(yE)DEj}XCw(f?Z5kntta0I+>Pf$b>BHjFZ}6lKV0urJZr~o~Nk5V4N5rT1@uat6 z`VO8QpnU`1$)5BLSjg?QCf(q#gD1U#>GP59j9xZ)YD~U0{Gyew>QVMR)R+;(L2+lX z^tWEWdc;WosB6jsRzVvul(}Qaj4+=qWC-v82@XX1E#?(@;18u+`>O9`J@ZiV{NVL} z9RZrR3Nn3FTwo-2(8N)Jt0d|uQ|L^MtRE zpJj~mRaamv1krW+yFb4k564uXTO^9yOCz&mTp>0hIep*2=?DkX36Yl3rRSZ|d2y0*s8`|wGm%9 z%X2*>W&l2338g`}>lsnugMYj*Sc6~sLzQ3L6yzB@|B7*$OUa#9f9h`a5tdzlS4VtXd-~*Vk2hNa2Op*@)+Ft@&MvU*&^92yD!F7v>?jlFMri=mqyD{IkLxa;(TB zTNxDN5q)Wwt<7Xyq?$Pi_z=Ek+}f&M>#IISaCRwtzl3(c#Cid$LvOVhG&oqzI$Ife9WEKNi&hF*CcJvR~x16vk?q>XRrMrQN}^i5N! zrb8y-B{by!OkD#(gCDpE62PsxMz90exO79KvCF8eu)3D0q!-f}_+rOu@Qb)I-*k98 z)*~-KF)fm#4QGrfJ`H?6iFeIH+LIifZ?;FuFOr0sRJMh(2SOA@nDRK~G^N@UeROEh2|R z0JJlw?L$?XUxpht!r4v&XuGrY;^r7sv3Y?wHW_t{#|F+U|Z;f&%*x92`}@6 z)6i!p{%ueGGZ9X(PcZyRKgJUN0Y2p|pu}_3QI(TVI*z2bdk2`0T7?LHyaGJKWlj#O z0)uj#N55_6T|PZaXRFmqG>5v4V}Y4T@^d^8AtxV1A8v)ya#R5(J?`^Ai289`{UQA5 z`}|}-{L}aOug~O7^}OZI-F?3HMUPj`eSQuq2Zqf!d}cOEJ02=XKeQ#{UrEcLg5?sq zY=-LbAF`)lHo0dl63M2{NAk<^&PajS_xSAyWae6#jm;yqCXng z{1$O_b`CG@FGD=~#QKjHrjDQMr4IJT9GI|7U;Wt<~I*A^!=ZJM5{cNcTc#4U) zXDi5T%30m?rqxYhRC`_B8K%1Hr8>>`P@@>~>eXY2x&h8adEc9>8d)$q&8iEUR(%4a zOgHWE8hwYdYFv@TrO;d!YtgjW7EFfmKAqqNx9 zeYz?3gf3Q!VwUv3X|XAuV%L~r*Xv^CC|1T|mo+VRE~5+?^f1N#B*pZ-%*Y%rRVD}w;K*})=Rjm z5|YF+O%|odZ)TukcYWk_-S}q~-+P027D6&EBb+RiC@5>(Y-FJm3sP!v6h^|uctt7$ zA8-VemQ#c$eKWQDufdo@+a=Cmfj33El%BVo%)#Rwf+$vXvL^K*q>u1rre24rs#O~UM7ydN z7k60>=3z-&0dUc%@VAn>M8V8uXXkIyU=Vq;SW9GSD;UJ z;(zqSPxQoF0LaO67xHL*h80a80nuJG8qr&@)#u$ITw1NY8k{yX4ZY*vFl;ai#s3ly zDe&lWEdQnqRB3_rAB=OOn5hb>t7{UESjs?X1mkJ8vR2X@=cHa$D|+Oq<=%+<4HIB>$zi0`L`0%xktnP zeuk6&@8s!Io%Gui(lzUAH^xc7HX*&8u79YLer`g#fp375eo|bzLwy&6`W$*P`}2bW zf5Gm$O|XkKuiuy}|2ld^Z@;s%?u6lz9WE%Wv0d;IYup zGa^{2H_*&KW<+p~RD$xzf3UF%op=6-i5{2&erw(!2TG_1s;MBEQqc-Z#~Xdsr*S(? zR5^NudHRvp5#z0b(sW;SH>Bs)+RSG5^-?f6OYgy5eH-A(7}(oa{TbMV-oblz=SIJV z$yxm}=T?I|x9uvBvx9$kKB*OGPSe`Dg*CuA{4G56YK--~h@-`rXf1HLZzWsNv6#@I zO}Lpi5$prEn@f1Z@l|vY=V!&?4~u9dUAfVx^(ZBg30cSx@E1oe&n+%khiyc$um6WM zRn07pOwQ)1-d1ouY%~w|cirJH*m!eCYc9aM1^;$i1$C1bgx6HpR=nm9|Ae|SQ5T&3 z7NFTce=BlXVwJGtMU@-WBf82XO2UoBUDp&(fmiO`x7^YJ0RlJa$iCs)>RQWZp&sBN z%W_O9g++^L&BhIJ`j7w9{?GsY`>(6~{rb=OOlz_iERYNDr-y$cTi?_9{kIThcqFh4 zXXMWLJ-3po3TvHSG;^9BpC_K*-}eg7#DxB&eRqFHQ>I@@g=L=29X7gDnolK!B4t6S zQ8}+^K+XqA`wRZ(tEvM5K*hneytqJbtAgX84xzN+k3N@)pAzgo_zPn6RdH`!f-O`A zA~v4n&POXczR-$R6sj**$|Fjr(_*dRb+GVoogY4$#zNN3h4cw(+^yckJ&fXlrNOsi zlL{|=LX^o+fkh5J3e0(a%wi6Ag3&1Gvn-B01s_zvq->lYgC}xPW^qsW*$F;bjJ*Oj zad69qN!D8Z13+PR-N|hob94)am;=DwoXZ^TRJr8vRnxB|a+NX{jN^ymlQ}Kqv~&za0nP|Y7-^>RcOA#ygp3aa@(j+_x^Meb4fVDh_oN4{QM=zsOiRkgCcZ355F+lb6`I8Q zwLAC{I3~aukx`ubiND~>z_BrU^eybE^3hFDO3S4!udqUOsmKvj)E}W&&bw)oK#hP_ zENn!sqS~*j7Y2FbF+!JU(h7eKh0?~C*)A>^W4}Z7V3@u9nC$*ajDi&bLLxV(*e!%U z;@SW={utZpLqQ~1?UAA zD*pZ1IvI(W_r6=j?=EMc++^RN9_N6>@)aPTuPO}k;(bSSuzTxa+*fZ!u2D^dzSi?*X0Qu>ya#m%hZZ~x4xs+|Jk4shs|~1BD;f_rW?o)qBuWG@BaaDh%-@9- zy*M@WOUC%qw=GT!R$#VO`Ccv0ESxqzbKBw;fy=|IeXj*N?;05nwBJQ=?Y{zRB8NrF zGmFD`2z`8J_`m*0-?JM1;l6o|ez>A44y|wWcU_eFR&m$2LSHnZ_Hmu?o3}i?BD5%@ zB+~Ybl5pE@1*^twks32mBPt88MpcnO=bdP3rzC906lPyzeF+wWu%0>#YRP&~R6^Pr zNV}bB&ooUt0%>EI7DbwB1lrUO{BJY=v++!^7}C5 zpmi>u?_m%kA+jfoxUpyHi-ldUpQkjn#7nSB9|C~9`ypdbwAc2xzM$K;X<_HJCu*4I zG~TbN@m)gWYoFVbJ+|>!~!G3bD{3gXT`GMHaiLoh1T>APxwjjE%r|s2* zPR-oE@vg);5#JkOA%}J$d*S{g+m-uo{-$b-Z1L?nM z|5VsQ>Gm!434}x4`8%81%_X+K<*5T|zY@d8{`Z0XoNm8NUFx>~L{q!D#P-J?So z`>#HN7^?f<6A621f78E`^k42DCe@gEU%|qPh7Imb7(gOna|YU?;;D@+l3Uan+}A`1 zQ9(u^Kkr+)|3J{htLvYbJ&rVe)yC6XX-sQWS3^}m8D4Y5&M?F3IVdyuDi30?6A^>ZAN1 z`Yt;KUuw!@&OWQ&J|Er39UCKGVE-@v3HMn|c@U_ENWZ_eL3)sI1Aqnaz~Umkk4E}( zh@~3oQ<5Nk0!u;~i6NcO?YREZS*hCYAQt$a6^H+Cg#?55GFuV6!0Tbs_@9!9|5`(@ zBY=&P$T?7p<5X-u5$g|sPlu5M70?I7M#YI`alsN_RRQu^(FL(g7zz%HIu3c^RNhzB zS#pfV07T0R3CHV8kP_Zd3|p&0^(;RyMj)9kIZ$3g@s}I8#ERmq7)pAcK{EuIj{1aw zk8)SdlUk&A!-1}^idLJ<(@ip*h79&hM7jD)J-+wosJ=iYR0#0OA@s0Lt&qtjx|BC*&IQ*0LuS&U4jwa;}T1A}dt_(BM zo}r0jFh(1y;J~Gvc~4++ID`@G&6q>^4v;geZ~*O@Rh+B1tE4Wj+8kVcJkZO9C&E2Dq&RsTnmS%vEnMNTYmKBcWz+zI`#P|Ml;Ws%^$~``4nqerfZ}W86@V``l3#!~_oMpS8O$pm z=4ivPlX*(5f<>AdN@-t2YA8Z_zbd#trG|#{eg=3Y#s?GJSCz(AV{;$J_v)_yk$UUp zQR7dAY@jIDRCvN-AQ9TRY-r^QRTjTkR?`|t((+XgA{h%bprBD!c!f4zf+{alO+~}Z z3ym2Jns5L_@`OW^dXi}MNhoRO<3FvJf)3Dh2;_T_A>UHz(b$JTzTyKVHov7RLzbva z05|yXRUITi5jzGar?Q5vs8r1XcC@Cb-mbtp=Y%I9oJ7Cb9Di#{!Y5#!k-rThC4qzw zC4qeoN_0p#@Mq22zJ&;=iEgY}>%2twZ$otPyv@<~s!Xv`GV96}V0Aprwo}SXxKY4XQoc6v%O-q{s^_G9?L6cazIKGJYME7Qnbh6sejpE`ETPH90bQ zGQoEZU!+jWnQ#`86Zj&JB4Sgi6EfJN5rz2-Xr(HUF|1cMsJFo7IF?tVKY8D7d|303 z7{!URwp);>hCdi1sd9*J4oQvngiAf)3r%=m_lqk*yo6*FNQGUSQnwz+P|sjF*YXkt zId;mU8cN(Ryn&v2POyK|ezDZFe+wD2v|r2iySnXDklRc9XD4mn6&!GsZB(?$?ueDsKh=Ps;*8Y8DOwHbJx zzApw(R@(!C=XwKAT04QqB0R+go>Ui}%g{!1@O1XT(;qeMKYl(HNx)Zq#vuYv8R2;y zoS)-$1D0xyp9rCC20v5pjo~MNn)V-_5(Ce0AK`KRA)H`9`V0%D2I*A-+zd!R-V+1q zpQvm<>3M+>#P7`X%qP(T401uS32QT;i~=b8JD+-)_Md2v_IW6afteN(wz3*an8w8} z0M{GsnZ=d5+#{)-l3klTDmq&3(4C^Wy{{WtBeJj~O+Xd&LiqO7}r zGSZrB-@beQ+g~7Zg0K4P4&UwmzQ~s;1Moc_ffY@}Ko^EyNN)~?5gGw#1f=ddhUZzHq1K^|1|u-s^z%p;KTI7v7O zT5(t0YVYW$jXjT}qjznJcr4mfm>p`s===vZcM*1?K?rHG?^Tz51TiXlH#ajpCa)W3p}VQ0&<&;!m_yHlXFQ=-7PiBYZy_Vf(BuP2pRR0AJY= zG5Bu4x@6=g>DgZ4tE|~C_znjta2N+4)fB!X*Tmy*+L1B%R$)=l@NJNu?G?WDf8Q_o zUI!is-^A>u@ZFpM-^`<9@a4JiwLAGAf=#Hg(hbVC^mWh+B=?c^ zK5$PUPdoNIu~6bvD2g0qg;Xl^SiW1|Ifn6X=xZv~YoWskZA=Bdt6894+QQ&-{P$M$ z3Q@64fF!F?+ZN>#<`56JuwisBbk(V;cY?!exu5iDp9N{(^G)s7Z|zTCAdmeSb6oQN zw3GNG{kbk#f1bk5L-)rI{Oq+quSJ{hkM_SoJx#Or5|w5@a6^tJiYawebE(5!VBSS1 z5`anEkDLNfn(jy3^&@6Wlzcz103$;*Rvpil;&_u$gQ|J&Q~R+6N-H^7ya^i+%|06d zb^>$>?DOw;5Kl2>qT!zjx73^5r~lPgRgHxs)VS;BZlT6sd{y_!*N))1MRPkL2ay6QBP7dmv-WGa3IRRb{`?DIyxa6^jvO> z6P&t!fw&fHv1smL8loyE{o}ZFXPa^c5bWrCjXilf{1vQ*eOsFND-g3PI(-;FHh5Ba zC5+T6Q8Bjeun#|f#Do!n^t{!GhQEh#^I9Syur_b?#?3W(tKnH<%xL(7Se(jqwzoI@ zwg_A>@x&kBQA@B@|VE(9Qwo%g>K1c9can>1M>!s88L8V$(3XDO@_cZ*1V!X z$=LCMfn(r7AaFE3$K0qh;Io?;HH5aNI`oVC`XhpC#g&1K2fl9%zM*ddus!*H3%48I zj;#;Bfqsp%g_2%Q{~;^HkQ<|4ldrv#uX|!X*RMpQgXcpNvUutDe-UyaWe8lT4R%g8A`#*GbZ#?QpDf{nlzd9{q32%jb5B1X6O8|O2wZIRfv9&O+& ziGweO50mddPQK$4^SN}nv!|)5MM4%YKAt$tWcn0hMiP8LGV={h>t#rpasLnsoWlEGPZkxO6>Vemv9^J~b}U%f~u6^QBE(7MB&C=G6ZUq_S9- zi{$P{#IPNLn7lK@;UR(!n{IdhHOuLX~Vxk1y{NjTjev z;QwLo-Q#nv|NrsHR#S9Mp>P##zrU7fe!B`iRTp=9h@qD_xt1dd>yW9*U;hpx&8k5?pChn@$o!8o{z`<`FI{) z=I)N%N9sGE=n>?6)T+O=-q2uU+_pX7E-yANl3iOe5MG*;pxV=ar51QhQt;1zEX7&Ks2o;~(#7vpC)( zmtVvUfS-T9x_2sbi9Lmv&C}FSU^8zpM{cqYMJiUKSn(byecYqMwp&gb-sB+n!<(Vn z>nvC!x*ptMRF=LS>cg!Dyt*M}2NMoFcqFc*Kd;HjRaIP_71E`;n!$u`Bnd85GZ zceHU|Wna!mH99c2xd&Z=Xzn$fFS*@k(HWY|l<}yA+%>>e_T?(UmHAvLdW+f#{_^6+ z%nYUs&C8JX=!?uMPtF!hHV=*H_c=&adzrdow7BZ3?ydv9;!KAHvwrS-P%LW%fjTs;Xn&N1*T|WhP;LPpnD# zNCp|MnQ18hTp~O=6wEe&**3y&%~*8-bTNx5S06CgRH_hJdDitml68?T5t6wJOU|t3 zE@G*8WEXMgC>CIr7hp8@W7~ z@db8KcFnjC4bGG-g^gse~!awayf}4Wk|wmhY`lz zUfh&5x&n{NS+CteQxUNhz-Um~n?r*%6WJMoW!~U}sZ*t2%6y)jGQ7d$^W-k$5<9=y zN>vVtgUb0(IeBBDH(8;K6wDh7L+Qqh)>ISDLP9Dm25n$ekgCNR;x!E6uuQ*4$bK{) zsZr-1Y$LN!X{nn6j1=Wb#ff-`(ky6TOM{9AmY1xIPByVp7i3J~fr~V!R_?qB<5;E( z09Zw{w(2u!E}pYcS4^-BCVz^(StB9)XiQN{)-V}wE)X`k9zimA4|0jUq;fDS@`jws z#IS1^Ssrc+v%cldaJgH%+^t;hbeH=Am%9?5o$Ti-1#s<<+}{z?aCt!yl2xCj{B=T;1D+j zae*IrMkAp!^h-$gKN#~^9=r(tHkbP#TT}%`LmREGH#UElDV;{Ep;pJ2tFK1r?&V3W z#VCzU4xa%B+6cRmvHip5x`ccW%!{^_Yy*?v?p#FElF_tYW5I!ea$M1alo-^?7a9hZ z8USQ72!|vxcnuxaQhxh+6X&3O`}qO5u$6bzgq&8s0C;s!T19*s8aD`Su2#**QBue? zJsg?aqNcat{dKvQK6nZ0gNIS@h?0B__Y?Sh0bEi0R&Bl)Cznd_rNKJ+fp3K0Z2rS_ zA!I`r0GODMRYkn_f$u;2_Xs5wz5{k!%PtkDCXOl?&FYLy$B>kPbaU#BQQskzkoWeu)z>ho#xC`~=ZT2L>=kOjJEV1)v zzV9hL2lem<2jPR0x25?qakBJBujlg5dGzj7sZ4MR4~HFb?8HKBchq z-nRoQ@sz@=1%WLji?%e`p+a^ab!l*op#hKrWa>d-%&noT$~ZJQwycTh>Y)iHq>wz*28$ zL>9%%_=)g_24ne#-g_WFLiC)Rtwm4YtU7Vw8^J}UKLR@nnknl+hxyin4wLbq!`7hc zU*yOf?$nZtD1SP`UDJMU@mKe*cqxv9%EdND3o|PQXL&>81y&HgLD8tA!7XI8g~BWB zgT%*p_89_+*KslA6cCBN-~!=>&{WNI=vZNev%n(esf_xtmlOoYV3-dSUYRdlJqD5h z&tlnKU7x$ZD}$5uml=*8-*;tv=lTM_gB*tUK+#*?OcdxTorl)ptx8mB zSkxeb@)k8jQ^s={;!Z4>{OL>QtZx4t7We8-nAM$tXBN ztdM!q)MpFXF+n}n)F7ElJ^lnM*XBv&kU3gBq=~F328RqbkEoy@(PU>RJ7-)KGD(gf30B$c{| zf}Mf`#qq6?f@T}6sR`zxx*I#HNZwj0hTXe$YJO;RmU`qtc9EI&lZh}Kz;SkavQ4$R zy`5&8B-IrvOtVd!m~7J~7TaVA&uPBFcVo5i31A(HbH(9dU~bj!PKQ@=4G0Slfx~5A z<=3FG0|)_x&EXhIDAqTWenoZ3DDTOTFNLw#K= zWmT^7h64RsAT>PEX|HQ;2ngdNtJGN6VNoMM2Y^4Btf(>3Mqq3`5TljiZgt8C~N>U-v zA!PD~fW7pv84QU%R%)f7hi*Z0@G?h|$`MMj7+~*U7XxgA zM>=Z+s^JU#5Pl2P@|E1n{gW9+yf|^`dGD`nskZSSzP7!SJ*7J+6Dskh2>uEd z3>!&uX_b->S(4(z8=_ocV13dFcvBAOLuuxh?8j0r%qo=Z#~ah9!x%&{;pg|~3y=(w zeHcr{x7J(5sjRWM&`>uYusJawkF-d==t!1{6&#tI4LJd6#&h&o7HwA5oGVnToV!57 zB9HD8N!1IDg`^_x!I}wxI8V2J6h&9t9%%hqx=iaa-64bo5GJYsmUV6!a0108S6+I$ zTryBMKgk>Fl!A{LqVf1NF&d9r6gZ7f(v5G<+DPM%gG(CE53TzG=rGI#=#-)?-TDq= z(E2=7DMuQPUuky$9dZ*I%tyyZQ71uHf^PEq|+mrJ?7&_ADI=STYI zeK_#_2UupZCqUDNPXQjDKLH_B=Y6OX=AJ52&Pyyrff+GZw0}L;D_u9 zSS5u23m^D{O*O6W18PFZYCb)%3CUH-&!CZ|^&-2%52N`i8J=O>;rHM`|G4fd(&!=lMEjU) zu>t`GgGUEq3NhlqCKf7g1wQkIiZRCg9~ej5#U2DFX}j3DaH02)l-{S%6k%Es-_r2b z&$tK}tP4SwTvM1*kQPwRQl2!RDD8&PV}FV$^##5cQOeJ6NQLtuZl2|2gjGFwI||A| z6}23JVi^g+G8!`gmCP68-5baU7am8O0+(&P!?INikd|72bYTr+OS~H)@pu7KOFS`+ zyv>R1h&zv;PftLu6k zZCtY~iL*=;&VDrn6Hp8-)DK}^G$eD1{qBHTihS%s3>ThCgM_6AA_A&vmuk(aOQ@>( z(?|XsdyB)L<+z_=@n_iOPPSRDJX~RiuL$1{H|I0+*qGlOyvCAvD*D|A*yrLhy*G%r zMW5)+t?XOy5Si=^9OcDxx_JB!Y98NX4GzJ8#;4|&`~l5P$PDQS)63;p$pcVQeSB}>r(FG)WfP@z$ zyrP|4B|07wiV3DncB#ie#baGJ?#NHIttSIGqQ zm7(&&M7X`7h3r0WKwqZ`zQzQk2o|>~rrH$u>3N8*DUn_eJVzqF&}`aIuzkuOA&=K8 zUuI08+S-iv2IN(wpge+T-I55%OF^Fb{xT$(n<&h zg%>e6=wO0+kj^aj}m!=x<9LX4U|01IZh6!5ED0@GaXk_f+( z%(&$o8W%*j^{s&9bD@E^78<#Lg=;VP!!wbi|3rze#B2?(bNuCuuLr^=K9TW+b;jSD z@dL$ASpX4{0W>qSugDe5FA)!zGMq~rVb@SiAUbHU&464<3{MkXUCORS4@hR@QGIlN zOffruhROd$e0=3wsCOTAvtHP_%4r@G}dVG1av;&jO zt_P-)w4<{_VdQ}DbV3U!-%QCT)6L0h=8WV{a&pVm3%@B18H)YUG7mXcYl|Ah|8Vpa;L%Vwl6`)7X&`e?p_dB z;e4PSQg{L@9=t7bWmXIk+@vQ&F!y_zKvZ`uQGA3*Laq0ggPXM8e-bW;VoGAjKXB2Y zBr1JdYT~%U{$iI)V2KUpY0jq;Xg;h8VHfGfQ8^s3%LrB zZrK06d1-&o7a|MQ>~vTRL&BCgA68jHX~jPy3NY_Ch)={4d|I-UP=fFRZ-wLpeIqZr z^*9nDEDo{!a|ttcxJ%@@q?wT{9iW}F1IuXy?8#?EpwV%c$wnIMK@M_-L+p|(69s47 zLY(2%xPrKYJ8R(pQd0hjJV?VycP<(6NG7)B#)C)kW+r-=?-^joFa|QW(C-*!B8UpT zf%g-6A21?~frb zMK}|U*OO*N_$;_%@4v{66jxcyaw{lSe1Cty&>R`Mk;Z=j>n(BoXq zU~kzBHlBlOP>03qP^@fE439e(@xypcQJ+k{#^>MW-9SFAkLQAIUM62_UdDzPlAPIFvocm3Waav);S)j55TT{_ zPSS|rUSu}|A-m!m$lkOsdxM&Hdy;q0z0Tp?m(W6scPGKEzn@{@Wo!kkM02e>L15P& zF1!r$J6LrvIvQtvk~pdr9h2#9rQI2HchT-1=rf!G?Fhk&ldGYQs3ZZ|W!pS~9d^d>I3|ZE!ct zOn*~oLRLpJS4!8v%Us7|L^K+kTl47%5BREwi?7t!Yn_oQ!01G;XRPtj@+8LKtVTuu z|35fiVx|5!2L}u|>8c~G0dn*hxy_}^V(PI66l=mz^WEb!}6LM%|nz~(kAS*_CRd4Nqz!*6|brp|(Ph3Crpt2aG z7nPp*Q_9djv)uHC%*n5a<)uCVJz)|PYW!s_In~{#lSSo>GxBag0`)z_s970?rX-?c z^>Pr5Opjd79?OmoJ}2WEoFrWhIFr;r-!o)6Z!Wx#bCpXy&0uQcZs5^KO-ocFr~?&u zpt-dW_gn~jTnwz&p7!?YL6)3@y@8Et+h%Z1V41z1)9cF`>rUr=r<&_eUoaJVD#jXA zsyz+0h5d+Tn`HI$Mp()8t|QDo>ZWVqMFfn&wDd&oIv#hGy-~GACBOqqaAB8%z^_~9 z&>m&?gxN^0*#!q#ZhQQEL67oMuam)F8u6-aH|jZFgs-YZT=3>CEST%{Mo%IV*whU!f3Y%SHtFA&Y1Q0cQm@U^OC=n_hY zQ8E#2>CjoEL!0kh(qT{c+N8tlSGuIbOn4|Aa1utO!&uE|`nwS!{|>Sph6p=3+ReSs z+mQ#)P7wyEr6*$&1oc-eLVi)vCb_to{8A?8w=qI_a`u+H`dH5)CRN8^;^y@*8^>@k z=4c(0h8R5kuTKJGNX(ATLM;(7$&9&>L*}*D7&u9TZFLMA_Wivj6?OFIK*R4Mmm`m& zvheJt>zKf4UCa_8G^7`1^nFi*?>c|y6;mj5(&_oLXDhlxzFVeCLdW+|BEZqXk>vndp)ex@nGyFVApC32EMp#EBgTg#c0BV1%nq3@hh4Uymfm0!A0Fi7dT1=K zuO)76OnHm54oUBU#eihWc;2G2Ab4vUj#c7l)n>>Y9Ig767^jim+~tQ-wyX6b>55L` z>C9#u@R;4`S z@$pl9=(c2EW^r<1ChUYLTwQbxJF^=Olm>gFg9cy&uhPd8ut7pEG*zq-Y;3p(+5owL zTzTmS!umvXE}zs3_eBiDdg9lvkM4ggg%Wuxi`KHwh#@%=kb!tevJ*NN=a>`G`LKTc z;tS$(XJ_;-Fx1Z|kf)kGrT23H0yvBcrozz3dh#yFI$3g>b8N7!C||Q3-u5Vd%$WM# z_R{cy=<0qrQjG^3RTgrfyY;vzldzFa=y~u0R0N`H0{7X#M0}cHd9rKyqUU);A@fZk z@i;a63i9v+IGMeY3s>;W&_)1CZX*SULWporZz)dUqD689w~zTf*SNH-fF0fyVwapz#g6_eQ5ke_3z04PA>E$uEr`Vk^as_tdfj>2XGy^!A z5?Fx?%bww#@Nb=>HZUADN}a%u_v9qvW2^}r0f1dcK6Q6E3fGa1y&q!bs<73`4W6HPFLY*y=}6Y$sAgU^F`}fc_}U=IR3Qv-`_NF!W@qyV^>X z_=t$Q6CE0v05`JkI!Bx8nV<_3xZcGT zH@Hx4K!-}!VA*CsqIMI(dGlDGyky+dYLtq!Q$->e3v=E8EUy;UXO?!R=A*bd>?zwS`JSo03UBBxZD09bKz;`9$Us zeTF;aa(-x*<+ouqzj8dtGpaA4BsBa6^kC0$VT3$ zIuH8KQ_6D(UVdYHxvGCTs^^+pSIXSVJmlQEjuo|;%elW#wf%mq`Bj$;U(5U&F4#iP zuaH`Ww#ArV7nFcqTOg(Tg&+MMs)aXT3BbL=!PqgDX@-{p&`?)Tl*)}=h%`W)EOY=- zbc!0tja7v7M&5b5!L2$XO?6=eEDP(O!V%4ozJyJ!?ImQ$k}2EZwolltyHz6yOTN#X zm>+DN>YkO>$NBJ0vQGi7nRWpscW6=S8V*Cq3%(kPEq$|F#gCKW%29o!#jSt6gC$=n zo2=85Z4tgwh7c=z{h>1Xa@hhXCjMRK#RnUiz*AaEG9i6U`dzRfJZ%=NvD=uano}Q! z9!#AmaYIoT(wAM52UEu~FbKJ`(^GmDKF-SL2y_@K4YyP^Ienq$WXdlCBu-zot7IY)*TvJ$c*g^iZYq4d4z@+zEKH|sU9*;Rvrx-% z<(&Ffzm3_$eydWM9oYbj4H(jtAz+jxllYBGPw7;C0tfy#aAA=Ci}`69_)mXa`%Czp z82CN72*da~@LL~rUnCq@r9PF3S*^Zy-OEBzixBJ!weWu`V<=T41bzX*@9HlNw<$Fg z9x)V7oW@SmH@iUL9tp0rv);z6U=y;&RVM2-ChLvUnN=?PRH#1xp(pZAJzL)_ir|U# zo6Xmn9ozFVr>0wX=^oue*^U0Fe$rLkUAzSlqquh^u~Yw7MDW)(j@vHPq*G;R3fo#O zEjC3DHbws$+0EUf3du9cdOgY!bI4p`$eeBBTSSsMHj2!CiZ(R#G0hnMdvVIedXb{8 zA@!9>vr&f4^nFn)^i+(_cuf*Jo$-{&&e}Sos=Y4$acPCezXZC(x{W>kH$4_TK>;6H z{s@fE^$VEdeiM@|w7aDap!n;}k#C6*ehIQ2+C-eR`V9;jPEu?cqWO9TK8$5?<@R4S z{oiv4TM0GQ43m7%O&n>PLBB)_P_Y?wm6KzL$#MT+8HUTP(R{@af7(f!W0IcSD}wl_ zDB^?Rx4Pg7L#2m9<QIXIW7#^K2ZLO{) z_sevu4Di->qXFfV`HWAfi%@^6Bu#xXJx_){UW+zgq)%z1Kl z216F4HVV&#W|H+j#soISW$5pn1%Wjs`w~4RJg%9303ZA;JUW<}9mrS`j{tt|^VnR^ zf9hxU&kNMgz<&M_B^&D$CSp;OnLVLV1}h(a25hF+!GwsoIEJs=mh4X))-L@()~*WD zyTqagzae;uLvS-L1-!o-HJjh)5)utBh9^6)GktA#$#;7K>q?fv4iKMN5Qx7lH}n0w zwikrrPw>`xf9s6wz$fXeB+Y7kLlkK)MVd=;GgsZUouiuU3&nf9b#{i&2HfyM0V}k~ z9;_mmmD=A?PX2?yQF|{TD@3PJ7A!&99Hb=#NL0O$K`%$j!wvA^M9Y1=afj!)0%zgN zhE{^7T<%9)?oIdrq?KlbEBswo_}lnGp_S%MxLpglSom`Ej=zR4ai+t@m-qd|mJ0Ap zQ}{Ng@M%d1v^U$MD^yoZM`Z-x+b;mhAK zsUz^^5tJmgiv4aZIuc)=zFmv3FGVA`@nt1LFt9fTv|fDxj7`TMc3 z!z`s7Z%EZM@eP4GY%tmAHF|0)&~GUHjq*qRo?-zjMI+P(YL0HBJEwybkI&P%Fx4B| zbeG;QRAJwBSK*ANh>TH%>msXg604AR&?<~?t*daE9v}ZrQ2%(OCm*G2b&PAn01a^< z0vi_rQ}|W~U!7wr`JKo~w@P1)5QCKpUqpWaT0Mx5S#im*4ja*)e2vdctjqx%~Y7XA%hP**P zSD;?%7>3n44GJ#Qv0C)SL_g;ui3Mu*|EOC!Ka<(qUG+Re4EkYTPli7V`J_J^fqd@M z$mdlv zpzg?EL6WCj-$;MN<@OtQxWX0K312(6GWuNZD_riruJnCe?gW#@I=@HTK4kE;Eq@K~ zoX9Wb0oVijw|R6ETV(J~93#M^6CS7?@0^6qKgyfs{4^hC_`&RHqkv(Umip^Zc&Ak0 z#Xq*EttXi%yfa|2-Nr;E`s;A;&NSkMe*^CveLmUhu<%Y*3ntZgr_Unrf=TJW=|1h> zxy`{l4+@7>spm|d+5QLt_@D&a05q~w~dd;F8aw4eaA9;CbOGo zL_3@8XPfLTz}hy(DLV}fi~%tAP}Vy{-@yw|YLm$S+Az*J&B@_y_Iw`+DBeIO3sCeI zKmq1#^952-kv}3N-AZx{LJXcreHs-7o@fX22)lUGj}D&5F$B6e$$xuFCokw6(LLw0 z2&X00n7ryFgt_s=(GHb2go@ya(yL5I5l>vag`S#tVl^cu$QwMdZzISr6e(I;NBwy& za#)iA`agy>*3h_iP{84z~yC-7di5m>b;|)m%Pt=Jb zxwDn7EA=OBBQdNf=Sy>H!4nNlWK2BqYcmp$QZ^ocZf$tNvSTz8m7awo0{^BRqbYV$ z{;B@Hn#jV^-+A!-@AdbImZ*n~;+eO}Dzs6&gUP5;rSqfum&&~T-AJgWAdRJl4{UK% za;0+IN4ngfxYB%P!o!1H30Aq><*vkcBm5Bdig49m)8E%^z-%=7`;l+hYNNli7y&W7 z5@NWv{jlrj>;15J956hT{yqk;#T% zF(lq*7zfqO4i(NQ8xUw}$!a5pq;~zZ{2U!SgOd>oUiP43?@B!(NwpR|nI)%HQG6Yq z)u1_~p-YSYm-Z9)uGEJ{D3q}YHTKRO}m@ot}?}4Cp9(2eM7w&qqx+l;u;;axNA@xyZ)hKcD=KmwDD^_m|sx3ApXY4 zZeAk6PA9!#l2s0mB=fu>^RS73d~`%#7e|p9V3Nh@f%hi@2H$h$`SH`fKg`{Ihgp>quvK{P{q}mV!Rg6u$!M47*ZYp^l9n3ANe&mF}!rqUzkr z`*DQ0_oXi8W&ps>l{mUZu(R@q9TpBc#YD{o9${3r6II7VJ%NLzjLO+$=h{436Wo8b zj#~7+9rb~U`reea4Fs(@@Z*=d#=FyO95&q~|1~#ah(1RO_e@#=zh&WTX4?IhL**Jn z<@M|cDi23d8AB>qG!Z5KWa=`=p^{{%sGJBY`B79dT~uB-RL*v&ybo(OJNwK?Ds`i% z{L<8!ad#LhRR}ZqwA4_!A+lcZF1b!g=11^?+re*UU&L^PSU0(>4B_> zhW3sk-UWV(5l0&;?HnrK(U_?B2IpT+LJ$#ziUYr)r=~=zW5^pc+Z+_tPe$#;7WXYv z^t_qDA&ZS>>m!L(#|`UrOQ#A^_k_5gApp`uvl#m~kx<=*uqZ_9c{l>mP6ZZ3>IV$j zY(v&Tv@IjaUPrPgODba}gCdn3LF;6Py*=3dbhfM(V4GngV*=ZgB{B+ldHmn9Wi_@3 z``i12Z-1ftX4Kj2iE32}rRY*W{Uq3ttli-c4+m|@uP{OwHs<&c$@eXLjnn3Fk~ znHP#748x}P2T#CGUJX26bRO{HxkKM+no;(lcRv4X_;T;(WGihSx^XRs#o)^g zjKJ6ofFh`EKWyJ@Z6A96i$mi}Yd_2j^<%@qTFzVj5BI~osIqAz&c{+&9gcnIU)vA+ z@no{rVcCb4NK%b#vtI$9It~!Gm z-N^Po3<0BDImD=6Fe&|);cY!?>b781OIr>W4y#fnCQon}n`9%`!4j?fL}>351EviHM&#Zf^T8}?GFqqcQ`+H6}!W@#^j3ak6^>>V z+8neB!%Y=h>hZDm!!l92RzZ3{YzG9IWxjIlhcz*k{6r+ZTa7J2h`|T9VCxf;N{zw; zc^vY3kZabMm8{VnJ<&0fe5RyA9kCe<1=(VgV?b2{RGM? zhimrE0+Cb_`G5Oihdvi{?K9}DyCERdcTLC~Q9~TDA9fznYMWagGFaGW_16xxDR;U5 zW8C3AuE5dXIEn9dxktI&Q(WmMx!f0A{Y^#Fufy0fFn-pyqH zW^hDy(NB)(+y6YWH)D3QA9kt9-q>V66|8MzoHy&DfiVDvqO5m_&LYvzME=*d&C{eI zIlPU+(Hu9Rcm|m)K;i6%RUj3Wm>_TP z#E(3_Gh3u+Z5{QK2RW?C5F1atk0chJcp4PhRo4hncUR?_qOJX~*6>H+iBDjxtcfRl zhGbns(!mou8|&6sB)_8{bscN4PmKMr)1*1I;E6gWGA5qbbS#NSDVzVdANJSI^}6@N z9)6sx!u_yWn2f5CbbeI-%6?dXBvgK+vGjNP7miBa>vCtf+;v^g9)P;pA&Tbc`;(g&2_$==g)2P3M&eQbdK`M^{@rZ8#u`IFedPnzDP15 zz1wANrakebX<~e;Iu=!-_8v=eA?J3OToD^;T@4$+O)T6QLx8>)Cdr+9VNyxlBQLIT zDXdJ>t)ude(Q{uL2uo9EFv7ALiih_GPM1{thGCm$p8!|AQBFBoQ(a5zaUF~WTi3zn zK>oPY_4Co!!MYmhBYCWiw=!0PCBJYq>KCc5hc45y@?5Ys%@camDLs=J0={_DoUJ$) zJW2nIo3w5j1Ae7HsgL%TeWv|!y|w=iFg)Xj8vicjx77Pn!hlt3Zjvrz(ar1v+nn(f zf^j{p|5GxCGNe=}_aoTS@cj&hy9|YWw?t6rDZv^bFl#4f1)HEB+FW3=UTm^n)}L81 z9@vM=k&U6rsk-mynhn${bxah!-$hU?(qmJjpWD}SD*6!)+ps%VF$cQi6RD^!tvl5< zG-PyXPf1#*_MwB8wmQ)%?JU!_o~E?#U8Sw7rEM*vN<00arS(B+Y{wHfaG0GZYazF$@B<8{+1Jd{)bc_H45oSR%iE7ShuU0bNbV9r?v|OG7=li= zNPZ?M@I6yn!EgiFTn#1wZ~piQFBpBU>>t%Z|*F$gd<)t9tv& zlE?p;J{d(s5bJ)~U5j*Qw3B*Pt6WSQ*X%mmR3Aj3?zgMP@Q2U))7d{d$>jfoiUgCq z6tmN^CuKnBxfyId(u9X%^NsJAnf;?Kd!2LDcwFOOx?gtfo_~HWi=PX#&t;8*=U+IN zmFTu3sRgk{OdEvGR7iz!jQ5h41H}|V12)6L%Z#WT1 zHFAWZ@WAyE6t+^3+uC)%`da+e>KCa@;SdXZ&NpNhn)q_S9}9a{-c5H5{TD@h4E?qC z;nMxvr5pC@Zt(Af+O!Z+e^YvUQ+gh7i&grUJHVtdN^clddYyxoo?}Y?T^}j(;{)$N zL@g3fu!D%Ut3{B7+QgL>zLY9UpMGQq&lEA~*3%Co#DIs^*cwGQD_=`J#>aAuF`-GI zD-JP|KyN2`f=S*hh3&ML7niaK*I=CwzfswEbh=8N=1?f7G_uyR_aE1;E^ zG+KGYkn|do&I<3MD3a$$irUdi|3AQ5wV{=K6B!e&G?&OIh34^NR`R$@6k2iJ3tKiv zcgKTAuv4qm@P|V#ymFh#?=$&7!@Rff$^;4<7Z;>4^V&$flJ)!l z0Tg1XRLC<8@t@~T<+zr^gBVvc~2_x zJ*6|={wsJSNuBsMX1u{86L6jatU^OtvWjB_cyU6v+VRLq6Eq%KjmTBgnIJ>c9Lb2XgY+CYo;5z8Hd4GF5{nF$YhV8ei=4QJ{BtNQ^2=_d z3bnZhuhOx0rEgLUA08B$0BPoeBC{YkBhILEzSl04?_t4_P$cgSEsPF8UPnTapBMs` z@S9^Czf@=_QsmQWYC3q-f+EifFIA~`OrE7zvPrgXdRBt9NJGQ>K7jf55W*}ice}}c zkI8-n6s;?J-^lE#%zh=ao1Lv&O!l@Wdk&ab&Vn3J>mi0?0f3}PlAi=X@(+>cmRTek z#$CE=JK$7{B$VY=`jyCJDg9hXey$5~{uu{xsB~uuNw>y(93e*Uw;RA}R;q4Ib%%b8 z4z_xvry(%FN#4LD@0T3WIhV5tBk@u4QEbTt2y^THGaV|GFo?6z(@(-L^*%UI3>BxH zN3u0l|7MCr&^M~TA&(fX6){;`Pc{0@QT+eeL_d>4!M?nx8(XDo2p4C*rRMQKPOszw- z>VWRIbnpAi9CiAeafe5iJAoTq30`oypL4lKyWDTWU7NmLibF|c97^YokyLv9k6J3vEQ-6sQ@Y1Pe7cnGEd(s? zi(zy2=^7Av*oQvt`X#XBNTs_5R&z?l2ZYz%w$@^XfG?78LxX20uUTr=|9RRU59Vb2 zP~2)@{4V${C48!(+S<@)=VcRZC44G^VaMNmpNx^Q2kcTuBG}S8KM0Ffsh=UiS;{?7 z{Vob$OR%*v*`+?9paNlp(urC1j!?PmMb%U-!69<#u(c`>$yROu4 z9oTedk0#%g+}@PDBC^@%L>1D+Bs*Woc>LEu0a-xeWUKuY?`Z!%S0f(Uz)`Q+hzd#T zbjo~D4VG?SUbCne0R;QOC z#J#^#MI$)${O;2L(n4@Y^j7l3bxz=^Op;@nEe$VIAW(iW=J})r8J6U zp`@rCw#?niO4R~e9ygIOVaq)dSp&8_78ADE_j8UjHUDNOn_jIpK^D2B!U_p?cw`>@ z;WXMSjA(dE4joph=_dd4xe@vOQTdCQ|2AMG3olJ1D#3d=y!Za^;ibo6UU1{3zw>_I zD(unNcxe$lG4ax0d%rKjUZHx#8nFn2#IwW5S5UZ%DOzgSF1Wuk21(S@h_*1(z=aMx z8sc&fcDen=9Zp*0B+hgtxW(n};d1-nt_?p;ocY)A)4-Wv1B0Jd=z|m5UeSdS;KlXO zleO)i+%{a}r$)~n5=o}oIUH*Lq=i71e~h1AAekuq^v>NJOPFLZoaa+d9TGoz z|M~t&zb)jOL*b{(B$eQ&Wkq18)z5H(9v*)B6avkKpGu?mPlizf*m5~~;k{xrVk7a> z#HY0^y+T;tjh`}%eqEEP)!rFkM)FBnTkT)`u7j6;5{9Z$@g`6G%h)6vFZ~34fc=yC zBV<9|8CD@XT`_(j)Y)(6=jQ@8iCkuMaFr~qs&CDZlDO>~mCG08(mMReW}7GXn={pv>eEv-vE+S#G- z3k~Qf@Ph=?XZC)^Ua^(bL&FTBGL7dn^) ze-t{n96Nh1bYS)~mf|cTTUBgGI_RK(6v=BOMeXR|vG3W8TF}7=6B!d7+#r!P(82DQ z=)kp~@$-|q?u)`~Jl+RuA2EtrobOAap8mECjTgtzf|U-UOG&;p0sKXV3#PO zS@b)s?vmY|cy&p3D|7<_x z%0ZY8Lm)2Hm*}*bm_pvg6LWp2{aHvW`sz}ox9~;$JO?t=Gw$$(uE1?`odoC2cigAD z+{e4zAG^~34m!2ri_38I^ziL7$*SHHU@wC&T1{a~%=wHRQxO4PE{5LVedmc><=Q7n z&HKN15MSW^Ul6I~{?Alq;{oEc#6W}hf1zuLSIQV+A0U2SAIUTaG;a8J3^bp`FwpcE zV%i9R@e#GfApyqlziyz}5_Lc$zDmzc=|do%8PX}{)R=f^#`*SJrV@bB=XUbn9kjG*-{`UV zv=#f_u@E&iC7*0celD_~?Ck{hCRZr$^rZ zUl-bY+mH&FG>>FDJ%9GcvC&?yDEbBT+bS=*=O6xBH=?67!s9<(&|aIXP_TpccBw=V z(P*!ExH+a0^&sp_=bQS4zhfD0gtHDI2Iq}}?V7M_a(&I}ab#`cJo%tom3q}ldX-5! z>(Bk5XLI-iB=2ITdz>7nn;aJ(En{h$mwL)^rYd!%lk`_?NU|Ou?u#JaB8vE_@EZUr zk102>{Ah2sp}KcNbbGfj#71W=dd>iF9=E1LEVAr61F2N3; zuYf;1({(=OeVkjQsC?DrZ;k0@olj8^2<{P|z|5P0%3SAZvw@uceLUs`d~)Nl4S(Z& z$~}8r_MY3}iD~a?XPr-J^e>%HS<(mk@LNo1l^<(BBg{dQkXG>6>qu|mu@7H!AlCaX z_j4}y;x}}f@SfM5#4npbo|~QSau0K5EJe5rkL9J8>Cap8iQ@EKg2qBirjq6Gp>%KX zT6_i2zSV_q{%Yyd$`=}(nuHHSC*9s}*f4&%GtfL0-s6Y$xwW5s2$q7SA~*E}NS9mi z5mdybA%sD#;?$iGW4_QFf&m)`6yj@lvf=95tJ$rNqEx_SO7UfG(ceA6%mMtk=?jEM zf`D@$(tNy$YDH|1{C*f1`%|N52H`RS^vq?}2F&!3&M?QsFFZeD;!KxdJ#ip&dJV*= zPC%Gt0(i<~FErUlVcz*dsH!>3P=6&ALpNNZz@-WVR;eqH5?eaQgOW3;cBuI(_pXO90zT_M zN``#N5RA{AXKToF&1?tFKaG<&Of%1K-smV!o)E{efeUi9G zE}xuAk?>6tt|y&6-#z|K8l`Y`Z@gJ>j?79d7ejseFQfH6BYz^cmqF| z?7^p{=Aqp5120E>3F_q<-+_8rzAF`vPe8>3A!a9r-_jXTj~hy#qcGd4CP@ zh$x@>=@JW#cp<o8q;!p~fcVAE6UNvuTaD1olII_HecGilXGcs9=+7 zbuj{X5@assH z@!ir~g05Q4(AdRABiG2>om^PDMN_5`lG3#rvb;e>I6wp190^Ikd=u591Q?Cx>%B@Tz!l|u;51h z7ahji^#Wcs@SKkM^_TGlrwj4Lxq7mYpOU-_`VHxG^Wc6ReDtO)xUvI|fWVa|FoS?i zZNkv`AoP>*i~)~)fQ^xnV5K*P3-o%&<%jM*f~x=ml`hQL0~zDgJzPF4z})2@UN}Iw zFLQ_IzTe}~iC`dn7o7t>hkO{BjGrF%+|Qd&R*%=eUhl5nkHoP~gIkcM5Au-cjYvmJ z>R437fi#01NOS5xf;3+sH$jUHX>NxM;tS@RA@#(XqapbYmG?a$>_Ys02)0TkMK?~`fJ!?r@}Eeh>;33pIT*o9)yU|(n<7b+Z< zNE9<0_}qnJ{$L{KoY?`@NhZ6XnCPm^ScR%YqL@MBv|2k`)TeV{UZaH6LE7kP~#-`}Z8<@({iTl-3llnS++Q?rARY$V#LCnGvv{623 zlAQ^OB8!^c>e|aFJlrs*ND|oxj%R>|>ccP%WujaD;z~yfj5L+MK$5$goMMPl46r6i zh9EGCSq73n>Zl%|#)6VKr{r$43#hb}$S7sz@qfc{8n-+OsNj8DBQGD8Q;|6T^0DsH z)U#ajvP$_S*y+n6_`^$F_+pQZFZi8FrSX8LB!s5?1x)ZZjVu->cmW=K&wLr^ZNS$s z@hQwGOsolT<<# z#lYx9^~cZRfSAfjR5#HRnwQKRA^i#aKu*#xo;&iAJq>e`;V4M+H0+cHNB0a*!>$={ z^zwQd_VmKhuZO2$-yU$>KETs(&;U4!iaia76~nQ30!Gr)a3O!-^%LQF8kX<}-VmAG z(=f;%c&987?bu+bb z$#V3=`kuYYExa!JwVTyrkl14)O-X5d9SBw=)m3^7UHATfLCjBIXk-e2AmlLm&Reo& zPhh<-6lCW$+vBawNkSdsLKEl*jmn&4`n{DUNeJNI(s12hytDCSQ03KBDysooQdrM@ zkRl)pWC+R;dsSZILkRdpW`{~n!hK03HZR`TLOzy_YK!ViiNLKe3kGVV$f9xv0}42Z zyB>O}6){S=I)8=3r1w2-@s}~b5nZYJAApyK<27#fhSh3z20JBYyPN&4J4v^{XSwV3 zCJSH7eKcR_j->2vH26t*CEH-PaoPAXxRh_{t?a0KqazIk_a=G$2Rx;iV{z%bRQmR~ zxZF_hIt6_<5i4AP<*6^Q5g(8bd@pd`@r`mx--PqaSFHWl$lpe}W(fH19==4Y<(l&)aH z%#HZ&5**-6e*Gud3DL)6VkI(vDK4Kv{SmDJF`z4vM8+AR)E%}?NfDhAzf6x?hCOZ` z{|eTiWVu&3Jo|?1UfDNh-&Ahw(||FFZ07+rutGNo1yyQ|L{R7r{K$7>zoE_-HO1S}xT<}bWj;?%8Jg4@oxzFSc`t4$&cR4h* z6#E!u0k=4}t3hzmI`$kjXwu`6y>X!MB-J^wtfcISa`XM>{J=VU zzu?cVFvdXAgW88!KnN zFT+WCMX2>zbhJ|Uke4DBHW|Lm4W9c3$$afnqY7XMW`=?Tl2Sje2;4A!hLgrZBaqp`TMl^wRfC z3{LODD)i>G=z)+pa3KYE7jI^jw!5O{SnCX4h?XK8Ttii6z0;H>kylD2R;Vte)tgFd z+;UD(%PyjoRw+wC6;^rt_aY6rIE#4h+|b#QeZ| zTgap4b@$XJi8PGQjQp*DXa zBl4>~l(cHq0Y>4%_d2T%)52}(am>*#W6y7xz{!6WWT}xb)oS#t1-7>?wEFg$N2B`_rgm$EmK@QC zTwy>!ls+wU=K^nFwfg!q_FpALS7BH6&=;7&p+P|M=W)}N_;ic(Z>6gH4jU2=gS$cX z4@igXsZ%r<^0X1ca}pgLkam25x|M<23OF!!hwbS=cY4tBM@rz#5M^8F9x84aa~GJ%Vg`6i%D`$ASCyryV;O=!x~VYuNB2bSj8o^!swiQ}5|o7S zH%&OUbV*c*`2w$|zD&0e4c0}n8So}E2<`I)=hoc;w}1(p)v(k$*B1a2*W_?6^ya`k z3l8Q4hT0yLngx{D3eZy5i<71c=XDAjmIiVtPLLo{GRVsyWa)x(z>`OTI60}<7r=^1 zKfmj&m%O1;yT(cG#nT#@ZkU?h5I{EY1-H$U)!tvV6v(nI$k1z0&7aI6x5z0KBOOq6 zguf%<2@kx7P75y5MOnShBNPoe)-ote9n`58l_ki)SqW8FbiHeRLcQ5#zUU{tN2B#- z9Ec z<01?yM?)fH$do8o-=O=f%HCos*qy?`7&#It8A>ia4l=?L7sHzdkMxEbzrPYZId+RYi7x7!a?LRSl!Lj7VP=o6c%2l{} z0McOVau>bjOy7vlw0!|GdxrN=UkdGhR!;$3zFe&t#rvK0=tIydlZz4U8Au9U8xYqS!jL^swN{7CRPF zGB((WADCn-OD3W>`Pbi5UFHk+!@SQUphk_P=%5%@OncM z3*S`u)I4J9P{|r}Plf!84x_px_rQ)LRLHdaQxn1>+uTsqnhhfYmb_mPe#&-J$iHO! zR)o{xo~Z3+GC!`3rnD`2x=yHoM$mv&+F|b0!FF!)Ch= z%4P$}8z`|Rn>E-xFE*QH*TQC}06V?wqVSTw1c6$c4ySNipgq^Tq+zA`q!_#micfz`3C#)-X!g>`W7k9#5 zAZ+zCe2zcxzBX07v-tz>yqCp0hd=NxCg{TU6@TEJvQoU0_yg}#>%}{bKk&Yw#QPk7 z;C*e6cxUqm-g${=u&3c1{-_>rp;t;GmVVZJI%&K!pDuK{3taBc?~h)eMZOYNH0*7O zh{MyxI!qskmGp8Tc5*5^`kD-isumpH$y?~RnE zu3>8H!FBNv=RYT@uf5ZbxD#4QO1t0c(~GpkjS{<6?kZdppwOU%=~r z&Y6=fY8@F6HIO{kHzDl$HDk$<$4-6~o~Tlzs4A6ojhq_wLz zjP##oSgjqo;RRiKvXt)et9a)au;0|+22+Du>N+*p^Ek(=W(`_J)?g=8jXLF^HMr5# zpotzG|7om2UGiI~&B>+)U(M!iv2Y54X%7jtInqQdMFgucf$7l^WBH4Yn1ygIyxU>i zxnYuz^S78ys?QgC$hVgADVdIcwx?#kJ`SZLNr?+u@ZVRfNKH>{0!mLq*ekrD zMt*cZ?kvoHMgMtsZ}fihBM@GEe&91yobozReT24CD#Me-Rd8bZuI!3Dg3Zx&@?oW@ zn;-H4?m)hE;Xg@g+w&Y`LRG`Y4EEA;A!Y|#C^UM`?!fC{oVP050+sazpO;BekoiYp zBi5XmXjGyY`{r3Y-x;oazpZ2=jRXR3QHs?p^ciH%1gkDn zC(lC95~+f7^KpEU9C{SPOmDX}VZXc_o14F8I5@~8Pe5{2DQSVZSlmgd1bVWaeL1k5 zy0)QnIk27QzLhvGh0@nz$Bv~3B)3~g4v#EjCK9T?l4_ArCp?c}sem`7G3dJ)Gg;+D zsbeLeRNq&(Qcbi{-6N@L`9@nWiPU=Ew%K_6e*gwx(}(aN%KmH}=>55eZp(IW^8KP?B-v*Ii|j~Y6KhRz?5h1R{nH$^(xM9v@)ABn7!%Ytk+ z1do1SvmI{w(T>UYqLQP&$FTtE{@y{iEEw#~e!iT`-}5)l-Z84{TP_oeW#^sfSp2bv$ID3$IQ{;JlwR6|LuqsV%B0g@>grYN)0W zEIAUd=62K4Yd>UnBwpRd5HLt-wT2xJfG6oM+^PNNgTF16KT|lXN-Z#X%6^TIfior8 z7GF2FM5{vxv#`ftlYNBAUT1ei_M0QKpT+E*ncX~q-PdHl#ANRPmbTRH7dR&z3n3mG zNpto2pt;XzkqsEWnku&4G)Gm|GbOG>4j{tQpb{s7`*z`cB=y=`LZ~Jld;;NaJeb*l zbFflf^`Y+4Zs<~j;!ZPB^G($A=zSAa*F;SNqToW}G(=fFd8VmBOO~YZ;AeQBfQ2;2 z&3xA)paJXX;K7eE)zx0eI*ZcXriniw%uss3P}&$tsT?U>luAkI4N}4qmUHrWQ>SST zr7S~f>N^p28WBn95>o0%N(OQ~dX?_qs~k$Zj^X6dc<_B38~@vQa54JhFX6#&p5%-< zG#-q9!tTI)S7lE{WeQ?(QZ5A8g2Xxx2dDSGn9{MmThCgWGk&+nmpgw7*;DyJ39q z_pI#i+&?42_|ARp6!-2$u|49lUO={n0?0nC0_A{&1${nmmf@k~{m=sc# zS7t?4B@3DHy>+XDYc$KQ|J=Yt%7!ZYyq zbo|{*;qT=5iynu+E&L^W5{ep|LVLsbFNg2Lb?imICFivA3GoraG2Do_VL}*z%4# zZ#^B$a~-8?i$;R#T9dDOxwMrhL=e*lF|AF^=Q@UGAQ00LF>?&Hg*qll$FxAqCnjbl zV)zb3yl(bICinpa?^=)J`WuexS&sXHxKZPOketAg=v;LB&Hb#A5JMD0yAB^%*q4Lj z?<)!W4!EXY-@-fY@@959%HzKhVGCebj>BD|iT@vaUmhQ2b-h1<1cHJS6%;G#hyjDL zB-VwnW=KNb=ztMHu!s=CKvF^ylNlBf2xg`-9Y?96)@rS7)!N0nR4Hzl5J=Eki@2dw zL0ovpu(?58Aiw81_kG`aXELDuw!i<3ADQ>P@4e@qbMCq4oO|vjP{w&KA9t04;u|U{ zlf8?5R|$l(1p?ko2x-n>FG9ee4-m9xP}KV5->?qI6R@QZo+*zN?dA+_#iG!4boZuX zr61xh+B4o-t2~e!g}BK&I@;5l*PW<9#TIYa_B$1a4jOA6R_@V}U&92mi$nf;6pEWd z+lH^4LNf-!X5{tc;fy9M$Lc`tF~%CR#VBYUW+MBdxbs9G`3ME+UKPv>VUg7iE+ieU zUpXF45WzA$Nx?vW1EPuu&~_}KWAiy>c(pRgvw^?^t-R#<^-7V+q}ZKX>t8t(1B#XM@N05BNlp`;dvuZ3B>=-H7H-4RF~Je1z7FZ8x7)|GjQ zfp2g+ll#;|`w-*xga&8oyXYEoh4N>sw`^Vrtk)J^C`>(~(`#T%FH)WK!TYm+=LhmN% zQP6w5jo#Ub@O}{wZ;}n(&kT6WO?XojyvF<(ekUcubH~H$VuN?F0dJ@Y?;}_N;P>sQ z7`zQwKp)q>pKgt#_lY}V{QDSf!$8%0Y$M8xU%?w-!>=|G-fsa<4f6NtUK_Bx4Pd`e zzG~bK<=Q&S~Z>bRzwX)kwy+70l+Kd%UMVPdKXYyr*X{;DoZ<)-cmW z-TK9d`^cR@T<>_|-e3`=>NKwBXDt;F7$$dX2qvU#hAaFB3wNe z%lXY-Q<+%tJ+H>NFw<7+?PxBtG|XlrOTUI0M_{7gdRl~ruev(}4$L)(eV`K5Ufao8 zuj~OC8QA`brz}1D56}vj4C4~t-pET{y!;FBBy!QcZlbhbKjUFw7;0ffTl0vBTC_|B z-AKIzifR}o;1mOQiv?~*!*blS!Fh^0hZ-R@XP`=E*wSBL7;tqZZ>cH0EON=Q*7)Fe9gG5S6>;CN?ZnvHH6w2M45P;-f;%U$Kad z)LagN4Qf*D)O4a^Jb2leigu`C5?c?n5~$eCPoe*sidTM?jEcUBircaj6`_YLD#nbp zwMi!`8k16S+|jA{3SP?pfQs~_RP6ezw8fTl6&1}7T2w3^b1W*Zhb8OW7Cnzng&gei z-?zoMV6wLOi=yHt(G~mk!w*ZY~-?o!PRe|fBsmP{3n7m({#ZUizTdZwJM#UCI#UU|DIG^tKR$B}_CKXv= zZD%UR(dkM~MGimx_f#CXF&P!tKf-vzetpvKEcEA%JeDX80#7@m{{fX!a`d-~zWRR3 z3EEW_HZ-yf7buJb(%7Bb@5Duuxl1?8;lD;Z1Ur&i?{N6sw9k6_TJ~(X(NMWi%q4me z8wSE79_ok;5Ci)9uR0t4&S420E_oAAASEbN`+I@E`!TJtF&b zV%8&cuR1~Av_;qgHxQ#4Gp=G;nI!q{iN#fq39kcD-R}eM#P6A}6{E551Mlr`zhAyK zSnclv@34g*CGBClAJRP5*eAI62;w0J;lSa0dwZwvAML^SZ@yIDv*gU_xUtiwHhd4` zyTIip>vNbg2q^}BtdHqSKS6pEwg4rhzZOOM)t%GNXZoj~cgo+OBRynGhs9?d`lb8u z;d79p#=AJ*;4HPz^;PM`@9B4ot6*NQK?jD%hqk1iivFWIN%XxK|6}E^Gs<86-Q{=0 z+9g&VCrm?&yr-Y`-Q}AOS@g!r=NRSR7V~;c{O`8fo98$SC)K^FQ{$JJ~T?I{YEcm>O&KlY?Y{F0i>>iZ5Qq&Rv zcrVlFu?!`gI0)g)$GDfw3<;R!Ao%g+93VBRBUxhqaT{Jxzz)pyKbdHVizKH<48vq$pjsAUK5{`5NxW*2!73bQ< zVYv1@g&~J#(YeV0!m)}cIo}R&Apl0NhDdd4noi}8x0f5ka<$3Ip}P3`Uh8k;NVh}+ zzJzQrs>JG|5AIEZ2uX{RtsCtCpMqtMLX&qUpi{X^?d6uST)$-Xbt2#-d$~fCi)(=k z4FV|2(GT~0A4HnYMlREf`2vR@N8d`;sXBFzkiFb-)6T$Uj4ef3h`?>Y^+y zRMa;IbI(PioF^8gH_LuCIcoTIa~~v54y(X+Oxspv1liN>K@F`%obrJagdi{g17f&a z2vc9{2w%-A6d^`kgas6>sAy?lPk4}Q{4AD@pCi>lGWqy4-^Goe?r>^mC?5w^%njv_ zV)Vzh3$zH+t$kHo9Wx&|$6&8-bK4oKv2?}Q|9L$IW1)O(1H-v2sfZR4EKV)hr!QH? zVH!{jFYVj5Mt^A`rUNX0LKY=N(*9YO=5SB;MCSG7@fliVAy95qd!%D*3XeZv@)1;q z$GgbcP|pPH^Kivqkmku5KYBp8B6eA;j)*@64R-!L2J!ZkwR|NTw8|e4hK-vQdNH(aJu@2Dqmkd61>Dt)7&9x*u)E z6Z7_Bv>JAV3VXU6j&%56YG^;+8T{up3SjPQH*9o=`k`I1VZfS<@h2R4yxpf1Tl8(< zq2_1ZQ{}uanF5njQ@}u6>(PmV)v#||niniR&{14=Do^q|gkyp9hXK+Z9v0lY;-qK> zx;Oo{L7Utu8-sh7&nzzc!VO}yvNv*G^rRfrw=bq#HU}G5{98XusBwdwhHpB2mm|s> zV0SMJotr?zKnVLZ+ayvX@6f6o! zyJQYXLztcCsAWn6a3|s+NC;oO4?ZqRn$;2saPl6{2NGC9Uwu#$) zWr_RuWSg~tpB6gA1Jh<9wrOjCK;|?gK#F=Ah~7O9DkQgz8M-Hk;lVeH#>$~L z(|E8@$*MwpoPn+AP&0^06O)*DU4|(>BCCaTvw=h(!41ceH4Ka_@e_wa;or+E{5%HXa|*7 zgGoluZpj}F~(2=Ltc(Kaa?uS|%lGT@Ol?{`!gX2G zdBA`4<7$~=Eg)NV=rk|3jQ+Q#H^;#zVEuMx3hh{rKJStarfC(N9<*obmNPHY@&KgH0F*!3NeAT~m?359?^ZFO8LB zH8x4bp)wHD!XzlD-SOO49GRTi6TVl^4AANvgh>tE4|4&rK&vU-%3}h?Zd7B5mVP>M z^ZnGot@nK3*2#Xr==L_w-4uSAM;Npk=P^{d;t)0uW0(tLNz09s7&I}+7ktM_3|9a( zh_X6~!Hfs&^}U+xJcc@mwwCNXhELc%#2k-oyGtKM$%&~q!yXQgvv=093=Ml`#StWv2sj4Rc3klbeSdyWIYtQw zdo^sFWwG3_dt>w(=y?E0MJxF?Mo$3i^+*-uG!b9BzJ0?Gkxq!};}AoEO}3;oTZ`1u zG7s1LN>>0{kX!fD6q1}5wX!Lg%iD>qU>a!Bzl0RvL@E7UXlB^MeAvTp(c#ZsaG;|g z*XwZJT3?B$kXQOVDN9w9QJ7+s>8~s>^$iMI{Vf^(okjdc#9`v`M^_(>#D?}R&cGV7 z*CeQj14D2Qvcla)rXsH2nCoY_P(M!$hjk7Td5*R49$a(5W0Xo9`du7f!G7e$kj6no z&cHY}43ubzM9x#@qbCkSl73UA!N#RP#qjL3&>PVPplFv4bG?ma?~W=Q0}!B#XRgW1 zZxFg98^uCHB6407du@q|h{u}{OD*CKVGUel2*lN1RwAVFa6s<8qAhR3^P=wbYLJUHV(|A~BXn#jZHcjFwNEIF+ z@`-74X8>DAZ1P!J4*A5?O^3d_LbW7(IEv-Z!2@Ynf9)~kQ=H&VY71xGraSyO-=#rE z$LSf4&%)TNH#sx)1%^}fpJB`efATDNXW=aRVVBn(=s-L9AC2z9lYTJ}w%hyS(3{2( zV?t;nMDCwP$LVbQ_k2cqa|Y&PDW*GoiaYFg$aMfwbP&A*5-pC=pRhQS!hiH(!joX0 z@aSa#N;vPxebx8J=Nbc_r?7O_zy~L*1DQhD9{mA-tB`*w4_$mCxlp7TF9|+lOhw>~Z+uQ@+j=B9 zp5fxc^=w?#!fPPlI4ckkSA7bEsmy6|@tZCIHJpJCagfz{sc`$)r|A-<5-I&I2yNR+ zvAcW<^o}Zm9 z->L(N$~h@Dio=PNTSPt~K|I6c4}jf-P$>Hd6_TOO2&Tr+Ps6}Tgrww#10C?=Qz$4l zLzmzne(g2r`UkSB{SLN6tQN;POmtO$g*iF9sX=&WX22z`${Zg6yipIw00Xb!Z(IOC4J*6{A39Mf+$6$Q~Xxa6b zEUk^v(^+j@ggFD!bM}oggj>(~2ei#ZQ(=|V!*p+`|M*b-GEB>-)xVq`+5mZ3&pw5G z1I>KF72l;twwD<=u3Q<5f7m4+hn1rf+QcM~xfltkWi{gTc1ekOtaBklyr!at+;b_H zwGoD%+{@xE6J^l8Ik1P}DpXt)Z{cuk+1a*_*HUC zfm#Ml+t^bq;STs|JyYnxWsp-``_?1yIzeh>`MqQ99(vVk;fh8!{GbhNX?mghY$zFa zIY^F6dYe8=anW}^NBN}LX7G0sHjar#s%h0gk5^ZqdU2GSstFGc)=Ukl6p8Ap?59KyJ`y`9@gly|665_bt(L6)DWYrW1cA;^K zu0)BXGGp9@b^5@Cks_qpBSovZoUx@X3(6vZ9Qep~RBjnZ1kwuned`VtobhejuaV;XdqKY=bNPOx zEuu$e8WOXe4UM>`=x^gZuHw+Qa3WXkA)7tnVOqF4Jx;A?iv78JedV4|o2nPa2kvh^ zj&*PK_0qz4;3B0vXV6{71uv2OZ1W4W55C+WUq<2s4?=YYZomvCiXqU^JWDc6XNKH& z{SQsR_zs-4`6vhG$#}lN9cp2h{2YdiF`AscIgPlsfPtABdg4%O``d~Pe!3er9hV>R zJ>qEkxNC?jk;@M1`Za8*ch;X2!i6u~IfiAdP?ssF8E}Ikz@@jo7(A^hKo^blzD;Y| z)fFd#)jfuAd0}v`GjJL+MT|2}005H}fy{ae1i#M2*UKUWk049ICI}EbS7yGS-|;ey zFOL~7=}|5%wB(5%UT`^6)=qJ(TBG(|gv~{+=6S*X-n=y?ysWqW4GeQk;#3_Ih{M-d zr^(ermtIS1;ei<40Qb=VI=g~1I22Ea8A(Ngj|5jh$-_VnEGSri8h9iZ)Pz0(i{6_~ zojAr5c~VXR)0d-iPw2_aMr0=vAd8QzZnz+^#z0~dTQv@eW($cPHYB#7H13WdGdJT= zY6j4q1RB0Ka}|F92C@`T$M%H(l38ygqC*=wG4d*BRM>fwtlGqJ=+0mm)5OiM~XekNM2+iFqD$)c^ zatJ!x0PP~^Mgz1f9`qpq2QXa}HNJkV004W=gvH&U1f<#OKsRWSn2#K`XfQ+<&yl(+PCG#}_P}~4TI*aST zghfKVd7_Z;gE}SaY6zE!qwwC$BCWwJX-1ZvWDT-V`6QeewQHJ!(#R|go3eOuuq?f# zOp0o1G;-X}1OUN&odHDp4(s`~k)__q!a%z-@D|$>KFVsQGTTDQMyM4?2nj5y4e2>EfReSfMWWl zc^1^IGx%e~D59%u>(rnLzZAsa5=L*7A_YL79>^QS1nMC@dJ8C$aUZul1g2a4Vum%i9Y&#=P*{I3BYb9GVn8Otu-K((o;ehX@dRNjy8Mzlt#mS#{h zH3cwq7S+rb9RQ$Q&nk!eDmb?qaCRoZIUw&6`1zLF6MYQaQ_3Z}nQ*M}JmC#D@fvHu zYfON*B?j*=0?%j-=8I;;!y}1oWy(7mc#nudK#9Mtft4B&6tA|U$YRm$0BQ2ggy&H3 z?ls`?)y_KUDT;MH?C_W`nr(vz3jw9@9zCy}*jo~vg*HUINVL5J&ut!QcX@vZ<)Yj; z662SopTT@{lzgZr1uA-qpq3ByCi8A+QEC$`0XU*Bg!$l=H)w^WuISx@P5^L0L#%ug z`*Nh;Eo=+pXtK(ILo_5U5e2 z3xD)Y`qB~2)_;#7wuj2blM4;u40MAfXRS3@fxz(sY>+3SoR_v~c6q`AXzLb*dcvf^ zD4fJb!M&h$C>D}+s z@1nVl_+7=3Lm{^dHOOj#3o-ox!?Fo)wrfOyaG8OEHLrCa9&1<(6PP*&USbO z070CLFYrY{;REtzEIx>9F%3mBiW^#I$;X@U5wQJ#lGd9L?C@o9TVx*ZKO1yJFUM#0 zS4ys>7yLt@6DZ-hT*nr{AWVRA2B(AgwntaP!;iklIfK7}X0v}Wf@|o1Ns6QeC#J!v zk+lHP7a>d5_|^FC#dj5>SL+2Hq`YBvKLZF%kG5XU3t-4$881pk@CR<5;*T}%yAK(Y zkNX1h#T@tf5VWkzP-_ob%IoO4p9|033+LPP+LyWHMp6`k+mEefaMoG)X~2_iNb_2jWfs(8PWm!P z<{V6@Nx?rMI}7@Ks!$1><5?)EamX%(i*qsDJf6xU>`ez0Fbo3^KP1-#@-wcl;MO8_ zN71PwU8bc)c3N6oOm$F?Km&Mia6J0Q$SBs);y%w0eYdn}7X5g41_-UK&hRtvj{Pwm zZO$d4}~U5(*Hz$i$iZ{&zL4hmN(&!GWJPN_*@NEIKvhz!tft59nw9x zmr&WH4caqP)L#luRu8P<&?59X%(-XK2gSL2%yU$FB9*fkxlK5ijQxT4`8k=HAxDU! zvPu(h$E23h%qty@1D!JOS!ki9B@@C6G#Tf@=4Pwm z_UVELhTDM(DZbYkJQqo{1Q2ql0&A=*amyq6OYpk1$h287Tynj~JNi1Ngqr2X%{{(Z zB45R*u{cs_+9y2F3Y~c=?Gx?+jTD;p2@m{|s=hezg$BwQfU8H+(aAT>k{r8=X{7f0 zA7qzv7Kaz2Pww^%`dEJvAGqKK$`>M39J&^q-&`Czp*S=i6riasF~`yEpb?^Ozj^~* zm*d8DJ0WBETS5LJI?}4YDjf{18XbflWY`y?LwyoF9eJbI;UA-XLt{$qGjT$sIg2)E zk<>h`X=j=VwC#@u979({*9ho5MAIAyPDIDcEAWx`jObpBSdIP)kC%Q(HZ;c~bV77@ zh=RBw+3fl>*bs}a^-pNb>Db9w{x>$E=!iAqriJXYu3sUue7Lk%2dLhE|+%B4qJLeuW zI+3m20!-6uq@nE%DtEw5{Se+RP6arJkp$FnB#z-r$}7nLD(Rk?{|>1_`{yN%X>Z+j0yi zdcA$cvwjX*jLeR10-P90Op2YS{2kQ%26ri%)U+0HLKx$-zL-Z$q$E5(BUF^(Ts!`> zoP(>1PLur*KLUAo=5-?PGT=p8R$?s;$qU1yGsyc;DBhv#>|ao9$0Dy_yg^=ztjUR! zFS!13>mS2d-D$SJ65YSEC6K1(U%2Ta!?ykt^LKsi^LKdvQNsJ__V<>e(^Ks4Q_ORi z+ux(8H0;48ai=@NFNnB(1K%syxVSsoD;+n#Y2h8@dWs zLjhB#rd*46q_5uz^mVuBt9{0I43C@jG5D^3g&M-c^)8~`d76oD1l8MyLYC#>E12)q zdlM2+z^ee5jzdl^hG@@-ehn=YlNSwZg2Rh-EoDb|k*ndA6#dWRaGl(yxb+_vz3C>s z2CYs-D;F}5R`MJ4zR$5xWJt$9WAv6BR`f1M-FAAbs1ZSL8|l5mBLvv#orv#x4@K`u z(9u}KXVJU0K(ZV3W)e~Yz2pBydXK}GW6=AoyA!?A2f{1TabAnRyCF9a_O~aeIl|e| zUqQfQ@I>A)>WFjBFyO%9b-3{$l$sgthC?i2lGF9yqT?UhMxTU!VsEtoH4R8-HS1II zZR@)sQOIG<%c3mfEm+XO*%~NS%Q(jlsBg306Mz!e-zI|x{0LEyG*^XaP5Qu! z%~WZ?d(cZ2Tl2;_9T-ie>ZcsFzI!1q|Cjn2-a9=X^<7Z0St?QWN!6^6*H4P`7SAZq zH~1*^g-=b&G0+#nR-hhO_tJ1#sslBiTd~>k(yvAeg+kkiqt?|3(Jsdm zPBWzBv;<_c(W-q_f55e{4+BnU!=ZN?+D}=BB_kcq!VPV&7=F~c)ktV-)F&g4sjn~; z4{_xh#(HVrjxjZCcYPN1CbUL5iWqk8*N`d0&fSJb6zDpVz3*8GiMKX1LRyd;U4wCl z2C+fXS)(6}HSPSS==oTtYuis?)vs4cQPCpn+W~6&jOgjMa;HhTSZ6Tpscn7Lw76!` zI1)eNn~J3p`fV6Ok(ytD|L~IyoZ-x2nZs#XYrfdnRrxSBE%|*@u;cAVIMda%u&w!G zt@I%vI<$%Q=J!~!onTZ>Kr2kM28GS~0Rwewbx-6s!X{|UWE-?zH7wbmKqV2q4)5Hk zgz*wn;td#AK9!hpq-H&cs$%QMaiQqcEcawB^r|N^;3X_&HaOgxjnx2b6C0D%Nl@TZ zYY{n4x1yfE_>-%_2Yt1&X*FJCdBUI3;6DdEE%X-sY5lM09Y`96L-erN+?BHxcH%sy zg}Z`@j+Xo%VX<6ZUvQ5eizj!dGx)g-+C*OTTVZq+H$MP{^-KF=TpI{AU*bsc{YpWD){@$yff~k6-;ZG&gog7AoDF9S%1lReNn$WJ!wFWAesq zoKCz|??oe|s?tkQz|8fLc24ESY-jLYlp$))z$S=!G#!{3<1M&GvoO;kAA>lkmTd$^ z2&V$L9*H8?u_cOw@kK8f949?QJDdOH@t^NQ%3Cc2FHPpgD)`NOEo;{wLvtI+1)(Us z297S(;<19)v-RIH8%JzlLC%X^y<6!~aJQ>?qJ@w&xCOV$L64hF?_?QKZNX{7CN z27dxlxkeD{>c7xJ-!S|G#yp4K%5A=6m}A{7C>=eB1pO;CXI%Rj<~2T`mLBc~p5J;e$~LsWd&9X6jpsD9pX0nKj07F+Y{i zLfv&gWL69J#y!2&X{QYb=%;J_RaF&L^M-2N6LuwzG)F$o2`?~H3!kiEcQV)Nv|;%% zq8)~DMAnx43}YPt%n|14to3z`KncPMqrZ(O;R2Q0{LOKwoME8y3B=q)zlUm1Ppozo z*4E-sVQerDT`rT2YO?S&N0g#r=uta&x#phSJ=IqKpJVm6Wak__d3 z0x*Hk=NRzLwZXe52G8L0-AEz6t$AmaR#py8M3v_%$6VMrKA&R1Z-sI(`SA_mC-1E% zB!Zp?&?cXso>Dcxs(MkCtFv5Hxx5tgIJp{(qWaj2>_bh7qtfmm7GdchzEhv+AD~OX zWmr$ym>%{2*yex2BRqUT8n2!0#&H18v49A3&#{V+;QPDyZbq%jy4eKzkeANrrYBsTBw~~e-9uqK3z`Hh{sichUafeMLq@IaMRrgbZ<+jn#db-3_~%k6M%!o_ zqw~4WZph@RU7}I- z2f$#He}+9lC%80S>pHPhZCZF-Mpwl0Lp?J`kHwIBIR*<&DML8$Wg7QbuvRSu6|T!6 z{70>J2-~&Ocsr7IMvk=a_;h;%oA_zrs~ADZotp0BK^pat5GX+)l#7_&n#Sftc*f)t zg5gs!Cviy}^Rlp|7%Ych$4SK84W3YDCc@(z)RA**2^lLFf6mQNtM?mFZjT$=&S?bcbK^EaY3-10zMu zx2(x#m&6>C)jH1L6C4~gY|J(`U`u~-hZvaZhQ;!Rf%9GuYT8jM!&<1>D>J{qo zr+%FO8+(KcDtVE*Q$5xJShdPfUFHn@Ts>A*I|F}Ek8_Y=BOZlhG9Z`=ES0^Jv}hOW zy?#ZP+0Nh`yg$oMi;No{*!~8N{(j9nVSw zvtHfFgKyC)Jk4E=JoB7E#*3a!H}h~(NZz8CGLN*2 zs*Qc@SvX1x)|uv8w7)&y5=^P^OPZPQAZ&rWMZdk)l~=2;%Ic0kIOUV zEjrttugn>|fbi(D3cQP%k8jZtc+#&Pmf)W@jDdgA?!0LbS}KfnW4+EA56x88`xjcu zOJh2Asrj_X)QqREEM>s{B%c;Kb*{KbdFgDrmb{Z0{I16%{D!F+?q{#`OU5c@EC|hn zUlW&8>@@N{Gojj^Z|c$VJv~{$^D20B&XU4gH`Ocf=BRx1r;_Ev*B2(2qnm^lXSC#< z5{%>T7pMlV2fprio|vDm7j&+cQ$$$^CFs*o zC*=||JkdSZU^Xw-{1Sg)&!!|qbY6LDBysyRZpH%r3apkW&dimRv zmmeEfo-${zpG4W~7I}=TANRq7nI`^}xg_PSx~=k^`E?&ck0!sa?p4k=#Wxk-(L(T{ z8}O@sl|I zLIST&8;?yW!e5Biv?iup2;&90{GR+B&;7EU_?rQokImmRZ72^0nyNlDC7gDfBB1wM z#zD_+EdS!{ze=H(QBcIy8|-cI}p!)BLlX!`mrW4pZU ziQi(4FSV7`>GkmTP5IVV7R9|oX1hVfrVSsMfBy20YElyl}4b2rNPs$|3C^bDeKu zasltq8F=4_OB|bI(g7@VX%Sotr8k~OtD2v#mErUQJYZTV?))4?8*sQ%v%WZ!eJ22K zRIP9BtUtPCChCtbnBtt4#@|Hy#)BvaT>GxWF$EfqyRP-0!G%`S1(Az1e30~J{RK3x z{wMZEXvEuqg~n-v?Ko0QHrPlB{a4HsluWuT5E45=-Fg3De3@_iV(2sX)Cr+~xv!cK zYT+R)|1{5e{L*wnDATjF&dZSDF!;}g!=Su{oDTibp+E_&gpDb{!4?Pl5Ir!L$W%yrIX)So9`x1bg@kAu5&sAWY{Vd`Se% z`w-kMCSYJ01Nv#vPhK;2QQ(J&<`n;h>#Y^EaG!A2Q-oxg~DE6MJZlUAQ731beCitBFkUSU9wSDJ}Xt z(jN*kU0T?KCBJHoDV16{PZtRc-K-=Xu%(pXz>nwxd}jac)MvwKU09o~>zb8jq(G#m z2y>NwvOHX8us?aWawFB4wGPC6Ee|R&?NM_~BVt%A>62!aQlfxn<& z{c^w`hSTEo=g%a3ehYUq;6H&ja0X%axO^OSXn>8$`OOer1$zf4EMoZIso-P6RrZWA zAX$I?a8UG?f3QA7;NL*_-3|DY1pWiUXu_`n{C!&JfCYb>9X|C1D}Y$*k3pA5bA>X> ztnbH4UK3RInX z(%(9r zt&ku+eqA5dFIoB){nVuC>+}x5Q3Lr+(dG%U5!3ydey zAQpqI+*1y@j5Ed4kU&qc2>To#P$xH_cdP0W4Iy2*Dcp#tFP>KjJl5 z@SMz}< zurF4w%^RX%2V6W5eK_3f68ylp0$uh@{?UX@kS!Z9MmaCiqz}iZxlnc4_$@{k6g#is zg{ZJ5Q%`I`dFaGc`31~v0ufr;wCx`Fs;{3z+m0u03f+kuG2_lRvC;gVB@%WVdJmI^ z>-VA@FbyEWBTI7m6<^w}~nVQi7CUfij8nuT!?1mx}gZ>uEO+Y!C`w}WQK``PL z`))kLzV}KQz&wg34dfH3W#5UMY2Odvnf9G}n7^X={z11k+~=D9kB0Uz3@KcQPI84djoN(g`4fv$*><8y{ffn9rgA4qY=`hy@2vX4c~!16gF}6J5B~ z{Kf7K_;@wC7G-QBzuA zE&45}0SLmAc=;^DL7QgQxc@iOcr@FT@NM+foP&C1>J`VRpXbZOsOfE>fJDd277l&% zexloqyWY^X8;PCi2gwT^mbtyzNsM6tr0jmlWw6Mrx z$Z9P|@J8meZs)sMk!(lPc7tdqPF!;`Ig$3%nc@**?iO5Ow@0&xL%0()Q7>%aZ#XT2 zeE3vu>8CK(OJ4b(O*29Rbsg!Ev}}Nl(>6qlt#oS_@$F^ z%m?a~`i-xAmcbl8y66!KQX#Wg+5yNI^_i*g&00%9kDf2w4rJ0y+C0LG$-I>tX-(rj zLSw#ULinizsCEKfHExS^i?4Pb_l2I=hyBEK(~d{w&fp_}!@i^3wD-kLGhD!1zJcGf z+79oMcz8_^w-~%dT3OtHq7Hu3mf&R*=@NlQa`M-&NZX+N{S2PubsdV7# zE<{Ol-VJ{48ER3)A5nq}Gf(WxeqeTfo4adV!Z#eHSBtX>X~W{w0yw$$cZPWE?_7Ge z8jgzP|B_6TZP7E7|7(Ny06c12`FJ)*3zWZ|?Ebcq;&1DZXAu8{9tAJC$BD_(x9FcH z&A(26J8Am;dQ;N$Rr(*3rDKjB?9n6mW_sKe`7zJ>KHKx_w&y?Ep7U+bZrk%yc((cj zft&Mxo#%(t?4rim3+SkH?!f0X#$D128EoMY7sF?)4C513<@R1m8)7oioQUE4Ba|OD zuQ%%+r%6zAbd!M;_9u28570fH13N4$lc+iAN}J<>IS4T@d~v#nUTh?AM4AfY9(w%O zoseW0P>Dng1CA%c7?hoCt~^y^07)|j0OL*oAshg7q*1;lvgbl4GNWh4005=~r0cK4 z$YU4iML(j2=yfrE)Bu2iJpLsa0HlK;4gehZwFUrv@j_}@lQ{smALTg!kYCt?hw;w8 zxB{*=$0NMIICDYFv6X&eC1nSqzXd=CA$r>K5S3_Rgk2-NLy*FTr} zK3?JR>~sc(i*u%IHiE$tPNQpvTazM>iFdXf9Rbepy8Ajg!#+qNHBd5NUBM0R1So*D zJYkF(*n!RiOz|mW{_wfS0ES&(HV-n+@!tu9VS1;pK1DW&cTN3tG}I=&|=%g5-;}oIju=)Y$8s0;|#w|{4 z+>-^I(YT`5q9uggG zR%$ugpVC)^+bM;ih!T;OxU2EmbhIT8#q{&;WNw-V41%&%jyAg&cq5MXW5fvk?|%M< z(=w3{pTyCoZlnI4W;xo@aS8R;3hFDpRcFT;F)H%PUaZfO4vYCZ8l${8M_biWz#+Ngy1KF2xQk{yn=DwcK=tFtLqvsNOizXLHPi)nu>n`WGCxN;-SRJ@}N(^`Or z#c=)rsuf3jHd;bChC}ISKitFa82%2N!3syV1!_@fFNSl7-9GJZ$jSSFk`nd7o8x>| zarh2`RUr+Yq4fz0G9Jo!>s$H+fF=uO#r)%O0{=tcsXQXWMr;hQ4M+YuI*Q5s<6!`8 z^JhOzx1-&564738bg=U}`LnIaY=igPIC%F6yu;x5QPA`XJlptSmW&Uc0npg^U;y>e8zhYKsZ&PRs!YG6Ul+o0az|O zQCqCy8tq;{PBQK~E1nN`3s`g9b-O@?5;OR~@Oa#~t3CewK)CkocCaJ*f#c!be;{>I z1H{L#R|BHy*Vj{mOf3b!zI#%?{wwB!U!U8PJXPVM2YpjP-lPCm?6W&jnzD0jAY5F?-@ucbZ>vtzjU!|{1mTrs_yve_D z9zie0H**ZJXn1T4F*7&zJkOTyvZdD}z0-Pp>--HPbgwj{%~hupt6X)?oTrN%b*G<< zt3f%j&Oa;>;YO&$`Sh2&fVuR#=h2MW=hMweZiL-=lxqkv`k8PS;B+^hV9lpLk4Jiw z^s5h`TTBRJ1ESNIP!}hgz9JLoebY|R^q^Dg)c>&=b;E+2Q+fFIOHjeT30;?A_73g= zX3ON7UV%QZEiqmD#=fk=L9}#|gOBbo%+yoBH(bY5CinPnSgz-)BPo-^asL zsrdU*C)8K>Vje}>e?Fo96B)quYQs6t|I-Qe3!t6Y=Y%ohZhsN)ZvU2Q5e9E3I0wI2 z=F=erHh0@e!^!ZgF|qz}+{Aj5l>eDgJkhOwjn+m&wQ~d1{>ZXIIX4IjIZc*UP z`Ffd8=X|}2e+u}x`TE%cUd^Z5BV^Wmw+^dj`FEY>>n{XevHAL50zYoPzKg(r0Kyb+ zkuCTi+Tq9M(|7B$y22kRH0*MsKVnH|;(U4;3LJGl{Skm9dppmk4>s+8Y`)yijpziJ z!Z?2;o|>pNpKit*qZ8?mB%M#c>035(g3!PN*pW1Si{6?veVzU&(oM^JC?{r(GcSle zUu}CHW_$h@@>}!i)`=f7mCl$GmYF@CMl&GSAKs8Tt2i=2qB$?d1=VQrV5!4t*K}uQ ztSVC0)g0hz5o1gnYNdV@8_vZ?F8u@Xw1*U+Tn-l5?+1{J#^QyRw^0!Aik;nzXDvJd z^Q_}Dat_k+Zet3}(@qhof=n^J>yXGlp7}Woh@{S9fUlfM6T04z88f+U@Mds0s7s4X z&a6RWW=DVdJ}oVW+hYS4fMD&&t#hK8ZaRPYG% z!EjUfAS2bC$WL;Qeu~E6ZWKr;V;&R%sqFK&u3%*3W*N-Gm~8D%JHR$IB9|ljurpCHQCcB9-fT@@YE3cV<5i?$GNdA$_I4`3 znZjWz^PQ+uA10hrew;N__vb*7vrEJe)6IDdNJS&@MOgbW*t=*Cy37x?$2w;1uvllT zvYwlx7iXL4&CwOM^!M=`(_ie~iT<+DKTqreI=*lJe2!xEpY+fCGz#XB2T;!HpTEJ& z|L^{JS;~LVKhKoR|3CZZ%^XkI`{&6HF!I0ZpA`-TGEc95S^8&VN9uR<&$VCu@B8OC zpz&Y!&tYFk|D2Tqmc;kZFTu9|YyZq8xTO8_R^iM*A zu%2*iq_9hF%d*o5GdtyAsII3p>hB1fOAuQlg(=!ETT;8DlXWdvm6_F$pPpju#85KS z(PtSl$MF@+G}zkKXlwA*4P#Gm-sHoUZsqdv>V`<4%X;AKS*)bwp^V?ePVr&9Sik20 z`Z$(vmtj5nNzT8gjyt$9)fv2_8y2P=p6LwSjE938UH*9m;rvuLPRWY&TDgQylChsf zYux~Y*de#5A;yT~Y0pC^j`qQzNBE(SOoUIc!RG;1!%6N4AHD=PI@aHKxRlzZf$c^G zK;pkb;FTi&cJ$*r57iK_&1ZI ze^MNE2D!&L1~I${5P2ej>IZt)L@2_yi#XRDUYZWR-3ERbqZ05*e{Ej^9g=^D)^aCo#ca19m=_m~@2ORt!(4Z$9jtsvZ&jT&ymhR5u_c`>_V%2i(q&35~-`6DhBe4`=&%b zQ1J<@Z%|x)ioa>G3L}e$>uUj}wW}Ptz`Lyk?~(p{wa5zB`jLRD-+>HTc)klOOIw$r za?Cz-`Fbx8p9}0JGb0z3{y`dX z5h+1Kq5pv~#Phzd6rWo2H1;Y;rpsul=Z@gC(bjwyQu#{@>M$re%^nYsZu1rjOCLWX z@Z$P-9RR(Mr=VmI3ZRLl?C4XDPf43xZ)vkPDOe1Zb|cE7PxzK84G_JJ(-Nyi9u}ef zJmGoiY^>lXcyS{voEO}?yg6xcvWY?J8$o^q2aK&ie)kZS9Jh9MR*LZk=ZoYvLz_7t+KZE(O_W z;>qiQRS9KG+WeY$@}mrX-l?t?L}xGgBMCK z8b;%ecJhx$lSNA{UXoxu%2s^Kscwho>*9EQT? zdb`%HAlVVUk#JT^zL$`XMz04|UT~7+f#f@)*IIZ;z7cp8cn9%Oti))f#B}^>P?~0W#j^OqveLTKJS0Z(FYgd>jN7OGl3MdLo)Ad7G;DsKKvnJ0F zAkZ+5=p)tsdkKO%?I+Q{fqh79+L;OmXCN-ibguVxfvtdY zqGs~pyoqQfnwin7E7MiJUPpc_`BJcD_fi+OBGMXeZWqzcX8{+~uo$4Wm(r|20euG28 z=B`E&oBL+$-^XPlfig&)c}7BbtZDxUFT8BH)>;U(&^oP!Y)~00z#l47pZg+txbZp9 z{9KE1MzC?Y7uSQaUtSvSx0_pmJ)AaB#$mD?S)w znBsEJr)G|&1!ilEc!NS}b;)1XE zcSoOkDeH&PKj^zOJTW`?;_`e?cs#~JuVQ02#tNs#`V-@Vf-EWHp84L0+`mf|5B54g05%3+6IkMk-3 z=w<2z=PIgAQ--kD`yBCbEMDGwkQ_6{(VghM1z(RwuR*DhZEjf4b2JpCroh+*JrJda z6~Hm*#S>6lKT3GCL*Mlov2%tP=#TM8^xIAFNbq2`v%`)XE`CmIjRRkPAMBztP|@m! z!()B(8xEiCn@fHL=Oe8(|3cyfwvNP`p~q>rOn+K*-NU~o`($vXzx5dc8zxfRyE8X>@G9CWD z&h@-b3ztvv7L^peg^h)#e4h!Nm)ALo!%!|q{uwetQ{yv}C!)AGSyUb2BW1r-hEL8oU)-N&uA*ISV5P519()!dG>6~i3V z{+?Bb`&#PbSe^1t`k;pTwiaVU*95@;LGMXysulc(`Ld%8P!&yDR>^J6>b_!S~_z@8P1ngzug5 z$H5O5Wyj@L)!E=Ph}4z(E7IpzRS;81N-D>0*sj2~wCf;|4~am@X+NRY+J2z$k97E*6z+e(;SRMlw0HRbtzrRoXv#iH)AQU5iDtcoD+N#xDpr5teYpK) zOVcrrkEmAnl!B4-d#*S`>pBwS75$0m-j0HlG6`K-p?=&?BIeI!MZJ#y3`)KX9s|^B zWK>2Q4*p;q!cgg7e#)*d(LH2u(YpYDS5+zgqf~{6LIL?P>)d z!}&0KD-t44{X6;uPz-2f!wHng(`9%XEZoH^dB*z~JDW$?Z`(9}B7e|3*ek;;h8req z0Kq~>P?X5D*8Ds^>cO3RJ90V-BIPOI9WJ0>ex5;aDhjmb7cdu4vBl0nc)^NXsG;Fx z?i5{^n@5X73asZF`#hoXmqY^4CP~~rWGhXYWX zDW2R9aJ~dS6o&`nqU3!Z(P%gy{u9w?|Hks8jy@xaHcksUimTX|=Rs^bNaRT6jrcS^*rpa%seOZaNl-hTN_}+rYcNTG^KAGw5TPXRAbW z|GhW1o`6}*h#t-zkn^zOV$w=JP174>t%i#wOW)O4U;pS`Q$7*3w#(-n6o_vCgZXTS z6=$22GZSbENVl6~DJdP-oT^Vcd7c4nEw3l+&xxY;<4t1FER$L?s zKNsz&^agsvgD8b2(O165NuIPHVW`H?JBQ{t_1aM!+B;#;;qj3R&v!=_9*5Ad%*LkT z3tZifK1)%W>ypa8DK2{hmqU6&1Gaq)fGNB6#$5=jt;PBHdjC=V7UBNoUiaaQd-OJh zcvosEo5ytQTwPq&^2|syth=El&6BdT)iJPiK@HA^Of~5DM3$u#gg%c>7FQ(Cf&9pt z%4B567nGRi8`+YVifg)&C)xK(<9mkny<1%Q(wgelysp)CBOTGb;+8<4Dmd}^uJcPi zAM)|G2*XZ5&#l-aJcu5W)Orf)gxuY}>ENnIypxvgWGy5V3Ji=?OyqYkaD*xh1|mG8 z7Ck$G92MJq7nde8>m6dY1M;ga$+D6T}PDH@*$^ zgtK@GG58rR`VvbI!l~PEQ$vP+6WlZ0+-LfW#i2$lo>iY^aK)Hw0|4aCaII*O!I$&a zW}s6LF3c;0+}(mrPH_31fuZ;f`!%e;7!D@|XXpJ(KcB8&2-p4faRWbGNXG#%P4xu; zh+R;57}gK3zoARVasJD~Q?i3wR~!$h1o|{Hh9_W&*T!^Ei!#$m|6E)`B|zNQ0BAdg z67Csb2u>l1?$~C#7W zDd1(eFsmT+8C6L5Lg=aH6n!>?2l;Zht=NUTEiuHt^=qV{*sXFGAdqJ6NS|2%56?qt zFs34a>V<-8o~jtRMj{uv(vP*995ik@c}m1I0CpJu>eNW8h(j?Z;3B;~`UO~U6%J;G zJa{6#rgY*m1ESqQCwzJlyc*uF$4wKY>V0&DjnK`W+w{{TP$6 zG5O%qdadlR$B3g8hno1A%lgB;w_$Wa8-nF$#^_=RK&NbS=gxGkc-jr$k1Y8JsJp{6 z^Mc!*w~RD|h37jLhA-E&vUiKai-vnrK7epKgFi=Bj{YXWg(xm7%1haVC9X*SF_)y7-I(WNE_8J^>T!lpm$fYC{GgOrHLD%A%Ge1lW|#0o`B%< zV}N19rY=x;IQ=!NC9ex;7e3s=n}3x=frAJ@9Hvl_kA_fjmnnFM+>on(7lLDjVA-u) zEJil=hd`1At*NQQPziC46n3@g8jK${xu1!vAE)?samW#{v^z?laKwXq=?fx*x$qxa zLrpT$e=JJJtu2L-8`4sO2bYh;XjP39io@e64?2f);S#uji!&lWN!2GHYNnNKXDIKs zH_@L{n%yZo+__b*6|cC%M;?cb&RZTA3LXzwZuT zl^5K)yx1MNyi2gLz*+E>J3JBlF8qt!DL5uQT7%3=dW$A#Pn}*c=>RBp2Qkk z^+(@er@1Q6Ksd_Lx6OK+{KfgXGB{ber*A4mCVYnTd8DjRi*FDn7rZJWeA|cAedkM zdx&~^0Jj*t1$k#@47Ed2Rewv0j&G2G3h?Lx)!|&9dP-9}5NQSm9nl*gxn_KV`Ur|3 z$~*iB`UU)U2z+@%g|;`iBDOblGWEtj!nS1zx-~!i{lI}AIPe1pe&E0l9Qc6)KXBj& z4*bA@A2{#>2Y%qd|DFRWJdMgx-+}*E;9;htamhx9WAnJ<-Z}@18tTX5{}=B2?T|5N zFIqPC)(!qKzqv%_uD3(WW?ZBgFF>)wY z*ObS0FZGpH=2utEsbCqcv}#VJw|2ycq{+gQvr8*|Xo0f%6TAyt z0|&bL=a*KI_KGS%0R7i{T_u-aSv<{ES23>&?NY8lx)zmtt6bGpURP-)ui+&z6?MM4 z{=|iUOU>(5ZA6yN^?7T-E-%Qfsjelpl@(Q9p|`BOwAO6VE2VWNdFPH8QC;J$E%jB` zPM?uQ21{o$dY!7rE}u!MWPhDkIuC6l1=Sxz5=S~qP@e8UKdM8(- zFWcpQ!OXJK8lS%wbd4VES}=0~1P@%P8>-~iF>37M1(ieUd`l|5b>&{K&qcL0y1&o6 z*f(r(U1fh4ZeX4}y1&ZjTIj8%*pBX>Gc>!u%Ue}eJqM_d?muPn_#wmlkH!3fonIbE zhL@LVPg2befh?Uf$9%~$M7J2t?k!zl%U0s69XQbFxM(*+Xlg}FEtsY()v^s;i)u@2 zAeQJPIrsp1H4B-7S%>Lnkm!=X1zr?Ue|5e&t~uU?jtYoqDfE#xy>(_J;^O0Q@l4IRo`s|0qw zcZnzoS844${{pnAYk?mY2ZGAZS3P%xtICVk7!2ef)q~j$eXiJOr;??9U-e+u5^w_rs;ZgYQMkAUNPw(TfB>>!5Y(XG>zWM#odX+5X0Foke(rCGu9c^IgAclhDP>z*)k(WECk{p1jc)ws2QNXpmgy}L%@xKk`tW|>UL(0 zuXdCndW9lOF!-CTJUh|_Vv6h}1Z05G5D9^x#*eJC17*m`b!qkbS z=!QlQWVe(=GeIHja@W+us5|z=9y^H;BdIUgD)ku)e9@;K%S>~N@%ky z7QlupGb)1Of-eVIpIcd7>Vsr1fV)sp2WxAf?J&*QcxHfZDyc>@URF^xM>UpXlDAS? zz*bgq$!v#FE?2f|PBl6idk)3O1v62{tJV4Uo#n@jhAKOH`9jk_aQSLWtLlgh8lOCZ zIbt`OnSQyVw{w!-AZ@3Yr(L)EpO9==cggv(pgp4 zG)i0v^;qWhzz<=+A82)DuXNr#lhbD}C|xoadN1DJz7%@O7qb?NYGIsAYmpU4M81E4U&*1F zozAbR+~VM10As?K2%}&sB%k4EGi_*Dc}3+MxDPhflq0POJ#9M2)pNy@L-$$Wnw|$w z5h6!{nK6{hD@=dX7)nis8-X6QXvB#8>Pr8DD$994%J&f?7FEpgl^Z65e1>`RRs28h z&ILZot4#PO5w*p%Vy%_hsMAVHXmgpF+|v{YB#_vUq)BLLNt-5_$)!v#otZ#rQ)OM& zk9D(($|~z-6%}2q(Z!0&YPMpnZdap=T9tLP%4*j|zYv1bN-^dA{?9q@JGV?ipsk;4 ze!TqO%eg-1{+!FSJN2v+1KsaI{H3LK(`k2vBJN+vAU%=x2L`%>ekYsEwqQHCwvXI5 z7$$?nNq)9@snlu9Yx>%CS+oVLMQS^hy|OzLAKu9D#F1N5AJuQji7vxH+xybe;6ShV z8K3@6D4f((D%jT-w!Oh%Siq z+(Z80R=-atGU?LV(?_wSBjS>QDxFtXPj`SOn;t^1563AUe3cqW>V;0%K)=i1%J3;n z99)?`e@83B>Qa}-?KT}f`ujRd={_8NuMk~U>Gp(fp%T=!hGU|&myr-dlI@{xdIj0p zZFEDsdRl{9vhliuI-ja1o64Htwgy!69bq)@bk#4T5jr|y>N0wcnQi{?Ha{a9H%|Lp zo-F!=b_m@$B?SZ#v9!^YtR|j zhUn_IN;0)~caYj4KUI>%hsMOGhr<$G~`rA z6{UcSrkkEBZb>S1(jV$&9Pgx)ofWmT9C=CqkWLG+ak8Ke0hvTP=(@fUf4h6Pc1vG@ z@MVTu+d^4%wztWUHDt$@ehVGYEs~}B$SQ3EROw_6;z4Cj&Q+?rw>>aG-#awW-p-J# zV<4boLq~++^FX+NAZ!9wCu0`r(mSoDWHG0SvXulfz>&_r^!^CDPC~63LZ2Ul;_4?}C zCX^^mrh|c!M!XCT^oMQLgfS`RYHBc7P0{M43oG(;G(1L!p$%egU413yoQ|EVUwU?S zk2h)%bB&ej@4#TAzf&qA)4|%>-Dh{TY@?WKs%+R04WRCa*=n7b5Mr);O@lt&mnM{e5*yufqW`ucYQfF|7f?yk+B+&rry)zQVY)L$C1!dvlG%}6>@X}rk$Fq( zSCpIDY)eb~;GoA-S{kcKE0b1Yr3^6Yw6e<7NA^fnhAp~nS)RQ-PA@QL<8KDxeR=>H zXs~4zKR@`3GHPXfmio=~3i3AL55kN(Qk`Ia+{!-JvzKXVj0|oxX=@ z?wxjdAx@BxqOyu_q35s|X|QABp}Ril6=Pm8-XQBq#*KTaRdgZ=GA_f%n6xY{?G;_+ z&`_)^Nga-HL)?#X<08c7sOfHURN|_-msS^b!Sd$8+S=tJ#Bh+5i1a3;{$spBua(Lp zq6cL~T*Tf$Eq@nbQ$jEGt>bU|ri-y0r@u(vo35ZgM9)X20BBRBd{-iRUwk^-{klf# ziO`KJ>;mQ3qzu{RIj&1C<>uncxhcOFwzmZj!X&Wc8Cc3w~gmfYQ#@c-fCqh)<5b+MF(g!z<&WUrPs zls=me_R2^FWSplyiyb$v_xGC0nNfY@-X11J#*C2Xu~ zm2(-q_p_38 zFWdAyT0`g#bia6x#$VePC2YWtQh)j8&9vZ-`oTq&64Jw_WZec;8yWA_t}CY}MDrwS z;&#TfA;!Nw-C-tB&6r1qeGDs^17w)%@1z@Px|CTm4Wd8N9cS9q)rR6jM%&ITtu~-F zxGn2zs@JUDw5g?`a((5dmd2*?rplI@>J8ORb~?uBj~!jLtBqM!CNetEVWOIl4p4tz zV0&+05A&>gf<`Q@Ni-zgTqhoSj7MKDG|-kE4Hoq&Dj3_x1pC@M85c4>W%MZ8NFL(t zYn!qClgCOiC0tM(1Cm zSzAU&@s7-8T{X7*dzqr>D|Iz)M_1oN#z9F;#zlLsYit?olEk9ET3f%7QDu*wLPr@v zW|uWAMvvDoN$4ZIM(m8wb6flSL%E^tp$*2xT&YZAU$n@Joc8{Hv2wBD(E6Tv0&p?z zF|)BHNyJ11iP5^KaB6prdc=e@iHjE#&R}bgt!KYx@H3LjD_=DBd_hr?g!u)b#>!)_9?F-kE)fiei0~cL8MT`)k4z%NX{BeQs zM}2N-GrrkTXo?s4g#*QM6o0U(FS9Aj)#Le!fTXJV+E6r9iCeC~r4UkhO|4(zIXQw^iavr)G{p3lIqb`$7Z1+&ON?j)ZURoN*P6<2>Ihq|&&w{J4(AP%Mg(>}Wd0 zrp(QqDGBEQkuGit-xQzC5{gr#Wc!$HPjEeXiME}M&3Dp_+#~bUGEFW?VkTH^mA>DX z<8p1(Q>gZwge$YUc3s^Hdje<9dY=!`wjig=)cVnOP^Y@qI#b!`#bDA&mfV`q>PRN# z&&0g6v}Hq!ZlYWCQaD*t*PF0rPHL5Tm(*$ZoOXQfa5$wWd3Y{tKT-;kIw0LzB;DKD z#oPlk0+O}$Fagsw%x&1wj`WA;4yQOTrP(wUMq21mS#Be}Y~AaLuGE;r7v`l{T;T8R z8(<-lo}i#Gi7KANVQ#&rUpmBEZf&vaA4^-Adb_j~xUl?mtrlA)X^||{o^FN_#)Zu{ zly8U;-L{}Kb~;=}W`YLc&@HB`rB^+0Lq(?N9hnWG z(-h`hX|=X*AYc|fNztMbW0|I&@rWdw^st=NUWj?=2`#{URD9a-oZ+wqRqo7G#`OXz z!LfbBzBWC{BYi^#17^*OG$`5)ojnxGKugVvIQ@T7ktg4I^yImVo%{TP0=IMT@)k$l zdx{GRoc9IA?xNZ56%{$(i;CP4Hx}$(|uLE?0p!-<{`0dLD0{ z*HfI2`19TFVozRy*X8o&XSj0X-4*9@rHzpmRnL#w?)p4llf0gi00%^}N%XSpwy&0l^offVn&#U+)^e=D!5FwYG}fUWD|G8FD4a$&rq(Kxnp^u9dEz#M$l?wlc13 zk~IT08{8yKRc-bLkK40h&6-kIp6Bs{Yh%r|_Jjtg>lzy?T*ZZMSLGdbt^&7vJx0An zVpRXx?)q>yiFr>GrtvOfJl6eaI9g)EQKJ8h>(Ovy*hQ#a8{A|-6Ka1zabK5$nCDpk3k!0Jo#j=D z{^W^2`O$FeXHQOvj$c8Jly`~Og5pzLj5|&`#K}$CGX63$7z}Fmvhv-$p#|Z6cb`o5 zn>XFT2eg?`Uk7h8GH78KdT`SzI~eqhZ5?}TKQKNz@-yPo!7hkI%d|0w&)wq5$=9-6 zXq?=<@w*7^=VC1RY@y57AZoSxWIM#2r?biJfQVsGILLF$~^cZii}Lh606m*Zaen+FJZ*PsaMX4Zp=W8ao7Itappu;Wl2_M$xidARZ>S5s3=~ z>ct6vL{}kW#)ZWr&I5Ale&%$7O9oRy<;kolD=|bQ7~inB=&D2KCFMX7rrx8 z8D!~NWcz`1YFJ>z{~4^binBh@r^D0|CP&2R?bcmTvxU06Nfu>i#@UNF=jfG^YZh*a z_bp;8AtxHuo>SD~?U?KqDUcEUgQK}aEB?aN5bF8{Mp2C@qgsPyTOBd2%oKHCj;-am zndN;9%32&%I?G{wk@a+!7Va0WKWWgz<%`w|lAxxtNzli#W@)x^(D7qoO2hfpx7D>3 z)u#8z#;3lX9+rx?>!oS-f?l&akn!_;=K2^`=v9R5XVN)cmY8deBWqLp2U>hRtu5qf zrmJKqtpCtDQnfO2mOg|1O-9kSa%t{)1oTPfAB#~pw04%)ZITHGdB?z-Rg;1Ztmox6 zs%?_}NcR3mSyd@Ra9iQ1=Z9DxXzRVA8j>W&B;ZjkqwRp+$28C@3RW~^_R_GJ{S95968MXE=zi~8HxAB zhJ%%6-5bN*fsh>z(FgamqIL@O_4UtI^D5gjmRRb2KukVJ2dR^OkEommBK@Wc|5oW! zQWwiQFh;wb%zkboT2jsGy&s5cIlESjIdqidZ&8@9FdDJ7tVr)=-w4TT8(Ek|?T+zD z0>pH#Xq%Zs6}L(F7*+EP+Q1FW^2%D=UReo^7>yovyQ{kc9l1=4_$mQ+IzFRSUzhFR@PHW4Q@x*KjUuN7H#_flbYx;CR#zb8I6T5FyqJK$tc zo>#~a0YgTZxWBR2-o*DH(Ub~AltNkwL2UF!L$mhQM3Ju)Od~f&`S{$?-N{^(?|L0r z{?q2_dhe8Bg3LCNvSE^pff8F=g9NS7A9ku1H=$S;(Z4y}L>CJgyVnM~C2{be*DSGf z+}HAMkNZl%wI++Dcw0$XQ<24*BS-mBN{ifBG0o(K?JO3vvt6~7cbZ*DIzglL3mce6r1)PNt``9bF+JM`MUS>cq)c*&T#D689Zu_vzC<&aVzDX$cMRt%VpfXI3q zwF(uq1bIMD*GPo0H_QEq9H=2}Ic(RV(%!`A&skuPj7$;`7Ogms=5sBt3ej>&KP6@@ zzMWf*Yqnf%bLNv2TP+jG84-o~obE*;V6t$xy$-n6zbz7aXEnaG9FD)S-|4jmWRVWj z2OI)nOqGX43!ocRvonKJ5okrc)RxgE+vTb>TNl_~+T-_$iNJQV4=yi{{&0R_t2fV` z-%;YtEAV*R@=E+2#qI7kpPy>Eu&~|VmRID2CmQ$2yhMn`#SyH!t8c*U!!li$NYm-k zTV{O3Z;&R|nd7D|4%j_ZM*U{H5ygruK}$kV>G?R{jlIn5UTSIG1F)-UR&d!fnKV&b zH@okV7$%VyRkl5k(-G3gFpypm`6V&Wo*tK&Y^DB=k+eyXNVZ}NQ+)lf!JMFAXLVEG z&=1gsa$}R(4wu>4BXi;{ve3+)j&rZbag{UeW+!-VS6`1m_kP&{;t%DT&8WF{|5yfz zba_K@D>L*9aa4r3DbiKu^*ZW}hF11ini@wQOQr20w=)OWA!RA*^<3ut32oI}<~nrZ z-s(g{#hTL_Rcrbc{ADUoI0Z4%3kVnwnjyU z3ekPzS(5Uy@yh8hOGlqM@u<5_or>Xc5S;M|cVTv1FDml}g>Y20eP!Jg5@ZIxrgO^(kjT z0o5a`lBkD?nDnLWEvkCEBQ?(Qn3mB|5Snix*9{3Svz(R{#Oiu|*i-CD7%W4ug(jyu zIax4LPbtSicAT-kno0$ak(^H&N`K^Qsmwl_H zs<~G+hn1EN14!FXHt?D^G2!5y6Cd@E?m?Ml)ekFC4$x4uV$WIb?;OrhTKYEUmK_a7 z2zmn{=~8ai|9eg9_y_&%1MI;K_!ldYPG?_mJBB3XI#_4v-_{r0vRFlK`LtHDhN}q! zoJM5ME8?v_oT%*j>}+<7uT;4!RYp!;hjPitEV6-I7bqpOT@2dvaX~yp4+i4F{K?Tk z>iRCWR;%mvs4=9jXJI)Vdg*1T$e|9`b5x5QbRnTv*GIfjQtPyuSh}_<2Fm2Zn0^u+ zNH+ePt&`cSbh+!(!U@sAYGAzC*TYU^^nGY5bQ?(=jA<)AKgzj-V#}D}w zhZiY1#)!NlTaHiy1TaWPUJ+9S6xDOcYG=K5ok~XzHR03;e^{BlxACUPEas?^ER3PT zriLhY57u}4N-xKjWC9u5$RsvGknyh! z_{3^fOlh?1oXBq0IDL(C8j=Lisn6&@>vMuQ0f7y-$UE_aeISiw61oK-vN0i2A!WHb zX*9{LenQgGr|f8nNjm4p^MdnE? z@KP)Q`z0nzUDfvPH>aY}@j)=U=fKcJPR=65OoeG4>Brj#^+n_x5jYtR*~;kJDHa)0 zB=m6?6h(hfni_j0IGbtYFg9dKCXq98BIm-W41JD3eEy;)W$T>ek!S|eV`C@lu-jdZ zlq6Af7m`Rg;dY)~neIWgyg9g>|2pKqUimM)Tt;4GoXn^VKh2i9kss00zs<$}{N9$j zQI6WV#S~^`+D@r6>nJSLFb!sBfwE6IpinxQOX?aT8dA>j4b{Dk=4=pkr&->NAjxW# zk;+BY1-r??6k*;WQ_6Iu)3c}QVmzxy6>FVCsdROQ7YSjJZBQZQDrJb`WLRx4-k53( z`&eoz;H$2-qyVBh- zyMD`-%3p0>ZCozZy(xVbk5moI>HkUxQdU+wCp*!oT)s}u6_jR!qh4erdU*p4h#tV0 zXQ|*se6bBO9ah#(a@Y$aDL$Ll-|;n)c{Ayu+~8Uf@z)s_C3>3RCyjk%+SRGsLX>$% z=6A|DKx~G0t885{xw4gOD84~ktjcNQBvj7+4_ek9&$2cw4Dp7#sPHREIJo8 zPp33dA~5_kQ=~Bqm8FXl46BDkf%mX-&dn)x(at3f8y4%N*4>Ape)`DltsSC&OKql) z4Ap|eI}=pe0MsmW-pW$81Nix#*4)yl&l4x+|j;<|D z_s2fjM6~YaJ?8=W)N+Z#@*%S}7i+=ZPLqA5?H;1t9+Ebj54xGwp2eN~=Nv6VZZ-!f zh8!~@P^~HoF-<}vrQ3GGCR&vtS(c-+w_-NZuq#oi*}CP}m%2M*dVkpj&Gb&32_XAf z+HOv&QQ2?7MX7$JAcwMBL)ki|IoMJ042wM9Zf!ug0r1@9Sx zXFGMI$`&y=Pju*KAA;kw&30(FVP0Bm`unI>=9N;R8J+_kW&?djmz0SNNaNf(tZxk4&QTgFidbn^k#tbMAE z%9cD$b1PFWx{{@+I`h4{l&I`BOz1;)RJNqI-NLBsFc11@NG*0JZ^RrsB;_tU5HTgy zgGyq|smy4hxo2f1qE6S#n4a8c{vK*s2!mb|o{k zLTVkIyi_BJJ$Jptnrd*h+91~S$T#9O=A{aYu07E;g)~G`3ue~Vq1b3d0bAcxU01up z471`~NVHDev4~_6MyfQ{R5=f=dYD*n)M0yA-7ja%Db9XXwHs?xV_lVMY}%wM<*I8^ zm9@94^0l|&O8XYQ?M$jE(#(b_kE-#mdz68y&Ns4Sa;EVFj z@o17V=F!wB*)pV6J|>r2gXSJB8M`IJ=79>3W?3p2e*TmGR9}CWpTR;$INK-;y8LpE z7+sI9_%|FY#kn7$Evi2-5He2b=~C6T9T$2Pu6FnNlXqyA#aAfyq)Yz*l(Ewh@n){b5oHD%h0U1{l?^c-eRyR~ zR_QG_-JE^vjk(QuC1>McxTi%lLUJUusp}i%AZ+I($4F0r)>DqWQxZN_N6ijlv`@pV< zNUAwk0v(n^HOx-RNSGtTL>caC1N84=&XSN0vGl8nF9w{cewr##luDH%4zp=ojwoa~ zTPHH?MahvMAtPNma>&gmpWok4L>uk)vMj2qS*dijM^)rvdo(J5#r83-MvWn3rBdZ8 zQ}-@w&bjI4RhcU`-}BJJLn>!;^G)|I6J)O7^+QAEfp?4JUM^NNCHj;hJ!==)T93{{ zhA{dVL)8{&?cJisD9354=b`FZw7sgJHnB1ov2KyA^pr- z%E<#c(GOC^(D2y{KB6Beyi8HhBanqI#*XyN7&_}oA$*rEr&9t{ryNGo-ENO0(AxP* zZS9=e%;>`2hJ6n;h(1}Kv##vZj9b+8D1Kzc!}Y|oC9;}MlohfMS3vI83O$pr%8V** zrL=KdYNf;C^dDp$aTA3}IosVLFYGRa?3;`;5P1<<_M|8Kd>o=Ft8Pt?n$f84_lPo5 zmTIaT-Z1H{jk3;C6p75VNEaz;RLoQkhP4@I@2EsVM$s{*_*B!^*(mDD$m&#Ca-wqd zBvZX?Mb&PI9iu`=t7;Zc>2Ne@wR%0TBF6NdN&T^gx;j8JG9b#jNECDMRI3X}UuWP- zKR&v*USguxWY76ky??mji1#(uzs2nCIZ4Nl_OXz z!Rw$6p&!CP(s5J8jr|n;YIgCMy*9oM<&zZ&wnf=1g$kACE4xQC z`pMophbosEQqt4eOBb<>x{!*ppUx3IUil>j#{|3WJl>)l*2L#{RBfHQtFqCy?F^qn z+c~+Dd23RX9)#YcC!eCPbzi3s;$AE3-31Z>q6B6DEDY zZ;NCK8NzWx|3uD(b8cnvsQs1_YTub)$ZrLR3Qq?`8JFx3>QC}TGy*Mpct(*Aw@~;P zU8rDB$hqY)vWhagjZc=08BaKmL;He?mB00*w5ado-gPHE4DQKTvp0#U;8s%uH&n8o zr=e2adMiqSo{jo=N2+Gl7;|Lx3YTno%ay%u$-c@SJU$i`sWnnh#&1KjeaQC2+2paB z1OJnSNW#g1jI=D$3`-iC&1RV*coVQ}y$h#f1udCu@o*QYOp$-|quUerQPL^;u`u>q z)KOwfsG{ze=crZtyNuLCWH*F-tv4wCQ(Zov&L{FV&y!rvx{?Zod~t@oMamcBoKKvK zH^DBD7$Y~t+0JGQmCDqa6>TYUV8dOkM515v@;xQVzj!=Fg)v`@6%$ciFeFO(UaA-h ziM}t0-j{fy_c|<6p2TD}XNG6Xfwg9zN?xhGHN>^a{7Ls;AE-}{tB)nzx{1l?pz~hY zKyA~|q-2?hs%&U*sXNOXYANqcm8_XsSEnl0tar(Oi~uUvtwP^fvq5dFy=|4+ER}5U z)_Y_!hr`(iL?fjq8erEzPd7);%S;cw6J|d(Xll3<)66V|L=7qT?fyW(zNI@C^VHhY z#(STCn?B)_Tk&ygYp)+KG5H{GXtD)74VotbPvWtxel|~C=1IV}t>#IvIi|JdDTZ*7;0?M4i_T#UqOD_x5H>5Tx{qrR=h)v5>i z?~Z8*GzN3Y5VV&?5lY&dHnE z{oCY=tLILFEQ*vZjCTmMXxLe0p%+}xn8^ARx(WL5TtwS1uCno6gY3(b#FtJxR=Xso zoBO--@(Ot3ou|>SvkZ5932ki^@ZKAFFJb4sfcJTk_j%^MU~^|H9dR6VZSH9oc2hw~ z?xq9m%3Q^Nn>j>EK5UkF`Gee1zv|?w$))|l>4BbpS7588TBu(Os)0R;XdziUZNFuN zEPl~uwzu}+f-E%QMMGV6wq!V$A27YN>7O5${b; zfE&|EksDTI=$H>k`+JXzmRR0O8zhvrN+|J!n`wA-l9?RUKcJ@rBM*{x`XSgg5NacY z4OLjmP<~e8i&*;FbeZU904Nc@2hBL;i36SW;m?$g$cIhh>0R<4X%8qk?R_p&k~Tls z%Guty&Lf|Kt=sDL4f#_?fv%Qxe#9~<&Hq&9RdpMf;Ufn$)z#PQyA5@BRM%3qyZEGU zr0&)wQrbr>lW$Z5zj~lpJfk+$RVddwyW*>QP`Mgfbx}dTlUt!yWVz_lvoC1No$Peb zmhIU$=^~T0>?y|#pK3%kA=7Oe*0@$9njCqd$FKAcWvYgm3@TV@@QrqeG!q4PvJdvw z0)o1VKRJ1WD{G(9Ov2H0VApDm8`$E#@2r(-6{+8I%p%ZslyEQu^$p#yef> zm<|=`)llyWU9^j}b^2~?U4?$NlF?l+U3#f5^=f{ZU?G(T`nv<9j7ukFcI(#8dt9r` z1NmZA+xhqv4@p>tEsE2cdf0dlj&N0Utf+H`@XKe zvR2hg2HDWZNKTyM=kO#r^2;5J*Ko?2R@7rFR2qDaQC*R9M}Wae(gx*au^c}R|@MKIZ#co0pANOba3_P#_s(ZMEY zq=zi$iK@+K8H#bB-7I0HXrKg<))w^jn*lR5RX~~TJK3TJF}E#ptJe#g|8vZWNBcp_ z2Agv1CtDw4Kbbu*m1a|n{Vrych+WPbn4TmSb*!@3*h_q6FN&-PW&%Yv)#wPuZB)@8 z?R1iqF~_b8*~}ndEYzf^sOXU9xEiHFlRP75sj={-aRXD6qM&Q1x|Y=EIYg=$%ZZolIs!<87J^1#hTvV_2(qg5D z$iYxe(W%ZO@(6LXso3LfTAmP`Sx|jc8Epk4&Vp_``f; zrE`41^)`iBR>;aUGiFDGSv^Dj(BsqUWQmS5i7o8{(I$4d+eCvc67Y4i`gaA*r+mw? z)hCi3sC+189O8qJjQT{`Yd2!D0U0SKMNIKPh)yLJEmh`IPOJ>24#R#fZGvP~)icQC zD2o92?Fm|Ai4+wA=eknmFc;hvD=P`DBwCJ6bhhZ3(kR#vvjuXlHTx!)wA7b3RWX|+ zTPf|Ic9KSf!lRf4>ul{C%#p{4iE@rCWqw8ii9cF%A;TC3ej&AXeM8;G`bJL+yEmNfcY(CqR7G-* z#+rf9c2&m|m%n38P2Cz{jh<5CrdA(+E3X<^eAM10ck-i4inUzYFf@j_u?=%)8|F?M zeu(vv(rdfHB}+|jaM2yRL9aHkUj)QE$=QyHkoGM04L{xI=hq^&ecjxL?FaO9&Rut} zeJ5GNxn;$;eH$r%szR?y0dgL&s?<~4IyUQL_hzXLW+#S<$zalCBV1hpB+P*_OC4ZA zo@!}nQFimB=dkspjTBwx?s}<8n5&}J?F*s`akgloz2&!C?Iz8!>r_uHoscPJYI_#c zQkja@x=oytwSs01nQrU}CY>T?Y(ssdCaV?ddi`}Bl>6V#0{bJwBN^D( zPqqv~^0?W>^bUV&v2<7;7Bz&2yR7+W?J(3##A!G>&^BKw~fNJ@(?Bv8T(QZ4GZ?ANeX0cigm74`+1_l%`Dfut+~;(}o&Z z258>f(vTOZiz4~mB%CfNG)(quSwcpjV!R;?F;80CfsZ-~lui+u+wM^kLA@ePItX^i zl#wE1Dt|w##ie#%+cm&Eo1C=LzSX&x_x39wEB^gZ7GW?QE=TE0#V=oU$D)z?v)tzk z@*?73Qy)(eC)Y8rV1JE#u;0P)7Rh=or#3+9$i zIbC|`-rmm?YKOlKb$n)}vcNWT}zNRmvWV8)a?7Em0FR*=%Je&$ue<)~Sq}LS-4O ziOdMydP4?3)hy4s86keHHiMs|e4oKiGuIH8W4?_039kQq`)TW5u8Fsu zw){|@<(m1@Y0G;!{*rgc{t0tmiN0U<<$9`jV{rhjMy<9uE4syA2j%f{CVt(T@|u>G+7^$;Q@vI%2$Zv(D*Omhkg1sQfFSO{rn2~&AYmJ+?e10 zJmWWuSR|t$IZunH2YL|5%I9OTJ<1HwxL>jaI9QO-Ya1m@RG{0x$DOe*NFIm7+ z!|ac*wfb(P?)AuTH>@>hT}UNr7S&WXNQ$`E>Y-Bw`q|3Lje)kx7UNxV_dVMEOLV*8 zw%W#Uk^MVrYzL1yk+-_NG3@b3ZQjC6JHG%~-Co()%76S7+98UU!AlUnZYS>I(@Ws~ zCB{E#^k0hbwN<*Ke*N*pKPFHyS>TT+d<9XV{ZWR`^G6;&?;m;i^8U!fm!CX*jbU$I zOJhGj6DdC*?rUMq05cR?1yF7GT`t^qxaVs;IJ7ib>p{J}wX&wRq@|^^cR>GWrng1Z zIV?V9Md0>IuWn#&y6EsFwmlaawo9yirS(}@jA9DEv>$)y`03Vb;UWElhwl>Qe~IG% z!^_{ao(oQZ|1I*D)_1{?iYWsBTjD3J_n&h7r1k$(j-T`%{*>btDN>oC_@uFTA5tfhRbhhpw99E4-;XRIdAGu9riF|M@yXRQ6+XRJxC zom|6wAI&r7n)&uL&rTI)cagl_0wEp-aA>#Dyw9JcE@oj4N*)IycDjd?Blb-uh_FPoARKIF-VwaCeN??u-ZD{N5| z7{!Gh;01KQ=1E(+w(}?MLbB{!qSNnR^zb>tCFtG+>E?@cc|Tjc&X-y8%}XlZi-@(8 zU+2nl&UbIM1eP;9Sh^RC$&=3aBK=*G-cb-5L-zNgat=Y^ON>n;cISKb99lm6yVu>| zXXPU0A+}uMn)AKT(N9+P4)olie+DT&Aa*J{=H1mCd%`9kwhpr0j3t3G9T|1claB^e zevNXiIS3;XZYR8UrjERyD-%&(3uA|O3#vq79JBrNc;hs(Q3KBRr21KmMdKS;qo5R)XwZwn<0w-ba!|D*PcjQx#){`nl3+rI68gFkRF{+s-hkp7pX zk2cAa7(U~EoP1w^>$Bxw(irxcD#}x27?Ty_a*j!X#PG$~&#Tnurp+h4dHpY7%0M5u zHlGXg_)qv*ksOk2Ft-cy*e|GLZOQz$=MBG?>c>Agx7S*Lw*MY?kPJEd^L|r!+PE1nAeu2{-C783n7m0nA!X;XF>eHfX zdR=V4o$I@&;7&HJbDDv#-kjs&7<9rXt#ur`m{c zmiYqYB`5PG2F$i$oA=OPU}a!{9Xj!ijQzdP5sza&KXSyG=~_AgaK5vfMtAAszee(x zC!y!$Sa;+-tIy>ah`1luS988b-7mH~Fx0#a_VF(|NgVrywBP1bn00L0W*f4dV9s|E z-2R?a9$t^>AH_JY+crIIC_$@aS0+n#WaWxKsM}l9=Gg9gJ;@C@@t?|13kch$8;a8GdnJpICAs_u~yExPLL@Kc}pS6HfROh7q>wk?-@#$Fr%21IA3^ z#>pnu{WwDr*CXzG3MGA{`>bmtlDSwqsL^^U#!B3+6aHEDJs#WsJe@CGn%jQ9U83TH z;h1+*KP6OcI$ZX5uUq0HOQ|`MC%y)a3%=ujiLU0QC(aP);wPU)Y2D&tTp4rdyMF9V@SR|7Y3P3l9qPdH~~e6WwYZ zpQQeK@U*+#m_(i|T1aYF0+7spv0gpE4~kPzl706SX#+ZXn3`8iN$nR#mOos`dUF50 zvG!w2vq_WK|C9RfHY+RU4Y=({Qu}f8ojYyCiKO_Z>G+-uabqJE$kMm!rZ&JH+ z`R`>qke$qWIBg^mS=~}pImimao@fA)`5!SfSN!tg^2a5WXs5s=^M9W3=amOLb-B>O zn=^bS)?~gt&t{L|kY2NRgg{CweK#pk7k&$gJ%zdZS7hb!6l{3p|yy0$@bq< zWcp4q{VO9d=eyC>*^BNRVdIb!e%-&a)nnzMb#iQvRwz043!NT9LZl+!lXr(5_dV|F z$O66?-y{CVj(5mxg?L6 zUnz*4Ut#%Nb-h!m#7|mXXzDgbYSG&Tgn#zf-IF+WzNDz>KrF!jVi{_St}kAfw=h31 z%Kcfoy@mM^mFDcbi}F8K7r8*M7vO$;{g7;FzBftR{8IU!P(Qu!w!K`p?F$UgK~&cz=feDm~;ldNxWI>++K(HR=0w=B;{Ty60}gU|Yx z3ocK-5O0#k zU0%LW|LNQQfAycf@k{4_W4O45gZ7xj4dl1fa;!vLZ#5{>qtSg>sFf}uB)AyygOzUV z>$fLd=l83o&0XnS^NbD{AH7ibJ#p%?S^4M%x$n_&cZd;I5Lt&D$GJDg{u+_QgVDQJFHOAdZ( z<$Ml(P@o)(#V;uH(<`!C)5SC@=UDQ?M*)tzK-Q*8683HELIS(c|{I`E_k~fxFOMeQnV-WhZQ#rl+dR2E6z()X zioh04Uv~@V-Z<%w^ZHNngWL#DyiD1ru5jF)oajP{sN>8U^Mf1P^s!AY10UYVp)NVm z!<@{aGfXLQBpN@vDrY@%%9K8;vcsNU;#bb@)W4@L2jO(9L_&YKi>f&(HK`CGl_)mmPhXzG&7?dD%8 zrG<-sa`ZYc%pWIy^RLN#k1@d4yZ`#+7xw+`n+J7$C28SY+Ho~)?-QA}%k=ar^Zxi+ z!)tFfylZub{+qJDPk+_CKWp1Nxbj23w|(Qv>u!JRhyGUnPOqX=^7mWY{Ib=5^P?M2 zyej84D`!4+`uiK&R+lZ@qgz#<;H%!ad+3}S4%jI#LWNlyklohxlpZs&*~Moe|O)L zl_zxk@B7{_R_pgmpII%Y_nft?-9LNQ8sxf2Cjc2W0 zcb~PUtN(XhueoD(cy|!5#CSZ{F#Fv~+ip(NS?g)yFLuV0m`il)rFg!P^mzI0XRRmd z&RXBEKWp6!o2y>@>vs!u_q~|=^V+l4XKT({Pp-eTYiz@8d;4yi{q8T5nEOEzbIHQ- zjklh)bls8gUu~f|!84CmIgfU{gu~GNx*`Lb6W53(y<9NMJGn;5UA#^hTn#{h(c-L}4>vP!m+UI%Cb|6+Bagnz} z=1e`g*U;Rv%2!r2Hr&?D`UEplO#ZzCBlCUtMeHXEAh~;t8ZP<(pN8`MmfJYVC*Fq_ z(|yl^-A5kwq<3=vJ0kKRriI}y>1v?8(rf2hy3J8dEyXSNdK{K!7la4s-&DV~e%;pk zIg_x`UL_hUgBRd_p*c0z)DM*;Ik8Y(PRW_Pwo7kYlCyf1+ zbpEsb!c(1xU-q1}k82m#AXgXHCax;3Vy;ZCv#Ec&*An9QFC))cWq(5zTmFKLXl`sC4h1&~p z*Go7)Tyf4CEk9?Sxb@Pm)oW+ldlVTby0>-B>~}v;VlL61Jih~TcYOYwb^l>x_r-Ho z$Cu7ocOSw%xbwjOuIt_}%nt9<#3?Zz4Uf)#cigsn3|UMNf3b7)bF&yH5t0VIWbAF#=9wyej$1VPuA7aqG z=UE=iZtfRuUjmTC{-yVi=Ig)A3VG5#%o@G)WOkrpdNMCj|0*tgBAE+>FQva@#;RJt zwRZt##GS)jC%Be&8h2OQ?6SGr<`J8*exFG4Zb?^s_*V1WmGDm7*q!9vVcw}NGuHI| zgb5zA?=xYseJ|gt?E6h{7uR0<`3QW{zCVk(nB-HndHwAjC6V6@aEejHi2lxL3R2L_ z50sd57Cg$WIv<&_0$hi<M>&DpA1e|2-0Z`@sH6HQ~lxu5{1yRvA|_ z*AUkT@5Z?1uy3DIP^r?|p0~2NMq8h^#)tBY$F*9jltg0_6cf9HI5S>@-C z>=%*r<@AY|?^-;Um7KSxi_cp}xejve^*Ni+;`pz_MEp)!r#L)ygM2=Z)Na3kNZmAU(fq5z^}tG-rdLdyIc)ySQ{X3yn5j0+{lZ^VZTYlU7_^T)Vjra~@EZ?~Xx%P6oc`qW-{*=h90E6)!lZyhsBTcz{XU|({Tzk02xoVz6=3Hs#NK>xy z-;;*0297_=JM3I`1v>1s=+)2t@tEh>Z!hHji0$S+XeX^ktnU2+_bd6nD!-txsJNu` zmacHxf5Tgr zW!$)2eo#CsJ15ue@#g98OBY=cc>vZf$GlXBj%X zy6@i-=;`h2e;^nN4{Y5wxcxz~Y{GGKu0$f`x|iMJzE`Plyh^E&A52<4?nj@Vw1(j% z+%J4)(h9tty6xFXtL7a_)xblr8P2?0sdvEedzAVnoP3{B$6?j`l{yR0d_bw!{ch5l z_@Gjsf@-f)x1F7|mciq2$KNWI_S~fPG(2<;|NdU7C*Z+-N=?IMA0?2#pR~q4uGEdt zwIBb5pHONi9E6X;qwpBa{G?Ln;SRWLX3{zatKp`9P^uTEeM+gf!TLv(+7FMwr=a?b zQcuIx@C-Zz7d<~|?fNX|fWi~77*_qGQtRMB7=Y;qm3k2Fg8v8Z{hU%Cgv%aP>M__4 z{~M0MwDXhJWuI3nAMSv6!*RF+Esh=-8X`Pr*YU#^QTFpOI$_p!gj{h+27la$`gooe^ zJOTIr59$1hlUCUYrQQlhU_V^)E7BA0f~#M7(pvg!rAjY5X&rz&;gV_Gfs^o>%Xxm5 z`~|yU4XpZ|QXhb$a13UiC46uvbS*w<6+frcy>Rt8(pR6f7A;CqLvR>= z46c58iW-G!uS`)tf%%uEsAWqC-{mPP3}@hf!09VelzPocYtxk}DjOb!cfGt9 zvL(0!YpzOBPeJwC6xDSV=HUn6LHGn*a&?OOHSB^*UVGAd5|+WT*AZTL5Y}9coUTbx zkG_s@z+c0sVc|8z@AWC_9dH^RgubOI>dM!jw6d;EQTcEfRzUTJ6g3W;-~>Db&%j03 zrKl^Gk}qH>T$D~YVHbQiRBudC!E4E{ueggJq5Uw|$w9derUC8yu6jcwi zmZzw#a2$@n{1qwcakv{!!x@-=J@U9IMYX{RcmN*0IYoUJre~$78MqT(e*@vpPEqS% z7YxI*@GNZ3!QHnYPx#Jdn9og7H)N1*Zo&bdgcGpLlcLgZM2_&mOv2|)QBTADuyzIh z<)x_AHxWMg7|hSdpPR||@XJ}qv4HTv5%{+3lh)ORDe8O<`LBq0B~P8OcD_T5H4DWcrhq^MnR7yLP#gqIcL z?gspWS+yx@Cp-kFVSaszx~7D1!!Fo=J8~!`AH!b@8&lL(Z$a2;}PCZE(34!8-bds5W*8i)rx2bZ*xPK~7V7SbCY8bppw z$n(JzwF*|y?tKi74N<=2{X6mhPSXFqnA?OL--kVT3?Wr*XFvdBehP%IjyykN1;4@R|om?}NxUNcn_kL&X1c)N_N> z1F-4sxcg{|digs^SNI?ALSCPz{@aawzLcVd;ZZmOcOOQ6u<4&t)LY+6`}E}$^?CRN zeC_+lM_)-%A-D%V0?Wq8Z|^5v;BwgX&*TsI1Uv?dA4^f0d&sA73O0W=MQ#2Yby@z#IOaa`rDN>NOw6J$U&?2=|keTd4juMP0iO_hArD!_UF4Z>6YT z!sD>uqtpZ6PEotzQTPp5HIAI%5t#ci;`trY86Jcmhne4{e87G1+K-dY|CXYf;qIr9 z4_x%a6mJ@kfcKv6Hy5$l4f&H-RIQjZ>yg!qoz73yzmiz_# z7p1DcN6B9=PgR45kSF{uJPLPzfqeRkRCU>5!VmYun#)tw8@^0<;k{o$&Wo`(M!ew^ zoPdk|8FQ~nRrkR|F!eFwk(R2if(PJgcoyCPyRJx8Tfa&=U74!h4ex`Wgh$}jN2mv1 zovPjecfe_Q9Nzmi^2d@?H4gW~cRx-#T$QRazm7jwrz#(uhM7;0uCGf~0eA!+gv+iW z{NJD+fxF-g{0;1XJ>mT(`4)Z)<}XcE#s5M%fFFbE+Ek^UB%bg$-=Vy{0rTIb-hwy$ z8}$La_bBD^x>Oa0{m}b;{CiWXdgR|J zCvfs7r1P73o}gZUD}PG3;8Q=toGVq`|6ha)s$Y=a@B>fd{`ILU>zBwIKK?)0zadp^ z`W5!!)UUA*cTQseEyRBc`|#i?;t#{8Nrz>`_qUjXN6(PoGmz`E$O+b*CB5L{bI9|? zRQ2TV$&c`z&y(+$r>Y8zd=67nrmSP|L#b0%ab~J=FPgIU!Y5xoWu1lhzH-Xiv?5id zUp{3Wfj?P1Wi7i2`J|zk0U-*JD3BRk^OkKK$YvrmUqosp^|>H~bNtfWL(I<)*5`ZzO#1vo756q^if@G58c* z=0%RzPgz-cq{~~TtPyx-8R3R+$e6MM`KjusH%?hcVK{Tjau*%Bb=EUw^}~1PVIM9lzQ?NRrm6!gu@6_S#y)(i9Q(JB57uHIs!Hs`53Iv}8Tp_J`|$BrK+?r@q^=AN&oeH-%dQ>$V0>zjy^nPbycORHE*A?o`gTyF=bU%r>bAW zGw>YT`Bu{D&!())ZX+GxFuVy~U6ZOx;a>Qzoyc_q`RASFyIRuc{}5iN{t`LYrK)4^ zB3w}YHTLSszweo{cELyB4D5X`;krFlb-ZuNIsp&9pZwK8{@FwRgJmC>vYHynHy@m` z#^LB*+-)M=KSVx*IU`e+Ya{jO-%nX#_-^DOHW_C*1J+ zpCo#@{O?cq>&rDhBZqo4}@`d5gBPZDK1?04ucz`LJ zx!seh-Ug4rz*or+_abLF3WtyI+>)vug-^g=!}|NkpI_q{7Qt|9syYIngujGWw~?-J z9G-X_xwfaOiLXytWANAC#62JB^RJ{6{Q0-Zul`i^rtgx@9mEG7gVS)V6L-Idyt-0V z^AC{+{N*vyvzz=rfxoc-XSjDi>G)q$);@UP7sPi9`R~7xBiwaj%32*Do&GQJfh(uT zhdq?n)8r4R&LAiFlV{P5_NJ;s&k+yU{5M1J#>tAuodKx~y z_>|>)0Q+gDtfO$|%2U>|5cXbu${K+O;3Vu`a>_~%6CZd4?z`%gl|PWGc3geRYT8D- z2lv4-I0N^*4tEDr)mvYG${L3^EyezJ$^#5ML^}fS8%kA6uRTRSH&v~Ju7^oKxasZG z_irFP@N?G@o*k59xCc(BpR&^ajCT4>r>vbY_09MP(_GlQhkh>HML&AxdfpGwZ_PMm zWzr8VgTvBqxbc*A=r4&UthpC`*K*uxL0^-3%GwLl;V8_4M_?Iz3f90Auo=$409g{fz9wB48SMgFr0uRa2k%nMSkJ~m%{XH?z_J{| z14p2{gZRNN*qn&cJ;zE$2N)WpGgd|KU>D46|SWu7*Rf2@b0g9bq~Q!z{Q9*1-KR08hXnI32=0xG0Q!a48&xS#S)lhU2gaPQWfW35Vbe+zrzT za2KY-!!QfF*=U>t18d5V$3w^i9)an%l8!I{7Y*S)%z{HJ3HQVJ3rFDuJTA|x$Ukr68M@){YVrvj zhhs3kocP1EHTbiGaKhbi1|EdtYmw`p;ZG&;eFx!LM|fe{dh#ipft&su_p8WvFuj_5 z2g~3X9D+yT2+Z8c`x^2i9Dyg`7+mxh*xP`Aa0s4&6L9xCk$Wxg;Sf9u$KfTmtKj6qcl!y1=e;elDgrD%k;rq$Yy9q}C_h8@w!tq|-!wNVG z?}HOC3~Pe83y0tVI0m19FPEBOs(!KYvu9NR>BoP>K|+IHNBS?~$@4wrlo zcORskfkO`=UpNAX;3zx-$6?i8%)@3l0|#N&5c!aKtRc7*j=+342J2zX!^8`wzYY0) zi1%hv5!50{6gCcmR&UF*pv7!U^~^oP=j# z`iBVrBbbN%aOCg!4kzGQI0@4}jlUz*Q*aVC!e(oP8eipQB!YBX9&}JxczD zV=(^^@%TLT51fIcaQG1E0n@)g{`>;=zDRn*z(4a|o?+S-asM&=g~PB5rXRsR%z{Vc zJA4YJeU0>jHSn@8As^_5&5u)mz)`pxmVKRY!3ntfFy_8NzJ_CP9FD`|u=$(#|4)2} znQ#PFz)`pfj>7<)fIHv}9D(WoLOl$}o}@qfWzqrGz~O(zADH$n{DDJo(N}m6m%<5H z470wCoL~(M!}RYEKiCXs;0RnYhWjuJPQcZ05;nmZ*ag$ROa6rEa5o%(e?Yjt$}`*t z)1D$e^dD2M z3&-FjO#2!6;BoB1Ww05R!C}}0Ctv^uevTZ!jyt~~U&G0#kqaF9Z`^+ZcYaAYVDtar z-Zyan1mS~ezb2o+=Ko9hzlpoB3y#4dI01LV8Mq&&PZEAu2FGDDJPwE888`|r`xo*R zOotQD4Tn$SE*ynJa18E-HB+?n@*PgX8Mx$0{5eH_g;~>>hc$3F44lS1oPp{8%J<(Q ze>eem!m(#4KQQnt>G>_f1$}TB4#IJ`4^F^Ca0WgJ)6bHg-^L!yg2S*1j>2X*0SDpG zbI1XvpCjII1TGrK-VFZ1akvA{z!8}BJo17QaLIQF-+A1H!xrIyX(`jz)!)S**bK{3 zr>*^P1|F67FPmoGhxCM5ux8P;RRxD&GfaE=v~?Ud!x?!GmmVctFdwG9V%qA0S#Sre zfn#t8Uj047^~!0>{e8Y)hI?@4Rnu0@4{$GS+DiK&@0Uzln|{pmYo@KeFaSs4Fnkh@ z!l7e??<(AdX|J8OreX8z*vtJNyoXtE;+kp82WMc_1nypod$0x`5?+V7pW+@Igz4#g zhgok#4zLDJ!f|-n&u|y|;KZAzt(|ZNjveRwo2RV_I0>KlFXZhaJa94tIsBY>=T2LP zVOkOK{sr!rPFn}y%-U(|%ztCQV%n$LZ>^|IwLv7R6qLcXNo3<*19mGf2 z#dnx>Ki{WdVA@&@CwoXoINCRD9f2bcAm>vs#CPEU-{I&s!UrcGM2^#h<6+`?n)ty9 zSo5}NYtJ+A?Z_97K=-rwy94)rhxtF7wgPbI9n-7@#N3}xTW8?}tT;A0eN-3_as0=>=y# zJ8d0=>5ooZnTv1_*1+`7lWwpXE`2%XVKYoWL^$9uRIk8aI0i?)h@4)@JnNV657vw! z*UQjbKF0gYv3G=LSoU?oy_j&pd^iC&!Sp9cUpNf+!_jXbH#qi9!gmGVpF|Ev0dd;K&sD z4vxVQH~|mCw9~|ADe;2KVBj~z9}dHPa1@Tgad-?)!ZY&xTl~8gduK==IQcC0-+-R@ zchgoFj=-nj1YC9<-_Ig1nDrd_UHE&_IURpyh##DUqe2VwZ^ZqVowoMEvPGw@qj2=) zr>!d1B~8Bav~?IZUw+zhznS>F>a=wLmR)h$a=Cc^f25rcTx3<<|7V9$QAR|iL>+Zh zRLsdRF-fOnmEC1`M@2#TxD5qT(hTYj^cF*tqJ@*b=E`PLs^Lp*R=YGyP-}C?6bI!eUDBPhoLx0f@m6hwm z2zNa8U=XHYD|8>eLv=u3@eWmY0_^~{z~tL@s5DHxeTQl|k$8_FK4HlYRZ>d$Be4hF zN9|CJ&~x+-H3$>Xa}xRSVizW1FHD@cL$#euxt@ew=s$Uf3Y>yJ*bEb}14d8Tp;9mf zi^}j(>HTPTML>^9RLpudHBIE(mNcc=jv-n2uFyoYcPQ7@JF+d@9yOF4gnbe)6$htbc) z9}K(?K7tM-Z~#VO<9S>^wnHUh6i&hzbX5`0#k)Pwi0g3n-tb zDW7Wc^EuK1eV-?NYls&HVE{J6NY@TE0h7<}P>yw^K5mj9ogV zYOlfWRfL1l8>duN5H?P!7!0&bsnTnS=k6&LZy?+~Q>x--?6poQ?=7U`-YNF$xo#sJ z&De(xt%Q3R`!ERO*Kyy3!!QiTVFYGi6uPhHz6`xE4l7^+)Lb7;J!X*a8!9D@?*DOu=55g?+clJYz~Vg@_M^p%1o0KkSA9*bjp+0Yh*M zhN0&}#1G416js9+tcP(Jf(h6LQ?LVOVGndaPQIZB4nrRthklrW0qDM+cwq&M!WtNZ zK^TY4FabBiB4dAD1YdK-7ol#m6L1hF;V4YO6wE@$UBur(zlR=J27S;E{je4WU?U8|Rv3a27=~Ri0{dVT4#5~q z!Z=K{5I-D)NtlKyn146%Ll1O6NjrjJSbPueup9(v{-=lshT$ZP zL)S-ehb7S8Nj<_atb%b^C+@IG+&_ywafj_N0=r=p_QM#gZY3P-fe9FgNjMBsa2#e~ z2D+c7-``6)!V2hvHP8=(Fai@W1zq=1uAifvVG3@&pL9g&k74}55RAe$7=s-!4trn% z#$gf;!xS8cS(t(D&(j|n4?WNeeXs(Co}u0t7u{c=d_RU=*bTFA7zVm%cQ6Xe+OP{V zF#a6n^KsJmMbZ!b-L#_zu?NdG!7tOEU<~pj4@U|XL*G|umoNm|VGPE^9hN^td_A-; z7=z8w{Z;(I5cFsB3VSdPV{-j#(j(V!T&_nbuP<^9J<$If#!b0~b#nb%^4E>M z-;>|}!Tz79pC955$Drpm>H`L0$&bh<9DkAY{24pHAp98p5{6+K#^w5#xWjH3_zUTQ zNf;f*-s|)i7=alWhmlvw=U*u&7#znA^#2Wizrrp|!xSw3HST|>y}>AKf#H9UZ@Gp; za{W*IjgXHwxF5g-jKJi-DOVWSM)~~)|5J<`Fb+qB)8y~BFpax#hI)pHowy5k;r=`9 zWXM0v?j{|hkow6OTEGv^h5tX!ovh?fkA~G z7;sFhA#qze(1@YRuj6owC*RvF>p=zk$!#nY-4#@;rq zyyN5>R>1h%i3f&{m{!9u3-kX*eo9CeOu!nLJaSq^ghx%QIP@Pqt&0E7HLQkV&$J4| z#4*z<3A1n#rjDIf{(q4FenM(AHZ ztp;GEmU7xhI_fB2h5P0Bhrz3{<6s?m9p$`=^;^TVYKPGek{&1PpeC-N|JG@haItO) zO{>2BSl@k!dSibpe#f*53GbrZ4`6-s5%L9-t)wfTby0X)jl;x8Ddz&hwUG}PdV+Qd zJ)fbx+}MALbPJy*eJ}+FVD^iY@4=+!tKAkiOF-(|%A0_}!kjVe)U&%I7DYf1g$jFz^rZ3sV!*DhoaT z!XEnu?l-2D`~Bn>R>M?^{J`YDsW%wjj(zqKf;%V=_7U7u(`pRHVKMs%@oB=bkC51j z9rh7CyT~sL!A2N|?a-Ye|LiLyR;5*NE%68W09iLV)m^~q_QZRZl{#n<1%F-&$dOizlSjWfTpH}`W z$VXLLMPPJwS|x>R(wr4QJ+Div5$LN)D|bEdtWT?Y=--%D?Jx?vq5C5I!7y~NAKIjCtm2fo^aQbKA40- z7;8wY4j8yG&HKvm=Cmqd-ynQzS~Wp`hrk>3npJrs|gtSEB0chmBA^*^~8+Vw1gL0jve(xmR`_d`|`4v6uN4RQ+ zbt250VLeFt_T!9N7fOp$J3dPe!aM*4Tp zs2&({a`y7`ggbDj>V%=gcBJjlCh?!OQ`Phm?!29vE3RAEWW?=xjf6Up?&;whb z4{n8i7==OD3&U^_#^5N7!xT(F2lbqU#V`xYpnG7a@2zKCGsaa z?1h0r!qYCp&+t(4E}7V>J$Ear%DSG)X&G^E0m+~ z7q|<5i8~ApbM7|nJp3xx!e3Lro8WIq2Mmpo4;Xx7r>fped}-1NJ&JOI0rxId_7M3z zVwVcT$g#Ur0>)0;rIPfU#CvwJJ}3M+xWhmV?!vlV%Da_#8g{8B=nw5uaTvU37wc>6 zKp%|Xze}~j)I+<}2#h{Ve2?JoQ`m#aj$LXPW}n`rNiNP{_ZCo&!T^n^P3s35+5fV zOl~3^<5gr!M!6ZU0uN_YK==s$zC^lUG4wo@QEku%JD|UlGrWbL&2Y{N{y&#d5g30q z!#OLY{gR7 z@)&3J{)Biqvo;AM-MdxY%dmGh?@y8cIPv_H@I#~vW`DI?#fESn!T$e|j#2Ex&>xBa zXSgScABM+v^S%=N`)(D6?up$h4Ws|utwIUf#~ZuVIE<$#msg}dcB>H>n%b=bzaV{S z$`iVG5&oCt54J-e?1p~W4+Ag(gRp9Za?0#hebB#$GlzdeInI(k=-Ep-|CV_6aYivr zI`$~X?+EYQqgr4*k26SNct5U3iRYj_Dg{G@dsO4^33mwRz5W5a#hj7(N8%~jqk3WB zm_4d2iG45U^TOcCoYDIy(tX+<6@gLT9_4xsowIsN(&(4%;XO|L!%FCb0qBPfFaTR% z2yTTD7==;T3uAB)#^ESTz!XeEM<4A27DIm>=Xk;h48SC8f>{`bfy+577KY#ejKU<0 z!%3Ke-L(I}6~qT)a2$HBBtP_n2u#C3aF6PvKZLG>wCmLM_@`ZGZ{Vy=+Hd%#J-kOq zK3geA+G*@Q>`40zlYiP%;$!5S_7r?@kMdKG;Z1vZUkv*&4WlrBm~=r8jBX}hat*6t z64s0U5akVnTgVUee1h=e4$EG}eJkmKG1v^_a5GH8PMCr*n1ut-{qP<&0zGg7`d}9N zVbQP1H!OugSP4Tg0K>2WMqmq!!mTj=2;~A3a1oN|Jt zFqqk+T48L@9yKJK-J>!vl{c#bf1@1tpH)#9DwHp49Jf*$Xzio@9PvnmUduw;UCoG_~@geT9cHW>2Fsu7rd*Q_f2C;Gc* zRS+iMH>-MKFfglJ|H9uzv#JS3;bs`ComCSsektjFgM3{@dSNIyt43k=TH;HgUq^f} z0Bd3L`dQTu-3_xU2K{hI*f^_-|4lwVII9|==Qi>QeJ}z2ADUI=+pzN>{$ZkhR(ZB# z?+Nk&15eGW6pX{tN#gIEWj_%8v$LuLdY+k89IEB;!D1Nw0`b6P*R1M>iDzfkn7DTn z&lLIo>a6O6VK@Xs&y$~N?8RnPJ@kEjR&_$pH^?t^e{+_7LhO8dRwZHNd!%Cq{rl7# z48&(u4~+bHR{3_4pO5a)u`i z6l7IVmhw3=s{%0W$*L~7hH)78;=Y%3pO|GolX5wUvsYpKl&o^^BVDIvRRi>&&AFn` za}MXA$~AN={GXRqtuP+Qssv14L^>S&9=R5K!ppD+Q&(n{cNM=Mh7~Y$6=#*g;5CGU z5jX}t*W>QwJOdaI-bnl~(U?^&(9IdG5g378Fb4Z!h%;YPqC;06=Lv9TYb6Z9TIjol z_@EzliaU(KFdT$2n1r5NIp5SpJa=bR2aMlC`k?RAq-Q_E!A2N_Rr{lNkPhgFeJ}>y z2ar$bgYGBs2R*P3`d}0E!!V4&UKodiF#MUU%D@P8=M&#kgoi;`2jiWj8@fN6Rm0E& zGcfwOtZF`x>(6sWEet(FxgA8fFW?_WVMh2I{tEbAKHLo5U!?xXj}Jy9U(i85!rfW+ zl}R5Q!CxFszy!>~(3fa8ZrouI#$huIewnjwVH6f0OuhHeK4I{y)PEu2VH5;UX5w2nEx1^tZ zCx1sgq~HJhEa%OU-q*<|OuRvP9EF{KQ;skOeMeLO+bJ&?o+SMqI7R(J&kX$*CU=ql zW5~yD!oln;c8`Ut_No!+$=j2u_bS(ET*F4_K4PyLlxtY(G;`&7F!Q?wQs~EaZBc0`x6Rd&}*aQ=>9VTHnOu>Gbg$d~P?Nwti z_|Cnm?F{UmPPxM*?17$lQSR@CoO|3QO1BK`{OR1zOd!b!P) z?_O1V7T2&B2G8LPX3n`u!e$secdr_jYgm3Z*M7poB%GA%_YuC5e8659ct7Fa%Qb9< zf%6D2*RcE?uB!+S6L3oKJW^*RUA|E+D*I!}9lWT}^lxUqiXVx*a~(0wuO3r1n(YRadU_66fG0|S>3{(Rzt{V;GT z;Vy$(J}`-GmSNYCY5!*=0k zNe}Hi4D)HvG1y4HJx_DSH|dUk4xRM6pTQsg{m^p-_4x(LA12`d3_VLbfe~18C47$j zz*LOx#4gPKl>U7c?!)8{#zrZ}t0~{Va=tiBzCk@*!}T=v0V7$)l_36I z`&1Z)3pqy{dJf&ELf4YMBRFdshL7Yt=uCXYa+dH0A^b_xB3?B-%a{q62@T`jzaf6oNW#xu>Mx;eqeh7dvO0E^$Q~~43n@E`nvaVUI*!c z!_fUD$_IvE{zvc!OJVTKqz^`69QwaPxwMjgxD|$;Cmf8z%6oDDI_&~xzqLqYmIF6f6TxD|Rhn>`AHFb<Ad<+zRZ0Yg*N--GDW`&2DV!U&9}@ee&Sl$%`dBR`vn zAJ)PoY=lAn+G+=k!d~cGrBp(gr&Jb3pl>tjg{?5;Qfd&!;3!PNl(<93L)6QDN)>Z#~0A}GUQ_nBqN4@(n!?lg`7Hs)n9orRrg^!}zSa?^4IA)}mEM zyAQ~3U&T4)$R7Un3~f^UcC|?ST))tm*IHces`E8E#j(YDq z&MZ9vRfiA4k}aIWE`s?HyDj{yLU%}b^CQN2Ez{BYjwyA3MeE{whfV84Ye(D9;%|uW z5wwFX8n3fCw%Wq-s+ME3O>>doHnf8*VN1}$Xy;foA6gIE85XSyZNwI~4y}Q5JKEx} z2`z+XO>-En3C(TsCuQGg)4EN2R)76yL7Tq>TD?tUi_uYsmMdy0XSRuS`VO?jo9{I2 z6<9P6n%J|JX*rtM%eVNeMyo}$mLF3PN5JNf+nA%qrqQ(>)i$jItqRSWz8*Bc&0id? z(&ld%t-|JS9If2uFN5Z@`E%!S-aVQ%A6~Rlo4*P)ugzW!ng`8Vzd^JTo7Rk0Y|}QQ zb(Kvm$ZscF)TYJII&InjT8B*=L2I{Z@;Az3KV4X+S+pKBYnqE(ob8Wh?SrLgU1(=o z>bw#yfws}21<>+s<hyYWo%k6TH2-!qD`V%+si0g^pu5t zI)&DWW^K<7GT)764O@)Xi)QWTWoS`b9DcM;TUu(-I&4}aT07d?EM?Vd+5`Hd$3HH_ zo;599XkyQ*^`VJ9t2Trdv1v)Pt!UP|oJ8AlUxce9T;#t9 z*G#y+{~}xu;gbJFxG}=HILq}vEte7+kMF+-S4+6M|03L0!iE3CaMD)>2)FsfDRqpr zYfE1lMUSA<-StQMS_*BeO>@veCA`&NFw`hK}9-F^fv_YG{MzmqH zLQB|Iw1iEIpbep&VDZ<5HjZ|ZMe9RzlrGeU&^$IRiB^eb&D$heg-vrY=_$8qC1^5# zv4-`b$^6BtRiRbev^q4IzgYb>p-KO=YGE{)zgV?)v_A4{)wc+36Q8ixn1#^$dat=gtlqgC0odNjXH3!zoov^KN~o7REWW=l&C zTG*z=(OPZVFj|XE8%JxlX&JPTO>;9bXtHTuv__j&f!1KtYS4llGd zo7RBVVbfaB+HKlaw1`cMqHVQly=a?l+Mw9u+-_^z9Tj^vErnKZ3+p(9`mkxmXtg%2 z3@u>O{Ae{ctro2s?MTab)o9w|7Og)r7Pl^8FS3NaF4LYhZ+&Q0ws?oo{5CC#R*5FV zrFfa{CUtyY+5;5u|<=6 za5Y*Hn*AOeTq1n4Ej&qaY&OGN%b^p^ZHY(x#nAH6Bu@E=HelMbY9nZpKdUx@Cgo+- zvS?ENR;}nTqdu)#DVp>Lt5%5?v}pmfCY#oP)?(9I(AsR;RL8n zYtu&2;x;XXHiTv^XUE~pS1eiyWm=5Z#oq-&8AJDg>70Et<|O#F~M)KX{Bh*HmwpZWYYp@O*X9otPP+~n;BzRNoB@`DQVSIc^U z%W>QqmT?mgeapCcaLcE?treSk9CTL6KqzBUC2oG)Fs(llPk{ew&`uR4Ame7e9yi6U ziT`}0`6O{$U0AfbF#ozj42iAHxK-gsm(+VrqIHUYY@H<`qLF=_? z6KK*ut@g5LG9FpAA|`G!|FCMMXbouAIa4K?+^?)!0IlDqHK2{7S=(0&+L%q-ik7r# zQM4NV?u|8UFPi*K9IG~nR%O#h(fl?og;r_P9Bi^x*tB9a$*(nzGBl6PpC7Hnrq!Yq z+q6csBAeEVX1_l~(CqhzE;Rf7p%2Y|e;7iu-yf1_JwIGnR+DJ<@!Z9Y-aej}pjpRr zc^2kFlkt2V-;MTt2fb`f!CG2*KqTC2i0>4hugD(bW6qkwl1KA47J4JDKw;Sy*<;+a zzw?=c^giSHxqZg-3!E1(R0v+dzbN+liSHV|i@k{KS#FU%%T2DU4=OCF*4vcT1&z6{ zX1Ec;Nq+v5aOH$`lSwK6CnP@l=oV*nVacYv>O!yce4<;Yd+nNnI|@tI>#vn~t0K&1 z^89VdGyA5GImy?fc{P&f)spAclIOhWDq9XEzOckczrTy`lD{p^brRpYLhl2GCB_)B z=B1Z0wJDD$p2ir^OPD&sd`!ad3G#0cZ2;|YNyEmuG@L(|2BX|t7bXGIiC2D6Bgxyc zU&Qrj-eXSZ>$a*{T_EW!Wnw?cz3CCY8|89Au3W0-%B7~@gSm2%x~nHlkUDr&!dxhI zM_F#kTO)PnypmAlk3Hs^f=hB=jj_6&aK-#>sxu@UWwOb6Q(^wPm-KVj7;crgT_kSv z^>bmN_ugE2X@4X5Yrx;>3;k^<^j^rL+QOm>Xs>0sW%1X9ztM&MXs^z7MhY3F*A?io zx9nK@Kl!na34XK^n^ucfY||Riifmddn%kyD(Byt&jiU?AWz+i595!tTEo-~CC($xC zZ4xbQ(WKwHj-!6j&Ry7ssjG-YdCn}Go>c9ByA|S z=A_B;8#Bfev}!4TeSf``@nn5L4fP}UyD07%_x$rJX^XvRX~KL_!qDF$(r30vAKm0y zS6J>09HgIM7_E!+aEoKU#QcqVzCgn0cplLAWwGb*vcACWt=f}xRS;&Fbm=zAwP-bH zZq_4b@?AbY{sq0peCyL9*!w_`7RCU!t}uTi(-dtZg8zJMY!v@|{QT?ka=%0SiwJsr zA-|92>At;jZhUbz*lOZ@u_wq(DliK z_(NqIP3iITwlGgfJZ|{!5ZVU|9Ixl_we`U32W2^9?WpzxnMQcV7lM65Kh|f z`4VovAFnO+-agmuBm>e%yYO537X2phEAua1emWoX>1i>Fn<1yVKbe*+PG+KxJ&*1Tx^r($L0R< znAGp1uJa4aB69!Ovj3XG%1sAU7uGtzQdr4g&W!~Rb2rc$f(~IPMLqJ9N1eu{?W{KJ zH01TJDy+n^%@9GwRxuAf+ep*@uPrIN25iatJI;5>-=mU0^SL9jZ`w~f?dOfM-z`jcKw)hz4RSDuJOz>Hy^Q&VzO*-c==bA z$NJ_j-t!R~@*@!Iy;9uy*NC4H;`x^NX~2)}qs&vR@#r~#lO`z7SLdp2E}kB2wCCbE zX>mLfe-9m1_M7zDf@>+CI9kczHuYD&8|{);k*sA~U0CJ3$<{8{7wECc<1+Rm`H7Xo z^@IJLGA?d$(t2h7(Z0(0U8BEn16;4?0A(y(qQvzpGcNOfE|U{I?$Z3dgf@nUHO74) zNSGS-T65!M31OSjTF{uHnPc(%-ckg&R-6AWwC-j6$HhO-4RZFSoQB1}O&doWwrJAE zGiV{~cG6Cy?B1lme9XB_e~~;@pUn7x{rB_Tm=}LY-(SS70k@H5+`_nJmT;4CyAwBg zK6B}u&3m{vUc^|MukUI7xW{m}m!phrBe?bAc9n#s&&|~<^Vr-(Y3)ld8~2A(SpSj+ z9gn^@ew27*sL$8#Ufk0wxL4sW&##sX-++6|GVU@@Y{OliFU`-@^_a~Zc$15pn%SV% z6qR_k(=aQ%df{D$%RpZvXgqzf3 z18&u%bDhMe_XOtGOyb^#yF9O3&bSt?iJj}a35L0-SG~_zmt|vpBMLv72KQRXIvLhkORUkWRl`OW8y?=_ z(>A>SxebO5{)Q~ipGn)Ze0S)1I_qbdACx=iC+e(T#BU9L-Hbz@7r%Ng!CYih-bJjX zYm8x>v3rBzw*|iqq^(i>lDCM=JIpnl^YYx7Z_fYmEAJ=16~77mPP|3G8T|TqNA%6? z%DtwPjf7#!;U|(_y^gb__mgussapG9Mv!pwKE+b^=vLf3#NRA7?PYMo!ZPT_Z^K*k zJB;7%x9B&E--);2*H045-o<>AGI&AK%N~;6!W-%#Ss z{Z?bD=Md`mm2K()?7E)dFo31{yWYdAE^KiA`=G*dRxh@dgcm#VZbSVCQ~DW$>o)8Z zHq7ts;a{`vqj3YsT5T zD)08C>z~yN_Y3~@V=u+uoPSo@)8#UMXV2m>S=(9H&E|TyZB^cC*OKjNb-}HL`FbPt zm&V$+=-u2e{=naumpXpab%AsDGFEk)4`OTRkK5EL%G$8Sx^U? z7v&~N7p*C1o%_DApnmSV6pF-E%%I=)mu>2JvB5{QGPEe#fm$&%KUyc6JdTl%_^UVI?e@B=}R$wKgoBO$H<>KkI;J(QrnakkEYfY1n?v8HU#;d z(r2Xa?B?K?mHQ5RZF%=D-E}q=)M8KGZHS#dr5?%0-Y;|ZnDZ>!yEFUZm^1H7`!CrS zr8@QR#Uk&aT~KFwjTtiD`!C0>8@&ttTD}|euw0v-pN3VND`Z)>OPEo@MBiiXg;Ega z9su|2ODLHO%tu+l+#?$uzx!;XJ?r>yFDzPb+A2jKApSv#pK`O#*JLut#+H{98MjJ0 zk~d%}{?t3!yckS^H2MTBA+tKx?pRJ*GWt*f?6f#hr4G5=}PJ?C}?)N&MD!T!tq3(P2z`el&?+?8`^oYSAQq8S>>*!oNl|X}|V) zp!jby{U0Ho`AFOD=R)G|;k)a5{90{(t|7CmN2~*Z*q^|E_WG0_!(E@oKYdlk0WWT2 z*dN5!oqRXOVPk)XRv?eI^jyXDUhd<6HRme2t?2e8aebY*jOU)r-6gJa{1%TdotFS^ zCAj7CF8OOfYphuKo zS`e-O%qjIrz8mB3{BLgN=FB%R{?aSwCe6&MBy1;P-IUSiRtkFyVVObAg{?9A-Uwl( zK5HZ_A4&TJS`bb5N6KxJ^FrM(#LY#AZ&<=j+G6!l)E{mSiN8D9E!JgDjPhK(+_{?e zVcb+1#l%(%{_81!3G2ED|7KgP=DHoX9&EiRZs+30Sn`-W(>I@IQ6}c|@^w7w;2v$C z=h9%kgdN3>mpFP>VdrRxqjteOSJE*`p4_y>Pw`#WY@3`9(Bjt?aNBUCacjp-&pql2 zi|QzeN_00uKl+G-(f3Oh0Oo#rjXbNkyl`@r^K*-Cm}PjcA#Ct(+tkHoSnIur7Y2Ch z%ySLgq^-2zw++A6wzU;4jCQny*Yz{MFW$X`|Na&Hk1XMTVg>)M_ZjKQjX_d=C1{al z(o=z3yDj}SEBJ4;`IolQYWlxl@;m=*RKMHdtTkGdem_9c!oME;CznW%xDDbqwuGCM z^%!pBwzQ^K@L$9xzTJN*+EVr_uwP~R|2W@`zOm7quQ}Jxjniuj=D(ZIMp_By|NAz@ zZCZaMtr4^)G-)UD5v>cY(dMrYtsU(c?aLU$htQ&EXNyK_GoQ~evTSnQkh?eIBxPT6 zEcc`GDRm3qU8iw)pYGGFpY*#Y_s=C;CME&=)Zo7j+g}s^1^CxRIUUV!S&tv^SoO)kO_eDK+>iq`&dqtVM zUb}F=p%mN0ge(5XHuV9%8~M`rGI^)tqTKvh`fCP%LHtP>SlXX1FK6w1fk_>dR#6Z5 z&GlE&D$&C4T6kXzplwC7-`B){6K+wP|1et5GX6Vpi`)Fi(1w=rKZIM-=0Axxv4nr= zGa2zu`7Sly6tAYe>_%B0S&VTh1{_9up-(vGG<+BwnWJ`Y(t#z67_v02@CjBG0 z_1e-uv4Vfs`3wCwk{)@tLF|8H6>a`q9F(cs{8ICKy=NiM=9w!kvC^(7a9**DgO_-^ ziN}3)N}a}c*Pl7SlY5zE>qPgzA^Z%}{+^b!{1QJpE$sQ4YmK$Cf3l$e^CC-KYuU!0Gz?^bo+uZzP;hewL$@?AibAAR2slxzan*KTe zyjQdawDEUNspI%AA8AW1Xp?Ac;h6KkhPiuVJ8s3StE~RJ(Y$C&`5(Zo+U9=*t#%3j z689u-Ex27d7q?ShU)1SxGfC;kP3qs6mpU)Yxs~DOrY$ZNt{S&m+?ER0fLk|iAD*|V zGb?Ec(qam_Zi0VP4Z5tbB%rO*o%Mvl_`DRifa}A&HW6L z?MUF3#MbT72mZ~$x%7cW&qVZl7V8QdnCjW5j2fDt;>Q zGyTn!-p_J<(TL0XzJuHoE7y`H%Io8KTMi$-hINOz+Shv*9{hy}2JVyJ-%LwxzcN_tH1aa!BI- z7Rw<)xayqUZ!NSd?q6)|AYG=9;Wo4*|mev(BuCwGw~Bg8jgn_4Ehqv&_&R8T*518MH!EBZ-b?v^3h| z(lBc0_OEUG_U1jcDlZ{zdGYpjO@Y{tW2gl^S_I&?+8oS4E{p+ zlYSr{86V3}Wqd?Ck?*csIsBX7kw`xj|79DP58!qH-{m8kAFaox)uMHyouhqG*RT<7 z7){1RBTf4KY4)Tq%dMWZy$JqB@pqsZwh|7KrV+He`R@7y2bIsSzv(v@&kdm)3uJ$I zZYi$w<9LU|arI^9eg4aYHOEs)M~1kv*wyz`p66ND3s>g)-~~Jx!LQE$M(%%;^JT5` zkCt!KYSCP1;w~RyBboz^$5Z+vS}U5wUtrN9XcF4?Ayxmh3fl9!}Zx!5~i;#>GEP0FN? zh2D)w&1k^vZ@IPYJ-KA+^2y?%6MxqJR&){f6SSX5 zSlvb}??TJIgmHITThM5HXBSOBpOdr%2wOJ2aQ)tZR*JTt*yAJPObeP9jjC`sE|a~f z7MW&hw|3m>aJy>Gjh7>E^m0A?PST6pkNEC7gg=g;_fDP9QYJFJ(c#nhNnD)Lea$sH zM*G1$ZeIQsosOTh@vgD!4cv_I->`R?wR>^BJpO?^3n7@ingt%`}%(Af0yC^VD6``H~y^03+w&T z+`nyhK1yG?z;eH&CS*Jc6TamlbKLj=;hAUUo}bA*GKzbgxK9%M&n{zsU177c3;Wz1 z=kCX*{UqVf!T!P6a^1Sveirx0PR=-D-{I8rcyU?_M#6tVk#2Lgr zw2OI+*q?n(mydNmuHUaV=i|-JZ!sZfhGBhY!Q9L3#?E8J!!+07N??a_n)^Kxn#47P zpRUX{^`ykryEv}-edCRV&3P`S4EEXo20fk>akHz*<>}6)y-Jjd%;}u)&xMgy-!f$SC0RLNZw(1w!O5*0n-|(j;TFl+YJPKD9wv`J&e;mg+p45IimzlG!PcFOfyNwBKL=wB*y7U9 z!7k)?CGv|i>pGF~ycX{**ezbQUHxQ#$|?JMeP1x=!?rb^elKE!ykAzo-;xtz{f?3s zn?u;FB&~Aabo~LFOU#LfNOS0b?Z*2?_$%jM5^XD5AK#6+9PQlP!(d9ja1WC?t{(sD zNq_!!()^*?5Q0O%t3dm%v3UihC^WblbSw>6W`{Xr}yd~~OYxMdxjE$xPw=a0! z(~j1N_6|uipA!CcqqU(uCjw)i^FCwnE9P-p|{8OggHylgPPCSvX({iT91lZ27_w%jAIE$^eu4Ym52 z>gGz)SFl|_19zP~y0E_(zq2(0@JnE8;1Wy^5H`Hdyk|_Y17_Yc==%KK3+CI{{WRZQ zui?hKdggwTUe7V`f7qIIhBG}cD}FC^hfO^`eMfB0?_N_JT-z@g$=Y3Lk%~vzOaBo+5)6ePVe@m#J(-|+$;#9=HD1ImK zn_D|b_+GSev2tgt9 zd$Am?>Ri@aXixLq)rT$JKbVQ1SVJe7U`k?DkiGO|{RM$W8jAQd& z+%5f0*I(V7xwQq-#-sSHJY>7NL;Nn7i#gXCUKx$n7Dy_LKExO-c^M&GGvTD%<>TSs z1X>8KRs>xy^i`IPGMALJ=3h&ExUZdaXMxKbLPW%C`!ZS>!tw9RNoi=y*A|6WBFx2?Dxu6-N%E4q&UkLI>$rD*Lotr9JQmfJg! z_ycHSFQ-WzHlRuT4~acJmMrlcyJ6vTY_ZizxFq4Y^*J28H!FFGq2(X8-PkwKd665z zdVMb$!p)DHgq4r9wIo_4+Vdi4|IUYXb*|P`YyMxDFJbbpXFZDFT-rtRp!K8W%0lX* z9IX$HW^T4g<_7wVjGJ<;P`AN){3Y-w_bB;@y%5?c8dFpK5v>i)b@;+M>p+wKStGvm z9>qs=`;#*0#Z7*%e)*gm2TRa6#VvuGoX4QYRvoTsF5Coee%y5X)^78^`*SsLuOVIb zHsZr(^?9^++-~K&EA^^*|Ki;T<99F@%=N?E{1^WpU2V4IA^e-~Ka~?cL_8DN3h~|O z&w6el`yDO&`{&&T5ab9EV%eng>;k&EM@%Q(`I{&$S52^3w8@NAU zKX=avplwF0MJtm$@=U-wm(pu{^2oU{5hDZiALA~$S~d?CEWP=4h?MgP_R8P3-B>T{ z@j{m~i%QvgGL|>%8Pm)+8;$Y*Mw%L77PNn~8Z_N^u`B5>M;k=TJqM6>SB*A+*2s5R zOS3(t->nq?4Y(D*eY?6%-1vyrg4T?7kX8(BD_Y2+)#5g=nz0q_0+~xc`O8K3#zpVl zjIGN1o@>dQBX~i0hcN^A{R#{`XzC?IQtJ&Eloo)PA;@z&!7W+#~eiN8W8n5!d5batviLVU ztMZPLHnRAkr*s=#9;4X2o%l|cynaIBTiiyn_z9e_U0o^h-e$zRTpMY2er<8tv)1!s zznU9nSuStymbey{z0`9PeyUE~t}c?e-o8>?)ztGh7so}NNL;8e@mkl-LszY0{tLqv+e(<+mSi;>3uG}W|6s7 zjG+&+b91Y81>DpYOs#aklrjx4N$fdg``q6-(fLQ~Ln|R3BmeXJD`Ni3w)|J(t)H}Y zm2FoK^WBvhvW{i8Xa0KLIJe;Pkh1y@HdPII1HD=Rm1{N!n;*b3tR3F0}4@2-0!9%KBJ@t_sA+IMVM?9@42 zH{!NbA6+AJIvMvz7vG+^8+x%bfStNr9Ay&6!m&s0VdMB2JZ-z`<-5ym#AUsQt;@aF zLc6fnn%u)mH#!_|Ck}lNd+n#hvGBbXFO93%w{TuqfmUSEq|Mf#xzTtOVb1N%vh(sA zE923)9uJ!FSBgIw%jF~OW;2=>E!S724RoUU&^%_lncpYc;?nQx$k{$Wv)z`NrHTroGkm3)Zx5^hI|8z1rSL#sj4 zs}r$W>^?5P0kZy zs|s^2bfXcUb-z#hVFPXQ-NrtiQSSU`%K6~jO9bL4znT4yL#I}J&%lSDnlsJ4SKao+ z4tGguduIEr#ZTV~cBHSg;HMosKj8bqzLGm_k9siYL|ynTt=O)*O~0F1Z+T@YY>9Ia zKW!_-Swz?g{6w(h7dw1(|3~XbV;jtDkH%9~@n7;`#s}Oaz4Gz$&xclW7V8}m=JL%Lcxo9j;IDY)GtHgTK(t*o8~u<`tEM zi4x}R62@FZN<1x>FrPw~wX^FFFX(p&W&JFDHAI+7^28Rknf4ov?KpFMh~U1Ju&0Z= zPNT7ZC1HDT^Aq+)aWmfA;arvcfE?5%@ebi0!Tp_c?m?ZuTCVdiHS%|f^tlbBiJoqb ziF%!CTZ7cFoX9)wP1YbmY_^?Y{?2bdY}(c!(r$uxF&`vNzmqiSa@G4V0UGf4=gO5m zn@XIw;x~!kKJiQXtj}_sZH8|iY^*6@*U}tt^}I{MPDuU^o6_gFx;{Rz%E5qasY3~o z`@u7BhMV6RKXlt}G3rao$q1*@$k;AZ9^=L>4FA%T_OH-{pH^0x<5A? z)c1;N{CTnQ8}Vm9ALko$^|j#qP>DNCxFN#X`>XWrPTUf>{fcr~vc0l+*s{NQkEqJK zLyDPWIBmtewm@u+W2@n9Q|e!D&6fV%|N2F?j5A=$@1dTKm{JYcwTu-^Lgs%rCocqw zdl0{s_}!oVp(XP`yRhWpGt1@Sp2A9I%eJgxQp#|EIL1pB*RA9`iCfLt+tncLb@{fM zyU*rbAjiBcwe8SA@UoAvJ|Ld;E-scDKdgDF&8uD7*7^eH%S**!!B3Pu zxFvDh!FOq6)-^xxB$&S&c6Ku(W}Y|K&-A;Q5`Kd4(PI{c=beOz{C+VP{tL#8dM^Bh z(oZFPSu6E%BV)nw3)9b79+AHvnJd4a z8{y~5Pv^f#@=y5qd*}BCO3=b+{b=_7FK(TtfBXGf+I1gp^7l-RHT$!*Em+d>B5AR< zg^dNb=vOJ{5+}AC_c4BQuIm445JR12rfL=_PjZ2I%djHuvm#)oQBV)|sK3-iQQ_3YA^m$tq z#8Y-Z^Fhjqq13!T>wOHpHjzWOapvK6 zzAq}Le#(h+f@oiQJQ4r>`1f(v-&^%Rf&bK7^dG=}$wwJ4DVr0_er4TL$~^!kw$+5ah<|aJl@nLbwX6qm<0KM?>zePGYi-7G^If$(FY%ZSg(L0tS|Ul9 zsZ&z=@3gqiC5+`g6Av~=iBIzTHNHzb*yMD6hJL3H_7(RG?qSXnWBAC;33;P$emzn0 zG1@!sc+0u#-;qk#3f!tVduh3_b+~uoZVxNtZ8L5z&SBbPj@^sq&(?WeZC=aLbE5V7 z`BfZS{ipG};DzHYWB!7B(qC-j?OYr3UQgY;Z@WIb*j4b|h0pfA9E>Gp&iYCg8q)4- z@!xlHN}u=T`fHyqb9rxA%0%96@L}tNe0Tj4H>1q;!B)~Qn%XFD-1jrnYOZhiT^f5x zY(OnF4oI9`gsXf1;&vl$aop;0V`-bKqq*M}kKz_zBAg$uY1{@Vx790`+dqwRo105q zB=;%FYkdRj4Q#*8ch^6@llvXXtGRKs?&Flzd5hDm>mRoc-;{n=Xvulx!uoHJ`d_?! zTBqmracq_Fdu`r^UV2Wt&{mV!T0F1cP(XGZ`47_H`JJ|7?moKIZ~e`=a&6utVr%hz zbZr6qflKH{xrK{wC%Z@BZ)Rhf=RKgm<6$|38l^!&V2jyyWu*$;*bhwY+Tf zK9}p08(w-@ugS-6%V2L$@PAsZEr)b$uBDGa^{`yTC(!=eu9@MD{taG z>l4g9)naTC$oh_i+#f18Q{ESBSM3LKvFtv8ZZGQ!Is2`B>35v<+)wrvV#FB_Y*(M) z#S&Lf@1ng0+gwiDJZ6RSaMU zy&<#wCiC+C;as`=TCtfq-uw;Y-ft4`WS%|VD1O3Mu$Mylx&DG5U4~25n^}fkt~~$J z`PFMYFL{~7W-sx|cauP%@SrEC(xr7zTBubjR#z;_wrmOkSu_ckPXHr9F!MB3oo`b6^4g{^LEEjjO& z*O`oY_ZsW`QO1%{!lejzwWLAs>&Ux;8wxlhT94rw+i;aa2dkM zdk{Py1TtHBRDrBBtBHqW-a#he50X z7xV^hg+n%pBLsEZ>%^x2So8NB_1LsMbL}7<&DYPrYc6x01YyExUcS40gyGz_jkM)z zt|xG7!|j{mR*W0{$+~~c{DJ%I{G%#%p?F~Er7`C^kCCqOTUa+9V?Mij?RnBwo_mz0 z_fTqaA0nQgNuPKbciQNq^7p5#=YFg!tjfEF*};OsSg)VewG;l!Ir~qF{i@vSQo5{r zaj(2#yZV$1`wtlQ&G|7c#5`xq+J-nM`6=0GTfFfpMeXoPdECl;jX2p}ceoyuIC~eo zPbPI-hM$HH@GgYZ@y+;I`F>W7iM*$mn*d?Y%fB!->xftSh0DJZsIDmrIfdvxr+F% zLM0^~Fkr%fsZ(dpnmUyfb15n*=@LY;0V^pf$)-|bOGSX#~6d2cS zj6vk*_k5kt=YBq)dq1DM4fV(4fn3k$oY(vOd7t5B-3t87m`c;ym;N-#yWXtZrcW42XgZy;2d3e zsg^2cO&4P`a~t2(=gv1L)_em0JBDvt8g@BvJDRy}&cX4f!4kcTw`dq|FeEBe3tX;V zfY7P=DqBO@+AFc;-8L*!oNSZcLkN_uQrX}Io|R@@yOOf0t9IFss;sf)=XiHy&XC?U zZ$BhvxRkvG8e3XMPHm=q!_{xU{OA?Xzh;-s&6?5l=SZg{u6OBs{V!+rM2b{XzHPzV zFTaxV4cD>0jG#ZuZ@>0@)bkni)%TkzpIqqD&lnvv*N_MMbpdDAY(zmiqn@QyQfi*l7O{1)T4 z`0bTf-&aw7^pah6+?88FzW4h68={`c_f?c_Ye1LZLcFlnB07QZ%RRG}^VdM`{%U6; zQK+>@*g;_SJ(6HrI7j9cxoeS4V2E8bi2Upc>hlOe12OesBK*t>mA9oF6yTHm;c6ZM~1&W`%qY8Z^M>GE=TQW`eWm+ z*Q#{ZC}L#XGa3uPTK~;mfxBeVe(HJNvOwp~+^8g@Yg;L^oig*)7PFQ}p92fTX=I&; zlOEbexjJM#YQWX&0ek*@&z?UuxQ41D>zI|;1C+Z6dra%Xkgqami|M#&gy-kf{KO;C z%jF7l#;*|?8%{j1wT8x`opNJOa$+8wab;Z34b*l1 zH+I>l^4q$xCAjADWi!S(mwaScVOqJ6 z2fs;v4)=_2C5J~Y4I1zO3%8bXkAQoO%8eARe~x@CX$$$jesZ_-mPhJ`uFqkH6MLDQ z>j)ipZ$bUmO8%YXH)mxwk)M7F?rWR1JndA>bY1-C;WHGh_=M97&Uo6ReR^wE8V56B zS;Fkq6A$ga=Uh(2R{ZgB@bz?~(y4p2?Z_QwRK)QN0-we;9 zH-qbZt-3xaJ0{q$>1IAGp!`{2e@=C|TG)O}d6KmGIHIbSaW;qF&V1o9Xif~`lu-Ds ziA!5Wo+k2K;O6n)@Z@Bt>o!x~GQMwzUMG3Ss=kMW>udHabrdX7t_m}6ypfm#gc*ym z*I_FZx^;fz2hMoA6JajTcA4%%J}pvOI1epV(A9wu z-NeVEWlMR!#;FCm7P6&|-_H7scw2VlWG{A6=aDOR**B@(lc=-NUDyQCZ?F(T9e0Qg zU{j61p7Q|oLoN8$DD^{ghMz!mYsi!Q)-L->(d}M6B)Vm4WSFk;|0lt01#{n_F5Sn$ zjG)^|o|4;k*%yiKJwu?&dC+(?UC%F4ypVHn(8cu>vzCi)SI9q9L7wDy-1c5M1iJL| z#Av!Eo=ELo4Q3~F&lTNMqTAa+o|4;lnK#3%qtkTJ9q#xVo71z^-AW!G_IQOo8et|rL@l`4>VKx^B7~du^*FyI+(fz*Yrb7MPMxMEM z5W69|H>BwzcS8K^`omII;>XeLl`9~Y6fHL4Z-Oq{(=n^k(9KvQNOqQJqaJ$z6C-Ao zlE>KAM%HrP=-LcjRYRT{@;8wGT!>hQ3{+2dEzq8<9MxV{IjVU|V%>;HLqh7>?8U4D zd;Uz$>B}cLB8_dvJWJNN_Gm+5d$jAX+{g&)M)pru6SFQ`=kMGyV#YG6Pu;q<3`_LO zV4o85GJ1Vl1Lm?(JDodio&$4K%dntCliaFlLI3{{napoT#>>Ap*}Ok8pKn_zf26)? zyMliz`P&BW#?!j(C93P9LF-!0m(d%XHC^k+5uU(yu=_xEWSGj?PXP;Tmz4UNz_ ztJ}WO;$QoF!SRdchq}aXqt{zg&3Y?E-8TP-dz-*k-GX~e=?E#}jN}NFmNkdXYsp%2 zH|wn*@3PNz+vNHOf_6@+j=`N3bjwjj3Y@QYwtgL%cn*3_?K~-?ou_B& zSeNhX64P_FQ)94&`nI0eZQ{x!$KbR;>~U4%{kiz45Uk>R7*E=M0l)P}X%k4>N!lSM z#Yw9qZF?Y1?OJ>jHt83-?L)+ax2y_|pYiF;@!p&C+Vz#_?fGfOH@X?TmC&eT9IOi+ zJooNm#)4RyM;vj*7!uTYp<^rYKQeU2P@mC@VzJo;?t0*O$_L`6RNuli@b5+4_6T>J zgElxmU)Oey-{_1Ya>UuYos@r8Rtg$N<4_0Q=!-eW;^M7{;AeXQ2_T8 zW$k}0CX^w6r?b{Nkurh45oQ(NEAC@0Cd`jSU=9-|hhgaN^!jTtWll(A4$s7_0&@-D z%YVupJP9!W^W6}CWceRvjB3M%6XS<1!4p`eU1d42@{-k)`L zSf`O)r`<%#mJus3;Q?YigmaTqx8S^Y*RFN(OTu$nyw*th?FYMSj5(@@zYfs%g+E3< zgMU1~b%uzoWi*7j!ou**YJG7>VK+>?}_9c_^_Db1qi%}&=QYZ&wa<}_(fXT zGE%hKi*XxIzRy$VgO%?g^11p+{5SSqstLvg{0`U%+8T2s5gh(g-Wu{Y4I!`Q$YS!g zybE(gecB1uV(7}wa`Z0ecnAfMAQ!C^-#1+H&gG)|vF;Z7<4fK4|HQkut#o;pITpGP z#a$P%;O>fKUFVI;Ht|NLY-If=BC34W6`)*@P*+(4do^75A zUe?}kA#I4=hyUY2U$(1V6DZd(&$UC|pRPwvn`uBhM15WljkYV^xeS!N*i7Ausqe&L z^wAG*3(1QtePY%Gv!V?|&z>v!Ml5#c2v_cX11J+MKfrh_>$Wj5LTd~+svHYx za=xCZa7V?&>!>d4s7vv3;&2b5F6ZZ{i?0LBwE!I2iZF-pCxT}Y3$X3G-S(Z5mp>Q+ zUPnA}zXm&OUzvHPu^Im$`=zV9?d2}N4X}4`8tnISWLM$&nh4e!>Sr+*P6x}Hf$#e3WJ_YdQ5X|8|D8VcWtbE$_H$$a6w`w+KLY z-)br!)tr|&A-b=D9k8`_-lxLe~f*gj=l{P&UL;rh|XH)D_g zdY65d+W9|5*!Klx+IdKO`8n#z|5~2g|1XoDuGEH%+e3`msPL*#IPT>OY3G33qneN!1@gJOH1|=glc4%^KK;m957rQCKL$(q3rQ;>?NZ6$ zocONHDU1Iqa@@cd)<&=@?|SET71rp7(2IA!b9+r#bzs%s^Uirddv&c~ZCulBU(Rnw z2M6}?Cwa0oV;^7TMza6k#k~AF<7mxkGBThk&OU*=$EO{&H-b8nK9y`Kqg;)>!+9s* z!;}le=n1!u??v#;$AvpAjf>-GNrL&l$eO|JMz05Pk$K|H`Rm}h$HM1hBoEhtIht>> z3$2I0Y3drZ4c)V6W!eGDFb!Gfsm{HW-}KfFXP(?o`M{o<>O6WSGWYRa_TTtzeaFEM z#yM(N@T(E~ot2auNnaTG*C1T>11;x)H{s6X`@|07mV{fA#x;Fm{4!>@aaty@>br(= zuTWou`EBME#{J(B>>h11psouqW zul~(0nyi1p^%Pi{ZgQtrAm?vI7*@Bgaa3q=>)-wSuSgBz;1 zI)$zBjQ3;Evg()hlrIDS6DogxX1&Ej?T;Xze!I(gC#Zrw)|t*CUTx~9Y#ra8P}xsX zHY*+)ekWMPk4cqc7tPY|Qucp4oS4)@MAMH+t>SwX-?xDKvk~C#`G)DM;QgN=JCA*! ze@FXjytUUFFrSC!ld9`2q8Z+A+en_|v)Bl-iEbp1k(F8Zj&ehSdzZqDQK@+1TsaZL zK72;cvH8c`PMhi9i!{$36WvsXk4XJkMxK!`?6UVtpRaM~24i~-Ph-RRJvqzS|E1hV znJXu#P2U!_KUc&XtN7mbCwGtjItO=|d~=!m%guRlJVF_h+`02<3+3OU?lXm7C46iG zm#4)Wo7?d{z3ATGYStglovETddKLZ=zWqmK$E0batukpdpSZUxf_63KpHI{7h6mKP z0PU(@LgOX(zCAyzUjBKE^_XMS6{b+JBDv&5BqM1w=(;h?szNM*OMLF zo^rQRA0t0*RDI|RS1w8Kc0sdui|?ma9~6C$bs%XoHTGvXv_k!FWJ+}Z*HFG3n&*LK zofPha>PMmb=Wze4-3@%(#1wRzWBrXn(+O8QhhhN z^_`&a7iHAf*cogxd5e3EYd`t7@84nW?z1Lk)>r&ewA!ifq2m9KW#IX`S|?ehuICNV%JKtEB+r;1uts>r+0U~saOxA30WNRXndihZ z?pNeQmm~#>XCYzV|f3DiUL&`Ns247X6U%XTFtyZ+*)2QD{v)kvz4pvp1u$ zIn1FO+zT}Ec*buqOGk>AL$Z{#pyR+>!!HGEGyGU1dT%VIe_GY`A4%VO9jck%ZP_E1Il3GzhoqE4DQ$BP)x3~_DrW(^o+X*#!wPDea#1F26J@V)du zyX>!t#`O-3pzpw!b$;7&I9R>5Z343>P4lF1+bW=|*oFzacG)*-ERS;NM)PdNsFu7$ zF>^ZG*=78Yg<&L61 zoc@Nt-1y(L4H5r#mJwm%_)9o1#aqdax}1|QLj#wOHzIn(A!E&l4uVAg-K?*_L#(3u z;mDgpbIJGT&epj??bUoFnzbDNaq$NB6{-IeuWgd!)433GWNaa6<$RBI@3Oz>wU0Np zGUJ;|h7bmH%#j2~nhEgB5^S!Fi^}!bK zoxaFi3pL<12==gJN2Vw@A6#Rf{qsg}8$3Hza;cDbg01~D8DNq<^PyG#Km63{kMlEV`DfUCn@$&?zZBWS@O2Wr4d9(Y z+m7M4b(Go`wyn04r{OK<{sSxF&~*95TmQAdFu^@Q^;>c+e3QoBf+h~E|3rJtGxROE zllkq)dxR5i0XIa()US*@qiuIT)!4WQ=s+Iv^HS)PlIJ;oTMMA$^Yei9>!94-{chW5 zh3mH-+H1k}SN0I%bYy4ArK3caMU)t|O->_##^i9k<4=cjRLiVgObqZ3eEK9yjGk2EvQ@)FO z7@PTc%KNfT?#z2VQ3um%ewO?Mf8idtpWjFRz*&fLzFF~Z;(5;K_FJi5r^E=dq z>xeUCopa~GV#o2N+_8PtyCsOv`)Ye})_|Y~CMp<6s80KZR&El4v{H`$>&lGw7}@R0o5sBOLs{){^jJ0JH$lU+XNG9_ zvO5WW)h6~whvgn$&4*QBRFUUVwRx0NhhPk&Q5_dBVKIH2^|!O;?4;Zc(4Gp0b+Aj@ zbwtQ!+XU_Q;VCaBQ~ldT+B(v#1phOzyccgo?+vSx9@g&u$=ON^>i8EH}QQZ_@7mujm?3tj!Wca>j`5+ zi$>x7vDiXiU=2Y=fsU&gm>{I;$M*Mq)v?-JF{)z88eadk)R z0p1=?*W;vcJ;aN}~;HcxP$GoqKTKOVdJB< zAmzM!mL>1wHEF)4oz!71SSj*uR~>%))o9+CiBeBomp!&7CP8Dn6O8%PXA!@xHDCm6 z0MRIT5dIvMvbW04Xv(1B&wE4T(uMxGY(Z!ApN70gZRjDhO3A-hgyt*v%%1LIlhv_Uk>!gaFR=$CYz zJ~nur#*=^X`%?A-_0vHE)oFM3Sa|l>0xP(Q8Wduh5(ukhXQhuO=G z?5B<7uOk08)#))OziT6s-#cdrfBZppVm!T7mZ{T3Xcn;NKlZSc{R`FUK`@NXp0y4& z8#;|y!|%xbO3MG1HW}IRb+yTt`;}nM<9ieMO{(LUoI1L;b(W23*8H5cFgq*}Zj{OS zN$}Q#*9g5P)%Q}->&&pLMYD@MYu}%;vG`)v>Fu>()pkXKKya~K1RJ9#lHe@{ zZ!I)$5Y4hM%@XBd= z9zZHY)X?LDl7~4XM;-ac;pwcoCc2e;Tt7Z#A2WhHsWe@~_x@bV@>i~pjypE`Bnf5< zm>tlarun-%VDu(MSSvj8qc4TJ`cEK(UGU?6e3uj zBT@L~BK$e#oq;5@#?ih%KF&Qw+_5~(JzV5PM3etnac-K{~F4t7>|Fe z{c9u2f7fe&c|P|5x&B?#e%WlRD8H0>U#RleQ$DbtEM8psvQxi%nDc|jbLLWWj!(A> ztnss)byMtg?a9VxjT(856Z{Ok=vjYZJihntoF|z7C^o_!+{rB7zn5JW-{z*0QoJH^sGsQVRbR^k!YYhJ#7b#UEc z))eNBIPETs%Qj0Z^0m%uq5Ky3h#N^`R) zomGLC0%w(iw;#N<_jQ{!f#V}%4WhU4l9)6SV1yGRG3(R6$5W>C725xkZkr{#(Gx*G zYutY%HREpBIuu>wbgG)p)#hm)};872r0wfJZu_#44LMELwsS~F=I0%_{=jgR3c zXzjLB{I>pbrD<2N-_?-SK_3PF50#5O&b~mp+#^FTH-U0(_q+7IHS}@~l$-m2TW;Ra z%GFWL#a*mL9{m5u8)p7PqqeQve!-ic#(wbEronRwW%2tW`2w51iu%@cFb`&?>^EeS z-p*~QM#dXHGq$il-(8!OwaJ&G4IJZ}OM=-7=H^{H%zJ;FN5J_WJen*9ba?5&vl<^H!MiJQcr*#U7(>*Me=mPjzE| zDPR*tFMy`zt1gQvyMcbcOJ#fT$kSKBJCcmQnYw_H;kYO_o583NM3N&MCz-Qeo53so znTz+hgXj9|$jtfoGdm2W8$=9qw?-xOchIA5FT0D}9%DQkd? z$JpD!`O=UWuBA84&r)a=<_y+S@Y+sK*{8*6$DeZG1=o(um&c=RBF|3W3T7?sI78#{ zb1<{!O9|;)x8aX`sN2{D;=7>CjF+WNbYwhvNB)ESL(Ds#ys>pd!>uE4@euN=-`h4Y z-e<7KmY_}l{Bm@^`#d(A16%dc{XQ!{30~|;d~$E>aNc+MHF#Njr=?^mCeMbm96z;n zmqXKC3pn#>vNxYR`@M!TOTd*(vc4)@KOR)=Sitv2`tsNEkzJUh9cH|}_>(2kOV~+9 zhHM0{nL7S554;lw!ZUh(7Ry^Bz{ARTy6G3iHoUlVhh3)n7pVT3>tVI4=ymwv>`dJ} zmb5K_v?}t|gSDBo6E$YfT^>DVrme0nU=yz^+E3-_f_5;kp?>pKzk9*VT7#;Ow~}Y| z=TlDH!R_QR=iYM4Bbf;Oky8{~FbUq+ryZJROivTduso_F&)i>eXZCRFbzHiwzTWfK z;ij$J7#mMKE#GH&AWSTx+OY=A^4}1fAlYzK8gl?&K~>_8Xwl%@iPj6=X8PqjBf#sK zH~4roClbBUcm5cDFQ$$a8)LCcckHm&^4r=4<|I8b9hBBi>_Y?j`p-|1kKeIL4C5Z#Bs%e*+w=!k9PslPB~A3cmb_hisCy51iXcfCn_ zr$vv6rz0jj!~BKr?V`I}bTgYfmh@WkjG3Eq?gqKiq3g<5-O2RnD553fquY@-L)Zf3l=3B?_+ znI?v!Xeax#^HX+jW?t-NY^=3jW)lac_RM>ZJ*E!cG1RuMDlm#8}RS7Df?6W z)*ty=6x&cqT7ky*@0S`r4cgHrzF;;|o`d-rySHeSF_bU(T`YD4bj{xE!<0w9yJ0BC zx1iXD{osFC^X~@^zH8t5YX;LdZhy08_yr9O%dU$2B=i=7*AG9Q!*A;<(aT&js7)>8 zY5!`#FCkBf%CCs|Hf?0N97 zOPPC}t@k?k%k>UH@a#KnQal3zJl$dclH)_H0H+l?CyLH%UxH3cMqG`21r@unwXRP& zZw8ztzB00lfHC)eP-C~byk8f;jh=e~bNMN}0-Nvv{f<@6^LUAW&vR&59O3NyY@!Zh zzm~Gcigz!j4n|I8+2sECuokcqr$x^PRGWf_&iD(U)N+Xzbi*OmBav6*3}x>;?Ri9hV|NI95Z|AKchG*72Z)@0Gll!NNK4)Sb&)?Mo#>(C6! zyaVwasP78@h&-ST{p!1(i`~A9(kZU4=Y54EqUVrzjDs2xkm zQ}%5)#>k`V&)uxP(;aW|=Oa7Mu?x3=_dI=9s=j+dG}}UU&3^LK(s!3hUObp?t54I{ zpRP=5%uBoxZH#)hdesZ8?SALHn`zyiff>bnT66q1QboW6M*a)$`EI*YeRr9I=f<@l z?3d`x=taZuZzM)iu?(f=+`H37`H`L6?V>i;gzGcI+bcCX3r&(poTBjzD=jm>q%+2E zX8ym>ZL>=XUpknfJqgNdPXe9saya;GYJLqk3&Cmn7CyLX;2f1vw=BEd>0QzRln}@%nu7EZ&;3za%^GwlH18>wZj*Y^*n;#nV({M{EG^aQ0&l z*Ld76nwfG!ZQV|uBxCjpzpZ;6no)8heim$mW#O3-s0&hpCu%%7JMl$yKA4XkHbDOw zUEuOo%ZS8={K#=L`*^ay=k39N@LI}d+r`ykX1|3R#aE%ioZ}a04)x=D=r{d6Wv`O` zYlr)hxzRMtm-BiLQ*PKWXM>jnuiz#0ID4-B{I(92-Psiyy8=Eg*v>nF^tE(fa4x#G zSgCoZfZ6G}WvA!If0;Eq)ro3DEqELM<-SiGg-31UFJ={Xo{$cXl37>H2d@>p_J2F~ z4XS>@c}e};n9xL-D=iRqj^}u4eqwlb+RS_|jF3$6a!t!Wj}(Hqyr#{f9Sfmb%mz@| zf4IXH+c>w~<;u~r_{vBwsK}q4Bi-D(6tQA3yf_|`YoOn`E5{p{gq_Ry;X_Xd~jgNNSiwtp`y6R#WpI>%VJ zrH!2@b_q}CzteQxFTXin!09mbEm`X*x2C(>K9k@2GnT)r{*2BftzK)5+p)8|89+$sM^GPqXm{3FY$dfcn#Z9b{jG<+vW@P zduKdx-H6DJ_hiw=ml^*Z#5qc)UYoYPDs!!^wU|k4j`nF8%p}zs^B3&to*iZ%*VuDf z(*zcx6O?B^@~WFPM}#~u>rI{BVX!k)Gg?Z0P(#^GJt>=;B15vol$8hIJ?^Xw2;_R; zf&y7as$~2o>N{q4%3dp;`Ab@#`tfH*ulVxN+$}aETGxAeG`TevyP7^Y7JTb2FtgUE zqFYX$>OCp@3i)Yn9+WNz4C9Hl(xYKX?CH@}U>2wQ{&_<;Ll%qfdh%5MFJ(6#1l^y9 z>1OefIU9fD$Vj^0m=~gW&VlX&YVVVxoB1xWv46-@J^W4cewuZkLpLO6X`9x}&IO&> zrvMxqbs;!+Kuh!8x<<6BGR^>~jV zE&R5=>D1M=F??S|CB}bz1{^#kU}U)GKPmqyY$wSxW2iZUuj1?1%T*#j+=F31ep68!YL3mmtITfV0n13tqv&J?4!A z>v{(-Bqu1$JDGZtB*W60nO{u`mX>E@IGAl%&xq|GtuocI#`%%z})cB9{cyI zXYmj)TjIHVGKSa9{I~LAWuNM?F9P40|CsddU5D|h-u$1XH!d7e;Mf?Y+h`x4sS+h~N_Hp2X*y;uqmwKvCUC%5UFeo?n{jlI-o-RFAjBJtBVsgG%+8AHs<;9Fg;-z61K ztdiXnCFtDx6_3b^HBRrb-=K{S9%qq*@w~LpJ!3>{r*maM7_Qvtx(2X{PwlZWL0~#h zH?a_9UyZ#Rmm$q~7m}rg{JrEqPWkyGp4#$H^!JP&yI*pqt1dW>QNAVJl@nKBY4|$8 z8798V8kraCD16f%r}nXA4(iLxy(;m#^i$sd7?~iusQz{Kt4`~&D>eR?I&}&0xY7Er zIa~#Lz^&d}u>l`=#*unGHlYc`x z|G|UjUrGMOpLgrO{R`RspHYAD`Uchi+#dTS>E@@&@5`(xUY9@dPr1~X@KOgOKM#G= zyxAyT583dN$B$*PYPm63*vs>n*XXYb@XGS@VvEn~v2XEYL(cV!?gD=; zH~z9O^w|GYTSqu;U8b`G!MiD)SNzaA8LMt1FNDzx#{BbpoY=i>=b8RmCf`aX23l0l zCq-jS*g?DMU5wwnJ&c856kO6{C*+&IGmQ~yOU`)HIk?1(jNO`(zpMt4eBDFca82y?@z=NZK6wBmJ`nC@K$KG9g-It|7F%7uCFTE z=GGAdf;6)GgW!Z|;SG!F`CQXe%EPF^uA6ZHiSf3m^3GbbZd6{Z`YS#5b<|yRH|V>I zbFkjkcP2)ohAhqGUqk-yy7`0i)A)@lM}_X&tT2yH1*hlCeBO#@UGBMZV|C!|1baK! zSU#>E&zh@dET-yCteJG6o)rjlKt(=If`~I3SVZ-}&i@Z{@X8*$T61{JxgmLF&X4;3 zMAljHS0m|6&5!SnWCdq`sr}Hr*v|PqCXQGA>grtMi(s8(_RZu=V@y4vH6#DaSt-1y zlId8#c0T``wf>^W z&X|^OPRxYoMMZw%zw*Y;2+bH)P-Ce>S0VP+*M`P_lIP=7j3N0KOKyGt9JlRJ_Nv=;T)J0%mxg)#j; zb?saBb>Az@aNn6dY_-|qpg_yw9&;b?py%zX;`c-j5f)(~SXE%HLBAf&Z~f7lrJl6r zn|th^E5YYgSaXT<{xv(r*qIr;Dg#qxTPQnv$$^(GqwH47uA=NO`7OF3S&2ccecUoO z5wb<46udB!?}Pp=Zy!TESPw=s7(d{*BLmTc>GkLZo(%NXY3<$QTiRpSiEqAqc5wco zH(b4kWLh*lj^9fwM{iA4kw44nNG}Cc@l8Pwe{b!v8-zLionw}PSqElGQ;$7eym)jP z)6A7D{jBSkGt`S0H@F6j@yoE^g^}-I4B+e177i=;$fb-~8})*>ZMlp0+F2p_o8>nj z5KnU>d01X-Wpj^xt8_-rwW&MTs^Y(koEyj@jX`rS_RP0>>@kvumk*(C?Bgi(Awmn8 z{wo7>8<=ZW_1LA7SLZvJ5jG=smYxX8m|~usD%nll?&z`eRj-o=t(S=@%5h<&;bGNl zA()kS?!mAkz4n=v24`S^9w|Dl~FKAxRN#jMu9~${(Vt_t9EE3V! z3c{=gvzI-)|BM9l>@;SS9X&;MG^^F&iSKD*hMiB|T52trx4yi?-VDA~0Vaildv=AS zuRS6!HV+@wA^g^#a{hLyeJ}Oc%f&w*aOx7$@kURwJ!&3E37cy2VJWsDwzbE(kFLPM z3EI3+DTiVm9~krcG7VDnm@|dMcO*j3Ib`pq_t(Gjr?FCO&U|r{83%zk+zDo_XN@!UA$o0O43xn4+rwCC2bRF zqXKE`N!yr})=Aoith8;UssBC@DBJJi1^cDoLk`~i-FzCCBx#!|`!S_e>i!Jp-3_&8 zBHy<2EttQGwBCsPW60n9KkbF~IQRaZK*Ve;yB|NA09-4Ww04W)o@sYu>O+(4CHtr%HZ$v(|)PGvnnt@)CcQekZ;(%hzIj zdurd9qnz;ywy%^ljek^sRPs&y7tCKrn#Ln4|3bcP$;#hM+O{0|TlvGK1cp}d|SY`Hu_e7O8MJJ+UTjf z?HiR~UZk7{M;M1I|Hahj-B7l&c)@s@xgWBaZ0jh~_)3pGPGwM_OXB!>7A0^1aqswy zQH4|7`2MZrn*ert9!W-~NUJ7otIB4{NV9hKZ2-xs>)?>^${7n#b)Wd*yjThKxJOuK z--LakCCE4Sa`adr?k!)%Q$}@fpv*exmmwFOx=%Y~_>`u^B1?C>7L3qjn82r1!M+buD&pA(QBS|Oc#1S>t4RMOy6xkqwfRzLgi0y z%ZsuxC|btf`aJDt?Y7tR+gdcs_*UI}Nz5A1?Ee`ZtVc^S)_}%mJ&|&2!Ds;k6%ey# zfx);0_mGVKHRpit%4)E)hqRsYbu--Z#Rp!#B%T*b&fM+Xz5ZWzvU1Y@VI=*zl<%Va z9@YPk1C{?lWcjs}Z>e_G_ymBV4D%1Tz+ojy>{l$v$ zC(l0cvYJa1DZ3H7>2d7ULHVdkQwc`M61Fk|)rO^DO~iIl43NX`*p$IN3ua;b;jHe% zu&*Nf_5|{PHW(j5<4iMt1K7>wijPcSwnS9N@T4#&TG(4vE@s8MgV_w`meY3IJ24)t zLNIgAJ%9iGyNV4BOCWFUz75RzwJzo_-#MnnVgfM+g_rEMzlw8C*@n^U$~F_Y z@_iNx@~=A!7-P$;-{w=cykWOJMQuFYDLcSeXepGa)S4sQMh|l%m}S=?&oKV2)dOL= zF#=#VMaM#Vm}7`J7<0>R`;V%pWKPbpaD6*qzNJeF!u2%%0NEc6V6OevZu=aqx858A zW<&gfNJRD$)R!ILwXfQ3AEkB|%pRbQKELdbuA^DMtpsy4@dOrn<+LNf{3e*jE}wD8 z@KaYLmRrk)HL>!F_l!#>PRtt@i{HSHLv#N)NuTzOOU7St|9#2*cYBV1|3La;gXyTc zvy2K)QmC27;hTBY}j&ZMMC}2NuG^suw#)K)@btN95cT^ zDx&9)+{-5Rq?p);l@IQ=mx}IVU?M-4%br-4;LLuLg-x(znDGh%kS0gjb z_=C0O=ezCKHD1>YT0h0uP1n*m%u+K=9AF1{3p#e&`_$ey2gNgUsWf{0O?$Ow9(@q{ zdK2~{hQIX%Y;5{)c^p|AjMp*xTB^U{pm1}Yvsbm?6l~dTKc>2MIXKbt+#ic^(R0$1 zxou!B`1@}AaLviPP9M_vJ`>$uGtY}?uZ2=9f5Wi>t#a0t+{LI@d&EykzSZ#USQc*9 zSZ9qpKpV`?`*!J#@PL_kC?o&C9N)d$K1OZm9kdNI^mx`Ql7C^<==IA+Fbnr%H;YF< zM?DATdsENnw6+Oj8d;@!j>*TLVq>>SR(*76m@g@=J&ftKy#dTE!~5(TRL{4D(00~f zzZ#^T8^E*S&i z7(zWe5{X-*+wNi3gV{T-&;E=suNneoS0b?`y6r|rtDfy(c8%||_h@d`4gnJx@^Cb! zH%0}-3p7pavp=DFHVy$3{yaUJ=e@SqfjM__pWUf>v~XyctE2nV^DnOhbKA5&`xhGb zYleW?nU~lUJ?n8>A1Mq`?Nc&%A$!K|ItXX8eTS;v5B)?Ms< zX0BNp^RhR#k?PV*3qHkqXLg_cIKR15p({_}CM^E-Z6)8j_;!rGnX`6!F_V2#{%(eD zFW)xs+j<(k3*BJ6rkoafzudFTp(mSuJD5##`s|8aYs5<3v+)fUSiv=7MZVT~#h=dO zJwIXs-Lla-(%8u&za>&bA}I^OY5;5Vt{%@XD*VNyb&~ev(D0v$#77Is2J3wf{X;vo zg>L-x@cN!~-%0=P9OE|+9OE->82LW@$#1$ecaY~D z(yRgRfi%qrqiHTAPiwbJ^M~)8<|gniPSdpyU%zUyGn_f(Xz&~12%%$cxIoySeVbH zF|+pE45r~}_64m(eYEWM^y`?z*grX^&wfjoYlnczS%+Jq7b~7VXaIBW7y9f6g?Y;m zFjH1yX>>h3UAO_v4Hxv;mkG0B2$-E#;`nGx&sHlUuAuAUKKm76)(ioYdTxrw^mNQT zFbm+lml1MS8JI>+m~l7z4<_!!$Q{?8(3O|yXLS`ZvyDBSguObzeDSwC9KYm$z|4B5 zK(e#r1mxYNefA>sr9(4{FI?GNmv|*w{Z2D-zF-3W@-Jg^VIvFyYkxFWg^BC00jqU> zpZ&Tk)1%jzI*y&;6E^%Q{ks1B=+|rdOw5?IZ&pap=}M>~$M?iJ9`Cp3i`h^4t&|_d zJhdKk%CCrLotfqiH*dec%n6f=THdHWmBbFLUeITMUv|k24&Ji(j7)ux(?4+vy^;}T z&Hg}ilP7nlq3dhLC(6Z6xUImh4F z$n(X=;k|f|=f;14e*eu5yM;Deuj6aWy1Py~eEf+F>OsBUUZiZ+d6b*Cw9igps94WY zZs0ZQ^ijx@Ce+~awuyKY3K6a^k;ZVa=UXqcrSH&B?FNN%&D94^;6p2nwH9%G^mrkD4ReIe z1LsY?D)5rDw*+YG#ZyD}sM=dK8U88o+dH4MdeTa_^x0=f{`mJtM%6*<-HNE8o|GQy zs$gUwjf!OEakTjULG={;_3!cfKx5uSxu!q6WBxSd{JQw@dGBz{MW+`!^S8QmZu|d3rwTf? z#2id4?6prUpl`o85FNK~@uBByFD~4-#-2@r*#>4w`wm<9*3s(Q#*BM$)VFQr><5hT z`_{-m(mG%1vqyUR&DT94T~QWq&%rY0PQvlU=-;kB`^VA=_fB`^b=c02|2#`6AYD}N z`IMi3WUu{E^~<$R`RKXr#>dhx=1KK%znHa963mTY*8RercV%Ek^vlMn#48-@_lwpn zv13>tyw+zwqP7&K+k$7%^-;QSSC__r6>f{lmr=fdTc2}hT-P+WFR(@2ceqUqC}yQD z0?ty9#x7{2{MwK9+UJV?gHHKSUj*N;K-jK{931CP;ZE=xAK78IQa5WkcoA!pPLj+2 z;oB#3$vg6+#1D}6u;JAl_3-E397XzaQZ7PC&dg7|DDy2mSaO1hKdb2Gm2dj=D@j`l z{btfe$Ua(;rf+tLT+E-BjQUDv0@+XAzx?RH(*J@nC)6(;66ns1{_IYH- zS(<|*M7L{L(2@|{Qu361w%6`e+|y9#a>w>T1H?2W!CVaH1Y|cSfjKW>+M995w&<=U zPut{PXTNV|y1o86jVv9;WEr0LzuaOdCc68<9D^>!YZ$XmGIT@ZoBRZIo6&3kLw2x7 zcYuCw9PZfGIr_O6y7R&8hVDzE`x)p?8r7IVm^^CpYVx(t?zM-juhlOD+e6bwu@`IR zUYNIxpF9a>3e4Hqr@j2PE>W91GM?!W-O*#w4`=tXcPMnZd-}WL=`dZ7r@O%H|J4qAhUi|e_Hw6OVDm?| zQ5Pjp#yXr9NGABp-d^>@Cmf?vnY5tRzZT_sr=AWmA;^$AC+AFAY2nQex`jh z-M!JoAsW6g3(he6)DzjhT>6nc_K{#adtr*Ka_09!Xf^TeHOZETsgI$B?U~Ep-IAC1 zTr{tEHb5tsCCBcuf2le2(=_G)@~U%KVpDW%m8Y+ZOR?8V_t-D1o{tX&(=yMQMvS?) z7qkG(u>k+>aPO=i0Uzj{`+(m<^d^#L_07HZ#iG|U5IwW4un-ZMP0zD6mV&j3J%wh; zsd1v0=_jd%UaROW@3rrEFL~ZK5O2D2K=-A09H011VdVTXJd*_1BDSE5J+!38cjioJ zcN`y-k)mBfo{pAY`?(L1=NIJ3IWGdVyN*wM`N)B3H-fwPDPmgXf4K)iJgO^1dkuL; zKi+E}BidIWl!ih(b$sI4BL=3uAKY@{X@4epaBh|QJVZPB8O87S+9w}Qo}*728g2T# z;e7+sUI6Y_U)W*4s6M~v^vFJ6O`fLiUi&N#rCCRvF=W~$hYw7<7u**(L)Idn&+DA! z%o=aW{$7&1e%SBDpeSwRnaIzqv@xV@$x16FZF5#yIcc4w1<$9|xOl;|d8BP8A5}Ad zM7NQ&ZCPn6NmKoT`PRC4!L;?HseZwvF$`j> zCHmVKzDHNQ4W!NCw{CSF54Z(_0-g5F5p18-p+{^36oFobUDxxr#Fv>V7<$D8p ztI2zh^0G(T6d(M|*c!@oQl<>~InbH0P2}5t(w?_ID2T@S|j}m5+Qd=St%`wr65&+WFp?{=N&jl=XcJ-#hqzzRJJgeXmNF@8^3V zJYl~7BJ+D0Wr`-S-a2`YIfrQ7!FR?XcxKJ$Qj8w%S7EAz{SiqpYQZSryt3wkRR@N$ z2kw(WPQ}$JMHo9 za_*duHtdXDR1W6E&te}__p623;b2DF8|Jy1g{Xg;6Lj4;_kb@3$D;mU0MoildWg4b z0v#p0bS-(B@9DSSD__LTIqGlhQrExHkZ6c@GdTAs^n=$id5`^;@TB{q`orM4`n)0W zndqgK`~DYk2zR1W)YsNHwV@$sLYO_)3Ksa4Q}?_pXW>?Y)iHg~0iT6aU-nYhb*JvJ zw@UBdO6=O8ZO?rMDG6TrNv!8z++lx7ZT~)aS#1~1x#US!?Xf3`S8f;z&BXVj`}@>< z(QF6rb!gV{+xkW{&8_6wf5smB2#xXO1JN`*qkGma!Ey*MWmv_F=GckY4QZO64bvP? zo+|RJJ#&wJt!RGGp&5+5^%?{L%z7yEiKfm7~R8 zTueP{RL_^d%z6)@jPz>qj6QFVy<2pD<Mvj&sx|M_ob_#s zCkkN6jQSc3)wcqS=l-Wd5;w!~^mEQ=fd=X>g+J@yC07nVaKdMwiNCjR+I zUZjVT&}#>8J@kyc`GeLCnes+7w~}Y|B`(c}$usyoACTr)VhC2HY2Fm3Y4~4x7?%a& z(~BLN?)xeTew}%5NEC_xF@K!UJm;*~Qpy#6X^-8ZwdAyc>gvjOc(pb9T$fp6tBf4<0eu?@hhQU;GX==RY zlc)UZJ$8}&Syv89)128G=!|a?%#C2)2;IMn?&0FU%(jZ|PV(%$(WR?+$(;P)_witK z%O>F`NYlMDOm_lw>&dh7);;z~8rz#3-Ve&ITxW$fuUaU3IdY&>?b1Bg9jdNiTuE97 z-`64+?;g$fGx?rAt7?2_RqkQc?VKn5j1HnM=7*&px8fet2~-jW`!^9YmoAj&pGW>% z$bTvSHs<)3)3D|YM$KgO^CSKCm74Df$G!-*85d~cr3^jb#3M9QZtb`C*c+rLUma9u z8Q!=pT2Xp3dmEVNFh(=ghtEm3gn45m@d&Zo*^|l4)@gk?k+dy* z@AyT(JyW<(JM9VTAnf-=!!!tIGYA~{z45A(jpX!+;D)`RC$ zn+N6z)Oo4u{Cm|oa~#S@Zzj+7pYE}b(fB_UuD7o{KbozJOuwsdHiL0Cbc`*rMs$4L zDLK%~_jM2MvHzg9H4W4@R~I2`mqd@X$72<^<&S{o^Wa-W8tcrqiS9h|jQJ&d0|n&y z-#~O-dkh{sG7u*Cp}Rcb^Y+)zxzDPL)<{B$ zhNEY=jyPt`6|K7964c1_vE*6*aKF7lGNsa4tGhDYwQZ{6PXuKZ)}h9vo^tiO_t>vU z-yiRkTcJ9J_BnjL`=MyQ_hf53m{X~5zv|l^?i!4Fl38 zIOS>S;V@lq&v71@--GTsqWcdsW*M<-qT5WKxug2+^F;TVLC4IrccAm}Nies8c^!05 z5ncJRvfgeM-H~i*RK3UT=NpGccd&l01#?ompXJ+%psTBR=DxSzUa0n#41sPcFL7sd zKYQc58O*nk8^*^R6Wvs3eEZ4Ma9F>+Pixd|gUYKJqXs#Xt$wbo%!~aAy638&H%d-+ zW$d-9pBu>2e}vo5twW$Y1b*HCW;=8ZKYvAZJ3{T?uen$T^B7UjZZ^##{hFxn(h_| zMD%kRd5Vhr?UyB=*OMn}-H;WVVaE6C(R4lAY9*K_Lf6=@Uyr8SPM*eN`t4tE~{}JS2FE--dy~s2D zg_N)S3ijEt{TX+I){(Y2D{Ve$jag|+Nn4newwkmBq#?%4AJJ$dZ6$TY-0;#ikk(8Z zW|Eh-g|sHpjtZphByAOGJdx?;i(QF6U)P^;H|S{68UkshatO+eBJPR$3Qn#aU^+q$RV` zM$TtFLt2p6#*kK&l~zjH=&ZDI(h37<@(b0FRzTX}$PQ;7VH0QGjnNRl$=O}QU5I2c zFIbxx>XnpD1@P2YYf0NlTCfk+leRr8t&_BEqy>3=8)laCXDy8nWG;DPpX|3EkPq(0f$HMgYsBz& z4zd@y-lc1cu3~YsVtA`a?;_8HPxad;i>_kLbM}ExcTqH5b2o_EJO1-|u>|97d@qMY z)2$&->^OJ*(TxLgFuFrn=e2^l2)bsS_X{v1?D0{dP^F{YBV2(;FRe-zzMi*9DTzs9}b3)tVM z_S-)ZUmZRu-2v|nNrG1k-ePD@7fo#_X&)wF*odbZ$+KXVD<}4|X*C#64M9$92J;N) z8aeSBFtg-D8ROYcp61#8_CrTgw;$!8YjmL7$IzV@y?&mOpZJb?KYXXjjQseUk?cQJ zuM9>^3vSWqiTp4%|6J19ugmi3=1xzTn@FQdB&I~qNe3%DS97Pw|1m&iqkwXgPCOXh zxtu0_A=ejmNtg;Ha$FWR({y4~iTI8jP`OALy+84M)`-vUu*b9DvZjl_GyRUT2kOYP z3f<9uEP2K{bIOeeF>fH~g5x7-pl@83=O>;*i1_9tH{+a?k%K!sTHY5dQmKbXeFV%B zvtQGG6E@PT{q~QjhvSbRJ~#cQ-p#~I5i7uo^3?1%-bY`+dabM9K2`GPA@uve@%G3) zEAhwxa<2^XbHS|oXTN=dWa+~W=CZgsC(Yi`63gh&SqKOd9hULZyOEuRU@Tok{NVO} zFIHK&9pF}wW^m`dJ=`vE%m3};jt94wv@+5Tr0*m{t1iSBO}XbJLv?1<^xbUFwl;pb zpj;{A-i}D-n`F+DwSYHaSHFF&_OPBy<7M5^W$@g+>dts#fzEz~+1%Sx>IJiYZ@=9r zTja<=$Co|Qc;Y=8-!P`x+tJt*-;6xn-*0n7!~BtKudQeOLz=1k>+eq8+rZp7e6LgY z6W*P=cTxA=gZ5_Bz33wB*Ms*ucT~SGgARLm%XH_t`&N#tALyf_qWj3$&Ek!DU~YZi zUVD<}!1j#($ij5TvdY|)7SZjK&HGX7g?HFq=bUgmc)_y-oq0SaQ8Xoem_XyPll-lR z@3l|R-uU;^^s~+pqQ$%zXl&z)qjiO`E7Yd4i;-_1a@+LTbU&H3WUe+%9f;qXg_m^u zeQ&ysX3ds`H?)4QqmJ9aod5B?&K*Y2JD5TH-NeE;HzX-K+jF%Y$Q?!%m!J#Ax-@Qn z_i3oFTcNS(lY8w3$>mcr`X=fuK5{u8$1xGXKU2)RCi}tL`I)`;=OhQTp33rBPuHg3 zmorq4S%YXFV8UGdkH_z|zs@wVej9FYI!-4ZugY>@I`{Whe*^hCVXyrWuwtj_%`9^? z!QA`Xz_)6?eNf-v=|%Cg&6!EjZG&zN-wfR=4xH{Lu-ASznr^|D@OSd^&9eW(Qu;<>k$Rnd-`TQsd+dbti_+(Yu9NUk8-f0_tt0V zjA^yx?+2n~i@9rAys;6?<|%van>3au-@F_Jf?)n(IMbMbg#CrL{y~g+G@G<5j z_g9Plg3Ivd*1Pn_z5Db-=btv`Q_LTd^0lX z_u+mXjBXv+7q0y`j+*7I#1-;7LZbm+bvnWS+X`DOIiwXXcQF~>L# zQGQ6q)qq!b-Cld9GS=zX$b5Rv&ZdeQ>#0*ns@L%k9tG@zY}yyqo!;RN2|2FXqYxkPi z3P%^{4aYeU9T`)fD7K-E@4r`{JenTMtaTptg?A@EE9JwYZS%?b=S9}Un@640W%T|2 zJTmj2z5YVdP>V6^v^4#kI(ESONoA+ifLHnea$I=2ODKzvT$xxJe>TfJWR*IB^7C(_ z{DXV#zwz5C%UwV2ood_#wrJQ)Zb+@m^0w1LwPiE3w^8;S*)I2{We@LOhT=^Pf9c%Y zlk`}4bxU0u!7C;fp!a8c?GiTrt;^DQe&1yAE2dFAz8pZV?aE@xnfdWEA}QfR{BHDU z!atIIi&ygg;Ujy!7!^k<_7~F)Ludzp{O=-NkR~ z6AoU)+^>s=pJ+7YD=EJ-UH*Ugy0XUHU1#Mi-$ePQU+%U4CHlV~p!|=sc!pJp>c5Hd z6CZWU-*sT+)t`!Om{`jmo%rS|%4hkav-*>xT=6~hXOxdMmISXByz#$wW8^;tURJ!i zXf~2(0d;;vdh-2Fo!z%MqStgS@%Z-0L7bFd4qhjC+kd^+e$1=`9K4WCfV9*)r8yqw zh4t)Z$|U1kD7psy{hPh!%~|V<;251}&i8Xq!PU-TON5segwjP7p;UL7VuSycYfO z%wGF$)#0rvrd^@_H0wUjS;iB;gHCpbdOos>RoLU3{5dQ+*9iXFac|h)(;R*keBXzI ze;5H*L`;F{=fpW+yZ<-U+%2@8vj62yEy)M#=al7uq2A!ocx>TY1GFyF8J9bqdasD{ z_RezMf4I!@W!6;Z4f>9FVq&!4(A2*a%&`lYpMTnGe_lH3UNC26#w#Q~%Rvg&5T~-7 zwps&Cq+#uU-Wz@Y5qRtQc8l76Zn}=XTs8B}w>eomBoYT{Aj4}#IAd@<-PWP zjn^mAnC70iDF4wceAn@PIp&k_l3!(fUICBa)|?^WbtU2}z>5+J!fODp=GDFSXtnvU zq2b+|15e}J0bWVhUb|Rh@|Vf(yvu5DMju*<4@FM~(}%(weI54hHtb#Tj-AHz*YM_@ za32%Kw-WQBwU_5}o(pEjPM04aOt<@;@#A_hx9)cNQ3v9Nz>k~mAiii{G(Q$xPrMV~ zDhp`$73n(q{OHda*DmcCp7=tvU&iapIxt5L-{{N0jIzD~%Ri!LUC z59Teo9P?ZCYy-36kbU+ks^@oyhPiZrdP)XcUqeqHy3d|1|I&3}8W}w0km2SG?de+I z&0aJj@$4|xW7lxi-1vmY@VM*2`TV1IY$mq(|+h};oAo^->*;8%en{C%uRRf8%HMQM7Q6&U(mXN`-F~m z`RTzlW)zPOou6vJOdaF$(~kzi96CR>g4uek%THg+zVYgmc?xY>8#xz{l>K^zulYcOA3$*^8x@ zpUhD=v;H>xYVJXJG_tibj9jRZGq7r({Xf+!!vE!uqw5!K8JRdCS}qtJT2CEY!E8N! zpM9O?{x{QgG%;lKb!ieWg0uP_{Ke<&bM8Xp|HWsU z!Cph!*JT4Lw#&$5-+sxe>n!nf4&S3WXFVEBYYp|S_4|Y*Lw^kETS(V9r_)MF+wjGG z_DVNR<;zK{x?rDuGHj9lqx#p9zTm=r_Ix){c^gREMw)&j{|jd#{7d<{l=PjXuTwg0 z3i`!$z61x9e@_6DPUY7NzkZ)By&^0r5@Bs7y^-`>SaX6{XbNGC{1NuiMPaNY>7z*> zDwf(^O_>(TXq}}$N}EgCYSJ(}%^%TRNZKmWj#di$gz5{WuOz)KD?Lei=VIamNWXyJ z);}j3*}EvNovM+u zl{J$Xx^uKBxr232#G*tS|Eg2{&BR;Wzr(&wb@~8?QV+X1&(1&%RImVaC?P z>P&O)j46$?;`X=N%!-UYBx?uQ+rP5UzI+VWmkiVv*Z$C*plv0I3-zvE*v>M@#o!h# z$%{>)&U(YqD#9kBP_WKqG2<}iUig36K0B!d_)9yr8q4vdcae@-F@Ka+L0Z!f_Ssa` z{1H#qlD3MpaY`|F*qsLgJ~#d@;M>LrxQ|@lSXM5HeSI{AruX^k9=|clg7_A zgIK0Guc~E46wJt1+vih$CxpltpH$Ov}H*9moBA-^lm$ zoK*b^VbTqx6{rk_*D;Qbw5iBb=3_rAS++gsi@ZI%}u08!5AJc_z+Q(iV_*AUK6TVST*9$I(12 zCM`zV>F)e>by?P16Vq{8{|{Y;_Zu$8s)JjNv!pso!6m_62=2({efBhdJL5BZRPsv) zoBJ}g$W*&p$TOZi!SPr}TJs(I><_CPf2#Pq^Bcr7lka-*-LqT{l~eAyHhEWG;+SXy z!mMwTV3ysAUW1o$JI1VLFtgs@6y19A6#qZo-UK|VVtF6#v(#iJGnq^_412)A1VqFu zN<_SZL_my)iWgL_qH-0L>kk1H6*25vfCym?LS&aU0s;cENCXrRL=Y5^AYlkbUL0}Y{*emg`u8mD`TmjQ@VZc$+||Hr zpLfQa#+Z+=+}se~;zQtRI39J!JZ&nF>(}Yp<0=Qu`4@5i-eA&}{bZBXXTc zf{YgMamYj7%Ci;S$&bfE74*cLRSKXdg2FR`C1hE8H~9 zcfvL14{ZB&H}lMJ8q&Q0Ik$1TX)MQo#}ns!9pW>AEBnS^#0T}W(7xdTe+%HrzR|^> zZyux8F<4)K)t39l!$uy*2Her&*O^Tlz-~pW;2WQEzru537hs;i7)|1_ax=>dexF>$ zlpkgjg0FYBs2~FNWZi60L?gC;)wg*T4h5$SL7;lCG(-v{w&z`u*@<;5U;^fxpAaK5wgTZTdU zLrbYYtU&soQLq2y{I_QO0-LV@Tt9me@1ADjH@b2B_$=%*eE2b;_)QS6Lw}O_|Kr}k z`oFIH_d)t%A3k4FS}y5l3&!WZei8Bc(~FHWm$3$ZU|;v| zqfMPTBT`GPWL;ogwJrP%RG-Y}S!PCLd3~AZhxBF8*JlLJQ(ZwT450DY?gLs9@HQcQ zJv!|+$lv`{v9|&Dsb8C!Z36px@cZN$>=j(DONlgyu#SWNwx!tHiPLX3(ud!VKMZZP zKhzbR0tD+YavpBD9QGuX#W(+PnOlJ71`V%C$Umla1T6_PM*yumXf;3!)FJzUmROE2 z3$*wEz9eAG2F(Q;-z{Y5N$85009>t&Gs?~&Zv#&{c%o58V-EJe5AlvM%gfgxUM&l^ zvO_UrtyI!03UhhfD*&47FHaNDx{QbaALMmHSkJmAaNfr}#q)lL_X4+dzO^nJ=}thW zn#$?AA|2js^}RRT7_=;W*uO{T`O@(j z+5h!1s#FjVtLW`vKn>7^+`L|8mC61?GWo zi@nYGEGqB%Fy9Z4Dc2>QA1?y459;Czg!Op_W{95y)(>8v%8wP+MVd^2zJ~qgy`267 zqz_m>IKCs|_X2+m$G?nt<8Jl=Tv1$y9adugM;%s2*yyYNZ^C3DZCk`W!1mbNedVpt z{tJ67X-~8HA+!$5bmc-|_CS8+ezh;>H#bN}Yk_Q7Ct^I#E%xq4Sm%q|p`(N!|7xaD zD`mTvGCAqM;Qe|l#<-j1gx>ew6FkFxa;p7ra#jFiwolH*rXg~;jSqmQ2y)uvgI;a_99U#23yU|z8o+hd{6HSh!15dRsR ze+_9_$r_Rb%uHau3z>4=>dP{N*AOmO9(WQzG0WA(kb5KLDnk0Qay`H@g3INajJ0!t zS*`{K{@*QEH(-{PtMu-$+KZc8!s|-mL);> z*QK+hOi{!bU)y{bir*ITuEl2l-wDFUylm=pmGrmaNI%Wj-<}J`Z;SlTN4!{K>MU&x z{P5!w)2c(OgRU0FVs6+YF9K^SWIYR9{VtYO+EH)&(pba!{7{kSpzAeOYc^h#jmD zJnjR~cUW$(Ai3qv4gGQ#hL>Ab-qh)en2T>%-pl1}6kcu@@bvhp*sHSK6rbD*&*9pz z-S4gNa?5m#JYc?xZ;Q)%{`t`~*gxVsnP0G+WG)}(6?2R-ehT6XfSwec$ol!QaZvlReQG}9T_=mZ@~*36h)4UH`Y+b( zOuj#2C}9sQ{n{0^FI0q(L$)N~6ai-u?%&zW^TZsMgY%mJ{eWe~!?$3zPgdUlE~^W0 zblg`ZW%UX#D+4^Kr;5EFL9YIO1+t(zbGa~i$jp4tEBztYE#6 z=Wq{rdO+3?mUX`&%hcth-P}LN!uz9~;e*$RhVW6y+GXl-5vGiQH6k7H(|q_Cf&q@qfNOs1I=d7a@L!5C1pB%P}7A+&z5$JxHIv$Hf0E6yGrq`k43Q+6bcq>_Gau_}-u# z1BH!3`i}?khk*Y!h2pbsL#Z$S>w@sFEB~2DpLNj8 ze?}<&BE;7?ZRUSu5PrGw8$SOYq~CVP%zyh(e8&R3{{;NuTtA&F!w=s-(~8l+x@t+CBzlwNq#;l+JRE8hEeo_}fpDQ%+>xbfZMtqVF|IQo7pN#ZF zkDK^c8itJJ)rfBad|5wAW%%Li=PJ^#J7MB~6^fs@81KLN@OL4;!u}H;zcbRGKWXBR z55@0`_zWNZM>meoz6~kAn)uI$;vYbKt`GmU8^=#v0z1=b6aV&5{8Yqm^x@xg!2lB{s8OKsZO!Sz39UpO?3_BR-N8gR|LiXbb^B>P=&B5>Z&79BP zET5mZu1BntI~X{Pd~)yh%Vk?$F5=ok#v0Zs>LTt@_Jb@dGbUoQYf=x;X{$B8-p9k8cLhZb|mc{RSh5C+`*@ij- zvp@2%hiwJ(IS&OPcY5{(PveWl-dcQj-pUH(N}n*(7cGOdjPT#!Dzk;{0Oo<;&Ui1g z-0>_oBgl@-^|RwU@Dvw&xo(Yfx#!CKO-~`tgE&6dGx`?pv6A1je!k2f(TynA9_aNY zhQE-(2V14&>lVb93cecPOD)6m`GEb$*J|?2yes&cfX~5v_>=t~w8o$X`dtnOtzkLZ zG|*B&i!zdm3_SOK3VR=D>D*^F)W6Wab0E>&qo& z-(u&!Z~(L(pw&m%=nI`?Utrl65jP)Ln>g+-e2UqI?cR&|p|se0!Q>A=hUB}pY0eJn zj<5$JuyQh1Phj;yx&JN}@0kjgqkmj8b?W`efjaMX>7+?3U{^yuNS!(d=>zP7>A-J+ z__n|w&0}tkfge(Kzi($6Y`p4;u+v9tdlK;2w_zmu%@*#v&#}B3pQQ{rK zJg*uuO`mV+PX}@8uVMV@JVk5kJ_6zZ>y4*njlZifH$TiJu*c??(J=AO7?k$M1&p8O0|43!(Uf5ufkF z?{VY!`AEOA#KdnLieHHMLg4q~`fpYlJ}zeovzKyz4!xk%#J}baY2P%&>r~?H!T8o7 zd^yKTyBZ(&@>e8M@Jdg)vzNh0U-z1czatcXHsa%fFZ<6Ah`+)1EkydxUK4+6D83Hm zvI+2|?SFP<_~C8;X-GdtcnsTZ_fY(9i0=q|X`Am=8Gd-%{A{GpS4{l7L-F$w-^Z8# z7M07W@oA`Tf4(UIG5x>HRe+cmvwr}|S=Og_~ zWa8(B;uj)*udn_WRE8hE{@v@aE?P|d*F*8s5P#8!-}lDx2P6HS2ot|~DE@53$6L() z)B48o3z6PxGw~xs@pT+}Hu2%d-#C66(*HBk#6M6sq@$)&}ho5)j_&N--3mhhXpHO@^;6kO!zD?I3V~s^yAMm5EjGX=?DBZ?S>}N{$N~qa9p0)Foln%2rb53g9h>@p!*wnX_1Cu+Im}JOG|Ndx^Iz z%Ulv9GkiHAlivvs-PX5}GE-2gdYs3*mu0>aDwFltbnr}zGRNs)L#FA2Q0|O9d_T`b z`abbyKWWP{g7w%%h+pT!fBeSrJxISG!Nji;itpHj^8w(?^MNEEez^0c@b>j|q%Wvq z;uj``#Hai4N8LF7BBUQv z*TjD`6n_WedjS7E%tiWBmEk`YwtgI6LC?I|#IG5O-w^Scz?c0exib9l{ig@g7rV{= zbFNlM`(`43oe%#S;wx<5@c28BzVj_6{+3XD58^$*mp&l-eE6_gWNPK+=kPut4Yy#Q zm2B3}lwf>bbJ7v-aFuv-x&CJv_<`%3v?a^$3z+s3tU0fRUFTZLHD?;|4yAa!8+Z-t z#PUMdxsBjS^~ucm`!ZcyVK2MYl-VS_%qHOJ=9BsFzb|tz@cP_l%8Uswb3S;od@`H; zeVJE*xAAsU=GmGdb<28Ljcw?Ukoh^c=S_ypF?{wgTJ!tdpgjj!q+{WLP@fy49lHT1 z{vRH1G`HjTEDP&;fLDStQ8VLbdV@(Y18`%Y7SW_bC9 zkl!^xKI=0zzQ%e7n%uXJFy!BeKGOy1o8M)Qmq$#wWV~p~`27&y5BMK){dV%A39-yU3c zrc}{6fVA;9{|2_&rXJ(0X;%%jt8rfDhP=**YtaEZJd!0xEyO|iMSHutkG3I4;7v@2G*B96M>mShB!Zcf&aQMKWnO& z)g9-jrw9ENvfo9R|F}-(gWnZz*2y^V2esw@Rwt#vEJpv7bORgxo+WTE$!9~E$V=x(prfHqDwZkFO!?xhd}DcqD`ep51m3Rf zhvWxsZ5?t1(#Ec$mcv|xD(@lZ`Mn=D zu%)$1yay51`&TvRcjzOgKTz9%eLs$kCRF4Pln?Bf(+g=YT-aT9zj{~oOQY^WPj-@km%0n@A*6bYcZY6enZe(DWtm;TQ=?9a z_i>h4+bCa%Ous(#2(C_1@j`HzE@GUGEdpLQ$UMa3;YcE676jQEc%Ik|9_!5|-Xi8X z2c8Q1rTK14fuaow|IS6(dA@r${KoF_c=t2rr{U$c1y6<>XQ^D)b$=-rZ^9|s*Wu;L zcOSTprvWqNUXSt4LH|&>+=n)TC-s&Ro(;jX4zl*~_iF0W@sPE z1y4$Y67LdzH}2L@nSR@m`5sPlX`qN;9b7oV|*|8_Rw;2zh&Qs4tJDz-{ErJ z37!i3t^eJbnDCV=-yLTiHCSa^-&M z!LskMJ&f&-wmQ6AIj6GR-N1A`;PJL$xkFfP@Scgw%f1cq_m+64G0z7g zd%Q}B+~$y52%c{Dm3S{BtRDdn>N)ToM)^Gn`R>w|uyz6WKJ3rZJlSLx-b>t$%MASR@8-%^+!kVdmVY^+tRAy~wdg^Q_b|)q$Fg#R*0L^;w*oxb zElRv=nP*r9@^BHvAPW~tdj?f#PI}k(j%oZ4@F!?vj+@4uhv2!eA@Yz4p4}}=4Bwmv z;E}pn#lAV+!CwkYdH0aYnErQ62O};YSc2>CY=YT7*k_t{3A2526>S}gQqHi2ywt$I zZNOLt{2#ea)&PU+&1@r{3-YgET(m7Q?irMK3Cert+BuW(U66K8S1Wk_u&(O?Un2O9 zAJ67-< zygs?z*^e-EQ7+SW;?arTYUlCRg8Nk$VE*!y$BQ9quA8Cd%>d8p zNhRKU`F@`@*C%&R`0|$3^Il*+@Qla%B9Ei5!StmRkVKmgP3WptD|f2z)g@FY&(0W!`1THrHd!(V2Sd zvUf)1T^w~;FT-vh>s{!&oN@%~+w&gp?JP5!+csDy;@vuESpGvodAlmg7vD1SX*=r+!W|4uU2E8L1I^1g(v17Xes?%d{2 z=Stn68`54xTq7N6_l3^kXoui$X+vpEVZA?e6I*60TMf(;sF$XkpIJPIqdfxrE?l6m zMxGXJDe*>gp76(QRD^W%L3^9qsJAaK;l_cvpWdiwABS%vxz9`jX4+9jj6+_M5!UbJ zylf203)>F5gC}oCiLo!M?URdsW{yAq9#hJdyOD`um+c4To_aO#T0^F6kHf5^1ec%n zxz)IMBXehow=?&PaQYlyM?ANjJ_pZb&Trx`$nUo$-m5%zhE%3knS0_a6_)~rX)#!H zl7QD8cx#{Yct;?t|C{rh6}0y8o+1-G&A%)0W-w1n@C53$9n>ym#(vB|+~?MTzX+JJ z4r(%H2l@Rg#yWtwp1`_`^KbKEp`GQsLLZbt@f}2rWj&^dZ-B-9Mn4t@EdRSdQ1I}6 zLWzt+w7h>h9<;8YtzZJ`HgF7uyMvGWUJuCdAdUPk;V{UMIt9*qLgrv||BG=T{$dW^ z2+X?3_j%y!k8-|)`vJ=>1kc`m=zFYp+*z4iv(H2BZ+{^-wGd|kkjr}oy)-tg+%Di* zbO8Gy)}ac(^H)05ZdI!tUWY2P3FZMa5&b@j%W|3J?hfilT;9FlDf|WJcD%;c_m$T_ z*8J}@nR^k){UH1rTP8Qe z`E8^yh*-7uJlBWr$IA4K*}!b@lE>Se$8vQZ=egGMbNy_5066dV(xCTyR)e+LHOTwuMx{Kop$7NviJzbWAY$&L5|YpJ&d z$K#LZ-&D{Xwo>m2Civ%H|GU~e|BftYOMsTs80?czLLWz3dG_2CeMx@X4D;7e{(j#e zU2Sb_@^LY#tS8Rn4x|w%6X!>_a~}ocP%V?2l4;wJ9}h6GEXzNp9RlrCIa(2Dh2>~E zJ_Jz!n(sX`);khGI|Le^@dnM+Nh<2bJeY-LG7Zt)PbnfPvedgCVf}5RUzj#BX&aIE zcSzfaT>8d@Q^k^yHV-%rU-o!+abIY~;~(=~fPsY9uD#&t16c(K`(&Bl)RcX&oc&sU z%O@*r7c_i4-M`|_%2zzz93K1kvdmyTm&?}{JOz+BiDeE8DxcIf%a!ldiprM-oYg%% z-jOWpiO}+~tQFvix0iaWqq+4N70AM+;_R1^6{9YOta5juq)8p36gWTppU0cWvR;$r ziV3VsmX&lGHWj<7Kfjk{C1FV9C@4a8yEmw%l90$?(~%>T=O znSb=#@cBJ;wRrouT<>S?SHq1wgdVHWMOHQe~t0~e9*dpR*_DEmBW9>JTz%J{*mSs()i{CE=Rlv>!+_A z2V>;A9p0WThYnVO@^xmMS9SqTYG2GpT#i}5;c*i%R#{dCcoL&Zy=xKHH-yUaj~hOQ zP)CKzGS1Sr0q4*=9`A0JH7dL;4|sY&)?++w{z4YoXJx3Yhvc|v@*8|x`gy!3Sk_pU z72G~tuFl};>MZrH=5lSWpj_s-sjOVNz**DZESHoOT8H`ISpiw!ak;|Cg8kg|pGUuo z;g7VHpAU?)LC0A|)Ea8J4mIZhF+hn4i(Aj0GzjmS1zj$c(Nf&p3#++3;Jo8`!3NpFaee?S6kT+*8!(+ zq{lmt=kE&YumC)LV@kcdxLikkbr@b2`uvJnN3>;5h_Y z3j^vf%pHUf10}NDF%Ii5nMnV`SnTJx9~=Fz>4;w$Cl z>&+<3Mc`y-dAv7q-+L{zEG#SWci8tKYdXssR=F(ny*Db7)fG4`#(BKcbsZ z3LFPMS(-WsbzDx5G2Z*h2acNK@zyPC&nzu)ongCIejL7w?Jo6xhA@{Y6TXPhrD5xX zE}c=POSiK><+FRCKZ7;t0_%;R?JOL0cC{3~&{hC%6DRzOeICpA zfd9d1o=U$t$9tc69MW}#tZ|Gh`xEW}8LGia7yaq|;6Bvt650p6TfnLxi#F{b=zk%0 zAM^fQ46LzX_anyqwE}ooQ6`vj@f{Z6@z@HmeR97&0G`ITmU{QG%ujqW!`VRmGIJ}D znQ|HP$w#Kl7ei(8e3F6*bsA*)bV;T)2W@gWS_jawL31FU|Cp~EXj!143(G&I^#v^x zG@m}tv`o;3m!su^Hn<#Z1!x%oG@b*tfz}VSlPp2n7IF4JNW*@dT}F*#@|Jcv8{lG* zw!H0-HgkcO1)DSsmk#fXo9Xb;BA!Lc(s5o>k;ed+M(h%em% z#C1Vj4>Jx<305|E@wiF63i~hON)5QlAPaxXgQ7@Vn7JxUBkn;Kx9~C(I;P zH^dbJOWx!1a(OJgYf|nWmu&D~!x)slBKP~TSjWgi+yP+avYcBH=eMi){S@Tu2xyKV zM+M^?qX_9&1N#7{zu-VVu^yX#B3$pTKd>Kxo#!=z~xyeJ}Kf*D*Q+Ck6Gf zlE>&gQ%=C%rv>o)fu{y!ZQ%KHxgpE+H+i`1&g1sZB1LP0B_&87WLKz!eSlp1Ffy%F!XsiWU>-TS|@#(mIL4Bwv_9^*S}&oG|Rj;V;V z!a1@FuqL5Q71Vo{%5J(rSxvL^yqboz8}BUjeyZb#w4d>nU4_QG0POhw_!ke_ZqVe|G0W4K2c^q+w}E+5!BgX&Qg3gBePwQ};`IuXhq1eW zr!RQ8E%}dWJwY1`8rK{DHO9Zepyh)0Hu{RO-r#`F)L;0miq+WLxAHAJSj8D(fyHd@V7aEtMU$-#r zlFvm3_9wPx`X@wlZt4pD&KL*sjOJeOJ6p(kf%DQC4mMqY#c}+{bP zQ+_Q`#%CgaawYML5WgDn%>vW+@TcE__yZNhbDlhizl!+VI6eM&47vY=y{%=b_jQEz z4{T}46Yn#+a3mmY@{Hdc>Ds21 zdhgK)DgKEGK^ofJB3pib)dJ%+!&u5H!B>h5Ld;OPSA9aBBt zM9eMvZeWJF_pc{-I;WRuczSj!^=2Tfj{=XJ=S+XqFlWn&@EsTe9b1m!ml@MITke4LO%OL5ShKhc zPh3YCigaxr`z(c)0VBs)Plf}t8RS*vGBjg(MIm=4E&|V?7tA)R<&zsur#H{!(Plq| zZ!_6HlOS8bN8k|T;-0q=rxk`9Vym+%JTJ$XSE@uM9 z<50e*Snd_n56c!sOkk;qPIANl2D}THSNaU2Zi2rB-k49sg480kJj>~Vv~Axo?BC_& zOf8cGs}A?!;ov<4-ae+BARER5W%GvArnsN327kj|=<}@fJREGtd6;d&*#8f*NDq)e zpQqM#tti5o+TPjXDS0fbPHhGZI|cON zpmTm&aSr9WDcf51sW<#frQstFURQ>pXO(X^Q^#ujX1R9bNs;9gA#FC&KEZP2IsrM- zZ>X2ip|HU7Amg!LBSjV4zVCa13BHU4o1Wy&c<*x z#0W2|fQRgTA)^2?vWH@SSE&rs9^1LCv+HBd&Ml$%?{#)=n@m{dJXw@~r`y(O@Vaihqgp7_OjB_-jKjS?h?$3Evew~9WNvf>8K6=2r8oWGL2K0UONf^crMmg8S--`Jf zd`_Ns@z)vuQb1cbveXOrtH89#srDcY7^bBGb%N8gM2u@G6craf>?0d<+hAZPVIO%D z3p4+`&|&e98of3}26Q_KNoe-koFGEI=MXVYp+ZfJRT2DBCA`CVn1f?A`dJgdX-3Lw zPea9-sc2upSy2ILqe2Mo=O6@C9$WK~&c{{pl|sL(VwOq>=c^npkYOa(s~a#)9^j`! zFxSt}=)*{{jOY&=ZrG#WY+_6VQ*v!g*YI6`esJ@%!1b4tCGhm zG8lY>g|=A5Q41ZjiWL#`g;o4)#RLKH`-d?5e(l+{E^$JqPh4UO(SR6HXsNx-C5}cS za+;ksxrE1liL>M6$eGb@u$Q__sg3dMMbnI|BpSr1dU(D_-NjflJCg7Qy(K;hBm{C; zo1oqPkKU1Gt&8Nsn^RArH=C_gY=rOXXz#1qJDP^GDw<_W^i_2CCmAOo%B2}DG>kAQ#x8pVVY2hC~^Y9P#;;4gU_tE2`8=m-W zYlr7cG~Fm9_feU@1jYU<3mC1^OieL|5%LqGSYzoXaSNhMA}}n^Emg;8vUp}E*B_&< z@;6HZN0mGA9ISNsMHPVk0p4)xEeIpV*YB)J=nQSJAqFj_18vvDe+Z_>`O1?BPE%>Q zCVp3$JWk{A5{<*0{$@i$YBp!Ig<}=R_&=5G_;8+Vrd{O69O`jQK8_NTH2OSBd~HD{7DdqFC^6T{guMzqQ>5^0(O+Y_;18 z(VK<^b()CPO1?76=*DKLES*=D8%j2wa2nAVBV}y^zWPhFQ4YN&x_X01tEFnz7kDu?)zXuLx#w9rC_m=eL15-U@N+6bT8oo8>0 z@CXOfSqOJ;JgHNoLqULb7b=fm*2OrL29nsx>sYbc|Fn)7yB-ATbr2Vj$EtUMp(QO> z#S^g$RPnL$0)iVj6_{KP;Q0)Fq>2g3AmtNd#^6FBF0wZ*RK+gk5&6qkWh?R*dd zI`HB)o|`TJB(gPrKXFOj8PtAG?&Ga!wjw&wWTTGF!gE^wXG;ag%amh8)-phCceD_q zf0IoH(bu!EV4VyqCa1Tb;EY^`Qei~ZH4v(FS3gxmj-swn#6pF`-^&c={9AdP^E6SR z^%1!Cn5IUEOA0NE5KC2>8^PUZOoSMs(ZC3$NTVedFD7hB(vc)&cp+a(MD)Fyi8p7hnw;n?hruz?79|x~LmSHNL^e;)qniNk}1+Uh= z`4YXe8MT%boM4p5S7G!9O*0f0v$E`ixMbrkRN|EUNd~`VDbYBKr11QVstJqkUF!npLJtdR?eVvxz>niuF`Wh+nAg*H-bNg*CQKJjd;@)SqJ&10!e(I3l3a z9*n5_n^lao(jQh?{F`CFN4{_A1m@SPUem-Rh0beGO=C}J;wtBExJo~1&}1`E4dB$P zH zDyPVz8VjAsG0gyl+KzXMSr!`R6iY0zB~iFFmopwwb$gV!5$!RWY}GyVtx2agUr)7g|_bonaB%_0JUi$g=Pc7HM{^ z>O2Rw8L#AOqEMkvG%-)5Nt*bK>i}#uSlrX&)o*oiMWqwE_*$d$y2#b(C!?Ei*Z1bs zQEnQb(61I{qWV1!GSPq&BE)R27++@umX+tY26Uek?^~Q2;*haDjSiYGtanjM@dN{7 z8g9)~@I@prdB}aH zi`i%!U93?#{FO={>O4gujQQ>(U2M}hykDaqb#Y#!odyhdfiigjs8HTx24jtOc&^ZC zj74nLX&@#_oi3C34$~#c0@OG5H#a>-hcqlvbWy_%V3dKZt8~hk0NNN(wH~8uy7)rj zlI~R&sOU1IWtUm3b2hj(o-{bIio7a5G+XPji(Jb?w3|;Qh^yQKzt`#a1aX1BRz6A) z-$rPkRuN0=gz#ZIeNjc6v(x-4Vo(&#s3P)ROkWp^R2Skncr2m2)NSi4HIFKEC`!w~ zhBHbVNIzMzmvz!Ir`Y5KH+rbt0im*T?on=k03@s~10%#A3f2iRSiK8t#wcx$g5_c$ zVKGtWT6h`RW}$!uMC#BO1HK;5W1>n=EIP_ibt8tv5euEShyj5^0`i_x+CN2KImH($ z{TU@nRQlB^hH6blIMEI>)$g35$U>hx#b*((AiOV<4m*`i4qEIKyB##aDK0_-bc&Tx zgaqG3C494M>~!T?X%Jut0=aXad7!Dj$sbSu`1IvFL+j2 zX@^xD4CX<7&QNG!l!EDLMHCKFzC(Q$MA08nVtBdw^eWL!?!}a>&|aJxsiwMQ4*mE# z5Z#G8?skPcI_4DFUv-{x&_m34I7T2IZh__F-A~dn!nX9ub0jutiSK?IA97u9qIQ_3&pIppnZ>5xuFjSvOg!jKvRMQ*&t+R6+~tnwB8W<(nG{Fi;htJIy& z&G(D?;_OHK$IT0NElyh?_f<{=y zWPd9ndr3TRx1$}Jc!w4D&s3VPiJw$jp@}IPhq>aKf(OqBnYSwyk{F}Va0@oZlnuQ~ zp&cX!YaE`cMI-jGMhA#ZMjJ_F>r_f&jZQ^`PdIRx0p()hRX!M_oK=q15ofeQKD-JnmL>;j_ipJFut70gpj<^!T;nT5{Syyb1ukEQL za;nm&bwzeHrmUz&^XrN|H96I#nkhh7TZ_?7*5cStYNtTT4(@cw$^%QeZr3QBSGi9( zpwcB|nkb@^Q+C^fbj^GbEts-$$C)_wz#5D|*VM=r8IsNI9OI*Y9=VHrN zevG)L(%Kj?SLg6SovyjW7et3+M5bkmf*(IYONi!;+{hS|x;-c(BWZ|BOpT<{Xt66& zL-=GQ&2fp`?-@&#E2`=MqXOXRA^A7_*tQyk!+l~ z7Ad|}X{248(xBsgg3LsUQ+hp+zof=jY+{~;CP#|A2+E8Uv(3I_nXkrgF_%;W)y_@! zt+H9gio-3)9T?A>?!^-`1!lI1=ro8^^A!9DV6idl%QPWixbcRKh8u*s29V`bm99#O zoRCuUXGJT?z*Mv1Pyu-?C!bxi# z&@r;GxXibuAzW&s-=oC%NamjzSrco^?npPngYCQwW!vi`{EeM{j1s5q%;UAwoM13OJD^%Mj&TEC2}AeX$rr$`^De#QN{Et`dCo2g*z!0j?H$ky6Efzu2D6MI(F7{yx4H`Late3C~ zOi>c%sbZ5tV^#5;r2L{Jz(6rlr5t07nxbr6-T!>S?CWONwN?YMAvKqIGFRL?26J;@ zo)|_j(eZQ!-0@gLv00iytn+UsR`3_{Ts}*|4=&IxIKsfw${_JKH4X%H#DG@qrcUCX zxECco4!@bVDxP(zp`@86c31b>Ld;T{4pPN$3SBX(!>r1LTfsjUMgpuv3SEG5slvaO zg_{hK4}sy8BMRPbWvW?5V@%zr+?h_B$L zLn4o&K*FY8YJ7=LA{W?8C$MHPS)rd4u~gAE;l(lqR(2m3&OJNI+}?`C{Hq9m4}GJMg=u z`lABu7p|RL#QA;AlZi@;ZvbhmikTu!Hspi`_)oL53+GgWaS8TmxMk2Z6KeRy| zZmgibRgdSByPn@*)KF!_g!=7ZmsS!6YrF+4!O1vR6*nR;oUOUP;)idzx*A~vFjq-{ zDG;mQK_kv=fa=XTCw%(&0)2r~04&`aj`F@xJ~gst?q%b-bF`?6iM4xm%&V9(5M&W1 zOk-}xN9dZ0wH%(VJFo?UqQJ8r%;`%sF@lHW0=4N(fU5+*t$?(V&tdV-Rbuml%I)e1 z)6I0H#$r`$hDAOo)6S=1!|Ko4z=sO_O#+H4_Zl5L9SDM|-m)cYHjU@2VviDw1Cb0B z-2k59AOz&2?p?^^eY9G`lr&CRq+x|j$k)WrD(|{;HFdX<>u%ses{0M@MZ}BDa1zH< zT1_ZiLOy|+igdAAqup4^u*#4)q){%3aXJ<1;()G}8uP?GFoOWf!Goy|{R8bFf8+R% zGm-)0kxCZ{>N@3FM5&gr4toHdGA&}a?wV~8r%0VFZAutaM#>71@?d9CXtvIoEYLZV z9-T9}PRFLowO1FDb#T?L)nuz71K@|J(fd}6u!Z^8xcjBNkjq7Vps74G`5 zH-XM6%xUjuWvfzMYDU{*Fz>|fj}eEY8)C5LB!2G_Fr+MX zi6c7t?0n1^F3d-9M_l52qBAa0jB`>k!$M?12(abZ)5UVPC?TU}zX4b&|*n&lFQZJ4SrMbh|K=!WsfV#HeeGR!EY4q6y1MnzSh z5i6EPQ3*h!ko-d@or@74JCXdDlLkRQi%vqtMsxDR(Q!zQqEf9q*c1?Wc$R|veS^VE zIQpX>NSs${enVoaT5mmx9V!)*7^Ed)*P_u`!secqk=UcvoJ**J#HqxV{V^o==}jb@ z&Xo<=b}s>Sv_f-;t!q=D&?q&r3>{YL4IrLz&?UC0K=r8fsoc3@ij-P;-%` zQwnwS>&0H>eI8FUl-^rxB3GsLkuVF;vPkg_jxQpy&94Q@aE+$2_k-()NU=tvZz6fb zf__TtJSGwarh$>dqwiAigUwGiu{feG;0{OB0wv2D|Fcc}faS&}JXRMd18sELhE*Vb zk4^S9Qz7Wq6BUKE8+-G4%1wpDO@STy$7&6Pp*7`N*armr`rlOE?`LbTf<9KKMe{$V51>8gN)?x$C31*L!6FG1pinVBpqV9oj!4} zaq=_cgwizj-rgG}->Ed(hodR4nqUXjQTVMKSoDz1lL+4B*F8Q zXYpLF)Sd(joI<$wa=Cgt!sxx;2)6#hdiSYzFDRFxLRj&kTe@Q9Eh8wUIvuf!B}B8V z;wz%1RDafZc-Nklmb;tyi_a0_jXfnvkflOYj_pnMiV3*%tAs<$~#?6=acIB~&B2jj#L z8|{x3Q*5s7v0|l-mdA>7k}@EYR>g^|NY}Agu`rU(#frK1M!-2{rz_HsawbL$bkLC) z@rk1f=-)W#`xx<~gJ#5uUmY|)PJ9z}Gh_{MQb{c4GujX{SQIF;g?XED7sBvz>y6U1k5H-4GyZx#1p5A zqEh~i=M|kkixNB0!7xH2#;Ev#23Q{@&O10_KbHi&2|N?Pa5O{{M{!__Tx({;6Y(%w z;#@~F4qr!LtQ(3>Qazqs<@qcx+i5u7QLx{c6nyFh?C9E6`7rZtoP$c0@9&Tv;Cw#K z1D1Cnc#UOF1kdLfp*U~@^>bDv(fcuQujvSmg`sOogji$Y5xvVoM~$J(hisg8tP8i+ z9;zx&P_d%*>3vqwe67lHjzoG0<-&`u_~(o8rMrt>QD6`ljVl3oQSmJ{D4Zh|zyFP6 z{=V?O!ta{N`27IQQ^fOhN)d1HfpCAyQ}}FHGPv%>6AL8F9n0lz7m0LM`tW?X2R4G3 zq83`Ak>0h+%8ob(VKvqqC#~3-&;>rjRpADW`DC-4NkG3!+AgbDhCyl-7kF05wsMeR zUpHXucER&Qg;(@qg%|TVDt$$;q<^KXgU)4YXt%ux#bJR`doi?9?6Gwm!r%Nkn-*(M zkjGskU?oxMV;$}=ugTo%riyxVhLQ$o_zP^;m4jMOShjUmpfLygi;22;M0qd;7Y*=9z)lzfwP!~}iwih|gDsL? zI_?yoV6}8AS=Oq5;yB74h29jE4DyO7rx1su2*Hs~H_{jd<8s+vfdm*Wd=6!7Z>e4# zjRvjzb4|fc;463&X^{x8;Hki@666K`e*XZWDQsB2dh#mw^5Te%`lLv9{y1r4k5c&X z!y>%PCQf2Cisa@vXhRR93pR00o2hKJi7ixXm7xJWh2&@{X)^0X=2?)-B&Nc-zrAa} zp~=@Wi1!ZS!IJ~s&mz8tEd(1NXf1FkQLFxF;d48Lzfter36+WGfh;)ufwI6-b%Zek zm>bt6O0y&!qQpa^!O#=pq(UBtn5kC3>JXdM>Tqj9=C?U`n+E!aI_-7vfmZ=sqHv~# z9lOqSoTMDHi_Jvm?BZLTa@oaH3)A<*9l-(bR(6>B9Vh%yvm%(j2P4xVewE=;oXJOt zV^*kSAKK!#+r=ImX51nyo_0}UYrFv}PbAH=i*1p$bL?D4)Z!x?Zg_KUQ*J(rwu;g) z^L-hGuc%O7ls1m0W0g7&127aRCklinGHg5OLuowdv6}6VP;eY^#G(M~ltqDxR}i7> zh2c9wISDs{2&I^+Aw1gx_61hjW)+*QwAZTqW;Fnfu~buuy{4e0#FtQrEy`)V0AaI7 zaQ@Iwn$SI>Z9p2Bdbpo-rVLfQ^(;Cx4^Ez7@vM7CRZJ((XqZ{%C=VluVj+xkh~G5~ z)Yw0bp=|CcqVGhi2WXp$W`iG`1Trlm@jM50qNysTTik+zMGYXeCiHgad&-8cd$~Nv)zQXca;d0Ua z*!;p{i#p?Yr7RL)4Ct81BYF;6v^x0mjb7ud;hGW=(VNiw_H!Nh>k(w4Vu07-f z>r_SS4g9a3Jfu*b9s2~@YsV$J*9+ zN|Wtkx{Zd~73j}MuriXy+LZxz4jZNO<|HVQ?;#giDrNX43z?^yN=$m~`KmGiuAizl zMd_KPmaU$g=P1c-sz~?^yW~PPYipP$Mv?}+jigP+vOvlPy&A%BC|_gIKC{qf3y+z= zzFS90_!k{lv|fZIdOqfLIPUXGk39Nyu=-Qsm!q0XyU+C(gCpr!fAL!+?e8zXv(xww#94dtun$D8!@cwaaoj=M`-`nnw7kEV z>!eBj;cAh*p+62|+@t!7714xud?&c*!u#S67wvyvOpHn1{=V22Q)krsVo)rd>nEni zCLil3cE={~?n9f6 zM5FqNtvA)dw{9=p7gJu$tS8($FIQ?1U0cg5)HwEtbP zxVn4!d*W#II`iHW(`wL$_r$sy?(Of2q8jcE?}|@r((-r3xLP#tUGYaP8uhN2QrnID zKX%r3UwB6hNOGTiM|_t=2j3B!>d@x5#QeIn>kYB3uKUUxqO`92%o`%_<~pl-i8D9T z*j{3k+r6-t*x+^#>Lo6?-Sc{j74_&!FEQa38rxfx-a@;2iD}91oZe!0vinRgF*wCN zsJHkog*NvR>+92`H^rO=G_Q~Ns)74tAMpqN?=2SJnuK>BPv1&o`-trgX;&Yy>^9oa zTkN^bJ?c#{piy#8AF;fV`(Ph&u@N2YE%x0`7y5{Gjp;&faj3C-b00D4j^yRN#TR$D z=e;AY-9cO57DxU;tNMy9chbDK#ECoISNe(xO_Hy?CAKz+zVf#C@ow7srnqvqd+a-6 zZqwwYZ;Jy>lV|i53scGarpUR6j`S4+o6)Yf#LQ;yBX5fznz@(0DMsF#l=F_*dM~Yg zTg-1x3;T+(_tB`g#M1lRXZnht?@K=OmdN_2`^?*7-#=;Xn_~U_H0T{Mrv(jqTYS~R zJ*cm^*dqDZn__OuI-C27qb+GYT>88%-IwuL@<8&2cSOMhb|ySP1g z%t)t|cq~n?F%^%a>FzOjOnAh-44MA=5t_?+Z%@TYcc49;#p7CgIt}9KN9l(_iWuF2 z*5I+c15L-{#||_Q4{rxLF;Ee69;0vY*!~zT!K3ssnu*8E$7v!S+a9Npc$|Hlu3;j` zeuB>9vE~Unfk(j;^b;OKJJPp!Eb2&K;<2YAZNVygwIi*;WBQY{1dseDX(k@0pQMR+ zWc`aq;<55ybPbs}^e;M($G}c>8N~UW=rkVRcA}s0xY&vI;4!r`&3aRO(U}IKt`2mj z@81?@I@5GWyYLhZ!(-CZl!eFIr~j-{g6Rj78GTd(lNrzJ|5hG(48eD)D3aaH3nSSO z_?cZ4IowrbgSkzpf*C)#MZU0GvmRvM|mv0_K0vNe(pL=vwv z>if;_@vS#^C`pNg7jSN&UsdtkEd|m{yI;lm9y^0$pJJ@7>ifc4mgX@f?L3=|&ua9Y zQ-hD_VW)-@`>&kZF9f^E`Uv=AY4Gn@?9|5D{=kN43j1j(LwWZ*36A>EodcC6S@cfs1OJO*_WTPZ$W{xOh)>u<2C z6f51jVVjB#PJOXNWd{P(U<&ML&wpKC425~9zF0}LupUfyw5lF20yFC=*u(CtuY6&p z^(k;hp{*(6&q$h?EOy#yNlEro>tx9Gq?-$9+FD{x|UzrhuW%AQl z*X|VYODu|iFpmDLFE%Iqb7%u`Dv{-7Rj08Hl%m>9ADVR`E@yXs4jDlytx;oedcDCoo+%RPd)nj7IB$3*<V@vE(3 zY{Vm=pN!D(w)nXSLO93DKxO#Y$*ytWGiRi}m-LUQHB41CEZTyJxz`y(8JPxYO zL8sWjhl5kBbkeDejzsWy679T4-D-y)bk#u)u|>a$DSF}&J6@%uWAJRIsQnHx*}|O5ERowC;+%yxIAF4i z%5mU)K?Oa-S{rCzTVdA{d#%;xIm7|pZd|o7c~c~O__ryKz_Ry(WVti>Se z+yT*lHnN9(dP+epWsOQ7)x_%xw5X;AA1_eQcfPBoLGcCsb8OdYDfyNr2#>WsxwfX} zvC_2K+V55xU0Xv#pR1+iMruQAX)ugksi{r1*ZZ=T_O+ds*V3{bG`p5IKI)V{p_XKO&8i?Lst=_d-+Vbiu!e3OkLC$wFe5|?+at78& z0RJB~+{gur^nQ91OslM0r@B|^Vwt&}cwaPOIyS<5Ceb%8TmI0^J+J*I<VICsz6r!IZ!~}C=>BI0U)f>Dk-2maF ziOts(jbD?<;=|S#WWH-u{TPXN!_`p}#}xLI9Eih4^PMN|K&JJ~k*!Tv2I=B6u3ymW zoX}D59rW-gaNf0OxlXa)hL}N40wKoF=0tOfpJSbvt%b2fGKQ|hA{`u5LgxQs>dH_c`N&|!Av;T^05LB;t#p- z5bpR)nV`UMFvW_+5)^)qg$*SCfxCzDJKQf6?GqJ#Gi+B0Xl$gs3nubk#{E zL5JhS9H+V$_WJ0zw#SJhG0i~FizS5D$8qcyvt?qJDZ_Ec!(#grC!@ubs3Ryl;NttC z(k3g7*GhLPbZfJ#S459|`nIFkPVq8=)RCQTgBkp^@7I&J;UzQ}hmE+(em!*CZs<+d z!x@a?Plq}){Cqzo1t)S?)pSBIlXv|%@7auVQol(LS*^KLxqBZ83=W)x9@1_bOky_? zC`Xx%88#|+Ut$+9T1+_GziqbkZUtok?~JdD;S1&N^L%(q3kZ#W+sE($CIaP}DZ+I| zL9NeFX*R!nYoOZO;dwznYK5mEgy^gZ;CV}TJmGCH#>$)4(g-n1ry*7`iO2rR2qw?w zAq>u#1Ij9(u17b+={(m2h~Xr`5qlL3mESt)d#5nIqLUcwU-`92FKs%miNAI7Df z3(W^+8MEMy(dtBXAc;S9bXHE&4Jkz=s=Bx8+;hI~yD|3Vux;#)l@h1wtCWe~ z!~G!{eZGPLL_lt|$Ef>Jf7P~q=H!twaJh1qNDn!B(rb83;(1>?q3kkwgZ`eZyi7-?X&?Fc%N>wU;5b=4zxWc{d~OK!n=-_;rgP;BP|#WY0CF0 z^_~lu`C(vi3_etXvf+jV<<~A1w>EFEQ$EFS#~9;>h*O7@%}MV*=lEcYc07*2F)*9)xh8 zUyoVwT#puFX<~|VV}XXs8JE1;)vm|91Z79N9<-G-fQ?R{wY3vrAZ>tUdByekkG1lf zi`gsAF6IWJ#T6HGTimZNCgz8M0bJNIamt3P?d@?TPT6EuJT9yCC0aQ&V6E&EuvU_v z+~fNx7HE0=-B2+i)2dwJG-r4W&vDu&8?#|%+y2QlSZC2_!u0*^-nX&AdwKh>^g@D- zl&=#Ec=}bG(Fc|$IOoU&C(<9>8d<(1D50h$P*d zBBBba;ptiEVi@ z*?xVNY}-?bzQNSr3Jv=^WX85Q%DkYH2e{2iu$Cmzy;$*8CI^V=ejhB2UppZI;eUN$ zKrU5Wk>A0s`yD@jlPU%FzTfi>3EtZkgSK`V`M#g%21JuMZ?Hv6j0;C`E{!A#X~i!b z9qTc6mU|9v6xgmie3v{eb-uY)_Wjqd3p?9bS0ZF_#eOLb*}t{TKmXWBiNLnq>VA{? z1%7U2smC8#>JcH1=+U0X$de1G&u^_HLL3u7KM~w{UQ6^W_riKx61^3_?YH}m zO&walaV1p<&$a`00MaZ?MtGWIAyPUzO$K{)S{fM^vy6ajmuBycBWXAlX8BxoZ<;|6 z&ZGelF$;){Eop|c|1?dW`OUH^pyx^U2ef}0k3F+I3+l;KnICH&(al)1z}XlI+#yc8 zq{*~+v)qi=EdVJJbOofe1hY&_)H!K#JW5G9c(RezaXiI{GGkKB*O;Cv)4k2Hbc@lssd59J4|X-n6rZk4#ktn6fW7!9I+&*N zwo8?M&~s9ybKI*|QLvO^fj5X$*bM6Ox*^{a`4reavh>VL=LD~ z&cbrfw3+$YOnK@v3w`)_ruE_BS@hx69!y)nE@jE%SiPHRQ)VnT5OrND&TQ;ZL@z12& z0iLDX8H~uViY{i@rkx^on6VM7Xhp=@bu41%)Fm?t7W>-0MZeSwspdhQ0z(6?H4VgE zb1a=f!=+g|eMy?!^P1%tX_GX=We zJMhr3HE2oL8h0pc72OZp&O=kI5nu_Z^iYa5;(m%XVrZ%zcuA@?;$bSFOrE@dYWMzo zYn@I|cz`BD==5~9FYtMBTxZ1WvoAO%;MYF)xnI@=EJ^=3u*kzN&~@0XM|>+Q$J-AC z9ocq#LM|2vW7Ie;G1|{|MW2=5xtJ+D>5pX^(zSaQxxB_$Ht^oev>vu06U2vEHmi=# z#JSOJneb7~veT~*Gi6~w_hbUdGRvNzuF8}pv3f95?#7yBf1KW?kH+h?Oz1){VmX?i z?Xsjpy45^B-S%CVZuOidxREIxGOUKt8Me)`3~SH93~Sq@h}F3^V)c9(u{s|_tcAle ztyN1iqXTA4dkLJY12$a`*O7H_$LiRCUt33ddh}eaXdGl?j2^CK z1ihJcO`l*~U6?*PsIGKU?Os<%q&}%*x%QiNq5(US>Emk4MbhZCjp*OKHbj4YQcL=w z$WmJ-1axL?*%Q!>wTW!emJ_jhvz8%f7uGU%)zn%B6g*eYrsr$x$sB-!^^C&f&)9abhQ(TFOOuM+i6UFjMkHa01wm+BfT^2@ri zDWrSr%HfcXszXowxL+L^lcGCo$r*b)+)C9+Wzs24dzHz6G~HNNCa3Arx@65hURz79 zr0dEuSrB2v^$|T#CI=$AwM@=Nv~xYV7tsf0vMBT8xilb4zpO2TEjB+XNAJ{@#W{MZ zwrtALt7URHM^BZ>&`KZgtu13J>&jBOUxf|3R@DQgGOVg@EtM%%wR0U=UR58I%EPK3 z&n=bq)wEZs9LZzDOL;n}R37E&uu|!fuUAWDRKA`nm1FrIw=b151^T3(Oe$i-1w}fj zzN|0O?)7C~k#4Ln7mIXheR))*GwVy2VjWjsmK5vFdUCwFavh#luSx|AYE}Iz#G$f zQ<&uv`P4KSrS`Tys%BZ?Gd}~)HgEJ?bZfLXQ#?fnf8k2m_VShI|X zbA6FG^9g#zn+16vyn${B=6`HTFw19&lf1idAGqN-BOyERh_D@OdDxnG6iO`aK-d~L zBE=fIJjHe<{!XQjQtSXDQmt9bQ|-V{xh z$omKnU)HGZ$R;K*!Tl1@eS8UCvd!+22+or3aX0M?&zw%#Ov~IagJIic%haT;_RG^` zJ(4AZLQ45!NUvncqtIsiVONSC&z5s3_5)AEL)o%D)%{^~x(?2kh3WP~w+!u@&1+We-HtLsU&3cvMAc*yO^FtEe13?ZF=F$0=aV=Oy($Yq$; zLH`V!8ev(Xx+ud?!rLe`2uzz%h9OhA%AtQr2F+;k>>g^2K7;Bckae6I7 z?sMxhq<5-qKP}ZP4^pk3L20({+%(&3XPO=TYMLFfSGu)lX1cXuXSyBtYP!|gE5qtp zoe{ks8y$0;e{{rom|^iL_BihO8D$_s2RRR~QYMr@D^A8(8GRCti6cOncOY#6^-md` z^D1iff8WXhoj^IzoN_n9=ovC5XyuDRYxOg?jDJ8&+r`v4Va)U)X(U3VkhrYMKfL3%XD z@`XqDr9*|(ojlLxx2gdQ+d;UYy!+Zj|akZi~;hx#!bv8A5#cZaVlTv&=!O zAYIM|^l`e351QptP#2`js90;>(O9czNSyXghh44bEn!Zh1{ zZ<-yQ+fM!6)9tvk)1$ZdRGa(cFw^d&72=n_+8nzly1fJ!K--ad2XZoM^XLeAbaMd>L==Onw{c z*o*uR>px0C+Trc%DMl0XMh_~2f1vJb{I!?Fs&9=3XJg_R=?N-4&2yds#~ zxGin_NqzX8lbtNWO9MRJoI5_lxj#jG!mE@|#AsK3@R#7d_p5qN%U zd=i<+!@dDY#=IGsBp2cydib)~A{ktTqL=vmZYhDuUe1rGW0hx^=YY>B4%cB_xnWA8 zQ|_j}aI38c7I38VR92DK8>|4$HiG~8{(|C8x<(jCeb@IJIEc%S{?)oJJ&NIC_Pn&1feJ@ z<^CY~AyN9H7U5DMP+p>pFNToDDi=!qB`7Vw z(E$F#`<6wIyV*T13S#hF4nw~1{&#%;w};G-V2q1i3HXf7u#iAUOKQK*C@AA_6ceOhoRuHP8IFHMyluHG-u8lQz?Sf+ zu#Ys)kK0|V6`vo}=d6c1k$!$?Fddz4#4ufT5gvp{optmZ-*`zyvs$@3ln#rB#uNFP zz#dPEIE%fFCmia1gEHVzI>XYK7b!E)0ESK=GQ$@<4}xvo3>D0gqdmHAe|~lO`Y>@^EZ0>zr{(?*UcTUX^TSHFD<5OV z%cZF3&~HYsX8#~p^DX)il5Vf3uZLTA&F$59wS+Q=d3V#|SNMFdbQ)n_C$h~)v}zg& zWTF#pSAy1#}Q%2 z@Ag~ha45MSwZ9ut?zMok<$*5yEGKlxpYL9g=%^{(2!z9Fy^GMaGsiiJq!FOXfOPTc z7Xj%Qu=2Btcx)-)k8NYM0qk`<)1eD4e&wCw_ZXxU( zw9xjFpj`AR58~+oD5f$mRe)6+;Pi$&JbcBHXeoH!6IF zkmsUYnPBl{JmY;;tnTAgcw*?fTK_QwN{+fBYh6kmnxU?~1fr{B*~b)G#p>cboW?&W7}vS+Y8d?~IRHPQhHy zQs1>C>jc}94C#70$ypPp2b1J@d@Jnd5_Q$DIS%NZ)Mn2QwU1+--1AI?TlvR7#n98K zdzR-PvTaFn9g!rSk=~3ON#?6hPLf@|gAPB>41|{_$?~9%;;|X*WTq#v;dx2Y6Avs& z#>X%BU?Kp=E*+Czb8CP1Pi8qt768az7nJ3mmnp-WS`?)IcPSGa8xLqHrkpZVm|;OV zt^b4aHJ{E2qD5x*Fa5g0`fU@+(<}PVNn}51_9Cb3+#B-9X?yGq0~F8t&|W0;CM{dq ziu`fgIju~z@ltCGkRmJMuRHNgIqxr>*4m~S<66rD>&iWYW!t~U%fIcq@5vnc#)n|a z+7r(IGOq6N4`p0@>A4RqHFoR+1dgCP-%BX#{F(04l7v7d_xowZW zEz_#${Ws-UHF8}`^J*`BS8nIMJM&%HoBz(WcVudTu6bKNFVF>V%l!hK@RlqnWdBWt zW#`_Jo<(hsy(5>4bnm;;$2#%2;<7#O$ob;79p95pB|4xjAUDo@YW1>v@5;66Z7;to zyK3mjwsNZmTX(8icH&*xTC?pJ@5$6!I{YoUSPS#RT4h7ulhw7`_IXdnls_W9ls~1UTFL9eOcQ;mwhPr8;~VE+OYPK_hoRS_jbK6eHy2p ze_zfv)}60OrzX1LHQCmLJ&!dh>+`;hYZ~eDzAR|g>dAYuyt!U~UrrmG?soICz8}ld z7vJynv8;IM<)t4>-xhkOwQOlY3m>(pd+2pp{c`E1*QNa{y8CsRW^d9Juas^4NZPk- zyW%4`)l%1eEDu{Mdk%k9=}xm=RSt2l72du*7Ha>!y>DO~^1gZKzHbKnj`t1E2C$lI zY-sF+0iX`zXIs@=>f;E{_;eIBXnR1eu|M=5_a8^f7)!F=Ym?sVupYfu?ojb8`b|IC zbLii7tej_t10bfkfR`W2E1(r^Z~~meKwDz$mi;^HuCguWiGu{{L3l=qyeI#d@-Ta3 z%!}(~cB{SuK^8f$kGTSu19~+UWhQ+PE1P1i{7n=7eQo&nU6a%y-VL#{A}AH;_=s#x z>=xjQ+t_HvA-=bB+0#d5oITyJXCCk@b$Ul+6pnWUDNM51Q+>;lv3%Z!!y`QB#RT-_2mzu174(b3S6Xaa#n3ydmYwL9@4qV;hkUM#Vc4r;{VHn+P1q zpJeSCksYCil(&b?PHJ&%gg5LPlnJ&ijL6j#ogFbS7nVb*7TY0eMY(U9PR)>^Y5J6C z525*poKLsfI%inT6EmzK*D^Lo+Z#98X?g(-^p?Qs-Zsg zd;doJ`L&DHaK`%zbD%k}O?^@6E&Ohzou45l=#yo3dp4>*i<8@`o&C}Yl!i|Z_!M2mXvgZ1czF=3JrNa%(+M!*;*^P!E9z7M|C2g#u7ePL5`d`TN$~Xd zdJ?e51i$GZo^biVOwV|B@OQIM`{KyK#)BbC2*8ilpZTibwST8RE?BrqKUCm4=sW?} z+2m|-zVO0Wa2f;Tc%LIBxvSGhgv$ljUcWAN~1-SXi ztVW@qvHnEBrcV=swk2G@!%1=(0fQt^vbj%^ypQAmfGzJr+)R?E3HoWWTuZclfmKk? zmLz2x4s6#eCzfk9qLtJ5Et>M*70H@mBv4&FD$p(PFX8T90pb;dwt?x`f{9)2iqT$n zVNb}qL@W9{X!ZQm`JrK%KGD7*JKy`sP7h=R5rgwi@J01!RVHfc}D1pnOc$o z?e>_jy3KPr$>Kx{$^OQn>ME-e^;nX3x=qdP4nvnfRf2Vm`QP3%Rk9JT_cqW)9&Zah z>Ue))UlDl|Q!PN^{hNJOu>Bl&AFk`)@H6A_FjH=ijtwG@#blcS#v~je4BZygt}Ol% zbo(X;Y{!0o?e6=A)A(oX+YS1J*UMaTi`V-Z7-6p$@c$!^_da6b9@7CHR68JY605xv-pa> zqZ#hhq!$QwRyIN0#cNBqTz}p*r9Rs=a<}~p=O?e~@GuIOy~D&CIv|^fq;|+b{o_W+ zx#{`Ys<2^v4}}bz$w=FzL%nB1a*AsZmb1Yh%tHz!uCtlWBq`foPO?Ee9AH&g#wXjD z-IDxAZ1n4EkYv}HKED*kki7<;_e}z!L{&{0&3FWG0H(#uZJ*wTA#Hxgp`fCo-Xs1; z^rB}YRyfXlr@6^Of2dp2<*ya7Xr3*T(p_YCy0a6MUAoNh{$LbY7yV8@@;L+*GC*#P zaoUra2!6tA??KRF^wWrglBK|7Nta`>`hZ{K_ITKc=@)gdV$Xqe6O+WUHOVq^dy@=2 z)HRfYWge;7G#Qd&Tat*qL)OkMlN#BWCOuMhDOiNmd|L51wS+@{>pIx8sIOfC?$Cr^ z55{LBKKDB7yxhTF#a=S@BMM<1v(;Gd5B3+BFwe0986Kmb6`C;5wE{wt^-+#t@?Oot z3`?s4fYkfBa@hAtzkJJ+%*dDCL7kLGoWoP8lF!QyOilnoL(oC5U1z!WtUq<#Gcn}T=;sv46?Z3*m#|nFEitHdA=-k%UjHR zC_cO)U!KGxYriK!cjn9G1nrt=(E6cE)&urMQK*nZi=K^_} z^@E;O0YEqOXRa6y-^|ui*!?o952$xC9=6#FJLLwl_k=-ME8|Q zuM%BQBGXD})VI8k1s=xbGv{v1pJK<8xK4h{o&vDZpG9mDgRk+#&^Cx5SBDuc#s$|Q zJQ}gYEaeks{t6wGOk-yB%rxhc@;n7eC>hx@qF*+ujM}w6gnYjx%Ve++*z_VnSTP8HXV=z`bW?7%R z2lmJ<)AN8v#8$hUX-j7D&WOuCktv^B@kCtq{!IDQ`qq&6?5^2SVOk_nYNnjt6N6z2RwGN&c|I&*3U95utj;9nKvfu2-1$px|utJE>I@X3#J># zKoD`5u%02Q9A=I%Ek!@el6fgQBFi8`D8Qv?pA31Lq8&4&k3}Nkm;3EzW+F}g7f+ps+F=)}x`^Z$mn+h5V9mq8grz-&q)f2k~ z2mW~gp0ibG5|;+6eL&=NO|!L3hSLf+WL6y z8*Am=u`Sqsc${_%>Abi!%6$?JIeX#5BrR|@Cd)m$LEjpS#n0?G?>n!w)#-k3dnbYF ziGTt4;ia^d02wj~;E27Iurq&WUVYb_O!#fwMAM zuK$bn|CxK7zjOWz31g7RT<5T?jnOASn{D!c(yym+0fX8d?c*S-QT>6dhAjJWGbA%? z0Febhhrx1KzVkj&MUudLWPqz8FbME|)th&vEn%Dt7Xc5mf+;1dWfL0t!6GpN8e zQA7vT9IK=IDl9XT&9~ZQ?KqNb?inHi48)MhNsqR71+U-=6nAA~C_EeS zsn_Y~wVdjQbA6g#+H4)zvJ~ z*QWp-Zl&DSr-$<$)_>_zV9T6f!6Cho?|cRpEFWZr)w4fPGQXNV5(nnmBe8!q*%iz= zmTO?)srd$&p^OUI!hC0Ryso#mqFEp??8tYVSNQaOl{4SpXa(SGJ^Ex>CNIp?mV2{t;b9%@MOa%+&RH&fqM)kSDXUte$mQC3mVx zw`{#sO$KD^m(^rtcFyP3?9JLfPcG&t<(rkXSDw?WvL4TqTb0dnrwXoy)32(|&3o?a zeCjyu@YN8EvUlED#FS#>k}HYHbw>_#0vWIv!#uRMWZ0)fP5`~cSlDc*D_V3(jS99& zO@;T68hB?n>pu8Qo|)&=3cn>A$)m#KC5`%kMa7ueLvHpPaIXvccxYfgXYgA8SQFzc zb{A6kuP;{mu518@O~pEZY7Hw${i>T4W%6rg@!nsInx`; zm#Eh@mGf~*nZ@1KH+8_E?rkbh63oI2=}1#&Taw;sDyNgIp1VmU{Ts^)vMG&ZbFyA* zM4!kx*GMLY^l1~B8CJ^6QnW`?=U|EsZ7Lg5&2lGA$2E2OrR%JwGBw@mS(#q4wvlwq z(8G%9&<$A78Yb+0Q^?YNQSS{yB zW4Q#=yNTS&Q_5Wm^mr3ze1TqRBE1UDGNwpJH+Pm7>5S$wx!5d=N_2fQXJ3i#Z6+(L zn`LJWUD({YR72M_m-aR7Sc7Vo>}o7WYwGC6K>oB#W9eHfXI*1CP)lz$mQ%Hr^4F#M zw6W8tj`nCGPwJSZSD6lI;!G{mtxaTLJ+q9dult%f%j@fyCNlK}v&?CrQ<^wC8t8&1 z&-?Th$2sXH-rU(7`OS93hP?`N3e?VJf?)AC5G|(F4GGR`^&}QK+z%WR` z5Z*$=*QdX<#2yfmiGH0AGQn?)$DH$PpP+n24<<#845INUO^zDTBv?#a0`?kR8#H-M zd@q!Ehz<4!1{`a1NFJhFV-4!F2Ic5Dg>8*LH95|p-*e&(<~7boGRD|cljHSttPFM6 za~YLjhz0!h3CMjV=!t~qQ?q|QW*)s@W9C2u8#7xQ*qG_uP*_ppK?7n!b+0xs>84W+ zY&=hDfLmHJhAm@sSTkUgN|}7r<)#jv<%6cC$B6|chtHcj;O$N~l@76H;ceKVnS;J& z-)1)bpynfSB?B7RbYo=$BYn?pAP3@ex;8Kb`?99;X`)i*sky1C!(9B+rZSG0XakuW z(m_p~ogtmjROSQvXAmRW9R>$b*D-yA*ESf=Dy%`0+B zhBuTBm2_T1=~YQ5HvhRjQPa*U`O=oQHMv%SLjhu32uD>G?)ZuX;B29@H~S zhZpp-#?I&$^j4$iW9Fjc9CMog%EZw104zvCD=~7yYb#5gMf=xl(M`0LrvSf*kYg+#9Eq*ytpiZ;VnYWk;xeEKEp(cnh<3^{PmXK#XQJ{v*%{9tlTp0Sg= zs!?|)FQ~P{=n2SDIECmK2K8Z37PCSIiBewPv4oXPQ0`=`E{R8^0cXtspNuBJFk9n= zlyDb@Zyd6~hK)jR?M|HOBhV$sCYUcg=;|q z7IvbZOM#N5MZ9VBOpz=@8?}h}SI*2LL5E;R4FjZ81_X4dhBJ|2U&D~QSmvSQT*HAY z+oPtOPqca-CYDStku^#Bpjfsi>D6MnlazCow!wO-VR&B3!@@eIhO;oNGizAf0}J$| zMKzogsk**~+)K53dZv}EDYl8pp<+3fraOwIOM1@YVp*K7N2<%L45hp@qUWnSK+tbj zmj#(-0e1eRx^p;7d(@DdSyoTy?2>sUvOQZnGt17_6D86vC+A>^&FIHfmnoH$^8Cs= zv%0gpvM#6QDrQ++RX0?3_E*)t)#Y+ktLItOl5Hij5y6oX*~2I+;cb*NszexNmrG<) zo>HF0_$qO>w&r;zzq1s zZ$LfL9Z*moxgeEW0n;nq957wARX|eED|S2bA(kTmRvxsDyfgUg_Qf~@Dtw#6HLc%u zuVwx2Nloi_bLv>XI}bG9Q};+6>vw}{S-)FX%lh5tuqnVZ);8alGQRJC+UEPhgTVL2 zg6})6w)wt`Yn$&&J@~#`>X`3)v!?mJ=W3eoy8@VfP!HBN-YCcls8roq+h)wvvo*D(Q(ftkrZa2F@HFjPS2m>OJgsA15DWwO50vj^z&UURKtrk{ zw<2bFl&KTyI76~@X)T$ZW%aDjDmhk5x&uX_RoU9JOjc#*%r2Ab**dRO&gUp)eBWKQ z%=d*>aHXYZn(sTjj!dm;^{lK~GNDX5=IXw>(mPi-)s-c=IZMjq5&4NbQxLQt^ntG`8dH-1AI5V8)e*}A*AUB#+5ND8c za)ZM&=^7qGXm|G#9?*7hF@XoU;H|A*>l$=pU^O^2Ka*)fY3hsVTfNhMziZJqB~T3 z`)^_UpLP@eBRxu);0MY7jRZX0l@Q%(tF(8jf(S*(@mZ0rkxi+Y|BD?u4P z&g|bhdTf0T`$_k>OHpfuB&fTpUdx;(UT}7)K+ebn;=?@iH2fC)EaM+_o8Pdi2bqn= zw4l7kZ)L0egXpF3AYWhXAMOjX6z zI#9uM8ku55xj9669PN~1Y-ub+ktT+X?=&UF*wR==#ArK`i=awOg2gPbr9UMqDR$1RQ zkxy}1oHA-&oMQWafrEzKWu^{ERod`>&i{F@$#b6~=Yq3cF8KuGlCSXcWi9hXqK~1L zl>GWp4DLK1>HM0)zIfAV-BD0SbJobJ&$cXMrrX*zG2O_yuwd7Iz^Ubb6pr9{P1hp&^0R7aHAk zS)ojgWkaa9a|>mAtWGJEBg~i!O`COaA;Ed=RVXXsv{RuBvZ(GvG9*-8`NA+8J_cHp zXX;eL^Gq^oNuJD2(Rq2s>|2#*;mB^J_AD21F-@OUlSgTKm3$lY@Mm%5j{h%d)ZhSGEkwvV+66Cql7|Yiz<3!>lW{KC>2Lb!SQC?k^!ulL~FqJi-%tBw>#zTe`pHt+l zngxU}94@BMy;I>nn`I*l%%sR8<{rqC1)rS z#m^AN*a5;AJ0Bn~lPY&Yb{O(C9FoZ+hdB_o#@%tn5(cGMvlgaU6TfvraW8U#7CFco>X7P&7j%^gM7trCLy?S=Ww!}h4n%$-)+v}3t1NPI&x!A{qY|G{D3+RiG zRq=Jmsv8itL%L08bpt-@emuirU3>Dmz0jfLeQt_r4?LK<`Rxm_KFW9l{Cvz`K>1te zeY8RrVQN^~CAt~WC%UA*hyrto@ryv1o7J>#dQ!K&O zne2+sED#rVhKl?uYJjsImOXK184|BI!?K->QCLR;%=G$U3!XIf+jb&3fvwK4#)nsx=j_mvSAhcU|% za&sASh0tO|J|_@Q@|Wjjh73v6tzbbD&C)wbheeDbdLSaFk|vvJ0&`6`wmjt`ax~2j z00x~iAO}lD3({@VJ@D=Ua;95FaGPn@lngs3yWus8-Rlr*z@V|<>Z0ACQnX{+7Hixq z1W9|jOVZvPC28}8Dc8d+m!xf9n3_jP+I(T&Jugbq<_n>oE>V&;Um$58BzFu+n=imd zx49&3%8;~IMM>Ix;ZZ)?C23QJq}@MC(&h^!?Q0~b)0HwOayrYjJ}3{1DD7GrDWHsA z1I-$i`4Q#rS=K7M-+5i4_q)COg!-{UZa}{XZUop@xDihw2PfHVV?mOQ>Tb!vbItM; zzH1U4Sl1-MZhZv{PeGPVej0BU&`(&FC)oC1pkBi26|SWZxwRyjo#-yGoM`o5N692f z`Xm*wy^jv-_<3K4~duq zLK${-Pgg;P@_e5@bBW`WA&!5|LHyshGWiC|f##GUj_-Dfy^?ITlb;qg{6St#tUT&9U%mxQ1Q>looDW zY$}$nsHP#XK!g|^S)6UNCSD(=$?bUU0xT@SEDuOdK>bhD{^@c#(Jb=-2d2q+hGCja zM5uwbr6@;%0Y#f1r&v3O63T*mo~pEP55q5AZl>Dyz0&OH06(aIW11b;u3W_o=xVep z>#Y={B|RjC4)+TRxyLNC;PbdMn*J%k$jm}=hKxR`s?ku$W6T1<9NfTI)gGw^g~bBF zd@%HLGO4`Pea*3K@ar^}dA-ghm}7xpzRe|=?{W#|SjajpatY=~T!J|k2003NI6z#l(Mjgm7{D#2qWqvRGfLu zIy@{}=Fn3PIb~miMfT`dcncoI!Q%E~ff?G?6p42fyuJV3CCi$$)4|gRx|JKyQNEA zs`uU~)qAE(_1?&GAwH%2t(*Egn^WA1>OQD{7A}etVWMkPVrIHfiEsF<*B^4l1u0vl zO`}bSoi>le@}l>t zgG;3awQW?|;VzZ7w^3<_+Lv!#$K2@Vr|A$*guwhnPwFbx^aQgV14XYPS9xia^+GrlXGH-A{F1WOW-LKI|8*koZ~Vc{ zG5k;B?EbzSV7R@bcw2hyo%yeEdw<)nzwa@A@9p4PbT(883-XNhIuFs-@LFnShWB~k z*z~aDEsXZ2mdk(T6HmncaSy5j!hGs7Dq&8t_GS;*-QHOaAhsKN-$UlbZe&f!gnU+q zPCU=06GKoYKG(se6Hj*O#KVb{`b`}2YoyoQy>zVeR`mY=t|v;-&uG$rAMQL>19`F> z46y;qz@I74(@K<4>UZlZv=LnXmmAfVZd>8LA1NOqqQIJ}F_kFq)##SF_LzCM$wHE& z&Ua_(fABl{tL!5&<10h2CQtmw~QXW{_A{x zQhzCz-}%+XDA$_kI@r}qnDFESHf6!`$Zr<7)|733BNOsz|7V^9Y^H+1$TS3qSxns) zv|sIvc1NHVvL=OX^~O)x16J;oc#A`$Zg9=3eG!%QW{iwSMNT^*a_>9s@be<3fvjm1 z=we@OmIkxuYmV_m1?rvqEk@c;RcKb`nAql1XU&G06bNMw}4q|gld6H-s zxp#8uqnBk{a+}XymhmB--O^Obz|e+DN4zWp!)-3SBv(-Dep&jaU>=`Rdh{jm+->^2 zEQ?b0iI}CW`?bs$9Cfg$%6HW;gAwqKjXV5mo;i z)3e;t^)Jb>+%~gY$bxD*q@|px#vosnS304EJj`oz{YBZAuOnWSyB6x{R#1B8McGi$ zW=IPeS*R0Q${LF!?kgGZ8$`t?h)qk5awFUrIk`q`_p#k`&)HA?5dD1&RZIoe9D)zsB5%cxo{z=zi=J@cwe zuHEK~SLJDKz0gXgm9q7U($dAP8)f>9Uaq3I@g6|eYtM!?QC6EbM>pX{?EOZ z(%s(hBkI-e*-{SHtNH8|=~G{?zbeZt`>~^b>Fn2}+Y4>Fwvv-C=!upxsKLkdwg#oo z=xq(#eBDa=Hqv{q$;L*QXEZMD`I=m8+~&;7vZjf4Y%P~;*gk4fdqitl)U;-w)^fe6 zK6+J#H^V%mS?SlW$i-%DF1#XZnroj|Z5U|ndmw@-Eb>9B1T*54&wa~SQghxgLJBdo znDRw!ePErLKGn^g4#^zVZQYT9)dwRxDKU6K++YPN&uu%$nOm zKC^V+vS2w49}L0iHJIwvI9_b|w6-?dueP*~563#b{8Sq`Ndm3hP(bc<%Fy)kO)tsqblvs3bhRNeJfnQ&O9u5k*jl<e#IEkuS?*@Sm-vj}4sh+2sRXws7j5w$jgr%*34X4Nat7 zB|ZPT45)-*a;5U+K$j}(u(xE8jh-o$%WpK7PF1x3>oTMYhG|vGFEkgHf9ds>pbyCX zu3A2{p>)gDhplBqE{0jT<$W4Tk7_#UEg4k}!<=g6M_-gr^K{zlGREHB^YY5~y(qo& z^;&C#Lm>{BUk>)EZ-I_}T_zM@SX5B{u%YxX)Gn{fBpYc<3d?6Vm4QXN=yhXmaI=fb zCpVSB#YPWbZG&!Karx7iWmbs|{H-Mzj+K-jZY)cx>%=!?Z*>f3tC#O-ENg1$-Ij9L zM&6Yg>9at@6&zWl3!v^QP>zSLNB-<&T@m zno^z9N)Fq2yi!^|vw>`>qch6olucf4*D0UaK=#ztRjIucYzS5aovAPK3^Iv?8ALexMFCb8D zE-Ltu^9f15bEx*E%1p1WO@-a`&Yo0brz}Y|Z)gpxQ2X8{kbH=k3jt;bXvld5-nof< zFUUdca0U_bvX+jF{{ah0cTUjFgt`+fvfM4X7|X6?Wpn15R7{ML^7N3EJBIT)_}Xwj z)pta>mF1pOtO<8g3fwl=>E$lz*UdBAVa^BGlldR8o-cfaBJ;6K)B?&Qe9b67vL_Gc z{lDsY#jkUgdZxw5ii-PL@C9h+FIcKO&X(io7q2H%$fK?FVq#SeOubVxqBnk(v+~5tUuyjNQ?G{<81EQ{{x5@lO8Gu4AE9l0va+vIn*P)4WEMEI0%AG{yP;9jPd#~20VeEh!?*V75mveMfeXT`XPSjSk5W7Sygnrf;d6-1 zL(_;cEDw_rsv=~!HqPHo^;E2%CCA_k0o*4&&svl&$eC56NqmeC*!m2h*)I7>nH)i& zGR}yJ7vp3gqzP81LUc3E;%tl1D+9t9FN* zDy#>9Nj=I?X`w$qwnK2N-)ke=uyqMLe4qdSs(cU<0v-c-gH`F{x8+Fg5G7KxkO98u zw`+9GZ?K-v{4yA6S-`K>Eic(0s`|4R`TP@IiM9a?6vYb!-9hn)m({j1Hz}UQu&un+ ztD8Ws#-vlet1U;zo5meitt*-2c+&@A8LnM{maG^(HmI!lbuhN&6RtJ-&2e(n9310D zediL!}egPr6;!HR*OKQTs$wa0i$OW_IZ|zw4A?Blt?XvD%5d zGB&XXs4KAbJc45&PU! z9Z6)|EgwLk$Q9Y(DCEPb6X{)!G9=xOa@0IFyVfH;PCw7j`0`8LnwB`QaO=r|zDIhbta^DOI^?ZEcpSE8^S zYjda;b{1)+RYSr*8H?UL3$s!W;$37KSbQl*9;WW5}RwFx*kIaFIa^OAHyb8M-*4)CGnN+Rt*D_U>60 zqqj>88T6#Y5_30-42?0P#G-!_N(>n^oLw3EpxNyOunAe`5<>>{EH=%;4nXxG&=eUm z2#`L=ptAr{%<%vjbQC}eG@xShM4qw0CTl+w8#1U{i6Mio6+A}<0euGpMhYfj_C*M|q3>pLWr^ z>ZoG5U{8v>nL4@H(#mU!WlWZCEjF&=xdLMjTmUeXr3Z?nJ*e#>Ib^ff3)woiNFJi{ zRwUhXbbXNw&Cwl2@>z~vDU@Y7daF<_=jfwCS!Yw(y_K{R%n3M+Me=ne9b9D7+A&4a zud+@ll8Kc~so+3meNrGZY+k#(iisBNs-mA3%9l)c3oTeQqEH@H(Q$>+yQ&d{#}j7fQ$c&GfVHk>3Og9er;a%;51h@O z0e(3T5uA0!$o{i57|K9Ec~!sm+md%*`3(?z${+P{dfOnKRZ)?-YbnFLJ)KoS)Hx=^ z@PUYpdkpvelj(#Sf8q4?IIP4m)ng9fH%SS0OeXY&K!HcMxWqy02mj>!@}-a=wI}*m zoRlcl5l3$;ljWMIA;3KJSCy0QmyU-3* zh9K@`$%-?!NOG46T)h4TlkvH#3iod6RyLih3Lb>~m?=d6SM>+3q=ubdxS?CJGtivrG@&pTgc9C3-tAX^kqo^!appX9cwya3u9%D^-O>b6?go(Z;`Re z$>;$`m3xlgkED!71!1|(&A;=eJ4YhHy~|1G#A%by(y1dEE9gP{m}*fU%cBlP6OAtD z>LGV!a$^mlg19F3fExrfE}B@iKr7~tHv9DiP&yXR4GG}m6UdJ0w@*4NvwgUI&C_MS^14pP*C1hS?ek`Yl0^BEFPlcA~6q<#vEd?@<1}e(8~) z6>xm?yFB0|ki+U=_s<=hf93qprWbGP6|a2wp`g30XKYb2*6i~loC_f7J{^pH1v3IY z6+2I68$J9o+P%x`;imgd7M**|lja5!J=SOPqsF6$xC;OBzK>ktwk=#vH6I&o_>X?- zhB>0vKfwAY+R-Dw_#60U_LO)w;%}Uvyh5R^ktW}VV=)z&2bc%)d$w?#_V9VHpeBgp zfMOLZI2y&$1_L2x6!iTjYR!am4X`ShIBHYSDemfr>wLE2AyQ}u{HDA7?ZI$=x!W4@ zXqZ1z6zvz-z@-abOg8D7Js||^U!>fbOM-Trw-M!MJRU;kg7}w1vd}v3 zIwA)liyY7sgQkPQ)Q*QSs}rGcXT?Xcx-Hp+0aqo$AWrsvUMl| zK@Z~r2ygp z04G-EiX`eu7PGPB#LOgJk}e06Qpph}=~^IDmZ2DttdCg#CRuN#nd$}-SKC2wvd&_d zA5m^*rQm+(T&2mz6m6d-2T;C(qL8YySmuW5Z<=hjq(%P>lNK74q05-{WoVy>e37AD zBF~?+uGXN9yMasHKK9$kCj&dX6b#+Zs@RP1;6`F>X`_M7j~vtCAx9`(v5 zw|v9)gEi_N@2cmYbbprN+vcz!~FnJ9yh1^>xXRsctdT~1}? zt~ec)WmG7ZkAt6biIu+M^h??kZ}oR)eM3~560E!k!HOKY>XsQV2eM@Y0L*NYN#oax zNjg7UzD_bE=%b|fDBn*udq=?2oJGjcsVt;Nd1lD$D?-{X+g9rUc6vQzz}em5O%6Yd z12vfiX3#czoT`t2qo!&59Qi8EEZtBo&5@Dm+BZkGrJLnqx{f5Ckgk(*WO{~Kwr5!5 zMn&xMAqmaJT4O0K?r?)&^7&8t47#3E$Vg#v>KOc!Um`r^N$#hpT=r&Q@wy+brn=Tm z4MymW*G`V}ckXk#dS^eYg6lT*@5UBZ z+aiCI4|w$?Qus)H68&>^P^Y0Y;+Lg%96S|J;`k2W#{fQCQf}KgB6iWC_~q}OZX|K8D&u7J5fkOVAXz*UEBUX&=wXi3{<0xQ$%=cL(u9Zphl4EDD!88gk$wa#OBXuBPf#TA$m=m?ugiO zZfhbyKkb1w514$0^h9QiZ4&iKhK1NDBe2SHb^yjHLvmv&JmcB0AYQ0CmVF^zlqFw= zbX=AJ9Vrh9+m@5z)-wO-w@+o>W_&ja0l*rWQuBmt@J2h)!nx&WO&=k~x{S zX6Bkq?Va_lwe!DlvgGJotG0AVSJ*XutD?^JMOv6%&+4)L} z?a(vTs#uH&AG@VmMI0pNZC?I-cJlngckqP0I=7K6;(efz0HUmt1Iaxey*%vf_BLJfk@{9?T-3PfsSh^orFS4#&qlqc-)59MtKVa_bL`&f&*Zl*wC0a+?ryll(?S>Ir^~_Da?}h34~B{dLyqM|RkzjDbui z2|l6&QDeWuj2YuM1K3@Q=SLWRuFnNvsXHb?3+xy%=8BuHa^=?!c$TR5v^VP@?=x>6 zIkqh^CR=?mCIQRy$i;VNiToM=TPz{Q#(2dq^|8JEjXhQ)Uf1ppJBhgVTqh;J+TY91 z6L54GtK4Dx^UY?rXS(McFuYR{8VuI9ib;F$g*=`s|G*Ds%&YkP_6fMxpu~x^Y&jyv z%d`>4hOj&85i>oP9848$oWn5|*l~zAr5akSO&UQWo@zEzPvc=yv0XQ|`83*|c*7gj z*LUO<{egRUgBQ|_-(;_1)xKjfw?ET<9{Ddi%45<8ol)*~ybq%45rxbqsN#S6rqzBx zTcL6gA|cdu$72ua_FmcN5aGh}@estY3trLO^ncK;h>nr6_t>gR45Bl(U=&+a>W{*_ zW4Cjc2P&nFIPSp;kEz_b8^lzLekNq;hf<*6Ip2*Ar`BKd;7kVGq8pM;hg-x`jZz%Ui+C15&rUQ~qP4`hMECa&sMm1<7SFLaoLzdqOPtCONP&c-9> zYyS^*$uMu~qFDL!+S6j~g!{+Zf@!!H%(~EhV%9}@ytgX9Zb5s>l_#Y<8Ws%Vr9>=( zGS@Bhvct|$+ZL34s>E`k98yLY2m2hH$)GLQHkrl40Dr^Wb<4(-iIv^~&=3Yy0{V<- z6J@()79`~}%TmC9u48TRY;dFpTJVm+*k?pf$I|`3_g2-aBd*zvvvj-3Xbl`E;(`u{U^{~N~S zzwLrFsL#c2W<%ruV((qxrJDZ#|24B`pL4oTr;Ag$jIJkjI@3L=j3P;D+*4%IojQ#! zBxI0ol#xqGGE#)plv^cCN-DQONWzGe`$!a$-+S%%>z(%cp84YQ{eJ)d-{rF(^gio3 zuk~JQuYFs4?R7a_Hx6ES4E=Q*%_{Fz3!Mv)rbMSpkDe@a8Gi1u=mMl+s!mZ#XZY)# zM#CPoj0ZI(=poDYopp2{hrKjhl*rjv(=}L;4%a>MCKU0$+tp=&9ZFf=yh{pfWnzuBGpfeDe zdN|Q5=G)YVj+WM=>GqvDQa-Dw-mYlB?=0l<&rTZW)GfAe^{CeNe6Q+d-{st$lFk|l zTyjS~B4`K7uR8o^Kjih<;(5%J1Gv|S3U!ta?zsy74-_(^l-HEo)xadkWn!a=y|5pFsQ6_oRf#OH!k=U%* ze%hk@361UQt?$J2ywjs#^tu)=IJF|WL2sfn)k|YF=yds)BjQ}6`$$XsR(-C0<<*1L zcX)Ms!#gxX8g2o6uKBvsLLQXdKfDM1pAqde`?`N+-~K<1_RkI%)c@>8@;6U~f9Biw zua%O0p&jST;h#VB{(VpUzvP~H_AT_4P@it{7H)Ux!DoelyumMfm$|;KH=IqMuW5WI zRZ3|9tIytEpufq|kXQPC{Y3$-zcqwb)g_lLoE8dt$Ui~79=!G=mTnQD7XzC5aRYU& zrpbA!CxB0XEBVRCx4@D+=$(pY8KhRnD*EHacU9D5zNF{9D%9Pg2Te--Qr;A63$37C zX{~pPvv6QAsQX}d)?Kv+*$>*f&kc32*ZSulZAGZW-r!H7HT4rC(Cp6k)$HZ)xeWtir@=3Ld|d=^G8xRZvYdS3HRwbk3c<0+t@4#(S{cvN%y0}s7o(0d+L zs+>>yS+8CMiBfo)4vv>*9-*EUB*%{Yv%A#4)&H&n{<~WI?`y|txNtw{>@%*S*;Dm> zsIk39*K4V_Lr?ooOV?{}v2?xmpi{4~(*5X&C^%ja5GVX6sQ~H^bl0cfk|vsb1CAKIEYe zR_mRYX?iR7keK4Fr_K>x-63NKbtH41Tu1f1eydNtPIDbNlXWD0>Q|>*q~4F#l<)xE zV`_w+z?fQzsR@m;u+dTvJ5IpG486t}`_FYu`hEkfs`>WZGqc?vCD zK=%-fDudtRle13#|3QZ>8|y)BE$!F!-IbatXyI_`JWAbTAF}k)YxC$!yVw4V+P3s< z>6RnP>R*odkKgG2Zr!-g91pGZOovfkDD>ZUm+{ZLU|u;dB8H@#IEy_oS4I9px^aI` zqqC`OYN$u37j+Hw9KAo#*x^I;jqu4D)cNzwM{3a2dfo1;L8IKd-Cl!cpF92L8fsys zVf$$&%&Mg%{iv$_A}OoYp}&{-U-tgyOcGWynw}F&oaTG#wMw5lKBAs}UNzr)F}1qW zhpjxdn7--Im~Pvi<4hS<=?eeb9^D$b(b-WtFm$%J)GJo?(yRSa3n+cqr5B>9&MM!B zEJe%7zCv?<>krhc^d&&wFOT=s(jC}upkCq@b=>>K(w)9;@_CNv>pz1q-cUfri(k4&WmXap_2 zLmc#;#ZLOX?oIe;7_EJmvlbWqO|GdxDA>}bt|Psu|GPfL=g{H+UYq(hQWs@P=`k9N zYN^lk%h7D>9LJS?wf+Rjv0v0#Sgq?1bLs1y*M88cG|+6W^u+$ddH8R#C?dsPZ*_8F zx1)yS$@zLmsnarjzFR^gFK8}X8Zk>Ri}`xRjrBAxgGN2%tCwthMZQ`{-Q}Dq*6CPW zRG^_$JN zH&wJ~PPBU~d1zsPwG}J~jUch>bN3XL;ql5K7hh6I;F5N}_CMv4ww*75Iz2pK-3zM(c&7naZ zD`+T4f&D!FT|uu8wYP%(uJdW9-Xu~{oBa#AH#~JjpxgZ%ry@vSC&**Teg1>u(qIjf1{)EcDWJc%;!$=!9CRXG5dlb{Yo2QHpg6t@X!)KC}Y7 z{^EJNM-S?EqU2GHl|CI%zq08qk(XV3S1ZtLm8w%K|Py*Ihi+Qg>Y zRV({-5AEr6ryB^3rtox7y5sNr)N7dLsEoGhlA!M>y=fHo;U)>Hq0@Cs9cHLWg1*K4uHCK0W&aKmuAg6PQ=jye9{XA9gW%P3n$i8?pshdbyld%>*{@l2-_*ZS|MriZ_NA@1 zUa*!34cU3sR#RwcW1G4-pG<^2JHsFP>jkL?HKmoNX@6*Sc-kLYftvQ`0qUaeYjkII z+MlmH6!<=`&ToF247eTry*IzkR9XVFAftbvDF$dY>!lUzJXM_*c$#VvqG65X>Sw=p zMG3WPsy{=u)1UiB=_VUWiMoW-1am(6My_i=^JpFrOHXx1&-jn65|U7?zFgd&Ri*6B zucjl#tLg0hR#j(jYBim`CDkZ$ajYZ_Bth(Bxq?X*I4!`)O`Z>vsp`q%pBxJsS57+gY24 z&L^6)!K-4_37RI-%(F8z*=3$4bia$yqF(uWaj@^`8#g6YpeJH`w7}j~pfWW0$*bq? zpwVzI(i}Gx)Xx<(p^X0ftkMPXkI$+Je73)&Z!XW&)R+19HFXQ~_L_P+#V_bY@-=#l zW`_6O=A}R^zt&Xhl$l?L{{Ak%*6f-z(XRe`M?tOMXri79>pc|MQ?b^9nrcC%S9Oeo zRqDJ^Q@vF6XC0u~u*mPsnmP?SWM%d3_wrN=`}I6ESU*^(lLn0tqUKtsl1DwD=wU>d zhC{8TI=I(9zRMi7CAFfIhb~KttGtKyR zcqs5{UY$>>s=M;v(1D){>MXBHBS9w8-@9l8M^!bM`awI5^sSD!AMsL?^(?O%Xj8|H zgf8FhG(U``c2V`%(gXge)qD@V4_fM8tAr$fmeE)G_WW^motIk+bs4=~U6;{Kw2F+c z5iP6nsqY&P1u}WH=Fpg?{OjoN#Rau!)r}7e-tbajZKXOtSEr@Je$jzt)pc}Q#gSZ5 z5~tSJ*=b?lMMie^Apy&J;t`<&3hrx0=rC4CioCM>U;Q3Q$%b*S*$$(1Cds>d=ACRM_LC zz=xGEjp}s+`p*5OmDJ~ig>1(u+RwD5I z;i14jI>8EQ+1Wbu_f9&&3Tc_{_4S0?grzLQ0z3vrBsIpBJ^Sdm27rn?>nmj`t^=;kj z<#!)lJ7*Cg&vho2-m0C<^w6iFAG}A?#LG*pxDL>d(lNAsq%l>-=~8{ZlCC1JpiU@O zqjxLOLgWiQ^Jx_(yVhpvoszfOOMxG0krN8g9Q{sblp3w*{43L~eb?GFe3ZHcI1k(^ zQ#_>~`>4C)Gv2p3sYaxuB)bi>X=KnFb<0Sy!rGyE%!*;rz$n1c;v=eROuZ1B@exXJ?c@js6oU@w_xm)Z_yOGoPGM$mby%TVc9SG6pe0uk~L?sr#keW zN3Y4Gp?RFBIz#g--S7LF)(CVQ4P((zeG(6_Z>yz-HjUNNl@yxNjjGB!=-y6Qu1TK| z8_~RM-}=7vP~gkFI?vUlo@j09@2~UgEUHEKffW`7X3^|ewbb6qyFL4As(n>6UShLr zYA-a)4tb=kpQ|gGSJ``Q-Fxdxrn$i+0oBGxF`FC2BLxN6?&}n0AWNqSYRn>sQyOn$sGm`fplbY)NxHc_;n- zLWTN?5?zO*ziGvV`OVeZiu&(YDi+>VqP}eve#+S%snb?5Kx4fX1mw=~jxb|d?V7V4o!9q8}RXwBUg zH0DD8{ZwQ73p>@QoWDaBf|vDp5ph5CV} zp`;uY+c%b~N1N)uX^rcdrRtTYS~K+o``%Ku@&wIk)!xOW>MQ5({U_KfO4Y(eebd8^G4|l9{t<&7vcGIp;d(fB>nnW5J z=hd^3{k&}jsTJ6w9(lHPm#%tvsFmR!pOyC5KUjJ&<3gXFY=QWVw6FxdBs+67&?^uP zxc!D2ifI02AN53b8YK46xE?*e!EV;`ZAojZ!$x^7Yen}Ft1~^at-dsx-g=N0x$${u zyu=otMUSDSK5MW3;%-qNb>j34pPjFsqBDyYd8a!QU9dhqJcwrGn3ZSEw&|_XqFLMy z+SXoM>yvqshryDE#tmjk9>S7`Cc6El6%CWO&a!FVjC-h=!AHxj*vowuJrEN<>kHix z(V||w#P6rpBAUUCCK=14hADfQGs!;9cJ?!!R?854^e+`54~j41NVCxgi6;XO%X!9{^{;x z(RD@xU}#E@NAfLNWMDzQ^((FTlW%Rbb)?^EjlO(qTAqD#zD0f0f6cRK96xdASX_)e z_!`tIlQyg#4x{5320qaL$*zMZ!9AlA)Z551gG2~c(KH_Q6TIU;MQjnM14l{yqt z!w$7h*=mJl?{w~_3+Nl);p3jAiTUW9bB?{QLE+)_wrPG}XHTnA`tV5UO|>Y!?OvVU zLmm%RDes_l(W&jsM-N5&1xrum_bYYfwd7dNb>h?c)VS>oIhK>fr*7V{I#H8}bs>%J zv8b-P*yEwbF>1HnM}2U8x^0r?^506mEG$}4NPM2^#INFvy`j@WwGn?!sl|ql%YH8% zm&ZK%T9{&araH~Ox*Lr}D=p}6sPx{NwbbIn{`O78Ip4JFO37o!VN}jdbrH9r;v=6_ z;?(=(1+QlVwYB*yD($_N^%a$bj|Saoev?zeGwEHJ78q~_Gtu+*ZryoU@;=S+Tgy|a zY1wKo4MnqG@;Z%-(Ld9p(~6!n7Nz%|SEqNs$MY#YYAjt(rlt$ppM@4JIca}v(W8d^ zuGdX4)*G~dg>BJLzgKN*8C_7=ks{f*#-}cqee?a9)_?21ExksUV;xWB(wKLX<)N3J z)rVV92Boqnm0ZnMs{nAY7>>AvVIwXc(FajnDt`>(~p zf2MW4q!s=jO6$PYykB_@p7GEL?Ck634x{@Vbs6x{_4%HUuFr?^^!53u&+{G))%00( zMy~Q%2Wc${uSMSgh|}CcH2Wo0duYx~S`&(<(^*8LC-QYiwRw3KO|)`Hp0%3l6L}U* z$3ptGhwruHkO#X#-;HvPMjS@>otFB((@EcQE~LSS7BxaW?D5bwNB14N!_j?*>PK|n zp$eGmz7ufbSMk`#_ov0bJ<9Kd8+qz>)J=n@*>`$XL=V1N?9l_s)_C~(q=g5s!o8sJ zHR~iVTOCGuX+fu*bs|l&X`M$O1g(3Wd*E*8tfeR4Ei?}S)v=xXJ~am~J$!$;>#)yL z?-rjihfx`q>f-IFKO~%Q&!uwGcN3aVQa@kmtJg}OMIRzx^IG(VOMJOy)BIL6bbzL= zp}7ZAd3xy6K^k~Vqp$NUDrtHm(#22DwjZgj&F5KhxQzYCLteADEPBv6$N3&7vPL z^^$sYjXU`n>EuU0E4m*pr@jvR*UP>LKJ&Kd;ncj}KJiIoYb~pTeuSS(Llg9KoS#4U zI?tcD^ZZ%w%y&v3%%9TtA}604#_4jSG17NYrxl;)S9+-UtkpDwtIxXEw&}4-)fz~- zE=SML)-=V^Z3Uj2>GCM>(8m>;QI*yaEwJc4^N|A2S2S~Mfi+bRz>Zh2@2)^=&K}`` zp3A*n(3QZas@Tu#<~94%n(DQx_P5mjTg_ffOF~w&SJYI``R#XWsu|VoU#Jndy1kkH zF4W|m8WeRe4Q8*Y?x?9F>AGcaVr26-c^LHD{&}%d`#Zm=}=34RSfg{^!z8f#yvTxv+57D{myoLPJn7(=qMmd={p7UjXXz?|z z;-pZsp?!--mFh2P)Dud7W%{%0W%Gvi5{rI&Kz}l#k42MpRhsJ4+s)x7G^)wj&z+w4 zIJKIM^%tv_Hhn|xr9W`qqTk&~qsQYK<8Bi)yNLc){GW}xy-sUr-SblN-X3*$v@{gx zW{wj3GG|}Gs%l+l`*Dvtt;qvU=}EgwdFs|w&-$sV{_grwRXtVOmsQn|zB!&7odx&a zs;U-Ld|3w`r{xi=(o)1rbwD58HoU9d&L#UkeFCGE*r-xYGw0Hz^0n2Iw*7r=TJxkk z&4;ikFYbG?w%SfpgV(0-1dA;S{7wsj)K=4KKJKM}cGrpBmDftqUbj1JqOK;i(41xe zSes^Sw&xs0--2fO{-Bg9+PiDhY9x2*z^jEiu&u`J76p#TWox>T(oWLrJMARBmeNih zq}c#zSLi!0?bibpH~hJiOR79-?BsD&Bc(eewIA(umY1T*vvyc5XwHETeEU7yowMC; zPUWqW{M%aRQvUZp|1N?5mJ*22dx+kG)L&n3NxGTpEd?8)4RqC@0K!gy{)s^s0*^zN8BZ7I5!+nol3&s!E3`$a^S<8v)E2L|0Bi_02pfh~ zN98%XjK06nmTb!5NIwqy>v1@!Tm5K@Al`vLc$4&_zjC@Xp{}Fz!*3RTQ}7#w-vIn3 z;8#&+HoavHzsUpaFZ3<^J1V6zvfngil->efMXUI8WpB4yd;P!Xc`M=`Hc0JKkKx%f5);5szL(9DNY+vPQfl;-wKUhIko- z1Be%*`BIPEHX&XTx+vnM5cVTpa=SZT2Jzz1MG!B6Fuis<$wZ8J2M{j`T^R9V2xqB% zL~k*g3h2nqe7`hPRMG(#)UeJhFjCeulf`}JFIE{E2qg+CW=Z7wUcmae{h!;2F z^+miay~F9vk9Z34l86^Jj$ah<(uk)JFN1Ib@#t05@%!^JH0zVz3fSaVK)5nh188em zf^fhIs#dP;?EVvA@hjNfC&F%KTkHavlCqABc2 zY$e`s#ET+c0P$i|SQkgUSZ8;<#HsH6OBvye5mu+M-f!%009^7DIwGtOv8fkb_YckN4Wfu8Jtn!zJEcp?YSLIrJIujGyw^r;+r73OrKhCTo;=R*YH zgrQ4-Ck>uHBEG&JlekaI{U?s&>&0_j(#akXPqV<;oWF!|pHF~GybQvjHtuo?oWt== z9swV2=o8>U<9?k2pKIvVx$NKMA@EIxJ_auNP9YpNbn3kF^Bn>Yv~}-i4E%uMCj}lh z^cnD^p%0zU>6(6G;ByT>N${k>GdcVOE@1x|Lmvh|VDKooAMcq`ZgJ5Y`Hz*df6=87 z?rX$XLDrc(1g_&dHC}m+!J%KmIByT%M~(Vo>8g!kRx8AzB}GF#ET)GKS#XSaqf6o#ET-H$`MaB zbH^({J4XcZveJGa#5Nr90*IH)5ieHD9WROJg?6Ry#}TQ2!1v+%xKSU;AYRnUiw$3(#4 zRwWQN>vbuKZ}`oC2Mn(Ia(W4)-WUKcFn9=D@)0>A?9|6lUz7S+v6RPfiNQ90M7;m( zJvViPPWuc<{R!oH_<84cPiw01ehH2l;fT==qWZDke13(%&F54KJZ_Xvpg;RDc`OId z3hAi9m6()@0L;HyXJprf8bauf&4@eKZ$TO#QsvqUuZJtE7ZUI{6&$!%ruUdZOb-+ z{H7$G9QiZbJCHpUL%b037lzFse~GS02j!>wm7l*j@)JdVk|@9MtsFo87x^>WS0sO7 z#FMZ>eJfDJeuHA=_zdLyMI;`L-PBtk%K8xX_0n7B3bx7J6`XMNFY@Pz=pVCPM|c47 zLy{j!ALSTCIc8Cgi5%q^L^*~~j!~3j3g=z8L_x-vU2?##pUmZ4ZvovW-k3{#9wSK+AC(e+bzuY=vzQm2NKH0q=vs2Aq$uSmXE?L6^&q@TB=Z zD?j{iZq4sd|C?v`A7?LMv|r?MV77DQ(y71cFK2xGAnojbrTeG92XQ}6e!};&Sca|m z3CaDM=8n=^-~;#XVf-F@oUga=QnnI5g5M+Wa=Zkr{2mqm!rycIkKuRG=d^M^%PIJ; z{gCUuA^vyshvXCgP%pWb?}HM~W&cAvSq@?FAKrgLfAc(^3tjdS+$RUHP0)x%y(Mt| z$orz`Y2?2vrw8CCbuq`!z(!W{{Xd5LuJ{qXpJv-Ta`U6VLIm++ut7akg0{%DY{if0 zH!VmhHMvZ={QN&Bm zXI=Jwwn6B_uo2ietRMHU7`|)7yK{X$+MnYmpbK>4^DX-Y^ECQdN_$2S^|ugg1U3dc z7wtrn&kXYC$9{&Pi^8U0rCc&-Cr{C219}TTfc%`p{jpOtRlBpbWg9((ZA{PCL0jN> z&UZ4w;m|Q0FAhH$8r7<|B+4~3m&2)hp}&u90>6imp8rDj8v~ES`q6*;0QOt*A3}Oj z*dR??a^#l6{V}+h(~HtHC`WEfaGax$ak>#a|3oA0`)TAOX}kyZ{hRmSG}7^RXukXkcIIsTU^)1)A?EfZQkHLF5 zAJI8%vwEN(ZGZQE^H1}W#Bnq86T8<+bv9A}~Pk7hrqD^X6!r=*{NE{OK7ENpD8JKarEZ>70K^%jq_O&`rR1Dl2Y ztM+XFYQ7Ewu>aNe>;uSObRq6fwB)_s639>F3r;VI@L#oOOa4-Wxg0_?<)Plp_Uzc_ z%u|vM>P6;xQjGI9hI}O#bG#Vh#ddT4{CF=(ZRB*#_Uue`zOP9BVk21>)`L@Z{vKq% zk)F_<$u|BM`Rj}PrD5RnH?nY)Zm7kL14NM52GD;W#ChaJeLL zyaL8?3L>0RT+ZQ__;{s{=dkkQILQ9!A-uH3-)0-2d8PE0-N`od3ENPP^C*gTL?;sc z(?QA^?bGob?eLj;?(z>Ko*(g|$Mf%L=z^#>1~4QJk#f!; zUbYU$3+ITJq?w_Q+zudK2Ju2U;>A95r{_PJufJ41_UA{u6x!uuO_>KfyVEO1yd>f& z#0%rRNH#{i4(@m%#7iJvHUJ&sB@i#$&K<8W;>8g!gLr<#iz1()_U?F5#ET(b8u6m@ zSr_+h!;S-7~&-nFNk;nBirYOcyYwb;yOqp zUI_8xM!Xc_#Skwe*DK-$r95HfyxxX*QN&9lUL5fP(1(olvWOQ!yp&w8i07Al8s}NT zDSV!V5icp}HA6WdUe-7csR{0WC+Zq^IDqin!8nhxgOMCOk%Om?@T>dBEg8Z7r2pMC z`1h`I-*2;sXMS(;Pvm@>JeY$=a`03R9=NuA|DhZ_0xrj2Y$^wjT*v;+er-!o4&gH^ zIWFR`;V_32eb{FDvkjibHU!<_bm1og9?jt=dojlk=kT))eqxB9D?h=JJRmiA1zR&e z=J}J$kK{j+!%r6ZNnJz}xzHB7gl#g*=Z(KsMTci!bq`2L(^~fbXrtBb^_CpL@uCB& zxuU0Nfp@({Ut*j5lGBgV?8_fTr{E`G_)AE-{a6=)pP1oqmFO;HT@?EnH}*Fz zx?V_E%EdUJ_dpkiE(x15bZRJFX|6y1A~q6v``CJmJZh`~DDn#vK-2E}Qy=?+?LgY~v%{_lsQdlDJQ#jQhnlqB5aGcYfnagpGfG1DHe#q}_-QiRp4ktRY^*`v&cNY0bBOk#W`S9aB zH1pv{J_4```3M@}5W->D&?oME6kN{NWg6*Z#Tw-nfG&XihG5f%E;GfrzNT_Ga;5wF zkB#DRyp+o~2`k4lj^8CLHjV4ewDP+gCkcxUAs-SJ8v!@dllxVu6^=iw+y_ki-*rDo z82L=)$X^Qg!QddyUt};_*)O?IrcPlV?#foqZ_}FRSLQtU!+9m=*I!y>ATZ5+9!wj} z$2&X$`M8E{a3az{yoeDmg?ORoSQmkn{Y)5o;VFY>;V09mkR^@T24N*$L6q~EIi7z{ zG=Lt0)O7cLMWBx~XI-|$tHV(ha%en}x-{Nq#GTWGkZKfLA zL?yOy=u=fV98qlj1#B~ikYAg_DO%e=Z{d6n2k?6kze~QR%`o;K*L9>7{KER1aoDut zCu{gw0za`X94`(lqgYR9&oL$3&Iq4og!>rbOAtOrG60L|UZ?{Dd*)iNQj-^QKI%Xh zZp`OJJ%o#4>%vaJ??)rdt$j-Ubm))K8qqRV&c>~sG;a3<4x`nSCOhRY*Ls!O-GRfX zy(vyzsalK={|mROXdEl#y)TB0%h8gz_M;Fp+?DrNczQVhAo-4cz+ri7l=P29e9`^( z2k#$wa}Z5q`Ja@!n5XUs8Q3hW8ie#=1F%8Z5NsGW0vm;m!Ny?|uu0ey zY#KHLn}t<_kv?nyHV7Mn4Z}uYqp&g9IBWto37djV!)9Q!uxbd>hYi36VMDNC*a&PC zHU=AqO~58$Q?O~+3~Uxw4MqB}0oWjH2sR8GfsMk(VB@d}*d%NUHVvDB&BCf-NFO!; z8-xwPhG8SHQP>!495w-)giXPwVKcBt68-tC*CSa4WDcCe@ z1~v<;Mj(CI0BjI81RI8pz(!$XuyNP~Y!WsFn}*H6W?|LkNFO!;8-xwPhG8SHQP>!4 z95w-)giXPwVKcB!495w-)giXPwVKcB< zSXGAfVFR#1*brOIU2GA?u^FxJD-J!ScJm3ICqLcnWnC{3D&iI>W!TlVs6vGh4**WZX&u z`IB~(l;rzH)`?%S$!VOw@D#S`=H=@|FXNX2$gl8-v@Z%UYz+C7_TU7 zYO+GuMp15VO8phkt`Rc*pgjD>aXTFUfgJk_eW(<_!*8I((4Q?ee)bs0_~jVNL;9B_ zyBP71fv`~y85~y`mvlIv@`rJL$h?g)Igg-Acjols#`z;|4qG`cXwOO;`4L^B0l#TU zyO;387T^63hyUgu1u=e8(eF|6uBD^)ti*3Zy;TxyU~g{3@rELNBWx6Q z0_-iYx5GXFyAXCU?4z(xz^;IO8g@18^RVk+UxwWb`xwh#G=$IdaCj!dcfihpoe%pU>|)r* zVOPMefqe!x1^XuKhp^wm{svnC`6)whH`IgRKtRwgKxpHfH;dk8KV7-UPNKYOT%lx}9f=@=iA1vbEM^t3H9KVl%zniKuKMucNi2WQ3-950cG-urv zh&K&f=Jovr;ZgYgM);F?fLq}AXW{30l-Fp<2W%X65$t2I(k`-RJ-6#fdxU=jhowEE z1Hy6_jv!nO_n&D9OS?@H;ZFW)TK%NzleEyw{9H+ z#pho(zHHq1K+D!GTD1t4v}!%x3AbqqqMDNzE(zXWnZ;gOh0H_-60nuW5qplOfYW@| zg8n$%ZiXmMbED^6kLl4f{}NI-tyG=?e*L#@XLMrweECi(da8RGRjpCUIBLG+>Qwg>=7)+V*3m7URvRThoKeGj)U#bl>}#khRq9g7(jRgz zrT=YeiPBl5rF?#?T16XO1*8AzkK?@h7u^EorN66r1Ns-|AKRlUcqRANJIZ5QR>hun zQ6Bw~cTtVJn`}=%FD+^288uG>Ck~=$6Y#V;JD%H z^xo$Oy0vVNG7prD8acXbSjphg<1ZUIq@+WTz}Vqq$6Y~o-1xE~oreu68!~3ZAPNo~ zGiZ3{2_4#%v}+S687BYrX%#4u|A!75S`r;Idfbpf<3@}w>pXP)$dQ4Pp_h#xF>>$- zN@L`R%Z3diPeaQ_my8`ZaL^SZ9zBL&R3}othk;|SDH}9=%;>Vw4?@H+LaC(GftO@E|M05 zRH>86Qp#RQ%ho01d$zx#teu4TbcKTU|I&7CXjjU{Pbe8yHXg43Dmm4Xj-)>F&gLBP zyb)NVfv$D$9pikepu!#F?($U(#g2c#S5TFZ(v)x4N&i-9SMCNb1B#^7zhv*7YorXRQ;6r&egfcfzkCBc2rljEv~;1P4}r`5wuEj+ zIzM4>Y5%?mJYwi?1dkeg33$xlZ-K|bCI4PJPCDI$p)UbX8v2XDQ-=N)@U)@V-JiAp z0Qy@?U34FK(BQ}Fla%x(?*Se%^y71IJxoFSi5U7H!2K9UCFRh9GUnvd;8%bL!R7pU z5!K2`kpOxTAaQWV$UsJRnS?5CZ{lK$^pWDF|#-)gU6S$0* zqM)-K0+;bea{iw}C#p_Y#{Wn;+yNee{|4~$CU_hiy#iDX%7FHh02e=(foF_-&H%f{4=(c_ie7hb(|VJC1}^g}ivB9fnAV%T0$s?O%RG*vpPz%5($iS$ zBbZN7^e^S$=Tiks>!XH#PY!-96|C0B4E+Z=czZgaS|2y`n{)8~R87(PgrTQZsmtZH z=!UNKNkhLR2S16b!&;v*^z(D@-@(&{{vEnNv>%f{TAO*s&`;O3E7E5Tekr{+m&e=E zcSOx)y$?B#wdljA=CYoM@UL_5b@YJKdRcEo^bgVpQ_W>P6X91=O|v|H7JY!!JcRW} zL|<|o^RU6KK>7Rw@Q9&beLU-<2EV<2`Fsdn_&Pr^Lw{OB=5d36k%Lcd#QKDxZ`GK2 z(%|_`%I7=4Q-=PzV%Db(-oI)2{5SB7p$3*Gwpsc7?B>j6y&pMVElZgDF|JYg zyE*tZRBzYiEb9%4zDX(bApCUZ+oYNW9tWq}j@T|eR2a$iw2P=M#Zi)OG zd@s1HuOs?Rt&mSczo0eqkio~bVIDSk&$i4X2LBp7YVcG$*2fGUY0o@va9;=J34?D3 zmw9nzzeb(N`jnwp9hs*MekXXw;EhjWeb(Ts!DXIeNw*g*grm;~nfF-uW8gB6vhYrH zVrae0%Pjm}@DSz;5Z;^?*3tSfI9;C3HUwPe7ogj+vn>Qq7=CU#nf)XUep!fl%HUm3 zVV*X4{jSV22KRPjo;CPRa9OuX_G{*;te17LgpWLpxvZ-tymoiyvQC%qpTR>|7fbk} z(^($|Z$kBcz18o*JdO7D*^Jc;@Yn{+AuFNJKZEt5jm*bFe*t(3{08vXME?rwZ-<|L zJ&`W0k*c>D(7y^E+02|STW9NhChHU6y}_r0XTe*5zXcxH!hW`a*XqT7k{EAu67us6 zxU7dq)h%ahcNXg-m}lW3@I~MCS#dnU)D2EFu1J3o8X1(yu;DNW9FNU9f zXR|(q{QJSP;A!YrfOkKK^=U)@Ab9*8_Wv35KZ3`$GJhMq)4A*?@E-HIUjE@*@X!a$ zFM|HY^H?wI#L?y8Y@N?%F6+(-FS&rZtb-=}*bAAUwkohS&vTmS(h-E_3ear8NgiTRk;b}FbO>JF_+te z;4gy9{8=x9?*UI_SicT@?xpNM`YH3B^nRZ(%^yGiRFt9tU3n z{dVFWb+n34=N!`Ot+V|IKF#1&hOs^hF8kHk;q_EtGLs1Wbb&r|3-dS^pSp;+K5zYJ za{i|vKjXkVOl2VVfoH&bfH#Bxg5m6EoS`oPpA6m@`pMvrfy?=`A3P0C)hA~=c?A0} zn8x{O0lp5r9k}?Za5?KQHu$;VHyQi^@FfQS68v?8_q&42KVck~G2n9zej9OJ&U@iU z%JV^R?{wZT$$!B}))#{ZvA@?4*XKzZ$FTtXN$6!A(q7;@9et51Xv)XE7~DUK{hRue z!DSs&x!;z7%X+9Uz|Z}}J=AM9Q|$KtD)fDk|7y_xk;6}mGR}{zv-&FZmw*p9{M-RP z0bI&+1GubjQU&L8ozd)n8uU`mW5H$plt$3MOkD5RG_0=~Lw;&U+0QcgsRBL<-1PGz zxU9?48UCwZ$$r)veujg~Ix7pHUkAR$$p3L;*pI@xvUfv&4so6TpmE$ML!UL$U7N$t z_uvVvSGySg>r+KhpU;O3KmEWf&0wJ%mnGo!z?-1lipH^@t_Gh0KEmJ!!Q%$May1K(uuCy49wtzf46y!sHl2waY1r|VeX1-u05-T*$* z(0>R%+u;7|+0QD2p9=mlxIEVugZpN=kBes#`#Hhj?ZCqZznr+f&nHk00pvdp9y7{k z75t2cA35$HfKM^}ccm9PU7kw~{xta8;8Je2W2~3?d}M#m1OEehdA{5PUW^w+IW8}Q z_XZa~c{j3unfJM#;;jkzIOv;$KP>uazC*TwUqcmOy%pZ-{W_9#r)(^ddg>B*g67c!pb-}L#k7AzLb>QEEho0~`q}b*kZn%a0 zKLbBfp0%eikFI2WyaMYV0#|F9PvzoJ?WeN-WB54%>88Qs>sfy+>Vf^IvA$q7?^h7| zufdZWS-%D8j+@T<4$!xO-aCVNEX{g(j$cMxpU+E-deN=mNrSHhUuE#09bQkxP`@oe zx*cxC{lw5;9K9%oTX#Y4)uU*{`9-qPY37+;yCUCmw6Y@18;T@>*qo52frWuF>pEmGvH}(Ij_!~!+z@C!#gVa zC&5Do{}OyCcxR-0!d&*V$l#;EWu3U2u)h`VW&KX* z;Idxc5a@5dkM;AQr`JzsYdD{|tjj0l0Q+e%ew4pgyl&gZ^yj-vyU-`({9YWrFp`-pl#96#BvknO_f1w?SuX3tljf_3~UE z2rlavj>moJckqVLzXv}H7P5btSC<}J&h`a(rVXFxRlvJH#QLnk9|!*x{^k7464%d{ zs8KH(wTS&xypQvL2K?U*ey+iv0he_rYvB2K&SLg6ANs-Y^CP&L&;I2+Kk;GKHwLc= z{Y>y+i1+t0@HfB{2Cw-D`;mE+MLz~S2>&JU^D4N^WBfR0OP#QU{S1I!%3(7267Vqm zJPm#Td>HsH@I?Irhg66EPLHzxOYe7=!xi9@!6l#b!B-f37x>49pRSLwe;;0mr5^YI zcm(qa%lYsVc+}wG$JtL1ewtvvt^w~0PPbEMTL}IQxa9v;@VXE1{tEvYya%|P4<{|< zbju8W9r#_~&5-Uh;MqZZo~#G=Ji&fa(DwvC8@ytI^Yb$JT<|pb5FD>hz%%37|1VyS zaLh9H-))K*;^pkW4frMEAAB~rl-tALtH9;>T1ob^ z349v-l!1pAak`?v6FdUWwFsqFflmOh13$G^u>U*2OTasTzhLk?z`p^P{BHs;M8nBv z@Y8%H`~MmIJsg)u!DXKCLC}8${@NofECxU3N%pf3yf1hJyw?)e_X2+te6GQJJ;i=L zH~4qp!AISGT0YJC>kPgCT;@kV4*ON>8P;!tzAf_eJoxY6cYvSzEbC`I#tvG8UkM(^ z{N~l*|9kLt(4PeTm{siOAh;aIyTF^`2H6{aQs5JoGLZBCXYl3Va(tVuX8&6aelhs3 z2A>HYc!K?lpBKQpgG)ZY2OkIC4g1x04X3-x&<_Fs0{k@SUj}c!%$;uWbL{6Fa7lMK zc+Akh3%=OkC$D8cTMR#A!4H7njQp$wziv6_XAAh(;N6qVH-OiFp8Z!`!F)dWh2ZJ8 zY=_Wk;A|VfABJA`tKAFiXDj$^(2oa?pn`ug_-gP3_$9bc9t1!16zAu1=udi){SSZI z%_o7s4ZaupcfmJ2!}>|!byMu8>$A-1vU0Zm;EA7je`Q$N0q_IRcjsv8_I2#1%W4K) z*^R3F67v}NP2gvNd)Ki32Kf05{HEs^$o1QBJ^NV&F8A9J;OW9V$McEsvle_4^nH-7 zhYqx^$Eu@PUj=*)xZmKdUS@sKT6TO3^pAl1>#-lnPm7JL4;Xw6_yYL38h+F(tgrn% z`!52&4!i~UgW&7H)8OZV`!=zkhA*(6bHGmrzY1LPnE;;x9)kWu@MKeW`5e2M{ih5* z6nrE6jDw%2z&pOk`H^(1(FLf>zbE(-=u5%(f)4<{2t1r(KXbq*gYN;a1-=OUckp8H zU%(r$V?P&yPk)v3GYMSU0XBg9dvQ5jU~z;=udzP5p8cE!Kb>D^{sMS!@MYkYH?aO9 z@Y-*%ekgb&@PXjBfp-MIAABQtSMW4=svqZ5-XEL3$^Hvo=5$9wKNUPSfc5)*{KH9U z){lc;^0O3t9=M!WZQo-3H{fS;GU{dUF0U{MBHd6T`U`fjK56K8gKuhT`1y$S6AXO@ysx3Z@nhB( z82V4aW7DXzvR#3bVS{dybTuW?$b$DzLm71$m4VI%mMZ47FI z9|WKF0fPgIx8|R6y0I;M{wMR9KQDYc>z{x=Zzt%-5L;GyFyI3$7V{Xy`U z#Rbp;`&IZk_SeVU22X>hZ05VT_|!|gSf4<;Cm`L`U%*dg);9ppf^UJIE?Z|Cu$%S4 zCoCr%M!FM;>+|7S<9v7#e4@d9dsu&s!A}RDVDM?g_48;!h7*+g-lLAbNcF{fuk!qQ z%i)D8R$9}^r|5ryemL}el~F&*FLizjRSNpXyu0d5hZm`sp}!h>6=eTSp??VaxzP6j ze--)=^pc++q0d0y0s0HR;{3#*kASasc#$e<&pDU;?}k1Dy|f$D`da&;@BW6qo5KrL zpe5&D^jAXP!_YqjeFXYaP&@Xa0`G);hz2v{fUiM$m!F_xeJDmKtW&fgY|0C-IhJLfd3su6<_ut3* z4u<|)hZm|)JGcKEeqw#t&{zLi^Foy|^ba|_NDVjiZTGW2*52*^6^GOHW$1?=V11wi z>ldIrEBwOwnQQ2GIGnCu=+n?I|CRMgL*MH+_MbSB{m+B`ONSS!O@{utgRBpAWc{1a z&-|VJXAFI_L#z+z0Y|jm2mNM;7pVh=e*Pb_5`Qtsh7a8l9iMhQ3W6>q95I_4)a%j~e>z z4yXH1$gO{(fb}taXDmj!y$8O;;LVEl=->Z1F4$Ya<2)}Kf6C8`YVgw%JhqIVU&U-x z1U%KUlB2w!4o8?sTtC;;ZCvsN@N>WTsmJ;*wfTot&>y(ft=|EC`1gvAu+g!s-w%D( z(ATTT`Hy|f`d6WEM_lJ;kD>1eedblx-$%C!y^V)HW9Sd}tH(U=Em*FkKYZY;3J!S) z{9f^od2&K{?n}S!H1wZAe{3brf8bm$p9awP0uP_Zd^5Q8Cl6r$_qFiz8}zBKIX^F= ze$~D*%I7=gdOWk!_BCcks;;QW5|2XsGs&M`XgSW$Z+X?6Ao#4S$tgpjHy#b!t z$Y3}8RHcScU0+IXW&SJlJ%wi&G_B0(P61cnGJgU3m%vj87}Umo{Q({-UZhD2E!=S)VzE`6TGafk%#KUI+Eq*TG{=n7@m9av<&|d@|xr8~o(Ws|He;IQO!&VjO#Y!Ld>=5SC9x@O-Q~9U$%X{Jh@SmaYfc)H0 zm-X>0dB0A_abE(S8P9w&xVIkbqZ65rHF!*`k8Sntooe!Qc_-Eh|gEyfEuFhw`;FlBE z`g9|b<|cjjj!|M!7^ zbBIA4d?WaEl#1R0xZb}2pYLNX%XH;6<@{``#C!$PZ45rWkokM?(;fWMqnIabE{F@y zDZd^*1p4emu9(RFO8rw^%UtT8GOjZSzKz|h7vRT#9qUJdOMNv4{t&p-SA*BHK7{g- z`f79%^Ut7{`fB6`=5*RSo77k1G3J}W)d^f~k(-z&;pYNybqtq}A6)9U{+n690$j#R z`VIXG`0;;U)lsfM`F{b05I6sFtyXs5u zN$?~0J*kI>Z)Lq%5BJYvF7KEXT!_PpZ z+a$<-vddXt2Y!ZvR}L_c?|0#KtS`cQ$~Dk`0=-<<^4=GH&8=Sp{Y&-P zzv$(CF#bO4PeT3=Lch2H>x0Nox7M7`q>oz|q@U*$@N|a#Y{2=v4*XsCITL>5eK4_$ z^_OwASb5s8|3E`d_X+5`g8Q?qAIU$fYrtQJz6|=O!Grmn&oiNy_uSZC_A?p#`#tn0 zHDcj3_zAY<{P+*Dz7h883h?#N%XK90#UaJ#$y@OMIP||l{|5Za`*olq>mTLnsrm}~ zO^rD})QskA&DwE((zRKCBJwi>d}9;VH-TQ>m;Lov{}Jzo`VRVUp??wj*6rDUwwU!b zQSrSJd}%TJzZiOX@AkK3y-e8n6!Zm6S-${!c^~(8X8q~d-=Cm=82ay_Z`XnI6RW_- zaRa+k^8OwtY=Acb~w*1Mnm7^`Y}w-x25A)6mas#`+JT-wz(H%;`%1;px^}m0N!o_#{Iw?Fq@N-THmdKWXTtJt1@r z>sz6G&g;VI?txy)e+78#I@Xu*?y0L3Tf#@UP*-5P5j`Qbf@S)Jl{iGUISAwT!x%DkhXMJ-+zZ^UiXZqY*{olN`}sHEY3Toe zUfOw*_prVT^d)Do|2JE4{^hV*@7yOmhte5*k$DZsbd^F$pYUBK$1Rgz( z`Fk8qtr2~F=3Std_NCZ-P8Y+o)z8o$M7q7OU()WBO0a$w_UrsJIX^wxaDoG&mv*i2 zV%E!h!Bfyb3Vm-Azk=|@@r67oL{d_VNdp_lfh#8TF`L4E#L=pSy&4&H`d+MO~h zS^pUFf6`f;?u2%%KOOoQc>Gz`%W?S_{6*;HxJdg|U^VNXY`~6A>COK4LEi@Lt24mk zjrh2%LWQ70AJ%7fu%Bfphlj(=i@Pw8`a_R%n5XdmelO1FA>e(Wm-oJ@#LN3Wbr19r z=IW^ll+b-~fJ>ZA2$~&La9dicrTHsB< zr-93Jwm10a;0vLjM7+H6p9#IJ7mLTZ+6q3UC#NgN@h9+mz)Rr2@B+@~25`w|Dfo8q z0QPqp_^+sd7s1a*;Dx<7UEwEP$o@|N9|iq2;ByVW20ZU9_9ObAz{eT9O<(rE)8JEy zmsf80Kric2O1Vk9O1L+tyH55C`occU;QKCh^OG*&{I?p&T<#BdfM0bP^ON9bH~7jyZa-%a zU_aTxZoU@0#Zcx{opZL2!K1^NKM$@hWj`%OFux1D0r*RoGrt@BZ1BD#-Fy=Gcca{V zCHUmgZvHWN-7DR^LWJ{^9OLF~z`Kug^9cBk@os(__!u;FN&Z)X7oek}@NdBvOmzFH zJCO6!<~ru%pIjyY(xKJ;Ru?;DA`-TWHx0dw4b9tPisiSZ;qZ-dX6=hj<8*?(ZZo0ot;bHAHk2;S=f zH@^vdXTr^&0H3hX&9{M9UF7B!hjD%uEq3#E;2j@fF3;b|;5`k#6}+Fpj~dSYF9&~{ z-Kj3%ogQQGGkBDEdG}Af4xv6St)6h_XFYgVaJf%@n!}IOyZS=Ej&Dn9FZ?91zA|;& zbGF+@aJq@L)t#{LW|uRsi;Ak8pAqnt%Q>GLaotS@pRj^?Bly?r1?v4;04~>c?JJmH z_9W}&yy^jd;3+r13VhZxZvGH>!&Pps*9+9?u37Eoe}IRdbMs~+S^vdaH@^`4x)HCJ8pAY`sn{IwB_~f_T{6X-#@3{FU@Z?rE-wWRTJvTpgH0Ni>`)+*g+b;%R%E@D z|0eK_m6*$YHE=cOXFwI^@;o{hyv*PW!6zAfKlm(zcb~xi7a06r@MQ-72>b=`KAbJ( zzlQx(t@Qpnb;0LPWPL|WXd&+@>#k+K1bhdsyF=iUYq9_L!P{KN`iqZZ zUJU=kz$e#XUJpD49<#WE>bv~28hbtaNz`L73&*$FB<7KP)-S_*(9t(AZ*es1<@r?@ zWA3lQ`iqh7ui$%+VZF2m?!J-rUt!{_p4hL7H!*J$V0}06XTc{N&-`@ox;L{vRiAl# z@KeDLG;s4l;K4@BAA)`g_}0eEKLURgd?h+8OFlP&A8g8csfX+aFFb+y2k>*lgVr4aO}2vAH04k>yN?l zI_4JEhgveP4L%6`g4WEd;Cy%-d~gT1pC7?*>ge`!(iHYT7aeRb<)78f;0I1-Am#rm z_&6_fsj44%VRyHm2f?$aGsojo?FQe}llh4#&nDB@zxPb$-+^BN zo&_%jUjZKI#rp5T_ksJ*VlMT-qUr3v9k_gF=>uK{F72Po!S6Br_-C-6=fI~U-PYiz z_I9UxA^7Fsa-J*#p9sDeetrQTi5s5OhmX0H(~X4Le-$=r5O~?S4E*4af=@!n*xfje z)o)`zL(u`D6VA78#LIgxkn3V$KX$wh`8*GP2KPt0;8%l>14ngDJqUj40M_4!e7*{v z8OUG;c>S52&&!7}kp9(Yg4Z3v9MvyX2EOkK=5qhn^IGcbv1%FfW3j)h!J9{!`@xT$ z#rjTTn5V(d1g|`v`4`|5!S`P6*1rS((nRJ5pjWrE|25Y$-vT}ud~%Gr?AKl318#Qn zm%%$sVg3jk^(A;_Is++(N^ws2f6;X&a5GomAHOY1i%iN=sIg=Vjj}viG?whkgtFI! zWH*)~Ek;rl8ImQ^kUiBD6(uGuw9hX@iwq?y)wD~h|2g;bxv&58Tw`9Z8qfPV&$;KG zd+z$Z_kNE)41NjYp$>U)I(S*y)0@0t2KYjJnTN@D%mNt2=N&2XmUD~h*+YKQeDKQD zf8I>k6K5dY$@qzqA0@w>JS{w5e7;Bdz@_I|Nj8(l#cgdG?&8)xFZhAnJump3dRjaI zJNME*C1%0Ss!tZ>HOWt13|@_PHYKk`?)s@7*0 zIiGw9;o6?0)BRAJ;MiUkE?Rls8Ab`$!Lv=RE!s^`s_1 z&uZ#9MjnlWze;}U9HbkZ2tJ0qBzclN&V5;WKcm`n$V<19<>gGeHl9pHsHZmdL?4F! zk&MHp)bj=P@NuzeYk36|odrGa96?v=3C@R};%pDQkcSq4yMB2fdF%=B>zVGo!t<5y zgTnQ^WOy3R8#bl=v&qvBgU88F6z7Yq{Q0JRnX;6`*NNgvf1A&qHCE4srra3#!71Bf z`2}Y8$fEo`;YQw@dOz)V@?Q!+SL#bD0eLr$I&1Dprn1CaGKdG@c)D%O-NGx$`ORQ! z$QMwN-e0Nmsa}wGx!Wwfl<@EZ^dK@#v!CkoM9<0PP0EXt=E5-}a2DeGCY6`pWUhms zF&i~zw3U~1>!QP)z&~4T<;$6s{fgRo_I%i%xuz&@LcYEuc#wK}lE;UEJO7Ljp3ly- z6Pa7{PS z967q08QV=gnP|~;t1W__;ArUCNjgR?NuNSJMmY>+#uZMYYoaPN%@}Su^S-io<~m+uKtPh z025CO4Cy-{trG#n2PH5_~B2-!I&j%LVY;CFG|p0Z&Gt z!Oauj6|VV8cY-}`AKj1S83R2pQIFoYm@m#d3b*k&9{XV~qWpB>+CH=%4u6g#UuyNp zd)bPiC11h)q79bPKQF zHRcEE3GTvgqm=Kk4EAs90{gT4qj8p(GQnP`FD=N^!quPQ)zH(0_E%aCds6eUA@>E! zcOj1@;J2nscZzWJTPTcl@qc3iE5PTC0I5MeHH6!8+zvmuJhl|Beh8LFIl`;PJV%~- z2L8#=&Yjd>j_sjK_bMg1y^va7p^p*&6QIrv6R!5;x+5Nz zG3_O5RQ~wSi^5et=#|ScD=+(6AA^5fdtT)k$j84zJJ5ZYRc&{B9lKTNb->U%T% zb{+k>h1}m?bd>s!Tn_#CzcJ-fESI&=GnNC*(ZUzYxF|Ojk_>aRmGZI4h~xt1tM>EI zlWT+gx_UZZxGi7C&nr|^>;=e2>mtF&Xn#<+%4c{0cQWN?k;fl^;6>zjuZ5mKn0h#U zI(;2@vM20u^(7`;^=HdKkLzFNkVl4=usQk+e`aoYQS}`E8Fd1F-wF8BmP)au0d;T^tauev7{fJx!Qy+4bN7uf4rXcs{?)I02t0>mzDUob%jjv}dW6 zmwxj+6i9jUx5&+Mq{1*Vr))sJ5~o7mmG7nGf%OOw$6E;3d_^xrzTgdGULX%_0^i4U zuay8+dD9!*jk`vY$2;QSNKMK=DqQmw9SVCMVY&ZA`SeccX^Ag0=vB0z@tLT1XuXY@ zCtTA_d*!&7JlY@S-i_sQRJgWd#W_xPdhXf?d$I+vr#tQ3Mjl!Tej9m~JW>Ji_6>Qr z*PwsOt*{gSH|AO4)}H~?qvbBnH>tdgx4U8d5Tu^Vg~M_JesvL^FMdW_F7XgYNwuc@ zdycURSEm~iz&up#pM z2<LCzT4_?KmGsrX5rTVJCN?} z{8hI%k#6E;l)f8R%n)wn*&e$3Sn4gv$JRsM)!&BX!81@^&Z>xT)e~NcbQd$-XDJ`} z7jaUC{3FWemO#D|dAqmix8Je4LxpMeY}+~WkT(dUwFxw z8N$^+k*4s!^V`o>&++*^<9)~{Zbn>5*x1i&jfM&U`f&u6lCA zkzfPLPZX|pnpN_jd@iJXjsNBMLo?wjA6$#_x|4eDaQs~4_X6s9%IcAI!UeE@GWj1T z&|mIj==bMS^~vMCkY6``xQ9GUBWd^LYE;P;8nR>bO-duO2ZzcZp^#FRey->-j%GVM}_P9 z=Spw=v(!%7S*mEhS_@Y_@eXL=yVCyQ!d=}YvR@BUK2{Q~(4Fi^mQlaC3FEY1SiTiM zL0lyxh%49MwYR*SN%TT~S2B@-!Zl9(arHC8)y`B2#37S4pOR-Az}msobNMd%rwim= zUb+fbKPS09P=oT5gloF#s_<|F@(R15CwV6H%p`9rT;=0KA@A0^l9W%JgcMiN51&y! z%NO6d{O#KY74-B%}&|C90wmW!K5l>Z$0I^vDTItkZuOuvm1976pw$io$oyT|Fb zRl?Q&j5p3~@CEdklVPXp*E$Ke`CW(#@i?lVNsvb-!4H2i-Pg#?E8vfjAEy4$QrPL_ z&)-A)`+|Q&`8MPUj!)e9rw@7ba@ct%MxaLx$q!kXY$eH zp$71$NawN*>+<&TakX(tVIma-Hpaj-Q8;$EQHvoj;l?TTaK>*}uG`RxRHI(-9s4tev_ox<~_d&R;0e5B>lf1Qd*Ys7lGR=DPON{6ED;U~h? zpXtuUttTI2xwJn7`R=_TAEcjO5N`VmZ@uDED=+iq4(N|uzkHPP;S}QPA{39Q{w?$* zA4UE8ocb>puJ!~@K|QU`3UeEIXbAWvlwT%X^VQv}cdt-?^l6lfYdj%9g` z{|@$~o5IdVsDGAlwI|`tFaC4#2Vmec^xO5{Lr-8l(sk|C2=Wm3C%blIx^UH>O~Wz! znC?+4&mRhXH9V~PkN-q0m;T-Buam-6f7Dz5*-rW7xv=wAr}77u3)fYO(Ld$M{pXbf z$+M-Phs9;?wcIKF|L=@&wI}7Z&)t4Ry4i-%(1G*T@xoO;{xxdQVA`{l@_}pM_ym*K zZ~6bH=l)ggC+Nwr-KfQ13=^*LQ_vl8?({4ap3l#FEtmN8#?P1M=;z5O$BSs^$v>-p zxu<#@>cwSDw}EiYSD+*6T}Se{!fkv0Hsa8YXI`hCIG=~QdHUCumow{cg#887^B?tu zc#(i>SFezUTJw9PKIC1y)I)f_{0_BT;)?53tiEOqd2}1>9LIFGlV_`dccvdM{}uU4 zH%5JT_nY+)Zp-%)SkjDo7XAhv<){qx;7I$pbId=3?E(=Ce} z)nmHfP(E55@~+(o`~m%$m(ifQIIksK^+Z=fj~nLqKsbd$Fs-P@>V7P;~Ed#n(y{z*-S{wFB^rj?iVq85n5mE`|Y-aH9A-T3g< zzn~{J6}%4Rw~&V(1s_koU%1A}Zf_sO=A-JL<3HOimvxe#5r<6}w^#g)bOUW+{}24r z*}~P&iJ5R%Yx32U&$7P=lmAMdVVr+NKX*6=J)wH2FRt82I=&2~fc88nT=Ui48z-!! zd~PNp0nuelO1SzznK0a@}jorPj68^vk3l~Op*VQ zN4bB)wX1&%S3Bcpz>{trY_ja?({+IL-a5cy;c9<~`)_Aa|3>n3Ta@E&mg6De`rIn` z5aK^V`O+sTFJ)FtM*X6=xmI|-xP3yn+8ODAxaH$RleY5G4opM3?%Ykm$&e4V!~7S& zHRfjF`Sg!J0Y4yI<00vdyNaIzKSZ`e+Za?E(@Nf7uKvk-@!3Y?RnIo|zd`!pCgC=2 z?=G6JiPWF+_7!|a9;|_Q7)i&~JN0C{ervqvQ~iaj{(!e%t6VYgG}qNbw5NgaeEw-| zxx}s4zuZJUnbxqM$4kr(%4fL`#O3!}%11h2ezc6~UUWL_iB(4&oOrAahekI3C zUkT4==ikCB$#3FZ55I@{@0N|1S}yS+m9e3G;I(5>@|4$JRXZF03H5@0 zx4+_M@-WYX%T8$f87ExRT{!^hwkCgCxY{3m7xwo;H8$l-pu8eCqTO)o#*Kw*xkNag zarM2QaO(%!Uz7T$kSDuCzvIWKC&v2AFf?bJ1N}M9(_Omlgj+i+qrL4*{Ud~^u+Yf%0N>Q8@x_;1a)oi7JS^Tq$h6YydI_$_m1QNL9Yu6~Q& z1&`Hc{pw@oWu3=cx7kE_KhD1ru6_u5?d{p;B41&)pD1NxDhapc!ga;T%Z9zGd7RJg5o9KX4GH_&n! zf3`w?8&H0+a2s!<5Dzbt@27mU6XadJt8hNcw>{#sE9ILAS3Ul|kr?H3tsp;!@()nn zaG%2<@@3>nu7B<(|Acx>XS4&2$s3kNx`7dh|0`L+9u}_U5~jSXziWhRIcE7>$&H8i zST6nY^+nr_bL2o}zIt)FaLsSX+XvFs%Ik9_{1r;gn6Z=(RA>7``~MJb?U@QcmnJVM z2dVOtOFW6H*RbpT+K z)52}smY^RHzUCh*U&s*tGav`qR6fo9kS_jL3D4)}jh0J0b{XQTI`teRPxBm&^UtYr za66x#Dwc~L4kYVQPgCJ)Pk1jPB*t~H1;VvlA{;-se&N^6rwEt#*?IH#4I;1O;W+nk z1*!iJrkgt-R{g>_SyTajPTqxl-N63hW#MX1?s>ErO)1|(4jOB@qLU$K<~yk30dZrjTC~M0{@Z;&Ui@n){PoyL!KHwcl_Y#pcI6CEWV$Y}6MQ zw{MciKY~5)G2M!lAfIiGcCrb1f#v+6(AN#Zt)IR9NGYd>>AH3=OCIo^SN=<$URcx* zohxJfALagDxb^?Z(0?7{Z7q53TExR->S=fh)8)LC!$33I@zJqX$hhS~^`8U?D5#-TxipI$T^6-z4 z-$*_GP=DInm(rs;^e4EU?BeZC;p(5TcV44p4V6Fs)6jBRcbW=&R#4<-;kutE?ac=h z!c~9J8@F#KPyYo!lw`S|Rx^J)P(irH)p~Cq%WUE5x4>M)$!V?~BMnu0lO&%7+f2T%zQ`OX+|13$ET>MIPq9 zR>yk_S35&jz|MNqa~FAl`<4;a#;mn^C{*ZcEA=P5^@0C6{oJSF`l%z7k8)kw*>klF z)bqu|ZNjacUVHnQaCo4QG4juvbtup0u&x~&B;1yxw=Z`l<)eJz+XAY4MY#GuFdicl z_gw6A>haH6{6!vp2Dzxq`dF?m(#>uLZ@~D8lAHJ80XGktMIQ6Y>sjF%pT)iTONGmz zKXwk{^Ih8CQn>offBv;rxax`YNBdbo`5Ga}2R}!Bk!1(_nI}A7xg4Z?sxey5Z>gtw zJ^J~2LhGfuds zYwkunEZd6gXW$hm-ze9;FQNQQ;nr_nzxD@tW(`{Y>Fkg?)rUXVd+WL};Tms=XW_lh z)c=NX)gQhZ^{y3pdkGB7%Ynli#=I|F^@J;;KYEzyp4|}gNwzb6si!Hq|GZ$da4q-N zVU#=mZ_MA8%Q*b5qH$iK5z(Q==MHkieJQS=S}0uOt(@Y9|CnyAKiM_ zHP?b?&Oo|bXz~={YG(~^U+V_S=jx%|9!mL-gsYvo(y+wYbC~j>E%3%V%2x_A-Ab_M zdbZm)3s*e}&L7?SWb&s?jAKNR}fbOK(oDgECQ^*YJFsUuwdlVU&X=4&@t zUPv+jc_-!5-uQFj3FKd-e1`kGczn@(djk1DGuUZ(&a^etZAxB_=imy+Ul6YLCtgIo zYfk?a#1&xpn^X*U5NE_6AOw<|JWgNVttR_B$?LYsf=?qlR9| zK>U|H=GCL2Et&3b(sszlW%^zQ({?HnDqXyfnPsuZK zyM=x(r^@ne5r5`M_Z4cV$tm9s8FVh=k&_ z=ThOeT{?g`Z$&+`g=@N@$KjI-tdq$FHr=fjz^SHYl_trO_7Owd+UcK0D<*BsL*Ad}b?m0fcaPx}` zI?@k|;D>tjTVvtYZ`Z>9{?xUQ+`I@roqUII^;?Gf7+rn*p8C_?df@4upg+R>4;N5R zU-B%^0o5VjEL_VgxUOhB`73$kOZamf<;zE)KhzxU$uRP{xTLsjX>RDZS-BI;H8 zp^0$yLzMe+k!zWsQa;oVej7sld&z_BkDUCOouNN>E#xOr{%-Qr5b#>$D}-x#W%-=0 zD)~p05Aa2ZPEXS=s{i=U4VKILwzn^RHhFd|(yh)vO_L|Q@%A^u)ejloN8$RHMqQDw zIQvt_yO1Y1&q6C|%%e`8>roZx=by*}O`+j>+EeNV=ucLKoz9F6`Rv{^Zg7;kS~MzmGh32HKN{ zXwN?KNJCiCfbti1XTC0ipBGX7X5m_|R}Mvuo+x^4 z3fFvvyyxA4Ui8mhuxHLG_=79S{c{0N3fK5d_ea0Hnfm+ohCkEZIlgJaZGM|TzpF<} zgsVMSKF@OF=Qk;z=J^7&a>nTUIaEG!LDBWt^ZQUg_c^=yLOtO&zkAR>J_2``JIQln z5rU>U z^BLvS{o$GC*$`B?nf~;~75#+Ud~yG_Yo8w^k9h6*hva4q6uW%ogzGwR%sbavAqxGu z^{~@D_qjoMzIJ%2VcxWd`Q1W2ff)Sn>f^*)px;C>;`)X4^e^FB9}Vwua_vC# zzLaNw>f&cBdDd&Uelj_IWUQiu*k8rTq^HS9_vffANxV zt#`>PC^gp(WXQ8Tzu?9pe_K6rzm0dEwBrEiPj*Ir-TuIl!ZlxJChU9-#cvJ?&le{J zx51wH7Bn!>X3SvWTJEV<@MHn=HN|piXZT#3j~&cn;hJu?0V2fpFaJ@$-wwAJi1G6g z-izYelgEXte?rw!5f3xn(+0twa^AY`Na0p~JRPDCoWv&W8U-4 zGp9KW!t?q6^cdnQ>#gH86Rz=)^`55;6|VMVy!DE?l+V;eh2u5fCQBao`ptjI z1HBQqwHPNCk7T+{;0IS;orK%=qz`K7X4h96z@D zr9Sfc<3&v4XYwqc7iY=KjDelO!^p3zr{l;?U95YA>4)XQtslH{EVv!<5aW2s>FFR` z<#S%YHlFh9z4N^5DWC3umaQZ0tZ)a)G3%|L46t0zM|=C0X9(AHL$gr6u77-1xQ)-x z5O0q%e!ir9I1c%rneJI*ncw#4-)oZ360YrhdQdq_@PA|0Q9krL^td>wH4gISxbHDY zJ-vmio&NgvLE-u8UClcopY+=2CxqKL?~XXHPW{^`AK^KX{^Tc*hdnXYUpGFfC|vy$ z^Tyj9Eax8=`sz>lbT`C_45#hq1>u^nco(!Y57N(9-v#}dS%|k$)HOu7jgx)oah#w3 zpnQz;GB@6R&3{#=}VHpFzGu zxW-$!E8@-V!#rmq}VydNe)m8-3OvD3T1@gwT-`-`8g9vNr$gr8ebPviSp zE(w%-Kk~lhVb0$hkl!m@?dk6AH+x(-JVrr&9TKkjja-HL{xA6rlaX%t6#UgNK5*JZ z9zP5I+(G$Ygj+r5!1KlF=SB}ePlEe(yHdUrd1MXrxcDC`T;nar`!rm?IYYROAD$bn zMm_ISPloelImT!|#UG?SJCU#L2s?9+aE+fV57xWqu)E2lcfy{P)L(iEg`XMG!^AIkLSLV)bo^ZwLjdrsNa6H z@)FTEA%0w(-0%?O15*({-Kl4k<@}-0*G|d@d9M!LX39PcJ!w8KbLH4bxcVW<^Pwr~ z8c+Eo*KgrHW0nfn@=b9clpE)~?euv2AO0qf?MF-K(yccQ_Lz?F!E3gSdP;uALDa` zrj-A}^5gCQm3mA&==p&nUFV6P<(z5SJ7+pZxNV1dZ$=l&-%Fltgz;e&go{~9o|%bw zbN$5!s$ctS&M!jLb6B{ID{mi5nfa6-hHdT=_m~S>l^cgqVY;6H~`K06sb%V`Xh#pL1t5cp`djM*$)^Of<=v(#Ov=^p=SE?n=oKR*sX zqjnfG$jZz7=yDY71N_tFhCE&!`iIcY&QC&rn)e~Ndi02JE%zwzWp(4v zt(1?IL;ZE@qDO_R{VCqtP@4MtCc$&ZVC@+4IC+-m(Cd-UBah5QJ^GLQRpDB`iM|+r zZeTpjSxi5B_a3Yz4<<35=Wznla0%>5dgm*f3)gyD;JrU$GUXF|f5g+YXS;B<$M2Uz zPf<@h#FeY>J%y`$@bLKO6K2pQ&FQR-s;TnhjecGFZYrbNu;fMW{-ys~4K)|mmGN4s?e;yPj zPdtUc8b|p7!ZqDk4aEO+@&|?I)BhCZ{qy+isXtT=cDne?P(Jhw^xsbX|4}~0bBnE= z{m-fW$A9XdfVUT}_UCqDr1uf~mwT+d!~@UuaCl;#pnPZ#>f`Bbf6hx`9u)BAL1E$Q z&s<%M2M*G-KICy8M9z@EO75Sp-(mUj`8rJbw092WPx74iUYm2ChduuKVKdK484po|5AR6w;#CP3-DXi^ILD>S}ut= zMkcO(m_Qz^fl|JW{_nUpf4q$mu6iQgeGBWz!`^zrwd>%Y1pVg5|2@fr-=Te|$bfi_ z+`o76YvG!1m@ne^nf{sZBJ{_WLxIcJW8@KU-^*vhRZq;@CwAFO=%*sy`gS|v`QpEi z<)VlC*4+4HD!G5J>9gcf?q70tzA0So2~|RUbnRismys{Sb)hQE??B-ypZN~;Wg_d> z9Lk5PqC?~BY0VDdx}FgB)}M>5hyJ)X-Y8``6D#!9p7KGS7jX99P9Av+UgB$R&1~V? z@5g!0*Tw(#6X-uoJ&DC=Mw)xb^F=gBlqunZ?#eNAOBf=0=~g=SvRW*KeuH3d@5Z1ne_IVG=B~L z4}1G?rVCg3pf|tUNcjZ!$-D8%=af(1igbCMmI-Zwe_~ws>%pvy5w7u*3nOw|{Olz^ zqW^glqgK z+asevH1}o<<HgKW-eDb$k@+sXO;~^;<|cx&-MSpq{O1R|sD$>k`2@Ya)JaQk0LgUvTrmABC&^3GaFL+3!NXf6iqfdEye- zmV{s{K8_Uhvp;raAGWVysA*YRAvSZnpj^Fgk+IQ}8!gJ&bI<}=;1 zGw^4Q>p2@3Z_UV)D-k%w$or57I1h6D{(ZuA+!FD|vCj+Fc<|pVbVRuNe|HCX*wxeX z{s(&u@AZ9+c3x&Ve<<|Ti}L=y-(}=6zNgZSf8G*qkQWmx8*ns7KhsP8+Oug8U}JyG7Xx{mxq@}PH~y4EKs zub6jUd!leHU;jOB-;rm}#rXU?>aVqne)Hx>ZO8**v~SLyJB4eU6z90YwI@FcSNk*H zq223D{f&1^J<4-luf1@U&t8X;YR~$(iafm<tN(cU zlKYXa*$n&lQDi;2|6ZOWd} z^50TE&h;7BkC*rcdi?Q2P2rl~pm$&QWG6ohHTM$gpH2BF_t&|2+iK-0ROsuhgPQK~ zpH9Lx-6#)IyZrv>_$_GvdF`WVdx-w$eGc`ga)NO6v%KKhk{ij_kmqhVbi7;c930 zYV-@s$-knW_1<~jQ@^Kwo`OA}a=zJLxatYdgZ=l?&XW#kkWsYq>7fYg;(Xi0_ur+^Qkj_p`I>~tV%ug zgsXodA0R;7bH& z2v<7;d|oq%@>_)GtEW3DALTlg%XR5LRL}9BTP>G*?VbCWPo6vlar-9!bhB_9=Uk_C z`oE%lE`j#ewQoO?r~gLkVd^RVC;SlX4UakbE6Ed{pI;ZAFTY<2SN}w5r|XYSI|BVl zo==x%*?tnj^ZDVa6Y%1HL4WWP_yM)dm@2~64=Hayz-^QdcY(F@Ss#}O*Lcpd-*NHz zFL~0-?}JD4+d1EI>F+o$b>o)hcMSdffpASX&Uuq-$J+mmdY1F=Cy(C?J=K`s9jZsx4dULo<>X`e^HoN;`g5Syj|>xT+kx?@ zj|-^(%74I9oWHnopD$eFA;}J>7xQ(1@@cLQxaT`v{)K#$3w3TjJ6gEf6OAIm3#ez0 zaJ45>fOaoSUhO~ViF|~9Z5-q6M&T+S9tiv0I#?}(_g1GbLVan&{&6ySjOQZVydx=G z^`yKw8E_KraSgVBok`lWSh&gue?$Fp>ztvJsfQaCUAy|BaP?b=&$%w9o`aOn4uSm} z>Hq6a;d{4d!@_qc-$}TpoAl0^PH>!Y=*Fw%PKEtx@BOM*30Hd(r$Yau)W1Nu&DU<& z)1Q9+*~(L>&{y4J(3AAeEj~^j;XPWF_&2W$*M20*`_sCSSCEYg8V?CCK1T~zdm`TY z(rb?MIh1R=j#5tz@BP|MPluhk3s8@C(a-k_SN$R0@8sHz<&@8Q#=hvU*b%p8~5H*xtu)9`y7U_A^wj%;XUuGbQa2Mig!=lwZb)DDR2Cc6|R0ra~-u3 z{onFz<;Q;pST60r9F*)RiabId;kut&Z(J)}<0t7oKmDI@TfW|SwM~iq>5jHs>X&y9 z_J_h%f6jYP!7r4LK7$gJ;kW%%IS2WTmjZWjew*dT=l2cDo1c*1)45Lgvv9TFUmv)z zB=r05t7Owzuz~Vv?tgae#_8ulPsn?pQAOcu z&+ah#5&YknDZ*8Mur~U;Ynb0{=c~NzTjROK^0f1yaIHs?W{4BV{}ZlyV$+Z>x4t*8 zH1x!{f7r>tEL`O?UVnW_8Stccj`hs4NH;+L)TBKH!fm=GP$IXpAs#^a=qo627ym0L zAM)CVv&+Fw(*yI1d#Hc9aLsSVYlojF&wBgreiyFxq;E#QJd%29UI0BG-46%5`N#y} zDxYF~ar28$tUUj?(AQzgXU;)+x%1$qFJ!vj`*bcBp09noj`E>aEH9?9M7YL@@#3UP zdFT&&&%d4~58V$v8>pvE1<1#TqlNs1dxkCIn9h_>c>9r73RnH*ymosR^<=L^eY}fyHoFM=vu`5M#*vQ@ zuH_hc10CQLwlh;HpD7PL^C*AX#Ynd}pWD_TzeRYy@>(fe$J;6IIo)n6FY}{~_$!&_ z*v}ur)t*cQ_Ee(&lCm)%pZ>mnUo7xVMtpFY|G>4|OSj6?uZ| zy>6U&lkj}$K7IoJjOEhqdHZSK5w7;c?nIpAm~O+$C>Q_y(T(K(^Nz8?RgdBP)Y-X8 zxNY~m_wJov1^WH|t}}VC0FgGAaT_O(zl=aY?J#B~d3quGmkBJdEyC5FY%k>NDaKDh zRi@hxJ*k`5+(#bt_PHg=Q!`*sFZySdaE+gg7eBj%Yr2W6P>*=cw+UT>bVK72w{AYz zR=BnEAnLWdr)Vg7qB-<5LH5jC;cSv=3BF#Ue#8Ap6gR(6Plol{J@*`2jrQD%D0-9w zi&w}q8Kg3V{y#(>ITM=4F!hV7Lysu|1+KkaB3#Qo!2K$2e7lA6iC>T}r{`<(P-EzC z!*Vn=P_O5C>y71w=ZpV#l+Uq!E1;c&gj+v*_cP3~dc+oQU+%M%k1b@5XwNw{k>4Ee z`CLc+S6j{>3Vq#3`7qD_y61y;3D&<8<;&KAels2Ub@gkZaP2pvJ5Y~aWc+M% z{2lPSnXg}{Cs_-6T)NlSh5qb1^sX`;_v@JBs#4 zE$Sg(LC$}xFpVL?Z9D9(o6WQGR#b*uLC zE_ssYL!F-Q$)g((C;KR0`wFIe7UHcHc{}p#wUBSmd_7L??@!(!TcgG@&tbWG)SEn42erwy8)Jp5p3G>Ji(6Oh(*QhiBg)ss?JMM= z?I7hDx2HCQe2N$5wPJpU3D3vrix%?xcJV@;L9Abbc5w{9J9B zQYd${D#lC|uKA66`?r@1S36_VQ6na?zU&pQ`3l9Lp%MMiurYYF1@!kM?~ga7{P83*~hK_1x~{IX-dq z{VB@l79xI5XPlgOwfd)&iF)seYhk(U18I(OPg4H`;Wk}w{P{e2#5)hTUAX2q&F4hU z{@*BX_?)W}^_RGY{`A_z^}@9rS9XIv3Ce#>`D_|-wU7MzCiK6z{;*lN+7mwsMdabC zs245{KWhp-u?L{%WZDyM2A<^lp3}d?aw;wKwT|*p@1D0k!lAj4u>7-jbLjW)GZ`pc z`-P-8K7UNO<}0_kXt{K6!E*HOL5&Mn`S4SaPc!-T!t;$cc2Yjp7xk_tEBr&((GPrn zbSw3|OrGk5hU#qA-zqH;|6!iPa_w_d;rY^?BV6swR7XSAkL}(LD=+gP?>>Li3if1I zz^e;sPdnkNC;K4s>-KHVr+jD@`l*I2-(8e9yeHq)mt(^1yzhFO3C)Jz+&JMz;o3e#yyu=

ehg5q|6b45Gl z$A1c@9oJk<|z^*KWK|J&EP0>4%wz(p{PEP{=#|W5|Q+VW)IY_OpZB zJXv&H(e?)D348tHSmA2tq2aJF$aH5~F5?jIy-tUO=c}h@-U$8irtpt@Ui_YL8~@(^ z?ft^Foy@RZa`F7P)8ma326fAy?kvk?KHCHSckRG;Cy@VJxaPNpH;)+J9d>4UULMgd z@1G^le28)xL;t*HIe#eh^|f$~XLA^S=*-_;)&o4~J&&F&Tm>WhqY>0ow+>mc7wjxP7;)m_d4+J* zW4v+HzrxiIA#WdkkKW*6@44+S^4 z^;z;rXXI-d^_!bSzwBel+zCMoePhgybzk-`6{Fy}i(uhO*7v!>HGY!be!}&_)lPr^ z=l8;4xpM%%Pr3#2v6-md4Q6UNKJWnyxq>3I$wOR6a_a+YgsVSuyuZSY z>)xfje@>x%U)U1}W1K&l`WupG_?|4Mf0=OgTVx~*@6Uex)_%~FZVx?OspkQ5|9w?k z9p^ruD=EKUxcYhJNW=+d0ml4EUe22bUECk`815&>sKA&u?sAztt)K2YH11;+#Dd20>5!KiKm&<(rX*Zb7+x zOn#qmEtiaU58-;@8vj{uf9$W8%l<%~gR4P37Y#9V-y7`jg)C?pw&?-gxF4 z;hJu80D83BsQ>yQ%-3D;k1O9%Q4Fk{ce&eCk^8k6O1MGD7`0Ws` z`xp)1H|fMJ>JO(}fdH+7b)z2}$7_ETm zZV_(#9j{)8MnX@3?LcM9KPO!E1i0RtAkR@gdq2jjP3fPiqo5~w6=NBMp(_dNPb;hJvrD%6*|DBo@j zcs7i9aOXr~!d1WFea?L;KSQ|Mnef&>pQU`9>v;7jzmM|kz4I5PZb!PYC(w?$eM%KA z=N}jPYD{^v812=~>=*78uH&C=-uPz$<>Nyk-56i1#B#4T7V^0>kZxDX-$L%chhn_ramcr({Ku9TasdDNC*@NQ zLf$>ksyR;6J^pi*aLsS=7;@zL{jOGC#^FC>!Rcva!`x0Dc@_G9q{<}q)bP#~ZW3WPs1&*dKxu6Cxmu8Y5t*XP|0dkQ$e7)Lz?!nNMz z?nO>r8FeQQ)kpkqrkx{&tNzq8XgA#bkPC$esk89cdg_Th1^u7$msj2cJptb9;`}^G zxU-?Ko;j2^-u$}Jz4U(vl|xPZypq-6t)V zbxYn?R*CYjS^Y9D^49B4pQw7IzjzS^%jU;45U%zly!zPD%2R2fuhmvw)-iZ5eI5Sp zbLvm=Ipz@ZzsRF~P~r#JPFB1R_N2K_##Rvkm-ALP&L1pX?F{vU2KQc-$>fpWP~Y3J9(_U{ z$c8>RWRpS9%azKFN}l+QZ(#o!N- z2PZ>Mt{>`qocv1iAmhr_)0>2Aeq&!F&RzVxM)}Mah|*z5#snWgTxGm|wu^A9=O*}P zEE~{?!Zlxsx=6YXA8@y`FQKlQ^`!d}4 z{DKFOZjklDjnCT%uS}hVzxq=?a3#v!okw0|<)t0qb1_(JOqnSxFTNjb9{tmlJjs4m zt`o7J736{UQLxRK_*UUsPs852)*r&vpJDD#dxG*^rXt+{-+$`%(LEqs<;|0*Uw={l z2g*mjN50-6Z}br416M-66?w6T5w`<5&M!`0Pq>z2avS0y#qu2`T+>Z&gdTUF*muG; zUo{${q+EHOF%5iM8;}C(zgW2H4_=D6b@AC!xYh5qpU+r%{&AtNH1)(9!_FKtaME<> ziJgoHe~f?AOSq<+W1P5te;Rq_V))J3^CI;me#HpQJ&&&aNdEPr4#M-b^D)b%-S*C9 zKO)?gySHBPpK#j`avzji-)=So_J{dA+Sz$8d4&7)#xTE63b*=Kzz;L{2Tc;-32(kU zQMj$YcObxB`KBnJoCF7VqW+RI^XIqj33z+q+D^v2=dk01tDQ+cXS|B~-w>{TNb|kY zgURd7f}PR!C@*K{5aAk!QQqtB`u+PUA9)n=qp0U;;hL`Dyv(gbR(}-wvn3Iq7qVWr zBF|KT9;bh`a7{Pq&0pT7e2Q@uWV#2*Lp&FGJNci&ZFxNd&5twP_-vM!H;z5$G1!@Y z4eg9u4{0M@^+c|Po=xmu7E(TOGNSZbrkkUD>HymFYbalJ4)PWE?tdFDT;nABE&Onp zdd6I$>t@G)Hc`*GdPUoZ?bH+6i}}I`e3{=ZKVHwdbCIvW9<)Ew9oWwb;c8Em&v{)r zZl`>X>(5Q7@)z<{2>z+TdU4G>=#Q~pxcXIbKJ>?4M1roJY)qa>puW_g{*l5p9(H@r zxt0poa>?=eGQ212Gmk^QTqpP^Nj*0R*L?Z&vIm8$o;dqKS09&KdH!*suaOI&Kh_!g zTl05Igsc9{EZFbn^}DRR^w(|B1NNkRgN3R`)(yOS7zSG|`&Vy({vhQi3Ab^`d6pY5 zy&zoE&6R+M-91{RpMZR{1tR|0o@vxOV(HbS2q5OqU($74Xiq_beYsjPDAg)SrT)kAd<~I?B zKkD|za7V4p0*fz0^U6XHONgn=y&e{yjgfY z|HLVunveeR1?qo+Jm$UEZ-><*?RI)72tmO2~2mT zaE;I8K*ViJ@?WSY@g&;wbLi*)$m9NdJ)T0kIo`YL-aEg9JZhk)JoUUy?$7H_UW#&z zdgmx>3RnBXUcdjia4oO&DbT-;_HUtloX^Mikr!JAJ^sCdy@abDQhcuD_7B`GJYP93 z6CRL$*WD%MLcw1x(mr8r^9cqzUPFipEE(!xLYY-awYU+E5aLpkk=8e z^{zF?53b&|r+nxKSm^d;Jxuus=SKz9^R4AFZsESBYUJmwf;}nj>vr!!iwe(IF1K4Q z?c{#6lkadmu$FopFBmCgjTV{|4CqR#rf7j}v(n4S7 zKMg&m4D@`&0rUXj>bH5`eO!x$Yk6fj?ixv5TgemM(Bao+KmI%Q#JOG_r2LFE)blR{ zT|c`@xaKR!=SprqSpONsRgm*d_gto{aJ47OcAz%(N6Gzln0v{CoR3eY{5tYnXV~AB z?Z8ptYESkOl%})i!e^0gocm$iJu|lpS9$+llttvm+Yiv_Imr9>du$>Pa6HhIb{-{< zct-{?`{wq05e|GRtzo`;^yS7^zvq#te+uJMrKc-YmWxx#Hc ztU&$kOgo>ae3bKISC0--f84Xb)eF$$?=O8uxZX=|9zlvU#~ifsOsvq?Kh)#T`z~G! z`xD-HroM13uV?`4d&^lLXOjoK_WTHWa6alwh;iP19rUmC`u8u$Bi=Ztnv64STzSty zx(m1EG9T^39nA0?@(Ayvz$jO?os*k(XeZse-v`v6@zyl!hclz!T;aa`} zxxd1d*Rzz*alD6I8}q)Empb8{cm7_u+8^LKhzF>@?8`_u{Ri5mbLr=Wj(h75=Sy6w zf0EoUH<5m5MxMAF<<$mZXXcWJ7a?v(k-sfm?aA^SbddHG+W;Qsc}dq!hJ>pha^C&4 zA5uO!5&gw$wEyB)AV0->U)8n3HQg}Jp}6&{q2&I1Qr;A<`HgU%g3*pKBVMKbU6JmS z7?zo7$_TU@uD)!r@>aCS|NcG!KX)_z(*gCXEB~qid8jk$sT+Sz6Rzp* z_U6UU3fKJlXRo9BW^2E&k)DG`>cK;H!q;w+ei6p-^xF~8!KG%oAsW*e=S`7v(4Kl8F-ui zya_GyDeRBNkw?7!5<7(3`Y7$9eq6u*o#iyH(AOnfq2FAO7VHcDuD5X26AYmJX+-`s zd6?^Li^z8hSNrFA?MC@+s^|DmFX1ThqQ8p^S3NoJ{`MEG9yy=Wo1 zjovJ=@)Rocb(r!o?)MnL-_5UhYTj}@>;3%Yd$Dj$H!~jP;`;HP!h?mE^iK(#=ykQ$Bkm>et_tpG}_j?sa)vxaN18H!u5|JmBq* zJ^Le-FJ+=l(J#9=>>^z4iPcB{(wFJ37OwdXc>B^TWau~V{R<6++c@XGBd2E}<%8!T z&fWNGy>QhZS%z{f&T{M3Wk{m_pT(4OA^gM98A^he7nzmnXacmFP2^Ofd4`PtOd z;bY~;e@0s_?d=BC_s-P6gFL~0*8T0j!qxs{AB;cuBYURe_Wb%o!c{)n4-s{YCj4vV zB_6!>sPQ`>pY4wR#kFI*gloPMY&Wi=p6WYkPfz&A^~-VL8YhQtDeBLYK7qVR7Oh7E zh1+uEeGYDa*JR53_cZP!_n*gIwF~;=Y_HsSY!G?qA*4Hv_P;A!(~a{UAs0WP-LQXN zw5a`)gsVT}-J!?zUw;a><<9%+o!?4-3Lba~{hi}YgxhqPU!-D8Ps%4(pk6GdonwV- zy6Ndi_W=1qC!a)p|C;f$it_$B_wzr4o`CnBj;n=hd3A4DG{60Y>+`iRpXUadZi0Hu zi?C-p`8MG$R*CG_VXI%(QF&gkGJjd>bNDCDbAp}8N0CSQJm?Td2{E^cOlO<1k?aV`aXb;b)xbk{mxa!IFM1E`1p7XwhJt?loCdnHKS9$+E zzaxcfoP;-_d{K*yd5-e_dy`A-g}mXu3)ha-7OwguJy5TEvK{C|`M_G}ch7n660YT# zO~7NWe_1J9<1oneZ8zSim_@qTm!W4g!n^ure6*8g#|52v9T zn5An@${Qya?Sns~-ub~c!t=$|BH^k(<30bXyC3#vymg`0meaUGUp-I2hY45xajuKD z;NNT|&w24P{wvrYVm+!s`3=HVPx=~^_$mzJOx>^Z=j&n1rM>0;L)Xr%CXY({s-Jq) zzfHL6PjdgWE0>E7zz@+F5_I?DO%Sg2sGN6yW|H!`Cg_j4QU8aQ^M^uTCw&9`x^AH# zmu@}b8V^Zt-(7#Z#N7vT&7;@i{^P)7>vz^OfcKtd`^*zK5RdL(mf;A1~bc!8-@K zPPpdRzc2S|^2`L(zN=Wk)eb{Gy&d^Nv>4Muxatp%LBW2^{7w_D@et;E9jEnX8TI({ z<$aFxy;m+@Wq*Jl!rnf~0^v5@kKr+QkIikuHD9@BVL!K#nfc_IJ+OQ%{qsNSNxuX8 z-94z?euO`xTxW3QGDo)(^}v2g28)?X+86ZHhRp6qzppP(oE4bqLWJ%3xcuFoXB z^_iW*Rev4cPq>8k*UB+n&ad70X9Ri3JJ++>a{h6luTO<*zM`B*xN*@xpJXNff#8*ZlI0glm37KcGbBFmB^kUi|Pj;>7K%SxNaA-^)Cn`bYo9_~d?oAo(=m zT3#vXZ}syQ`D*e6&zpZuUh;S9@$MrXE<9g;pR-)%O`Pwb6pVRKxaKS7os&B057-mi zf)UXG*6ZrRRX)`Oap=}tmXjx&fyZd)$$#dzr@ZCTZ{7mGxpP2+gsc7}@AGlz5nd;c zUxJZIGwMI}FW4FHi5yL2xzr#}%eY%Vohjc!xa!Z8Mn8Lmd^LIYAoSNHA9NJ*@tMfi zYVt|KZM)G5kYfG7={i=T~ zzn)gYZ9mKBl8yLB_gQ)A7j8yFGK>6a%BOkn#}(xJg;-;!4=*>b3b7>BjlKn3pMkCb{8z2^qGgK6$JL z^f*66g=@b2`$HxRSHGpb_wRf}`D7OHkY>Df{118}(N_KNR}vDqQV}--PyR0DrfMdXg_9PMkl#6t3g>oHw37Q|{Z!*FN+TZsomw zk`G&XsqdxWH`i{gAvb~3tR-L24~I^mzmYs=Qu__>8E|oOy>RtIvM<^h9?Lhg$zy$B z?K-&C>=JI{@JI9%Za+g%-Y21YvV0CAPh{<K+m7F zzoztyR(~xx;8F6n!quM42WSmk`!mFH3KjaAKs~WV&~qPuH-~!CtKt7D+$ghIxUIh& zAG)|YOP=TDi=ToM@HWELe$yR}JPl!Lo+tP3-+0&Rk$6iZUz6$2N~fb7v);U^mvHri zzh7dea7{Np4wmPb-=pNAx8VnOf7Do+Kj+KW8*?52E9+CTkNr2W5H&L0YWoqZ zn-t~!b*ic|FS35)d(taY{ube?CsYaL(wh81^7H|u_zao@^C@}m9%N`L<$os+4gq&Q zFCp!qrW^5|$EAg9y8b<)d&&LxGMAVA?oKC@v|pnwmwH+Y_8;OeXOL&V!e8wyi(hOM zuH{&q&u8P5-!5G3OnCS9=yQ7IX`bh;NBP%<=d!O!i2D+bit?Lb!QH`SZceSr{K)NBd_AS9{{Dzt6H=`jR}w zb5&Jo&|lQ!x3>X#Uz*wzj1=|5CBpNS?;y*iTVFch z`Hl8RJ99qm-y!FqYVf0`#*7uN`a??*x9&XAljN!P$X6}u*(6-kO|e~a?covfK(C_xOH|&=qWX<@ZsJwp zswY+!J^mi**Y~(+e;s}h{k0o!m%I@2Ij>#1Q@H9+ay{S0&r0%K9OZQY*)W0fkk1{1 zKV5%ampt(?{4kB<#(~1s&NR=NPGlU;CpVt|2UXDec>L!v;i@OZb_rG)vqQMX;co9a z^%?Srl^k z+w$e}*=5wfLHY@mk9p?~J`--^%DdkqULEogK8HFL z;cJ!%SNZ4)#9Wgt?7pN{`7j3uSM=Zzi1=e>i70d4WxW(I^yIQ z^E;Y6*%a|PihP4`^;_6`zFfX0^rtz0Wbs2(k?4cp+a9LT?+eyA7cFG`s=#nA+EbR zKX)KE-u=VNglm5N^Vh{|L%;tX`KoOAnhCe%xDbAxLf_3H&v?(@Um%am z_)$MpV?MT=e_ZG*^+x{lhJT2>wewNf)0FM)q|3nl`{fI>XR4PP&dg}mJ3Rio~EJQe`h2}kS|9vY3^&lVZfw+2t`WFaSJL7y$=y3Ao z!nM5OH=(}{k^e~fB=>POAwT1C)pPu(f^fAn!F>X^G9EfudFiKEF3vywgfA9NQ@GAg zH=BxAz|JI}%e(fuiEtgyL}nEoR}2!a^)ATshP`RpJJb{7`>>iZAP$fxIRACyy)yOT zhXU_8-9q8&w;-Q)a9U|L3b%1P3UT7zi&weU2RsDKMU=Yim3G4$=8>6vEDWYS6cWin}|=PmG% zo1X4FGyT%r>t!hllOi3!Aqv*+&XpY)TvXaPE{TAUC1)vgx{=B{=i2vp2DS|UcFVp{hZ-{ zzaDUs&$HtH)O>ia;JHv{d5~uk65kN``5$7qj!U`WQ8JHZ?pN1KaR85+mkSCG`hSm4 zIvo+Xe-Zdu@q?WdlJE9t9@j~!ldR?QdccVft^Wwh!`n67sAK$j!DIT#@9`L!FUeQB zDE*!UoaR0GBRs$N6#0CmZeQnqH6Q**+Mi7FK6^;;-1`9YIU(|<#0wezT7X9HE1gKFQAdbxVvxl`Z=L=GP%biNC4;)9u|{0-F}anU#M zzTA@bAACmieEq-;jOX&*S^gg@^YUoGXn$1JC1Ag+Ik2^Jkyf^BeNb69s;5h4J54`13r#3D4P=F&=%-`>WF4ti$#`jsMq} z&s&23YZ`9UU%J-{MyHV)*4xG5nte&(zIA=Qs1py-xZ)py5&no4J%o+zL3Y z(_4(XtnUV#^#55y|9@4%e6xocM6Sh@bx>X>ab=9|xTHpOkw~t<&!HIPSObNLGY1g8z1bU%Wr}tL5_z z0>5-G)}L<{#rJW*3BOslVd3!%zwo;(hX)0JQ{b2G$()g8k$5KH#D_D2Sg)_w3H*{# z-|{O^2d0cK1ASO*7)DX_d+Dcw{cZqGd_M3KJfauKe(@}UUoiOpK7pTvKa&2q z`@V+1f>)OI2VP%d{1@KBh>r<9C4nD+T+<)c26z`k;O05*g21O*+)~m)5?=+J_r8<&?->i>u4Cg)4d;1JO%ogC( zzF@qIH&fw$FNweOIYQ_209SUxlX>2?{&|`uBp&{dXn!wNBo#}s_z<(QXqVvql zS#n+`^7aLd=M~&u+r8hj&h0NflIQn`;Q3v^X&qgbcm|g0MB>AM)BH{?v78)`_Fq(R z`N8+s!Unf*!5>L~^!c=|;J$|P&pQcDd*(?|Yyy7{;505Xza~{>{AVSfx+m>#23*b8 zlbQdr3=($;+`Jclli)e?dZzQ8g6G44D|8bsP7)PxOQK<7EI> z>*9LG|2DzDA?=gKyQn{>@fh~@H=Ppv3p`(WVbiq03&y*9HNchpOB~(x((f+<9woQ0 zS8(u5?wvm^?Z2ZI-TrxQL|8`Zu?~^!VoF9Kv@R;?! z{#D=yjCg}5+%Ei-cj0*!5{cUZSNcTka6P{-5x6ObUjdx>bJ@6`eO8<0WX_1&`L+(@ zzx)7Zq_!U(tl+{d-(QcG_Q{8Gdp%#>KJ7mOIMH({!}i1KH#4$h-Do*^g@VJr+Q;~R zQ~LfpzzI)5@=P_I*Y#w)Ri5{w(mn^c(kF)fSpuBq@zS$+9yOmg1<$2LmXm)KJRcQ! z!l;*i-6rEtPBERoAnkt^a9WS|G2Y$2Anm9AiskL8B5&USoW^zX?##*iGP=apX~uu{ zg$&T+dVzvVXTHDw0C2)%zRz{{Ery>l{5Fa0X#PJy!9kD2hiLn-2sn-FIYyoTy0pLe zU>?^)g{Bt^y!9yZhHF3e7XT;v&%T4#-JgCJBbvH{?Tv)k8+zC40#5VW z`d-#c+uVKP=K&`=KVzH|zas5VK9l=>xzPE;PZGWv{-RC53BUQS)=L3b^Lv1Ie7)}< zesVNFU!vexkK!NG`}-RKS8^!%xepe4J^?u0Yn(Iko_^>lOpodJyHVh0UdNKG>yo_) zaN_5Aqn_3DPct4fFJ@Wb$@efLKO>BOKHxOob4DD|N2Gn?W8807=>K=Xsow)nAOd9j(!PfGi*2z(#T{q(0G@Sk{E zwEyr{z@zr}I^c@_Gfe-N1kcMGwr|(|FCin>PSX@{^Ffl38j0S=C;C@cs3ju;W#G$q${9-|bg$ z*bm~*)bhLtIPu}a16XfsKhiq{e(5Q!uU;v5mY>1xO+EiUz@zy52?fV`|3mi6iTY0L z!}_Ftlg2r{2e_hN^4Ih|_*-@RSMhvZC-i(>wTHjRh+n$*vt(Sxy7+m4?=$SicLPrR zzx+-fg}yiW!Dlo4tQ^o^CjI6CSA5GdJx2uoMS+|39*;hU+n<%XSh^1XCg4$g`y&O1 z9D*+Tvn}{PC3vQc^>Y1lna=a_&e1o%i9dKU;I!^881w$C(*D5rGkz`47X*GG!Se+% zP=EeQ!G#FlU-x|;_j~e>8H1LqM+yAWuP_3Zu0)~*IPvYILI1}Ar+GgqbwqjBP9*+K z@Lc#SKEPSh_dS1x@gyF={MYB%*8v{I&$mhY)@^K2|B>MNCxM?7xw<6qhdf{ClzLG2 z6ZnR}58TQ9ev|O|ZjcYwkkU~8dLZD$|6i2zk>-yLILX^N8JG6|KLv2&PvN_G-F?5< zQFnU*x1U;Ie#-L(iCYDJ<^aQ=F8zK;!%s4twNoPTCBO;)rJrH?KPByd^5>Y&DMSCC z2At@;l;WLT^Z$8(6P|<-|90Xm!_PQu!TvaRpZFx;#D|0-hu;gkhv1jQ-k1}5t_Pg( zANX6w^Mk^NTL33|TEEGN|3TU}r2V-!@VK-c^*m{RM$TVpY5y*1KV{?D`n zmcVC7`-i-U`VId%tl*fh5Ap2l{qa1?GQ3-Vrz7`2=c!wHT^tbj!po!e-je|* zdd|o_OGVnh9&qAwLGE*THWP_Im-c68m_N(X{(9^mYCTGwtA`2vR=^eh7xQ@aef`H& zdz=eyVNI*)|2p8*?}5iKKVK_&HeSJare4i>?jsxF_x&ovPyPUF&NoT>Jm7?f{KWKU zUf|CYc;|GU7G^4=o%o=E)QImUk;{GdPA$vn;jPU9_9dH>S) z)a%mTtV8l=0xvv*<@1*W&%IvB^3ZBAf2LF~sHXuqjqCCYIR59gy!|I$DDX29e=h7v z{JMs}jPdLB_+Ntm>?-5e^8bui34YO6`hNKj0jF`DGwigVcr~{_`5wlU|C*DWJn@jn4q z@_>Dn{`|i5`;))Mc+R|mXZ96LZsNIs6P~FW^XECz{vCi5p29i1r(e>C6j0XswS^YbkE@{DofIN&so38Vh}2H=Ee z%82*)zSlFnP~aY)D!h9f;EK=i-_V~a^jBRDoZ(iRoMvI^QMu&q$p;y?*~e+jt#)orjTl z+#8slOA`OA`S5(eqxRF+s`jY6a)RkhO26+GJQpOc;NAki)CbRhD>(Gkk8&^i-tgY% zdA?3Ic|p8V@cgreOW@U8MW1iIk@<7xpLo2t%Y3~BaFP@AJ)M{SF2gSy_l)27zZlQC zzh=hF%6dEjIM1LEB7Z#_@K-{fFFb_#a9QA=7Ce_aOwY|i&!gTH&Ce$&IN254Udzvu z04MqjhQIya1l}_2{EasY{ZC>%+RyV;fww9w39l9f@ypjm*9rMw(%$s@eMsP!9>UzP zWW1jPT&-&(AO8p663w?V;3Ut54>O(XvW}h(IF0w>XL+423;quRPWaCo`@%QBHJYCf z1f1|B<^2~ucNNth@*wdTj}-jR5cq{0^XHv1UvB_h^=s5?{d<95minc?CwTr{@SHu# zNxqbf(voJzn%=ZlEWA9ygXRe-75rc*2DQd!C#PkKrPRI(FgxM z{s43$_vJayXa4A}uLE3T;KXO9&hWPSQ4~7 zbAN%G?^GTEoc4u8h3R>Kd~<@sK}^ z9@n!K9Q)VrvtcFbIq@EWn|05=A@K8;Sy4S!E+iiG4(@l~t;`3lhuZ=_X~cEB7;ut@ zeNW&XbzJ?Mb^E_#4oms4#Nr<@{>0Z<9(3KC-xT=1M=)HU*B*O8+DpEwmj9m@_{D!@ z`nCW6zJDz34>0`|;r}M!v>q=S_alEV@T8G1_V0kxxXyiw1@?^S^B;aEnIr?_&75f8-mzlF<1%z*WDGW`5QLexE;)_7ZQC75F0nCwV&{ zd4+nuZj$zg{{r@0%k|$X3e@4E!*Pk-~&&hf1dV$XXPJB*0p69(P@D+g< zUe1Jk7yml(DS=-Uxzh3HmG?0HX8g}P04Mo5Cw@7tH$JW4xE~k&sn2oW`e%$MDRre5 zgr0i}{A8BLbw7dI0^j#QhHL!K0G!5k(q;(CXQ@An?`8Za-^zOFp@PQ|_`d5HkG?N{ zrohjBnelX`{jclxPvrJm-u_j=rIGKiA9)|sGi97lpCRz1_|3F7{yN}M^7bR|XFM$< zU*M^Lt95h})6oR{`zwwS;vfj<{;;!kpa(Ek4oX`hsQx-Urk|0DP>N<6JB z)5Osa3I8RJX;B9DECrX3eSiJBw7)pT^k}>2zXX0>-l33bNj&HxkL&yymcvC>ABkna ziT(}4UU~`OBoD3Uvp$sTfy6yv{}FuZ0o<>q|9Zd)&u8R(F(2ThobHL_n|$}Q;_;pnxBvTOQz?7VMje3aH4154>D&yCJOGiqIPw3y5ts57fnRUrlm3n1-)HFg`+k(^xg>VQVZna@ za2oG{?_l|Prof*j@QZUym41Kxt$-6fx5#;9PTF4<_{J%gklz#dJ^z;RCqB)1^gKQc zaN^Io=dyf0U)n!U;4Q+OGI7fuDU-@Z53lkITFm=aE|le*PXoem)y;HShQ5^NyB>KLDKQykyh|_#bJ% z??!I?R&Pa6K5dw!DXKl>=A^Xbz5rxiRrFCPG$ z;(Vrb-4&6;F9S~FdeBkj*h{?6B> zU+bTQpN3ucc7dNa`24U>@pxNz=kaR!JgneCwC}HH0j}hKHaL%W|FraLoTnZEIPvr3 zLm2~5;pvR{guuW3vkX7^ zUhem#z+WWrbC2cr`n>;$&vCz(AIqcDdEB=HPJEuai4BCL;Q2M({*BDf_Y3^P0#Axu z>HCg<5x7~u`tF}+I$LL1pFB^-+Z6bPU*P>(=kdKCaK)b&2IcmX(*Dw|>?qZK)cgNy z^n5)5aN=9?k<5qdg#J$m{H)kHyt)&KAN_*xLCzh|lJ>6!obqB0ypY$swnP3#!KIP! zum1o%N)O!Yi%idXBmUt9fYW$Qd-4r{t31TB!G8Z|NMgBPe}a3+XY^~%=j-F zaU(Al_{j${pY=Sx6>y~oPVh)|{gZuP68NWh9(DbVAO5n?Z}?{lfRjAmN8;Eu-`*na z6K`WK-6HaEzppT!gzTr<4|Au6KZWI1`$;YWuIx{V6F4a2z1LTn&WlF8{c*sFo`l3v zGglLdX9;}D@H=JxkI*CW1N!_`0G#+^uDidJ_WO>pKj*7L&ky|@;R*jq0#0}?KZE(H z{huFH?P2FgzK@=l%K|U_JoDjpL3y9AF`f$&KbGL>Oe_FSa&;Mcl>WR!^yJS;`+eWf znBOAsw+sBN_<0^A_`m7vjOX09Fdn8hk@zvdiJxbsUa02h!=?Scukws*d%G&|2^-ES4!(~zslgNqEqfxn~ly&bGg@u*V|kd zJr!F{c_>vIr4CVbxLWHv?ar{~R;gBNo?h8#H%||1o9Qr{2D2qKU2T+Wy^2%pmCH`2 zv(~FEJDpywI}Cj)bGp=S%&#_k-Q(3xr`lMb?{u8DV$`rvc%Lpc)szhTAl=z$o<7uT zmtvu}>eYsBJOuMxyVp3;t~l)>?PlAJ^`hfchBV9eI?h6~*6a<#XJs&=UafM-S?#SK zggBoXg4s%zR-5ha{2HWWSkr0ZR=%-W?NnE5&ajEhZaVGNW~bWS9)>r&>NLt5^-}xP zQggmhs%>|wVdSz%Q}&U?69?xPZF|YKtkhDI*^;lfYH2Vjw^X#TFo{#s3(bm?qXj$s z(?hA;X3Un*2Yp-46foW`kD`HSLyd!&=klzMumF~w7N*E)r>wP7w^Ylu+s$^aQEv7c z077;!<}4bkmTS3aZDj=+XDvJHRV?J~qrFut3tgo9&~P55R*geGrnRNul*oKB+W z+*a9X(fV6yml~Z~soQLiibstA%6Fbr^r#=FW=R!yOYLs2<fYcN$e5Wak|b{H$A;kYE){@jSXiDTR|5h zpn15|>?$SR$Sog(SXgOSdFC5y&D=7@=%nT;r#;^}+-s--WvU9&Pw`k8EwPZf@+mAF%ToVx z+6N)VRRujjpevA3{>5+Bwm38e>vpS+E8cHmbEsI|7FY z*kGQd(xji~J4@KCXisi5yBkg$GTD!$IbtzcDzk-B7ka8O-6++aepU|CFjKCT+NDf| z#m+hi4Odw#)mJN}{No|HDXU&Og?+GIhxjj68&09rhH1c3on&+D5Hw^icVmsjzdLK& z%7n90tEEo0Y(wFJ_I$b6wXE_+scm=LrE0g6FXxIS{0D!g?Oaf4?+uayTf@~SDZTf& zL?rDoE~WM!mx!c2#wBa-afwLUV_cfqdt4%t_86Cvdyh**(r$5SHMg4sX6(B~`!4z{x^27KXw^z(Cof)-!Nz5BkPV)+t%(`oWRP#>7MHTNz24|4D?Vi}Hp{2%RY9~BoRRN>vKV(%*On~C9Mv@|i||C;1!XbrsIDzpj5(@nRu#DD{e1~ReS=kl7z%2@aj+Yn2xHuq~3`+sH-GYyE;=>Ul7SdyqA?u zZ2GQ}c*Lde>d*9;f(+mIUY3tt9@SNns@)yc1Y|Ml#$v>K1G*I1Rmr-NG>$7LSCGc= ztVhLTMG-XUJ}7h@MAJIkak_L}mRpSzvL^Jr|NXh}zXmdkCf z*egl9IB&05_Dag$U+uI@Y`hh_bN2EoQo|i5Un_Q}Tcv6{f2>x^fi8UE)X)>-X13Z|XME_0WiryS=E^sMEYFm4dk-_*ZOUw| z*cb$lBXSVFT>osRw`$j^pwm!Njwum|UmO7S0ce^Rpbtw$6xb-{d^`XNp4><>RrV&g z1Phs~hu*{&)WQ?d$0DmZiX>l;$3`!y zFk40;4V;jOUDHA8N3G6~DWM$HdLvgjR`$^}I!Tzj6DBPlC&yUwDOx)y7lJf8djl(4 zFNGU0=5ESrRh_bPy4rD&ch|r{s8{aVsD(0vdNVaAe*>un2-YDxe*;yZAT=|q6_BUn zSlb|dPtT9S75x37)`=A#i&r)pb9Qv`qfu+ujLu{fjXCa(7b;q*+~O=&K`Ob{Y@^6m z#igDqvH7M{st!qkwSjd*c23wap=>S=Wl}07SPm(@;cVqP`Ey4_$l2+s{V$RsszmbI`_ILnW28QOU^J@=7aFeVe>bU0SI&HSj8- z{9&F2Ml*db*Q#qd; z`8D$B%X+Y4#OB|pr@}FrGgSeH%3|e;$hr+Ee>fMk>44vl`Twrc(B{RGxQfM?1&gvpe{Zd07W=!RYvFA(bZ~qJ0r` zrfs0YHq&Z1TiT%Y)=^-P127V@I%A8rjK`ppM4pXlaMWERQngL(dja!$-nT~J>>w2h z(2zBP7M@6gMsHsqi{Ke!-4Y#Q@?#8&Ci24!Ubkowpy|ry;Kz4Q=#xtYM;x4%$YSee zX_e!YvWA+e*Np2HGXiNDRzASG%ZxX!EB-DsVA6J1X@;+)W8^L~Uvd3bdvCz8U5a~; z^f7&maqorhG6Pnp@Bf#!3$j?QlJ+zsZAJ|A8dId>UL_3|X*vH7zSz$;QK?l`TMgAl zjr1R6+D`+G@yHoKoE<2r_07Yb%Ws&!~2*DqExE`gkiqA1=Y= z5pP!Xk*yx#)qogi4_APfHT)FjC;5Su!;eb&rr}_~3{#0<9#h($%`d3;6zJFiKRFz< zG&^M4s%pN}!;(#TLHg=uIdpZSg=nNJm9a*+%fl-^R&H#R2V;ztG0vc_$e6qpG`cKK zaJff|X!v^YNJz%CKQ`-XV1Cwu>P|1DR4IN2++6BpPOPnvlZ+NETxW}=JGOIMtv1v; zs@>=GqSP2?42;0WADT7X6}G7UU6k&V2SYZhwQ8fn8x{40`h7D?sL?%-;@afnBO-H4 z$EcPzCM(&2bK6lh1L12-+H-lSn2r@`mvI4_waG;wdNGw+=+%2D=3m{!s{s6bfw-Pg zl>P?Xin=cjzzLi_xGis?(Eb8s5k02x+=Db)qK6&)J{8$kXYx{lADV>f9{?5h14}Z9@CQv5an(BZ>em1IJ5Tc%H$EUt9xNmZ7G5_sJE;AM+W zuCi*(mo`AsrAkGujnNCdyBLN09?Dv+A4}amepXv#MCK0qW`1~RkI=&p)v|tWA&X^+ z$A<234k>#col(SI-0E0#cOq1} zs!jWiUAxO0NIFMB10DH|^gafj8PXRe#Bb~v6IhFw;Lgp}?#7OB&EQ?C9blSe0>-r< z)mtJoA4R8uCw-uaG7B5cY8f{`qJQ)@r1*e%b{K$)XlWp4OopgRmNN8tio2Bc&Mk7^E%W_2tKB=Xr<}# z8H@-nchaPrxOH8(>D4O+cf~d`aCCh>rvZxSFA@X>6xdy*QxApQ6~@6(4MK2Gj&W-Tsa)jVb~tu^)5}beIgwqvU56V zYhTM1W9{&6cZtEnJKhyG>$Avo+u=7d8U>2+rT6B>In*Lzh@!}}DJpVmnSMWYB=G!% zVe?Oa7(5AtZjn-Hb&GVOU0o-Cf`^gqy`5tjI+7GW@2NeW`Nr{5x!oKvAi58rLnirx ztQ3NRJM$ejhr=JSRcZOoiK!&N`pBL#jmu|h%O@GQ2J!4;ccE75bjabUk*lMd|0PvD zRr*7X6Mnt$tC7=dcq=n>567Rnk0Dw~-0;YQh~l9bU6kNzHF@uLkio$R2EGwAZ46|Z z210K$7SscZ)-0w7@q+YDv(Tnl;+|8yW4wAVHP`7@p{VL0!Q+isX5}!Z11ygI zE&xXhee@mqLs@@AzH?b2vt+Tv9LH0U?XjX_H*-i@Xu#;~Vk<(>tJ}eVoh2m!$m%k1 zsQ(O}Y~_1n8sS`@^~Yt}n^os@RM0BC1DY~DKa|H{Ol|--9M=&aA>V1>M^WD(^<>aD z{Z-;=j4$xo=4pyPIE`xqk1~VNQ8O9Mr3mCcwDGxg+M~t&Xc(8GzVW!ErQVvZRae`k z_BL{X)V&XSf^5-01KzR0?cA-%MCMM4*5@-f1HJpKK003Qc84i75zpOL^gHodnkw!@ zY5viZz}SWK?HJT15)0|h&2>K7R?2^6;<{S3UQ}-%=Qfd1reBXH?|n+S6niao=~jW% zsYlqW>b>^h3Z9jVF{*cAgpX)x3O!bx;VZQCJkI}=E~$pgBvX( z^OTY!yeJ6#fS84>iYUqDR{hCX(2oc>w&fC4J;0V9{Ja^b82VFFU6n!yC+xWH&FaFm znh)GDYiUA*wdy)w-^$p%tM`fEapifEkw)g^$Xdzd^|%gW#WdU7*gUAIKN}ZWnPzA{ zC29^1%|{E5EwZfKv>j-)0?m6WPl`w07|)$hAcAO1)e~DLH+xIH#%@;9iN$6#r?{=# zSq_fcV2%*t65RpOzad!^syKK+XyFYAsdiXCy~cVE+X1fbYj`pnk6v?T^6==Y5QUzg zBcBQ6P#AU~bZXkh!}sAV>pe@6o*Br}7|~~=^CvP5y?8JfS_Wc94AL?M7jokUX8C8T zh8YV-`Glih7D7=kdyXdG%q4AP*SF#o3W&?8VO+wT;eX44kU*u7_5dk9)>t+&;ZGqc zIZhFU3Gybym_0y8S`k?CFAbuJv&?*=?GN>WnKf>1!V=Q{w{k=<(Ml_F8@72cyjZ_iA?TaIJ}8_{O?5 zOVOa!#*MX>jxQa0T@ZZ8#LS@^=?NCfXPrY_JI?7nPD~j6`pH{DdyFu5m(zA&$ggKj zi$hg>gjTZJAwMh?JP7$f+4AtbIaaz;MrvOrS99uA@pn8Uk@k`_JVfFthDezHBO^b; znh`g2AovyG(d2{DMw~nJes&+O_+auLbxJVac61LA3ZV^|i)>w=KoTT(HzuQo4r$Ic zWmRl&JYzPMWfM>QcgS@Si4an=$QIpLy_d z?pfxUwCy?O!5_V6nP<|r=a`2?{XNS(leXPso+@DE@nJkQvnv{JB9!eO!J;pneHiLOqrrJ>nBI{0@1L$B62g3y{&slX8B?)RydybO&#dZ$1 zz53fWihk_bxiD!n8SM*dL~LHKvr$wB4}bb8?0@-D*}X>iMx@i!@6xg|ZI!6(v~}nR ztaQ4;3S@aBG9rBQ4pr*+JPmMH?5q>*0t_%C5F=A+*S6K+0)Y==#Uprz`61${{l~lG zQLrpz@8zjv3kBGQu3cmVDQYE|>3&yXXnjqi-Jk|ne^H^3*PdNeCT-@T3Tdx&np4$p zY&cuE_(RYZM5k6=-{`to_8}dZnpUUqUdwHwC(KJqN40s|*(y6KaocWn+f>BG_hab1 z-{13`Lg+cw6QDCYGKqcNDo#1dTa!IG#KCu%#EIlaR$H99;dBmebBwjp zm^#n`l=@Y<+GbqLj+?;CG)Q4@cqu9e9)dcD(Vro>oHJ^Or#>Smm`uF zqZ=Yl&fE-T@-p)+BqnT8DVF1Dy7miIFRl_|0C0tdsHr;%KP6bd7t*(h9RF4=Ir!gy$cd@>9BNJLJ|Sc6z! z8|;X<_sQ_R&-|*s_JPn>JPBosJ>t9YeGz?F=fr+}t5j%W{*R%WlgCiKeR187c4yEH zl$(?ogB}^jvQrbx!EyBOHuT}pdoOERjyMN<$Z2re=t=FUzP%&bM4-)rqk9lNp{sBi zQ)C&UsF7Rd@;0~m;K7UHV5y*{BBWnD45H{OFn7qrM7bJNV?bw~UXjCEuu-l}!wof> z^<$z65gnqtfAUS=67M+_)H6AfQRk0NuZGa(R=0;oTSEQ&BJL+^#iavBTz4`I3Gl>Q znC3J7tm$^IvCwPNYn*g7HZivN`cQNk)^9L{;RO9wKl;?A1T@>4%fnd0Tq%2rYoSs2 z`gFxvD}mW~tAl(fc_fF1Y#4ujqc!8I)B^phg6RpGtPxC!x~=MWSk?xfZ@^Zx{tc}W zQ~CYDjrE^@hQb4giARl09=ch;O)7%adgIn@Q7C2@KT=@y#1*?GN< zEj!3PpzUnHSmPWiS!Edn5peXIcr5%;DYP4=-(4g@0|sdchnK*M(dKjn1g=yOP7Y+TgfjVzg&&9cA|?OS8LYPg4{wb_cEqOK0Y>(obbC z@ojR(T#QHO7}7^5x{p#@9 zSug&kFNs-2;R;GGj7c16;308S85}r~zJbb_?4Tn)drqQpHdwOm>G29$=+0Ox+yTW$X`wNzJi8^Ur+TkNQhwzK(4TIWXf1=JK&XDlIeg3Up@9 zfuAR%=WAPm&u7$vVBfa#aIzUT%-bEn5pA3s2iuVF22ccY+_inI~@G z*r#dC>a1-{&JvvYLB@oYd0;)v(2OIhR^7Kza4w7Fz+hX0sYyk>6917%H&+cklMr`I zIiIsTYU`eni*s{WA~KN|YvI7&QIPmHULh!5?A7ZigtDOCJ#`b>L-$XV<&Mq5>UaNS zuzM^OWSj`1LnE}|qh@ge#}hJPCKOO{sf`Q*-Je5lVAOh2SC=Ga!_0`Fnsn_u zwe!1mEfin0Pn&)ieGTA=^g+(L)C{{^4&(KV8eHDZHVT(iP+uIbrJ!YC?)3qsozdI0 zq27YSF;N(LWTd@bpDVQ~Fn1bRJ#=|LrWBgADaymQ)zlsDDPFKa=u`X1;)#Rvi?+Rl ztuL@<=&fgU>m7w>1bH8ZN6YH0gF=3Y-B@ZK!dvH6yeZ;nhM8wGBYJ}N0CQm0nksEa z7-D>_gx3w;V5apA#Yoq{7Ohi}Z)(NMEMHJMMx)eRlepUWYNq z1OJ(N2quHeXR6f`>NKq)CTO^-tML|~Ig;?Eu1>D9H7}#e@_79OPue)Dhc|nAy*K1t z3egixrY0Ap)Clb)k7=d&`Z#`Hlw09n@f0%IA73! z6}xx@<$H#{Y=3Q1?lN8sxv=w5-zdQcUq;zQ5&x(Mh2W6~cv?4HT3w?CgB6+k}k-mPFKPiyo4K`tDV@ zRiJMzqboN-p`(0O%U0F;_~|oj6(UEY(*lC3>HHM8kb`$Aga|Vk9$MkuV+uuFk22!fLKLGlYl+leK@_qKG{t zzSI#9O8JTWoCb5s#p}dv8_ovMze<;D zRdx^s&UG0fM;~Z~YWmI8aGg#520E1F za>G3^sw{St2PWHTw!7qppj!a=30$wf-?;&}j|Oy02TnaQU7k%MUHC$6+nPoG!+fo# zP#4jM_WHRUM8{Oj(dB{qh%SISCmK2{T`mK>Zkab(w>{I}rx~MFo+jl5=bHo*8D1Ar z-a#W07Q@$Q%`e>fx8Pg!lGm9xRFT!?lDK<~d$JLOju3(8-4Emb$=R}Td0Fjt^5xvj zrYb{MuKK)e#qLbSxxJ@ir{`?sM&K#t8ojcBWl?l)4~A45_#js#VPwaKq6!FzsDhbL zRDn-GyVI>wwVkgODel50JKO24qK-D6_8ERdP*!l!oq#H* z)<3(s#nmJxB7?X=Vbe@n%q@b}p&P~NUnQEW)>EM+jRxAA@e?!%NK%&#g0 z5J&usEYQ~eB&kJuZ^9LeyZngV#psD?nWe{+a1yBHvYE53FRCRgp#$G%g=4-giX?Eh ztUSV}P!NG~O^A|} zV$61Z@C6F64?-Aj*axGTFFOcnWZOP?{gDiVaE97xe7jQvCP2zAcA-b1lQ@E*QAvcI z>)a8)RK#mN1h@Cbd|*`Of5VQ*% z^1PwDFtr}?U7&o-xz&E}T^Q~TDcUCvbEQn%3rs+#7S39^sy7 zbe`||AzkrV8s#4Mit~FE;;uO7#*}XyG2qXQ6IXb}*}dx{y5e&*QVh%$=l4j|U2)!x zDGeh8X^40L6`7x6(ZA%SoNKY*Z`6)1_quX`nCzl~==0&4!JbM}*-ZSfi)PqS{G%TX)gQ zF4*(-ioIYT#eZ{l5&u=cSuzGOUE=IL4)?I=;%70H41a7zemxWXdcfyd_2jS7dGPa8 zvTyIHxfq{k`+lCD9sYTGjz0HCY^7|w+qAd9S`;AiN20}!)Iu!Kid{HdEvzK%df^xn zKMPjcwl_;Qg$vr<(t56r$gMlf*s8g;TB%!Wu6L|ylm%#_sNgmS3+V!p%cVf59ui7d z5zglzTF^1?@>Y!x$*S4FRCttevl*nlCV`P*9GwM)Y;}p!!rw zeN%W#p5w?9UhE7m{q;m)^bJ{8$6)|LKO^)55dQjBDM{a;ZYi1MGvYKt1 z#Qk)sUCG}@F@uc`%3j-uQ!6{DRp4bq2fj^N1L(~h#yaV2p^B0P>jM81 zvbPQ@D6%rFV^_gtK`1}LoYy;|<^l?e5f^LCW{a4ZD>e~W2}Oz+*JUHjy6o34ad5jr zNMWy?iK3oive(wTRjM>US>#zp?o$}O$#x)8-|Ljtq1`9Qaaj|Uc6Ad)_MtW=id~pq zZnhmf@Lt(9O^@h>$16uVm+HqdpB^m@G=&y`-$RC^4e)t%gu@6 zl^MLFv^rsC2x6H16JCqyZnqA_XQQwcUM`s=Gv;^b~I>T(4?`pt50AG#V8=m7Sm(a7*A zQdUV^g>Im=#& z`Bn?ZJ`3ZfgP}zYDYAXJbUK$y;|F!3w8B(w8Y`kSEsM~0&BwCAm!{)VbHxl5Z=s5q|CWXwgjqdr%MKnEv6Du_1$D>{{I_PTi1 zNMUR^HO3#C$XLUd9>_g4S(`DXPzp0*(=3b)9s3|_rHXm#d%WHWLe154gzd_W$`W3M zQ=(a`piW_30pKZ$|7DuKTx~YHV}9Bm|5G}P>0V=w)LkQnfTmoPi1j~AGL3I#dnL23 zjKwzkp%z^tVNMQ;yuxg_mBKr;w{-i@&kQ{@*@h^zQ3jPxBA8t@M|6Bp5KQlpn|6qx zFT2CtYnI3AaZ#Ob{3I(#e3JVkh(oe`tw|olCX{0)J|ChZUy#vAK|Q6Cw1-eV7=xaw z{%qUb@AU}!vMr)}&9}ba%!+U-mtax7Y~WUI9>i=s8molb{SJ-+2uYT754#Kajf>-@ z@(`x?!8B)L$`{5%G~+|G-6(I2hh^Hsvgnj3v$ek%^chhf-i(YVnlmG#iQvn~IKo`% zD`=5S877{oOv5?7P^#4qqQI)qbqzNfYrYB<{qS&6Xdq&J zxJ%Tggj()obTWmvhoEkK%pLDV&gC`KKkz+P+K)4+-O%nh)Fqovff_QI5N2Eq;-|$5r;g-&@%szfXFJ$UyuV*epW z>27{MbOb}Mko#fqUvrH(g1Da!>AE|{)wy&%^wWM_yQ0@oPrHmb@DaZ5LqK-D+GPjS zh+WIT)fLMwecFd)%e>AVvHMXzcS-QPZn!~?z8#(^@8hK*ICt>L4E(vkup^GP7 zuZBFx(i|El;||7{(%@a>h}?|-alh`pfTAIxU;PkxaWBK-zxrVqF$k<5nyAo_5!oqo zsX_*J>C=AHd-E_Pu&WOO_u_dpx?_FTr%TIsEj?PVzJS9aQG5NmmYKr+$naYtW5LD! zv|raTBmeq+E)zXG=+H&rYCmfZ*8q#orc*oIZq_B7bC9oLl6uPRqTgA2BBk4Mr47fa)v}Z_UqnL{lh{Y zT@0=)XZu=qR=`RMxTbc)yz?mPf5GkF<6~dL?h4`vM)oH=c+ibS_(=GpcHGJL;@^}f zkKI^8lkdRiD49HR;Z6L|yOHMCQxMptV-b&AC~rR*5ZXLC=8*^wDyE52J_hO$Ngp{h zaU}dcn=KY!MnUeK$>YWV#n6$XAsvZa_sBR&az{cs3b~&1DAvTqT#6%NjUX5{>Co`f zU?9_#4knyr?_)Ax)(sviBbf~^5ZA7FNae&y7>^Y=?Te%43X8#{I(CO`9BPJza-s(P zpkPuzd6SMJomAK34t+=*?QRZzQeC@4_qMDUiqEHAuduXFtmp9t?)ME{aZTs9adyUb zckm;w^&wJc%~0HsN(F1_1=#GV!(6E_IQ4W;otV_eAG~J z7mv4g`yZO2j412UAB{dqd&?RZzdMMaFhs|!5r2NFhV!g|n zSm^!qP8@yobd1(bs=hT_1rw^Zjx~e86XY0nSDNhZ%~uz1OXe2K>6Ef2#t0EahKK)| zqbt^#J4r$LwPJ_W_d_sJY`u#lj;Mq%$C}5O2QOWtds!3=rLXIwa=EM&ZM!;p z7j;1R$tw)deaQ*56rumiT??<70ge~I@DfzFsUGt}KN}!a{d);dVOgm9fh^KCr7GF< z8%lqoU!;=uA!n`Bt9AL874=*Ft3n(3lXlyoFYH#cRxNL^k%T;-@|J=_La* zQat7-PdOS$(+Fj?lHRW=Qc_2q`*lp*SKw&%&Qe*fc^m)Z&hxasn~eq*FiJyd0{TXI z_PrlnNO4&o)XqViW!fMAX_0W@eZenM)5kt4_`lF zUig0*;)Cy(GpdBom{YlYtQwpmAL6m)V^@%}(BZ#>upqm_R;$RpiJa@c2rTOUIM+ZJ@l#A=qq5|jb|q@Go)zid=S;d^tD0OO zok=w`J#DFy6Wig1!0;U}1V)oeI%;-`)p`$!Qc%sXo3M=>b2IyV)54z&SUcQ6R)C=n z)x^3O2L5s)YLGVqU$2&$(xHk&3sd-eHK*S9qs}QdCr=GABQ#01QKd{i7mD=flb~qK z73(KxtQ9K=;;-27{HXaYy6R#(?uzHGGn{c_Ze4x>Qtb9R7?s_$K}k)Az^e8adkF74 zf!~HU9{+Fg7@AXRn*;E-z|u7qp7Go9R$g$+ng~j4EW3c!_jEb0#fi{LOhYA->BZ{$ zMi(hwU1w#x`l)r6SgezXdNWe-r2Sp-r-Q7@gArbRAGn z(837k(0UO?scLZ=mp3EX>yzYg2UePTaOY!S+YFi>FKxvkMK!H9;xwg~;wcM1Zrftl zX~k|^y(1Q0;ao^u2C~DN2IW2h8`zlG9EWO}aO5)fVv+4O&K1hbxAj*8Sy?08t!>KfQIs|kp!?>!!~YQ39A zcQ5|O03%ZDpAC{MoTD>=I4Htr0{O-0w0e^vC_K-d-%F-@JVw_nZkhHm9HfD39; zK=DK(B`sq}1Cgjy++YDlz)T&rjU1n^GwgNAM}c zqoQ_P^2*_~Attr|hCQNnic22ugog0KoB+}YQmd13g#~7D=Q#TjYC0>z-QE@zc@Wi1 z-!q08t;jd=L{MZ|kO?givGxc#VC_sg!vr%SRE_?4XI&E#iVFxZL3szf4JUXu)*8b5 z{jepTB6B666e2N>s5i)N^|VwZ#u2nwil$4`Na{5b;b;nYOfN=oDhBx{^rdy+3w>2O zo|;oiHBjN+yDHlwj)+vs3+A*DJKD8->SUb10mflBWwoj(7JjoKvNwsRH;(Q zuPrrmTX@`1d9>|55*XHQerb>YRT@2x+ELr7H#c{DZ?Q+#(BO9$A^UsJ#}}7mSJL(f zt7oCD%FWicdJc1`c!Z+dmz^He6JD=GMeJr-y>t#(J97 zGOQ!ANU0Y=6d{ew9;jd=eQ^w(74&8px<2^T zoO@R0TsSxkSGU&Cq>24GLdCjmqJ9}8u*0%M z7$ZDjL26{T-+|jXg8XQcDA=)HdsxCdS$iV)&`UeOB219Y*T0T;z?VqDm!(d-vhGG? zzPODWxOx!}tUJLpwv_)j(VPu5!7Upe1ls5|PEjDNkr)n<*>pP8C%O9@ZSu!i@^BPMm0ZVr!Eqh%;$cMuO#_<5!x($O%gj z`PxskC;^Qo38`>}O*8g8AV_otZMHw=UC)GNLGOrzq;qJ0ZoIghv$ zEpO^Li||E=f90s=OU=eXcxg^im4fgss=xUxW`c642NG$e@QNYjTrQQ?DJR@a<_j>= zqNIk!ChFcDZFc&kEJTcwVs!HKUgjDK9w2DKpWB$Uv+l3dX~#=!bPrzsL0NQr<9)Fc zVP8>s#X7K&=*}?6N|n|?ZEnjc_f)Pn_+6?Yw7Arvv~gccXy%{<2!=?FEx!vLJT=@* z*b;c;Syp~$rB0Wsl-RJ04C(D?T4s@~zeumpM^b88l3#te*C^+7aS=6(n@7W%?(!+C@8%r^sJh?2QX(u%^%0l^-|(1(YRFBa!R zwMdRv%k5@ogyu9|;pXLbcMb2h)l1!t{pAGol}$h58Mp360>A5Yduw>FFi~;Z&N^+z zZM$2yv2!;ZEEc=cwAX9RRa9T8pomGwF7>t&6hei!oSn-4WONG~vAtEh)NYryZRGd2 zw-al4vDmRIy?T8cpZI>l(~WqH$KSNMwx*sW5xP2*W4C}j<&F|%RThl@wE-ivS4D&e z-eRj&Yg_dihOypmo}TY^6ZP%7a)#p{aGsFkG=YcHu)%^s(7dW0uG7`u0>X%IIlhP| zuiN-&t?f7o(5}ki?6<(48h(i{{8#??J*tR;Pv~p4w+41}TJ3N%03$vok9%esB=bKi zRlG{nksq+2z^22?^T%^`Zt0M1Cu}Jra^mpeVh%5v%^zIM0ea|hOY_I`3ut^~=|($u zRK7WSXqgn9S)7P#s?mQNn|MqeVt~C1PvhpOG449kcCm%ag&x*)#cp-mm>jNgvoy0% zLK32tSwY0v0tjDeuwe9sr&n|CmSt%PE&M94C2L-dp zGlvdWZW6386HDz8$YTEBf}Pr*-akzv zEDC|M!X!1YV=}TN-P+K`&Ekju;*q*^$EU6olVVIufPq%}ASSS);uV*jwR{Cv(!=M3 zy2=Z+*&-$u>l@5cyz|r7$rUXd|I5)(+!?geS}rI?tD}CGSKDm%I5yxd5&$*!(GMco zRuAQwRv~SRRTf+N21GTuG$Z|jic|5gQZ#v3K|FU$#c3*FMLEs{SJ9c~Z;a_) zLTMh$5*a7FaBj7X+gJl+f7(M#33z(!-U#5BUzWvyr{9umKIWdR=Ls#(~G4$ zwn;xAD}_!W)bULd=W&oHF}OiwKtcxS;n5dRoLNxA7x_++WdltFF*c;gW@Vh)#L8M! z$9AVp0*0BU$?zQtcvbQY&e1)=;ac-_W}#W@)f+?){3! zDr|52RUnB7ZNMKeKD8UY#vnudkd_rTVDe9{wmLQ!h2} zNEL*s*v;DWjcuDA%YkI!foBSaIL^Pe>9ufG8i&T9*(x1&<{-!TCCr}8&DAbq#g?6# z{B90P3^nCfy`*;^6N1WD_9$%=jCTT7#h9?k^ws*%;E*%FQeO2aDm6$uTIt{>hfktL zokbB!o^Z>e8Ph)?&g!-v)~u3+F}GUkFXr6O*aykzq>Oq}4@0Nlt=5=D#0*QG(j?yO zpD1(py8NBKsI3)g2XtjC+v%;+ajCqK_uI9okJ)IpVflMee7J$2MQ+8dokzk+>hKU< z3e!K1;2&5B$5ED&LwTwVvRe^lSc9k@re-LRfepHVro}vdRzZW_#PX(1YLs=)EKWSC z$dk`phBc~oy)^s^tbDK}V24!8cD31wD)5noHkS1n{aIP<_Bx4Q+U=x*YB6IF$0K~;wHD;;AIC6%G)C65eV3EJF= zvTD*a+gJ=*BWY_V6=Bp=e5?*=!L`jCx$CG%uy!}BCB!phLlL9ExYO-GZYx}B)IBPs z_Rsim1_!Bk7et#@DDwhyQ_4fP!Gt_+yM{5H$thSBzsPNBdB6_XG^a=HF~Qn-)}+## zFb3~9kUZivxaw)g%DDg5M?`9>Pe#_PHZo+NDbc#NEg0F2PP673vLryd0>m5SkauTEjMo!~Gf#ektoPemJOpIM}P!;4@J>yV_?CS-hCc zL$~|n2;Z-_0VNV%t&ncARC3WM{i5kbu2%tw|IrN${6MGra07FIqO0NloTKgu&S7;Gkz! zbrgtXq9m}LB<~UVLRd1@tbcCIC@)q-bF#5E75JEu#im;(*rSL6Z5hs9@iG0`BxB3;W4Hz0{<>07XUg?hc5sE zy9+5J*UuQXo?NU!vb;dE@kE>g*?<}{F#*ZUBZGZ4Y@z1!nfgM+N7OM^R1L4$4W;djOZbc4NJ9z#aS6j`-3@qMt z<SQka0j})Y+CH z%DiU}pnG7CyTRs`SCqp;)@2%lay{f?)p?G`!ZBe$(EUiB%*YeF@^Rv{?z;(#@))2Q z-j48{<73!`eSJQA-_x%I3n5{i1cZ)y){MGPE8?yg>Uz0(T8Zo!lN>*1?ymRhA0~0gRNA#2r`f$c*lLM z0tsdGUK;(`ln~gU)>O{YWjtI|K%UrAF$Z;_Gn~m~!j&CxBU;`n*{d)~8#cI8-Z-#u z%PsQ<^R~4=oglA~Yt5w7Bn8-=ES!wtd~ztMTxqOgl*JppQ?SBd^|s@~ehkAZ!Z8tP zT(LwM>Mf+nl1h^)?s*p?S{(&$>@2*HEw^#G1`f|!kCQR(yQ3qHM%X0b!b!db*k|iE zOi0uHqR%x#t;rV)&qLr^e1RfBEBr9+nClpn9=Si9X)9yye&OX?a*jT(Nh@pf%hlcO2CAKd^{JZX2U@u^$R@kij z*315^f0{xkYzd@@w4rnal zBSHah@W!#{<+{+@k;(k+V5&J*Mc*3_*c@RxnD(sp3)8P?DUkz%MS|Sy!TS>^Mv{{( z$%**-Sor6}ej9W@q|fHET!M#@H597RVKG`n1K#Cv)V=4B#=>LU6KIT;5SWTlD)JHX$vuK5slL!m%8Ow;RRN)~MhoYm8 zV#rH>aoOoLg14;aa6!|d%fvCYBdSk$$hoX^^Oj9l8#GEoh>|#K;#6Y?9P8u<9;Y87Ti;6bi8@o~Mv5#* zRho3o%@&J!qQzyJqp#6v8qD8|Xiv)lRqhe=oD4mw;g}YVT_fg*ezqcfkkh9(P$Wtj z-7$8yfKD*O$;M%AEd3tCA?-gmk9iv$Tol?5i;p)cJWO_f^dH7YFEtOqln9`x6@T{GgajtLNjs|T%Gb;%4^x}i~Brp@W(Fuws zv_5$&RH!2z(AYZ=u&HU5id_WX^nGKlzd$3(HfgVrS$Kk?M6ycJ(vBiwI@w04(d^V5 zRo4DCx_hcN%iWq`(}B6uwv8vynx}0PXSJJa@>1nmy^AZrJN)Wle+m($bR;s^tk9K##*`h)dR}X~K<+Ll>|}pAz131Za>`dn0y3s~5#k~4DHXn7ds zf1`+<(OoHc&R!YH^yI5P3;3Kirc)&)`L5Vn8WnJh+}&Iu9Uj&q99+zG)7>%-W&Vpe z)E*&qaS%izRtQl>_+N0<_<9&I$_X3Ps8LQnX02>A=4`_mrcbjzKH_}0-8tTbBsJTX zg&0HRDy-1K0l^cngY^5T@`Q7xjj%#wNl!R^L4w#E*u*C)Dw zwXHRUScCpB$&|b-d}E`7^@BVtju}yQEe;+*yHS}TVI=gNBBw7XXHltL)71%d!UnuZ zIs%lXZ5Wfs1DzxiP8sz(ACY@#~poQ(Ag>F z%~hpEUH(MeK$5t*mxifK9_bzAddoF>b!CR3Ds?DacvdRqVg$F{b{mB~5fXjYn$08i z0MTMTK_0OG^@${*I~dnLstkCX3wgn0m3LG`-7c#LmsK1YC7Xnjb%Hu^5^g2KaYR}; z11%hBv?=FIEVB)XBUC;}hxkEx>)p<$$78EyB8qOF6jAzqm~-R;mm)JaBhZcF)nzG* zAdbFi(gkB$IoO;AT`q1qnT3rey$peSfp(+Z+BTP+EQ6FpF)PQMyAJ$|gQprUOr)-L zauwx+h)gdtkF!wXi7wuoK-9O<`OY_paV90!QQ5DdL(Cz*MtXf*WZ8cz?P_WD# z_EdV+8gDdLH{ttTcRG51@}0S}Hf28H*F!?Da}>ag)B&-{WD>)7YkDV=`!T)$D+APj zp+Cc~*3KhKu&y7h4KCR_WVzmVdEqz1&qQ_h|I3NU)lM#Zrzy}A1zI@vT%9&ac09j} z+tTMtNI@GqTk=hGhCsh*!ByNIuo}f=v`Z?(4T-~5^LVQ_k-%Om$uUh56rJ;u!vUEt z4~b<125lu<&C^bsmb$|>y>}qV!SciDhR%b>$A10J4a%-lW+K8Lp?jKrH4iyR^_Hd$ zeG%wBzUdgjxLVQ~QGj!?q8&6LgV>l>)^HmJ99dz3iyYs!;imv5RUlDoj`Arf14x~8 zD27k>>;Fp9p(5xG_+f%W4xZp}HdbNvK2?KkfzgsZ5X?!p*RFA|PtwCvn))#jdNGB< zDV!2drm;Q((`~|u2HDe-JhjnvlUHXFS5MJJA@PgIOZUK<3LKke`Pj4o2UKHQ?V!0; zH>Ftxo_p@e2uQ>x^Mn z?Q)yNNKyl3TJPK5F3OoS;(!|6Y9rUD`kx#D^)*A_G@DVg$}v+eAKV?0_fGv|&>5%# zK;oqSjS?uw+Cbu2#?Jl|c3X#$C`j>{6%`PtBkN>NG&{!M4OBY8A(cI-QZEC#TC|h) zboe6A=T!dFViU(4;_SW;`hfRE0El#C_ln}Q=Cmr%_LM9F}tjtg7F75G&dd|lcI7clta{)h75oA zuylW17f}8mBJfeun`(5}NCk!`wMI&mtHv8g6;Yr5DofK`x+($x87d!zj5ZPNWK_bh zY}Kw8AZVYY`{gwI&hHT+eRMeI5(EAM2`WDa;GiSQ+y~;`TgFh+5bI&7MltRodAIVj zTWeioxz4bk2yRREOM2;FxTW?M=o-jc3kZGqu;dR!)W(#DLGLetGcm1Ue^3)oy7uQ>r7#TkeE5jm_pfqaEa;-=YQ{ zqR?;Sv;GL|HRO@^R2|%u!|Owgd2EF1D2YvXoDvbfLo4bGlv?T`jj_VB^^GOP>h)c! zIO9g8wo#QZcvpSzE+gw_4k_cPPJmPjvZ{a{>U%@|o7$q}MYAHI2=ohbm;;X2L~!L_ zLRba=u7b4v&W8L3?m<*>YdZwe1-%H@tbG&^brYZ~aFFp$Y0+$itN+qdXE;iD!sk~7 zs>I|tCS?xQ(0n`4DC zvK{6MQo0~j-=ZoJNN8)dYE{mnz)f1SRKY=uiueSkl(yMW*`XAPOcAbomCK4drd5@) zB>C8&P3fC-Aox@D4VyfaaWIbL`Hu>mm5WZnX`F@OBEmZ+%86-Lx%Q7eXCq33%Ggm7 zvOFGEIJ{ZVYu&F{r5X*;rESG0-$gjqBD_GplOWvNIrXGE{ewhSGj|5eWp*NC3y!=p z)gT((1At(MAQ&C-OA>RC#WVWl{b|t zt+#mJE8}&w+3dh`ugay1&p4G*#bcW-j-#b)A!i*G6J{|Gx>-ksm@;K&xoT!sl3NuY zSP9}ZqiWe`)kxd%@+vkVhoS*TmvwIwp0Qbh_%|u6GfH9S&>agE#Aw;!lNyLnm#L&o zDXC1I;h~=7&>=4hV#~xqK_a#l`+e73dP9g2jOmZEi>R*xB8DAub!W2sNb(sM_ON}s z72B|8vM9Fva0oJvO-ig7rCh~k;d?01iJp<2_W6MsVWX&p5epZVQPo5 zcxYhtTK(bEDZrDSl+g`8C*n3&ncuHI>>FRq>NWM$M|YUB?Ya z7jLUfkSIi7f=O6g29MZg^+tVd9tekU{nGyPt$`=9xFQvRiI4#imvC`KQNudcL(c*1 z66C~EkytBk*uqR3;iDBQo>Q*}X2xF+bdV7kzMtELAWEJ#^$4s)$mmPNqdg9?8NBPO zO+Ro=PpO%lz=@L;9kiB9r#)fj{2^2B2wU2S1(01l9_5*>4peO;Dn2;0$EmyH(zwr1GcSgQzzuM3 zUG0#6b&n=X$IGb7Jw1mTwZtp>_-}DSbJXn41Jj|R1YepBmkjh;; zH&N7u{;gR4Y8O!x7jOhyGdOi3#;oebLk8@e{??!;c6_)C2dIVp)s)iP=Ss%4MuLYP zzU}6EsEPGDc|Ld*A;3&ZylKDcVCSxd>Yr{EA)Pv|PD2rSy;e#yWw{66i)yA=X9RQ7 z)6ux{#M8wpQfg$ao8v1$ni@i{A1|Ost`P%nJ_W8-hUXR7xh>`sQd2KRIYdxV5$41k zV$r!Cm(OSmdPWcd=Xyr)?w$0EZ1*DRTdoy!BKa?f`WeAT+DU7+w-n5*mxypXV(?~ zh!QtR%!2!S|5Y;fxlolGN^&7#l5VF1MnNe{|{kt`4|#~rfj z9^7Z=d)+1oRqXVHPbz>abDob}?*2Bw>0Otl9Y(aN1Ip)}AnkJ8ouPlf68)F1JD4n0c8g%gfiD_o| z7BOr$ilbDor$DoI+bR0zVZ;=SX$J7l?ry8GBZ5;@u$C`i?GkEl*Ex*V{=e+K>2e!a zvNftFa)CD1pTX_G)Cr|WUPx%$tFRofMZ_a!-L3VVZ&Pr{~&geyax*4nbP zdU1SYid6~A7oCoCYz%>-Wa(fd9n?_d!*KF705)7W=_z|h5HNlX63#4fvE1I-)VkcL zj6RgIBU{qcuiBrtuxHiZ4pUZPXVc`2f|rBvp~{~~Mv~+jBqCYjhgO{rO8<`E?{r6a zQdI#@%ia`17?Azq$XXc(@S9&1sVsad9Dsv5cFN@ZsR;0dt} zY+&@m*MfNs&taEA*TA(;N@Nu8XiUv}iEbwKU(pgpvfvr`>|8R3ye=uitv2GcAUX_4 zjRr%-of9-0swTA-xvdAzwOl$YOuepi}Ol73l1C zCW}Qi>!Pw<4z;Q=Zi=)tst!{6Q=+}WZaw3C+>HXQayX`)muEo*inQwOoRN+H|M4h> zw+`b`wtt$%M`0DQvIcAT4w^OF#evgrk(Lgtz1*TwJ6^C!b#UG3=*!2qF=m(~`09f- zrOJN$dW-Jne_6(9L;KPdHBn+qrd=Y7#jd0m~him^q-mt|T>+Jhp2(q;Bi*`L^pDN0ho&uQl zNIBweh3JXmD~2*Sx?u*11~j@Z6fPaXh~Yh{GRE3y`*+ymU_BxmC@LAj$u=oK*b$J$ ztC7^R%c(bkc@BSfcM*RlY%F%E$QyNaL(-R}{PA;fGQ#vvr4xe@jHay@gVFUMk)}YL z;`wYge28NO(ZqPr9S*9vhWNW?o#_Oj&P5YNto*~TN^%T@Z$Yz=zhjg?T>Z}$?bncT zLZ8Rz>L2_+DN&bvx;GCjIgLXoF$xmt^{)ro+74nR-6 z?`qM`)HQ@3Hjg}2n~B~ureohCu|YW>8#^6em)WuwH8vx}YVHx=eAs1pwqH8!#nv4peC_c~Qx7Z`8QpaF4Z0%0W@ z!#92Z6CJePJ5b3c8aL11ilPUSQJkrWXO^AQD%#~&ujK{u7#qhjAB`sfOU6eBV}HP9 zC6hayN3BMn<0K%pq4rbf2|CHc0CYyr8%@@olKEbIi`Gs#dVkZ!lwLRhmVCaB?lS~1 zi-8OQztU%AE1aM%*{K2+h@3E*ay#V7x=HgeKx>U?3VcJT8dY>K>rbj>eef%%(t1riPM&E+SGmH^ifwSK9>sWABaV5Fw?bzsPDtGUC><2)zk7_*nt)Zfoc>zm z6G$znrUp$asFiL!e%A3qb ziuSTCAEmlTVn|gR7upDbwgIojNy3JNa#0mFMbkw74q(bWa@nnVH13iHXTE=ebfv6v z=_(N^h-O`O&+39ZtN;cp`Wf)oi-)lKCLJeTJR>|^!mTS6-X{m=R{@qz1QUxmL*so5 zoKLw`rkgF}2czdLvK4CXm$Cql_$#Lp*o@?8-9*;57 zR@mVuFUQdveWI{N2BZ&r>Md2FPqtB=kvqcGbYQy==DcDx4Et%ZADYMTq1dsYf0rr=VwP|5>qjN4_BM3}5EdiL1owec*zBa3>f1VQ(1tAJ zm7HX0H* z&Zzx>^fJ|1ZY8@3Sms-(aXf2~u4~?4ydylZ+`&~;w+Dq-5cR=t5iV7hw~Mz3cdBFx zi=l(`nnXpf>~-d!v>+^{Gb-hbH<7HUagx@x4?4-m)dtx44g`ten+I+SPeV+;hfy{P zuG4b*{%OBN59Z{Cwa4x1Lodqmrjrd%KcIqv!eRZOS;P<(9--W+%G&YOnMlMCrN;X- zl0c6EsmyQQBO))6-1s$;fE;7+BoKGD{D6X=4oi_mAxe&+pkU;@>bOH$(F4g`lzh@T zqU6D-&8`!nsA9T&FFS+bWr2o`_I?%FTq^{mHzJ;z0)owqfI@AgW0u8{of;GyPv4b73&<}yGv1sxS7p|4^EvcS}kM!T7Ifl zqsN;Af)P(b3$cR5{c3Le>F#fdM*I35!~wRhFG%t=t1uG8 zzkT=V>pLkLaxU4;VHZ0P;rVvXbY+3p!XQu`(ZbGT>C^Pxe!mD?_4hffg_i&|NapBL zFIskj4o41KSVJJ+j^}7MjvUBt{8-d+>w+Mh{=v2omDY!^5Xb0c52W|WZH>dFgs>Pf zi5jUFM!?!2)k4}R^+(aQ5axT-JuRimHpphfMz>%plu|NeweE&q3O9Ep=O6#98PSe! zs%E`wSQ}ln3Zb9!WNx$fw%gJ%qdmAhS_q_BIzc*cTQ)`oqBHI-N7L_q76wb`2Zjrh zv`jD(UtA4W*gK!0QDYyeipLl|UT!wtxO6f8aqzx$rS4X@Y)Z^J&!w)K zYmfvbceOhq1ZXJv;gU>!&{YcGkq7q%%h~t$5T$v?#C*E%A8$Xu#YhXTr`Nn8iUM(S zQyLZ)FPL43F6Zsj>bpgRl9~i*;GlK?YC1)7@h_}y+Fqro2Vhc%O^qM`2&G|Gegx^~ z40Io0I5g{+KknRAl}0udK(&tmZt8mo_b2|jjj9ROx`{Bxr>O;iS$N8$CroK-<&4D9 zr6iR!%m~z7jK4t+alC|9)r3xYfe2QV3k#YRZaZmB{)_vX z4z+x>kVTeb*#3&Ywvev+Ki3P?gJ#HbI!DK=MRahqBI90;=PE;-TDj{u$PM*(h7MJM%p=ssrgzT zt+pL3=te^a{$pVrJfDspuOTzYPFBln8awm#;UUJE9oPf`g!P_S4mY#0=<(hV!gU@H zr|{?WZFU&n<;(HrCsSG>Da|wyIS2MP()xZ&xnKSKQx)9Cxh5uofB59mgO&{a>zmmF z4Kf0fVsm*cK-Ui}MUMeWv=dLp^OarKIb0Xxb>NaBlWC!^_iyuD6;TiA*#7?4n}>(_ ze)|+AIpnzX zTK|U*FRP&w@$l^fG_0!1{{@0>3+S15loH@}q#@|~6Qr$OO5NH>QGLNlDmqi-s|G6R zhW81|Tt?J(d{wIzvXvvug$L~z025f5ZDN8Z7n5SXoqEL8%z-~P;His17C317o=;~> zh(RFeiBlD3b%zitGGDzDVnMC8w5?*uf)z8sFFs1HKv-7Dv|A}AFZ!Z%K46y}H)5D= zR`dlIELj0FoPje>w{wi9>y5wdN7eqa=#ogLAyqS69KdFPRon&3pxBE$A#h8g3LTDA zIR9K33;s08V(3#9)9GOgl*pCK8a^ErkO&$!igbpI13{QCE2eAoN``JcD%u147} z{a+xVYUUft!DW3+S%eW9jWH6Gy61zB?f=59^9eD#*YkCltL=)=DZq2lKH{NzBNFG& zCm2AF-V|wP_Qf4MR#<>=4jTe`T9fb#(IrohDw3lYk#Wu`fNpcW#$~Bc(E(bAOalrhDJYG8HRk)&!;kHW2wZfNzLnt0|fcrAv zBPcM53tE>~$mu;j6rb3TFm#y=C=Yos^=mvxEpv4mX5mFX&5E5NOhR0^drzupzI@H5 zJ_=Hx%ke-ogb_7Vk9f3$yuja6wk5#y0BillJB;s0cDO|*{tDY+iBkoJtWh5Yf&bn=Bt%P(m(wJRQa59p8#_ z>y$l$OUV$etLoqZyRBMiGxzu0zj}5ilQTaM;o}Z4=~mbwZilq225(5VxCJ)P_pBs! z4fRi==n%|2x>{{VG)ZIup*HWFRD9|df9Z9&b-2x(0R}O*PDm)-Te1tZEgFt#ZW@kc zNMGz23DtbJ`B`y{+%b&ONV>b*r~Pia`mRG(_#ni=9K%zQYs=08I-_$N`gwUkjG7tL#S;7%I+}*`f0%bIY)4tUn%-601e)YAgPkZpM8PtD8g`XDO@T z)ni6eEoN^Y&0)X2dB&Z`B@cJTEL zdtf&U%!#os`m>rnDDcekbTZq-_&pJDhudAgK&^QCo{}7lR={KcVu#Cl)SIuF(U~NU z@+0?l&Hc1gSVOQ^Ih3L7;@swBahWYU1r`LDnI6tL+f>M+*xZV4x0tXiGFW#{c|_^V z&af=;Ok%#9@~mEoAfx$3=&^uc!sc%Eb~=^jj!wXc3x#ALS6e|Pjaw=mL1II-cbGH{ zDP);SFv9jYQLt-b-chnBcc=(F47aP3`_Ra^yo6_@ePiQD<(yW&N#fG#-=rx=#C{JX)SncE^PN~|N*$%p?Cy76*WDT{`>r-Z2Qd-HVwDK9#({pg} z1jQV^zMV>cYyyiMx3CogE7OemBdIivwG`ytXCc~7fsHdaa5 zJjW+H+1eQ4;5^leg|RoegyrN(xT;a)97+W4z}`?h8Hs@A)jLbeLk5k@$mYr&Ce~Vy z36;0cqr%JZ)sy2BdY<9uVT)*J9hIdUVnpYMkT*t3BeouF4t+>SQN+~)&=24-+S{W+f&DN*ipD_EAPea2YJwh_13ZhhnOgkI#x}z<6HlHmF>P^*B=s)1mR+-H$cmX zAtHSN`f>>l*X7x6-ky#yKL)znQJ)9^-v2EDjIpZ1Nj`%;yp;lu-awISkGX(=q&@|j~_i=++OycQ>WY2!|pp2 ziK*B&dbkJEG#W6{%P_ub_iq32Fx$M_L(>MFA7XKf5h5=48JO!7AT86lny}vS9bid+OJ#ZRgsh;32;Tsi%C# zip@2jE{D<*D_>Tn;F7qRhW2VaR*~fY`cLK^7IpM4s*Sj}lR0sfQJvg-1r*oKlATgj zgcFtmsVO3jmPUzTuaPSK!y?h@|Fgwah|Y9MaBDr@P!CR6@g`UlOFmujtcdfEpdyig z$Th||?0yG~!e`^(^VH?mYP;r1&=Shda+ZAtVy?GHO;iBN1EH3cl-QN8-6#c;?3Aiq z6y=0ti`hX0YuwKMw>kKcVpUpc#&04VTn`rnGh<&uXFR%uK_!zWIp8JUl+ek0T4pEE zPzzCDpu|?rW<+zy5eP zy8itx8(m+6#q(i(hf*wF6yfmoLaC6lv8SZ5VNV_MgO<0JQ|J)T4y(e5;{(y85zyg| z&Rw*8KrUgvrA&bS*CAj;?}I-m5V(BYJxLl~J}BxQJWM>`)Y@)Vy(N!9H~ael8QLiD z9-Z|HEKdZ?qg6fwZW-muSpY7@@;mgTsi>ZGQ|m!?*9GO~|F&F_g4c7bocM5%wI|;; zvj+s2zX4hwacYJ+0@K-$9b{byj2$?qqRaKw2f1y%#Sac2GUz$YbIfN$8i?vNgm8xW z^>x&@+q9x7l7f>C3udM(a5HS6C3kTd8~YH*ft;0v*)Uem@9+5xgze2__GR^9FOLo) zqJVM~)%XiL;s;>L1d$1-f5|2vx(Bu>FAa{RM~HH zX~kMCKhtLLJO@!(Y=zf01`=KJv{n{}7DH@A4KXKV5QUFcQNYW5`(=+3eXe6(i)DYn zQUh1yLyL8z>3=%q_Ua$#_QVN!K7_+ONUIr-g2W@fG^7E=w}ts_(acS&poC5~nHbzL zp6_r>9rHIX_s0phAk9Y)9z1rROwHwjQY;S--a0;d^8 zXFw7G??)~{^L>t`=HxH={4yg|P7}kp28Q)QT_v|7KAFx2!a05q;bKQQc7Hp?@Oyn= zZdB~s_{Y5k@LZ|g*bP=e_3ip&ehvJbR3fpAp{ij3zFYdn`~8=NTh;ksHjoN2*XWc< zhm`Atd;T~+jjb-3E|Hg0BF32LS*}vnPW3xIE$*9La6JUiF(`D4(hr5~e zD732RnhhUXUxjBk_s8-(fQbtIB=+3jh4ZSn3MYKTR0Hx0n;!;3; zWR=QJC^`MulOl~wDlY&nU=e3OK99HG_(s%fz`~}}&syAwR0URoLl1LIo>}zj^i%%$ zB;!ulOJ`*cxN}%+MJoF_-;>qX>5!#iqiPVWsLvp>qlc zlK`WvD(SQ>CCOaLAvpN2cLAJ@Jqgy?p8t1l7kXO zFs9I8x3A*z*^i>CN5xomg)#IKJT?xQP-^R{mxAUVf*RH5CLy0jFYW@wHj^OQyTQEF zL4m8u$4NTAfsmD}ceub5n;SeGZ9;`uXMI#X2wig$jxz@3YUo@)v#+VLh%x5I){xy< zDvk|rM|HW5*T;ppl{y023#Z`nQOkjGn2fx9{l?A1pL@(Cp8S2)-J55NPtBUjs zmLaKoo}rkye0vYT`OAvJnwW`8wJi{mA!H@F6K4R=+vOVOYWE-z{iyd#oZfSIMCk^J z2(S;+PRqo4A73t3+Z+}$8<;2r)!>M}O&iVU$01P&TxGtGS9LYR5UFkn6d{KpT#o9< zn={9Qfwwz%-UJN-#qFB@mku6bk5dpyQ4HfhrY-neZvS9 zU#H~5qZJ{0#o#P)8VKk@zJO5S*;1tt@In&0SVY?IH}(XZY=DXaaH0|T7du?$g@mDzi)k#ZXJ=ZR7dMWAI~8`ABEexA z_3gmrF4p}eG-e!bn?zQYX_&$6ozRv1IL_yLjHfa=96sd8$4*gUl7N7~kPq{u~N zyKkjcLx}OCYlTTVic{Ub7ZY)ov6=Jq3aB7uGm=SVbAbEgkd4`5IN8> zVk&5&{zNVP$7r=C=$+>(@!RTcjSqh|kaibqO3;DJwJcv)A&fV<6@_CCTZ@yCx$6lb zB3kv;=5r1r*zz&BID7%t1PD2Xvxr)f3$+lP{oG>cXAZ(zc1F#_?>Q_bENUNF)haib zk_apcWm^^pp(pSHbfBn4DC2_zTwNP;*C5$M0it*1Vt{MuNaB6j_Jb6d*loThcTI^u zp^3XJE96ee#Y`L5Iyy-%^FTe}$oD-O#c+qOe>=ets;R=&18Nv{w zh-Tj)!ZMuWO7&P5;ue2`LJfg7wK@^>{i&<$p@c}mF)LYYAUR+_Hm_y9+&~t;0q*-( z_4%=$VRp*oY0OLA%^p{qpVG`9k5eLL5>%j{5=|F+mIJtO6s6 zuU-aJDxXN|i0hOVaNcL~hvi`reDYxHfI;)2DB?w|dDMchp+m*|4wBI+_1IHAfUt^` zwiK$h8p0l`*5a>~WNu_EW;crg{Do|Uvu2U; zB6#S$3=iFi+QI9BLn#Ur>(&ynfWp<=6;8w(>Yv!H(ql<$q*dp5T!)%nGEexJ8vHRz zYGDHh6a@*Q?*>(2yo~&D2!8c2rD<`7X{OlEyA_g)?T7psx}{SEVmqJl z@W8(cvmLHjL3J!mE61|P=mI$-zB-MG8uo+q)vj@J0}+D;q(;Yv z1&JOtigCh~WY<}LW)cc~@x0A$L-*>^^MHrL<8@_xh0IAZxm2jeFz6&q>S6L7bx6|~ zi@Q}EE?L8&^$WQONorgU#0l|S`QQxzRD4tnLoUc1nbPfwj-roIij!VZXC4r`_jWn` z1T7xQ{rDxLx>akWoX+LxEvQSA*(cJ10tz*JgH&z}m_Icm$Ab&hvm#bDw`~4#hBEe`cxSj6W$r>k)l-j&N*xE0aTfT-=sk0=q$>LvZcOze21(g_hc zv}_Vx^k6Rvk4Bw2|8JOzR6H(3cGlxO*1~Cx<3RC-oH1cJa_V`yye;v`HdNC(t}OLD z;JLRT0RnO;AC5rkXbpAr2=_uW0Iu9+J31x-ORR|h~^RK`D0>nWp^tZV;TVH z=!3LNm7ku{i(nNS0D?>E0|l=76SPD*>CeiW~ZOV z|Kcec(#46LVLh7`cupYZM(W07fDVz=B`wUY68E?uk%`eJeJMFJNVr{j?%{cOiH_3= zW?&(nT@6OtH~7T?>QwVbWMI>PZzX-I?36e!s6y87gU%A6c;^AsgB*B?*2 z#>#+NYECnw;|Jk}_@=!gOq!fRdKxbd55g~kvPyCI$h$yF$&Dmaby!Z}f zuoo6&qdSgk-3+TmSsrZT@sS&!M)#$ukI68%2a|mWu%F$*4I}07r5bl3TS>#pAxXwe zH}MC`enDcMVhno5*_p@_84;rF^ZR&m@9llYj}c%mQ+ z$fbrYTts|bwuYj-UlHXY4SP$d4*mNl{QEWfroQ0DW#^V;%JyKerW%*CXV$}ox!{SU zvSfe_3Z%o>LZz9?k%Y#}pPytIZ$Oc|QnLS>^#s;*9D=xjc^aXK=1@7In%qk&MoRZ~)cqE)T#?PqftoBu9-^OJeOs)YedHR6=z5=^?w75r(gO14^ zft8K5oN&5AG%GCBK6gVw0d}@~T1~GaW%smflZCQP%RTAV^mah@p)pi*<>%MsQNghp zo!C0H;(Pk)J&-)9qhh#EJd%i)V!UKHw)%{68bLKpxtyp!1yL& z5?ze%(JKM?xGo0h^=5&PG2YC7>XRxChWpc-t`?95kUmu^tkuM(9%NQSe*A(u=TPp^ zqvhSsOOB4cn=pd5W;zgsAZA^nLa_s zgE)+(g3B@$r%D*nycR-Gn|!gDO;eQ+U8dvuLMw$D%0z6p3uWptnn}ESQ`Y(T% zdiAUAdQ(J^aSixr4@@DEJ5Rp*yXA;D=O>~R3b^Lk0_EiSLlT<97)I1}F(?g{f7F3v zhft_7(vK_&rBpz~7=fucS{L4s@(1#-7O2TrTA{4aW}#u$Sh5C_2Qma>TwQ^yeOhgIOVo8z zAk1CG2oj>9OAwf*nUAA;ky(q}Z>izI_$qoNEz_%D7Dp$Q?to;xXc7(`hJE}CvK!L- z+?vV~bCEdf{r$_`C?t%-F@;}(e)3MGc ztJ2x1v#2Llr_!X^TuMtLzJZ z#lBh%l-d02MWRWf3}eYts%b@0eEj%!o{zUyivvgD#~OT0{zFkGbN;IB&f6_6O0^tL zQ?G;nKl*Fp2pSx7y9rb3+mxZb92-fo3Fa8+h87{=o( zG_ykZkV>z2dFzYqw|q_SYX-wY5-Y?6gONrnZ+8Dm4Q^QYxH9xtxoyi;7i(G>u(i&i zSgq5RtHph2*nC`yG%AbZE<{F$DrNR07ETD4evxAxl{4933)xiDkcS&6sQC9xo+|?< zv=ym6G0_ST-;*ZLBPsgDhFUZV3)cvfsV(sjP|>VoXVZ>U2Wn*&%*B;vnYK*qt@>1= z!&G4zXUzv$)+!vb7^o_fDl7Ptbls^@jXQ4^q}zVWj5I!C6|rj2mijclpUL8fuMdS& zQ#4BAf4yPhubs(EDvmLE9F-p0WII6bAiqjVmm%=N+oQ@(5AR~g)`D~tUt(-UikPm#62=$u`uFeUD;X7^P2+?b^#CQ&xNd5!Ilt0>k>~Epmk?#kqRRwMnFcp86~YEZAK zLW3j1&HV?9MuD7E==R}dD#reG)WFVpS>L-v)GL0s^x#>KNDm{F$w?rQJIhKFxsB2N z4L3PN^L?JT$~Gi{d^iG7gWJL>#P;RrPM46o`b&%I#@ppj4Voz&EJ9l83In{W;v-bY z5%zivUR3%02vOAFA=ILXW*mtC{Y-KK4Tn+XqH1|3Xxk0=Sll(8Z6LZ^=Zj>14H;l3v;;@WXXPv+Z3}SjbM1 zcL7hFP48CJe9Ir4L>%Z;UL)#Dc&(}BLVqPT<$w2RZp|NZ?8)=+%kO{8pN9xT^i%)K zacO|MTyDcuhVNKD2v7IXcI-l=Q!}Yjq7%;&1HOa^St{Z;^+2s8ZPEa~#!VW?>`cQf zNjg;q9|iLtc?@c4w2MF_8{i-Etosd3mzd127Q-P`5W5+CtVNymj98Rc(cn9oDO60> z%ZQN%0N|Qh>^3s}Ed;2*t(hgsPC;O;Eb-`tBXb;~j5|15`5KMU}EvH`%ZTEJ0YdR^N9>)BLj5iDu_KDs2v)}*!hbN3t@((3Eb>~N5RVrpCNNNTO2k- z4_Lt-RN!75yCS~Laf(+ zki_E*$8`_n7|^u~mRi2`%>ypSJiniew)_qwA#J;Uzdk{3B}_XY;ZYWb+CR9?dEWWP zR35kMDy15xapI)ex_!~v;ul%Uz!d=q(Fp9D4ZUlnv{sX^3Pg`sX-@@ zn>kGQ)gH9qD$rD7u@BBNTHPAf(m<(-P7WA|*U{A}dXYnl&Y*s6RG(c)=?EzC9I_iI zK`&;QuMVw2vIQ+uBbuKMR5^nbhWi-ro+=9Zim@osBRieQ*n9nBi(jHENyJE@UGjBR z*pWa#?lRA)fTxz59blImsuJ*3=~|Y7V^2j28c!l&PK!|Th`wek7M3HvjLaVRp{wB! zXvd00mbN}C9nj?|E<<%3-+(GM*Lut7@qi@hT2_Ij4oq==-5ul{;Gpy}QUx%UfV0>g zOpz)W$Is&>BxG1rwuE<3$4^tevBXRzKMLDgsyLQoZqSVKEwMMgjNzHEKh*6I0*8im zFN3)@@bK?~@++^-0MWpFkAP0EkEQIWb2l*QJ2*gC<3r#ytsI0uGT@18G;V#HnZC|$ z{ODaoq#4!as_OtUzIE8W-R@_=Y*b3iWl!x}&uDs@md!`VU=S*BQwbLY8kbY-S(5sf zg4Y%+2tzF8!P*?OU8qdcn*dx=nLIBk63Ekvq)lm3JIwF($LD7{Yc8fEOKnv(cMQ|I z!I5p?Qt{Hc-aOKd<+bU{G<2o^$>KWh_;|*R+1(1jJ+mpapL3lBofsXc6p`=+n8GVt#OQ_eH6VAJQ{e z+)-2Ef(WNNCB&TX;PIIfJtu!(Tz88L(dA^7f^bZx1>OkoOh{i7KgQ85{L7WSO4ol96O`Lbm72 z<=h7AX;V`Y#!DlQh41lObs+V3fl`}NB^j$0VIcM@kcB&;*Tmcsa|mHJ(jyr?1IZbo z%UjH9`1JPC9hEb*$jajU3t`PeRKNyEKvV#>tHG|IwG&N^2&vu!j4&fr*w#?}>S%S8 zZm3poKq7@3p4h4yM?f*5yeVEQ+>(Hml~ixu-rGn;^+gQ{f!ycFJ7q`LDGx`lh7y(e zxiCny`t(}&tJQXQhB`flMWd8J)53$`9luFA+9O67cia1uU**`c-UKcND&YLL#RhhB z5$>oMZB}Po{|gL{Oy{G+EYra^H(##+f8CM1a!v1V7uO~&V5LSd zc%3Nd)%^?RBEI5Dxx34A$f;r@7=@6*lfHuF8i-csIrLid`SxNx-aXyIGITsJyz4E} z7>ceVssqnEqPQSgVC-|6`n7eE?DoB+{ zma$tU)-C~B_$SFGlmd|CR?(Qf&%|3*6vUVum39y22n1TQh!rM}=f8ho*;1As_i-35 znokFg<*j)#i@Qi|TC72KeT5e5^b(jMwG~UW@@D_*%~eCp?H1*=Qm+;fxM3>r8A$A9 z7L!yzw|6VlM3bGXI{sCxHX1K4p@94b=D!4cgUEKdMU8T`v879wv<8l7-eV#&qA;bj zz}Z8f{vnhsyVl_w!n6buBY#Kndo-b-JOn2@nM&0eA@T6~i7C0TR_!#y_NXOqkh)@C zf%iT1wQWD+?8kP!-z|wNpg>^I9m8idoUE!%drhIFgH;O6^BS<=Dg?b9J_2)coEdP@ zQ;9V+SW8iuz#fSCY(z(kPfrYA@(Jw{AJc}*euU7iAyY@RBKouu&pDyRA?>0YMZ)MK z2M9D zaf|R*SGlKgUm8-=Y21} zA`zakNT<6ja*RK_luYo?@%HTN1CP`!>~|z*t{>X1Jl1&L+%0&mu+YM;#_!d*t-hpF zQNA_G3;oDy^+o?`+}+4zqC>RByDtc z%X5@4!6SO=?gJYn$KItxyf^h@kes6`m)Fb#XoT1!D}-d9ZMCL0*iQY^5CDep z8&YFI9-5$d`f+g#l!1;Zw5_-(B+Vu^6M?<8i%e8LXodF#!Cv0BUOou!H%hC2>7CL0 z+X|NY6tf=SE@5V&VbI5&Y7N}Tg|f^xtdY%nsG9`$1_Ac2s2U0W;LA!_WiBtvk_A)W zV9$;qUDZaX2VlE4v8mY!FiNxj2BZ5>mKIUI6xXoTPXMtwvH3!?tXXCA6tUV9o7skv zf^aa@3Z_m@8M{WY(O|;)w_8RgXJ5=D6i-o%apYYw3FrZ zHuTH>)O;^0*6C%m*T-71YAQVUT3u~(1ocB;c)+3wVw3*4^)uS zW>2u2m6?HJZD{vQPK;QL#3QxnxeJjt8l-2Y;!4-2#Wjy(yM%zyuHW7qqh13zd(7(O zGUhGAf_i=lF+2#8XAV}#&Vv4xl5yHt7J6?7NT*!XBMKDwAoC8c+Gg-Yc4}r%N;hV+ zRll7MrH(URlZTQ|YCzzd8;45i{3-ko2xvr==h?q-x|9-;NMvP71eebO&4)cR+C`|1 zC?rMY*omXJLTaU35>NYN%licbvR3P#lqXwU*5a%*EM|q9a@a_E?MPe&ezhHH!s~np zH?bfskP#YqPy{LXq4d~Exx0nUytX8ndqTMb1BF!F_K`S%-A|^h2iXWD$aEMePv*m5 zvJnz8UHyZ9LMjtH%8I>bSu+B^eP5h{0>7k_?PD+5L?y5UCCz_t;;zpi@>}aqMSy$o z+Eo<3TH0#x0t-felf~(Oe*$^$nuc+F#aLrbJ9y1M?w5RlH3ZmPeY~FlJab&#&Jha( zcbJhxJ$$5+bV=$oBO)Te5J04Kmq9#AevIkl)QSy5f@2pV0KhR^C(dbrv1JFcqQ0n?>8X=rrgfJ%* z0S#8uCDYdDEThEeJCnuYW~qvCz^{KY;V&kjf7jfN#Hm`C)R6tywK_7CzFe+&WwF8p zkdZfh$#r9E=0rwpXc&_T4IIzPH(!o4{dPf(%y@RF4Hm~K@W@uE5gc{!ENuB(yO?1F z|Bn3G8acWTiEVJJohyD(X+BDGY5Jat4;Dsn@F!rc$#`Qe-5Q-8Ol2A~t1hcmWSbX8{|J*K~q9-;pE93v^wlCs?WiK%($19*?$ zfi-@ICf+BopT6BuBF7tx#W@>|R$ImawB4(!ia;T%wNdKd#?&+nOCwEC1Zn+I#JKzA zl0C2lqD0I$t|9t~Kt$Tjg)k$ z7f4TzQpER9`5d_d9$FS;x+0NrG!;SSWeu{JrFU7XxpPf?ek=oYVE}Lsocfe2kX){D zM-YATRMV@w&zKzYD4qMCu`^2y|HF3hg4q!;~`HFv~o390gdT&4d@N5H;m0$ zsJz%h3q*7#_W-Ads#D_!D5E_@@V9&7$a|a*e?SmrF;mxbe77ZTA*6!$8(hI1S~ur= zF{$=mJz=Y-f366ddP`>Ootw zKpl@Q7Z_w?O_0uDn`X5Z`JHHkvIID7H?xdR7G0guZ{zLLj&3ROuZ~U{4aebG2n`Wa z)&t`@r(W52m}x9{A!LB?mEl0)S#Hs_Fxh3${J@{jp!GN(fz`uGq&q0yZJ+pmf4TiQ zA_!qM9fAA$I0J;Sg(&GGKJDYEcQVoz8u{Ure`-I1=b&lAGx`n4ea!R8PyP`?(69~| z48dx-)(k9s!XedRdAj;{ept1n;J~LN;J=-jp z5h#DDYND$CREsFR+_?TKu z*&T#(KXxCHkr&Q58$mREzF#bvX=(PgoISQ})oo#0i-6MWwzUan3n)p}pw{;iJ2NJg z6cen<T%$5|nS)q%(h)LbFbA2Ll26rbs#wa?FfcBvtpx%#!mr52lRY{Z*Sx%3 zd1zB)#GD%BZihWK_8;?sn?tUSy z8=Fg1GjuZCY?iBE_ke|v?|Tg6s7l`vgLhnEyjscCIkRBl&W04gb%jUSh7-PeJ6n<} z+w<(~{nIMPls8%|!FD3vQg#8$jc&et`tH-$cS9b-X_m#p+RNQa6Aean)J29TZiLaX z)ZOYT^jj6Pl8_(%T}2cG<=}bEj|MwDZsd-nX_^eAsrca$v_C{E$w;5k|JiJ5dT?ET z2feNG6LhG%dAZuO<2xedN@Z+8!azV~yvRRx1b3CE0)f}cF*VEKouc@tdVnoLomVio zCoqddn>Lgy1l*UmSWgzime@tYLHrYqZLHzO(hAs;@Ei3dQmk1~RLn!MG5X``TH^yl zBB=vcqZ3IMT8T)1R?{b*f_KAVXQ+`*Bc)R|^|60HgH@gZnwack9Jiucf^T(3GTini zx~=@i%R8^yr95oWbS;}9((EkXD)Yu@N&ISVZ3YZZz*cb;9K4d=?c`}TwFJa}m*e^I zaHCHciz7`>e!+YXVR2>cE?b(>zuhmW`&2RzrhwFPclk6Q%hQcrBrupjG0ieCzA#YX zjx-P8AgD-KADj5yjL5?YnN)2HJ`UsGBTz&a)WqvY@!|mnM zwENC=fGC?dwA;@uFJ=!})$`Ht6xoHq<|2*sWxs%8)@$bRg)9;;R-Yh)FafTY$(I8% zl0^NVz@MP0Nj|&kJ*wi4fy#)vMNo!&?Ugq19KFNn;r{tG_#(Gf(J8+q(E=!Zescp1 z;vr-m;5#t2s0--^aqE@3W$$LP^DE=J8eZ>%Rl69jZ!9*pTyeAC{B3{F2dzNHOFAa- z!-EkK?NQLXhtl7Jv6RpiI*+?NGMdO02iktQTtphj_X%1$4`VT%4L#fNP+_|k2UD>l zkIqR{Up)zW7Ekl&iqPpEtrY&d?P&`Fb)fk{K}wnFI24qKJ1 z{yBBRSTt4K(NYvgZ(+!He6?D&-RdH|r{2L(sH^=C>p;!n@J+0P0AXOi zZS;a;oju!|Woilw57$=@$8X3IlqXybuKK$e%_mtnNtU8M zFE+Ho#x)IjAUPlAL_5cVMHtZhQZUd!AYl^$NhcYKRJU>@s>VG}s0}#xETK$<9`H@W zl|C96)uV+Q;gGW9BrAxjgeM)o$(NW04r;H`+=^~AIdT=LO@@%P)p*`E32tQ?hXmpk z8VAMe;ZZj$?HA&!=p$DJx$vNuffK75y_nmL(%b!bK88~J{dILJ3tM;-o4lqwMJGdN zXl-tDkoh(XkTfs1`C|^eZ?wCPYUzW3=S#l8Qdv|b_&lC$R$Lu-8D>_wkmV}IOS0iQ z3+%cX_(&%guP6Bs{y7<=_)Bw8Z#Z|NzuW=!j{33NlznJVjG<6kRT{8+yV?V7<+kIH z*-8(i^qqHJG$h3I<)w4i`2+b?${qzg9Y!I=@aemT;HCsR6w1uiJl*ma7-7bpxZWw- z!~HstcrE4*DxzfCfXQPT0kQ2z=nKmF(ZBL>;ctsmBwim0Gy)4Q@~{^?-2`$va)t~L z$ZC#aDfA%scEUoIc!>neDG6BG=vR1w)pvkq#3;DM0Qq$!!5zPW!RKV4m2Dr_(pwVb zJ=Xy?sG`N{MKe~3V1Nr?!sKquDh(z9BLZoNH4AX>K|EuXCb80yZ19DBU_&DS1V+Oc zE%0R^u;KI39|DmjjM<(KsXkrrAp>2bby1K2_4W`4BwfZPBZxC;KnyN8;xg}H%h!y>fH|p(33iF*3P||ffVlSdu4&9O#VQz zls=Z$qDV*?S^0A|`!*f_^gZd~=3c#SOY!Lo>$cCs6C2fwli7*_bxaEy74YT%@u;nu z=3SdpZ%dGab~!QncYF%RpaYP_kJ5ty=j5+$1$P9Q3Af;}@20;lsH1iJa17+mQ%r*K zPHiMjNWNi>ujhD*=6h63IZ}|j;bw*OvK%_!s75WfGjQo!R*mdvi0hW23{Rf0GM=Oz;V^MW zK|u$8ajMW1k^kRMi`MaQntYVvwa(c!`9fe%1J|wewl(lcxrP{utgQQ?QsU%x@BO?nyWuTJZAx!vF6VNgoB zy5;%H^oKk?b@s#h7;vySO93eT836j~+xQ6p`jDzvmZ~IMp_g{#`lsDrE;Ce;a<=|D z-CoK}x(v<>@gU9Ei4{udNsceDP(lEzcK*1e%2?G57;mNzGB&f5@p{d1J1{p6uhk|+ zO#Y{GF84%_U$T|Cb*~2ZE~#)DVt3A zD~JeW1!$`rqQXVup-}heFbU?0FJBkob_}{cx7zpy-TY0h*Eu=#qZL zw{5QcVCDTvvXoDg;o{2ZqX4&Wi`k+J@v@ehSnU_eU$F^qMCX>+RsRc1`$J}#_ zjClA5YrL?wL(Sjp^(SaI&Ou*z587%CfvezO;Yll&+By3+VFgh?J>*!0Hfr2y!PI-~ z55x5jmq;s-?gwAq9ch)kL|mGd!y0SymjYt3M-@O5iZQi(RgT zn1k0Vr)eN+13?hqA_pnjfv+&z6Mu9%hn$kM1H+imObT!Xx);sx0a`R`Mf9#-R*G`d z5ViXlNIl@`Ct7?aNvJ39kt8kW#qKC4?UGIN*nH3%agNA=SB!wgogvVPwqK2b^-X4I z3Hd-i3Dsq}SA4+zvoaJ)6uQSnnq8-vYLl$GoV|mb%okR+keddsigQw}tDe33Rzu_a z$c$;(@;GSma`;HpG4om~Pu^ew5_L_(Ffy9;p1obKH>)4Ra_#{;&Ra)5z6zs+F8Xq| z$tQ`3nTDd~kQVS6ixAH{v#QmTjHU?|wYkbv=Ct^E0Cmi{)R1S=D}nPlFsxm*pBoQ) zr#)<(w-h=?z2o;R-WL>1veR$_n4<~@T~#)T;0uMC)A|4i&N?SVxxf7zr2l`C`U&;; z((V@Fe(c%1c!ry|ry{y%TxEpETWUZ-oH{Pu`y$REgYT6+UHE$3H~?}TrKufMET90i zR-*PL0=3$d#DRzsWh~3}iKO16gN7?M1xfzWQm-V`mY~$VdbBGop?4K6Sd35uZpN4r z3;PV0`vq!!euNUt3T#UVS#zv(j==dlWHb^(AJU6|U;1wt7Yh^si=tf3Vn&yoqeqy% z8hfoM(lKM2rDpV)bG376;Spi)POI;W=WML{Is4Hz3&OEI zq^(?Lz0i3n-rcIb=FC!@jDfy_#DBG90;vIgbiT0axJl@MfssZ=%m;7OcKAZI_vw#H zoI9!416Gd+*07NbBE#FzzLu}TC5*Y&I=baT^s!=V8p;V}rfgPI-boQ^nEp1(I$eMU zTCvW`I@r>14?0-`e7nJ1hIC{lf~6k1*ngCZp5^(})fxv?baRxDm_z5qPNHm_4~}Lr zB~>J@qkQ=Dm(A?q7e487!aQAT0Br;G-_b=d9~!++!&tK*ROU{v(^duB2IERP=I}}$ zu8h@z9p@9_g~NVWs#XI88Dvz^t2)qLRRBagh^E`PL|sfY;%Rx$%rq~xJ6QjnRVRcy zpH*Xg^c_vQqkHsAP0=Wf7~(hd7C;Fcb%4==2uNI#D&mN$=yt$^!a`+^p>UW=n%Sbn zSyPxlJZu0e_FVi}f8|!$fFV|iBD-@PAjSqRHzF;b-3!bD)R4!tPl?Zc0)t%|4E8|! z6-|ApTl6_kN|9B|8F>ZYJWTH38F_NdsPYK{K0=GHX(T(aFac=C4uw))5q=Th#i5ba z@z^ukP{}zk!cq9s^_;+B?l!6!0_Ze5dbk<09||Ccx9gI`(3AXk-z+!;l2x2OZ0qh( zvXU8<7(a}E{)X)p7{OwcgZ11x(E+tgetgwr&Yz7ShE7JYk8IF`=PG?;>!K1`@%Fpv z>bpWr@&rx%rKESMPyUNI65fF&bb}&B2{-+mRnqf`B}mkY4W*fX%|6Vw0QR}1qN8Ww zL$51YiWW2M8KOm0cF^7s1|j%x5y!M4q5OM-U~_Ty)Cv5Vodu0vu0F{BSrj~FFzcL_1lH$m74nuc_pyL6dm9RB+0>fQT7Q@Uk<*)ice#9O8Y zt%?ps%W&h0-N9C5`?Z8u992bXMjU3Uk@P_Bc`}OX0Mvw1S@$IFMA-u$48}HE-Q#AVNsE(w*;C-rRrg;ovF+jJ6&ixQ7r=2l`aGWaeRjX6LRQ{U)WqZ5& zMW$ie+$G%kjdhEI**o_&;^U+3V3{3TCdny9YPFZ{Lt?>H22?z(uddV&L{ME8BZ|p5#t)H?v#m?Bt*w zxA}wZ)DYwvO9Y@qc6M1f5_zP);SZjyxGt#c=wrwVO zr4Li;9OmLjT(_VvDofIUn@oRmf&$C55os@T=P*rLI=)Q1 ztp(yt3;Z`lorb2j>z2z(E816P(a1iXzsVg(Mc-iN~FxCuB=W@nhxpq4? zx^O+3z4!aY9svZzL9G-_L{5%k5)uTk+o*-8#mXO6#|<2aJ8r-oOlR}mm~5s17FIvW z`Vv~=pRDJIEo~JX6by!A#kKX&ME+0KOf%T#QHf;JHRht2uZk;BJ@1Tdm3&d~R2PI7 zfiC}d3c-3WM$_FFbQ?nStqv`2sAqEf4ruqo>-RU#Y5@5tv0>CJ+m_-G8XLX7JP0J&j_7dw*8{^1jXo*D7*;>&XOQi$LKoa(UtDP^z)n{SpG{%a zdbL3ZtLFS;6+|yBb(!BqRi8t*x0HsPkB+Q=CXJu00u6;}2&prkyAy4yV8W`*cX_@h zuSlH{AZ3dKI#XdDQ%Dt>S`OjeppmNavS#;1wxY_cm*Nh7rSYY>Ynz?qaun8606?aTt(5J#JDF-FvD=dni*#DyFJ~{5ajani0h>lF2%{66B;tNVxCl8$*)f2 zYv`D%9Pe$|^q=&_RnBGc?IC|yrN^zs?Ts%{0$0H>9xZ#=$|D!3ULaAlr{PMk6p^(? zV@Nd&sxS>bn_gxvE6NYgmQE|#zj1JzF9ur&NOTa?6PFg^TW;WfB@*1^m&Za z)SNYv!#e)>y?K}{cRJlMRa;CmCCe6G*0ZG4K7K)qNZ>^u^2gpO#QNv^>FjntnV`?% zVLz8pON@Mod^|ADAA{hlH(gOjvJkh`rysu>KGu@%^MLqQdBSocgH022DS797eRxrC{qTcEc!H$#>e7zEs9jq0YZA4HXHi8IEA3 zbyS-{?_1!c+z{{?oA6|^^4+XNcsbE5C|Xam0pM-Atk61~K|gOZbb}qsNpws0fj?ix z%kc5k%Tbx!*DP{3=_Zt!QM0Jh+La?k1>K;cZ_sMSDd&qT6TvlvEqCw<;%^fNS2xNF zQ+Jw?gwqHajB5}p>ut(IQu@{EZ>4Khbl3&3zm-oe~>2W$&c~Km?&u&!rSC37?nE6HTggTqom@J zr`8Hrv2~)x;Ch78g$(|T@Gp!L@r}*DgOX9i6Y0d_a17Hd7e>ov0C?$4&nS~q@UYAS zJyYqFEmkrjg7ysmO3#=>c}CG{YB zJ=j)(wUx#z+L`8q7-gN@Atq`UG#68X09#qw1z>sU+)Uc_mnJCw3>+UF(J_&fwaw{1 zFfOt1C@HNnJH@Ev&1|^~!2|woh0V>BFN$>U5MPv+E|kSbL?U{zzE1+I(&AW;6-gFY z{AECR6r+WSvIWp$ND^NZdRyhu^iI^lLZcf<-fxU@Z)A8|yZiuk%HJn{@hqg{_x#Ov zx7n@IIoSucgX+Ld^xb$ncBkuc-c19AR-6|8yjXBUyVPd&&hKZ-$rI)>iTj)4-yjbK z^zGSTQ9fFyW+2%iS%k2#SzdiS0hD>~LhtTa@1TEaeS%7P4wGgm72r zX`~GQN9qg3(v_w?g(kU!{_b^3xppZm&WJ8WHjr$O<&L$A36ZRFvqrcgUKQQIpMt%? z;7_H0XJT-S1IAtCg`G4VpDqcAKb_SyeLA--rhq}(klHpsC{4dA&&aB#uVy1QH1AJ` zH}}Io=J&&qb;6pPj5?^Vzn43vK?NwnjV8)Q1$upERAUZU5xg;eqH<`3Oq;dIZobnr zT$c3-#}~q4_T%wxw~2qKAaQanGfAn|dA~nMCEh^P`rmpHkozVGuz_eXYS8qhwpC%+R)d^s7NsG;ml+TyXt8av@fwM~bH=`*ioL@Q0(M-P6xXW)K8w*{xSml z65`O4?ibt@Y7PRCWSWy7{d)$%wK%(pZ4O#tpT>*(>G%r4Xs>Ku+UGrvCu+v1ED(Kg zK(9|HqZLKg+rwm|M{d}rwbU}u&l_}=eqGLSU*t|jae3icqCY;{%oeNXm%zUb8&9Oe zoep5J=uT^}{(c?XvFTw}xki2!dc+a2CBc!~Rp%h*(OV+haY37LFEE3pkWCN6QQ6 zt?tE)rz#^*DMZ6>erNd$4Y5*sz2%y9CxGCYx?*K{-}r#GxV)ViBt6r>eMd*&>H!E1zuDiT*O zr&M6It`U6sPdA|_m0>+%7mC`!n;VsY&xQUtVV98D92I2~#tZ+3JCwfEY-iSpSgGV5 zEp_bTTeF$-o8qS5@r)2c6yW=zq=iVMzeh6)m7k}i=}40~`SkVR^-&Jd{6+ybMQg@7Hk@+n0M*JejxJ^e^+>6!icXv% z48whqQ)YQh_!hy#B3aHZ_D$a5)_XhIug0d8=*3InpS)n~NcqjQp*k7y@$DA}Bd9#z#;%-J7SMah* zduLXzeW3=6GdhP1WqqQ-Cta=#>0$$bzvA>_2=4<8%{r6@#uzZIVTzJJ*#{ZSSFY8l0VOCDb zK6*8AZ6mDsm1X%`F*UO~GFM8{BydAmUq-BL;Sgy(TBcuJ!b3Xx2bk}$o8Xg;CO>|R z@AK!Zmm!Q>S`X4We(~U5&C|`n-qbz=bq~MJb-6O*uZgk+I|! z=nuJ}r|Ry-Na0*Z;^Y_5?-B*r6R3(#KFyYoyC;0G0S1fx4r%9pNvJ{yHx)C;vInr{ z?|GQfwsEqNf%w(WO3gp^H}s|ye5F%LWaUkf+aAjd%K9|z8r7{0MwYD}2*h1PWY9<+ zpGvLKZ7?5>^K&{HZIPS9r}CuU10#Ch_pYvS`9%<-JJmy4D_C}Y_-3~{JAJ^2+53FA zbqB0p#qVB(aX4WW#gvj4;uHWb3^-HhNL~0qpT`ir&~FlJ&e&_1-2#8)~%1wPM*)!3DFX>skOoC zyj;$#2lP67e*K;*l}Z;Gd4_8{SsxPejAebS+RagwXu!wFJY9>~nlFReU~6Nd+I66B zpUT)&(*Nd~cK0x}d;!h~YrR{&AhgAPSLxW>O^~njTMm~8&JjD00Jq?xk00O8^D%~& z5wHaXp~6!6Uq)qgwR{Fwi4dE+gx@b)D=nn>_3-Jz%)WBYBAXWH8IdH{vjm!Yu8bLV zsJcdN`J5ZNPHwHblAR`RlRAAnK49(Gh0RWPhHHT624W_yP8sc>W%loph9aHsS@FRb zoR;ox;le|T^J=W$Al>R5Z3AdjCPL`L;a~^h5W)Fbt(C&of&4p;BCP0g2Y8%+#9?DR z=O-J`I`~Yki+l*e*$ZOQBMsFqhRWJ|gMJzhG1at(ucWu7ELAc75d{ExqFk30vF^#E z%Ryo%$YMKm(+q<+YMpJ2ke1CHG}k9+u6$Oh>5G3*0_I8t6^j3zVZE4hL_Ocm^WJDY zoXMvA?MjStlPlUIREe?V*sCfr&=_0JKIPO!Slp=+fms6&-8RNF3o2u9CFPsw7Rl=^ zK%-db0&vb~=rQZz{S(i`Koqmb1*oys;^52`Xcm#BIP&>|dHY>^NQ*^@EpdeS7yygQ z``RLsVsEtS$1O^j)-ir0yvUdR7zo7I<08wCN7TH-9iVa=4-*yYGV(+Rt4ls^>l1}Q zNYa|MW6ozh3M=CH#hZ|{k^B{^^lhU5y7zq*1fsZmFR{+%Y>Gp8{&v4xA&Rk6?>-$I zzK?GS*DDfcaU{D9)Reb8B@WzNn*YN+Ez|vCk=XkNoC(7q)&3s^*i(!UI|d<6?BSH->MQJB1U60{?7eL`Z= zpf+k3q8yNAXVM9JwVYUkxWxELzb}1XfpwF+9_&cdLh(DgX+eHs&JDfYpdd1$%?!cYv#ko44wURi0XnG1M4 zkVYEX&_xq{q8t|E8j~HEFH?X@oIs2U6|d2Hx5@f5>xiO%W#%UlvZ|~8zk|Al@b<6> zE+ocz#HAJei-)-V_b`PuDy`c!VhChdvLR?iV6W(jESdg3{z~jN+jkb71>j- zvCqv0ceJ=;jWJaxH`~Ut)BPyzMQ1lG-5vfyrl0`dsgNXub{L_~GJ#M2CzEwta-Shi zoaTT=kf+@4sOGq(r|hyWGP(}Gc`z9N&umHAAo2#eI_24ZjoOSxTKGWBs`sj95R-xE>C^dy{&1aKqQ;{w~3Hxx4oG(M{Ue)T73M%B8WZ5F)w`h%)I z5`NCOcHPT@`nI$RHWT>KZUb(H7yxq&mMj?TLPxHwbivcYqEZ#?TPYhOw`7hb1OUz5 zMY8zb(ZE*m4QR5g1EaJm1rNg`FEJ#S%9^7c$(Ew{IUYUkLCGAAC;z+06-ug|b)OEi z*RvKCN9w!<+|NPn?e}U9Vz)Em8@zB{$XpYCa(gwp{XqXmcB+VPh)u)2p=95;UpF)o z#@lA(JG`780AtHTxL&hc=G(WyOOBy2{p{B2m#qH===^T9+^xnbHp`U!BEVupMnc^X zhea7zwo%CUE z(iU%CTzx^rQH7Vm$=i@bGm_B1zCG>j%wW7N6{D#UE=>j7; zRmRB*IW*oVp?nO%tX}_oSP*iFkSxvFTx8&)`!ku&LOD4dI8sfk4955;Ekd#0ND71& zirEW;Z?G9_0fhnF?>9kz)lER(?wwZY(yqTL%O_z>wM81SmnB^#2GamX%= z-%$*^Pi?s8p^~^&0&Bv9b3=PZNY`s0#M|`YtoprF;prb?|h@u4$comg;CJZ zCm=Px=N^A5M90R8d&-FtiOLlrU{qkD5U5fg_#55(C_ZZB8xd&Js|HO23?g+ORbnLvv#R$p#dp!G#$N1 zBZDOPl{g5l9=h&qYHM7mPjh7y1SL~7MrglLYF3O75z$KqhPgA;fISFuxh(@s&SmhM(W(z<+06K;6m_a*jQ{$)0zNf^)wm=3R>7WfYtC)wmnCaW_= zfbLM2uv*jI4Kr3~!v^bl`odn+CG)AL&Din&qyG8+81!r1uTm_ZPG|5i&s>N{h z{8aR65&-pK_6(+$4_Pf4xdj#sXbDtu8VXN=E{z1>BYp6u7&*v79g-Qgs08ZF-kdfjX6t7 zS95t|w`{G=8H){%=R{a$J!1`d>G~CU0d4)~e6m?7^r|b;mNY_!uuK{O$=HNmhA7op z*pdxGdJg{ru4tu;8RYnpbT8s5KtxqJG^3H3J&L>lYwr@Yg@~Ox&gFWh`ddfw1jNsd z9v7>nu+~I~Uawd;i3`rOqNblCs0A9x)|?w8{G=^j^m+>m2!A^b(hAdq_I1=+af7u< zpVj(7=ILnOaWy%$yQI6Z7=N1?OLjMY#C;j-d)may+8Vm#+y880r>f_bNueW?hs<)O&G-N%E?xHM=j1{+e!z2D$fO(EO z?pOvvQNEBaUtwj-MTqPSOphDMH&WQ3i$j z)ZL$O-U}Kz&WFOnw=E#oqC{EZ6XTl>iO0HyjAkj>8Fa5I$1z%%WHcdTpXgZO!_eZ< zqt8kg`L9+jg!KIGqPF1@pr;{((cAq!g#0%n;3wh*j`T0&@yq_jQXsX(P4$i}^eiJ( z($PTJeIy!?GY?>q`x#ysXZc(ebBcOd1iW!m2Adbg^HlmNutb5NAd0gqqgf zz#2iPcyODbQ(wl*RRK=nZ#qkZYZydw*$~1$`I#ZH#zWN<-(KJDx6ep0;Nx}CRceJT zFnqApssVTWpaP@6{+LsZlfW%nDLDuM)~@Yq$Z(jB-;2hq)USOML*nT62k10GY7=x1 z7f3JBIS;8=#H|Q^;dtj5<%MiYe3f5t_hKN`N~n9ayq*)5)~U)=EK~!XCrj(+IA>H? zWhSh#{_y!=;GG>x{8Q-{*T#-zY?f z4LqUmF0QLNCt4ydhGidfO3LM&Sd~W*94?L8eJf%QSM$SXhuw;w7oZO%fVA-Zv_*KL z%KjM@ZbT!IK=auPqm#17>JffrRr6Q)idN*i1~bt-+NGR}A0@!iCidThP>Tdfao7Tl zu)xk&;j$8reU@)oEr73b3-{W2B}yiCm8A0vj;N&$6>*5D$olChuC3`YP(;6lz9lZQ}wt$P6PR5H=FYdsQvLiFiHs#-9 zml3pbUiKNt)aGhhej7KmzFa&*z{gbK4dAjJ`sP_>>b>Zy>Q9E(l&Th0HgBsNNqNq@ zG+g3x%UIT@h>F>SuGcQP&h!*^6`BGIl{l|nLI$)w7arJq> zqu@{tMq*l%@WU#24Ys*=0W_h0io#(S!79mwe^L@30g{aQqxrF->)THZ;`}6IU-uR* z+%~+_3`}|QN-hN~justZw09!HZ@0OO+gvR_%RCq={Nfg%K^G*K)py(vD!OjQKk3y+ zbJiq@3fsT*F3H9lTwm5aWLn-ein~z3f>yB6?DHrr#P$8b<;7@tVt*S5<4}H+cHMqfws6N0^9Idv9%@#)YSy+OQC#Oy)#{9F3NHik(Bj?*PrQI4H4~O}u}Xb2%g}6fPo? ze`Lw9!ssBMC;gAF4@A`1UVWOJ4q!@9JbNCVk|G;DSA)l@;!wcTUZaLuyitTWs~?6R zGNwC>2pA^?qLGm7PXfuFX_Czxdo`xG8gnqA@m&Z#yY#r-YUeTvP9 zk9#?&l%bo9HE|~uN16@^D+)}&>Dbb?{TdCmOq2M*f_iv$do2vMK%z9KroQ2iZbt$8+IE#9 zME+|6KDrUU6moollF8$8PilAIUXP$ex`42#smxtnBQ1b81nR)_bjR$M^1MCrg+zjW zARRwUr!5VEVi}*xG><0;wbuuj9;W8;&>$X$tYz#95?%h|1rK$*8a&LA4wgBa0<(Iy zEk4nQ`c@6>ya+(7Upz}`u_;fvdV6JBpJq+Lh%o2YYFCuK>4MhDd0T$$@__Bof*s^Meg(3Jxa` zYG8v7TO{)h&gM1ZTzV@UEpF@}x2do-ptlBh`i0`tY%wrAqs`c zPvd*kxfREDITVotAzOh;*#SfG`=nE7Lr}{XAS;)kp-6|n^l-uN50L(rPXhupenq_7 zXoXyHv>?O&1**r0_xMENPo}dW$8K^OV{J7yx*A(2!|LP9nn40>lY>(HubD#NupTeJ zD^xV5OJVtV1#L9FDjwydup9qSWB5F{uO?Vb* zE6q^X#-A6G=s<3RTsr>um)nmJq#Oaf8i8N-I79R6_KCKLe$YD^DVsumIOU((kFLRy zpFv%Xegll4c|Q3mA9r4?1GuiN(Ibw^WPk7mh}9wFG(}7m@(w#)mF#~*JnZ5r*^?sY zZF2Dpa<7?=EYr`rp#)6_2piMOq>WsP)K`>sVo9L_R&{8)Jpug|l{e}9SzWxO(ZjRl zD_CdFa=E?-TfR6pVeVagUs_nRjHeKRYZvZb(~W6>(T)#g+7#2Yf`~M)vgH--7R4a) z3Vpeb>aP7Frh8yw=zf=blbCG)W|s$ zgwMpUmuGwif>S+*D#AqIrf0uCs`b9AH)(^#u6jovND6yiG5I#s+zHpsVM#+cOgA?F$4 zn#8FsbYhdl7KRTCA|Om})VS3WX)D-ISk<2;T-3NGsYur#LN+`7x?Ih>OUT(TQ~q4p zB7TDbm2KO^`!ol^@^Gx-e?D_5wMzx>R>j&j6D&JgQ+~)UrfBJ3K0?=Qw1!wcK$`^} z?9l@Rqj%8^CDu=EoyfOE zBh4&jSYYoC=n|af%X|kAwla1H8Wfqy!h_kD4|KvhG9#{$lpa7ArYtI``01Aea! z&)BCd7d|XhM^n+WEKZ5O+rOCQ=z6STgG*cD;#^Ou&n_w9e}DbQ9qL0QqzTOlg6KlI zS#|vABRJBHu~HL-froD+3S&=UYhR(^>>my`5~x90zZuWMR2Bclrz36@XsEbU+;5}o9RUkPW1`uKoC6u3A9GcSjV)@jtb#~L;>-uw=oggbm>ap4F z*Sxg$;;lv%Wz-477%0X!qoWX?OkMj>1e$OFVD;^croHFraHr;FDmv`xJ9!r5Z?idl z@pQlLB@v)M`>i`|+X)AlScnJ*6z6^c3$=jrb%9)*e_x^!yuT;-wL8LGg9sg{sQ5FP zFc373Lw8O|X5If*4bR)#ewD!UroAnds<<+ZKv%KWUA_d{BmIO?rBs-f$ER6{%)g>- zsqBlw-6x_r**~sE;DTmxU4kZWzukU8{U1MjyIk#_W*cg%a3OkA_7bmr)&^XnIyIsN zAfS6NAHm4k&JK*cDfT7neL|J&144xffZmFvI5LBjkl-RipX%oKE#t~!Sd?>r_IADA ztbX9=al&!C>aX{^VGX$0un2XGU<{62t{CRU(%Lq>L?E0Z0PW5=+i&MHjNMRSPI)i9 z{J*1FL@kT6#_6h8RqD?{hItO6ejLoC<>!;>3?eCc@we0uydSSAFp?5`T0<<8%#hk$ zmI{c-tlTjI-2i3i%}<*@>`uF=chR}AM72fw@;BRy_AE-lFp|O+({RoS(S05>$6D4k zWks+J#?AEVKh!@I_&{ulkGD~re4z%yy@rbg3P%<7EeUUv6JbtFf`~ZwMN=(884TtD z^rjuNY_znjC$r}TqHf_q((zm`^CD1R%uY}N({*kX9m@#j4q0EtgrXAwzv1V9EO(e0 zGkpi63E;Rqq=@o&oOApL13T}5_s*cfGs8-e$_yoG#UB&a%huOB5BzTM?E!l!gq_d- z%y+<}|Cq10S`pPVQQ!;F@v#*s1;+)goneP!?39ypRFT5CT}eN&hq;zB@Oz=qw?+^a z>m?AjGYF`Qm;!$WN>3B{#M1}MCa_#*7(KbdkUC0oA<(k^dAPW!PZ*hmKJ=8aUtyJ? zUx6@yKoanu=)Y-r{fH)_iV~#S^EEUGQPhJ_PBvV0L#Un6iy9VwmKzp+(%)69ZYd(> z?+}M^jS2Ac)oNYJ&Wm^I8Vk`PRHtNbvyOA2af0z&|7le_I&tAHrA%gq(rCR6=hf@v z=iZ(pzu4@ybmjD?g9SVIt|wte0}tIMS9Lx7-`B1m*0_QFaDZyZ#-T2rK{BmTBu5F! z1vwr=AvGg_B7jyd6#HW3K~e?UZD9|nfB$Y2xWYr;F);||V8|1Q+y_M6J$Xyfo7w;3 zv+z80GUR)T%v+RA!x9696J>e)-P_%K%Yi(J=U8PiF4(LLN4rCrb1;JEPkfD;o3vrQ zVOpJ{m3tZ}!TV+)Mr!d-^X=DflE+j;YPpQYGn1Rf}e7@VQDT zlOzPFl$NxF+%f4|<1>h{RRcm3(7^GD6aayb@V->wl^5KRLy}N93P@c#3s1BN$s4S} zYjB~YqJZ3bv(o7{Mv}=ctySkn#{mAezh`Gq=(dJ>a& zjiPvS21*hhWhjz}b;p_bNEJGC_#Wd>JE-<=fU5|W6u7GDLLzVkb$qrVb-))Gx5k%e zrIfGBKf!`fX=ce8Y_O%TR*Je8?@Np07KM9R-0hE8?~t&Q!KJh?L4X14akt4IX$qHg zSoz1}2XilriMtt=2MPsRP>;%hAS|UI)@%? z#5M4AO+C=kir2wf{<46&X~7CNZ8#ZDY|@&B!zA0?yV_T_xCnxl+}vGl`U zK8?y|N?I^SS7d_~HNxy7-v;ZV3}iXuM`()DMU@JI9xzJ>v>O|7%X)=@kr*=$J};>! zJM&fLHgx0ld9?fx=n*Xw%?AMW8bB1{2YfO;|Hd867uKF^bW;%*iA+y1k`NFsE?NM! zbc14evDag^SHAoIs{5KB$+GOOv<=t@felz@FqUWuJRmHW@L4mPlS2!3qf>@dv;PhTr+R z@7()tym%2=HQg@FbYy(Ii1*$-_k8}&?>zDZ@ab?i8K0naN|KIl14l_TtU$3#(|8f- z4}03R!v1IVf;AtPskF3!sNFPJFki4$5ceX^9RmUT)V_0y-W?+8Bg^D)ODq9;2O?z% zKD7b)2TvLVKv#jT-{Jy+==hvrKwjj02dSCO(mEakqvaMc)6>~NTiJAx?tDHa7Oq+E zX3(eAkLTFJ3XjoNTCD>i#(lLIvre>;7ALPRdnmFxoZvd;Q4vp>;Et*lH0CBF8$8+-~;U=m!_&z4V8YDqXNF+B^hCwS^W=nE3 zf@yK*cZ!;&>fD&NT$g1HA;{HyF$tVcHRA&POcg(7)NFV5v}l-CSt<0VM;o~;p|jKu zw@`+e1AO#+&hz;)Tbd_tymUdw#Q+6JxpD)dm;g?03<$$`~-_^8La1L0>7Ttw81nTjpA` zK9ua`6#gc^W{T5c=6LxM!|qTX`^Zn6cIP*SHSk%FT*hb*>@0)P6@6=vnuH91w1cdh zcOeTJ*-Rnh==+n|JnaX<#bWV)0uXM}bStT8#vHKw#ts6 zIo0gsqZr=f6)JZVbc8n9(>qW;I4Kk+MyTWp-|r#SH2}Q0qH(Svz@=0H21E7-2jE)3 z!^MR97x9Vn`QWSNq$rnlP7kApFQ`xP)Ob>oow#(473-KWnl?)nEr%8ra-?dJRPfr; zs>{oT@|6Rc$`=XMeckCV#iYpwY_ProQ!KaulA&Z5*Tt<2xtt&t(Mn1`X}Jcx#qcNV!a_2HS_rX! z=pb{HB}>AYT}uEmAqj=%v{`w6oaz1YL=`d0Hwg+hAlaj2OXK7oH6wvJ62;aT<>fli z6t|daY<;emhysy$Zd;qI2pflnmDX7VVPB#S@FmZm1`qeApMwGp^Kc>=+NNL=-VZ>E zybn?rJfu)-abh)K9Wr7`zeNF}7QsldI)dXRKV3wM$a_r{H>j);8Pce-%?UF2G|-*Y zZ8ST0IGj-_hECRLpQ6H&Z<_@hdN`SJy&oWp;hY4=Z+oZOb63~elV|~Vh#`;Ue_u?l z(FE~f$0U}+5JhXmdM?5jq6=M(Y}K{2kW2!o1XaRJk(y|ZoZOuKvERsqV&qt5yw=e5 z_tZ^h`KQe{nKP*xV|__{+d;TbJiebh7y-$PlwjDKzj|{aEW{aQ^;|aMLN71@lGubo>FI^ zDvAw4r}FlP8|FAS`pmiE5*$%V8FB8$&NPE(S9|`^?@WioSPIEpO{kPMa$1Ia z7r9bd4&W1!_5s%;h&d^e+&I+YTHU6YJ-VM!)*;NhpzRloOx5?tyB~y#54tX<;N8KKEP^obUdCeVkCUFgGeM)-`4P`p}xAHpE60i~7Ji zy?^V5+_I~{>=EuIUtm-RV=y-j!oZK;Qg;S)Wa(J4Em+@`*@JY`#H$287kW;edGI+# z{xuabzV@d~tO(d>?(4 z$WdgagD9?lD~dge06K&_09VPpGr7u=WqCd8^+K^Nj36MWRN_)PJ!`4KJTKQ$BLQDD zkc&D6t?1NLH(NHxAaohvdmjDF)2Ny#>75RzGy@@T;-)R(UE!g1Jeg2MB-3E6iA@)$ zG-CDIrKkb3DyEoL#mPr(0yl}C^p^Z)tEC9J?i4-*u&vKWLkQFieh*|F5b339S}PFb zz3pn|t>SFglHxj{*!40|8j`BXrK@rqG4+IVxVyL`N^XhdJCLDQV#s9ZeR=P4C>w>> zz%r9>eSn)kI!*Xh-JU_Iy?ZBZj+?mTWkj*JHVxG=F-ifYvy6QT z{BHPqVvORl2z@qBKDC^Cir&dnPobB$EZ-VFJZ7Ha-hMD$zJ&%O(N?>I&GQrJV_bji zs<*DGGZV6_Bxq@3m1WL@)UeG5-Kp3R)xU{}MtD5q0Z(RVTw3wlm@6Wt`2H37TRC>a zTGhBOaGYi|RjMY3vvGHPeC4#RX({awnBFXAmub3biN74tLztrYNx=^Y>4y;Vk2(Ax zs)6QgQ;YzGg(uriRZhyF`_=&zkMMHZXi%Mnqv^ZI{q~(K2#vn!4lt`7G^okv9U0t+ z50W-C!y8#8s)G$j;OCC4Qp#eAj)9L<0mR-d9jfB9$@mEEm5gcg?`%>_D06P!cIVX$ zOkN~HoG`Ffj(v5d$}fzNHJJJ`=-nUPEXMC%VJ;!Y6`c_=3+`u7)=}}CKz9z+4on+t zpE_qXV7m3gB#Qc1bsQ9{Q8;CG;RauLQ<91#I08WVmf;ATHwL1p{;=4U2rRHMp7bS0 zOm9lJHsldR;cpNPy#4a|-5pn(k*%VH)e`2$@;oC^2D8MFhf5+exg0CR8ItcIsz+Y< zc?aBrl*N6G=cg!Ce})`xZeXypJC$4>^6YCijm3>x7Z?62lznS5V?-eSO9Y6^F+kq) zNZJOHM0)T3()%AZ`z(X|YJu(e4y0lz{Qzd!e?Gll5XR*xEKRF@~Jhh8?bUlyyMtKOUh*Krixzhc5)@Or>K&wsFm-w9~chbckeGd^5MK5`s3_ zq~?ssuhpc)GKQi7rajhG-_9bW8Bx9AQFgDiYn!jsief~gRf_Yu{u_&ij5smv{JL!b z#sx)Eo7*H2Zla0}gEuBG3XF{K#!sAdQRnX;%04_jc`5pb_G+0UWzW#cNR_zBJ9tUe zzGxwee>3b&Cm35iEpw1~H8V5SDj5;0*8w%$Aiux}7cDng?gZ?vlkue8`J#m!uTZr0 zNS(CDlZQCqdsZ-lPSzn{E%!CgYCD=QEh!1wdvd7KHwH*s+H0d5B2ASXj!-W}L_Q{( zRc3w^n^3k)IdiGsvBngS&3N(@x1ntfdVQdA0@FsZjV2m^`^Sr0iXIcdmx{CA3)}DV z1+_yk?OwVxt^zTst!0J`@UZUymZd0K_hqZggqgl%kz`ggt^XCbMVuQX&OqNgIP0SG zA{4+ON0c1}Qz+3=vwM?i{Fn2OTvWmxoh`Wc1KvPCU0$p3MCdh4OUH1%=d?B84VAlt zeDDV0NsZ;n#3+Vy#9NWN#`4-wj6a)*LE(L$0ax%YQwcuQ1<+=*PJjEWnB_X=dP8{^`kR96%lprX7QicDB5HWbnR z=MdFszl&rp2%oC^l_&>pouamUX>lszK|;23MmYlN(U5Bm;~^n-A;LZEVE@cf1^jA7 zB7v5TDUWiKYTX$}_l25sSkD5IL4+T~2JbNty}IkAsVH;wR7w6rsNw6`M^c$;d4fihdXnKorh6ommRWI@?8F7aO89S! zm}~pT(?I!{IDfZ83g112O^wCM#7b60A_HTmCl^!~7kft^a@rWS0U2JOS1j+?6ZI?x zxh-zTGn8@yqQdiwQFU18#g01Y87O0fBGU-HOJxTEPefHV(iC_(RN2bk>S0@h^(R}z z#_Ow5Mm-_D=b>$6A8hBePBf-|H2xIRc|qF>ShP?bOK}STc!vXO2W1)>Rt~t^1qj># zg*FK4!G4D+EbP(scsR7~i|vzhI9|}Dld9>hj;4E@!93^=c7v$W?42>IQE9K zmxId%F}*w|0#voP`fg^MHt$$51@6XDU@8UW?yU8m)vzy47Hyc#(xS0=Vij^mPQN{D z$dV~?PnaSx&O>)+;I4BZ(p;e^1~EVwsNR3{h=Qpz-VRlU;V?2V(?@EFd1z5?Kw+wb z{>g0ek~|ilB?yU=5U@whk+Drk$ow{P!k_ODxuGSua;DG?UGe@_R8iQED+=8QB|L*f zf9&EHJTs2x;@t_5+zZGy{+X6bHoP*(^d=LOo+>_g0~Hl-wj}-QcJgLb6NGSd@~~+u z>nGG4fe|1HGlAbop5c2FAt61E=zRU5ucXvOc~Cp5bWm^X8N0<|XR2$RJki0^=Qu6L6sda&@%84=rc>x&2->8*#B zSP~g`KUJWi@jcM_=a|eW`YTaQMKKt4?=a8kW%rSL6TA~!X)7<<(uQYsN%obKUxy1v zl&xT8Lg2Q1>b#pQVpb@rWjvPmY4h~@2dQ7Lu2sTqWE~m>%DYSq!iJXKER)RpS18xM z`8zLR+JyRj?OYF)a!XilhCs!zOhqMxY0tdj!IQysI+?~1vrDLCJL1aCQnTp+G zi#uA|xsgyoh>8dSu#1p%GPQHpGjOg}3*fqOe>C_UQ|HIS85pA!2cz)gD8es59Cp=( zAOCzrzAE}E;xCTQJ!MCFy5&Rpue91~JwnWa+z!HK$z|ZbC_*FN#Jp{EJK9O+=h?vX z!VGxS;aSQ_Q4g-c6T)-sSRsa`$vA_4RK+pR*t@-pH%g9IhD%6fwXBGR(Pf*NU$!q$ zqp1BnB-TZ45b6>%M4hK_h~id{SPK@#!6k@GZfM8`LNv4lpjXV|O&c;exgs5quj=#7 z^#-T3>^mqwN$ z0K%5C3J~YpdGK*-NpUE44T&wyeaaYFlDbHx^HyzAu~-_(CP|xJGkR+f*kBRhm7$K= z>n^Tuz*1=mhgsqrv}m~!i8u@r@!8}#a?6jiq3cEPV+%q6&_!p?-8>ciC=WMRRd3|LUkANOEoTDHJ5G0*Br-8n>c20h}C_lVnIcB zP&LaLqXJS}AYaF#+di$&vGVIW zZ3rRnxi3l1P4SPsDX9y=dMO8cM>msUZ@{JkXyjbC`x4LEZQPiVd-s8863*eS_AoT* z3QT%jcG!_uD3Oz??xYKywiRc~K9GG%ldmrQ;A239z-`dtkN%p~J1nxug0+y>DZyGg zfsu3hPpjh~3uW@#z#`OW=8Rb|)r_~kNnFh8Yzj0auZcM3r1Mb+Xk^GOL5+L*dZ;dd}KKmvf? z_4y1_qo6yj*L|6jN3A)#5}2HP_VVP_$*Z^L{DU!h4@Mb2A3tiDqaFl7Y|Zxnlrf;1 zzv4hvs@jcUGo_cdjb_?4c^&2UI{Lz0^mSwE9=_>l1U4My1(1)`L16_3>)2Z&rhn6&UJu7IiNYdqm%T0ykO(|lOfj;2 zPKvvd=lJ3?L(6J?LY;u);prh>8N%i5%uj2>0LTrgq^sfe%b{x_h~3J@`K;E8 z(8Ty1Wh9bU$a{TWDViEdK7dQd#X+B5eaJV}nB`1I5=;RnxUXnPXvksu<)Zp?9DEcz zaUP${NeS6XS+Lov>(cl-Y{??ggfO~9%uvi=c)axIlk?H$uE%(4U`Moxc- zqOlFCH4VbuI$?RzEpuk60&B-ymO<~GYcs>WDyK6~2bbMZcibCvt|n8cJ0ypejBh?W zkNDfkSC;E>vD^;leqP`U-%+B+N6nF_H{ETqHTLZqt+tMkthCfZzqpZ1OOsE*nv~Hj zPj|9#w!A*{?OGx`M2gXFiBb(kBWSZtd73^DRv3ey=^?1k_D=chU=YJ73cidIWX0xi zjp5(szBJe-@j4~JO|xM-rMpmuVus-_FD%YY*-FExHW^^GQFyZ9^s3t~;UvQ1w4Uwq zMPzcN2eUEHpt=G@1I?fRE&AZb#-a?;>1*n?cxKop9Smegv;}Ljh;`vsnnTp;&JJyg zXtcmOWgjcyQnH1n@S=rDoGrP}Uw+wXKihd$(5)_as)nPp!;olewZoq(Vfq3S*9bX3l$tP*C;0vj-VWAh8{pj8f)n&W5aIx`tpaV z3JJ%Eq1|!<7&R`kMYB))sdv0!H5Ue`Dsh~>I)C#VNN;LJ4~~fi9%lV?tBF3-naQ^P z=|-t^7=V~sRZHAq(7>c_EI6s=wch1Kp)o!lyMv_AJQXXsS4E8?#|Gl2H>OeBcJYy2 zYa|db&a{UeI-{XLSHTvy4`{V>DM#X3B!b+@f<)pH&ClT=HQwRw~%UvihbPrI=JghDDJu?FKr2(Vd*~`sRWTSls!|7 ziQHVIsz}P-J*$z*OfXTaswAVeqU7PhJ<(hMaw{Km0=^!t6v<2E|FsHoWt!kH6$slz zPG~cU$@3U50;A$mWGMU)h=J4lGwyv33F{ZbaTk*ZF{J9`?9;2WPlv}1sXfK+lwOgK zGi{5gg|qBsEt~Qa7rg9GU@n`#3+wp?RK7R1c#Q(EP24YtK7@bM3BtT&zAP!+j_WH^ znb?Q_VhKsS%SZNywmi^j)4BO(MvH4=kijT?^-f?}B*$gL>d1YR(4j zu?>1TK(z!2GLmlRAhq&i15~S%w|#aAM%}?6MjJFGybCi*5R_y=qt!8DUz@kH{ z3@0E9y>60~=_@IHcASF+hK#RAqlQd$-hV=nfUY{rMCP)RB)wnYe(i=80nQaX4msk! zW3O205>+dOn7ZWNj~sJzkkxrk*!>(fK)-Ok*p3Dn@T_ud1k{E(%@x<4I52<(0Q!ZQ z9faZf^=F5j&h>b~IL=n*H6_vRCZl2R@wjCx7;uLLYcjy~+xY*3GYdb1HGVZDRa z54dPrw3Wem`}nH`h6kh($A-Qm?jD9}-3-7FjuFbZ;V1s~LDFT)W(hL|4ekbdH6UNH z|40c+m5LmS-A-qMsa%*ni2$@idzpU=bv1xkU(x?i#v-At3-opb2Y)o5j?xOTWukAX z$ACg0ktDwP%(~2i71l!D-9OQ!c>QjOmx8fU%wp#!RItv_9TG9IbgN7(UHZAyn1vpU zurYnIyVy&!+~zj$_ap?AV49zg-^Tm9E3^pzS>q`wUbf;{pnryukrOB^W z(&_BLfJ_+xsu^E;dO0*?h&ivKE*ob(`R83Cg0~@oIcawYr$iB#l=yd?cz8ra(PnP9 zv+nKZ%-*w!^qw)vH(f~SADIQ`%kzjL>bT}War1cYX;a>+EioI_tV+puE(1+n8a+xU z6;In@*l;|6iw;~ns%r(t3W|iAM08qa$%N`f%UZrj7kDv8Yg4FRn(^WVi~`h_AF^_a zX|p+0Sg~geS@emr0ZmOOZ66wT!DTVxIJNnx|2WOvNu&elmw>PBLVp}0S-Fa7*-f6374JjSFU!8NS z5V?;u=r)8okth}sWvjq8)tF}bWOuX^M7dLnoo*k*hQM@ciXZM$@Buc_!Q?d1Fhi1$ zWM81FYHR}p$gfQJ#Ls<{xYfD>kEs)X$P-AR^TGZ^SnLjR9^JRxz^B5gX^4XnQtfOV z@3&A_FDtv0dqiP;-nj!oQ<9MkE0hGH$&k`2^OQOs5d#2qypgYRK7q8m`7Z=;sEZ@ z-D3WVA`!=!=Zs_fyf?W+q#{#35&oP)880!AIfYehOVCL$=_GBY%NR3R6auLT9S7pN z=GYj6_-J8W3mm+eqP6%oj&(6lD{k&D5)@#u4HWSZ$wmN0F$NN;bb{|FQg8xyk`o-x zy0kdwf$?C3_(r99m!F@!9${O95t#o$uJ&e+x0jPB>mTl>u_Zc<@5@ug4*FLdc6GDD zZAe&PD}B?1N-8k6rOg^-xtlo}LWoSaoVQf$v$wX@%4yDe#UMxB09^H=sEzu>+mv~R(vt)C6-=E!?VsJVW6K?2k$^puywXD?m)dM^wF7vpF$$M69u(&K#umejsxs02XG zL=3|)KvEpZMX8L3oTufV%`i0(;t#pV*h9w5p=TDyp$X8m3@NbN%BAslELY@!Stc%E ziX(+)Dw>#5cJrv9b6%-T_f_aS5B9cc(d@nlG>EY09F2zXL!E;nE>IFx==}}_f%vjB z;deZj>A+ty?%@&wC%tel0}+V>btIr8zrBF5Bd>Yq2n^I}qC%LqHX*Tg7OC?dT;})^ z+Y;~~Q!5miN!NR2#KKflueClAaB)sF*Z zi;=TXbqX2-y|ds$M2ACfbOLbB@a%%8xIaZ^Be+GeAG}V^EWkxm-P{hjxWHq>^6Q{U zMO$JcYkE2 za64wUU6+{z*qO@M%@2t#hu2MmotDkXl=H6H=2d)b^Uwl&_rrmq)b#A5K)@nYfjoiz z1M|`&$P*EQtcE<9UlBVfOFb~e8c5#&)(Cn+LNf=e7$09~{Bbg#PiV6V`~i;6uqVVH zTwW`7+0m0%IFm)QPB$?l*vsXq)ZvMIm`K8>(R;FC3k~3HyEfu?d72`|=?8B(m#bF^ zD9c2wAq>MxN5c_X8HCr!dVP}N!{}Hpfua(+=_q;~B;+4RivBaTZ2FrhK@RLC3Qcd>(UPEAwlx<%0EA zWu8yo1A;*KHh9S>p^PUqwuT|1NnH}(hv64Iqz%Ac2OScWfW9jf{i8BB=;fqP=KwFhCQ?<{`X@V*D--T)=t7#upFEZxk4N>g?uK zu~+h;W&R&;K?dom+l@`Z#>O%PUJ3dEzp64UFXDhz_6?~zPGd9KeyJXVv{>vWssI}S zx#3ciB3HRToB2y%RmU2f zR(bu-J~p~^O$)1J@b^%$a>VvXip`e33z>{eS4b6#N5**<;^ReKREQA<(<|y=rz`*=db7ZKey2eeASG_K zEI>3*dwartTTIT1zIph*Ey)00fOm{LoXj=*lHjE=NK(Fi zx_7o1>I*c%ximt%WVlY;)rY-Mm(|0`_is5w+<%3HCLxGVCxCQ*3d~q~&pl#-n&~>@ z!NU>gHeSGZc5Z>UL#sMk7HGKYG5YbAO{o?4%j^E;l#dA$%fpng^T7l5Oe}>rAguCZ zj0l;h>e4T@yVcD@sQEc^TVrHhtan*)Xf<-WKX4Q2f=?2w>|L?^B|#^zPbOgZQiqy1 zPKNf2sEOFV(Zz-iisQHB#aj#3oba}t;sAgvN*qA|LK71{w$qpCGo3yVopVgmG{mRM zvY$_hAEqR5SxW&LONR>TK71sR3Rm4oKv@XA>L(1h5>D^0sKaD?%`s3}rjO8~A^C6{ z&1_x@9^`2*0?s5^P&5xG|5%Fx=LSpRlHgUabffO6Oens$xZ`$R5n12a;C6dm=B3(y zU~wsyzKp8YqY)*q-ilSG*vK3?EZAFUcPFF!CzZw+b^7G^AP==jF-vShIFWTmp`Uo{ z5%b+akWYK{t!Ao-8|9SN%hwdqsDuXD|MI?s%P#e_&dDrUEX@6Ln#F5l>M!W_vHy{1 z7h~i;7`Zl-_N4*Xi#yH;`a@(9G@LJBrUzqD3Feq*IFwoiqIL|F6E>hQ$f?yfwUNR- z8K~b^sD?mrp@y2{fDEx+tZyC2mp2sa`WPE&`^EfBOL~;6NVd3p z{d_d+f<2d=jz>-!kZS;q=eOBz=Y>q!QBWJbTcRcq#DQH2K8pZac$bwsE!SMLYZ}e! zf$WZ~d6Q`?vp415)Q@wnC)6xo9B7n#8ob}1r_gl_s^n7$%geIo>V z!czpcF!bewaj2v9it&Os5I^^`rj)WyR_e_QRp zsjnK)PQc7~anO7MD_C{s%tWpFftV`N{*rG($O=C^hp2&PL72Jnx^utdo1IyEZSoTo z6tu~itB#+cTEHM}h_VVtWnu^4{ktA@U!fHQ*;BORl;;l>o|w(xr0F+CB4Vw8?hAYf zvX9xzR3#NikaL2(@DhU|2I2NEs7Vc(09>iLB1kxJ;~FM{pkZu=?#zYsOpEAXqR|9l z*4-n?nK`2RR_bK0g-MX_XdUFHjGAdMDPDF}6pteG#xxV8d=c1yUhP!G*+pcg>GVsx z68xp5S^JdfL%Q3}gK1o;Xtz1rPk>;6y1;1yfWlO{;3amW34<}^d31S{Q>YycZHv$# z0lA(-@5b^xk-)7%Fu;{7I7u31Phmolt(+TMzTEzmMcAK=$@2hki_6uKojF}c+kuNB z`reb(-3H*g9qN2M?!`qwW~o|QM}a=yy+v*Hnp7+tClHswlujN{QVgW0*b2q2Jnvyp z-MouAYG`(&p}#!gfRc-)eyVeT;(fQqEF6uq;VAar!BT_@mYLq0@j;*y^9A8Ti6SC!wLzYYTE6qJDUr0az#;# zi=GCgowR8)-Te(cg5y0)y#TS3~Q8Z=jUw_Uw2z84XMoZ|J64?9t#<$^y+M z1*&SZf$uc%@~k&7eLrPJh9Z~qOc~VrUrU=P4g7BG!*;9emY*<1y;edhN zS-rOWhG-PF?Malx1v{knt5>QHr4ImRzCoOiTwj^6r(9uN2~JnJuRN6?U317sg^z?9 zH0GKE>K7^-%7WTp7h7iP!+0GcRN{f-BxN92*`Nz*4ngA6)iC}&Ky=ogf2aB6-sre@ z3Mkdad?-!D8KVaak!^xXErT`z)j5`rB-xv*QDxVeOr+%7TejH@k(dih zVrGsd^%{g?{0?~hW{c6BPRWMRZ(_sf_K;Klp;-U)x(+NJtCIU|j&vB;+QSKfQNd-7QlVRTzTMJDx%h;qxKud<*H(C=M$ zI6dk0xO!eJt)A064XWowhw1AAhQ27S5Y7R>cLhTBR`Ci?UhtC_i{S`7JKUf}(G#*} zM~L|_##Pb=6wkiBxlXY2#Z{be?{w-<#WZMBG)+hU??Xp z!yhIYU9v#;D5Ns^Ptd@JXpWKDy(=m32yISKg7Dk*`4ik2UNqvSv=Fi$yI5b+_-Hn? zl6K7|-d>P|;U5XLIw+RWfLf!B#@*!Ipa-X5Fh#8hP4j1*0bwIV`QiGR4it-mQVY=Y z`CvWhlS>+Wu<>Yp#}xZCO#YAp+7n0>V^2N_hiFl@NS`$va{+n&X}+MXf5qh(lC ztThRjqT1eJ2^YM@CO0(ke}*O`m~OmYO~lwc6^uNx(@{m1w}RGHEOY6=0~?axF4-vV2V&mNbA9ty3!PdhS-Nx z1|uCTNgSwij&hPTPWDuBj?_YM)_vH=pQ&z8^I4`TEcOs7Eni2{8ToB^HPmOF&qC;T zS&)ny!inEy@_sm;aK0Yivssr-yBcVRJ5{6SE^&x5%EG3@h{`Fk2fbPLKwK)t$QVMj z3+qN;)b16e2@R8-@mr}}5Z1C`gC_pI2+2OzB?yf8e)wmYeR;htA7mVJrh^R2cRkJjymX;rEYip z4z-l=-=D$DBYiwUM_G4#JphT;?1nN!^ags+FyFq5M2@`K=XdR`OnVx?g_t7T2LpML z62*A>r6AW{l+vw@urCnR^0i7HOuu!`J!3XFQ~dI0u-BUP@c-wyE#r6h?a z-EC`J^=;9_9KC=p%II3@?F@RiU6gyxl*xqakMIL=Jy|z#rbJm~AylvgLJbe0;3yex z)5qIwX~6T7934iQL=79tw}d-^cFq(QT1Si91#(bejYnWnjj zfLM*Z6=m~LG9SIVERGEVih_f!!xPwj=;Si?Y(rxfIa`rq-v)^kC)(hp%_o&)OE%j9 zZHv%!*e5!7aa-t26?t!-Oy%T>AV(rvoDD+}J2RQ{THzJKxk%N18eD@=XbCZrEJJiL z$><>NnKHmL2v5iv+_<6j^4^`+-8PJVsfz24%FlTq7x21ZT%ggnlt@(yV1 zW+3v5o^vaZDjo0Pr5M9{zclYvgI=HuIBk+CO-?+i{C%sI>#Nqj*N8W$j{nU+DIc`QgI|^BbdB^?cKmnb<*gwe=_l>@-}_tghCTkz1O1>rr1$?Ty#8Z% z{$KaxgZB8#dOddj_B;0Y+xYnZbI1RSD>>dCxAlW`{&er`{N+di)Fd*w*O_xk7vV`Y)Hq|1$nekN=l=jgGMI-}+6xL;6Va?f<3g z|IhKJKmHRv&K`f^&-Ekbc@)x2ru=BPT|3h;8@BFL3$Zy%>pS2I_V|xGolOAvDzx5+I-X8z{e~Z81 zllbY@e@>47o!|XM{)9d5{Jr>q^!NX3a{TZAFFD>GfA81Anei8y{MfhtkL38%U;0b@ zmOcKv|7)L=$MpCA4_^Lr_`hzmt<&#{WS{<$JpRr2@F2f-9zTQS`gwQ!dp-WW9&ews zud(O$`13fPR@{F7Yd!vJJ^ss2?MQk2B!0T}D>#_;jvfC;U&(p@QCA*+LvJ7LfBI*? zYjX5&@tXhr@66@6@AT#I4@o(?e|Ee*{%UgmTVKm@TX*`X`qaMS6Z=CSe+|deciH)G z{X;!&A&)nS0H?=q>+f$T-@B#9e>ZuZu9g1TTztH0c z_CbA2kH1)Q{2%D?uU8y@x#akty_fsfTXFnYk58}jhkE?aB`0i8?eTHR@zV$S{eQCL z_wD$9q{k;8+xn^Za{O-ch8<@w|Fb2>@9FWP4eZn9y4x%CeX)j-cTV;AyWf{z{2O@r zze9PL+{@W*ZT)Gy9%NSz<^TT2ZL)S-TfhC&@dilGpUgw<_`lu$t9<;wNe)P!ZvB7v C<3t<) literal 0 HcmV?d00001 diff --git a/setup/steps/configure_etc_hosts.sh b/setup/steps/configure_etc_hosts.sh index 0bd172ad2..e08f4566e 100644 --- a/setup/steps/configure_etc_hosts.sh +++ b/setup/steps/configure_etc_hosts.sh @@ -2,9 +2,15 @@ sudo tee /etc/hosts <<'HERE' 127.0.0.1 localhost localhost.localdomain localhost4 localhost4.localdomain4 ::1 localhost localhost.localdomain localhost6 localhost6.localdomain6 + + +############################ +# Instrument LAN +############################ 192.168.0.10 exao1 aoc -192.168.0.11 exao2 rtc -192.168.0.12 exao3 icc +192.168.0.191 exao2 rtc +192.168.0.192 exao3 icc +192.168.0.14 exao4 coc 192.168.0.140 pdu0 192.168.0.141 pdu1 192.168.0.142 pdu2 @@ -14,5 +20,7 @@ sudo tee /etc/hosts <<'HERE' 192.168.0.160 picomotorctl0 192.168.0.170 moxadio1 192.168.0.230 fxgenmodwfs -192.168.0.242 dmsafety + +#note: 192.168.0.240--192.168.0.254 reserved for DHCP + HERE From 18178c842211c82b1cce33c65f4faee8a89a1f47 Mon Sep 17 00:00:00 2001 From: Jared Males Date: Tue, 15 Oct 2024 11:37:10 -0700 Subject: [PATCH 14/24] fixed stageGui stop working on repeat cmds --- gui/widgets/stage/stage.hpp | 12 +----------- 1 file changed, 1 insertion(+), 11 deletions(-) diff --git a/gui/widgets/stage/stage.hpp b/gui/widgets/stage/stage.hpp index 706de0407..4a736f208 100644 --- a/gui/widgets/stage/stage.hpp +++ b/gui/widgets/stage/stage.hpp @@ -418,8 +418,6 @@ void stage::on_positionSlider_sliderMoved( double s ) void stage::on_positionSlider_sliderReleased() { - static double lastPos {-1e30}; - ui.position->stopEditing(); double s = ui.positionSlider->value(); @@ -427,8 +425,6 @@ void stage::on_positionSlider_sliderReleased() ui.positionSlider->setValue(m_position/m_maxPos * 100.); - if(newPos == lastPos) return; - pcf::IndiProperty ip(pcf::IndiProperty::Number); ip.setDevice(m_stageName); @@ -443,20 +439,14 @@ void stage::on_positionSlider_sliderReleased() ip.add(pcf::IndiElement("target")); ip["target"] = newPos; - lastPos = newPos; - sendNewProperty(ip); } void stage::on_position_returnPressed() { - static double lastPos {-1e30}; - double newPos = ui.position->editText().toDouble(); - if(newPos == lastPos) return; - pcf::IndiProperty ip(pcf::IndiProperty::Number); ip.setDevice(m_stageName); @@ -470,7 +460,7 @@ void stage::on_position_returnPressed() } ip.add(pcf::IndiElement("target")); ip["target"] = newPos; - lastPos = newPos; + sendNewProperty(ip); ui.position->clearFocus(); From 576e10b7d024e8ba09493235ce02d6bea9eb30f8 Mon Sep 17 00:00:00 2001 From: Joseph Long Date: Tue, 15 Oct 2024 20:57:14 -0400 Subject: [PATCH 15/24] Update pinned envs --- setup/conda_env_pinned_x86_64.yml | 229 +++++++++++++++++++++++++++++- 1 file changed, 224 insertions(+), 5 deletions(-) diff --git a/setup/conda_env_pinned_x86_64.yml b/setup/conda_env_pinned_x86_64.yml index 097a1470e..d6d4eee40 100644 --- a/setup/conda_env_pinned_x86_64.yml +++ b/setup/conda_env_pinned_x86_64.yml @@ -1,6 +1,7 @@ name: base channels: - conda-forge + - defaults dependencies: - _libgcc_mutex=0.1=conda_forge - _openmp_mutex=4.5=2_gnu @@ -10,10 +11,10 @@ dependencies: - argon2-cffi=23.1.0=pyhd8ed1ab_0 - argon2-cffi-bindings=21.2.0=py310h2372a71_4 - arrow=1.3.0=pyhd8ed1ab_0 - - asdf=3.4.0=pyhd8ed1ab_0 + - asdf=3.5.0=pyhd8ed1ab_0 - asdf-standard=1.1.1=pyhd8ed1ab_0 - asdf-transform-schemas=0.5.0=pyhd8ed1ab_0 - - astropy=6.1.2=py310h91a95bf_0 + - astropy=6.1.3=py310hf462985_1 - astropy-iers-data=0.2024.8.5.0.32.23=pyhd8ed1ab_0 - asttokens=2.4.1=pyhd8ed1ab_0 - async-lru=2.0.4=pyhd8ed1ab_0 @@ -30,10 +31,10 @@ dependencies: - bzip2=1.0.8=hd590300_5 - c-ares=1.28.1=hd590300_0 - c-blosc2=2.14.4=hb4ffafa_1 - - ca-certificates=2024.7.4=hbcca054_0 + - ca-certificates=2024.8.30=hbcca054_0 - cached-property=1.5.2=hd8ed1ab_1 - cached_property=1.5.2=pyha770c72_1 - - certifi=2024.7.4=pyhd8ed1ab_0 + - certifi=2024.8.30=pyhd8ed1ab_0 - cffi=1.16.0=py310h2fee648_0 - charls=2.4.2=h59595ed_0 - charset-normalizer=3.3.2=pyhd8ed1ab_0 @@ -48,9 +49,209 @@ dependencies: - cuda-version=12.6=h7480c83_3 - cupy=13.2.0=py310h7421b7d_1 - cupy-core=13.2.0=py310hfb24ac1_1 + - cycler=0.12.1=pyhd8ed1ab_0 + - dav1d=1.2.1=hd590300_0 + - debugpy=1.8.7=py310hf71b8c6_0 + - decorator=5.1.1=pyhd8ed1ab_0 + - defusedxml=0.7.1=pyhd8ed1ab_0 + - distro=1.9.0=pyhd8ed1ab_0 + - entrypoints=0.4=pyhd8ed1ab_0 + - exceptiongroup=1.2.2=pyhd8ed1ab_0 + - executing=2.1.0=pyhd8ed1ab_0 + - fastrlock=0.8.2=py310hc6cd4ac_2 + - fmt=10.2.1=h00ab1b0_0 + - fonttools=4.54.1=py310ha75aee5_0 + - fqdn=1.5.1=pyhd8ed1ab_0 + - freetype=2.12.1=h267a509_2 + - frozendict=2.4.4=py310ha75aee5_1 + - giflib=5.2.2=hd590300_0 + - h11=0.14.0=pyhd8ed1ab_0 + - h2=4.1.0=pyhd8ed1ab_0 + - hpack=4.0.0=pyh9f0ad1d_0 + - httpcore=1.0.6=pyhd8ed1ab_0 + - httpx=0.27.2=pyhd8ed1ab_0 + - hyperframe=6.0.1=pyhd8ed1ab_0 + - icu=73.2=h59595ed_0 + - idna=3.6=pyhd8ed1ab_0 + - imagecodecs=2024.1.1=py310h06b5df7_6 + - imageio=2.36.0=pyh12aca89_0 + - importlib-metadata=8.5.0=pyha770c72_0 + - importlib_metadata=8.5.0=hd8ed1ab_0 + - importlib_resources=6.4.5=pyhd8ed1ab_0 + - iniconfig=2.0.0=pyhd8ed1ab_0 + - ipykernel=6.29.5=pyh3099207_0 + - ipython=8.28.0=pyh707e725_0 + - ipywidgets=8.1.3=pyhd8ed1ab_0 + - isoduration=20.11.0=pyhd8ed1ab_0 + - jedi=0.19.1=pyhd8ed1ab_0 + - jinja2=3.1.4=pyhd8ed1ab_0 + - jmespath=1.0.1=pyhd8ed1ab_0 + - json5=0.9.25=pyhd8ed1ab_0 + - jsonpatch=1.33=pyhd8ed1ab_0 + - jsonpointer=2.4=py310hff52083_3 + - jsonschema=4.23.0=pyhd8ed1ab_0 + - jsonschema-specifications=2024.10.1=pyhd8ed1ab_0 + - jsonschema-with-format-nongpl=4.23.0=hd8ed1ab_0 + - jupyter-lsp=2.2.5=pyhd8ed1ab_0 + - jupyter_client=8.6.3=pyhd8ed1ab_0 + - jupyter_core=5.7.2=pyh31011fe_1 + - jupyter_events=0.10.0=pyhd8ed1ab_0 + - jupyter_server=2.14.2=pyhd8ed1ab_0 + - jupyter_server_terminals=0.5.3=pyhd8ed1ab_0 + - jupyterlab=4.2.5=pyhd8ed1ab_0 + - jupyterlab_pygments=0.3.0=pyhd8ed1ab_1 + - jupyterlab_server=2.27.3=pyhd8ed1ab_0 + - jupyterlab_widgets=3.0.13=pyhd8ed1ab_0 + - jxrlib=1.1=hd590300_3 + - keyutils=1.6.1=h166bdaf_0 + - kiwisolver=1.4.7=py310h3788b33_0 + - krb5=1.21.3=h659f571_0 + - lazy-loader=0.4=pyhd8ed1ab_1 + - lazy_loader=0.4=pyhd8ed1ab_1 + - lcms2=2.16=hb7c19ff_0 + - ld_impl_linux-64=2.40=h41732ed_0 + - lerc=4.0.0=h27087fc_0 + - libaec=1.1.3=h59595ed_0 + - libarchive=3.7.2=h2aa1ff5_1 + - libavif16=1.1.1=h104a339_1 + - libblas=3.9.0=24_linux64_openblas + - libbrotlicommon=1.1.0=hd590300_1 + - libbrotlidec=1.1.0=hd590300_1 + - libbrotlienc=1.1.0=hd590300_1 + - libcblas=3.9.0=24_linux64_openblas + - libcublas=12.6.3.3=hbd13f7d_0 + - libcufft=11.3.0.4=hbd13f7d_0 + - libcurand=10.3.7.77=hbd13f7d_0 + - libcurl=8.7.1=hca28451_0 + - libcusolver=11.7.1.2=hbd13f7d_0 + - libcusparse=12.5.4.2=hbd13f7d_0 + - libdeflate=1.20=hd590300_0 + - libedit=3.1.20191231=he28a2e2_2 + - libev=4.33=hd590300_2 + - libffi=3.4.2=h7f98852_5 + - libgcc=14.1.0=h77fa898_1 + - libgcc-ng=14.1.0=h69a702a_1 + - libgfortran=14.1.0=h69a702a_1 + - libgfortran-ng=14.1.0=h69a702a_1 + - libgfortran5=14.1.0=hc5f4f2c_1 + - libgomp=14.1.0=h77fa898_1 + - libhwy=1.1.0=h00ab1b0_0 + - libiconv=1.17=hd590300_2 + - libjpeg-turbo=3.0.0=hd590300_1 + - libjxl=0.10.3=h66b40c8_0 + - liblapack=3.9.0=24_linux64_openblas + - libmamba=1.5.8=had39da4_0 + - libmambapy=1.5.8=py310h39ff949_0 + - libnghttp2=1.58.0=h47da74e_1 + - libnsl=2.0.1=hd590300_0 + - libnvjitlink=12.6.77=hbd13f7d_1 + - libopenblas=0.3.27=pthreads_hac2b453_1 + - libpng=1.6.43=h2797004_0 + - libpq=17.0=h8d1a565_0 + - libsodium=1.0.18=h36c2ea0_1 + - libsolv=0.7.28=hfc55251_2 + - libsqlite=3.45.2=h2797004_0 + - libssh2=1.11.0=h0841786_0 + - libstdcxx=14.1.0=hc0a3c3a_1 + - libstdcxx-ng=13.2.0=h7e041cc_5 + - libtiff=4.6.0=h1dd3fc0_3 + - libuuid=2.38.1=h0b41bf4_0 + - libwebp-base=1.4.0=hd590300_0 + - libxcb=1.15=h0b41bf4_0 + - libxcrypt=4.4.36=hd590300_1 + - libxml2=2.12.6=h232c23b_1 + - libzlib=1.2.13=hd590300_5 + - libzopfli=1.0.3=h9c3ff4c_0 + - line_profiler=4.1.3=py310h3788b33_1 + - lz4-c=1.9.4=hcb278e6_0 + - lzo=2.10=h516909a_1000 + - mamba=1.5.8=py310h51d5547_0 + - markupsafe=3.0.1=py310h89163eb_1 + - matplotlib-base=3.9.2=py310h68603db_1 + - matplotlib-inline=0.1.7=pyhd8ed1ab_0 + - menuinst=2.0.2=py310hff52083_0 + - mistune=3.0.2=pyhd8ed1ab_0 + - munkres=1.1.4=pyh9f0ad1d_0 + - nb_conda_kernels=2.5.1=pyh707e725_2 + - nbclient=0.10.0=pyhd8ed1ab_0 + - nbconvert-core=7.16.4=pyhd8ed1ab_1 + - nbformat=5.10.4=pyhd8ed1ab_0 + - ncurses=6.4.20240210=h59595ed_0 + - nest-asyncio=1.6.0=pyhd8ed1ab_0 + - networkx=3.3=pyhd8ed1ab_1 + - nomkl=1.0=h5ca1d4c_0 + - notebook=7.2.2=pyhd8ed1ab_0 + - notebook-shim=0.2.4=pyhd8ed1ab_0 + - numexpr=2.10.1=py310hdb6e06b_102 + - numpy=1.26.4=py310hb13e2d6_0 + - openjpeg=2.5.2=h488ebb8_0 + - openssl=3.3.2=hb9d3cd8_0 + - overrides=7.7.0=pyhd8ed1ab_0 + - packaging=24.0=pyhd8ed1ab_0 + - pandocfilters=1.5.0=pyhd8ed1ab_0 + - parso=0.8.4=pyhd8ed1ab_0 + - pexpect=4.9.0=pyhd8ed1ab_0 + - pickleshare=0.7.5=py_1003 + - pip=24.2=pyh8b19718_1 + - pkgutil-resolve-name=1.3.10=pyhd8ed1ab_1 + - platformdirs=4.2.0=pyhd8ed1ab_0 + - pluggy=1.5.0=pyhd8ed1ab_0 + - prometheus_client=0.21.0=pyhd8ed1ab_0 + - prompt-toolkit=3.0.48=pyha770c72_0 + - psutil=6.0.0=py310ha75aee5_2 + - psycopg=3.2.3=py310h7c6061f_1 + - psycopg-c=3.2.3=py310hce86986_1 + - pthread-stubs=0.4=hb9d3cd8_1002 + - ptyprocess=0.7.0=pyhd3deb0d_0 + - pure_eval=0.2.3=pyhd8ed1ab_0 - pybind11=2.13.1=py310h25c7140_0 - pybind11-abi=4=hd8ed1ab_3 - pybind11-global=2.13.1=py310h25c7140_0 + - pycosat=0.6.6=py310h2372a71_0 + - pycparser=2.22=pyhd8ed1ab_0 + - pyerfa=2.0.1.4=py310hf462985_2 + - pygments=2.18.0=pyhd8ed1ab_0 + - pyserial=3.5=pyhd8ed1ab_0 + - pysocks=1.7.1=pyha2e5f31_6 + - pytest=8.3.3=pyhd8ed1ab_0 + - python=3.10.14=hd12c33a_0_cpython + - python-dateutil=2.9.0=pyhd8ed1ab_0 + - python-duckdb=1.1.2=py310hf71b8c6_0 + - python-fastjsonschema=2.20.0=pyhd8ed1ab_0 + - python-json-logger=2.0.7=pyhd8ed1ab_0 + - python_abi=3.10=4_cp310 + - pytz=2024.2=pyhd8ed1ab_0 + - pywavelets=1.7.0=py310hf462985_1 + - pyyaml=6.0.2=py310ha75aee5_1 + - pyzmq=26.2.0=py310h71f11fc_1 + - qhull=2020.2=h434a139_5 + - rav1e=0.6.6=he8a937b_2 + - readline=8.2=h8228510_1 + - referencing=0.35.1=pyhd8ed1ab_0 + - reproc=14.2.4.post0=hd590300_1 + - reproc-cpp=14.2.4.post0=h59595ed_1 + - requests=2.32.3=pyhd8ed1ab_0 + - rfc3339-validator=0.1.4=pyhd8ed1ab_0 + - rfc3986-validator=0.1.1=pyh9f0ad1d_0 + - rpds-py=0.20.0=py310h505e2c1_1 + - ruamel.yaml=0.18.6=py310h2372a71_0 + - ruamel.yaml.clib=0.2.8=py310h2372a71_0 + - scikit-image=0.24.0=py310h0cd1892_2 + - scipy=1.14.1=py310ha3fb0e1_0 + - semantic_version=2.10.0=pyhd8ed1ab_0 + - send2trash=1.8.3=pyh0d859eb_0 + - setuptools=69.5.1=pyhd8ed1ab_0 + - six=1.16.0=pyh6c4a22f_0 + - snappy=1.2.1=ha2e4443_0 + - sniffio=1.3.1=pyhd8ed1ab_0 + - soupsieve=2.5=pyhd8ed1ab_1 + - stack_data=0.6.2=pyhd8ed1ab_0 + - svt-av1=2.2.1=h5888daf_0 + - terminado=0.18.1=pyh0d859eb_0 + - tifffile=2024.9.20=pyhd8ed1ab_0 + - tinycss2=1.3.0=pyhd8ed1ab_0 + - tk=8.6.13=noxft_h4845f30_101 + - tomli=2.0.2=pyhd8ed1ab_0 - tornado=6.4.1=py310hc51659f_0 - tqdm=4.66.2=pyhd8ed1ab_0 - traitlets=5.14.3=pyhd8ed1ab_0 @@ -76,12 +277,30 @@ dependencies: - yaml-cpp=0.8.0=h59595ed_0 - zeromq=4.3.5=h75354e8_4 - zfp=1.0.1=hac33072_1 - - zipp=3.19.2=pyhd8ed1ab_0 + - zipp=3.20.2=pyhd8ed1ab_0 - zlib-ng=2.0.7=h0b41bf4_0 - zstandard=0.22.0=py310h1275a96_0 - zstd=1.5.5=hfc55251_0 - pip: + - ciso8601==2.3.1 + - coloredlogs==15.0.1 + - coralign==2024.1.12 + - dbingest==2023.12.21 + - fsspec==2024.9.0 - hcipy==0.6.0 + - humanfriendly==10.0 + - imagestreamiowrap==1.0.0 + - influxdb-client==1.46.0 + - magaox==2023.12.21 + - orjson==3.10.7 + - pillow==10.4.0 - poppy==1.1.1 + - psycopg-binary==3.2.3 + - pyparsing==3.1.4 + - reactivex==4.0.4 + - stack-data==0.6.3 + - toml==0.10.2 + - universal-pathlib==0.2.5 + - watchdog==3.0.0 - xxhash==3.4.1 prefix: /opt/conda From 3a17fd2805dbd595d17fa820269bc1f34c63be88 Mon Sep 17 00:00:00 2001 From: Jared Males Date: Sun, 20 Oct 2024 00:38:00 -0700 Subject: [PATCH 16/24] stage status widget now has preset dropdown --- gui/apps/cameraGUI/cameraGUI.pro | 4 +- gui/apps/coronAlignGUI/coronAlignGUI.pro | 2 + gui/resources/MagAOXStyleSheets/magaox.qss | 3 +- gui/widgets/camera/camera.hpp | 361 ++++++++-------- gui/widgets/camera/stageStatus.hpp | 121 ------ gui/widgets/coronAlign/coronAlign.hpp | 132 +++++- gui/widgets/coronAlign/coronAlign.ui | 200 +++++++-- gui/widgets/xWidgets/selectionSwStatus.hpp | 2 +- gui/widgets/xWidgets/stageStatus.hpp | 118 +++--- gui/widgets/xWidgets/statusCombo.hpp | 459 +++++++++++++++++++++ gui/widgets/xWidgets/statusCombo.ui | 116 ++++++ gui/widgets/xWidgets/statusDisplay.hpp | 8 +- gui/widgets/xWidgets/statusDisplay.ui | 13 +- 13 files changed, 1118 insertions(+), 421 deletions(-) delete mode 100644 gui/widgets/camera/stageStatus.hpp create mode 100644 gui/widgets/xWidgets/statusCombo.hpp create mode 100644 gui/widgets/xWidgets/statusCombo.ui diff --git a/gui/apps/cameraGUI/cameraGUI.pro b/gui/apps/cameraGUI/cameraGUI.pro index 579d30acb..f2fcb307a 100644 --- a/gui/apps/cameraGUI/cameraGUI.pro +++ b/gui/apps/cameraGUI/cameraGUI.pro @@ -44,7 +44,8 @@ HEADERS += ../../widgets/camera/camera.hpp \ ../../widgets/xWidgets/selectionSw.hpp \ ../../widgets/xWidgets/toggleSlider.hpp \ ../../widgets/camera/roiStatus.hpp \ - ../../widgets/camera/stageStatus.hpp \ + ../../widgets/xWidgets/statusCombo.hpp \ + ../../widgets/xWidgets/stageStatus.hpp \ ../../widgets/roi/roi.hpp \ ../../widgets/stage/stage.hpp \ ../../widgets/camera/shutterStatus.hpp \ @@ -56,6 +57,7 @@ FORMS += ../../widgets/camera/camera.ui \ ../../widgets/xWidgets/fsmDisplay.ui \ ../../widgets/xWidgets/statusEntry.ui \ ../../widgets/xWidgets/statusDisplay.ui \ + ../../widgets/xWidgets/statusCombo.ui \ ../../widgets/xWidgets/toggleSlider.ui \ ../../widgets/roi/roi.ui \ ../../widgets/stage/stage.ui \ diff --git a/gui/apps/coronAlignGUI/coronAlignGUI.pro b/gui/apps/coronAlignGUI/coronAlignGUI.pro index abd27463a..f93f441b3 100644 --- a/gui/apps/coronAlignGUI/coronAlignGUI.pro +++ b/gui/apps/coronAlignGUI/coronAlignGUI.pro @@ -41,6 +41,7 @@ HEADERS += ../../widgets/coronAlign/coronAlign.hpp \ ../../widgets/stage/stage.hpp \ ../../widgets/xWidgets/fsmDisplay.hpp \ ../../widgets/xWidgets/statusLineEdit.hpp \ + ../../widgets/xWidgets/statusCombo.hpp SOURCES += coronAlignGUI_main.cpp @@ -49,6 +50,7 @@ FORMS += ../../widgets/coronAlign/coronAlign.ui \ ../../widgets/xWidgets/selectionSw.ui \ ../../widgets/stage/stage.ui \ ../../widgets/xWidgets/fsmDisplay.ui \ + ../../widgets/xWidgets/statusCombo.ui LIBS += ../../../INDI/libcommon/libcommon.a \ ../../../INDI/liblilxml/liblilxml.a diff --git a/gui/resources/MagAOXStyleSheets/magaox.qss b/gui/resources/MagAOXStyleSheets/magaox.qss index 3a9bdcb21..06a97f5e7 100644 --- a/gui/resources/MagAOXStyleSheets/magaox.qss +++ b/gui/resources/MagAOXStyleSheets/magaox.qss @@ -1,6 +1,6 @@ /* * MagaOX Stylesheet, modified from: - * + * * BreezeDark stylesheet. * * :author: Colin Duquesnoy @@ -873,6 +873,7 @@ QComboBox[isStatus="true"] { color: #3DA5FF; } + QComboBox:disabled[isStatus="true"] { color: #007ae6; diff --git a/gui/widgets/camera/camera.hpp b/gui/widgets/camera/camera.hpp index bf2b0a34a..7fdc5b6d1 100644 --- a/gui/widgets/camera/camera.hpp +++ b/gui/widgets/camera/camera.hpp @@ -8,8 +8,9 @@ #include "xWidgets/xWidget.hpp" #include "xWidgets/fsmDisplay.hpp" #include "xWidgets/statusEntry.hpp" -#include "xWidgets/statusDisplay.hpp" #include "xWidgets/selectionSwStatus.hpp" +#include "xWidgets/statusDisplay.hpp" +#include "xWidgets/stageStatus.hpp" #include "xWidgets/toggleSlider.hpp" #include "roi/roi.hpp" @@ -18,36 +19,35 @@ #include "camera/shutterStatus.hpp" #include "stage/stage.hpp" -#include "camera/stageStatus.hpp" #include -namespace xqt +namespace xqt { - + /// A GUI for an XWC Standard Camera class camera : public xWidget { Q_OBJECT - + protected: - + std::string m_appState; - + std::string m_camName; std::string m_darkName; std::string m_avgName; - + fsmDisplay * ui_fsmState {nullptr}; - + statusEntry * ui_tempCCD {nullptr}; - + statusDisplay * ui_tempStatus {nullptr}; - + QPushButton * ui_reconfigure {nullptr}; - + std::vector m_stageNames; - + std::vector ui_stage; shutterStatus * ui_shutterStatus {nullptr}; @@ -55,56 +55,56 @@ class camera : public xWidget roiStatus * ui_roiStatus {nullptr}; selectionSwStatus * ui_modes {nullptr}; - + selectionSwStatus * ui_readoutSpd {nullptr}; selectionSwStatus * ui_vshiftSpd {nullptr}; - + toggleSlider * ui_cropMode {nullptr}; - + statusEntry * ui_expTime {nullptr}; statusEntry * ui_fps {nullptr}; statusEntry * ui_emGain {nullptr}; - + statusEntry * ui_avgTime {nullptr}; toggleSlider * ui_synchro {nullptr}; - + QPushButton * ui_takeDarks {nullptr}; - + float m_temp {-99}; - + bool m_takingDark {false}; - + bool m_inUpdate {false}; - + QTimer * m_updateTimer {nullptr}; ///< Timer for periodic updates - + bool m_connected {false}; public: explicit camera( std::string & camName, - QWidget * Parent = 0, + QWidget * Parent = 0, Qt::WindowFlags f = Qt::WindowFlags() ); - + ~camera(); - + void subscribe( ); - + virtual void onConnect(); virtual void onDisconnect(); - + void handleDefProperty( const pcf::IndiProperty & ipRecv /**< [in] the property which has changed*/); - + void handleSetProperty( const pcf::IndiProperty & ipRecv /**< [in] the property which has changed*/); - + void hideAll(); - + void setEnableDisable(bool tf, bool all=true); - + //static b/c it gets called before the device is instantiated. static void setupConfig( mx::app::appConfigurator & config ); @@ -113,11 +113,11 @@ class camera : public xWidget public slots: void updateGUI(); - + void setup_temp_ccd(bool ro); void setup_tempStatus(); - + void setup_reconfigure(); void reconfigure(); @@ -125,124 +125,124 @@ public slots: void setup_stage(); void setup_shutter(); - + void setup_roiStatus(); void setup_modes(); - + void setup_readoutSpd(); void setup_vshiftSpd(); - + void setup_cropMode(); - + void setup_expTime(bool ro); void setup_fps(bool ro); void setup_emGain(bool ro); - + void setup_avgTime(bool ro); void setup_synchro(); - + void setup_takeDarks(); - + void takeDark(); signals: void doUpdateGUI(); - + void updateTimerStop(); void updateTimerStart(int); - + void add_temp_ccd(bool ro); void add_tempStatus(); - + void add_reconfigure(); - + void add_shutter(); - + void add_roiStatus(); void add_modes(); - + void add_readoutSpd(); void add_vshiftSpd(); - + void add_cropMode(); - - void add_expTime(bool ro); + + void add_expTime(bool ro); void add_fps(bool ro); void add_emGain(bool ro); void add_avgTime(bool ro); - + void add_synchro(); - + void add_takeDarks(); private: - + Ui::camera ui; }; - + camera::camera( std::string & camName, - QWidget * Parent, + QWidget * Parent, Qt::WindowFlags f) : xWidget(Parent, f), m_camName{camName} { m_darkName = m_camName + "-dark"; m_avgName = m_camName + "-avg"; ui.setupUi(this); - + m_updateTimer = new QTimer(this); - + connect(this, SIGNAL(doUpdateGUI()), this, SLOT(updateGUI())); - + connect(m_updateTimer, SIGNAL(timeout()), this, SLOT(updateGUI())); connect(this, SIGNAL(updateTimerStop()), m_updateTimer, SLOT(stop())); connect(this, SIGNAL(updateTimerStart(int)), m_updateTimer, SLOT(start(int))); - + connect(this, SIGNAL(add_temp_ccd(bool)), this, SLOT(setup_temp_ccd(bool))); connect(this, SIGNAL(add_tempStatus()), this, SLOT(setup_tempStatus())); - + connect(this, SIGNAL(add_reconfigure()), this, SLOT(setup_reconfigure())); - + connect(this, SIGNAL(add_shutter()), this, SLOT(setup_shutter())); - + connect(this, SIGNAL(add_roiStatus()), this, SLOT(setup_roiStatus())); connect(this, SIGNAL(add_modes()), this, SLOT(setup_modes())); - + connect(this, SIGNAL(add_readoutSpd()), this, SLOT(setup_readoutSpd())); connect(this, SIGNAL(add_vshiftSpd()), this, SLOT(setup_vshiftSpd())); connect(this, SIGNAL(add_cropMode()), this, SLOT(setup_cropMode())); - + connect(this, SIGNAL(add_expTime(bool)), this, SLOT(setup_expTime(bool))); connect(this, SIGNAL(add_fps(bool)), this, SLOT(setup_fps(bool))); connect(this, SIGNAL(add_emGain(bool)), this, SLOT(setup_emGain(bool))); connect(this, SIGNAL(add_avgTime(bool)), this, SLOT(setup_avgTime(bool))); connect(this, SIGNAL(add_synchro()), this, SLOT(setup_synchro())); - + connect(this, SIGNAL(add_takeDarks()), this, SLOT(setup_takeDarks())); - + QSpacerItem *holder = new QSpacerItem(10,0, QSizePolicy::Expanding, QSizePolicy::Expanding); ui.grid->addItem(holder, 2,1,1,1); - + ui_fsmState = new xqt::fsmDisplay(this); ui_fsmState->setObjectName(QString::fromUtf8("fsmState")); ui.grid->addWidget(ui_fsmState, 1, 0, 1, 1); ui_fsmState->device(m_camName); - + QFont qf = ui.lab_camName->font(); qf.setPixelSize(XW_FONT_SIZE+3); ui.lab_camName->setFont(qf); - + ui.lab_camName->setText(m_camName.c_str()); - + onDisconnect(); } - + camera::~camera() { } @@ -250,7 +250,7 @@ camera::~camera() void camera::subscribe() { if(!m_parent) return; - + m_parent->addSubscriberProperty((multiIndiSubscriber *) this, m_camName, ""); m_parent->addSubscriberProperty((multiIndiSubscriber *) this, m_camName, "fsm"); m_parent->addSubscriberProperty((multiIndiSubscriber *) this, m_darkName, ""); @@ -259,11 +259,11 @@ void camera::subscribe() m_parent->addSubscriberProperty((multiIndiSubscriber *) this, m_avgName, "avgTime"); m_parent->addSubscriber(ui_fsmState); - + if(ui_tempCCD) m_parent->addSubscriber(ui_tempCCD); if(ui_tempStatus) m_parent->addSubscriber(ui_tempStatus); - if(ui_stage.size() > 0) + if(ui_stage.size() > 0) { for(size_t n = 0; n < ui_stage.size(); ++n) { @@ -282,21 +282,21 @@ void camera::subscribe() if(ui_emGain) m_parent->addSubscriber(ui_emGain); if(ui_avgTime) m_parent->addSubscriber(ui_avgTime); if(ui_synchro) m_parent->addSubscriber(ui_synchro); - + return; } - + void camera::onConnect() { ui.lab_camName->setEnabled(true); - + setWindowTitle(QString((m_camName+"Ctrl").c_str())); - + ui_fsmState->onConnect(); - + if(ui_tempCCD) ui_tempCCD->onConnect(); if(ui_tempStatus) ui_tempStatus->onConnect(); - + if(ui_stage.size() > 0) { for(size_t n = 0; n < ui_stage.size(); ++n) @@ -304,26 +304,26 @@ void camera::onConnect() ui_stage[n]->onConnect(); } } - + if(ui_shutterStatus) ui_shutterStatus->onConnect(); - + if(ui_roiStatus) ui_roiStatus->onConnect(); if(ui_modes) ui_modes->onConnect(); if(ui_readoutSpd) ui_readoutSpd->onConnect(); if(ui_vshiftSpd) ui_readoutSpd->onConnect(); if(ui_cropMode) ui_cropMode->onConnect(); - + if(ui_expTime) ui_expTime->onConnect(); if(ui_fps) ui_fps->onConnect(); if(ui_emGain) ui_emGain->onConnect(); if(ui_avgTime) ui_avgTime->onConnect(); - + if(ui_synchro) ui_synchro->onConnect(); - + clearFocus(); - + m_connected = true; - + emit doUpdateGUI(); } @@ -331,12 +331,12 @@ void camera::onDisconnect() { setWindowTitle(QString((m_camName+"Ctrl").c_str()) + QString(" (disconnected)")); - + ui_fsmState->onDisconnect(); - + if(ui_tempCCD) ui_tempCCD->onDisconnect(); if(ui_tempStatus) ui_tempStatus->onDisconnect(); - + if(ui_stage.size() > 0) { for(size_t n =0; n < ui_stage.size(); ++n) @@ -346,41 +346,41 @@ void camera::onDisconnect() } if(ui_shutterStatus) ui_shutterStatus->onDisconnect(); - + if(ui_roiStatus) ui_roiStatus->onDisconnect(); if(ui_modes) ui_modes->onDisconnect(); if(ui_readoutSpd) ui_readoutSpd->onDisconnect(); if(ui_vshiftSpd) ui_readoutSpd->onDisconnect(); if(ui_cropMode) ui_cropMode->onDisconnect(); - + if(ui_expTime) ui_expTime->onDisconnect(); if(ui_fps) ui_fps->onDisconnect(); if(ui_emGain) ui_emGain->onDisconnect(); if(ui_avgTime) ui_avgTime->onDisconnect(); if(ui_synchro) ui_synchro->onDisconnect(); - - clearFocus(); - + + clearFocus(); + m_connected = false; while(m_inUpdate) { QThread::msleep(10); //Wait to get out of update } emit updateTimerStop(); - + setEnableDisable(false); } void camera::handleDefProperty( const pcf::IndiProperty & ipRecv) -{ +{ return handleSetProperty(ipRecv); } void camera::handleSetProperty( const pcf::IndiProperty & ipRecv) -{ +{ if(ipRecv.getDevice() != m_camName && ipRecv.getDevice() != m_darkName && ipRecv.getDevice() != m_avgName) return; - + if(ipRecv.getDevice() == m_camName) { if(ipRecv.getName() == "fsm") @@ -390,18 +390,18 @@ void camera::handleSetProperty( const pcf::IndiProperty & ipRecv) m_appState = ipRecv["state"].get(); } } - + if(ipRecv.getName() == "temp_ccd") { if(!ui_tempCCD) { bool ro = true; if(ipRecv.find("target")) ro = false; - + emit add_temp_ccd(ro); } } - + if(ipRecv.getName() == "temp_control") { if(!ui_tempStatus) @@ -409,7 +409,7 @@ void camera::handleSetProperty( const pcf::IndiProperty & ipRecv) emit add_tempStatus(); } } - + if(ipRecv.getName() == "reconfigure") { if(!ui_reconfigure) @@ -425,7 +425,7 @@ void camera::handleSetProperty( const pcf::IndiProperty & ipRecv) emit add_shutter(); } } - + if(ipRecv.getName() == "roi_set") { if(!ui_roiStatus) @@ -433,7 +433,7 @@ void camera::handleSetProperty( const pcf::IndiProperty & ipRecv) emit add_roiStatus(); } } - + if(ipRecv.getName() == "mode") { if(!ui_modes) @@ -441,7 +441,7 @@ void camera::handleSetProperty( const pcf::IndiProperty & ipRecv) emit add_modes(); } } - + if(ipRecv.getName() == "readout_speed") { if(!ui_readoutSpd) @@ -449,7 +449,7 @@ void camera::handleSetProperty( const pcf::IndiProperty & ipRecv) emit add_readoutSpd(); } } - + if(ipRecv.getName() == "vshift_speed") { if(!ui_vshiftSpd) @@ -457,7 +457,7 @@ void camera::handleSetProperty( const pcf::IndiProperty & ipRecv) emit add_vshiftSpd(); } } - + if(ipRecv.getName() == "roi_crop_mode") { if(!ui_cropMode) @@ -472,29 +472,29 @@ void camera::handleSetProperty( const pcf::IndiProperty & ipRecv) { bool ro = true; if(ipRecv.find("target")) ro = false; - + emit add_expTime(ro); } } - + if(ipRecv.getName() == "fps") { if(!ui_fps) { bool ro = true; if(ipRecv.find("target")) ro = false; - + emit add_fps(ro); } } - + if(ipRecv.getName() == "emgain") { if(!ui_emGain) { bool ro = true; if(ipRecv.find("target")) ro = false; - + emit add_emGain(ro); } } @@ -502,11 +502,11 @@ void camera::handleSetProperty( const pcf::IndiProperty & ipRecv) if(ipRecv.getName() == "synchro") { if(!ui_synchro) - { + { emit add_synchro(); } } - + } else if(ipRecv.getDevice() == m_darkName) { @@ -518,7 +518,7 @@ void camera::handleSetProperty( const pcf::IndiProperty & ipRecv) { m_takingDark = true; } - else + else { m_takingDark = false; } @@ -526,13 +526,13 @@ void camera::handleSetProperty( const pcf::IndiProperty & ipRecv) } else if(ipRecv.getDevice() == m_avgName) { - if(!ui_avgTime) + if(!ui_avgTime) { emit add_avgTime(false); } } - emit doUpdateGUI(); + emit doUpdateGUI(); } void camera::hideAll() @@ -547,11 +547,11 @@ void camera::setEnableDisable(bool tf, bool all) ui.lab_camName->setEnabled(tf); ui_fsmState->setEnabled(tf); } - + if(ui_reconfigure) ui_reconfigure->setEnabled(tf); if(ui_tempCCD) ui_tempCCD->setEnabled(tf); if(ui_tempStatus) ui_tempStatus->setEnabled(tf); - + if(ui_roiStatus) ui_roiStatus->setEnabled(tf); if(ui_modes) ui_modes->setEnabled(tf); if(ui_readoutSpd) ui_readoutSpd->setEnabled(tf); @@ -567,12 +567,12 @@ void camera::setEnableDisable(bool tf, bool all) { ui_stage[n]->setEnabled(tf); } - } - + } + if(ui_shutterStatus) ui_shutterStatus->setEnabled(tf); - + if(ui_takeDarks) ui_takeDarks->setEnabled(tf); - + } void camera::setupConfig( mx::app::appConfigurator & config ) @@ -584,7 +584,7 @@ void camera::loadConfig( mx::app::appConfigurator & config ) { config(m_stageNames, "camera.stages"); for(size_t n = 0; n < m_stageNames.size(); ++n) - { + { setup_stage(); } onDisconnect(); @@ -595,7 +595,7 @@ void camera::updateGUI() if(m_inUpdate || !m_connected) return; emit updateTimerStop(); m_inUpdate = true; - + if( m_appState == "NODEVICE" || m_appState == "NOTCONNECTED" || m_appState == "CONNECTED") { setEnableDisable(false, false); @@ -604,21 +604,21 @@ void camera::updateGUI() } else if( m_appState != "READY" && m_appState != "OPERATING" && m_appState != "CONFIGURING") { - setEnableDisable(false); + setEnableDisable(false); m_inUpdate = false; - + emit updateTimerStart(1000); - return; + return; } else //if( m_appState == "READY" || m_appState == "OPERATING" || m_appState == "CONFIGURING") { setEnableDisable(true); } - + //Update the component GUIs to ensure they update for connection state, etc. if(ui_tempCCD) ui_tempCCD->updateGUI(); if(ui_roiStatus) ui_roiStatus->updateGUI(); - + if(ui_stage.size() > 0) { for(size_t n = 0; n < ui_stage.size(); ++n) @@ -637,7 +637,7 @@ void camera::updateGUI() if(ui_emGain) ui_emGain->updateGUI(); if(ui_avgTime) ui_avgTime->updateGUI(); if(ui_synchro) ui_synchro->updateGUI(); - + if( (m_appState == "READY" || m_appState == "OPERATING") && ui_takeDarks ) { if(m_takingDark) @@ -649,7 +649,7 @@ void camera::updateGUI() ui_takeDarks->setEnabled(true); } } - + emit updateTimerStart(1000); m_inUpdate = false; @@ -658,7 +658,7 @@ void camera::updateGUI() void camera::setup_temp_ccd(bool ro) { if(ui_tempCCD) return; - + ui_tempCCD = new statusEntry(this); ui_tempCCD->setObjectName(QString::fromUtf8("tempCCD")); ui_tempCCD->setup(m_camName, "temp_ccd", statusEntry::FLOAT, "Detector Temp.", "C"); @@ -666,21 +666,22 @@ void camera::setup_temp_ccd(bool ro) ui_tempCCD->readOnly(ro); ui.grid->addWidget(ui_tempCCD, 0, 1, 1, 1); - + ui_tempCCD->onDisconnect(); m_parent->addSubscriber(ui_tempCCD); + } void camera::setup_tempStatus() { if(ui_tempStatus) return; - + ui_tempStatus = new statusDisplay(m_camName,"temp_control", "status", "Temp. Ctrl.", "", this, Qt::WindowFlags()); ui_tempStatus->setObjectName(QString::fromUtf8("tempStatus")); - + ui.grid->addWidget(ui_tempStatus, 1, 1, 1, 1); - + ui_tempStatus->onDisconnect(); m_parent->addSubscriber(ui_tempStatus); @@ -689,26 +690,26 @@ void camera::setup_tempStatus() void camera::setup_reconfigure() { if(ui_reconfigure) return; - + ui_reconfigure = new QPushButton(this); ui_reconfigure->setObjectName(QString::fromUtf8("reconfigure")); ui_reconfigure->setText("reconfigure"); ui_reconfigure->setMaximumWidth(200); connect(ui_reconfigure, SIGNAL(pressed()), this, SLOT(reconfigure())); - ui.grid->addWidget(ui_reconfigure, 3, 0, 1, 1, Qt::AlignHCenter); + ui.grid->addWidget(ui_reconfigure, 3, 0, 1, 1, Qt::AlignHCenter); } void camera::reconfigure() { pcf::IndiProperty ipFreq(pcf::IndiProperty::Switch); - + ipFreq.setDevice(m_camName); ipFreq.setName("reconfigure"); ipFreq.add(pcf::IndiElement("request")); ipFreq["request"].setSwitchState(pcf::IndiElement::On); - - sendNewProperty(ipFreq); + + sendNewProperty(ipFreq); } void camera::setup_stage() @@ -720,17 +721,17 @@ void camera::setup_stage() ui_stage.push_back(new stageStatus(m_stageNames[n], this)); ui_stage[n]->setObjectName(QString::fromUtf8(m_stageNames[n].c_str())); - + ui.grid->addWidget(ui_stage[n], 4+n, 0, 1, 1); - + ui_stage[n]->onDisconnect(); - + } void camera::setup_shutter() { if(ui_shutterStatus) return; - + ui_shutterStatus = new shutterStatus(m_camName, this); ui_shutterStatus->setObjectName(QString::fromUtf8("shutter")); @@ -742,7 +743,7 @@ void camera::setup_shutter() } ui.grid->addWidget(ui_shutterStatus, 8 + doff, 0, 1, 1); - + ui_shutterStatus->onDisconnect(); m_parent->addSubscriber(ui_shutterStatus); @@ -751,12 +752,12 @@ void camera::setup_shutter() void camera::setup_roiStatus() { if(ui_roiStatus) return; //can get called from several threads - + ui_roiStatus = new roiStatus(m_camName, this); ui_roiStatus->setObjectName(QString::fromUtf8("roiStatus")); - + ui.grid->addWidget(ui_roiStatus, 3, 1, 1, 1); - + ui_roiStatus->onDisconnect(); m_parent->addSubscriber(ui_roiStatus); @@ -765,26 +766,28 @@ void camera::setup_roiStatus() void camera::setup_modes() { if(ui_modes) return; - - ui_modes = new selectionSwStatus(m_camName,"mode", "", "Mode", "", this); + + ui_modes = new selectionSwStatus(m_camName, "mode", "", "Mode", "", this); + ui_modes->setObjectName(QString::fromUtf8("modes")); - + ui.grid->addWidget(ui_modes, 3, 1, 1, 1); - + ui_modes->onDisconnect(); m_parent->addSubscriber(ui_modes); + } void camera::setup_readoutSpd() { if(ui_readoutSpd) return; - + ui_readoutSpd = new selectionSwStatus(m_camName,"readout_speed", "", "Readout Spd", "", this); ui_readoutSpd->setObjectName(QString::fromUtf8("readoutSpd")); - + ui.grid->addWidget(ui_readoutSpd, 4, 1, 1, 1); - + ui_readoutSpd->onDisconnect(); m_parent->addSubscriber(ui_readoutSpd); @@ -793,12 +796,12 @@ void camera::setup_readoutSpd() void camera::setup_vshiftSpd() { if(ui_vshiftSpd) return; - + ui_vshiftSpd = new selectionSwStatus(m_camName,"vshift_speed", "", "Vert. Shift Spd", "", this); ui_vshiftSpd->setObjectName(QString::fromUtf8("vshiftSpd")); - + ui.grid->addWidget(ui_vshiftSpd, 5, 1, 1, 1); - + ui_vshiftSpd->onDisconnect(); m_parent->addSubscriber(ui_vshiftSpd); @@ -807,12 +810,12 @@ void camera::setup_vshiftSpd() void camera::setup_cropMode() { if(ui_cropMode) return; - + ui_cropMode = new toggleSlider(m_camName, "roi_crop_mode", "Crop Mode", this); ui_cropMode->setObjectName(QString::fromUtf8("cropMode")); ui.grid->addWidget(ui_cropMode, 6, 1, 1, 1); - + ui_cropMode->onDisconnect(); m_parent->addSubscriber(ui_cropMode); @@ -821,7 +824,7 @@ void camera::setup_cropMode() void camera::setup_expTime(bool ro) { if(ui_expTime) return; - + ui_expTime = new statusEntry(this); ui_expTime->setObjectName(QString::fromUtf8("expTime")); ui_expTime->setup(m_camName, "exptime", statusEntry::FLOAT, "Exp. Time", "sec"); @@ -829,7 +832,7 @@ void camera::setup_expTime(bool ro) ui_expTime->readOnly(ro); ui.grid->addWidget(ui_expTime, 7, 1, 1, 1); - + ui_expTime->onDisconnect(); m_parent->addSubscriber(ui_expTime); @@ -838,7 +841,7 @@ void camera::setup_expTime(bool ro) void camera::setup_fps(bool ro) { if(ui_fps) return; - + ui_fps = new statusEntry(this); ui_fps->setObjectName(QString::fromUtf8("fps")); ui_fps->setup(m_camName, "fps", statusEntry::FLOAT, "Frame Rate", "F.P.S."); @@ -846,7 +849,7 @@ void camera::setup_fps(bool ro) ui_fps->readOnly(ro); ui.grid->addWidget(ui_fps, 8, 1, 1, 1); - + ui_fps->onDisconnect(); m_parent->addSubscriber(ui_fps); @@ -855,7 +858,7 @@ void camera::setup_fps(bool ro) void camera::setup_emGain(bool ro) { if(ui_emGain) return; - + ui_emGain = new statusEntry(this); ui_emGain->setObjectName(QString::fromUtf8("emgain")); ui_emGain->setup(m_camName, "emgain", statusEntry::FLOAT, "E.M. Gain", ""); @@ -863,7 +866,7 @@ void camera::setup_emGain(bool ro) ui_emGain->readOnly(ro); ui.grid->addWidget(ui_emGain, 9, 1, 1, 1); - + ui_emGain->onDisconnect(); m_parent->addSubscriber(ui_emGain); @@ -872,7 +875,7 @@ void camera::setup_emGain(bool ro) void camera::setup_avgTime(bool ro) { if(ui_avgTime) return; - + ui_avgTime = new statusEntry(this); ui_avgTime->setObjectName(QString::fromUtf8("avgTime")); ui_avgTime->setup(m_avgName, "avgTime", statusEntry::FLOAT, "Avg. Time", ""); @@ -880,7 +883,7 @@ void camera::setup_avgTime(bool ro) ui_avgTime->readOnly(ro); ui.grid->addWidget(ui_avgTime, 11, 1, 1, 1); - + ui_avgTime->onDisconnect(); m_parent->addSubscriber(ui_avgTime); @@ -889,12 +892,12 @@ void camera::setup_avgTime(bool ro) void camera::setup_synchro() { if(ui_synchro) return; - + ui_synchro = new toggleSlider(m_camName, "synchro", "Synchro", this); ui_synchro->setObjectName(QString::fromUtf8("synchro")); ui.grid->addWidget(ui_synchro, 10, 1, 1, 1); - + ui_synchro->onDisconnect(); m_parent->addSubscriber(ui_synchro); @@ -903,7 +906,7 @@ void camera::setup_synchro() void camera::setup_takeDarks() { if(ui_takeDarks) return; - + ui_takeDarks = new QPushButton(this); ui_takeDarks->setObjectName(QString::fromUtf8("takeDarks")); ui_takeDarks->setText("take darks"); @@ -917,25 +920,25 @@ void camera::setup_takeDarks() doff = ui_stage.size() - 4; } - ui.grid->addWidget(ui_takeDarks, 9 + doff, 0, 1, 1,Qt::AlignHCenter); + ui.grid->addWidget(ui_takeDarks, 9 + doff, 0, 1, 1,Qt::AlignHCenter); } void camera::takeDark() { pcf::IndiProperty ipFreq(pcf::IndiProperty::Switch); - + ipFreq.setDevice(m_darkName); ipFreq.setName("start"); ipFreq.add(pcf::IndiElement("toggle")); ipFreq["toggle"].setSwitchState(pcf::IndiElement::On); - - sendNewProperty(ipFreq); + + sendNewProperty(ipFreq); } } //namespace xqt - + #include "moc_camera.cpp" #endif diff --git a/gui/widgets/camera/stageStatus.hpp b/gui/widgets/camera/stageStatus.hpp deleted file mode 100644 index bfd37f0b8..000000000 --- a/gui/widgets/camera/stageStatus.hpp +++ /dev/null @@ -1,121 +0,0 @@ -#ifndef stageStatus_hpp -#define stageStatus_hpp - -#include - -#include "ui_statusDisplay.h" - -#include "../xWidgets/statusDisplay.hpp" - -namespace xqt -{ - -class stageStatus : public statusDisplay -{ - Q_OBJECT - -protected: - - std::string m_presetName; - float m_position; - -public: - stageStatus( std::string & stageName, - QWidget * Parent = 0, - Qt::WindowFlags f = Qt::WindowFlags() - ); - - ~stageStatus(); - - virtual QString formatValue(); - - virtual void subscribe(); - - void handleSetProperty( const pcf::IndiProperty & ipRecv /**< [in] the property which has changed*/); - - //void updateGUI(); - -}; - -stageStatus::stageStatus( std::string & stageName, - QWidget * Parent, - Qt::WindowFlags f) : statusDisplay(stageName, "", "", stageName, "", Parent, f) -{ - m_ctrlWidget = (xWidget *) (new stage(stageName, this, Qt::Dialog)); -} - -stageStatus::~stageStatus() -{ -} - -QString stageStatus::formatValue() -{ - if(m_presetName == "" || m_presetName == "none") - { - char pstr[64]; - snprintf(pstr, sizeof(pstr), "%0.4f", m_position); - return QString(pstr); - } - else - { - return QString(m_presetName.c_str()); - } -} - -void stageStatus::subscribe() -{ - if(!m_parent) return; - - m_parent->addSubscriberProperty(this, m_device, "presetName"); - m_parent->addSubscriberProperty(this, m_device, "filterName"); - m_parent->addSubscriberProperty(this, m_device, "position"); - m_parent->addSubscriberProperty(this, m_device, "filter"); - - statusDisplay::subscribe(); - - return; -} - -void stageStatus::handleSetProperty( const pcf::IndiProperty & ipRecv) -{ - if(ipRecv.getDevice() != m_device) return; - - if(ipRecv.getName() == "presetName" || ipRecv.getName() == "filterName") - { - auto map = ipRecv.getElements(); - - for(auto it = map.begin(); it != map.end(); ++it) - { - if(it->second.getSwitchState() == pcf::IndiElement::On) - { - if(m_presetName != it->first) - { - m_presetName = it->first; - m_valChanged = true; - } - - break; - } - } - } - else if(ipRecv.getName() == "position" || ipRecv.getName() == "filter") - { - if(ipRecv.find("current")) - { - float pos = ipRecv["current"].get(); - if(pos != m_position && (m_presetName == "none" || m_presetName == "")) - { - m_valChanged = true; - m_position = pos; - } - } - } - - statusDisplay::handleSetProperty(ipRecv); -} - -} //namespace xqt - -#include "moc_stageStatus.cpp" - -#endif diff --git a/gui/widgets/coronAlign/coronAlign.hpp b/gui/widgets/coronAlign/coronAlign.hpp index 02b51ff49..f7ef0b957 100644 --- a/gui/widgets/coronAlign/coronAlign.hpp +++ b/gui/widgets/coronAlign/coronAlign.hpp @@ -163,6 +163,8 @@ public slots: void on_button_lyot_r_pressed(); void on_button_lyot_scale_pressed(); + void on_button_piaa_l_pressed(); + void on_button_piaa_r_pressed(); void on_button_piaa_u_pressed(); void on_button_piaa_d_pressed(); void on_button_piaa_scale_pressed(); @@ -177,6 +179,8 @@ public slots: void on_button_piaa1_d_pressed(); void on_button_piaa1_scale_pressed(); + void on_button_ipiaa_l_pressed(); + void on_button_ipiaa_r_pressed(); void on_button_ipiaa_u_pressed(); void on_button_ipiaa_d_pressed(); void on_button_ipiaa_scale_pressed(); @@ -244,6 +248,8 @@ coronAlign::coronAlign( QWidget * Parent, Qt::WindowFlags f) : xWidget(Parent, f ui.checkCamllowfs->setEnabled(false); ui.fwpupil->setup("fwpupil"); + //ui.fwpupil->setup("fwpupil", "filterName", "", "fwpupil", ""); + ui.fwfpm->setup("fwfpm"); ui.fwlyot->setup("fwlyot"); ui.stagepiaa->setup("stagepiaa"); @@ -320,6 +326,8 @@ void coronAlign::onConnect() ui.button_lyot_scale->setEnabled(true); ui.labelPIAA->setEnabled(true); + ui.button_piaa_l->setEnabled(true); + ui.button_piaa_r->setEnabled(true); ui.button_piaa_u->setEnabled(true); ui.button_piaa_d->setEnabled(true); ui.button_piaa_scale->setEnabled(true); @@ -337,6 +345,8 @@ void coronAlign::onConnect() ui.button_piaa1_scale->setEnabled(true); ui.labeliPIAA->setEnabled(true); + ui.button_ipiaa_l->setEnabled(true); + ui.button_ipiaa_r->setEnabled(true); ui.button_ipiaa_u->setEnabled(true); ui.button_ipiaa_d->setEnabled(true); ui.button_ipiaa_scale->setEnabled(true); @@ -404,6 +414,8 @@ void coronAlign::onDisconnect() ui.button_lyot_scale->setEnabled(false); ui.labelPIAA->setEnabled(false); + ui.button_piaa_l->setEnabled(false); + ui.button_piaa_r->setEnabled(false); ui.button_piaa_u->setEnabled(false); ui.button_piaa_d->setEnabled(false); ui.button_piaa_scale->setEnabled(false); @@ -421,6 +433,8 @@ void coronAlign::onDisconnect() ui.button_piaa1_scale->setEnabled(false); ui.labeliPIAA->setEnabled(false); + ui.button_ipiaa_l->setEnabled(false); + ui.button_ipiaa_r->setEnabled(false); ui.button_ipiaa_u->setEnabled(false); ui.button_ipiaa_d->setEnabled(false); ui.button_ipiaa_scale->setEnabled(false); @@ -851,6 +865,9 @@ void coronAlign::enablePicoButtons() ui.button_lyot_d->setEnabled(true); } + ui.button_piaa_l->setEnabled(true); + ui.button_piaa_r->setEnabled(true); + ui.button_piaa0_l->setEnabled(true); ui.button_piaa0_r->setEnabled(true); ui.button_piaa0_scale->setEnabled(true); @@ -861,6 +878,9 @@ void coronAlign::enablePicoButtons() ui.button_piaa1_d->setEnabled(true); ui.button_piaa1_scale->setEnabled(true); + ui.button_ipiaa_l->setEnabled(true); + ui.button_ipiaa_r->setEnabled(true); + ui.button_ipiaa0_l->setEnabled(true); ui.button_ipiaa0_r->setEnabled(true); ui.button_ipiaa0_scale->setEnabled(true); @@ -893,6 +913,9 @@ void coronAlign::disablePicoButtons() ui.button_lyot_d->setEnabled(false); } + ui.button_piaa_l->setEnabled(false); + ui.button_piaa_r->setEnabled(false); + ui.button_piaa0_l->setEnabled(false); ui.button_piaa0_r->setEnabled(false); ui.button_piaa0_scale->setEnabled(false); @@ -903,6 +926,9 @@ void coronAlign::disablePicoButtons() ui.button_piaa1_d->setEnabled(false); ui.button_piaa1_scale->setEnabled(false); + ui.button_ipiaa_l->setEnabled(false); + ui.button_ipiaa_r->setEnabled(false); + ui.button_ipiaa0_l->setEnabled(false); ui.button_ipiaa0_r->setEnabled(false); ui.button_ipiaa0_scale->setEnabled(false); @@ -1328,6 +1354,54 @@ void coronAlign::on_button_lyot_scale_pressed() } +void coronAlign::on_button_piaa_l_pressed() +{ + + disablePicoButtons(); + + pcf::IndiProperty ip(pcf::IndiProperty::Number); + + ip.setDevice("picomotors"); + ip.setName("piaa0x_pos"); + ip.add(pcf::IndiElement("target")); + ip["target"] = m_piaa0xPos - m_piaaScale*m_piaa0StepSize; + + sendNewProperty(ip); + + pcf::IndiProperty ip1(pcf::IndiProperty::Number); + + ip1.setDevice("picomotors"); + ip1.setName("piaa1x_pos"); + ip1.add(pcf::IndiElement("target")); + ip1["target"] = m_piaa1xPos - m_piaaScale*m_piaa1StepSize; + + sendNewProperty(ip1); + +} + +void coronAlign::on_button_piaa_r_pressed() +{ + disablePicoButtons(); + + pcf::IndiProperty ip(pcf::IndiProperty::Number); + + ip.setDevice("picomotors"); + ip.setName("piaa0x_pos"); + ip.add(pcf::IndiElement("target")); + ip["target"] = m_piaa0xPos + m_piaaScale*m_piaa0StepSize; + + sendNewProperty(ip); + + pcf::IndiProperty ip1(pcf::IndiProperty::Number); + + ip1.setDevice("picomotors"); + ip1.setName("piaa1x_pos"); + ip1.add(pcf::IndiElement("target")); + ip1["target"] = m_piaa1xPos + m_piaaScale*m_piaa1StepSize; + + sendNewProperty(ip1); +} + void coronAlign::on_button_piaa_u_pressed() { pcf::IndiProperty ip(pcf::IndiProperty::Number); @@ -1390,7 +1464,7 @@ void coronAlign::on_button_piaa0_l_pressed() ip.setDevice("picomotors"); ip.setName("piaa0x_pos"); ip.add(pcf::IndiElement("target")); - ip["target"] = m_piaa0xPos + m_piaa0Scale*m_piaa0StepSize; + ip["target"] = m_piaa0xPos - m_piaa0Scale*m_piaa0StepSize; disablePicoButtons(); @@ -1405,7 +1479,7 @@ void coronAlign::on_button_piaa0_r_pressed() ip.setDevice("picomotors"); ip.setName("piaa0x_pos"); ip.add(pcf::IndiElement("target")); - ip["target"] = m_piaa0xPos - m_piaa0Scale*m_piaa0StepSize; + ip["target"] = m_piaa0xPos + m_piaa0Scale*m_piaa0StepSize; disablePicoButtons(); @@ -1448,7 +1522,7 @@ void coronAlign::on_button_piaa1_l_pressed() ip.setDevice("picomotors"); ip.setName("piaa1x_pos"); ip.add(pcf::IndiElement("target")); - ip["target"] = m_piaa1xPos + m_piaa1Scale*m_piaa1StepSize; + ip["target"] = m_piaa1xPos - m_piaa1Scale*m_piaa1StepSize; disablePicoButtons(); @@ -1462,7 +1536,7 @@ void coronAlign::on_button_piaa1_r_pressed() ip.setDevice("picomotors"); ip.setName("piaa1x_pos"); ip.add(pcf::IndiElement("target")); - ip["target"] = m_piaa1xPos - m_piaa1Scale*m_piaa1StepSize; + ip["target"] = m_piaa1xPos + m_piaa1Scale*m_piaa1StepSize; disablePicoButtons(); @@ -1476,7 +1550,7 @@ void coronAlign::on_button_piaa1_u_pressed() ip.setDevice("picomotors"); ip.setName("piaa1y_pos"); ip.add(pcf::IndiElement("target")); - ip["target"] = m_piaa1yPos + m_piaa1Scale*m_piaa1StepSize; + ip["target"] = m_piaa1yPos - m_piaa1Scale*m_piaa1StepSize; disablePicoButtons(); @@ -1490,7 +1564,7 @@ void coronAlign::on_button_piaa1_d_pressed() ip.setDevice("picomotors"); ip.setName("piaa1y_pos"); ip.add(pcf::IndiElement("target")); - ip["target"] = m_piaa1yPos - m_piaa1Scale*m_piaa1StepSize; + ip["target"] = m_piaa1yPos + m_piaa1Scale*m_piaa1StepSize; disablePicoButtons(); @@ -1526,6 +1600,52 @@ void coronAlign::on_button_piaa1_scale_pressed() } +void coronAlign::on_button_ipiaa_l_pressed() +{ + disablePicoButtons(); + + pcf::IndiProperty ip(pcf::IndiProperty::Number); + + ip.setDevice("picomotors"); + ip.setName("ipiaa0x_pos"); + ip.add(pcf::IndiElement("target")); + ip["target"] = m_ipiaa0xPos + m_ipiaaScale*m_ipiaa0StepSize; + + sendNewProperty(ip); + + pcf::IndiProperty ip1(pcf::IndiProperty::Number); + + ip1.setDevice("picomotors"); + ip1.setName("ipiaa1x_pos"); + ip1.add(pcf::IndiElement("target")); + ip1["target"] = m_ipiaa1xPos + m_ipiaaScale*m_ipiaa1StepSize; + + sendNewProperty(ip1); +} + +void coronAlign::on_button_ipiaa_r_pressed() +{ + disablePicoButtons(); + + pcf::IndiProperty ip(pcf::IndiProperty::Number); + + ip.setDevice("picomotors"); + ip.setName("ipiaa0x_pos"); + ip.add(pcf::IndiElement("target")); + ip["target"] = m_ipiaa0xPos - m_ipiaaScale*m_ipiaa0StepSize; + + sendNewProperty(ip); + + pcf::IndiProperty ip1(pcf::IndiProperty::Number); + + ip1.setDevice("picomotors"); + ip1.setName("ipiaa1x_pos"); + ip1.add(pcf::IndiElement("target")); + ip1["target"] = m_ipiaa1xPos - m_ipiaaScale*m_ipiaa1StepSize; + + sendNewProperty(ip1); +} + void coronAlign::on_button_ipiaa_u_pressed() { pcf::IndiProperty ip(pcf::IndiProperty::Number); diff --git a/gui/widgets/coronAlign/coronAlign.ui b/gui/widgets/coronAlign/coronAlign.ui index b245a05d9..aaa59090f 100644 --- a/gui/widgets/coronAlign/coronAlign.ui +++ b/gui/widgets/coronAlign/coronAlign.ui @@ -48,11 +48,43 @@ - + QLayout::SetDefaultConstraint + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + Qt::NoFocus + + + + + + + :/icons/arrow_left_128.png:/icons/arrow_left_128.png + + + + @@ -85,7 +117,7 @@ - + @@ -117,7 +149,7 @@ - + @@ -149,6 +181,38 @@ + + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + Qt::NoFocus + + + + + + + :/icons/arrow_left_128.png:/icons/arrow_left_128.png + + + @@ -232,8 +296,21 @@ - - + + + + Qt::Vertical + + + + 20 + 40 + + + + + + 1 @@ -252,20 +329,21 @@ 40 + + + 10 + + Qt::NoFocus - - - - - :/icons/arrow_left_128.png:/icons/arrow_left_128.png + 0.01 - - + + Qt::Vertical @@ -277,8 +355,8 @@ - - + + 1 @@ -297,31 +375,17 @@ 40 - - - 10 - - Qt::NoFocus - 0.01 - - - - - - - Qt::Vertical + - - - 20 - 40 - + + + :/icons/arrow_left_128.png:/icons/arrow_left_128.png - + @@ -1294,11 +1358,43 @@ - + QLayout::SetDefaultConstraint + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + Qt::NoFocus + + + + + + + :/icons/arrow_left_128.png:/icons/arrow_left_128.png + + + + @@ -1331,7 +1427,7 @@ - + @@ -1363,7 +1459,7 @@ - + @@ -1395,6 +1491,38 @@ + + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + Qt::NoFocus + + + + + + + :/icons/arrow_left_128.png:/icons/arrow_left_128.png + + + diff --git a/gui/widgets/xWidgets/selectionSwStatus.hpp b/gui/widgets/xWidgets/selectionSwStatus.hpp index b7987deb2..4cd97eb6d 100644 --- a/gui/widgets/xWidgets/selectionSwStatus.hpp +++ b/gui/widgets/xWidgets/selectionSwStatus.hpp @@ -60,7 +60,7 @@ selectionSwStatus::selectionSwStatus( const std::string & device, const std::string & units, QWidget * Parent, Qt::WindowFlags f - ) : statusDisplay(device, property, element, label, units, Parent, f) + ) : statusDisplay(Parent, f) { setup(device, property, element, label, units); } diff --git a/gui/widgets/xWidgets/stageStatus.hpp b/gui/widgets/xWidgets/stageStatus.hpp index bc5626414..a610d9336 100644 --- a/gui/widgets/xWidgets/stageStatus.hpp +++ b/gui/widgets/xWidgets/stageStatus.hpp @@ -5,129 +5,113 @@ #include "ui_statusDisplay.h" -#include "../xWidgets/statusDisplay.hpp" +#include "../xWidgets/statusCombo.hpp" #include "../stage/stage.hpp" namespace xqt { -class stageStatus : public statusDisplay +class stageStatus : public statusCombo { - Q_OBJECT + Q_OBJECT -protected: + protected: - std::string m_presetName; float m_position; -public: + public: + stageStatus( QWidget *Parent = 0, Qt::WindowFlags f = Qt::WindowFlags() ); - stageStatus( QWidget * Parent = 0, - Qt::WindowFlags f = Qt::WindowFlags() - ); + stageStatus( const std::string &stgN, QWidget *Parent = 0, Qt::WindowFlags f = Qt::WindowFlags() ); - stageStatus( const std::string & stgN, - QWidget * Parent = 0, - Qt::WindowFlags f = Qt::WindowFlags() - ); + ~stageStatus(); - ~stageStatus(); + void setup( const std::string &stgN ); - void setup(const std::string & stgN); + virtual QString formatValue(); - virtual QString formatValue(); + virtual void subscribe(); - virtual void subscribe(); - - void handleSetProperty( const pcf::IndiProperty & ipRecv /**< [in] the property which has changed*/); - - //void updateGUI(); + void handleSetProperty( const pcf::IndiProperty &ipRecv /**< [in] the property which has changed*/ ); + // void updateGUI(); }; -stageStatus::stageStatus( QWidget * Parent, - Qt::WindowFlags f) : statusDisplay(Parent, f) +stageStatus::stageStatus( QWidget *Parent, Qt::WindowFlags f ) : statusCombo( Parent, f ) { } -stageStatus::stageStatus( const std::string & stageName, - QWidget * Parent, - Qt::WindowFlags f) : statusDisplay(Parent, f) +stageStatus::stageStatus( const std::string &stageName, QWidget *Parent, Qt::WindowFlags f ) + : statusCombo( Parent, f ) { - setup(stageName); + setup( stageName ); } stageStatus::~stageStatus() { } -void stageStatus::setup(const std::string & stageName) +void stageStatus::setup( const std::string &stageName ) { - statusDisplay::setup(stageName, "", "", stageName, ""); - if(m_ctrlWidget) + if(stageName.find("fw") == 0) { - delete m_ctrlWidget; + statusCombo::setup( stageName, "filterName", "", stageName, "" ); + } + else + { + statusCombo::setup( stageName, "presetName", "", stageName, "" ); } - m_ctrlWidget = (xWidget *) (new stage(stageName, this, Qt::Dialog)); + if( m_ctrlWidget ) + { + delete m_ctrlWidget; + } + m_ctrlWidget = (xWidget *)( new stage( stageName, this, Qt::Dialog ) ); } + QString stageStatus::formatValue() { - if(m_presetName == "" || m_presetName == "none") + if( m_value == "" || m_value == "none" ) { char pstr[64]; - snprintf(pstr, sizeof(pstr), "%0.4f", m_position); - return QString(pstr); + snprintf( pstr, sizeof( pstr ), "%0.4f", m_position ); + return QString( pstr ); } else { - return QString(m_presetName.c_str()); + return statusCombo::formatValue(); } } void stageStatus::subscribe() { - if(!m_parent) return; + if( !m_parent ) + { + return; + } - m_parent->addSubscriberProperty(this, m_device, "presetName"); - m_parent->addSubscriberProperty(this, m_device, "filterName"); - m_parent->addSubscriberProperty(this, m_device, "position"); - m_parent->addSubscriberProperty(this, m_device, "filter"); + //m_parent->addSubscriberProperty( this, m_device, "presetName" ); + //m_parent->addSubscriberProperty( this, m_device, "filterName" ); + m_parent->addSubscriberProperty( this, m_device, "position" ); + m_parent->addSubscriberProperty( this, m_device, "filter" ); - statusDisplay::subscribe(); + statusCombo::subscribe(); return; } -void stageStatus::handleSetProperty( const pcf::IndiProperty & ipRecv) +void stageStatus::handleSetProperty( const pcf::IndiProperty &ipRecv ) { - if(ipRecv.getDevice() != m_device) return; - - if(ipRecv.getName() == "presetName" || ipRecv.getName() == "filterName") - { - auto map = ipRecv.getElements(); - - for(auto it = map.begin(); it != map.end(); ++it) - { - if(it->second.getSwitchState() == pcf::IndiElement::On) - { - if(m_presetName != it->first) - { - m_presetName = it->first; - m_valChanged = true; - } + if( ipRecv.getDevice() != m_device ) + return; - break; - } - } - } - else if(ipRecv.getName() == "position" || ipRecv.getName() == "filter") + if( ipRecv.getName() == "position" || ipRecv.getName() == "filter" ) { - if(ipRecv.find("current")) + if( ipRecv.find( "current" ) ) { float pos = ipRecv["current"].get(); - if(pos != m_position && (m_presetName == "none" || m_presetName == "")) + if( pos != m_position && ( m_value == "none" || m_value == "" ) ) { m_valChanged = true; m_position = pos; @@ -135,10 +119,10 @@ void stageStatus::handleSetProperty( const pcf::IndiProperty & ipRecv) } } - statusDisplay::handleSetProperty(ipRecv); + statusCombo::handleSetProperty( ipRecv ); //always emit updateGUI } -} //namespace xqt +} // namespace xqt #include "moc_stageStatus.cpp" diff --git a/gui/widgets/xWidgets/statusCombo.hpp b/gui/widgets/xWidgets/statusCombo.hpp new file mode 100644 index 000000000..c6abeebfe --- /dev/null +++ b/gui/widgets/xWidgets/statusCombo.hpp @@ -0,0 +1,459 @@ +#ifndef statusCombo_hpp +#define statusCombo_hpp + +#include "ui_statusCombo.h" + +#include "xWidget.hpp" +#include "../../lib/multiIndiSubscriber.hpp" + +namespace xqt +{ + +class statusCombo : public xWidget +{ + Q_OBJECT + + enum editchanges{NOTEDITING, STARTED, STOPPED}; + +protected: + xWidget *m_ctrlWidget{ nullptr }; + + std::string m_device; + std::string m_property; + std::string m_element; + + std::string m_label; + std::string m_units; + + bool m_highlightChanges{ true }; + + bool m_valChanged{ false }; + + std::string m_fsmState; + std::string m_value; + bool m_showVal{ true }; + + int m_statusEditing {STOPPED}; + QTimer * m_statusEditTimer {nullptr}; + + public: + statusCombo( QWidget *Parent = 0, Qt::WindowFlags f = Qt::WindowFlags() ); + + statusCombo( const std::string &device, + const std::string &property, + const std::string &element, + const std::string &label, + const std::string &units, + QWidget *Parent = 0, + Qt::WindowFlags f = Qt::WindowFlags() ); + + ~statusCombo(); + + void setup( const std::string &device, + const std::string &property, + const std::string &element, + const std::string &label, + const std::string &units ); + + void ctrlWidget( xWidget *cw ); + + xWidget *ctrlWidget(); + + virtual QString formatValue(); + + virtual void subscribe(); + + virtual void onConnect(); + + virtual void onDisconnect(); + + virtual void handleDefProperty( const pcf::IndiProperty &ipRecv /**< [in] the property which has changed*/ ); + + virtual void handleSetProperty( const pcf::IndiProperty &ipRecv /**< [in] the property which has changed*/ ); + + public: + + virtual void changeEvent( QEvent *e ); + + public slots: + + virtual void updateGUI(); + + void on_status_activated( int index ); + + void on_buttonGo_pressed(); + + void on_buttonCtrl_pressed(); + + void statusEditTimerOut(); + + signals: + + void statusEditTimerStart(int); + + void doUpdateGUI(); + +protected: + virtual void paintEvent(QPaintEvent * e); + + Ui::statusCombo ui; +}; + +statusCombo::statusCombo( QWidget *Parent, Qt::WindowFlags f ) : xWidget( Parent, f ) +{ +} + +statusCombo::statusCombo( const std::string &device, + const std::string &property, + const std::string &element, + const std::string &label, + const std::string &units, + QWidget *Parent, + Qt::WindowFlags f ) : xWidget( Parent, f ) +{ + setup( device, property, element, label, units ); +} + +statusCombo::~statusCombo() +{ +} + +void statusCombo::setup( const std::string &device, + const std::string &property, + const std::string &element, + const std::string &label, + const std::string &units ) + +{ + m_device = device; + m_property = property; + m_element = element; + m_label = label; + m_units = units; + + ui.setupUi( this ); + ui.status->setEditable(false); + ui.status->setProperty("isStatus", true); + + std::string lab = m_label; + if( m_units != "" ) + { + lab += " [" + m_units + "]"; + } + + ui.label->setText( lab.c_str() ); + + QFont qf = ui.label->font(); + qf.setPixelSize( XW_FONT_SIZE ); + ui.label->setFont( qf ); + + qf = ui.status->font(); + qf.setPixelSize( XW_FONT_SIZE ); + ui.status->setFont( qf ); + + connect( this, SIGNAL( doUpdateGUI() ), this, SLOT( updateGUI() ) ); + + m_statusEditTimer = new QTimer(this); + + connect(m_statusEditTimer, SIGNAL(timeout()), this, SLOT(statusEditTimerOut())); + + connect(this, SIGNAL(statusEditTimerStart(int)), m_statusEditTimer, SLOT(start(int))); + + onDisconnect(); +} + +void statusCombo::ctrlWidget( xWidget *cw ) +{ + if( m_ctrlWidget ) + { + m_ctrlWidget->deleteLater(); + } + + m_ctrlWidget = cw; +} + +xWidget *statusCombo::ctrlWidget() +{ + return m_ctrlWidget; +} + +QString statusCombo::formatValue() +{ + return QString( m_value.c_str() ); +} + +void statusCombo::subscribe() +{ + if( !m_parent ) + { + return; + } + + m_parent->addSubscriberProperty( this, m_device, "fsm" ); + + if( m_property != "" ) + { + m_parent->addSubscriberProperty( this, m_device, m_property ); + } + + if( m_ctrlWidget ) + { + m_ctrlWidget->subscribe(); + m_parent->addSubscriber( m_ctrlWidget ); + } + + return; +} + +void statusCombo::onConnect() +{ + m_valChanged = true; + if( m_ctrlWidget ) + { + m_ctrlWidget->onConnect(); + } +} + +void statusCombo::onDisconnect() +{ + ui.status->setCurrentIndex( -1 ); + + if( m_ctrlWidget ) + { + m_ctrlWidget->onDisconnect(); + } +} + +void statusCombo::handleDefProperty( const pcf::IndiProperty &ipRecv ) +{ + return handleSetProperty( ipRecv ); +} + +void statusCombo::handleSetProperty( const pcf::IndiProperty &ipRecv ) +{ + if( ipRecv.getDevice() != m_device ) + return; + + if( ipRecv.getName() == "fsm" ) + { + if( ipRecv.find( "state" ) ) + { + std::string fsmState = ipRecv["state"].get(); + + if( fsmState == "READY" || fsmState == "OPERATING" ) + { + if( fsmState != m_fsmState ) + { + m_valChanged = true; + } + + if( !m_showVal ) + { + m_valChanged = true; + } + + m_showVal = true; + } + else + { + m_showVal = false; + + if( fsmState != m_fsmState ) + { + m_valChanged = true; + } + + if( m_showVal ) + { + m_valChanged = true; + } + } + + m_fsmState = fsmState; + } + } + else if( ipRecv.getName() == m_property ) + { + if(ipRecv.getType() != pcf::IndiProperty::Switch) + { + std::cerr << "statusCombo: property is not a switch\n"; + return; + } + + std::map elmap = ipRecv.getElements(); + + std::string value; + + if(elmap.size() > 0 ) + { + //Go through all elements in the property, which should be a switch vector + for(auto it = elmap.begin(); it != elmap.end(); ++it) + { + QString name(it->second.getName().c_str()); + //Check if it's in the list + if(ui.status->findText(name) == -1) + { + if(name != "" && name != "none") + { + ui.status->addItem(name); + } + } + + //See if it's on + if(it->second.getSwitchState() == pcf::IndiElement::On) + { + if(value != "") + { + std::cerr << "statusCombo: more than one item selected\n"; + } + + value = it->second.getName(); + } + } + + if( value != m_value ) + { + m_valChanged = true; + } + m_value = value; + } + } + + emit doUpdateGUI(); +} + +void statusCombo::changeEvent( QEvent *e ) +{ + if( e->type() == QEvent::EnabledChange && !isEnabledTo( nullptr ) ) + { + + if( m_ctrlWidget ) + { + m_ctrlWidget->hide(); + } + } + xWidget::changeEvent( e ); +} + +void statusCombo::updateGUI() +{ + if( isEnabled() ) + { + if( m_showVal ) + { + if( m_valChanged ) + { + QString value = formatValue(); + ui.status->setPlaceholderText(value); + ui.status->setCurrentIndex(-1); + m_valChanged = false; + } + } + else + { + if( m_valChanged ) + { + ui.status->setPlaceholderText(m_fsmState.c_str()); + ui.status->setCurrentIndex(-1); + m_valChanged = false; + } + } + } + +} // updateGUI() + +void statusCombo::on_status_activated( int index ) +{ + static_cast(index); + + m_statusEditing = STARTED; + emit statusEditTimerStart(10000); + update(); +} + +void statusCombo::on_buttonGo_pressed() +{ + std::string selection = ui.status->currentText().toStdString(); + + if(selection == "") + { + return; + } + + try + { + pcf::IndiProperty ipSend(pcf::IndiProperty::Switch); + ipSend.setDevice(m_device); + ipSend.setName(m_property); + ipSend.setPerm(pcf::IndiProperty::ReadWrite); + ipSend.setState(pcf::IndiProperty::Idle); + ipSend.setRule(pcf::IndiProperty::OneOfMany); + + for(int idx = 0; idx < ui.status->count(); ++idx) + { + std::string elName = ui.status->itemText(idx).toStdString(); + + if(elName == selection) + { + ipSend.add(pcf::IndiElement(elName, pcf::IndiElement::On)); + } + else + { + ipSend.add(pcf::IndiElement(elName, pcf::IndiElement::Off)); + } + } + + sendNewProperty(ipSend); + } + catch(...) + { + std::cerr << "INDI exception thrown in statusCombo::on_buttonGo_pressed\n"; + } + + m_statusEditing = STOPPED; + ui.status->setCurrentText(formatValue()); + ui.status->clearFocus(); + ui.buttonGo->clearFocus(); + update(); +} + +void statusCombo::on_buttonCtrl_pressed() +{ + if( m_ctrlWidget ) + { + m_ctrlWidget->show(); + m_ctrlWidget->onConnect(); + } +} + +void statusCombo::statusEditTimerOut() +{ + m_statusEditing = STOPPED; + ui.status->setCurrentText(formatValue()); + ui.status->clearFocus(); + update(); +} + +void statusCombo::paintEvent(QPaintEvent * e) +{ + if(m_statusEditing == STARTED) + { + ui.status->setProperty("isStatus", false); + ui.status->setProperty("isEditing", true); + style()->unpolish(ui.status); + } + else + { + ui.status->setProperty("isEditing", false); + ui.status->setProperty("isStatus", true); + style()->unpolish(ui.status); + } + + QWidget::paintEvent(e); +} + +} // namespace xqt + +#include "moc_statusCombo.cpp" + +#endif diff --git a/gui/widgets/xWidgets/statusCombo.ui b/gui/widgets/xWidgets/statusCombo.ui new file mode 100644 index 000000000..4be82e71e --- /dev/null +++ b/gui/widgets/xWidgets/statusCombo.ui @@ -0,0 +1,116 @@ + + + statusCombo + + + + 0 + 0 + 399 + 58 + + + + + 0 + 0 + + + + Form + + + + + + + + Qt::Horizontal + + + + 40 + 0 + + + + + + + + + 0 + 0 + + + + label: + + + + + + + + + + + 0 + 0 + + + + + 16777215 + 16777214 + + + + Qt::StrongFocus + + + go + + + + 0 + 0 + + + + + + + + + 0 + 0 + + + + + 16777215 + 16777214 + + + + Qt::NoFocus + + + --- + + + + 0 + 0 + + + + + + + + + + + diff --git a/gui/widgets/xWidgets/statusDisplay.hpp b/gui/widgets/xWidgets/statusDisplay.hpp index 24f7ce467..434ee7635 100644 --- a/gui/widgets/xWidgets/statusDisplay.hpp +++ b/gui/widgets/xWidgets/statusDisplay.hpp @@ -129,10 +129,10 @@ statusDisplay::~statusDisplay() } void statusDisplay::setup( const std::string & device, - const std::string & property, - const std::string & element, - const std::string & label, - const std::string & units + const std::string & property, + const std::string & element, + const std::string & label, + const std::string & units ) { diff --git a/gui/widgets/xWidgets/statusDisplay.ui b/gui/widgets/xWidgets/statusDisplay.ui index 7bfd20757..149e5e766 100644 --- a/gui/widgets/xWidgets/statusDisplay.ui +++ b/gui/widgets/xWidgets/statusDisplay.ui @@ -6,12 +6,12 @@ 0 0 - 399 - 54 + 430 + 68 - + 0 0 @@ -22,6 +22,9 @@ + + 9 + @@ -51,7 +54,7 @@ - + 0 0 @@ -87,7 +90,7 @@ - + 0 0 From 1ed75f9177c76156716e65f5e67a224a781e563e Mon Sep 17 00:00:00 2001 From: Jared Males Date: Mon, 21 Oct 2024 14:13:12 -0700 Subject: [PATCH 17/24] updated gui icons --- gui/apps/cameraGUI/cameraGUI.pro | 2 +- gui/apps/dmCtrlGUI/dmCtrlGUI.pro | 15 +- gui/apps/dmModeGUI/dmModeGUI.pro | 15 +- gui/apps/loopCtrlGUI/loopCtrlGUI.pro | 15 +- gui/apps/offloadCtrlGUI/offloadCtrlGUI.pro | 17 +- gui/apps/roiGUI/roiGUI.pro | 15 +- gui/apps/stageGUI/stageGUI.pro | 15 +- .../icons/application-cog-outline.png | Bin 0 -> 5429 bytes gui/resources/icons/arrow-all.png | Bin 0 -> 5933 bytes .../icons/arrow-right-drop-circle-outline.png | Bin 0 -> 5646 bytes gui/resources/icons/arrow_down_128.png | Bin 1611 -> 5744 bytes gui/resources/icons/arrow_down_left_128.png | Bin 2258 -> 6632 bytes gui/resources/icons/arrow_down_right_128.png | Bin 2776 -> 6935 bytes gui/resources/icons/arrow_left_128.png | Bin 1970 -> 5747 bytes gui/resources/icons/arrow_right_128.png | Bin 10451 -> 13532 bytes gui/resources/icons/arrow_up_128.png | Bin 1896 -> 5937 bytes gui/resources/icons/arrow_up_left_128.png | Bin 2193 -> 6270 bytes gui/resources/icons/arrow_up_right_128.png | Bin 3010 -> 7008 bytes gui/resources/icons/camera.png | Bin 0 -> 7206 bytes gui/resources/icons/cog.png | Bin 0 -> 8473 bytes gui/resources/icons/controller-classic.png | Bin 0 -> 6636 bytes gui/resources/icons/crop.png | Bin 0 -> 4628 bytes gui/resources/icons/dump-truck.png | Bin 0 -> 5961 bytes gui/resources/icons/flare.png | Bin 0 -> 6347 bytes gui/resources/icons/home-circle.png | Bin 0 -> 5502 bytes gui/resources/icons/power-plug.png | Bin 0 -> 4620 bytes gui/resources/icons/recycle.png | Bin 32360 -> 32710 bytes gui/resources/icons/scamper_cutout_sq_64.jpeg | Bin 1032 -> 5516 bytes gui/resources/icons/square_128.png | Bin 405 -> 4497 bytes gui/resources/icons/star-circle.png | Bin 0 -> 9006 bytes gui/resources/icons/stop-circle-outline.png | Bin 0 -> 5586 bytes gui/resources/icons/tune.png | Bin 0 -> 4408 bytes gui/resources/icons/waves.png | Bin 0 -> 7195 bytes gui/resources/magaox.qrc | 16 ++ gui/widgets/camera/camera.hpp | 17 +- gui/widgets/camera/camera.ui | 4 + gui/widgets/coronAlign/coronAlign.ui | 8 +- gui/widgets/dmCtrl/dmCtrl.ui | 6 +- gui/widgets/dmMode/dmMode.ui | 4 + gui/widgets/loopCtrl/loopCtrl.ui | 16 +- gui/widgets/offloadCtrl/offloadCtrl.ui | 14 +- gui/widgets/pupilGuide/pupilGuide.ui | 4 + gui/widgets/pwr/pwr.ui | 85 +++++++++ gui/widgets/roi/roi.ui | 6 +- gui/widgets/stage/stage.ui | 180 +++++++++++++++++- gui/widgets/xWidgets/selectionSwStatus.hpp | 117 ------------ gui/widgets/xWidgets/statusCombo.hpp | 9 +- gui/widgets/xWidgets/statusCombo.ui | 62 ++++-- gui/widgets/xWidgets/statusDisplay.ui | 31 ++- 49 files changed, 456 insertions(+), 217 deletions(-) create mode 100644 gui/resources/icons/application-cog-outline.png create mode 100644 gui/resources/icons/arrow-all.png create mode 100644 gui/resources/icons/arrow-right-drop-circle-outline.png create mode 100644 gui/resources/icons/camera.png create mode 100644 gui/resources/icons/cog.png create mode 100644 gui/resources/icons/controller-classic.png create mode 100644 gui/resources/icons/crop.png create mode 100644 gui/resources/icons/dump-truck.png create mode 100644 gui/resources/icons/flare.png create mode 100644 gui/resources/icons/home-circle.png create mode 100644 gui/resources/icons/power-plug.png create mode 100644 gui/resources/icons/star-circle.png create mode 100644 gui/resources/icons/stop-circle-outline.png create mode 100644 gui/resources/icons/tune.png create mode 100644 gui/resources/icons/waves.png delete mode 100644 gui/widgets/xWidgets/selectionSwStatus.hpp diff --git a/gui/apps/cameraGUI/cameraGUI.pro b/gui/apps/cameraGUI/cameraGUI.pro index f2fcb307a..f59570c33 100644 --- a/gui/apps/cameraGUI/cameraGUI.pro +++ b/gui/apps/cameraGUI/cameraGUI.pro @@ -36,7 +36,6 @@ HEADERS += ../../widgets/camera/camera.hpp \ ../../widgets/xWidgets/app.hpp \ ../../widgets/xWidgets/xWidget.hpp \ ../../widgets/xWidgets/fsmDisplay.hpp \ - ../../widgets/xWidgets/selectionSwStatus.hpp \ ../../widgets/xWidgets/statusEntry.hpp \ ../../widgets/xWidgets/statusDisplay.hpp \ ../../widgets/xWidgets/statusLineEdit.hpp \ @@ -68,6 +67,7 @@ LIBS += ../../../INDI/libcommon/libcommon.a \ ../../../INDI/liblilxml/liblilxml.a \ -lmxlib +RESOURCES += ../../resources/magaox.qrc RESOURCES += ../../resources/MagAOXStyleSheets/MagAOXStyle.qrc QT += widgets diff --git a/gui/apps/dmCtrlGUI/dmCtrlGUI.pro b/gui/apps/dmCtrlGUI/dmCtrlGUI.pro index c9fb25c45..c0f24d44a 100644 --- a/gui/apps/dmCtrlGUI/dmCtrlGUI.pro +++ b/gui/apps/dmCtrlGUI/dmCtrlGUI.pro @@ -4,8 +4,8 @@ TEMPLATE = app TARGET = dmCtrlGUI -DESTDIR = bin/ -DEPENDPATH += ./ ../../lib +DESTDIR = bin/ +DEPENDPATH += ./ ../../lib MOC_DIR = moc/ OBJECTS_DIR = obj/ @@ -35,17 +35,18 @@ HEADERS += ../../widgets/dmCtrl/dmCtrl.hpp \ ../../widgets/xWidgets/statusLabel.hpp \ ../../widgets/xWidgets/fsmDisplay.hpp \ ../../lib/multiIndiManager.hpp - -SOURCES += dmCtrlGUI_main.cpp + +SOURCES += dmCtrlGUI_main.cpp #\ # ../../widgets/dmCtrl/dmCtrl.cpp \ - + FORMS += ../../widgets/dmCtrl/dmCtrl.ui \ ../../widgets/xWidgets/fsmDisplay.ui - + LIBS += ../../../INDI/libcommon/libcommon.a \ ../../../INDI/liblilxml/liblilxml.a -RESOURCES += ../../resources/MagAOXStyleSheets/MagAOXStyle.qrc +RESOURCES += ../../resources/magaox.qrc +RESOURCES += ../../resources/MagAOXStyleSheets/MagAOXStyle.qrc QT += widgets diff --git a/gui/apps/dmModeGUI/dmModeGUI.pro b/gui/apps/dmModeGUI/dmModeGUI.pro index 781dded3e..476c19850 100644 --- a/gui/apps/dmModeGUI/dmModeGUI.pro +++ b/gui/apps/dmModeGUI/dmModeGUI.pro @@ -4,8 +4,8 @@ TEMPLATE = app TARGET = dmModeGUI -DESTDIR = bin/ -DEPENDPATH += ./ ../../lib +DESTDIR = bin/ +DEPENDPATH += ./ ../../lib MOC_DIR = moc/ OBJECTS_DIR = obj/ @@ -32,14 +32,15 @@ INCLUDEPATH += ../../lib ../../widgets/dmMode HEADERS += ../../widgets/dmMode/dmMode.hpp \ ../../widgets/xWidgets/xWidget.hpp \ ../../lib/multiIndiManager.hpp - + SOURCES += dmModeGUI_main.cpp - + FORMS += ../../widgets/dmMode/dmMode.ui - + LIBS += ../../../INDI/libcommon/libcommon.a \ - ../../../INDI/liblilxml/liblilxml.a + ../../../INDI/liblilxml/liblilxml.a -RESOURCES += ../../resources/MagAOXStyleSheets/MagAOXStyle.qrc +RESOURCES += ../../resources/magaox.qrc +RESOURCES += ../../resources/MagAOXStyleSheets/MagAOXStyle.qrc QT += widgets diff --git a/gui/apps/loopCtrlGUI/loopCtrlGUI.pro b/gui/apps/loopCtrlGUI/loopCtrlGUI.pro index eb12af847..b79a5afbe 100644 --- a/gui/apps/loopCtrlGUI/loopCtrlGUI.pro +++ b/gui/apps/loopCtrlGUI/loopCtrlGUI.pro @@ -4,8 +4,8 @@ TEMPLATE = app TARGET = loopCtrlGUI -DESTDIR = bin/ -DEPENDPATH += ./ ../../lib +DESTDIR = bin/ +DEPENDPATH += ./ ../../lib MOC_DIR = moc/ OBJECTS_DIR = obj/ @@ -38,19 +38,20 @@ HEADERS += ../../widgets/loopCtrl/loopCtrl.hpp \ ../../widgets/xWidgets/statusEntry.hpp \ ../../widgets/xWidgets/toggleSlider.hpp \ ../../lib/multiIndiManager.hpp - -SOURCES += loopCtrlGUI_main.cpp + +SOURCES += loopCtrlGUI_main.cpp #\ # ../../widgets/loopCtrl/loopCtrl.cpp \ - + FORMS += ../../widgets/loopCtrl/loopCtrl.ui \ ../../widgets/xWidgets/gainCtrl.ui \ ../../widgets/xWidgets/statusEntry.ui \ ../../widgets/xWidgets/toggleSlider.ui - + LIBS += ../../../INDI/libcommon/libcommon.a \ ../../../INDI/liblilxml/liblilxml.a -RESOURCES += ../../resources/MagAOXStyleSheets/MagAOXStyle.qrc +RESOURCES += ../../resources/magaox.qrc +RESOURCES += ../../resources/MagAOXStyleSheets/MagAOXStyle.qrc QT += widgets diff --git a/gui/apps/offloadCtrlGUI/offloadCtrlGUI.pro b/gui/apps/offloadCtrlGUI/offloadCtrlGUI.pro index 43ff260a3..d25b9d263 100644 --- a/gui/apps/offloadCtrlGUI/offloadCtrlGUI.pro +++ b/gui/apps/offloadCtrlGUI/offloadCtrlGUI.pro @@ -4,8 +4,8 @@ TEMPLATE = app TARGET = offloadCtrlGUI -DESTDIR = bin/ -DEPENDPATH += ./ ../../lib +DESTDIR = bin/ +DEPENDPATH += ./ ../../lib MOC_DIR = moc/ OBJECTS_DIR = obj/ @@ -37,18 +37,19 @@ HEADERS += ../../widgets/offloadCtrl/offloadCtrl.hpp \ ../../widgets/xWidgets/statusEntry.hpp \ ../../widgets/xWidgets/toggleSlider.hpp \ ../../lib/multiIndiManager.hpp - -SOURCES += offloadCtrlGUI_main.cpp - - + +SOURCES += offloadCtrlGUI_main.cpp + + FORMS += ../../widgets/offloadCtrl/offloadCtrl.ui \ ../../widgets/xWidgets/gainCtrl.ui \ ../../widgets/xWidgets/statusEntry.ui \ ../../widgets/xWidgets/toggleSlider.ui - + LIBS += ../../../INDI/libcommon/libcommon.a \ ../../../INDI/liblilxml/liblilxml.a -RESOURCES += ../../resources/MagAOXStyleSheets/MagAOXStyle.qrc +RESOURCES += ../../resources/magaox.qrc +RESOURCES += ../../resources/MagAOXStyleSheets/MagAOXStyle.qrc QT += widgets diff --git a/gui/apps/roiGUI/roiGUI.pro b/gui/apps/roiGUI/roiGUI.pro index 45849f6ba..71138fc34 100644 --- a/gui/apps/roiGUI/roiGUI.pro +++ b/gui/apps/roiGUI/roiGUI.pro @@ -4,8 +4,8 @@ TEMPLATE = app TARGET = roiGUI -DESTDIR = bin/ -DEPENDPATH += ./ ../../lib +DESTDIR = bin/ +DEPENDPATH += ./ ../../lib MOC_DIR = moc/ OBJECTS_DIR = obj/ @@ -37,16 +37,17 @@ HEADERS += ../../widgets/xWidgets/xWidget.hpp \ ../../lib/multiIndiSubscriber.hpp ../../lib/multiIndiPublisher.hpp ../../lib/multiIndiManager.hpp - -SOURCES += roiGUI_main.cpp + +SOURCES += roiGUI_main.cpp #\ # ../../widgets/roi/roi.cpp \ - + FORMS += ../../widgets/roi/roi.ui - + LIBS += ../../../INDI/libcommon/libcommon.a \ ../../../INDI/liblilxml/liblilxml.a -RESOURCES += ../../resources/MagAOXStyleSheets/MagAOXStyle.qrc +RESOURCES += ../../resources/magaox.qrc +RESOURCES += ../../resources/MagAOXStyleSheets/MagAOXStyle.qrc QT += widgets diff --git a/gui/apps/stageGUI/stageGUI.pro b/gui/apps/stageGUI/stageGUI.pro index 0bd76ab3f..7d3b40d70 100644 --- a/gui/apps/stageGUI/stageGUI.pro +++ b/gui/apps/stageGUI/stageGUI.pro @@ -4,8 +4,8 @@ TEMPLATE = app TARGET = stageGUI -DESTDIR = bin/ -DEPENDPATH += ./ ../../lib +DESTDIR = bin/ +DEPENDPATH += ./ ../../lib MOC_DIR = moc/ OBJECTS_DIR = obj/ @@ -38,17 +38,18 @@ HEADERS += ../../widgets/xWidgets/xWidget.hpp \ ../../lib/multiIndiSubscriber.hpp ../../lib/multiIndiPublisher.hpp ../../lib/multiIndiManager.hpp - -SOURCES += stageGUI_main.cpp + +SOURCES += stageGUI_main.cpp #\ # ../../widgets/stage/stage.cpp \ - + FORMS += ../../widgets/stage/stage.ui \ ../../widgets/xWidgets/fsmDisplay.ui - + LIBS += ../../../INDI/libcommon/libcommon.a \ ../../../INDI/liblilxml/liblilxml.a -RESOURCES += ../../resources/MagAOXStyleSheets/MagAOXStyle.qrc +RESOURCES += ../../resources/magaox.qrc +RESOURCES += ../../resources/MagAOXStyleSheets/MagAOXStyle.qrc QT += widgets diff --git a/gui/resources/icons/application-cog-outline.png b/gui/resources/icons/application-cog-outline.png new file mode 100644 index 0000000000000000000000000000000000000000..75bded1594d21a0e62c189f8565b2d49d9d8d845 GIT binary patch literal 5429 zcmeHLYg7~07Cs39LeL6DskRnEsIAl{nS_Ld$WuT=1woARvf^Yi2@&!j2@tqGA|eV} zgtk&dMP1fnwW8DqqVljnL9d|osx40~)QVaK>aEC2?nywz)vk4~ceVeVtgP8*pS{1c z_qX>sYi2S-7cH1fd6NPFm>ekd4+DSzMFJpOz}s@oK`FddrHUeSVQ4Z{tx-wk@ifczP96UCMnXnyn(r!Yi}&F5qEhD5Y$VyqSC;$w8tCWuEEkx;t~I%Hh1H=` zGe*Ar@PKG$ly8lbU*b0#rqq-y+ee-@@5q%y8!kMsE8x82!pKgGJAb}TeEocFWVmIx zugz)$e=gtUj4<=gyBqCUEBLM3M%qX2v}y_aBJo2_c9x!D)O1>K zg+uj;wYPbVvo@I*&S0_crgV@?BJPO~Y>8|N%`D2?pR#oSYNz{}!bkS9lToq0|drj)qAM?mfFwb@Y>^Z$0_Eto2kN{ID7^p-g#u<8r8a5pO9^QI2ipAkNsu-8a zm7cWjvz0WeT;fR!=LRFeYCk+yE=<+nOHvn!u+%urT|)ErqIl>95I}+JP^w-Luha_k zo-`A#0Ln%+lSVa}=;AzS5y7EUKa~cjau^&2LJ!c(lh`yb3e`g+kqW~6=Z`_aktZ!y zr&9}<%;e-`MzSkIrI9gN?(XhPgw15L>Cl3%O;PGlJzc4FHbRVI_~TkkBUkI>Dkas3 ziHcQ;I!_u6&QqVor%(q6kHagqV=O>En0i#rWHAt?LcyHqq16Q>L6EV4{?tP&f?Jds zhHF)c8VnCe!j(Gbi4YQO++Urji8rMq!I*eFu7IXmxGL*~B^Lw+hmLy~DUit(YLgcv z`vps#T>6}>7h*Hcn9`XT2y`FEeZl%!?j~bs6&x(^S7C|9@B;lkX~y*h5)~$w2uz|I zN6ceMd2Bl04QJCiY!*gGad#G-$Hm1`34(EXQt1S!K&4iPDlyy$1;H6|h{NL}58>m`kIs>D-RLOBcBNw|&kaK)5{?@to&XV|k;AS;<0nRCgpxogl+R_cSsawk=kjnm z#~tI-Q9jD0i@9vRRKiDGIef$fCBX#qRT>2f%PCi&GMuSa%1jeR!Uevefu1xrW7O27 z35`c}Qt04G3z91n_0LU3as|FbhZ@;r@!0NMS3cJjabqKF_5|-`xJC;*(TK@H7_M$6 zcVk%uFd0ZJYV1=8VA8`}1b!ME)u}Whl`7toW(QH}FheJ?=%@ME= z0h=Xau?1|l0O8XSo&cF(uad~6DgVvdxOu1^qa_#0wQ&6ulWKHFEx{8;N29}dxoIm= zsisXKK(Wyjv}h78F~te7MyIe?R4K#Z=`q%>&-C&?X$6kEt2@HSaXK!+`E(8k)=!LM z?sN{q5p!5L?#5>GUPRZbq`G8OgZs)LkB}?ao+hrSvrUC^dC@vK7B^M_5=Lhs^l`$V zJW3dIEMcbc%y^cu2lEe{c$f?(95T>vR0j_)cos6p55qCejK|L3c#YNKZ(IRFzgpy_ z_Pj;HE|6sDkh)#-=tG6b2zq9>NW29xr+ODLNyH9v~L6kpShJDTTF^~Iy zAI3hfj@vePFsML55HObGzX&~1cO!8b;tJ?5#9v|;q-uCtxFXNY_tMoL$4zVM6~B^ISC9_ zzy|mjzi^QLXTh+x_;^g!jias^LDF@dc~+p62#A0TsK5aJ8i5Lu2>&1649|z9k5At$ z00tWl0XW4H!MrOZkhRGNRB@mXWJUxuD!7$r98&?6Xd0SsJr}Plop)Y7+P$Z~uPt}Q zPAh}Ry0Wjs(KbJq1Socp9rewaUN`7SdYWF8#ML^V&-ZfhUiWaf-Rg}ko0Ci5 z`}R~mAg8E?`cg{n4O+@nn~qxS5ArG8g5Ty%S*P-=d4LdX9^Sirnu`&uI+*9SnH!^9 zK5X3`M*w!<^gwv)9U|E1OoifEbFihdgJlEjZ#cZJ7IOkCi6DF=tIi)Bdt&YQ7QyhX zhwbJDhra0O1d6`zX6&3`KG7$0<%9lyijxiaV94L;$1@Fu{D;mlfU1kqp|XTL?*w}=`_dyI)E>Ar_C}l{tuGj#FDDKA98=UZ997E@STKJ`(I`m(@@ZWuVY0#EitnSoH1jRD(?2dN9jG|FtIT=z5Jp(c0g+kc?de0a z$(>(E8(788$vM+~N~{1ogwReRl?F|qzUF7l=j!zS#VhkF^;`l>Bx28qUxGDgQ<9xR0IYr@-LpZGVMR=l&7o! literal 0 HcmV?d00001 diff --git a/gui/resources/icons/arrow-all.png b/gui/resources/icons/arrow-all.png new file mode 100644 index 0000000000000000000000000000000000000000..5dbb8106706a20a8e9ba9a91f68aa8ec722eedfd GIT binary patch literal 5933 zcmW+)c|4Te`##TOhMBRAt;jYiOZKgeFt$Rn4EXH2D>HdoUt>rY=bOa z6rKBd{3fQ-LS1sgsUW{(kJN@rwc6*KiZ?C%u{%lB@+&q0@eD;gCSRrCNO;op->D=s z#r0Q3g?kOcf*X?CL&hGqjkS~3r`D&}S&L*dR|F^R;x9`7sd=z1|2wCr%Bkd!?!qqg zNTRh?ZsGS4L0}-Bs50a$nt-E!x+6&dnr^9Wj^sWZ9u%VIqg?5?U=&hu)_(5!Ip2v>k61{vL`I-0rH>E)gM=HRin&(d|ArWz46SyvNTID18FEW*qR zk4V*;-r?4+3e%}(1>#b#D*&Wh^ILLA!#cU)#%Ck9Jw)K@rmb=m9W6xw(W`-m>W=wv z09avox%m_>R>O+{s&CqH0ifwYHIQnmB5Drx!i0TENvr;cyCwY%(rx^<0VSD>B2u9z z$(;ljh&Y{hufcTx5p=UU6-FM)T+~x{v?s4=$M`@*Z_}UjfRfkgHAp7RGp+UV3A?j1 zvxUU#0fg5&H3}(s2c@KpcKHALmq)?BLvCh2mB4y^>`z^UQu$uY!T3z{=rud=^{b~> zUJOgLE!+ZmR$pIf&Q1h~yjXctm+fh$;#H(;s_4uOjs8-gvMq41M zO?)}0%nZlFhuYq*N<+Et$XAcfE!!%x_G8H6)(xlo4Z-UfMohJj${Rc@4nX^AG@^EZ zyfe`a?RCU#_8SXit8ZukMch`HrCD}rs~NAh^WLcSF#aZJI=S51Y1prbB^zFsRn4h? zuPpUJqb;7TZ`ige$;?S3vh55~Bhm4&?wHI?8@n@GOeK6x*FVQ^Rak=8(Y2>sMOgbq z$vbfMg}WeXO>mp%!TuQ;)Cbe;(lBw-LN(A5%ZlSCr;TdJeZT{phSU5n<$edu$a@3X z6B1x`+fOmDE^TY}X&x*6{?vmrco4H~>=rvgy!z4A0R31!Wm6e-<@{<02KY{#u~%#0UJxcT)B3l2&_11a3_j*&}NsnFH2!T zc#re3iGzuc{kOgo{FgyN?TpB0b%@$@F8!{b&P``^twNd+ru<29{Z~8C^rWWuQK2qP z{A6$D>7_=#_p`buO;bQWQMv`5%a$ z03Pha4c%sAAz70uHhysMMwv?w$zkY!$iAA6VjVwW2_5D!c?vm0k9bRYCCb@8N+8Yn zky$p=tX51>Xxn!Wn3}zk!`EsV@-6tdRT^^KGTvGVbj~`f{{HJ*Af z(aGLittjP0c{$$G_gSOZDxi`s4RfNx#o(y=vcqG1NcH(`l+IIIe@@)7cCa9%_MwQ0 zHxuSW#|!WUquN`}7GPsv6@_U?Ykb!61xt<>R^1gSfKXDzmkuR=^@BGO{shIk$8V?8 zz$J%-A7*?9_~_}qk;@y1UVf-&F>)g}Hu0j5zAm6O&gD+gJAXvQ9}U%hVq z5HbmM7RkUAs8xur+Pi5ht?lweDwYV;G7d-t@WE&9KKI|!fet*X1oVDzyaz+Z^;24V zdq2qnB;f-Sp|`VrvN{2Sf6g~jFZ^V8A4HyI&MeBYlFPl{rbeiO!M-ueed7ABXp$mu zc;nLjzaawy6Z>d*FfHpRfOzdvM%}vS*MWKRGK_)JwORf+*cKMM4;jx_(hVl@7;T{m zBd+)eQC*#yh0+ zFET~>=*=Q7VDK{NH*-r3I-uhb9)N=Inm!{|0^}A@ybT}J!%+r!L8!=#Dkf6--#aqE zY%@*#oUoZPL+Y1+#aVY@q8ci6>#I9XlnBzos`Q2hU}x4{6rzJN6^Pig%-(x)k0w8a zue`_9#G)?sQ4~Q(m17SDQ^IaUt&l4VvgfJ*)KuXyC7(~(2zxM3V1#XPfb`6o9O}DX z%Ka;trQHL(zf$FYbHJPFei0vkdR27ai&i|#3!;zwAeu1Oe_Y4Ck^oOLnbVIi>P)uQ zg;cY(Ab(ldkXBC`{uAqex}(;(BnuqEFcJY*c&hgin94FPG8_28jhogYLo_Ty6p;8C z;bc9bV`1~p2rMjB{*zG57fZ1Orfh=DoZJ_BjT0Xa%Ypz;xGxBe#^m zNclNqJTw@bj76@uyGLEn7|cQup?3zFwjdDS_D6ZmT@fR`X#t%IYmmZ#i^~5L;vE28 z6zXi@hP2QoHJu#YmmFeWyoy7kr3+_GLmW4%y47z?&4UAq^xG%lQR%8UFok2B0o)T^ zdA}mvtc%y)FJTGOw=Yrz9P`g@QVKUpMi(Zk_*#YO22aitHD*d7-GY=s#!TH^7t;~( z7Js>E*gh*|>HFTr@cJuq%QA2m>_5q|?6?FmqQDbNqC7~V3%*Ldpz%3JA(Ifpj9d09 zZkKxGh53y^_OLW8si9x$`21I$zI+&vlI-e|KHJNAVI_vjbdQP5+Tu&(qss#YSyPeZ z!wnxCU=%$#Qpd9^@JaIA%mqjc#W^1wch~_$Fys8j5>_5%M+rddd%cz?wPpf?&jQce zHDgzix16O1<5RMCZc!QtgMwgRzs{M|RK2CJr&Cp9uL(^;QtaNyU8A7s&f)7odOtU+ zq@7F@1(?0u!A%lA!=Pd891L2e=^6?iTmMXwJHVm)ZjxD%nUKHCbM>h1q7-@9gD?Kb z9k@`uhU>0K`gL5teA7A)2fY za$S7fw^E&qn0M!cWndGC(E+ydHhOiQ$>+A@ID}Qndhvrln`|*;X5p$&_J%mJu6nRTa{auOFOT`2 zY_5`^+X7$jkGHhGmHplP9xia!3{opFt5(hHQ+)h1(3$sMiFo){gS3o`4A|Fj$B-NS zE{P8)4GI8}I9t}h_Rb>!4?}pH2-qgdq2t-!qLjA5E*QakE?vJah6Rj5^2|yC>&T-J zePlIh>%3GFKd}p+vE*lFAUweR8a69~griX>1d3S)=GQ9TdH?AdPNy z@dQ8J1SnwlTL0JiL1E+i`Ft?pmX4QhbM{0dSJ`d@<5~qXPfQ_Q5}JT|8m$K-!V*aZ zW}l5{#!sYJ5`cAHOn}_F(BB1a{3zeP-JlnB7(}!R6q(f)%Q`HE4`SU`{h-R-8L7nL zrZ4!6ESW=-;vjU3p}%B5t3_|VlZG&4qwWNa$o#zhcR6hH`f;^owdI$zp@pvC@7S4X z?xi$?{O#;>T#Z-U`*M$>4+xM21(iP~ZpEdKnR<^s$5Kb~X^+>uDL6@*yqYj5qNsfJ zA(!FRu%L*xJ~qE4fX+0hN`g?*J~OEaS1JZ&2M}h+f`FRiO3obgp8t4{2zd%n*?h*S z!|hH44OA42FqbQ@w!O1KH=7f-^RT|Y!T8NDRY0rjfyr__SE;0yx5l509=U6Jg;vkv zZFr}eJ^o#M1T7+IgClDLYRunvnJ?Z}!U{N7VbJ1G3LmQNzwhdQj9ku)TPQb$gp!m{ z6XS)Fq0HhtQ=C7bV7wInI*=TD_sq+wqsqMjq-3CZKC6ZA4Q|x1Ox7$|%Wfa*E&vp4 z;16YO_d@tYzaI`5;2Fvl%~yij6LEq2Q*6P?ZtD1fY*!j=-RHLhq|xoaFpUJe>m~Mg zkY;KZsRe8;fZ!d!De>31lFOJaFu40F2jV<+6cZ+?h5pXZSH!7@sgTsF?W;5&*!`st zkNRQsB{LNTpG`G$JXf;0*jDcwsbXn}YYjURMej5<XOu?oCC;S@EGF6!SOpA9{zds0OW3z4??J0du+gBqH-HMr1s1Z z=gt;RH~pzGIMguE)t%vHCOyUHdq8C6jd@OQ@f62EK4^?%4s2rki`;YZp0lHGK`A(^ zp8~lE|FZfBZ>$Hc2wBh_j9>;)$CthRPvthydL9o)Ver6^R_%2b21*3=Z`aJb_z(}$ zsm2k0U_o@BD20fuH;J?VRqud^7|rdiE?}_)C6^*b-}^?qCTAl4gWpP9>G;bs;23{f zg@TnF3sfWJ07m}In?C}n4*1~?sjmKfXEi`X0MitEsVi~fcl$NF z3o4%?VSI?+#x{Tb0S(aV)f}D?CvGKz7N zL*z!_&5Lf^8aaHNBtGIvjGW2W&|XeGOi)G@vm4=+8v}ZE^a%w>m&gbLs;YyX2U#sb zh$Ozcn`1H!KivEq02BxdKNC!7UQ0!ibmPBURJ7}-c^6tSPk>pCkURyW$S+lZZ#?-g!gz&prEhudJpg%cErwO0^>OlWQo;wb?ibS# zBf2e_o3c5>w{nx4KDL-0BGK8t;H&qnd-29!31a~|850CVML6 zsk8XCVk}_ndiip~suwjcVHnxRv83WLo`7D!>y4;uHv4NJP%feBGJBA9)q-jWn0*eI zz_Xe?`Y6PzBKq`hrYMIQ`mlB0B{F$akwJmqSfEwq- zF9CfzUGhAMgSv<5%U`5Ni{D#{`kiPmcMaf=R_Hrk*b18ID?vq-f`A6jWSJ4hyP4a@ zN2#vvCuH%IgDmkH;oN(E&t@f2Q4n#M^P<6QlADt8MugC0Z{FrAcd(MjWtGlbcqNu$ z!gaoK8ZV6|mX|yYhnx#iQ1H>o<@NQOtA~_|O+e_PdaLR!&80rB3Sy8te6qAvm^`A2 z>*YslS) zD*eEXXUV1~*j+WD{Q;w&x)r{4PDFB}DHELnmwHpAGV`P2Od)FHH~i1-K*44^N&lB0 z)LQjzTp`=Bqq3_r@k*o<*`#eeBgM!6BlGTVFmz`l5-e?E*b)tNJ+OYoVZQGm8iV}) z`xApC4e1Qe;tW$hH;aR7Xy5b}0qBWwY9Kts=_xnC+4HLX_nN3*KR(7O7tMJ5gZzBU zK@pJ%F_$t2cui+Y?7N(OfB2S&RY@%l!hdYkMmz+pEs4rO_soCYo2e9e-@Fqv+jjkf zS8A#=?)Rf^$0BeUtB`)<>nY~CQGC9}jyCnWv#gmr>J8H|O{y@mbGU+SC zsCS`Tv*H6f#Q#Y$uUhyFY2@iJ7`zv$`xh+{)OtxApN>7QKmQ+KwLD@MTjN1Lxi-7J%1{3E!n$ED)xHk4g8& ztqzG@Ah*1>+J5uCGZA5iH-%>ds(H|xa9au3Fom6{(t`k-oppuO9XulX^IXityg>EV zar!KO0D;I_NYXz2ADa|S)53t;!9AYEr)o5f(s=vm3<|g1)x;oEUOz}CikLx;`j1=a zC8t7hAp7gRj;HGr2+Kocb2F^yI2du&D)F8tP%msTZ`Qip4sgOC0Ylq;;)USvOr3U1 zZEa@+;Cn`9sWBMWQ>0Rr-YN0$WbWDCqRBFW$0W0_{%Nk-BFDBHxr{HL+Rt>`UuT>$L!wS1gE2W#EPhF~z}#~{m!RiDgd1YW+D$V>=h%eL!*Ge)4zeO^>M2P3;)ai2jq)%rT_o{ literal 0 HcmV?d00001 diff --git a/gui/resources/icons/arrow-right-drop-circle-outline.png b/gui/resources/icons/arrow-right-drop-circle-outline.png new file mode 100644 index 0000000000000000000000000000000000000000..9d04b2688ef76c0104c8490b053e5c85bab12249 GIT binary patch literal 5646 zcmeHKX;f3!8a=rN2muN*6rAccVv!-q%>Wq$4GIEkgaCCaYNneI1rm|~0Wkyxtri7m ztteKD!_$h|T1925f-P-9wAE@$jUt6t^#N6RC=}jFK*jaC`j%_G{xdAdJ>R##ea^Sf zK4)>)#mtRxB9A5m0Gy&C!(ss-z()cg*}|^`?O_G{s>+IAppTVgpc<`Op-RG0eWnIS zaf1pb4Y!hG-hb;N>e$=po1S-pe21%l_(`+)^3uesN0L6vlbygOoT%FCeAWr`ZIAu* z^VlmN3&&)5uE{lGAHS2mYV#poPh_{>l1YyKnfHSa`Pv>izlau^9xdCm;h^Yd13oDG0=F~N{t3sFQewx<%+qIwG&WYHWF(FjB$<^tr1>~!1 z?|gf=Mf2Uq&c{dnI^rqkkXxti_fZQ+5T2d70sG2R&6p7rHDku}R$v3gD>sEiUW{?i zkB$rX^;kR4CH1SAJrDL%Hl8MjA9h)mKX2TeCC}`Hqc^*IM%0`(n;WG+)YLAVZ#O^G zrH_!Bu8Gxea_yK+rb@Flnd93kbZ0xJ3KHk-Qaten!ZY8^@$>!l_oLF={?omt=lP+m zZ+33^gq?lkMhKE!_2Hv{ffYH&38%#j6m|94DYWqVHd-lIEu zKHi2OkJ~`W4-W`kMY2hYkICP_eaQEHo2lRXxU2B2aa{tr+)sROfxv0B{DyPCU6pdV z$DwyCKGC?guS_j2Wb9LWCI*ge>-{lxk&mEr)Y+?3`WLzF{KLDVsYx19Z4T0;HaBez zF>CF-j7)i4dMUasCIIPBJ{D%8T8F&r7s^jJral95)x3X>F`Hey=%Vg(jpuvMw{>^y z>FzUvSWoS)>9>k_&~gS9wAKRQ9KKAQOq0mfQk-T;)=vn%Xo6iw5jA^10ND3<9Z2dNKQ)8@eLsq zD=!~DTf%e-YK7>Rhfo#>W6&9DEsnBjY#K%lH>lE?l&NGiSSwfXW5Z?+QNU3MB~h=} z@ago7j0{=^i>B5p=?or^N5`0SCX)&gR9$9@USgo8=q6ey206lTolL9J=vC?z)WRu| zs?+o#6bj6v&)1i%5ei?>r|5=MfO^mk5)GX}!|2J$^x+jceRw(~8CuYvR_Nm438ly4 zI(3>>hKHx)Df)@SDde&j^_nzolC>SVjE*Pa$q=f8vocP{1#QnS@0RWb&9erU>H5G3GFeXsrsmQj#=$RTe5aqzYnlxlATYPL(rc z7?q97xKwEnM?qyVgQN;f%HYDOtWmpN|q>bx+X&H5nWxFObD$b9rnYmlYKF5;PCj>Yx)XoD7V{ z3bJM_+ro#% z<})xplM&Bg!oPebhl+9d*f6|Wu2N+FFSOGR8B5v6QC>WK2 zQC|wi8xo8@)G*z0XFTsXnEqdy1X}^aE*V%i7=xD=ybI|sF2faWi-} zNTlk{P$E(M7#)FN*)9Zv*R)6za2y{d0Bf8nD7a`h(#6!ZnnfWOlT1Fz*^4@Bt4{US(H?9+P-yZ7o~ETat{NM6Rsw{!&l213Bx;lq8(mD473sh0 z2-p<+_E|y@z3t!Kf++LP4Hu?N$#INCNV*Czt8J`(djkV8>_1jJ@a-02!~H8$SdYj8 zq?2sEQ9_KlfNZah1kH1)rQQVnXTLiMPMXJ<;x-Ut9$b%|?keCMI7$Om{oeazl>`&< z#BQ);F&_>!-*|M&gJ{6jxYGC2U0fB?Ab^&JUlZmiFa&4S8i{&aF6J#8hMt~jzn9&6kj9+0d=&9@QE$*7L7)CrH znh3lGa&&jc$I+cf)pa1Cpag&xAJA&bc58h0l|yv~Xt@zpHdIaoEti)d23(bGhxLEi zJ8-n5!T}6b6)(a1G z6)v{v{OwdZQZTT6>448?sqla#fNzufCZ{L)mUJE1-IP`aj>EaBw_*K{B2eF++561-HuvdRgxyY@_~si$`_O$cAK({#G@oyz72} z13LO}*Zuk?Bu3mg*GK~jj&a-(viWP~ZI=^WCAT*$W+v3emIM%5IQ?b!cDFl?U;Kst zdp}&dQvTS#`eDrsy9BU%&0SZlAKIGhE$(YJKFuK%uR7IDMkntub$Lz+L?#kiI?})P zH@S%pE+OQ#L98@q<_8w+FVH*u`UZcKU@=m+^g%soJIS%?r^1m;d#{``o|Oc{nXT*8 z0LgG_4?Sr&G268$hch5T!izFFk3^*WqBPEZkz;F-nsZy^8oo)zxhC=|-6Z2&7QJJ$ zc`@g_$Q$20pHn9CtKBT(91vmQTcS8_`EkLc^74y$)Beccx3|1&t&JvYLiFTA@D2%c z@jKQQ3A{C#M?!oM6iQBTAvl&mOVve#FmTZan!n2p*jM-1n@HjwqJW5H4}*OG)(pXz zrY1Kqvbu8!W{YJZ=!gS$greN0)qqrE4h4DQP81~h*~olALI7!m-Cy0b0GQ}zdbWJ& UlW?=^V+%4Wd~VqB>Ec!Y0iyWQ^GjoOsGh=3$8E&XB653(ZmQpz(L?LrwSKF$?)|Sb>&)5byT9Mh{(e9EyT5Div(>}R zSzFUk69$86GhG~(L(e$n4cCDFuP+8_pvUtlZ$IgBK!y;Bg*<*Jh>$8oAOe*0c`%s# zL4v1ePB{WTI;=MchwF7yBU=^@YDABwSqRopn!8w?dQO=p$KSt=&OD+UKndC zudh|d+tBalpoZIXB|p7oxesc`FBrM$l4jp=%;ff-XrmkXG2}zGf-Q+58HIP6iZ46a z=Nw76w!Z5{(1T7J;*6=z^q0<5{Mqiv!U0=ZW5`Lp^A%#xT>Js{&Wm_{ne~OcPcN~Y zmr~)tll=XUw#usQ0;kVGcL!JuG?rP>j$t#7+UDMFpX@Go^^21jC+u<>1U{tIk}@zO zb%hN-)v85OauOTkVKB9ge0zHjroH{=$f0;s*X?1rT(>c*SaWx6mbcLkMCa~f^kzp# zqY(XV9`hSD&(M>0#n|qPUr z%I!{W??$h|3*{G+MHOsPT+w^AUsZXE4ZS=I& zCwCU~W%}K?6Vp(&r1LLFadp=zoB34}*4{xB#pEs-X*=VSdg%4ubmq~Xitxpiaet!k ztfk%_&U;+o7Wa@K%94#1F2ufLMrCAF?2KC<_OSC(Ms@Vn?y1;OuFLT*SKC7YdGL}W z^_1@QW&VhBPloQdSM^TZot4u-xmq?KyE?r;;)rZGV))Hqa%Aih@?r5#a&8HfkJ@rR zl!$(;Wps`(3=MFFY!EFE6G0gYgIO<;ivUgtC`GWrAijWs94x+qMDV!`q%VnuWr^&; zV7^O~81#yA^X5c_aA;iQlEs?VaykSM21)^hJStB02^mlgZFB0$L~z!r*8$ z8U~BU;PEI(10_)iq<|bHkeDbT#xNW}2}jHqN%=wnLWv2mg%MH)5()JqKKmCYVzIu! z3nZUdfcU`30TBj=#$v+4Fyk#GQpZRLp{j7W91Iu=hC!+lXjI%cLpn2A9$ze!6a?|ZL@FzY>~A!seBM{GzVS`jqY7ud zBarzQ+;6l$$F5R_v{)>8V`>m;PT3c&JkC>#|4sRSC9 z#N|;`P+Sh(Nhl5jpy}j?0YM-}BnVPi+d5{4Exr{G}kbmv) z=7)h^Qb5Tjj)JF=h&UXXM#7QEgfX90cq>4$1ji2v{VeDILn`3#6g)_P(g#n$;ZQ^Zhlrw*0UnA>WMc^ck4@td zINzd6ggmJX5QDZs5RVX7P$L@p~O zFxb>`<*jzWa_SsNI9bYMIZl46sjsIo1v59P77`gq9sQ*C!Z78o9H!bVf?R}*FAYX0 zH;caOr_O@GCe<(9{CYbccxq+fZsSi!9l%Gl_z~C^%KQ?q=(`}${2rzY+4(#7< z1m+nGy~P%Poah-#Bcf2OmbSKaeKxlrfmZP?+~7ukt3-xQpju{TX8*DWmoxSZnf(5H z<_&9W>(m`fuUd!G)0`F5ig`C^qjsU8{daW&FJ~`wZF(V2OG`?Ut53MK@7`(O*oy5i zg+dXTcYoom5I}QN`eB`ybD!<&;0E8y_p|b1pK)J!|C*q^gw}g`U|YiWj*DCGRS&;= zpFb2qDh@XeTpw^HhOxOj<72iY!gy<`ljl!1=0mtGyW_n||FDjK?E1#60K zUh5*5#JOb?6s^yvuTcLpp%ul=T47+hX=m$@23fE?qk>aQXJ<*bWmzXjFX;axk0adv`sv5Lh1EfQSK_W<4HM?2h)g_7 z6(Kv4`V0$Nre10jU_uo5w;sU`4i1--`phww)1#uIa`KW)_e~&DD6%al=N0~v#+<#0 zsg|CeejGzi?J!G>GBh-#&$rpq+t+tW$9`^4->GT3@xWgdyI(E2A5+pu($doMwvRJK zG8peuvid*%B5cau-{6@@*q;|rQq46qHhxucX8YE*i+b-5>dhKJ?6^K!yuQA^eyLa+ zZD~%or^YGNu3f)w_FP`N(_=U#IeF#Pjj;WjZ5NoCh3sAP>)RfWp=?W(KvWb^thnJ; zc^wfSAFrMwdQ2L6a%R`2%1jvmC|>@O$Z3z@If+~H{HzAied{*Y zRLbB%H{^5f+*l?2Bmdds^BAWVpl06UhP!tOm0qjG?dl$j^s;{2J-o3^FwlH+t*uUK zNw?#a%_qDqYTEnP`EP9IHN0xMM!@4M6*b#xz)q#%hURvmZ%b@<_{$>whh5eCE>u=k zZFpnR{JOCe1J4!}dvt-EyD4SCRfEHI1?SI`?O>Hp2L@2W(qDVaCM6j~9}sCZg-ohb zAB{FH(9UmeEtfcn4^N&2SARY2TrA7S@mMV{rOY7C^Y<0cUQb&0euMEmef3B7*J!Pn zSw{{W7`kuwrugVt%+dYrJq%-m!HG};?^|6rQ26XI`9x2C2kPD6dga| zJwq1Fy~dXZ`}_L~md>BUga_i2HJ;>`t~kAJql~>Ywdn_r@EpjXP-^C@l>kZ z(W1!ZNs28!?Y4){u{noAio0tL_UKNTe{z>ob@$6@PaYgUd)9rL8r76S8D3)6)DYgy zaP8f(AHRpm&(+vi=3d>uEjztw!G~AEm@Bd8&vm|bL*f<;w_Qz4OpIN{Iq@d6`+~y; z7dMz|Z$A`XNBjIc2WEDJQ;mw2>)9-oWxJg7oRCwC$ z-CayuWf%wW=WS1EOA7_Eh8D;wJ3>qOn5D^rX$b_fLYF~gAuOqBWI@9ST0}3%<}SQ3 z^=9HnB;IhN;Ean7E~dk;JHw5;BobrHFiQpE{Fq~dZSCvDMqCWp)^bYEd;0$+=Z;gt z^ZeiQo^yKM0}%iK~=sw)W7U(d+e;OeP=sS!T02b?w?UuEjb@S`EO> zn>Vj+Zf^dg#Aj`7ZM{!K?;rpINhXtyR4V0A=;O+?S|=T5!Tg2*Ad@{29+OEC5|c?0 z5|c?05|c?05|c?04u9lx01h8MysP~gQ}lmg-p+K#o}M10EM2EgogyNlP$)F$a5!!e z5zk;tWw@Uro5^J2e!qVn-ONyHYil=SOcl-C&E{}8zUQ2yq3M!k`Eya5{@|w5={DSM z_kNrMq(6s0sgW!jHa0d25r8z6mzTe%h3=cp=09Sw*cBYp(|<5LJWSzmc%NRc|4Zcg zpNP2M?|%s$%}`BE&Br1)zoew(Z**}NIOj%_$s}q3QnD<+h8sZ{ipS%`7~66>ogayq zT_R%PaQNKB!~{lirp}x>Lw>)%MZ|jnUa$8XbWkBqr}L^v%{Q4$d|_c>A3CRyXfzsl z;I5$R=YG50{(mhI(aOpSnzvhvi;F}=R905DB)~L~A|med`Hr1Ge;&@?qeq_+sjk925W*O{5ekLkYR;%6Nmmnz#KPd*&P}4#Q-8Q;0!KzhUN#sE+jrYkGeeb^ zm%q&z+nkx1!6?m^>FMe1qrewx8vQz*?sj8iW8LWJD4MhvJRVPwF?LriA*igZ{25)@ zL#wN+1s02Coz(Hj7e8|3NHe;!#||Dm7*Rt2Y&P2>x{)JAMMa5R2f*!i51|t|Qdd{^ zdM=x9Fn<_0=e$_t8Vb8KY-VPLdU|?3xW57@CzpiX-Q906#;#*1=Js6RlU!W-S*_L^ zMECAcLJsxz_F63#ODa`%w+2)A`FD-T1lN)qmCH(@Nbm^MZ(`rluDZekZ_=%x3e- zi4!M&#E?^wiHQjsA0M|A6cqfH#c3c#M7*u7Z5S0-DZk(URyNNCN=r-sM3q&}X0v5& z{%>e#c#-J8CzU}(5{U#65qZ7dHz_;c`6nZhNX6vjB#Nz8^Yio6($eB#jNMUs8jxlA zQ-4%g5Y^Symz8Y3*=*()E?lspvVw@kV*4dYQgX4!XQ-+mdV70`h^Vx*^gE@dfnYEg zMr8%k+1W`A4GqtdGH?073Qtkl?e<*<;N;1ZU8tm>4jnqwPrF;}aiyuLN!osMDF~#$ zzn^?QUxC$XUC-cLAVv3$P4V&A%@G`0?XoMx!z9{bX5= zGscpaE?vSX5>-b>2N4mu-R=+58U2zZ-D+-begYNLh(I9VktFHP;|8FjqT({DrZL6E z#Xmi608XDi{WL13G0|u=M33>TfXn6jfruy)iJ)j&vE59U%k}G{F8{nF<~X>M)~#nPg)XV2R1FCy771f89oucAsC7Yqj9-D&ifl$2a2A{rYTLy@$M zbFM2aEWG~zqd-+v6;^rVi~9Qd=XE;WgDZW0$A9+96SK3kL`2lr*Y{LyZS9xs?d{JE v4GmdPnLM(zw1gr6000000000$eir!`?iA`DBV~ZQ00000NkvXXu0mjfU1q!S diff --git a/gui/resources/icons/arrow_down_left_128.png b/gui/resources/icons/arrow_down_left_128.png index 1a5b4985ab2a707fdc37521d0f18b31c915fbcf5..dc955691b93c9c4ce43a117290a996a770a1f89b 100644 GIT binary patch literal 6632 zcmeHKc{o(<`yWk~gi;bxjVUF}K4#0lHl&22kl7AR%#s-lA)y5^qKzp1(qfHzRVpD{ zLe!hQmXJh}wX*b*?-?y`{oePwe%E_lzwdvYxz3z(?&b5`_vg8v`#dMwVT+BTyoNjk z0#T%HvUCKm;gVBM2K+BKrq_a(pOt-9oZD?+!8&e*Q8L3Uf@kWMqUzB^Vxa9#SSMQ<9;Qh(pR<-!1A8R7!$sCt9r z!F4SsPtvxBUVSD=zL|7n+3P5CYcuG}v`3*MQP-m8>s-4y`s9sKUCE6iuMg6*K|6w_ z>ZJpS(3fH(2t+E9ZDHX+wXpb>Ihb#1=y9V><))gIo=%01x=L}d?t}}J7Aq@FpJg!) zTF>NjDQCoCW=V(FR#tA~BS@14uKxUe&zs7&FP?8=nz}Mo#UrC)R{M}DW|ii|s~5%9 zFE)nz>{wR+mI_JXo=tXkeE8bsP@~=hwRvJ=OYKT*uO&vYbJSl9aU1T|ubpi_&oo82 z$}e7gbZHE|wPHmD?(EGn(fKnjj}mP|wiwc%N=L6wM(&@ky4{1V#s=ZeCa>>}KIFK( z)+6VHeVizTba^l3wSX+%UgdVIaIXiuGpQKu*ywU9d5b`0gFa&ceE!3$7bA3iE7(oc zf`kh*8R7#KA7gtGYqlRWkC%RyZss>bJ1}zBEt_P}uWglRIvo2dM*mK zodzlM?y?=8^s%RnCw;KCiCrlb*;ZQVZ<90;Ub~VuS(C82=41rEh@mVpxyXA2ec}eY z*Zc8#M|D3m;ZojHVriKcdiVdl^FJRr5jZhEoE&h##BJ0sEmb2K2^Oe`4HlxS{bmZ2 z$3fCrJO+Riarj_`LLi1FB0inz0|;RZz?;oAf)C# zg10y`gMFA}7Tm;G-cUpV0XTq=4ij;FxdMvF2tJ2P0q-SZ6dX2ZBJ?qWyV^UzEO>qZ z43ESk(FiLMI{*temWLVovAigbmeyY(z$YX49-)v=L7@Tz1CfC^B+t(qg&~v4C^Qy@ z#Uelpgdm73q>B(-!5Rs~7Ys{4!1QDDg=`)dCc&gLc>Y2oI2_c&zQxDk+uMJK=L){E z0P=wn(fKG05{=?;P(OMIgjN9{$k%}W(L>-2u4j}ZAmI7?F#)RpfGb?{BLs{2-JkF8 z=R21Ui-`h!0S;&?07u3AG^7pH-r>84gaU6ihd<{9lKqpVknQysSwF=l(afduV<4dW zcif+>zvVt>3|iUSQ!IH*e@S>$OCz{sdherbp1Oe+sLf}b6GJ=6) zVGuYRlj!AzB@-|N;0GuwS0JQwnScZe1V^$#94wYZC*oL41ObgBBJgM?2|+?LF$gBw z%K*zH0|pEt;RlGVer&KR>ApWkC4pjrP-Fm2CINT?fBB60;(qBe906zg(i4sf<8j1UojbvIVU@{=FbV;3p z0COH-E))wtfG*_uIrDhFMsP_;Fp1}PwLQ3;Sac!Xk}d>5P&5`#!JsKvj57vDK@%ug zA_7gMpntIEvDjWg|ChC7@xTnfO!+3Z031JPPV{9(IRX2=JbiieWzQ`o7;J7)Q0UAr zDG2BR0BbHz5bKMIxrfg62Egv|wOqf++5c1ubR6CQ!vqivvKI@1#}k+cI?fA^05Ajt zEQ`n@62NBj)4&3rmoSj-2bg(-Jc3+-`pR`h^mV_ z*lnjyo2PTiMJgzJSxfNV%9f9*pMU52GYTpD+cR(M%DtIaJx}>W#J%})axsZf%cX*j z>&{=lh*~fy2YbL^&xi#J?Y^rRC+!_2uXz zxlJXAO*Eqn$NmB3u{SeIW+9n$)*l=eD+8i1l3LpLepW5>Xv^#*54HMWM#;4!7>&3} z8syZCkg2h{5&vzgO=b>w7OWk4Jd%)IM$?%O%~uHwoJcE)b=Exd?#?Y!ohfd5C)?Ne zou*niaI~^pGw8!%@#Q;Pd-RlUhx&A#yc;;ITL#fLTf1b&IK<;wS$_vgWlCCMK=yQe ze7tIeluq^UzYD5`=cccWDj%KZjZf?n(&c3G(b#1Dft`ZS&Xb?0^AJ1X5mNec;_9|# zTH+3q<^cUU!DP=_i|O@tmUcM{N+GH#@B0$R&lj#k2l_)~(04aQaJFFz{?u=}@6fZH z_BeDNI-Gny1aZ%_cWP)u($8@l2w_1#AcV|#Xm>ro_wpL77j@*YQI&!X4!uJ$3UvbQWp=8&?@)A zgHpZWraGHFuN*B~7q->KCZ1d=3$2qP5^uHp$DD!Q{^Yaws@>I`oav|SgAr0*YmCLW zI81jqVRYjzgXB|-S8GN2nm$%CvX`q75}vH5cG&8hYxLA8F9F)LghIoY#qprC%L z-d>UV`t|E8`Yp0*v^$s1x!&7gXdZ7ry&`SU4S_ILqoweR+6P}MkA=9;7(C1DcGhiD z*9<)*ZKIyPF{B(Yrxx>RN4#fw|kl@+TVGX}8G$f4rBkIrYi(LeC_4tQ%SKY2afpO*e)Hv&&oXxLtErV=T-XLz(Q<=JdD7&QU zQ)^UKRu(GPVE37M=R(G&rst=22YT{q3ocK}Z4<#PFE~uroi{mPV{KiP+uGWyEGYcb z?r_Vg6R9x>MIsm~()~8Su5~m+7b*%49vWBuRA}|^;`{qHH#tZovaSBfkly3R>g@iV zvissL-tf33?VVX2qX1hhm#Bg%Frf&w#+H_}3N8*R2=G_}JBAJqs7+#`0!|D={bpVkWiX4@Y`<&$AD2``fG0nwe?E#ZG}PeHq@p9xvJx z&0TWK#&=x%GuTaOL3ZfgD-ci5&L&(@=T`liUOs8{bcs)@wq1t^VcfqqZ#WFBwgcnu zTDESAM~%vKk;vW+A8;Ga;yPOrliDVGW>ZsBuRA@(=0`tyl2wzHm-jj5!{ibkWEPOR zR?ns1CMA@=d}l4EwcMroM9(v!uSsj;?z@RQoSlX9w?Uo&>6_Qp?kxJ$RPx06IG$** z_Vnq~2h3_Gv?sw8wTz98LsI5t=4HlY=jIwk>O}sbK*J_8_AFqy z*bMB@s9YbcIFgg=nYah6_ne#@!#JHo4;5glv9I>Xoy)sKPV*X7hV$3wTV)p(nT$Hv z1$XT-aKYKy+8SG&ut=49w^B2D>rC9o!UX^TtY5qk_81Zn5L=}l@1$0<&^U2oJQD>i z4vCt|kcoZnC{D3T$D{d!4-T1VU&j`8Tz>I@FdAJ8$$lOcYR5>})7Ek6zQWopU2s}~ z>`6;?*xI#gqkroX{Dfn@iDkvNQ+|gTWLWz8QY$ zvUl;)(+L$R2zvIZg9HMh({>sfX6@FfskwUzMNnj%OBrmYh3{OVp`oFvC4PL#fUl&4 ziXKu})S{+vSQlNY@48fV_vnL#sL!drT|o<@^acl2(}sqI2#pk(Y+q?!L!0)E!ot^U zRMVRWj24@x<;$f?X+MfMbX42-SR5yP>Q6Uq=rOVQM)$|PP8J@!0pOC90vZ|-5n*Yj zb-_I)GN60%iOI}^Ck3Y2O*fx#8SiA?^bf`@lwWWO>$*H9HW9B;zaeU|#=X$9%be84 zb7{N6M&F;win&g7iOP%qJmA^k2{4)Op$v6b#e|fUPb;dT-E4v#kVKCxwN)B*&HchY z<=V2nki+!6%a^^Wn-nS{Wfy%8&Ad;zu{+nes%rg~Bbc=4Nku zQ3Ae_27})Brj_h_Wxaadh&oIgVPCql`yDqv-_uJkp#2ti3*KRpI+a3ProsT^Y){~Y*uEL zs3B~W@wzbEWuvLJ`IYdMK|#9-Hy75eOSnF=A~$>BY5RL^?IzetY4!AL2Wa9IJZ_)y zr{Mj^(pGYknM~%g;^N}N<2QFW#Hm7Wk4}!YgpI!}KXSQaXyCZCw6tzQ^jK(kKLf8Z zERO4-cHJ3UIPrS;CNxNg5N>{9)0xMi<-x`M=FxuVuUzSC);(z(nQbVo?+cNYJu-aG zf2LyeA_9CH-^x!eImqME?043 w(lK!yRns$U=k^@uanpzYyg~V2Tb5FVX<5}7%}Xb>lV2tP?gK~#9! z?VVk0Q|B4S|Hp9xF~+eSpZH^T@JDRNuJhTD&;;9<1iXA;9Foxl8V5*#($aNmOS_as zow|hzaf8G(t-TmX)3lr3b)BXaO|)0jq^+BJvkz$(72P_ig0YUR)sW9FmSZI}WAWF? zIpqJ7j)YLaFGHw2!aGaYHe-3#+BJb@&kdu*O%qzmoLffc7K3i;B?D-;S{We_~X@>^P3Uix41<=@+}W5??Zf`?FkM@Pqh(+`lpDhPZ&-x~~q zhe&=b7W?WtFo zXe{&ne*Z$b@;M@ERDLBg|Ncwv2^a(_Wq&$d&OLu!m4MTMN{J_v0Dwp|dbSGk*W4#) zYir}et4V$+96lv~2tqZ)e<29M;qVW*@+y+=X>NW_ey~&R0MP68`9vadf~&6*`EBj( zxhj_ZFI?l} z)mMpppU?M*$zKa@3ocm^j1LSIZ`k$Md|B4PPRW;Hak-`Qg^qlS-C-X1BH!otA5n7DJ8$?o;`b}D8EE_ ziNs>Diwg@2kxI&MvfIxpG2h=m>M`?+AQTE+)ai7E3~Fv}ejWhqc6(X!zvOn$DOL9M zdVM~d&GLDEF+P{DQ6U_V)XlQ8o$r_^a z03@r`x=>6dD3txCre~BY`+B`TpH8P|XtD%8xqTbkwr$HlD6@+ykr;)8-&Wipw0+AD(tnG67+-e9;_Y6dzSj*9@$?DghWRFJCg z?GFzR&oc8XKyPpF(`87@1CX|xOm8Zc`OC+DxQ^0Xg)kb8e^zQttI(+TB&}6|y@P{@ zL?VHjnwrlwAU+R3+P!=CVE{;_QWRJYH*VYj0C+r}7qlS1rlv+3A0Ov2u1aGvnetl5 z{8TD6&CIVb9UUEyE4fXJ(vNW+r>zR}+Ydevj7H;oYR~-9(a{sk{0ftsodtlpy1Kf5 zf2dXd%41xVUj@EAJp7!R@BM7}s*Kre{*0sECgjk>1bTMv+^5!t@8H3MJjPXR8X6kj zP-EuH+q=yCD&cNw0st6|#ye`u{B$~hHnoLbip*0eT0r$ewT^yvyZzfVRAmeX!%e7o+gCnb z#!65H;_>(xRQ})xD~^|uN;iLI^Dm&0Lm#XJ6=Y~=2t7SL&f41APoa$?Uvf{d#2}~; zu~=+IBl1@Tfz4*)bWjQGcKgQ~3xJhDum}JxEiDvT3aL~ouJY#Z{{}%Q6#6EAO_sn< z-+2dCtMx}36u;IFfrMzZ2(DbY0#Ow8b#-+gX*By+UEST?qqJHikw_#izv@NHm!Q*0 zuU)v%NTWsKcDp~+a@m)!R4R3jHjCh{Bw=7+Ag1BwPujkH`#q=2^>SNVTND72%deFs z>%{4DeM@W7Yin!o8VrVCwzs!`A1Q2P?b}D0#jv=z2mmk`48PY(_M1$m&wKm&o;6!6 zCP|V6`Fpv3{W^t~!tCs9zd|oyF8SKJb?Y6QD83ns#fIg7xBRXGQvS~0`zmed@@BL7 z)~?4MJ1%GXlV^DRzhYdwb`9}(+ymew`(`J`FmR-@$#eETYY_fhs_pCy(CE#uu)vPbP0iAaGPGQ|F}xo zU-&!CX7eqF!|{55fB%4g{P{~uOO&wDq|@nSg`2;XfppJiv)xRm(}kJ+>eZ`UbTu$H z|KAs7IvkE)S32{pR_kB=e*d}7uC7-3^XBLIVoud@?!_0wWj22+$G5*VH8s6IJTg*v z`f~pKc`mYAkt7K=o9$A$+1}XLc(b#!^D91|ukhS`bZm?ZtZD{-2GA9Y!Duv=^x&ty zzWy)fhK3(zv)M#pl+5v`w6&A{@4gEFDE8Ek#bWv0^z?KFfKDFYyiO->a+K2^nM`JS zJ@LbX3&Upn3S>76^BjiUJ8+i$(~ zCocIWBF+Pogb+dqA%qY@2qA+SC7>O`2 z$X^*iyp(&Nt8*gL^PV7PA_%2b>t?HVbW%YB@4q}+>^~Dklp5HV9+)@Q(ppjFXT_^t zc3SGqC;zq~8p+wtmNaBb9SRtYDEnX;c_lDw^QYSDYER?0jnX>e&-v!IvqhZ+dD{K(uBsA2j*67YuA@ZVak+!YsSlWbKeDvv!84Zeq}1&7 z&CycLoe^tRk9jVK!Qk;cD=Vg*mDL}qLkZ{XJYvqcOH;4i>Qd&cuV8}?y~mt)+fe_d zdoeR!?$^x$zu(?5B7cmirDu3BF7Wp4L$zmj@4tLO;X)iR4uARnMgCii_7@|)EBijZ zxTZNcU_Q_VXXTv=*zBhMP}J_Avv?h;TtD7hu?~nD@nJa|aGaD}K5A?oLtPp*tSg;< zFhiMasXPsX?;>AVQs7u=X?B^nEO{(3`m|P2O>fQORbGe3kMxz+3zGL63Jp?Bjr*c~ zbKP|#E_K|tZ)n+fCNb}9fr~}Ps5@9$>t5WF`o#R1{L1K^U{)W|_HYd*9atw$R%5)b6kiIZ-wYm-Fx7O}rdD&aVht&&Mta6j+h1WXZ3AytdQdxS8l+{Y&G2_Vs zbzF#id~0Qw#}s)djL@>FUz$ut)+MFh92g$xYVP`C{y2#f6}_6koC_mqW%HbMR0!peYAS zCQv9?4#CtEPcb2rO?)YHP+ShxMi9nlL*?Z0+5VtWNU;B$LP9vzl4)m-AsFKRlrV$X zB0tE%9OJ+X4v+d%;mYHKE+V#sO}r_AVnW0da1>(-o`UoA9 zKuHxK!mxN8_MZte`j)VfWX<>^V>6?F;>2vu;D<#9^7|@-7B6TmH2S_6e&Y;^;D7o1 zR*V1T5CHIVkiW(6Pr826^|u)KTgE@T>nB}*i-Eso{Ik3MYjnx|`8fp!L%X0z=wpe{ zZmk1-Xi597x23~oCI6E*&!j*S*$~DSAq=KaBRSw{s}+_(LK%^rqqWRiIb|hjyo@H` z0*RK2tldRc0={Hd4x8I7f?ObyCkg;0n?<)>3aT)eT!!*L$dWs8b?=f-4q65vR~-AtsiZ7Kpp7S8Bcp)M&(LEUfGH+N84SR{2EPI? ze!q&n7z3!uo(5bih*zs79!HEiY`Gf$dIHfql~oz}Aey4t+m(G-_0H{aDIQWuaRm|q zhZktd$}D7dZ_2E?PeYI2J<)@J0WjFVIf-p9m6y*hJn`U!jCN)MBIxO*?!w{vD+d(^uoX96Eh@^`uC=JajhVy)#Cds~qh}7yHm|kl(NqfR z>Fw1y+Q3a<9@H~{CDL!ae&4@*wxqXe;UU&dz9*x#$mL8A&92}iEFvO;7o2N>KS8Zq zs~fe^-rhdXxri87>aYT?uCDGB9X0jgOAcq{sfhEKBa8*Iva%0l3*ulT5@`hMX|CY# zI!D8`O-`lwnyr4?I-Q4p@Fy3%rc%nc`ef?&PRh*7j@iC_f3#UwD-(lNy7lAS)YK#l33Z5S#Kat->Dg!ugi9`eOP&XYW6b_GtU7uc~uwSpPaIwMKm}%Q+7E4`(F#CWY5C|l< z^fVvLt^?Rl?+SXJ4Aj-t?P1#FplGX7p4(|HBJ9p}J77KJ^!mW?&K*0{oK9GnYuYDD z!7U!Pw)V1Wi_z>*xNF<;{d;Gm8t>d$_ZAtY2(v`z7Zveb6n7imdWlI+?rBcmzrVt5 z%a#dMT|Flx4UIg~^v1Js{j*F5nT-_@o+=q3%2Q*5dpqIY5@o}0zlEQF5r%t*EDIm? zGBGhJV0u8|V2*UzoqmLca#XgFw|b?ipq^S=Uw>C5mVtl4X#~A_Ue!>)E%IZ`bSJRC zHqJ?`3P&R?)zs8jNlQe_RZ2!iMo_Y{d)0=Ahb(t~-fzDBrsIyjw@cGZ^Vzd!Ynj1N2mqQ{smJOl6EtwlPZd4*SnK?W`t|};qL27jB1d+DOrfTRQ090H{YwLEU=en|`Bd7*REX!!<2gAwG?;SVz`*CluAeR)Q|M99O+By@6j%0cvVpq&YEF}dZ%MMYnl zOa)U9POKGtN~FYgozhl0v^MhowQJ->D4bo5Z%J&lUiO|%l~a#CH&0LRXqt_ke*f&U z{Jc}gx)YO4EG(8wAqwGH4k|mQ{G#!jkH3J5$98bIzjdvdiiQTCG%{WLkX|pR(7F8J zskaVj+5)1fsZ0EHd(gR;J3($oliy`*#f=-u$;qk~8^hIQWcF&IX*=cb0)~4x?b~El z#q3B4#g5f->q0_@J7UK_vc1qW$1COKdw);dv*d%qNXt+gm&;wU3$~4}tK~LyTzsgN=VL$ZEv5nERdG$%6MEI%E_&~TBOe0J zMIyHko&AW)p5E>csx#9Q!xTU)t(ZtxjMMj4@E*QgUj7_~2*{kAjM=7q5hH)-df(f( z(;CQI;(~%z9#+SfL{>=IGct{mPQ?H)>5miB_ZmwVb$&WkN!N!Y-IvPh;9@za}@2 zvR8Q1=P-M+ch}OKqll>O+uIwbq;p?TY!@Y7(L_Fk)gRRG+{P)li5oLJ?$x%4 zO*_CWY7uzP3fOe=3wGHTyMHfsb4Amv&z(On z=ae)o0l zAPaAy#?qyDsH0GO@3PCv8(7U++KZ^%vAe^i##>+MRd;uH3jvr-YI^!3Wx3k-6~9NS zXSEJL7_~@^4PDCWyt!@-mD&>rTjK2E^7vtUd&QwGj1x1%Z$EziOnRp3MV6M9PT(l7 zmuZ}>&MzqNwne|5e7e8;^s85|a;cX`oTx`keJ7jp^YZc(QE~a}WX9uAd+ykVhljfj zCY@EiV&_2u{R`L;E8i7*RUCIWNMC^xpZJi^C~}=l%P1XPF1j}zR{ChWiN=e;aQc@Ctv}`;n z6(Fmw(0hcAX>ie1D$X_QFXP}ZZs-s0UBOoTMK?(;4(7r5<(I1bGiT~&H-lN0C#G-v zNt<7^P77sdJ<>zd_VakW=(|3+_?T-{^Rw)n`Kf62Sr2HwTE~z zd3yZmz5p42;W9X*FMbX0~G z>nSyQqJ5H%W@SxWsi>&9R$cx4ms*1SevI_Y*fO^9#a{oU+LtTU9D!~hGv!9H5mQMU zdKWnaubMX~^#YC9CB~qJ17}Df;7PLWy*;zZ$ JFRb&4`#+$&(J}x4 literal 2776 zcmbVO`8(8I8$ZU3Wg1Ll2qT6hTa3t(LgcY#YiJS=+44lpo1HvnY*RA{F_@&Mln^n6 zsK~@)i<-uorAU^s7D6e!-~NF2m-k%PxzBa(>s;sD_vhT7^Ep?Y9j(QXa!3Gxn61qT zS7@aC?jk~vZ81I91q}k>uGSWy@~!+VG!Z4+oCya&{NLYQfT<~tgPg(wDtw^bS)@S4Irk#1$ zb{wuZa5v(|!rykwKCJlG*n*`d0xK6vLqbkoV;(IrwQi3B2>n&(3E&8G=l@~8sxg^N z0MLqxJD*s3=O+scE;eg4*uL(vlWoG~-?*`25Ab*I-u3G5@3*LEK8vS>&lEU3h@%&Y z05rgBFdx>HmurG-AL(7=T7SE`x=LlV?*ry02mmnB(ou_T={VntHZ3gY%;oB#Uyp-% zUea62q6!N`)z&Gt1O}WeZDwGw{VD*KVzb|R|)`r?CSIfKA)fI zlWL>_MT<*sOOwTJ?YKKTzuO}$p^)Q)A)8YkKGc|r{rdw^=w(@DW@hG+N%Rujx7a8X z1Xe!_loK4w8KHVS+HRsEs~iVj@L4mW!fFGa%f)#cdf2c?bvqkGsw&tdvye<0LKPU2KvTd1=&G zF}pM3dYOu|1~cJwrKd~iX#MV8ooT)1=P@ZX+CKprqJ0-4xx$K<(J4%SDyaOoy?v*! zOeM2x%KNaPp&y2A17P{`#oJn;E>Iqb=h;-@iAf?vks}+64!o19c?WwR2#k89NOW=jT?@- zMl#}cH8tI>?i`qa=l&~n`VoQd4^|81Wo64G6MTyE?CflAUtb>)%V|{csn~0ya%1`R z>(`kq@ic=1F#zV~=chE7bF9_InYV=|o+OeC9o9WgR{|7XkiUkg4OB4Z!NK#_82tkS zs@XOw3EJ)UfWB9Cf#nxrMF4A0K@(7=GUTxoOU;jJ_|q3pO4yp9yxEJ zg6ZrXl;5-X<%`)ckM}79Rxvy4V#CGI+ZAA(N&p+*tj-_hM&qsN3Vy>6RXwI!3; zmsY3Ws8MLbEq)GOx)IT=H`8$r;7d2WX@&x?aaL1FK@XUUF~cPoOME_Hw8HYVy(nNXUW`meYmt_xIO-OoR=$x6>5l<*|3cpSgH-^)l+C-^|%z zLrh0}eF|S*UT!*f51y5kbpR@mxjAPLX3q}d6*;{(5Eg;MEJSwuzzETFQrAD`Sr#TMZFp`p*u(BWquC_5r5}rn#z(on71*m&<*XtC_5SGFT3W+gIVPi5x#T zP~|NFfadASTZ!Ww>PH@rXB=W|Kx;WJhC($+0B3jiw1b?peFFm*wzjsK0zVINZW)J@ z!UHl5anaj7#rElE>p~L(EJrWA-z|qmbLO}roSjg# zSM5+p!_Av=(48BEyoY2gHa2!_4>FZY5mc1^wEE-z)2HrK(eb+zRUWk(X@Vw+D~4B~ zj3u1i+@w^oNNegoMakr_m*y6mo0}i`+)v~vk&4n%NKY3Q77#C@7UyJTWp}gxGafIc zf6_88Zu3Px&`Uu#XLtJF8eYrJTb-W_o74UzKTgoq)h)SwG`6|S%Z&Bv)vIVxB@24d zA8dp}Hcdh?Ej;0GSsX4IqKfxt6hW}UeV(gEpLi}vUYqNmf^^3h>myh3XQSNpy(Uo} zRfDImwoc4c-V+$y*7^MTbIW>%Jqf}ETN>4|?Qck0p)J|mWL z3iD3?4Ng{eh<;u`0e|q|Vj-K&&X~MptQiJR7+hIf+n<6~SEUq8PET(yLJYIAw6uhk z_h0A@(oZloHTAA;v^tu&Enjr+ULu5+lINFNNK<0f)z#1TUswy5E`c4yTn(L?p5F9@ z#ekVGIYFRx_G!h&L@VPb)DrS^ytgHpc5COeY`#f#iL)*l$(zZ@$+`N$Vy^b|Kz|he z!U7ynZr!@o@9`)q|D-LX#beiC1j>9b$Mw`H$$iSo>j(rw?D097hRFF`6jXB1D|U4d z@|n4*Ve4X#eiVrrS69+I6W90>AYud|Iy*JI?e0dMbaec9pQ!OOUqR@w+?!bJxY#Ko zQGa>(LTzAa|D2?97T;dgmCBuweDOj14*?Qf362sHOl+k~ne{;0!1+0b-#mC*=*g^n zdJ$e#HL#+%c&fKOLorcDQ?u)S@9esekkH4CW-Ha64<8ysH>rXiTLnV-{nWL5d;U$aW=ZIWy-BCuT7VLs!wF5-r-J?H1m+ zDnwFJNkW_3;v$7hu8^%om-L<)+CKMwKJTaZeeZwG%$ak}^Lw7}?|Ht@^LyrZW}A=q zVs#aL6#xL#-QAde=s8|~C@Z1gJrC?IAaB7A4@PcUz7fI}oigxDo)naa zpYENRP`KQrtB8|1b=6RxxAOdoGqWvPM>LEUtPL3f?)_OG#t3O4g#H}ZQDs<9L zB_v^>_z=ypIVB)ucgoPqBz9Hj!1*5UrETIvCfhvQpmQdB{Ve(lcFnyl4tJ{KnFWU= zOtU(gF@cqDZhkHM<_W(>N^Z)Q>Fx1Ou8STOy=Bg_Z!tH@(;t0*&%#GeZR0F!_?JNvjhJAaHDjW#`Qx1HO>McOVqeSMjEqzzjubk@N7)AN#j zl{YwTRT))@wpn%S3}|!hrr$aBpdn;rI_+^o@NX&`ny1`oxb9Kwdi_rm?3}HUs}GhR zi6#o3#`n(W1oQo;TG(|k%Z+)F$g=R5j1>L|HJ)Emzs(IwEa~c6`RLk;h47=Z!(!=; z)-zc3!@~Qw8T1zGmb{dZ!2YA>o_TeWTf{BKi}khF1(f(cx2dSo8V<;Oc4()!%JAkw zNPVVtM5ckKETGttTc6sy+(PWtpUF1gV`Cndty@&tvzeYz^K$lWY60^;>DC?-=N<9s zMe{9vFKRyOf4hI=he*9v4^9#%Now&bb=K=CWuaXru8B47J;q_{`Y-Rqgw-douMJ+= z>2OvyA?2PBUi!XkF=^B^_C)sUSxy}~At6hxIl7h?PIQ>&*u}c9+1uker}@3t6$D$t zKf%kezfkRvrAZXCH-jwsrEPgN@tElwGN7GV&} zi@_1_EI~-XhAm}0AzGaPVDBgsf}C(zf@8y>2;TwUd#MbMLm&tIQfn58C3J?v5Vu$n z>>ukLz=;j#&>_6z0u_510|ns05)dcjMexN8nFC&d%RsN?Vj>==P?3Z?;DcB`IA?(f z#!)S)mL!6U42h!P7pUOuMG%+a$8;TsK<^yzVG@auK_o^;M_Wc)Sqemc z3Wb1b5X3Qj2`D4*#k1uQV;D?W%n>0%2_oR*`)zS`k1FjY6=7 zDYmvW5@byyLtj9-^TiU7&w=GoD7Ynp;;=~&NT-uP0+(V#B~W1woxrw2ap)9~gkso2 zHf-(}5KBY|T9shLmtM)CAQXzurqIbS4Ta*;Ap(_5B@sXh#39&{KspWPlE@H+qJV-p z3|E1O2cqdjcwi_@6!JqA19HL{i+tQ2@DxkZXNgY)DB+?84tOtwFO_{B2tatSzXX)C zNw%TTt*Ini8w!a=v89neD+R(LFl6i0$kA9B&LS9; z2t)w_L4*Td?h;OJ`DvJiE++_-fJ{&Vqo5=Tl|d#kDC7XL6@x@ZuL&d@2I&iZ0fca4 z{*$(R@!;&oQtpO`(fMN(qOld_4@ZvOjon5dilv0ZDHa6- z9}1)0W4v5H%8|b*1umIm&9$ac2^0?57A*xfl|bjRX#@@(v_`3=(#a52!NMnWv4AUy z21W3qP?SfME3`ZnT;b*`5@q_ec61ml&jLyq0VU}(VU%&gh~ohhG~!H zzDfCeb^YJyQu+Ki1@qBeP&E3m^seoPx9EeG65Dez6Zjy1A1}??gG#VMw`F1g(6}K# zF#F6kW}?C=5_gu%ls{CaYh%==(*E3xiu5EdK@w*HPrfS$6q`jD!bKyJFr0j|xHLgS z7XT*z>dssgAZzG(67J<6J)^S!!=k$2t*8+0bMx5kU;Yh9ew$ak3u zqwAm5IbiMYWp(_jbZ|vg)g?m%14}JtD014g_TYrldT^5b{|^i>0hk0R15*JUu<*YV ztRC2&vVD15YimA%Zhb^5l@fGRHn#*hP6jj#8PGhfZON*-bjSOhoIz#dIeuB1{^94J zm36+*R|RN?-&XI#%;G((T~}5rhWvw=51D6cU%Z-ZQR5eO5PFlg|5Z?EH?sqD$|$kBzk--z0tsULbHLo5$8tC3jZ=xE&?`4L_RUDI|n(vyI0 zH;>dhn?s&+{0=FbpHjZ+mw+>~$5*>48*80bYdncrC|biAEjCj0orpGMP{1x=az7SLP!rtisiib}D zyK35x#pL?@h$0{1p&}`^i_n`K2$na97=AOdviVsgpb5`p9tD)A$Xr?Xx2tY-b*O}_Qqdn5B@RjG4#&wQkBaV!vsii#r7_@M$&Qc_BmpJ|nqy32AO zFG}9_YuZ(!TB7lOIL0G`^6ZkP&=6RA9R0GM=b#>nsU%a@i>Gl2m^XG7m>YP(*SA!}C z2GcBbJh_3H38t4u{OxbL>&5pU;y0P~_4^8w=UwqnCm$_Ns`XQfpX&5*rj15nQBh#w z!8=`l#u{N&RR@Ti8xKZIn_cWu57aGG#`4S73*Mv*3>>_FZfp8!TfivP)pkp{UjC!W znwpx?3kFSz1nar6g6CJRA9%mYd5Su}j^D ztS&JMwogmbx68T?jE?3cz0ka1(oWpCqrD?d*;w@kJ5K^ZZO(22hn@qk)(;QI8A+u_8Vw9>G`sTpt*$<3 zx*Rj;{<^2JuA!mf`Kq!gc;aJclz|@u16RsDs%g{mc8~NW2fFCR=e0^pPLz}|SUpEx zRD^m@f7#vnvWU&o#?0v2qN*FbJUBRir%_e=%J+p-rJR#$SBJ8*vsF(1jOQ9Sj^>^! zz9pL+p8k9ZhL~D6(0+2$F1t;;u7crZ$4gHZ+^C21<^_6Sr$=(gUyYpiG z0F+~9+g8)z5G9dl0}&b3Nl6$dw;feb^=^-h<#GGMDLNJ*LpKX{n3|i<1!khQVO4gZ8uf z1An2^J)!kPgoR!0P?fj6;_25pxc|A|{k3PZ)_uU(hMbv5_f%>{e*yq^7jNbnr_~$& E4Hj9G(EtDd literal 1970 zcmbtV`#Tek8sAWC#9W3Ugpgb0K0?f$CHMNOP=>7ynau5r4vmAp$u+k$N0G+2qpfDF z{vA3pEry*%&xJn!?o@AJv^LAo9TD}ez3z%h3>gs*@z z{)X65f$g#j8xRmM-q+O;&^)ZNA_zdSZWrSL0LkvZ0W8s%R2C#f@$TNvq8}uLg~e=G zwO~OV0K+>6Cw$;lr{C}k zkn0=y>XAO$jG-4gVr(XHPA|uRo^J{jGaHR{o8ty`EB$o+{sH%w6OA$+v&u<#D6Itr z$l%4ol;eVRfQaxA?J-bghQoAd6I6Q?2agh;r5|<%R_3Bk+$FE2*}Jof+JF4P*h<>1 zN?e;gzS~=29@FUmG)<(N*+zk$Uoyy103m@Q00_WAurc8ObrfZbOG`Co!{ybHdgkR` zk4wPWq|Wf?@2782HU9N5i|%@FmZz;j8mhGP93LOQB_pk=@%uuxw6y7O1_SCD86vT? zkV1kBa<~g#{XM?kmx(J&)%X;kS5ju8y=te+Nl#5kNYMKJ{d*u><*qF`FlGMG+j#zs^vfKg>Ye7VG_mnr4y1D(H1W)T6GA>AyCX*iytU z`5JD015X1|OQi@d&!=in4r)b8&?=7 zh^}--AB9Rqj-x4-SrwrLE-d!U%-+FeS@mSNk-k2rYte}ql5Y~9p8jjJt4?xct2a;K zbPaS9Ivn>g22p&5BxD=tk4V9wb8@1FKhjouO(Vfhk495;kX4G8*nO8=M>cFvFUyRw z*{7AqR72NQ53385WxciiH2dN#Nvq!)CJF61jT310FFWb&-u<1zY3`1^j+T~6Y6^c} z-|k_I1&4brFHC$PxZO%-YHH$C$n$zU*^&rfIm^2^xX-Zp$)1>YIJ zN7O0An~2@3s`}YI(;68h{TSUdBkZPiKQgwb?1;V*b|AI&*S)97lKGnynjEs`DK7^1BZiyic9JhCGI4k zDQ)6Ue6@t+pnQJhj^IZegMxx0Vq(@1DYvMejsAy5g>HmmQJ^@)`!W`*g~LYATRZ{x6#YP$*PC;>?WqBh>4bmbKM8 z$CMBG!ig9nq_^D6+&m$o-DS%uB;;c`Av|a4m849koqNiUZ?H5V>EeYz)Ojy2TUSI{ zR^Qufmaqiz-8+x{ejctPc?XS7PHvk+wFWS+7pg1_pIa7scA0J=6X{)@{FF?_23V<- zRt|9t&pi0%`+gOA9YO+(eIqy3ack0RtnShmcapC%hlh~^{ey$1N(I2TZC!I=23Xm| z_4P$JTg;>Z(W8Ff*Ql&c6tXI2TukH+X=;#;?Cs&VmoJP^FjMkrf2Pq5%*`oxmaOuR zIx2+T<6lj4Mj+11DHJum`in!0=c=BLg%6=x_spx2iLkS`9X#K}GMUVzOLb!*s=uqH(zS4eYhL6U@+lH+Oeyx8Oub832J`Ngn@XYF@$Ojyz2NJTcLP&CSiF zL&47KtD3sfj)uT7gOC@?fmB%CMH&rEpSz-}re^=F5tWM=H%UKCg^57aVKCUp>dyX} z=yz2d{kK>Cdc1DjqEOF`=Qp+v_`CKrd}G4fEYRywasn~x6|+cZZNchppP0H2m_&V0 zZGrtDSH$#>HdDIj>+9Pzf$m9{kZuDwbf5h1av_%C_rHpXgT$tS3)R$CFX7)nft~`~ Moso!U$I#pV0Ys)~Y5)KL diff --git a/gui/resources/icons/arrow_right_128.png b/gui/resources/icons/arrow_right_128.png index 4a2dc7c2ebd0c93eca3b2eab26bab91afbb01302..a7f8a6636bc05071081578d4f313b98f928e87c4 100644 GIT binary patch literal 13532 zcmeHtcT`l_v+e;0m_Y#@K@lW~fn?J(IfDWsAQ_1gnx=u4(BvFi{i%Q?6-7b9hzOFA zC|QXk0um%A0m;w=p~<{`8l3R%UF)rR>)n6e8eA;T`W1GFSq$A zn%z_U^O^JYdyGc)dFaQ?hYkdT((Exj5-I)C>B zO3u4Ha%D(zz>kAdgzs8@sSSljakIP785_3@t0^Y*5l&i5C7Y)xZdKm(>>R(J)_qP+ z8t)Q!Z&chIvQkhumw>&8JB~l9h3})D3>f9%|DA71a;Zd>>Q{MJv!(TLw>Io8+bhl2 zd=s8^BTq;hOtG=#SJzq_IjITXL(wa+Nj#kE73J7q-x}!P09UYw9q`YOh$a1B?XLuON z#YvvxZZFGaq@m5JhuGThEx=L3LM1Ut*E<1O3XDKAo z%gal^OIQH!YKufkN=hOHg^)r*2rvWT=Huj!_C`3lorOj0%TU6)VO(*}?l`;?CoB_f zh4*lm<>CVGIe+Nq=&Ygfhj=Hq0~7!rNN=<=5+xvrbaX`ib%mR|vL_I7pwNH2!c8A! zG*TDqhWBvAV3j?wPVQ&_D#9A`$9iWER|m2=))*w#0qY2+x`AC$f7?<;RYUua6)*(0 zI7eslDggH1X1e2S{sil9y1{SA=KNI=u>23Xf1CZocJgE}OG86S36JrB)l*fH<%0K@ zvc_X@)>7n;XmJ}cF-eRd0%Ij1ju63!h#|lSVT7O%3M-DmVnr}m(Z7gNb#ik@J7KV} zC?H$_2jtj@ic5;3uo4I%w2c@-#0rH0BCN3pL2)4~Ypl2!*h2U(BD7p_AS%%gf7J>W zWer4$3SmTSFhVv6D={EI1cenvpn-Y_Q5$hxHJp=&_n$BHagJC$cQlM9N?b@%R76lh zL_z{3Dj^~H=OhEHs~duVLMVNdu#}*n6!3wdIQa1Ae7rTz#^?Vu z8%`chnSGaE#kqm~eaJ)m8KsAH*?-!9bik2QiIbC@6jEr+z6ow zyBFFOd&w5y2(SX-NydtkhwLcczt8rv!@^zwfFV$Vh(7_7H~XUp01v zAo^PPm*NROJu4WbaaYw)rkSE;VuS=QTrO4wL#N!8jocOSj&M~Dk&8vFHK!NO-HsD3 z77cIFpM)SzNLA^QzIWgJATIj)>T`ibQewmrontB&PGu?F3gxt8W#!htt@c3UwBMU~ z*I@pOm~%JHGA?RUoKoYu9U8?G`jl`xP2}aZh_;eGiu0kC%u2bnc`mP_{PKzS{qR!n zrkOi$_f2*ZNzH}1Gjo%ANe9I5t$vwEJ1xEtHK^ySlMbmJhB`x>21~Jr zsOi%?a^87<`S?uK{^`~!LOUfi+|qur-+oGdZ-r)%elE|fs#RD^AmohVz1r#2#DyVh zZR<*IN~kFH6q91HA37vhVsr{KR+rNBGGJ@1Hz#m4zLI!}>R5&?(ylpVwO)3KV%AlnU{_6K_&ojg7dtBIJrJ%C~3i+p^8d z=I*gN<&r41Ic0E^NeiD62GizJ42u}s)rXe9*}8nw5clX4PbnNy0J{^YlQPTSa%u@0 zWZhtQoA~5n@e{z8$L8#nutvEpSM^I4HOC*EtVITGG)c^6<`0~uaQ&cp81k^0Zcm{K zqH8!!8Z#=LTea&iauoBNGx9@1k|VsoLLRU6QZ;+u*lydmnRQRJ%7?6QYYvpzs&V+n zPyoYdjec9mcgPSQ_C^3Fo*`)x*gknPLk`I;W(>h^mp^72=9n9McoepwU==S5VLwJw zuc&Y5?PvyLb8>7*J4F@{p6s4d`<=&Ha=pJFhTXeyy)=l#!=LksUT%G4F2Qd>#}dZ7F?B4^-)cK> z>pl-#waTQur~u zYIig9LX(L))ksb+jv`632ls|G(SQ5WwNpa1Lx-yqU4XWdZ~NK(RC)_$ax|r;&tWiR zG2Od^epifruw4~?q`4MpqP`^@OO2_!-0`RJno+h-d_laL>J6C7pYF{dwzM>fKB`Je0Ylk_)M8)_)SE2e@ ztG1WQ?ADa;urfy=mXd^uJ=DjK{P}RI>%G2~N1_DIQIMl!mf$g{DwNwyl;C8QatUiJGVU8E_0NH7gYO`aiV`er_q8~AZ1IWQE ztKSpOtGTJ<$QA%bcmxFq#VD=&yJ=cVO3~5L*2M#^50)t%jyDtl<;KwdtcebNjLmWL zr)%oNB+--6?2ms=Du9v-qD+b96=Dk&B=f2`D5wr3ZPa1MK94Y1c;nf~PZQ1Ye(#jX zo=mCPoo@8r^x8vZzj}2pPQvA7#mQ>0z@x^SxxeXYU!Prh2gz!xCojNDWBQj6g_<#d zaARS;My%4dVlp$x*d^gsnU3EN1AjpqU$QZ((N7F*0ye+@egbLosv3p@Sis@pe$jvX z%~a3Q;j_<)ER*4C;;SNFLd6svq-`7$NdCz$>K%6CVCoHm5+ z?amn9pG#)i?=YV=XPAqTfez7sUsKYk9!bppmu2az3O48IuY0D z9?x0A^$_;!yAR z=?*4lvO#Z%OFLsvhLMp)j{P>6hKTFtNf8GubE~RgV?}FpJLEWN;d%T0b^@^;7Vi1k zJ!a7AO5JA$P04SJKVYBCrcr`PEWC8{3U6$7aQty;$nt_7#^-3#f_o60|BlO$maa{y^ewTb2jghTfOmKLvN~K??!2HA7N(xJI_X1xly5IwW}z z{pp$Iy0bJ;&wKV*Vd)l`vG3~~h8D68ll9>$SAR-ThSMgCVK^h?&1`qSANu}g<=6Nq!VK8$?cYnt~P-Wg72FZ&s{e!Z|2GBo>?hXvA+|CNGe8?Ak zR^%=>eIp+~e?G$4vr<3J9)uW_rbqme8HvlO=;AT=#bt=39o`>Bm=uSvG-KT(Z&9^Bi|2zfN3_ZZ>8ootEECv*RHF}z_E zE9-DpNEd<>Vt*x4t^%i)f9^JHk<*vVApZ1>jQMg)aO@HMZw?kI!hEU15#T=YwGd2! z-g!(#ZYn7$sj8}aHX(|6kaST?f)GUekvmRIdBsM$As2y zo8PC`%tK$0XLeQ2ODltX^{hRnV%;jU8cj0*D?8p1xp|stZ@1@V558*WZOCzMKBRIz zpn6EzR^8E2WHT@nef|1A&GR7O74KHp`mUqgCa(D*so=^FQqD4Kcm!t>*zPgHyr5Ch z8H6JUsl~Gq5qBfync}59K01|7U-*_nU}iW3CB5Gq>*_1nyvIu4E1PmM<)H8}v@Di18f>$S4?sS)5f;Pu)Y{b1%1s zKA-dwWF^Q}pHD7JqwUzX%7870ffARGP4t$juz=(ou^@KCFpgo|aCDbi@`5C+7%@$! z!_3O6?z5=;#_w7(*85`DW(P#!h*e~e6^TP(?olSgqUG2E9IAel+6LFJr2~@Jx6wM(T z`tP~s`{1_ESCb{L&O8}(Yn7#|tcHUpO0Qu}`b=PzKehl=UYCd! z%Q|HbS+XL}^{C_1;guVnEs~Rr&A~>Oo;=0r1&!f3Ajsj4!B!D6)}A-5eHlM#F-{)K zVB+`G1;`U_Y|iUNszg6^y1xI^+Zt#f(oGJchsJ9&{4PM?xqaL2&<|9lWvjqobLolM ze7Xeh9i^UwG-dI7U2u(T@$^F#cGWsh4YFDx#==Cz$60uvq^n0bYk?B1MATOKSR#|V_d#IKThSeH#YaWT_b@lbAhq)ReeS%o8AAgfanj385lVK}`t=mcoZ!YQRotWKn-i}(E!_m!!5{5N3hgA6Sw#+dhNQQh?PwMsexatD zj+=T;4w*yhC*)WLNyuk5Wa1yjm@5dr?S2B?d!CwoMm`<^J{YW1&!Ef#uG5OuIR7HE2D($_~h5GFI?Bx zf8{-$lBL`0SziMZOWJsM%g}15+=rKIbil2ZDH!(u#^Q8PAoF8nS*A{Og!@Zf8kmz6 z*h;oq`Z2|3vGv&GD+SMGd|X4@b??H56=9RqbJi`{H0DuHi3_H5b0$O2o`c$W5?)qa zyx5n4Y}npd(Nn7RnT+Q?3hT6t?oc5%Rd~ri-;97o(T~Dr9 zeU+ySIFF%4aTzJ%*D2k0l$g`Nv+Q>hEL(i5wV>L9wu8(AHtrhbT3!kbE*ZIf_$P8? z$@zcZEpus@Xx6~Iziome!+V&a`8k_yyw818;ig z*aTejn=ibw)UIxt@*7M-0-44Yd{Qy)q3CW4;>z{V7vO3R&afIc8|C{&S(vpQ;f^$& zWdBOFLogc>ZZCdVX{|r5CG(Jri<*J`;y%W|?cb2%&yhtsIrtY}Fe&Vj&Sn#y`2L!= z`O(!H8(7bQXTtV21@;|63zhaaS)@H3bdBKhxAE>|Vt^DEmqC`v6M=W*zb0F5Q^9G_ z8AmtURST+Q;Li>%dBjmTt!9Sdt4{kA$4l2w&nnAafB%otx*xf8Q2bPh_nqs%nfOdF z@W$VyC-?|$uFCRtWg0&gsQ9kC#pjQKL$XI;$h?ftrsc(R(C?An^}a6$*FvsX0>C-T4hNu6v&3&&nmR2&1J>QSd*g7qp77s;WD7IE1-iIa>8$( z{d%&>>!q;be-|&*V>-F{qIm;0g&>W|hfH8B0pJ$}UY*$JXvTC4`cJ+1c?sAq< zo*p2*)gp@V*2aft^R=qdn0{is^#xyfj6r6R@aVD=W0&TG50p`+Y|@@#h8BK`N42Yq z{5Onm_;hH*uW8`2L>iC7p-S| zVs`nmTC(MMY|t_@lti&n6WTrYo`&Pvv17LJ9#0PpY)%aNbyDj^iC1g1Tr~AvxN1>& z7#rAXme=4^rUZmfPsHIhX%EBH_b%7^YjRt_UVBe2TCsE{J!39Idl7aeV+d0Y^1(Z| z$=AWb`K@xMoN#K5*TB~ZipLj3Gt{PqL6J|MnKXmbOWw$q4^F=uDONgP)ZebUFWe`0 zvCYRtp}R##Pwz1wAD?dd_jZFf+H>Spgl|!uVz{_kWJxy;9G|#5c^|d$wuwb~ z`YJb{h!N~Z*NFvbe58%Ecu3Qga64h2<#EQ8l>Hr6iFqm$SBeGB=edm4>l+(CH%Zk$ z%LFs9HqqQ~_1iP~puo^z31a!mPn5u11v!V!shxF??raUK-EBlWe5vO=`C4N~;|RNq zgaC_JX8014d?^DZhsvbv>3GuYQ6lIJlupFj&t+7L!}(_^?YsKzq}BV|RDdi#97Zz! z3`4WA*tSKiXNwaT52reOGX-u&C!OIsXV3E68s7l17Gd8ICP}XGDepFb+nsjw z#HZL(^L+(jWyILn`Uti-#uIR!x_;fTO^gT*zMf%_qAu{RmWP><0uYjdj?rG%%rg|` zN@%e6=5*@*UOWA|rmW#!o90K@q>G5zys~GG@o0k3A>0<;s+`WlX9QS%Sa*4op3cX6 zk=#l6;MOX0YG;$3$-XO7HOAccO#qV}CmfdVNc&a%CvXA}EHxbdi467n-wJaIx){J2 zoQ5{d<>Dsu`L_Du?9c1NSz{Paz_ps|*J3SMc92|N?v6$=kom{=H1lj%mb&2$m%9N>BdjP8 z=?>x@bCF+W4s-z8Tpw6J@)c=_lm+ri%KV)VU8- zfB!*cvW~(`T17)cBRwtcD*0HY9DfL}vNX3S5@Gile+ZCScsEJAkIee`7=zWvs59X& z-CrGNN=gEy7lF$Ylp`wn@o}}}az_ZO2A4Zz_5W7xq-SPc%hF4KNUNO&!bRbj&-|Ad z%fM_Kpe$~Eiy8gMD( zf$j`MHPPn7pfb55RqIErhyevp?5kX;t_4&)jKPK$foD!!G>YQl5-4B1e1Hx|#h%kZ zo{w9HQEqi5EqTAi&o6piCQhZQ)OmErcbrSP83NHg2Q@_FLm!6LkVg^oqs>qF+ZVsq zJpMolGnnhwZzmHX>mHm;4GvD+{hmrm0o=sNA=k66Iq(jx_}Hl2`+*4g+k?Bi9M+}gRrL^C)eBep-rx#U^9Xn~^ zpQiv-!t{|FUv8K$$2F>Tmx_RI0Ooc6CYoWWJo!iyHMcn%P)V!62KRM6Mt-ANh@^Kk zZJ67#eXWyxWy7Bd&XeV@pg;)^4i+Ew7p7yE>0xHB_8hs-55AQFmm+(fZj=1othDTG zPY$Xc3Rpj}zI7*!f}43>H>7PoO>5}IojDM@wy59Y=EL$?)rXCw( zb|U76Ysl6G1=(D1dIvscsd=B8K%En>)H zqT}LL>Se#?d}18?R#6}Kg)oko^z`&cA1Hw%wQFNjzRx+8i6DZzH|ILEl&UIK>S9Ih z+f!o9Z!SZe4ck%FNiCrKK(GorYYSNPmx=}jZ!MIy?l2?~B*0fKEeMNB8LyO)NK^Y{ z|IT1V#uG4fTwJ4f!ik+*_RmCDhU^Mk6Li46lttX>Mjz-hR0zX4r=(Q7s+U@1obP+R z!k;)Sx9a_Up;xvm`>2i{4+Qr|HG`~{{5A!=HtLgR3%;K+vvADc%(eMoQTPPhf4G8Csxfo_H zOCJUhIDeNa3B6duPS_L<^dFl>m~>Vyf8@_|pKf0tZR(qH8`lY1ZAkEORXuWALNJ?; z7k4@}Ve`odxTX58V4ucsPwws1Jw+&{fQ!h#KmQ`|F9QF!2q>Jndi=sbbO`8CHD>J5 YNuDb=Jo-Uc3KplTtf`cJ+4A=P0_BCJHvj+t literal 10451 zcmeHtby$^IyZ1)L7G;o-78DeTL6DSCT1rZ!m6UD}HZ|iQ4GPkwz(|9XbSdFhLPEN` zQEF2gzO^10&oI8{yI#+E|2%(qxmbHYci+D|p6zp2PU6f-@{=eO>Wq}6s3Hn=m<9Y} zJAM@040Z{f0srCIDoWf&Wi?SwgFjAKNvheRPy{vbA71D+0t#?>%uY&H>{!p~!-tQO zx^GESgR2X6V)yMtEX~agEbLGsHU}ZElv`)cOv(*jGd}T=jxHgCP)tEo^tao>8V~MUgdRCZc zXw~;`4jx2L0lx4fc<^|H_pc66AmpP1hl3)17y6)xP>uhnh(9Ik|3bv?LLao^cf0<7 ztoTzRez)ttCF=o4|D1?0D!xnh%jG6h8KDyeev)i{D?IK8{s^e-OGngIkfd_be z9e=zuDI{;$7)4Cuwmv+#ZS*2Ev{pq`iueEnZ$4%x8f$D_ovv(&V_3^sI5%3F>bVs2KhnD3cKbSx4m{=X4WXQ2uM{* z7T*e_3aR}RcA4L%n8fWJ%F8R71Vs?F>((kI6}6lBP)AfjK|#~18b4=fA{sEDoY_6g zbqGZewn+{wc8q}1`%Aj21hfVfAE%SWsCafD9uy)tUI=IRWaIKqEvb(G!}m{XyUWpx zL7Cbt+OQJXSMT7qDEc@macjNo<~{lAhF%1idB?ut1$>Z7!hG|6#T;QQ8YEP{enKfR z*J~&CuBmveXgf00h`L<_FSu-sV=T2F->QN-OD2bFJ70ZzmWH|?y(UAgR=|WIpz7&T zhP;xRN*60A+LGmi=-sw@dls3sWAy3wqGYAJz*M!*zEew~{jItA!zKOf04Tg<^5J6y zH9ZBU^wG_XPoAEZa$6PJO-91|nOroNxi2BTcuk~$^QE)9QxX`$Vohl!7%0#9+}GdJ zjFik~`I+SzF7`QW%`YI@Cbea0m5#)r7knC|7{ADsOpyP@=aSS&z0i)e{_=+Y&`>po zqjDp_0}sgjOfI`@>5e}o@AZ;cSBIq``k*58-u+@ZR=XjFm!pT%e6uO@6e&Y@=rw6s z{6|;FFW{ltsnBb4KI5OlB^W}w1$O=n*PTufyP$+O!w;OA@+A0@kNs>15-}xX!DG`p zxR3p(Kq`6IIj??E)mxcrv941yx_tKLww29oR_+F6n2AYETZ@%6d4`R?^wC_n$!Jn$ z$z0nBAkGXvHw)@+^IUfx<3c%h;Di44(%pIqn%dl2KM*JOQL?8{?MhO?H6ikX7ofwe zzSUyb;+*RCS#B1(Zxt5Jq@^dAVizzUkI~3fbd;>FzCHvTKx_ZjyqCmwqQNKe0gdk-%-NCX^efaDp2z@dTg@k8Z)`z{=9T)npTw^J>9BAZb?7qNpM+ToK z#zpQF>T7&jYO2qo`|cJY;SD`O9Or^|N&93u%F7cd_f<7hr&2I?!^LL60}r!#hN7<= z)>z5pw6rub4nrBpO)ba9;P0mNqH!Zzo@@@vWsu!*YTDkA5{$?4<3ks$q-JIYgkDpv ztMJC{a$3Z6)*;64RFW51oh%KH7hHX@9~mktD(n`0MN@qRrZ$6T-JVg#f6~%rf|WsW zax_RNFxsNzYDH@jhCXkyG0$l)Y6=Pptaou(n5S8k91NJrW!XLbnasQ1TwD{I<4tzo z)$iY2eai+3wWgMo@YMy;(8S6K32ZE2E5cn^!ujj>{ku0}}7tiHl-Kzim7P@9la@9W8IJd=`1$ zI2m#+tL*wle@Et_qaX%^`2@D+@>)veL<1Mz`SQ?ws%t}m!_LPjB?=7r<=Xoko zEK!_I6OCKtVuP(ot1&DmQ;9+1z%fs?ti_gEuVo)61A&Q}Ug@)Kt{tj=lGs^T5t^Z0 zdan$jlw3IAe2qaqjxyO{A%?kpYaz*rHJpPOK9ZW}y0vyc|B*tzS^J|;`4>3Mw4sTU z+5py$=G0UBnF+>gYHP=t_2o-d?Gc-dcNctm`ob>)TWhjA<2t)4`%DIRcd*~)E#3L$ zrrWQo*-XYt8MAiwC?n*W0;%|QF~OI=t&WUvzm|!&SUv>8o;H?%lII+#!@hva=?h%U zP5^$6oZfR-k+q(t+s1fHqI~?AM34~czFZxd8hSJBsVxi(-!4`(zfVimigs^9LHJKF=q9BX|g5;DnUasF4tl+%9|8ntrg%b?K2 z>U$BGn=!%96enXH2Yf);6U$@KFd=1C3sxStX_Uo>Au}@vO3gyqauZKw(PQ-Zi>m-m zU|h(-(sskNLll;_;RR( zw$};^2Gz=VFyh{%fCp+i&$KhEXf~@fA;rA6=iL}an?eLQW{(GGZ=m;&p1BZwbF0tx z&{4o$m=Dy%t64=OzEcis-58M|fiTMFp9(mMA+^-y0rX<6{{;@Z-i&VkLRQTPeI0aW zjWV=PQWK~&x*JR5&x^-`qkKX`|KbF|kx2d~AxO>QsbJ|~Be!J=yeA+sX=AlrSHF<) z+UVQyZ_SNWOHf;5e@E^Clkx~&Tf=(i5OJ;zIG0|1N`@!&ISjuWsR zbj6Ap;x+|F8RS-a$Wnt-2XgfEpf5&(Rgr@5mnHFx-CZ$OaW@y($%aztYVW zM&`C3>m9e9m9~9n;?@c)1JbiA_)6?%!(4WEwnB((ixpnKtDXQR^LX-FDujVu|HHHO zYM_O((AO$$qTvT`jPX!IFH=GJq1hffM#xrif8UsCxao!QGQ7jVs}x+v$&m0;R#73= ztMm6^?Jv1}?Ov9Q+=ua}ktcVB`hXr*lA$kN)I7T=GEyCS&9Bg`+ono%-P8Y0sEysN{_(uX3`pq(?3Nqm?K z^rHR3W!80Wi*7BZtP`V=QQ>-2n9H$f~K^x(t zVNrZJkooEcrh(ViOdIN+)HYC#9<4q`;}0bEFPljlJG)rP_F(TLj^>+0MsfD{TxQFb zgJI42Mh7&ZjorZw?g}u-#gI{z+DR=GFIJ3oX=Zt)LN7|j$_wE*ElTI#u3H9B2;IFykHBq&o-oBw!>%diIqAE zOVL+%y$OQwX;eLK}=)Rgap+#^*-g4*fQUsVUG2Z(W2 zW_5P?j-I8aEN|vzR9mhg8i8Rd%!gZWtn~Z%@gq-x?WBIU0JaFdM+puyy_S^%>YOGk z?+Q9~ESL9`2Lm2Wkl^Mc*mHIftL}eYyIBCMd7AnrkF)En24<$fwAOD=wb{%<-K8;% z^_^rnOl#?)+#TEEj@Jk!dxyC$LO&7~-+KY%cH9I6#La%bK1WhQ@vw zs1AxAoS4gZ&5-D_@0w_gPMlPbaE00F(Y`qrB2R}6u)Nf4-glo(hm;6}+1;~qgOx%g z%=hoI#mmBA5y$~W@I#iS8WZwN32R6<%ihz&XWj2F#z`SxS^{wk%}Lu&!lI>~y~Cml z%{~(e;xb8FAPB~Vvmrojcq>^*VNsSdP)2tzIpI%0d}j?0RW

d36SinD$KS4vPcx zmNY1o3jx2woVS^%9*pHA#m+3PL_Xc@Jrm4z<*ZJq!IW+1U{TNaZsWKAi0}^;52Dt} zj+1~=xo+ZDrd)a5=d#Q#2EO_14sLVRPd+V88%Db@6U$DM}wcBXpDH$^%7sP-&jZruJ6cWX2lP*gK z2BoDrIx4H&=u$%h`8kms&qdgPKVdEV8l(|=l=2$1wqlZq7Xg^Z3AOkf8X}%TPbgnu zV)6wUSN~4Kk{E%?)j=!LS;A%ag z1SKKpf2L?POC!0nYNl!+aRNH*+0+y*F{S3-6 zq;H{BqEAQXu<@%Tj07(Yh7cb&+-7aC=c)d5MD?K7*48U*Y(e9UvC1V$I+f%^2%ep+ zr*hQvr{d?zisD^f*HTeglwX+Gi_zorhLk)q<_U*oWuOR~EFG?$1!eIGV{MVNtK? z%F)xSi{VWyyr+^`)U;1oFdilyFst(XxNKEjg2+Q1*9N!~H-TAvPE%;97wg z0Zj9W5-!-R(y|?x2($u_=GUQWc68n8oK}xwScmNc`DRig`0Pzw?kREHfAgRX)N&L3 zyzVRKPg=_@4gm2S`_hr>|74-Rw4ROIeDh;TfoWm%Q4kv*%8&YrtTk;gm)VUbWU}4A z>45zds_LTs*mH@x_Ee?O(Vm{T-#we(!zM>0K{lETv|%HC6|NkFgo~xBw?J4tJKA4j z@7JAYSUVX1I3e>Sr21kzxI0DRG&$#$iN-h<<@I++7xUR={F;srCWNuR9*uP%Vy4VL z4z^IJiWDyMo|->S5RGiR;jV)X-e2N^XcGr9q10QDr-E=IfV(uSp(?myeD&_)Fchl! zPp}kZVqzM3@4Cfzf`s5Qbli?K1PC7@#yXGXrca`xE@RrD7mfcU7x8&)sxBZgBcnn7 z46WzdLO(^R<09Ab6bU}Z1}cK zpl$bu!iY`A$NPA9jRIkSlgRC6+OINQyO!8?HMuJd@sJltRI* zf$TgJ!*+lbw8!Q2R8FgS8* zH4@;fFjec1&;m34AJBp@`~g}%KX~7N9CQxjMWca!U|B4-+7w$a&wBp)m)|{)HUTHn zUIu$Q($LV*mQ3kz8POV6nxiK`7!6r{0vM33Q+Yqv>J=IpkEbC90NBdeP71jbzA~$- zM+Xh3I1JXg0oJ2+wJID&)RpOJGyPY^k%{({RGem=9qoc z#Uit1Yhr#r=TibIa_sy-zg>4jBwFSO01#m&O4|l@cF-afIjqeMTdJz`yJtQ}=ENsp zw*_M}uD=u@?SMlzWVR=7x@vY2dRh_7^!4(!>xV#qX2a3IX6%EcGnSQ@+3FF*QWpYP zBy;rY>->3b#Vs?_)U9LpDT8G^F)?w=Y(^f)1&#jnJ$~Bd&b0!c!kloY6sv$ks&*9= z6@Q@@_xBbjto52;}c|Riatq_ zQVHsp2Ve3(;RRXZ`~zMf(HGmft$%};m%l;KN>Wr)QqUW@J#n0)g+H%@xqj_JvY%{&QW$iwamD=XXx)ydjUo+KV(gET2^ z3=9llt)^M%?UZ_hat{F7TYbnk`NG5?6LF4oZE;Z>SwTA6E%fnb6;DJ>eQmVtNkevN zULzwTMPJ{Y8V#ecJkL}`Is)Y3Nr~dNqz0wNw{UIVl>WZQlWKT-MegReng||iT}`{4 z4S?7J3o6Lw@D}JSN25%$eB_d2bkmWoDiz3X-6{_}>t0#z6U5Mu(=8cldGHN{zk2Ri zdSiN;ASWTbPX!3UShN0ZRPVDV>5g^Y$eyU=c2l1(Ld^$KLprMvHU}UASvLL%5r>jI z&xRlIIGSbfDU98HXS*x1Ib4&&SW)~9%2*GW>Wng2wk77~UM~ToxsNy5O{s7WvJvtbj-yuS*wjr|rt%?fH#P>Pkrzc=4DlF66zVu9{4D@>;q@oOCc8b=sE}p^Y>s6rhoAlh8GCGgfD9o2 zKOh6O>qAEmltLJNhYXZE#9&HY2pQ~pbv3KDlYs;3Dg`5a^vElVqs5x6u#R-985z*g zy)9AQyM-+dI*es`leB8^10djXV!tD4xsq`I4f4h%ATdag53ajde0URA!Y8+1eJq3|M_@_`_aX_hK zjaQRnegP}Xw6^BY0KdpMAKh(;y&;{1O8Nu&*dSa}(a60;Xz2sJ-p3bLzge4`%U2(I z#tPbZO3wN*8zWBh9!@afXc<*Zf<6S!`nFqZjX(mB+O+l{^mra2(NgDs!F~iSFzU~t zi)(fx5po^zX^8(F-^1>svSqjKNff0r>1oOcvw<>R`$5%2@qm#LKej*$%c5IJV90>n z>`d=veoUI?&;Wxz9LK*^50u9qIVIdb`WoMZt(I6-lW=fr08227{aj){3()|)kktWw zD?OG8Wgp!69=zs+8^oK%Vt$T-n^TD*I|Zc<^W>hlFUpyBHr<1-*Q#{ZReM*&vE_i&9B0C)2-vuTjUVnuAJBHt#BPY&x~4y z@b1+x=d>IwLF3A4Vq#M9HU3MQN_xbv4{vLBRaOEzlh7u1E!XwL4Y%S15-p2{pRV_G zR;+R3F2wRX2Eu*2+s;_Xh3Z3}e+9M9s!QK}DTLuHHF_=%0DLW6yu$ZyX9d@Xb~lUw zI*jDE$@$?OK3bD+_Eu_DXh$y-1K;5Bn5j?Lkd|qv6imqPZkT3j=vcmq-jM(5kx_jk*UP}`{tZEo-^~G$*EMmyZqk0zjxoudzJ0$ z?K)G#Km&zB&2)ET`6KsKv(HQKKO98IWbSBm2(_LTgYZNDIG-ujXt+!gMm3(H{ z6YH@~PeZ+__xh>Jn#SciTjSdEgn{R7ciz6E{_sG=l~W$qHXK2FRowaW>aP5t7h?O( z#D2;4i;mhS%MM_Cs?5yMLDz+qS12#lwR9h6I$mC`UXUhFCYBAF1L&3{?5o{n*VjL6 zu0EhO)Lh-V%qk~AFlGF(5QRc#!p_dV?#|AiQb!UlO)9W=ySUuwQdEHF!9b(UxIgpv zX{1L4HlA3u4?D-{*v-QkV^8&Hu$zCl(X_ki84GfQ)b*kx=7mpl98_uSsCU2R;xQTJ zA2YkRe$BG3hwC1kS2@iMx^=Wnb?>v9Vt11b;mJYRI()k0AQlMsw*b9$+Xm-FjbeX& zOKho{{NtbW@%HqCD0G_bK7F~@IY;J6*l_b`w(OuqWn*9C-xf#YzbklFbw#k*lPI>> zW^=Mw#x4t45`W^sC6A8wO^33L8Gb4@q zKwa!B%(1NA^$YC0`&F?HD#2^7M8#rG?kTrngucK&?N%cmw<|fP9zK9__Q~RS9M>(s zHYfM@iMdGu^Yu?p!^cJnUM7_~pniJ3G)cwC2m_ilMUKi61&M;GGI(@UC7&#++P^0$ z4=GV8jFe)C*GdK`;1L0ifDI9)JRwq}C=_#tD{&dfvqDV5r-2pJ?&VqzjO(UK?- zMUyCWI-NwOlBiSyVnGng_!2-$;ENY3AU zLNBk+@O<${77#v2Qb0(e5XmGSkMy;NSmKg^fP4(--+G7xkr_?$hs1(-5eT^?Kzzx< zuOT?#XMbV5C{CFU2P8pp5DzgGBfV0->C)BR%lET~f`Vw6CscYNWPf8Rfw^DE`X)Ao zMw!mnfgtXmalf(tl)KUxvGVd_umoVdB0P7NJzmj2gChW84nz59X~p4^DP%UmngUu9 zXb_uBu!R6J!O|9@aM^S=l?zb5f^z4JB>*3U6i^5_5k_#V0mROhOeH`x8*2iMMy3-0 z4hRzHWRT3Z;!vm*EAT4_9}$dHB@p*@R0=2#0tEtq4QP!-W67pa2sCS3TLK%fr6NrZ z$l-7SD}W6sp*SF8g+Rmukl}=RKr}=W@}rds1>p=wUw3;vl}P>~@r?r{T*Sd1zY^xh zOTQ=rVICA90TgUfY^ZcA8ihimQ*CXmsWxAXRzV^$Qi%#o3YlnWt<)%ng@Gi45DO^k z6ai4mkz5$gA_$NOM1cZ9oIPF<5>DayS?z^PCk`M1SbzjVK*>}ZgF1 zqZ7zB4Dwg@0uIcT{U>Y1q>q9dRR!$`xPB|$U0QeyV zF^~XplyM?hA5>rrz>kKI)#GEiev-rgrWB}DYb$`vr4XnHkp!BR4V_@iv8EHK6o5{( zrqcmB9r_ksEZ|BK0TJXFjqr$Yg_Ng~E8G(0K$(4OofrctMgbv=Kp`Wj|Ccb*$An3W zHRDspOw#}3gsC+6YLP+wKFE;83t08r##Ag_=@)_ntqr z4UtS2y8R?Zp=LEIF7yubS%!#EUE=QLqW)B4j_x#y1y!7nh~`RMLL|-to?=&yQf?L@ z4lWUv#NZU0#o)AAdI)-sJIgUpdjDl<*vddx{VR1DGd!&t{GYR-nQDtFXZvX$V}<#f zdEH)IJ;&K3NA7chcDW>LW>z|`=vRmK@}X8-Q8@;`6s>Z47e8oK;pMp48MM|``7x^# zh6j%R2?2kXYeo7mICa!Q_@s2|)tZjo#o{N47sj467-MQ5xA8hzSbj$GP~KJ@)teNJ zg7>P}B#WvQ|Bx5P^B!YL z@=!ZWT(VEj=pAK_RkIeQg?hZ-^t9!C&rsfT^;z@qNJ!YdvquVd$S`B?JC9gawsHHj zPzKU*dY`z&r)&ljurP0H*52E}aTW5Pp6XcNSDUiammb<>daoABmH(l#)1kY%e?tmW zl(K25XHMa2Z2tDGEiFg-PgX^}8wD(*xBXl=l6$9Uqm}9J2cYh;L!qII!wXFof{i|l zaH*_!*_jRZx^Ia=)9^dl0f*d#{8o|f%~DkQ@YM&+yE0z4bD=(8XYjyA@q9FT5sp;1 zJVYb+ywpk_FR{9J+t;-o(rglgOSH_7nh z(FhSqyVMo0?z;wK8x#*ivJgvp>LX_5=+Em~`-=^EcE00== zo7E*PJ=&$iWGuP4XAfoM(W9P=0gib8xII7g5w|EnB?n z;lL~tje?}JAx+r9&WrX_)$0xoy@>RTHDA-xcePB@&Fpt4{H?BAw+hOJx=vLaQ}45A zRJN1qPPNysH5+Y$g4(*azO+jmX}Z9);OU%>xmE=WE*|T2=9pQGG)<;Yf2OKkYC1IG zd^pB)eS=eIslE?VLo0romcKO3uXo#>cIo!_M*7lV;KjNQMpSJxF4m=zo#TJkf6|m5 zRv|y$l4iX6wVs78#k!{EaBXNj??~m51Lr0&#vl>btc|m^q0L)1Fj4s`=kP+^tki4N z9VdE7qc8k;6XV1)$WR%FspfOd?g77Pc6JbN*N|Y@Qe=`CRS~o{x~;Cj+xk?>S`06= zJ9R#5ThvM1_k7ym-==#4C+rd&)1M2Tyfw7RUesx_9j`tZKH-_Oi#~c=78vT+QwYmK zZeuca%=WRG=AMlxF@64feMY1HFkqlxTDhmPw&u=o|AOFyO-F;z4>68)|LXWQz-g{L zZFW_>!)(6|w>{E_^EkHVdqdGq+1sC&7?}AylK;|DZkezycSc*ic6EY7--8Fj7y8$l zf+t2jPcV;qpeI=kk410g@?$@*N`)%T$(lReUPpJF4;xQud^1xPG$p45X*?30VVbuE zU+6o-r#pZ`)WR%Z|v$7gBUcT37YyDvLDphIS`6M+&b>q~j){dT)<1Kkx zce*tEV@t5uFzC#@8~gY32kYy14qPv?@7wKdFwf911!JcAHe3?$y7f`10Y8@R7$z29 zd$nN7yf2EXf7M8@s2c8Fp$@*7r7BH>ak)9QJt?Q>#9{yXO#{3*eP{?Dg1M2m<>2JG zb3v>(;NF*4o3Ht`U(heVuVS1hC~deWOx4rXxncLd;;3C(O>f=ZR3p@K( zdPsF!l9OKM@*fZ}C@cz>T6j8flz+47_1OB7zvBX9_5L!|x%*2*=YZjS?_wd~l)0fu zx0-r6ISZvzuYUx;|L|&$Y3N0{82yI@su;vy@#`Ot%Mp=Z<ar`75I0{ct({{R30 delta 1750 zcmV;{1}XWmF6a)BBr*YWQb$4nuFf3k00009a7bBm000ie000ie0hKEb8vpIH zxGZkKWp`kw57oxDsk*wb=gj_pk8sY+?3v$ubJ;nwS~uqel9Mure?z9=F(fZz&DHS zFTA$g;UHbt0}w#1sUO=}T>K~)48HK%k&zLqt*eVb0EJpVe-Q=0E-rql>!p-*=*SUb zjJ*Q^6rrT7%pc43?LHqhc|2_pK#i$i&e?P4VjnP;m7xnzpzlv>@_786ot-h?d#9s= z48xe33=2alcL6gtZQlG!H-}|sU8KC z6TmPGjWIU2f5GjhXf*m-X>H5Tk8sYFUKZ9=-4nRLFkZXj7-Q7U`Al8c`&1NRcWJ45 zdjc6_Q@<%GiA!afrb+cKmtP2xg)YD*;a}JFvBsvRxTX2kwrv;$+Gy&Rb-b=_cwlfa zZfW-R_ELk}Jp=*l!1#E z5r8q4`$0j$;6&yT3=QQCoQwnXV3mE9|TA+LWr!Ava;IYk&#Ku^S3*9=#PgF zr4S+wvw#GLeh^XSuSqwY3ourQ2~zXd3}c z(+ux?$=AFS!G{F}A;wrf1emD4_Q3<$)6-+w@-;R$lefM7iru;a%M0-2Rjl@ZZQ8W1lP;I#e;?+P0ctJ;h%;-JFMni*at;m-QmMmn%TCL~ zmKNaY)T;S8=lfZWLx&HOuIr-^AU;#SoFA&HqJF>MHUjwlemd9C00H7e*80LiTTQE^ zl;o(WAja4VJIn|yD}Z4bT8-1$6$*vOZuopYYHn$9+hJiS#j2GrgqTx*>J-_Pf4%$m z*^iSfWqN0ses4nd<+3%BqKfjKxSs95(0d5`SKJ9 z5F_vB<(2MG;Bcnz91fBd74xlJe@08b7@}uq_lZDY=6lPQ`G09`rSTXJe3VksfrAGr zUPr|khCyGfUQJ_TFMs?*W_mi!nK$pVRV!Cs(RDq@EqoTEB?aJ|OFcWgk8`dSZQq_A z%e|&)hEJS0A>$>$+}X2f$JVV&D8}~yP16kPx^DT?L@fJi*wY7Rnr1l05*C~C=KT0Y z-6ypdjI|ukeg=$_a27I?kQNe?kQNRHh@_@zs98jlfEFHYAOL^>00OAQ$nbF7(i$Bd zRa$^l)jkmCTr$Sij)udFUpp}=(=swLF6g>`*UCTs2m$_uuItrAR2@&L5CLo!1<<== s5C|XufB*mj00;me0Du7CpJ*EW3Ceey&eHbQ77|X~YMp_hO<~vNxViqQ$5h{CZxp{ z9%N5m9*QIpS&|+tg!Wax?`Z$M&vm_5*Y&>tHFJHpbD#6M&-vWvoVmY~;Nj*pPf1$| z0)fnMMcerR9FVYC5QwBVWnJIA z2DtM3z{J!cA4#&k9YP$NI=B`?@jC74ez_-*p`vlCTR1mOcfUc;0f7lt-M=xBW}Z#@ zy8(Bbu9~blyhN`pPU<<<+kj{*9=coF)Tlc7hhEC=2CV^+!8UPp&9hSCf%pB*S}R{2 zIsFF8J29MC(3E7HXmF~pv)3+sBshCTg4YPMWW@nblgZM323JeR?MBTssYP`O^V2+I zR&317^!H}?oPLKZT&-%{0*z1JrG(I>=~>=2)`zyNAg+QROYA$78*_Mq~tjyD>QwOginONQc*i> zdUB)HoHd;se1?ll#rs6f2!}Dv4gB~pjxeYwAuu5@ZG3y&bYtnR2iDB}` zVvMWr4Fr(sWP~p-%Lwl^2kJ1fI7lWY>$u&l*%6DLQy^G6U zTD$2<$_SOiu|LOv4RSR}zEALD8AK z001T7@WK3qKrC$}d^#f-5Wxe0KsMJ3F;Q8IfU}ua2p>}_hRU}Gg4oUx0>CT6jmC%w zW>_#0Hr7g(5)uf&0Yr4TgcHIQk|b7$8C(*0FB78?@EH|RuoYqh)dOzN698}mih#l( z9VF~99Ku=&ZYf~0NS4voVhK@FsE zJ6A-PAi2V2GKfzYWI)Ieu=yf3j|-P!(gS#6kre^~j>EtB$Kg|{U*WmJ&n$p^pe1xZ z8jHf9IUMx&7DACj7zpy&p?|ax(!gp)djdk9Sik@r!T_#l+4m4k##ej3SP(K34wHcf zLI4h^Dg60?GbCQ^aO{BkKp>WFs@-eD4To{uTEJ?Ju#< zD1%y5Dv8Wvh-L0k$W{p1{3Iri!DfTm~S60>M#i5GMdn$D0wbW=N(P-V{l|fG2Z24v!?7;t6<+8G}VP zWqk+XE?|RMNe}tnD;X3Mgks^b43;@Q0JNnukOZtbfDFI`1f+!-fx$F0!()gH#tamb zL2~2?ICOA1*&KQxfaY@pX9i@1lWaXGRtOvl^G)IrLKm?>11p3pn=6)l8=$c{fR~6a zV-rinS(p;AI0DAPoPe{yep6Zx2!voJ$}q7Q6#f$-vSlHG!GOflWqAq$%vgZ2kn9Bj zUBna6c)SoRgv=$l%<}6n6)YzvT|_6-MF0qj!4XJU3<-y&Veupkk%Yq_!87JNeIAp| z+Ww!kWyJ%x{IulGY#})R_8HNqit++NKRtbV3}Mfd5*$8L6eK$1QwTzO7{HwI6U6#7 z#0a8u0|Bsmd`{Oda`r!^0?XWjNCyBUgUA4o1Qv#gv;go-B;B0A#F?4VnWoJDhc4u? zMB#J+U>gYX2yz9c=L}cyl`{)v^rJ7~L4a%(K*Eq%4D#OzLw^n!E$bOyBDO^T8z+`C z3g0yu(C(8AY+hh5M1O6DpE;AYo&VwI^IH55X8@spP4ZLx{-Wy_T|dRZPbvS(u3vQh z6azn{{42ZuYji1ndz}Kf;4UZ}d|4956-|RLTC)SzI*}nCW#8QDQyHLS4&QmB5CT!T zB0Hd&#wtrdp@N7)bx?Sqq@}5#=?!W021ScS4jV-FJdSKv4w>030!(-~TNDJBZ5DlE zR2G6}eH5}SP0~AlG|Hn>tkYE6*Sz={biYE=8fEBWRh1r| z9{*J^cK6KciK^p-hZovhkj?qD*@jAr5jR5*OfJj0!DQGi^Y;(%gmNrz`t^H{X4bvz zdsSBLw=;FTa$@4y_Gilx)|Rzxks4s-oV7VQ&nP zs&Y&xdwR0o*G|_&-}{>rw~rI2roMFP^ugO91Mwn$TJuJ^KmfS*Vy@zyNW+QDrYk3r z?d22Vsj=G+5qbXpAE!Tbx3;#9JFBLxl{N-cSl+L(&3s;GuWIATz#QH=XWqOIxy8lp z3yp@^8qSLP?Gw?B`Y8hm_YB-0i7vhB?Cj(?FLrl<=*PvOE6T#!?!1Y|>l%h-2V6YY z@ZN>z9)7{`c*TR!QR2398&;%Sx9CdM?0y@lXtfSL_!{Muw!_osZQJeAK)ZN{cUwO>#*rla?PNcfrPivjRb_TRUxV|6feMpo_g26Sd)U^(k%6Ao)lwVWVX%d;N*?VhklRgW7F(P=JP=x2>q zQ@k0eP=tya+3I|F~^R)(H-fuhRSJ&3ohDAoc-w|7nQHHu^ z?AirmQBG84x7!ADFTEDqMsK~Fs=NBCS{*@xAx=cNhUC}`#=g2gYIu)CBK4Li=O7Li z1-DnkMz!o(sM}y&M_8n%S1eY5nxyQrFn&b}CI5yVF=UnU?(rSDa%y(YG}=u^Yxx#dsg^qNN^6&fN4`m| z^kbxInDqDR9rC&>7|RNwt3Eu~yV(ygIYC!1;|}yt82m@=$22w%gUh)kqia!4j=)7n8lDyX@^Q&V4d1!uCx7i@(68119%2iKQF1fQ>VNx-nMrN+m}5sFko#i zy|*PdQMJC6Ry-2LSb0JmuxwdFb)=#{nWlW!^R%Rrtl2?2hpj9OrAS5=Sj$fhl<*6S z+pAnaGUDaT_ujg7i>EOAt z*}-`DoRs(OM3UMQ^utZsx=lxf3U2@-CD{@ zQHN#ezj*P&)a(dn*lo~HFlMiJ5a7MrEa#g9_gva~GC$u)U%L3|?Sy;bqKh6K16I4H zr>FBi?r6VqMLy77mD*18swNG^Ln5Q1KEA5=^s3m7hK!?Bm3Eb2wqjQPpI@n5%@;o0DHZwC5$%m+N zl#kyVwqPsYg)FTh$H`6lCuHU1Tm`Ws6M9;Z-zruQ3`J-4rd=eti2}@Vjy+8 zzb5^UfQ{&)$*H~) zC+BgAe4%grxbGOc4!TkdD>6F-hbTGJ-ETva3dGl`S1Ea28pOr delta 2085 zcmV+=2-^4lFp&|EBnkm@Qb$4nuFf3klRgk03fc?<0|Yggt!Q|YW)LWU{z*hZRCwC$ zonK5_*B!@y*S>!|@b$fBHnuTfz{CN<;v_ickBlG$li-99LWZ=6gsug=D48^Adx^BC zEWvQk->|xS6X{o9z6|1tQt)jKrCXJ?m&mPA0oI*k| z*Oz1S{YY1`kd4jn_dUM{-}jtz4<-VWQ5Y6~05<00#f!Pe*RNkkKz1Sr4jgEjo12Rf z5p{QW=YBpgFo58cE9rEaVzJn_Dk>`eXt&!L5iy6u!73{&{}2v`f5aFQ5T!Dwv9Yn6 zh}e3UEXyny4F00EwYA~=`SXhLnp7%$Mpa;)YlVoOhC-q1j~+d86A|_G^&zOGh^ngd1qgrwkFf-o2bxxN+kKf?EnqO-=O_D1bG8Vh{v@H8eE5HZd_#*Vor48SioV@?`{?N0P}T z5fN#+{+zPbON8~xf>-GMBrAPu; zBL+oLn5wGp_Kx@!x%uKz9?jrR8R^yG{q7MqI5rAwFS z^y$+F@)NP$LJ$OjiK6&87!1CDIXgSsge+N81wP#7_kg`@rMz{Or`J zQ!RNSMl!cTAP{(qa{;V-1pvy6|A$2c*6gPXoqjpHM) z*E^rdWSWu9O)@q%Mnps&k7uD2t3du`v)S0LUAx+m)dFa5Z$DS+0w5yh^?H9_>bbC4 z{f1YrT%qOV<+q9GKdXT(S(cZV`!Spgq`JELuO&SCv#Ya&H&6izq_ws6YzfCr5JmAH z!C){Q4u>(CH%o7CFA))cRaI5}y~Jh%#^%yT$f5~&z22XeTKN}6@r%aB#tI^$`uch# zu~2T_yh({fqP;}c1ac!k6be-$`R1++J}iaguby!zJ8awi0a{vG&Itn7XGH~36hG5- zy#*uRWUgMlN<<_mit;gsZNMn|50R-Na`*0C@_0PAI5m8q2Lb_q4I{tE96EHUi#Ic9 zv)Mk3$Kx`xV-dk%@H3u9e}8}f5JtX*L?V&z^3?xjSzhex>+3*fEMR_qo_6ovU2V79 z|H)As$V!sL3=wp7bs|>iMN@6q9|XUIB^1%zzX*5+tRsVyFZb z;BvV>;&DnS%Q72(8yiCEG^iNts4fBz?lOA$zt#D<23 zU<`|irfKgJ$D2cnqAU&%52GCvu?h?m=R1UwB(cuUPPBt!QCV5}DeoeXWqAe0ut>Pw z?rT&6w}{EI%nlwrh)Q54hYug7{rmTKQHk6pCP@-Ie*8FpDuLNlRaKeQ28unS$SR7m zI502(5twWSzeiiUnPb82c25g}V2KDMNn(ja0#igY7#SI%mX;QmEXz-*z?(U$tE=5a zL{6vkWvfIW%ktCF(NR-#LjGc%`*LAX51lT(;k^cVvBb({tq9}eI zi^XIjqPn_&I?5M;rfFwaMPP|BJbCgYDuEg3y8ieZj{JvyzhBEwe%|je))!_iYzJTU z^z=XkTcxI^<_EO#efytoLQs=dwgY2!(An9EWNwyJDn)zt>}e*Vr!Oe`k3AmGx7Qo_ z>m=Xs1eVPX6h&D~rBbK_TWkXhWYR%RLj*3D>!s~~FoviE1u#53Jn(fhD2n12##z0M zM*a&#FlCVlm@LaMhJ`RXI!Z)D!C>$ehr{t_RaO7xa5(OCbaYf~v8ouxaK=JoxMJ)b zpb~6?wzf9<<*i#34u>fciBKRAph8Ce^F)wm3@w==9zA*#m4G9EVRmdBniflM-f=KPQYYYW|$)K zX$-C0J6JYOAfXcMU}Km}CSeSBawSj{W%0;=kt1jaykX(}1X)RvSUes_JK%73@RF6D z05_HJxlS-`<=#Ow8m&e2ITL|Zdk4C%zm2H#YYdCEcaS9_rmE_%5N*!MJAsrnGx@r% z-+=)v9Zz7^S;Q<6F_+8r8lqczvxBXQ!1#K)+lXq3ieL)|QjO&Qc6xeRAR>y#;|T0l z4l#yC+5a`7SUzI-rh5m5;k!%p|1aDI!82RQnCI_65$L);NqH-LDE&K71RjrP0MV0C7#0}-U;_UIT9e;Wr~8f} P00000NkvXXu0mjfY+vPO diff --git a/gui/resources/icons/arrow_up_right_128.png b/gui/resources/icons/arrow_up_right_128.png index 097e602945e8c10ab3d16114396f39b354ec6791..f1217a4813f46b0ad64704003fc491683f22bb82 100644 GIT binary patch literal 7008 zcmeHKc{J4h_x}tcTPl^Ln5GqtS!^?teOF{(E1DTIOpKY##Gn|oDIrowQp&zW5fPFl zDk|ZTge)Uu&64%^8TIt^obUIX=RD{9zW+6IKHGiY`?~kO?tQ<{`yFb2$WT;hix2<+ zqQ*vgmf(}ky;k#s_h%aT7vN*q&)S}8iT8ohy=Y{L2MNmbrIVl}7KID|toN5K+C`s1 zMHXByhIdKio-m3w>PYID;Yp#$*$f&V8GeR2FW5ercfK7WyMAAP)bRs+_62gH+P8!5 zDMp_hi9P%r;m4w_-dSyD=vX}^iX%*y&Os8V9=s7L+J2E^;GTo9J3W5RvP`O&w{P6l zagnWRdBRX-qGbPpg5DR+E&GpJG?3zVRadoD?7qs#xNs?w^pc?-rZB|Z&=Dl8c;)R zhe%y806;=0y1M4Zy1IYn4Q88g`ii>IGp()F&Q|v<<<=OiJ@MT9=I|X@c!7|9+S=o1 zZMT^yEC%m}8(+MX+~r6gBjycueagxV$%L*BU}N@UWFH%aE*}(v6VxyxwI%)$B|hxe zS;&sTP~OM*8=qZt>icc)y_T=s9DHGI5;9X|&kNbv@LYesSwD#$hb7L^)n729iF|4Igh!a67@T`&bU89g)%IHPA;t#deFQ=D&a|}TFd>gBH)W%|$dtu1 z5rI`xFM2KOZ1{K7@?^ZeT@)~;IopwK6C3|E3MQB|Q+-0ChW%RM^>IwYOkU5!L+ma^ zI*GZ^yc;=h?3bLZAHfcyc71xBobF%Iw+6XjZDmp&6RdPr2g1@!rqx429%->&4P`%x zXcB?~pao z&z*>MfoW<8sj+Y%0F}hVLs?W0PX>;q4qL&+f$v-~0tQ`CVY;is>`l#~x->5mR7pWe z0SVV5L5IP}l>sB}})pYWcHA1r`; zAXs=h0;PaNP^pMtEf`FFZxG~1K>yW(VGYh^ge8eVJLyFv>3fqrnLB=ka3TJ*r=Rrl zSV_l)h#+~8sGuqX^oshMOG9H*^Pd)63S22v`id1u_TMy_6!KqW{Vg``$VxiD1_GM@ z#QmH0pSiCngIcDhI6WHiBsV-`J#`q@KhA|lq`2T#UWtlCG7+VOgcFbiJX}eYpbRHq z31m2mps0!@D-nrk0{IsxV^0PX?@1(ap+Im23W$SORK}2$RTSZ5tRfPGz$n47WD*Ll zj7F-cDiTO|WsK@C5N2K!uq*K%zedG{asi=;E=UqyRS6HrqLeXkB@)U7j#X4b!^tXS zEEa=8p%jtdqj4eP3}{|dJXlT&74J$y&^=vOd~gZJX`36X!_W%Iza-`!cqSP%P=}dN zJWsOz8nC8NNmfiemrax^8mp{?LZg*2DrmGS_Aez{k{1K)L@p)@si3H`GQuqj4on6l z7SHWd5MV_P=7Q7pBH@`dFKZgjLmkEq3CgwnIcy3}Cl@>uuZL%nKu{!F35P=B&?sw^ zA`YpFLn_0$_h0mBE)=rwKWTF(4^-`Y$&Dxs(7*4B==+SaBAxjD_5IU>vNDyR(3MGn z!xO)!z`%QxTvp-)vAz!x-SD2SByjck(XM~WDgUJvl+Y^51QeM7SH@$>a3vS4Dp)_H zDjZK#MG-L|wM5i+T7RN5Xk?}j-ixH|3i1eY1-9o3SJ1sHg_8YyEIw`|ZWTbn;3y>g zKM6zpNEpFgGycq24e=kGsI4gcvdDmT-(}$91+ImNpNruS&cJy8m%ksi_+Pq!LVr8? zSN#5_>o;Bhih+Nn{JXn;)Ag?y_*crmyX*grE}_4UQzTDt7vuvTmSjxF{lSA4KjEOE z9)Cp}4x1|@=YBL@Zmtf}H&kQn(jQlL6)5Fd(#XgTN}y`+cdPNRp{<&(x(+ zxw~>;WwS_ff%;IGZcy%K(Jp9>1ONyMq zdUeQpg@!=0@=9opp}?BGxH(CFRU=?0z$3`k;(5PaGkVKc(;n}QbjuDH3 zP?nb#C&OD><>v%=vKxon3Jy9H6V5gW zvP?zRTio_5JkL|nJ?H1%6DnTR-luor>Dcqe#QEWU;mS$_yJ{Ynt`inLo6*^>`)KqJ z{5D1Jtf}6%MyQzNoc#nOsifqF8r#;Q%=5_|`qG`s;y0Fu+tmX>Ld?;X~ zdX;vI0|OG@=8t<5wJj{JJtC$Gy^ct1z>4v&JvBT#-cpmYdoLu2x6ojA;0o(>bB4uw zVrx3jg~HSBo@;s&_5>C&QmIUP`=N2GRDr9f0Jkqi5L%Sk?)$WJIrqJnmqzSVsrhyu zAG{t;j4T=PMfH703ttX>Fc)SW z3FVyHIXdFBbR$FV-e-GWAkARuTlwO~gPRZyHsdTo&$l5EzMF2x^F9A4l?)$A~ z%2xTBtauO5#VBZL67~MHu^|M*iQAu%;n687_DGt7n_{1GhVFoihUH21LQ35R3bWIPm_RlO4ykP5KU9dcHe+Tj2={i|M% zU}^b{hKOY?m$C%6^Yc1w-j-6=b0J)0#`s&ShcNxRKhfeu-q7IX+*=r%sBWBo;O;3G7KS3hTHQ#ICx#)9yIA5SiEUm?1VIthwF>7)^JKg7|vq zoiXqAADJERD_+*NfM7UJjb&vEzh=ehR2Q(`z_J2*L~oy?GXr85=VFU6-OmNst#-Li za*ifT%Hpgc+W|2GVT5yoBP?;N*9%Z+6?C|dQVYxgCX}M%v81Mtl4n7skcPb;$$4BvM&;#A2Y(Yj8{T}nJGHLu!@lEa zikNs%Mb)s!(C~szH}Ta?b*YhIyEGn=urz8|?Be`zcW!M~-CF z$G7APdl0Bt!dlWohcNN-AUaP99+&v!DM-)NtadA)z*1|wsu-P7OvH*Jy- zHYB8jaJf5iMDD!TiuH&|y@< z)w>(gZKm6Ele`-fkJQ+wikqwTkUkqEU&WxN+X&^$qQJxYEv%*BLsePVgDTR}_UdQj z!!xt5KTk<}I)wf?h1&5H^D#OZO`l}CX(LKVc>PpKxKE#)Wozjriu z%>#pQm63=RF)~PgGp1BSUoP7coBx3Kp;p<2jZil)!X2CD#B!feOS87XD5NCurthj% zZ7|yeY`8F}D1a&?o2$X%Dc;Q{}VX2_yMOuOVSF`=MM$`FLF*t*w{2_~D z<0*y#odMWYPUd$KyEAiCG>2YEN)uzR#7sSJf9+BP)Rdh$2c1U` zbvRU4?%1*IxTJnd5RtOt`q?_Mkn z4&LK6)&Pvc7J0Xv8xC2utHF0{R#4m{BWhXX91W>`QheY@!GQyZOba${*qCX>tw;+2 zCH_rg6I;Y678j#0tucJS>dn}f%=A!V*kb7OnLGf)+2Q==^H$*l66xgGpwx&Q z4!~cDCzYRhK67GKB&3dl{#by9%>t`UiS^Q z8oJL!MqGw=(2nBQ`lMMgx*d#1jW!T}4Eez>lQV-p^{{cK07$S(t#3*(dz8^P4Yq+A zXS#0en?e?xHq zRsXCybf9<-DL_b4Lo)*qvkRUnq#k5lMU}R+d}`y|+J##%2cD=uovW|M%=B25QD@z5 zjoyNHS(NZL6qk8D zD|a$z=31i2TDGx#-RJuUe81k4MH&o%5`SM zJ|m?-LwG~IkJr|}!nt^kELMDj&qZ*f%j<&wg%+9qA@k%I=z*J;b5n?H#YTf8#i@{`Gtif)hO zT93DhTt9K*B;VJBuY4i^42T9}3IIVxfa8C)rUEgx$^ej5qyumcKa_b;ly9pnA|iqc z-tXp1BWx{)<8CGi6a3aT*#Y&)Zex&FKQkx@clrY{HQw-?GdOg45(JPA_SwwcrH!F~ zO64zJ$dtQ#8Hh$Qx&Ywd?snin6}63PM@w?DJ(BHnSW{aovBeZ;oN zS)Q~J={jh}V+UMwwcZXeTzm(1J^e#7pcSNlXF0CByW9UJe!n>c03L_$ zx~z`89Q=I8ax_}8yR{>DzM}ty>b9plQJOZj?C;m*d%?J_>uRQ4MWF(<^hHr;EdOvV z298H4D(;$?bL~~p#H9GKY4va;rL4y}dRa6rkvEa59+`61?4g9}iAH-W^CgH(CWp7~ z8@BxtMqO>Xmql~njqX4(Oq~4|i;hzwzuiwwAsms{rn)uYgx0zFrJy{jIYjT$8n`qI zJDLI%7=|x74eatsvZktCiB388!VlqUU_cQIQpC2VYKV5s#0ubEX%S)=441&yZc*RU z9IE0gu9N|?B@VWV&;0Jmf9L<;1%*k}`mB7-ze~uLctrKfz zCd~+%>p7UY?u@SXZmC3oL@;4K>`ijY)2AI_mF8-`0z~F^F~MFB(=uh9OCh@i6}-GW zR$ArR5j9-$={Nmra|pKgJEc+@lPM=4JKM_hIc+2(h5WL>Y20cWgxhYO1H#Q8_x)4Z(>>=y zdo_RxRV?kiQs%LvAatt037^6Vf_1>lvWliG1xtC6yhVt_#7$Q9LG0@uu zK=a74ZY-AP!-I#f5!}I)C<%ZiqK6SkVufBQ6XRc+>T5XOkHf9|?}c3krabwd;my-T z(RyL&7Zso|SPXoAC~ZD^k93?wJsPvpiVWIT|Mhd?an(WF>nH;fMJp=mSaj5B3*^;l zQ{vXsI-l3#`%CPV5P&uP76jfbw#l-Mwyl&#-4fHDg#gJZ55OKh0$+rI;mzS2{rI%n zN@~ZqN>9-`@vzf|GMpGCO;dBTF^Y=XT&1T=wWxr?dD77=p9L+((IMFF(eof|7y2-ch6g}gfCPh*W7utqb z66x>OXYcG#GQfHBW+09D{Q1R1+>zLjz{a&=2kznb@7|9+GbDOsY>ujmzFcNxTVYd# zH&@0#eK(Oupbk;1R%kkS)#Xs#rq$KPrqCkyNQYZ@@18YI%Cl82>Cf}iad4ZwsvyV# za!~cm2b6&(aJpPC-qL!j2RGjS9=tg@>1~{3k|~$A6*k@_Ks1nBs-4i6i^*1T006s< z#?SW>qvcMfNy> z^~ATkQ%?~cD>5iIw7UGO#!R8Q8-9^RS+Gy#*4mLyPTRRwf)Wz2qYV0G1KC08kJQBlOGX8Pue!XL&-v8fXBBFht@o(fK{e1+7zcdM=w;vZ&XRwVVY=BD*-ZDswg zqpB4ZUQI51(z=wDpY!vc5hLsDk`hWA30FKqYN=3isHr*U2-$I~=CC58oHf?rPO4ta z29?rc0iUqge^`m9L}9nIjx4g++NA?=&})=07cU%@;L9Est}IMp=bz-obDw?I6r3R z;GnF%zOgZ1b=?5%#mVA}5HiQN5i@7;teFxHn(%SW%}%K6o~`83SL{2P!MzFQ};%f8f(<(K=zOm;^~=S}gkV+qh=8;ywo%8ybn z##SBB>bYR6_w&Ed*RIvyesosJ{9jg^?k%Gk5r+Cesa>F&yD~5FXq6mg$?eXTdw6c? zg5ZUXFtd2qiWBXeglL3l?>q)5Qv5-G;og^}*XCz=iPO)@>VazCoCTU&o+LQ!oy<2T z$vd`)JRhDDQ768%v%{r%vKi_Gs;6YIb2LO(0(GnigM-VK>l&+TV&Dn0K=VvFBP#vg z(HZ^mH$VBx72@0WNPRAJJ{{C5V6C2}P-sm-%S$4WEk2b#wInqJ;$-i<8(^ptE%VGf zSzJO=(zWr{6l3m4$zIEx>pK_zjyM5*Q!b?=j<=DOm4)j|@=o}*SM1-H_O?_5uL>E- z<5e3A3k#R>)Liu>x21g9$|9sRsInM7p`bm|^?V)i)k)OqzRr3^L<5YKAC%4uQ1)`5 z|5|@;R_@FW=rnLjDB`0S@`AQ@llLJ`SG|ewy&KQsQ3p-VaMYH8ARm|c5=869L-W&; zImp0rFNaN20JD7|@ANJQ`q@19D`5GlwAe2$lZ*ED*((fm=BWiRtz0S@Ab~8}4~2$Z zDJdqCr$Fp+op-SiPSXGVZnBJq`ALGUd~L^xLxZn>6HyO?dtYiLQ~^h2X=Y_wW9$|4 EAIec)jQ{`u diff --git a/gui/resources/icons/camera.png b/gui/resources/icons/camera.png new file mode 100644 index 0000000000000000000000000000000000000000..470db23a3bf271ddc9c386beb3d243246267b8b1 GIT binary patch literal 7206 zcmW+*cRbba7k}=@#Z}^7LQ!0MWXq~6*Cw-&D>5=m60)*B_K1ke9vK;B7Bah02^rZT zu8eF~_Wt?){(7GCoYy(e>pbV2=k2uCz3h=v;r zC6}+;)uB&h+Q(c(rOKxFuY_Ji!l-Q3GOfQ4kt=saZkVtbaKWOX8^_94=OO8z(I|Y2 z8A|6I0z(YV5bFzrMG*a$WqXIw5F?)W3h;qsowJZMCl)GfORM}!6-3i%s|I9L)NkHK z@@*^`O}b<7Ob=gRl(RV?E;!(0(MvQ+*=j9Dp!L^t6!v>;F%NP<6^}G1u(bP6gGZu~ zi9$3%S1{kxft$JXfIQlE;PQXMoB0=2@0fY@taaW^+D#!&B5C$ch*h?tI&te7@hub3 zv6+PZ^i^af`s6xE+@MqiQ}O|_APe!RY|ZF<&R;VGj+)5w=YvG%=~fR5U1tow{L((% zN8{0#+vII&McRo>9yFhMmHo*ZX)0c6_uc8U;$hGXSx>M~1^1LDD2Wcz%ULv6w5;fX zrQYJJ`7J(3^RMro`&`O20S#=AA^|?!)JzDDRy!O4?N+nc%#cSA9ERh z1);DE<>v=>$?K9GSJ+$=dV^q1qGMzv2nX_t1$`|X@avY1Bp$L6NTPmRCM0!IK(uVE zPj(_EWj}0gf=p3{IkdaRBB+N%$9-Tw^8Ru21D0lqmehVWV{_F8@X|V7(YD0k)A{+2 z$X8>CatHPIErCP!iscDGaGwQHOaRS^2t^ z*H`Pujv~zaj{Kg8C#13=#PPFw%Uz-c?xQmFzh%^`ug9RzQ3Sn39B44k&*f}opWA*` zDOigpGJ=NpwQHO29>hQAvi?aIYRG}?dZ-tFfrfO+pVh4Td>YsZSEM2yIkCPx?3Ehh zWlCXq_~CwOIPnSKa9LOOa}bXF#se!poY=GZRT|)=lPNBV$; zVp!s(tH(y-^s*tfkq5!`-ahYA_1W1x9{3YAIryx4{;CT7y(d53uB@%z6nSol0kZPr z##J4*>F9DbQpqxlq*+l%UOpD+?VfKIRI}XkT)tw?gX4r2gKC%IO%v~}ls~Vh>nzg( zGA&*#-Nsl&%7451=+ZcnD6KejB;=3j*;2NgzJITV1D0xtF?|VWTgT`}v~d=D+NJ2i zi$SZ^UU$uxHqsH|o$EfLx3vq=$;^=7t7NIfgjn674P~{l52A9fCtg{ zM-3D}-nB(<82FHHVnM;NIaM;V7-UtLTh-#1lFDhVoc-j)abwTObqp+>b7JmyQsz4( zp(5pM6mk#?ANewyc7eS#!%*&gTL?Kj3vb5Mo9X|g&1Sc3XW&G~!YC}Oq%<1Z#Gd?y ztx1)tC}AwRfy9Jx>>1`nxSB#0wP84y{+!WV^Yl!V-0g&hEIpCfHaXk3EleZ7AW!R*{AP}|6QSur$!KR zjh{6HLgW$|F$MQNsr@BcGYD1jXB@Cok~jf79myK7(~#OYV~rzF$)8-KxxjBq&F!;e zbR-5q%h}1X-m#{;dP9@89t>9e9eMCug!sQS>x0VbiD|88qjNnn9 zxa)cM0IQK26n5?V`P}-&)Qblyi1aT$8|O~RZM79l5%gx8JC^cUm@jMwB8Gg`(xr}FJg#}J^P*qE%vd;egM}XmEZgxd7*zhE#W7{111D5 z5F2`f``B`JA$?E30tblmx(vSxbbjt=rm2DF@QiuJ;(l&g(J^LuL($<*qsP?bYp*I_ z4hxOGMrTdVKwW6AzI_d9fV*LTPPV1Rt0Of>DIvTAyri$4ze7GzlAn5{*xAS01ABvK z{Bz8p`(gJ|T)|gI1+Rn^7lhnft)QxTN1@qKS9@f6wbI{j@07NX+EZ6hyg9RFwD{2_t}r2+*+xL3?ln2G=zG8%V$67}um zARPZA@ABk#CNiII36}{#b7$`Ch5xPbnsln~Nn~%^W%qG_3;51Idr+J&0Fj>Y7Cii# z#4g5|xjaEf)R&YvG672yRNK=cxXeb&gQWYCb!bIH(Ia0buva1V&w%SH$FN0Q=EC34 zIVfx=Lw0N5JdUvYEl>!4n!Z2J@QK_bb@}S%yzk%*2py z*U=euSNYsP8g$ZPd-GSR$r{g{pBQDe`IR9bq2Yo}G;43DrPR4ZGB@YTj0HbHT$OL@ zGJS9Z8E;P&pHwerY=7bK_@Yut<7kJP`I9^WODCJ7jEtQ3cK+g-!2P0*NMR((D)cjR zAFqmyl#W+>v+BiG=`7Z)_{u&tf7c>+&9o#UK8z%Nk()m2L67w%u8)@WqEoz4;E#m% zVDM+0r{3V`L2T_OK&}h*FCAb?y5@49{#yRcC>n#CcQe~dO%Ef%w=H7Kkx!%7z6_Je zDW)0(SrA;!n-k87(;oeBF6u6b zr0#Rj9_&VqGyGuuFb5l+Y*MP#B%=X3dk)Z`&B-3%*EK6kS{%IQq@U2V1`y&;vEla1M=K=O^}=pUab}ow(3A?E0*y zBGIXKLmM2i5gRqiMU0d9kmUyz&qfu_@Q1}wxbF`ojXw-2+nxPOOMFW%6xn9EFGL$v zotvw~p@ld7WNyEZBQCUJ~mZ zdzeb0<1idOhK=orNzE0D0_jwG?}oFgX+&3JoX-*OG*tUif`EzA3iDs)A^|amGCbeT zOe^L2{`L?e?t*4i7X}dn_U_+tvw7C0fNMtpy$gKab8{RcO@_V})7DhjI5&%6F)8*Z z5#P@uLbG3Fcd;QZEcVcg?fBKyx_qh%SxQ&6=vx{-z5=M&DnujrcBUOm+zT6WP}#GI zaEwWyY2gsp!o@L*LYN>S%SeldL-xUZhDj2}>hubL>HYB_bRz*Raf=(UsvsNgA14 zVB!t>tfc@w3t$D@JOj5>!FlfuXXiN)Cu8r9)v|YC_M)rO&VEWx(kXG1%Y({N@%&Jv zS2Ia)=AWofMc6*u;EdEWOXhbT8G>RA&P_!r@@;hu4Y4U!B3=)CxZnzfp3g3P4@ zCHkwbE|VHe!Gh4aUqwT*S@XEc-Y+waZ0C_vD~*iV`xsoR zDQr`bIE$cFI{~n>-$y;NV+K;)TcX)aC||4$8RcPgg#SEWOY&j8`Gq^?vX_AehKSt> zznsajeLReu_Z~z`NR9kEQ0)GuU*Xq!ueb}D(_Kj0GlC)>IR9B*?Hj#3I(SHyIwuC{ zR*2t3D^lK0Vofrx!oXGCzh_(xBqSm{CNFN?Ru24nmm5N9=pfP0UTSxCU)8|Zqx{kc7@43hQF6ns`+a1!`uB#nsFWudVdq>-vY9NaG@4uC% zpI;V6yObgXrwx)R*(iLP`VofV>~BThrJ{(|*ku5K)F`@Sb2?A zeBtv;5|3HLOiZb%fA>i^v?Rwzfp4mxmeZd5di%82iJOMEo~Lk95SgjXtEVFGgJ(5H zml;jDVA>07?7+pdX9`MmZEVzJcYU*a@0kp1sEZS&i& zI8##_*I!aU8L$C`4f($+j^FRtXNb%ihICpxC4Jz|_|5;8sB)#@$S*=Aj&}6uA$6^M zr0{(ztHg6W-9^M-AUS#@x1m|W^-V;Rzisa~`t5t?diaFp9W$qjI~r&h@GLx22gk=% z6J@(Yb^V#_2aC>yrCDYaLo1yJd4Gmaae)Y>K9gx}kUm)Bs!=~d_2^aNQpML^89t>o zfvWCI83uTgR^1mIhUb_(il=nG-@x@l&j0Fm$kjq)re7}y%Z;SqZ0q>E-mzuklYn}M z%N%i)&WWUi8<9hZ@W-pK?xp+) z*qQz=dbe1raHbY~6fEhVZqtVy!g$g zHLxzVl6!cRMQVKeZ)0G$vYStx1NHguqS4^NH41z9NyMp9+2_Hv@0U%l{W&Y$YWSD( zmuQG*%AYtbQpj0?$L3^k{tzE2I}yI4X}fX!AyKeJ;k5ght07qychxn%Gq)3$*ge&k zX(uGcmVw;3pr&Bw?%#2y{;h8{z4JE$;sjie^-ysS*?gN|fyi=~DuzEqAa`@a?wQ5d%p>D}`Hp%-qe%RouMxjHCZZ|dY@la9w8|R(3vfyK2 zv0l>Vddn8$1T{Fg{F+Y84Huo!6H{2K3T`~gFFOdazkfuQ;qho6KVN*{l}b(41?Q^d z)U2N&EuxNkP+M;EEi;3+1Zg`9<4$t2tCX#C;p-XkhrO}J=gi2I;N1POT(T{fn37K> zywtlt7ydX|+xo*@DeIV9p9G*sho^cde{0g^+#W;Q63WUv=jRTN{j?=R<)@f&zQiB! zd)5_ca;tabc-Cf})ubs(-RACGS<%ZJ6zoD%+V_UwJsHMg>5bq^YSvZBOx~}u`xM4Y zQLu5a7G$|2E4$I4FaM47-iPtZVdbskWY4O85BbNl9`N1%^LQ%u?IzLmpr|%u(m(E* zq*v2ao{tIrv{nm9yrrbf;l3N2TG&F%X|*41;xk;3z>j^}i(S%kQ~gC78t{$KYsR~G zj?s@*0jGf7tq2xtPnS2PG2v52>SO;NS2{i?%+isJEob%3O^apx!)m#}@!D)JMJ|;@ z629HgO*EW`xlYCRbV3xt2+l!SEiV%L?mna&=cr0~bYI78dF|1^R~!zywDoT!M|Qnt7e2k*G*_mZ3U z555E^r8LmJ+5Fj2r0ZhOjF9uO)u|Yp`y+kV;%&xV9{~3aU1z$cW?(-o3>7{W7k^Dz z@X1oRt!aF%n!u9jSvR7x97$WiJn7Rd8#E8T(heb6|`D z(eL(X4x_6R%vd$ZarvJr2q9g1vqrV|*DfaxA@?S#B2Z0YLCp9?N+O-pw%i+r#-R>l zMou`!{;oyl5@%9`jhu(5U2Z&^-w&sc8uVrZwjRi6F1RRl*VxqeP4_#a1aA@a=nSxWQ%QVUO z%YS*e13m?noBwmxCF%41nf^x#wjc3-ZlkQnC-ggCcdyNTUq9W)L^0#gaK1S3@N zvud)u+&$gd-(gNMR_l-%5>XwP61~_ql`1_yzJ42eyfhF65}pl^G7K4r zolgT~t2wLXUs@h;BMPU(@InxZUB~HjE-&69#G!d4Ip*&LvY9(g&rtjK+~m){BZ1pF z$==s||M4EAziyQ5&ynbu0x`r!jqETmPG^R4>5CpxMvovjc;S1ox~5l=K`YcwksB|Z zr)aRmElCF;Xl-JtjHO5Zp~2!^FnFL@%!QQ1jgiPOZlgK3j(hRy z2L>%3kRNNM)OKfO@QXEWq6OGMgx6f#h>slEC$ZoakxlegX~t=+@s+X&vN)Pvd_#b0 zaC6SXCb43lBd>uqDU!ILvN8bl)+Afgz{+4=*d7&7e_@P)l(BROb+>@Cz&_4Xa2$!x z-==s}_jHRv2)Uqc#Q_|AQj>#0;inZU?hk2v0a{|lBVVL_7liJrFC&Jg?{tPd;Q>?ff5V~I1s^ZLtG30_2xv)P9>;S>`+ zH53ots$s~Rekysw)e^{VIF7#6x({V1nA0_I5Eq}^!|kf8otbO%y#&EiqlxcV`i{O{ ziB$rp57%ReG$Nd;q`YF~Y$4>z1JT_EW}=o2L7ETIV-YZAn@yqTYjjE(zm8^fSX>09;<&V#T3y!q;hGIp&S9TG5QA*4sq*ID*8ugw7odXF+pdLR!0VDr{8^bhTh2OzgnuK`|aBalrPLZO)1+z?>|_~ ztK>IUte)%V5s{_;h{5aXC5k9#-#YnJDR69Evy;-)g}HB(v8)Iis0San1+$`pFc@(@ z7$b6HNEwe(J(*5KhU=UO#Veffhzo0WA9-&Vh1tAR(bWiy0ypJ`e+CKmn{eo%Y{f-Y zfnHO_n_*h@jmtr+&K@|#_twVGrSD%;skQ~g^1}%wFISYYPRQQGA{2HJAz?Sut4MpV zr>jF0gJ&&!%fcDYdoo$68cSd?b&!X@8C-u@p>hXl6=4^Uu#q?YH}S`1288V_y2y|l z+Lf$8Wq(`aOAEzgPi*kn3#G4C*@_>IwbqpSK|RA41J7!O+{FlFf#@)c=%f&Qqsw^= zUOv|#^%TPWB=p(%E@r~2FArzrLif9b@x zxdL}%yLxtfR0t}2$@*5~Rv1p>>)vYu)I${T{GqiLgMP#h6bjG#m=&Xf>`)&WVKmE0 zuUMYk^3*T)*Yzd}~dY1gz_+}U$gW6$$EsE4=g9UhJ`UF0@l`Uz5S~Ic3B{W)M z*gC}^0fprpUbv2$4ku2d@M6Vd;n^GK8H3s|#AK_tE}Zdf&@p|n*kgs}E>!Tz;16i2 L>8X|~TLu3QU2Zc8 literal 0 HcmV?d00001 diff --git a/gui/resources/icons/cog.png b/gui/resources/icons/cog.png new file mode 100644 index 0000000000000000000000000000000000000000..c2d2c9232304a1842705b6180214b4ec1b17c845 GIT binary patch literal 8473 zcmX|HWmuHY*PacQa1juYkZz=w4v7V%S3p5RiKR=BRFH51Ns(?z1*9aDP(WBxDJ2cM zK@b*MI^@sq{qTNz=9zoW%ynPqTr=m)Ju!y*T9g#b6aWB99qpTU0DxRHA%F~V@v-nO zb^Pzo=Z=;dsQSwC8vqWVb5qsW-)hs6^n;9sUkHJ{IP#T17^NXTI+g-LUNBPhTIz_B zQJgVWibPEd3DJo2r6#$_qf07H=c0L&Lpw2ETeu(^lH~ZxH)QqGz;Xkjx%tM8<(z4s zyr@-WmD#U3J~LTLH+KZUGU%>y+7ROYP@rJ72j3~b0=dCyK?N|opMJ;KXZoAj}qO=wQc z>)PL!q5Ij79E9CThSHLxlzh1jzmz=c1awe?gE-0Gfid{h$HmtW1sU8fx)mDeA<_+A z7>9OA*rKZd9emd8hX%)j)aEt?2bZoNX-}RcJe3pm8d77b{mVJ~!)@xd(H6o5*k|!& zB4#V*&Hdv_m`HRM6HpCLx=$DA;KOYdJG-4E12c5R#8q>00Ei@jA_`}@mhML_EfzW5 z90Y4jLMda^(eXGY+*;zjs7M?eeBl2((R46uV8z;^Eh{sWhC1_~qyCx7Z6q45^Y)TD zo>~BRVFWF>rl*dkfI5PrxM#gKWOQhB4y1mJBuEl?N9|7nnKU6Q?%vkR*k(dUF|;r;CPmaqW0}d#N33TvfAXQNv68{5q;n9*WP5tA;fe|Nw@q#^CQg1*N{KI z#B;|gxJN*#R{baFkB_jryOWQ(%SqSkngn7nnZw!El18g4pSkFR$ndZ3svGS!qXtVy zZSP7<5&~#SWq{od*~?o2Hhq2WY{0;AIWvLjp-f)iXHn%hRi6-hlz1NDW`z1_%*ZP( zw)E+#SHbT~0-|;-frlGkfl}_3P&6#@PSMQ4nGINdL>D2lA%|G5*J0IYD!JzfT%l=y zYtM2%&(04XmIXMJPSOneUJANL$rF04;VRP(7;TeK?vsOMKzX=;_; z_hz=h^S2=Ra-iX=Da`+=VSm^QSN&~vU{+C(+4JN-A1vL9nT7i2D%QTz_Eo{jYX0t3 zhzYy!k^o9`qp05$XUFjgi6;(IZ@6no|FEDxq>~0-#@ezliZ2I`z~iD(?VI2FAs?D+ zc}NhiYvU-cUEmad%LTo+ADmI+2xIoI_QWF*k~e>9gNw!B$PPHoK6JbI4;RT~1&7W7 z@WdGExzVv+MA`}n*Lc;q@Be%izT2sLtBd0m}H3dZ5KR^=N2z9;eC@pTa;pwnNk z6{M~YA<=?Mq{L4@R{y2&j?=l^+hPoXV3~#~_O<0C!QJp_?*>ypmHC4<=(a`pYQ1uw z5SmZ6z5)&5c1ED_9R4)vB%TQ@Udg)eq;S@J%h=o>YIr1CB=enO9Vbrjo#*v$_DcB@ zEiF7s8F(ZvhrH$n&Tct6#W>m0qUW_3|FU5tG3b6v)0O3buN&?N4yq}?4=kkEMg^)z zb4+^F*X^lEuHhs~J|ce%|MC>XQ9c`ZK4xoHo2dJYIB>HaQE;WON(m1`v%&X6Ln!9l z%jgG*6vf}U+|M1s$iigNV=Ktc^%| zp9El*d<+LjAWnYd^W!E^b8#IFp4~8k}>z8*$J2$HY!rGe;*+*tOHLD@c~Q zhD)3Jbd(UH)%ZE+5Mp&nstJz=YMTCdR$wZOsM(uk8VOzCM zi?qV5Mp>cbG$%o1_z|Bt$ojKuSrvAf*gswzWvMwa3Q)f_2gUTKtK3vRkC<7*@#<{@ zsV>G7F5MOoVK#5KW)G_etOb9sfVGl=>a&V#UrM?V-V`nqLiDl7 zTCX@QpKH$QxRbG~H~rSN(yY9muusd9FL`!^j(1Z#wtBGMwvXw#a;)#E&sOd3td>SO zCK)Sl(M8x`xJ+kj`~G~dBCMLPDJ7)XXG@+A|CPpm(~co7L5>kmOP=~P{OND=2tmzX z-fYMn%xW$C9pA>tHJpH$V`3sC=VN|Cu=73?M>x6*3Env(H0<7f?CfjYS!{nl&+@@J z2MDqJ_Pl`Q+kKfGVw4v{?KkTWpNt*;NLGV;RGbH=iUGF-WixUsZ9d;^C%|}COmPR3 zErqDqC_H_uBbN}rbg{;np1~|EH^Txa>2 z7jn#hlGgqjc09+HY-(PC*nc>f&AA;6?o*i;{+)`jeqzG8;#vtGp3AWg^D@f2hXg6w z5_Ve)x9HySJ+`$&1z;R~j=r!OZ7UJka#*Fx8PHiUr?@Yi#v z*-`xRmLm7%&6G%b&~|)!>_g9idu4!yDEMLEOzK@kiY6Ljxw)_l3OF^pzI)%z(Klwt-s_v zNO^tyvAhw%qqlH!;wn!6W)n+e%HmXv_kadXHV#TdhCa0x#HBleSIk0>Dw zHea;IWSfh`&iN@R%Mf#n490&2U9h}KpH1d^tWGE&|JM)_krLlHkp;ZTYERcxep3%N<5Q*o3_sk{;S&Fv%@fOm423@0T;UKf9 z^9%Lbb?7y{a;QizKv7-G&=O{}u_r54EtrR9`sCb)&>RW!GJ#9QZ*z7i-`sO}x{v0B z?<4TW+ub^`5G=Ik#G+&1D3;q6$_V{UGv~)qO%kAFmRiJ!d-!3(pIs>SnYb)`hYOD! z$C%tnt9Zvi+&fO3PXwo0!5l|z*Q~fUv z8QRLdEe}Z3Kw&DR;5`*9*V?IF5gUYP;4J?P!`37W_-F@pi;-YD`1kl``88%cdv zOlzEQ#F5Ocqnu0P)iiWhYlf>)aUQ`D)PNd_f~aUl;y6)EkaVs#K7N6VZj7#ptwX68 zl~NoMqK=h-3JW#_mBfyVy*2Q;3{43_{nC=5ur9Ty9cE;L($f4KpN`ATyp)_H1WFE$ zr9sJwgajNJ+D=x}BDV;Cm&)|b1>8y9YtW&K$E$;$>zl1?c(;z`cj-wqa}+qC(52LV z;A!0{aZfXV=8zrC5>2b9K7?hp5zlMk$7__`WGk2f)4`En)qWa=)~n~Di{29t=M={e ze+Y;{3Bc2dBAvFe`y&!O4@9kf77&5%@|_r*k614>T8PVul3>*zBEQ$wY%(UA?6*&X z848|a76gv>eYIYBgx^2u42PAexE~c8N8aw|&O`hfSO@GH9q>) zygcYBs5G_+GfO(~v`%h@pH~s>zjHWJ>1xU&LB=Z!W#(@6xqF})h83uXAK%YkxPFve zU-vGnI_+G^?-ffPwAjMNv*j>tqHY)OFeDij8#I5=|6%N5IjxZuyUh{ndZ)?XS9g12^Uz`&l|Lz=?Z!ELeH1|@Mw3ohw{3$_ZL315OYrpoBo&CYjorpWM? zyt}d6mp`%Mi@};T)|ed8~VkT)tyW!>(}aufk@4hQtq=v|ssa z#UGyJMg{HDZsL@W2?O-xCcrmdnm9L^ zg_k=#o$%>B?}RRjA4`ksAQk36;`?|bs5?&1gInM!YQ9|y{h171Y^@R%rh>q&mJOU=jC7wGaToEc+kH~JrU*uvZ9M0-$*T>P3Pe)#sS^yp~& zEnqUj?P07Fz=oGhXdRlKsa~`aq|lQDT@iV9yP-4pD70givFS?{SBQxdN{vdsbR(*p zSD7uQ|D^~;5{q~ow91L!8E7AqK34a%`230VH|wv*q)d4sZPh=8^}c0RO*J1S+K*C17!PT;h}`z^jb3hVV(XZ3;)wwX128o%GnjP>WwK3XH)WVn^f0Ue2;0N3F6fr1e!}j7P!j9iE5!w;M@3pXf)51c;Y} z=2f_sT|!`QFj)0yF{oTfu*axLQ=HE}-4jl9e&D`F7gw*hEroJ9md9bA3;L>o`2+^nowTUQKhZ?fq&40Y^rE3iFG-?Ji0 z<{vE!yyR+ze$Lo6U4}c+K{J3X$?*eYFC}`t(eN7u_K?GqsbOwA-$>moFj-|6@CN#yQ@>zr16fPr5R-V`pPXG zEe_|)1}V{AivxD}wn4#o!JGFtbPB2b+QFY@X3^2agjpY0WIe+5#b`CEm)m(6R)Sl|K4)o@~ga$VQC z>~MZmm?Fy(XQA2kCTOWR>A`-QDU-$zjRi`C9n&#Jm>6QI1({P7QzA)7Ew{diR{B(O zgiQ#;LSW=O-P*NlnhR`OKSS`K8Keu4hf&Wca@=FW=c+B~@FI+yr{_E#ujCCB9K91v!!eyW z)C=&%%paj?uDbw7*kR9Zj3Jy<5JNbSUtvq*GPIXx#CIz`VYZXYR=@qNWO#eDc`s)L zIngL!12XsaoEd1_+yejJ_ys$IW;#{5wX2C89GuPkf;Lrsrx|T@4U$i zwsmm{0igT;sFH|M^Y=H9bD>fnWS%|Z>OslYy=8PDZQt2VpnOdRGrz1G6 z(zrPGxnDXGed6eW?7pAQulLEe|K$ujOzG0z_!80!5z>sInD<|m6S~5AYnC^RbRC*<~mQkREc)sgt>|P3UVhQg12JlVWp{t+m2gbb?>%+3r*M-=49}QlpV|qAKJ9%@W6oqPedZiVs!!tC(Cm5=@=~9< z&hqo@@5h`fcCh;QDt&3=Zv{WDpg`)mDBq=Pv47MZ7Dkq?5H1l`^R^l zxHw8#acI8z{yC1!zDzNvAE0J(RYgA@{+fd35u+k}J8V)pVFuaMu(}4IDFa!l+)^|9 z-Qk`}3h^MUsV7aHbFW_Ntw39mGpDJ~k%L_!tk;!)%dw$HSF^%i9PHUWJ?fUd9tCF8 zEWar4eU*Cy@sBvCa4=IYiF`XXfcl!Ng{zvyJkRJRQG5fL`%;@D@jCCKB4Xn*-019D zSL0uT@;5@}yorzUVPYBaJ)fzE!ob0)Fk^}ckK6@-ZlMAOaxc6uhA*ZVaV$y$$V{rk z-j1*hD3vuR&f@y@g&GCF$Sp;Q10;!Q$&5H=_Ls6x2-1!*;u3HPZbQ4sm9*%zhz!4w z^S0jphCiQztVh*W+3Xhi*+ahtW^DaQ<}-(kjfEY2Jur_f$ael^XQ^>gx9PQ@V{*+1&gM5{0wO2QSD9Ig+$el7a36--5=KZ@_&VL z&f-AA-%2=%MkU|_?G`(gSEpFty?FY#M$8>wnf@=KA)xTUg$z79GfEX8G`5oMNu^@T6n7O%eyP>ELa8l>yVA-Bhg3 zW4Ou?IF3!SIiXiW5;n+C6uf~HKS8;m{SH#_0K@w=I3?*S{7Iv8xp8KMk_o^Y&;AE- zn58RYrc%jiOLwHnH%!!p5GTf_J=cqR(XgSQn(RjB0)l)My2FGruThH zflO9Eroc&vZ9yZp{2bn_rX!1b9mz1NIC5qG;=yO^wmRVu4*$yJW3e#9pgw*tETg2+ zOA!I>2IZIzBfp+R&xEtv40;j4)!Kfc;A7SG=zOZ64B=KYFkBW`@V3ru0W zzu5pk1S_y=Ha{r)A-vB=kN=SXxvuMsy5sU*h}$7<)qs1zwOd%_Abm{Y?(VmxJj_n7 zef}$*ehM7N*L~g^A6OsPOW~T{C+?kn58u!A{tGF#)sPyEr~VvXp<2~q#n|EM4sO7( z4|)d{lU80f^5QOybWp!JxVU0R)H7c{BLhO?D+N&?=T9(Ah-nI^(aYTB9Tw5M#DKs` zCTPpm71Mtu*@IS>u>9c0hqOsI*9Mo9pW{{AgW2vkddHQAz|xh6%S{IbKZyvRiZKGeTqP0lV2N$kmB~|#`c;H#QpUftN0?Y|!3eJ*X z?4)Am)#nb}nWxIrNU^>z!6C>6iPT?K49|zn6Hc(c0&R1?lnJVe>_5kyisFO)Pwto# z7{gZ9)L%pV(^RNWH^_jOPOold(Cu@&!nQI?;XnIjq_Cgdsy)T6_-^ zd`$|Ud*w$f`0SP7?lD~+KF)$9iYsmaY|l>+D=u%hJ8b5=t~gNND2}6;`Cs|rbbu+{KQuYP1m{GBf=oaG<37v*0EeS$@-(3P9bY+~u0 zLYDCQyrRMUrZ$^~=@phc^=oTUBS>^PIqeKVTGZ%kVCT!{9!D_X7L#7%)N$c-*||4I z(99hkH?d(s^1i0}jPgdM7Jn#~jwX~$s2gV4kkiQ(%Trcy23R|F`@6>X9~fOc?D2dg<-7i!Praf3nGiC#sN;J< zpD^Bv{ODh81+9N542Q6WbdsP0(e=D@q4@b1IuWyS(i=gan2@@^BO{Qw8b8DR+ofaY z2teo+HMtilTs%I$Fne z@>Y30D~|@wIYhJ5KqV82{O7mQZ4^l=RRj$ei8YVOx?N zLb0hkNWlu89Af;{3s^6t!-;vPx0H}^vP_7fQV?GY=g{Sg2;JO%|2-1tdJ&SPY|6AV z)Xq^CX~&~O^GoXu3KtIpKL7U?z)c-3ePM4*l~4YVtWNzx9=mZ`S9& z2<40C9J0F@vFpD*S?aOzL1wMj#SMY}YL>|piGFke*hftS#R>UAIh literal 0 HcmV?d00001 diff --git a/gui/resources/icons/controller-classic.png b/gui/resources/icons/controller-classic.png new file mode 100644 index 0000000000000000000000000000000000000000..6985c91c4eb377b608e0cee3bdb767445bddd53c GIT binary patch literal 6636 zcmXw;c|26#`@qk=24ie9cFH#PC2N)tV{F-_EGc`IC}hbRGf6^HmdKVY*_UWRXhPOR zmQ=))tl9T9-}$_Luiszyx#vFjx#v93bIyIv`@~t888D)FPyhf%!*jZp06-KG0!SLl z<%)la`+s)sI4s%I)!Za>GKjOSds&oS|Va~7g=&2cD6Ww6)8>=M<)qO3h2<8iKAaKpzo}Oe+{3V zd4D_^zOz~LE_`Qx#OiINWp((@gm-ZDP_g;WggRI4B2ZP%o94K6xr+-ORxCP{HJ#95 z68d1I%>rp_TB?SqaUZn}b?M^@eQnyJV}KCw4b3qal%gfRnQ9b*yP)r(V{cqZkZK#% zz$aQP!F?cn&X%=5n$vDU0QQV)+1ETt>}k5#pl;*93Dx_@rb@(-ezE?X+N>_VFpIEY zE=i`kPeRYHI^U?ug03^>SOaY4$EHgjTw&7IbFYA#_(S0R=)F4k`1Rd@ORUy zN_~MB;3I}rgOBxv8RU@DBY0%sJ z_rprv-yRY=ELDUG2T^%n@0X02tNcsL$2&>EX-J#{8pe}^U@S;-cx;BxV}a)p7t zY?OgpcF}Z=+`$52D~WglGEcmTMFtTe^vDo+huo|DKrnhmw@)WOF)tyD;D;kFn%pz9MGo1 zOg3|&gHvj*7*+rtxQ~XZgyfi@)8TiN|AvsAPYvl{xMBewbN;NL1rKD95aj#Hyy}4?W!I1y?`#lGOr;1EF%ms@AM8U`nJA(IB~-)f!;gDyD!siMa7QO~ zafrP0f(ROYfkd!5z!TEdwW%cdNFR9Pac|m%@@R1y?q-+ogKRZ@FFGO*CAGZrDl};f zNGr+n0?_VA(5klZMhxLBd{hB+O|~b}+nv#>Ui(*B2+uCf8>BdQq%thQ#3eNj#~~h3J1%wn zSSw51{c*qwRs3wLHAi08rgZt&e_h5QM1Ohv9o~Z!U&Jk`<^@o!?nI zkG>=YjbljM!0cI+BSijdaIxL3TX+ymyUGP7 zn-CTMWDq9>NF$__St}w{5Yq+cq&pg{AShgp@Qm8eyI9=llwb`b@qK0-c?UXtW>C_^ zLRtb>0NErd&rnPd9Y-3Qu^H{fj0=NKy*8qGb{^!UEf4{mu|N;gIcRK~K&R&8e`}Qr2r^Z-F6CZNup@>Lhbo@?b+?A8R&D3`V2(*2%2`naE{I-=y!jYy= z?QR^XKU}H$qcfS)O@pF;t%LjXOYn0{@kx}QbC(?&BrUI(MrlQ3L@;;(Dq?G$lvy38 zSuitS?yXm8sa z4aN;gp=)nhoo^77k}w;8ywl8MZXs%Z?i{xCm!~%6mM0SlFKlT-j!xeeBluQm!?zHA zr|Yk5Z=j}6?SF90{Hl*@zXfhqAwEkUsaa$Kt{bx>8}>&(T#b(Ch!dEQqgVbdvzuw; zC}VERWUw2$!VJcXQ`eKF5HvV~<0n4Lg<&T{c(-AmW;m2e^_(b*IEd7U)D-m{?qB1q zvP7(!ZrIORt|t<>Y#vNBq(`iv1RX?XO24bfT;o01VPV~*f1&s}%2C+GyxzPeK=V3V zLg$uuWHFxr455m`;F<~*Nd{3!zxF1xR+WUy| z{{rTw_Cl*)_Ha4f+x4)O{p0Lutmxy&wVI?ntdhO21S(DxXn)o`#r@|-qPX&uliq9bklNsd4(q+xdE?R1kIHHdE!0ppJ^Ap8 z-ryMj!V(Jty~{24ljU__5^jO!w!{#rdN; z1LbON^JhheoU+jz z;lBG)vUmxk^VNm(hHS98CBy|L8+}F*Lia-yx?Qiez-Ua!NscdS@{w8rhnF}tPw%b1 zl8mU_tz&aOgIGPpzsr)il|BCAJIcu%V;V&-ru<|L0*;J?astcrQxN&>+^TQ?_gDEJ zi&#h=@NTt4s{HYmEe|Wf;9TJaVc5i^_pVYAs-NMImC&y|NAO??p<7{nS!+p0m{e+j zSM79xdoH)XQd^=H-wj#&48Fz3`Z*ChfgG{VKNc8CLQP&wR%|2OQZ_thSb}H2s;|X0 z@+Wb*oE<7jfmRKm@zwkMKUI-^YZP>a7RU-mG{$_5xms}#EId5GPt2K1tNg2nY#YaE zK=9fr)D+D+b|Ou_)e=db2=GtJi1Zq@XM~1n%#N0@t0nVSj;pOnzk7jS-Iua)*Z7ZX zKe(JF5Ua2DA_7dbUjJ1-X0RP|+VY6U4ITvM({vZ_GR@0|P5Wnq*3rx;MZJS&xBQo{ zGp|uw(9Z{Lw;i0~yePL6keCv6g@$~>W%HpubcLTZz2V?sqV+DQ?To11W;dfQ_>N{e zMN&nrJhol;M^Aa!vC}Y5=R`~4sXJIeu)ZUQq()8d^z?nxbi|ep@hH~X)u(OoZ+dLt zjKo8{I7ixoRm9b7Pt26297oiA@~w3Dch*fFtML{eUFpc2^otKW7SLXopN4I_4zBao zJm{M;oVJmX={G)@IWr_m-r;WRjW}t}kjAaP7cxM~2so(DM*P3#}bA3qVXrtNJx+rOw z6jl3ej;lbY#Qy9EE3~`CA+$Ws0c6K)pG*RhpF>ek>2uC#7tu-X3$2Va*jF<0YPLH| z+PO$lH0Q&w#J$~R-Y#)FXi-oA zMsk@42 zI8pEFpsCr-t>{!L=cT-Iura1Vb!%ACL?G<^IS=_1*(ElzLaV&m-EYH}c`-O&zOkWn z<~I7-Z;_u+o3bFpE-=bH&$p7z_Rm#Bv^iCWNy`D`l!y4sQV<<9$@eD?EH;sL9NZUw z4XsSh7}$Y%=PQ$U2_E20$taes=BBwJt&2tf|IpXR1DSySM^lMIj(*>DZ>bNR z8Lp!IzO8Ah?Cb^6%>@shaB;inf@=;(t0$>e24BsLzH)hD-=ZvMzm*k=1Cu^5=B`d6p}~nKBa#O7f1+e zH)-j=&!}4e?Z6?1ix<|rWo3#$b4uO|xtY?tk7aaI@O507UXaMb%t{{HOTSD>f*82F z25Q?EoW8%My@VyG%F6NHDh=2iH%7J?ohZKb`o~I^|E&l&Pv4g*D_fvKXt({pxgooy z3x4IgWXfm~DhkftI87dWD)z6*y$Pkgpd^1r-9>D2@7srlj^a_u+<=}Jt6>R#zVdM$ zLapUuBM}gxF2!!&vpqZdP?+Z;Mc14v#Ou+YRil?`ca4_|ULXa=%{AKFcn^}NwJ-D> zq^B44C<+wJra+E^Tw&94kq0^}bNjEpW*nA4t^zHRaHGc1$o=$ltMIa~R!2|c!64BfQ%jnQ;vrM1Y z3fq?Il!~u`Fwr9mRAoh}%~8;5ywC+qxQrbX@}J6;&qFQP2~l z2hyPG0bZ^2^;RaGp>*kNT@BAvH5H?UH>TSgkcP&ajf+CY)UQd8Aw#E{P55%gwKyXqQx88B;7lvfkOe z$W@u~tLu&oSW=Nr1L9MmMGxJ0B5)Y!DuW}{p<C#&U> zQD^6vba1kOqZ9!#5U=zycr6s{_KnpZ9=^I8*;GU_sts8@8_G0O0X+Giy^^iE>S>~4 z2es#oc>Iio$bDxMTKn`SPA|S(T_5bVWbYRNqMGEL?^%VC79}~>Achbm{N#IhsQOmA zV$ko>uVTTw-;>&Et4 zxK?$azsMKwy@~l>2U%x&E~CMLM^%8rdE4$VF$S*)aR~8R;|E+_t?ryr{qC#5?B-?R zXb~*g8GDZ{{3PLT5CgqX;G~94loafQy)!y3>H4ju9Yxtr&*k08&mcWLq^K38nh=)m^#42L~UeP)c^RI^J5vub=4c2y$ zB=?T>^>(e#f^og@+lp#rUIneS@a<5!Gm6_&8%5$(KD7zcC_>Nbf%FBzw=)0j?ES`~ zf?5Av73NoudM&5@EfZ8J>D>sei>@2Sf|Or^f}hc3iF5b#T<2s{Tui~mcn>(Ewscxg z5JTu*eS|hZt{T&tA0Cw#nKc*?lLkK?1UVZscz3xxqFr_hh*httMQ?t&kRo$d$X@JENDzN3U|XLB1mSAxO!a(3-A_I+reD0~Vi!B0|IqtmQh< zS>a`_+s$vEe`zlM;f4I^)8p^(?tNJ*3q|WhP6PLD$9%`&)1n8qrQ;>SNuTA(kzhye zVk;(u9xNBhee-x}8Ae@m{_x&VIruKEdgG>i0yF#d!}XMEjg85hLP4iuq&}om)sNaS zNM5J)-McyRsU}>{_!OLn5hmK08glwv8qWV0qbTt)`qcX^HR4@I#5wqN?SZPix*emw zhzrx_-h#`br%MdM#T7N+Apd?;xa8fwDCcL7rqI#bi7_YI7z8#5N<1D;tZiZPGlEG6 z))KGjoLq`Q*Ed?Ebl(F&4@}0=lgub-)PBD8Jt+Ig(S!y)oV`_z7hpIeRpXhcBaLWSdCBT zn#!3hZRUs8RR@-pUp(@9U2yz#FZfj*meZNmW9pj^Pp$h$D(L!yw8Z-tOEKF5lsKqRwH-qDl2Qmw&8A_qI8r<`Sb^Pq}uUesC|X=-WS~_0OK_ zSf#CctSIPZn55h~?{_u*C!p)NhKy4boD+_DwLXK|r zUu>#}`L&d;7g%YW?fQ27K=Y^0FKX46o~9q~YMap{n$F8qPCR0K8BQ*=zA>?(xkTP3 z)6E(7gu%>NKGB7_nK~a|M9obWX6Ch9+;N0XBlF%Z2bb{3PPa0z zjufVD+{WMKSsAr!7pPwAD;CsvNQ;m zWsp+wpSy0h-;3H2S#w6NGJLo_6We;DEmL@;(Z8`IVC`gP;;-)v_*WwH&R@G!pu((f z=;qLwNVN-3ax{-aPAR?cyR*?L!W+Cg$unddlqKkwH9yGh$muI@@FlUC*i*-|@-)R) zVTqTO?60$v?9P!k7vdo+(sgcncrS=p&5*?}PhOHz%Q;>?-uoyT5%g#DUSsB$o!Fz0 zjpS;dgQyXosgW46lWzeA=iM~&9_<%HpB@Xzu zP|Z2ueR;h;VAPs$^nAr!D41`_=(!$@e5oJ(TRfFU*BzIlGjo4bO%y>MQJtUWC-Uv( z8|1t_n~&A+&NNAqyKEIhGU5!SwE>w^Q%tw^B9W6T!F3MMJ->zrY;dd)h17NZN9rD( z19nnO8tzxa(vc@MJy?;rl=sHR#@7V>kT4xW;A9K|ZA(v~g3P(Y`DM+VG+RVu-qAn` z4L*;X!Wi8L%3TEq_$V|ioc|n^-~a_5DzI} z53Q!QiDT09stC(TqQ{VI+pNB#h^!QN>4`%UiI{JAkW+nw=2n>rC;S}gNsW$AU7#bf zQ*fzmV3{>O0bPoJOJSAS4Q7E;p9H0B3=lQ`w7nYtfwZS!bDTRkqibhsKT=kR5KrOB z(UkYNhSwA>BheH`45|*GLg@sLnq4V8oL9Y?f8=An!)+0Gb%A?c1R*IP0GEK;#*$dV zSDu@;3E=mt<3sE(k-A&ohW0f{Qo?7sOzqHxf6c2rE@v zP3uM`R?6Bzb7K3;c(Q{}h&pVRvAdCIUm!s7DHEinqo*Q8`p1cS(P zWmqOXOD4^3^8wNcgSA4#e<{qq#$mEYL9ph(QwB;~jc#6lj6V$LaQ!$71>Om0MOvn? xAx`uCw)mS1et+UEeB-ViZos*!4L#nC+WL7-4)eR*n{s>u4E4-(tME>D{s#zh#V-H= literal 0 HcmV?d00001 diff --git a/gui/resources/icons/crop.png b/gui/resources/icons/crop.png new file mode 100644 index 0000000000000000000000000000000000000000..53191b8e5b249ab53ff9ba7492666929da61ff17 GIT binary patch literal 4628 zcmZWtc|29y`(At7PRD%A^L36PBobXilq2IQMM4xgO@;`OGTV~5jGavBsN|juC2mxd zUAmO{Y7iOD70E2~SikN5?)`r5_kRC6d!5hP>wVX=p7&YLyAx~nHj%fBr9_jA?N4Imzm$KPyBsa? z6@60nA}33AtCqo*$7k{rB;vjE$t(|YV?BZJawU4_%M%5+8s$&Ov%K%;zu>-|Pq=jK z7x&4@)}GKdec!;tf#I(21E?ZvPoItk*G3!&WCpa|NDxQJn(9#%o`+jsQUF8&Ir&i3 z-O^U+D^017xX5U?spK{h$nLx$Khj?9(#sz>7V;o&R!)heUcUp5CnWEV!-z-+k&b*U zf#BbXWYixsUAS}u*1I}hS&;inQ{tBE+kHi4jkhD0ge4q-yRKTK zG#`Zcx)mNiK&L~4y^!~(cMM(QT!nf^GijZ3=Djpft;Iixx~4R04<#p zPy=!hzuF)vE$DsZ`GeCCw{918U`rfu=+j=7V96xlsl9EcfXH2OYH5~yiK_LMWYoU*wKgg; z(dm|6ytA;y?qy026%ttp=Em@ED>Wmyr z*K;-4+#o8v#3+!nTuCmd6_?w^hHxMQGeGhUoOhD%N}Nrn18KFT`W}@J_ac7#I?DNO z&c7d(#EwIkyJ%HOHM2rL)JBTapUZnL_rHCHb7T2CJUwhaqyyJx%+YAIT{>3J?+Bty zNt`mLOV*eLDSKCr)xUX=rwu>0nw-8V0+mdZJ2!+6W+6NK%k7l2_kr*c1$1;m+#efq z!d4a6w+@a^=Gt9tqGW=V&Hh)x8B_9Z&ab&+f$l##^HORur_$F{``(SVvP?mk0KIMz zB)^IUqYLLtf4@G(Yk0(~jP>~%kv)_G71w+-GxPU5)&mzLdCy)pQX0w4wcs+uc0$N8 zo4R`xG}bSge_ep)n=x0FKl{nBv=X*_dPq<6EK>HQ*Oq_!XBsm_e|AFLF#!Y-Fl{ue z)A*B5^{MXz`Yp%hrdo%Dp56p` zGtZ|8l2GfsICOV0KSO{h0A+EJfv|`G6mA1;5kw_nJQxMY*`a$8dMxQM_~dik^Ka-s za=;%i%x4e#IEfWP9U0!)w$%^o2K#*y0?m`FIX+hImZD47j$35ZX48$JU&Fl$pk{)^ zuUFPu=&M}V4R)iJ6kX}@?Yi#0H6B|s6W{a~!~rXtFm84FQIj3DcR( zqK+O&q}22EnjqTGu_%@A(fL)tr?0$J!mrVUgi0Fx7mgddhNq1=aT#zU5~=CO~d7-QX3QnF(S?bs@-}mkcdmP}0WSG@AvIFe`(bv;zCA~>dR>iZzadf8#I&W#A zm%i2_@|K5s_Wk3wt`_qY%t6W&^T&qoTV^t)VS$OOYJl~ zS;3)lV=!@ZZx86SI`>-xIwAh_QVVaKck2%+OSPGll&2}6JKz??Eg`^Cozb1O0GnA( zOlT=+kG(v4=$x~o9CQPopZQ@lDAw*8QG}mceGJfu3h^`u3v|5#nhUvYV*elA#G`*7 zEQ$k9#QtIw8Eks@>=Wbz$vA93LqfATaGV};{0ABgQOfJR-s;;mG{SQz(tvyeBpW(U zcB>Mx2Dx#u{5sC=Kdwa>3fRR8V~v43jCi4?_-HPSxpbL9#CT<)to$It#tA#Qg2nHp zQGfVA`013=E`s2Ni3ky8wJ{#*$q4ROOb+Jw-AwLuZp@WU-FP!Y7UlZygx~UzJM&D# zp=n;M))uz=;ENhhK^&*vpWq(!wLQIwe(B6Jj<4&4PpfMYybelmnP%^*#X0jZPG9te zMpclki2M&;)lYEzihVuDGx6KdfQ$Is=J>T1)>$a)vzh80=(ghT?mrFs`fmXIp$)8g z+IZqVg-~#JFdb<1JaSaK18ucBaIo(Vuh_JzI{x0x+=8(M@59ZjLx~u>cmXp%&^U-TemenL{wKBoZ*d(x)bgLN8 zBl+-?ftA-vXmXmp5SAF38+-Zd^xF4J{G&qFx)W>Ce;_g{e~vA49xkAbGG+SO|Ud1{WUrLThh*imjfTxKsxr z^mG#(f)aQ-Q`Zic($A*2{X+h?N`W?llY9^0VbPc>Jrik{y>tt&01~zS!@{9EGb*@G z(Iv`ptl)04+za=6#dt(f#(Sc~>Jr~DZUYVRTZj8l*TM`}S@TsMQxFmRm&3yi1+D}C zFrlIhPDE#NfT#8RBV11Z?JFf?u!IRt+*)#PMQ`R>%CX-x8ec!>pBKfAy9;wVw3L*u zr4n^u1_#}U{I?xbV^xQk12MHkEkQiBBY#HrgSYja^A@81@=0uydZfUl&F#&cQP(@W zHbY2Z9Dw8M-VJQ{RP>#spF`L+I|m0TFOEf5>NNQit+t_@9db&~x^9{AAq2c>Q4HVLp-kYpK19VRe)eF~ zWdDg>NJ(f$@NBp8t-!WFE*tNs!_k!-27o3&TS+SDL?(?22~lFm&D6P*?rcW`;9h_F zXVVQv@u#F4!%Biy`duu<@`MKolVmRvI zwl>pZgWd0g;IHuujPwZAkzUaiCWV|DMKy%Z7cRsX^zS?J-JqfP&h`Ls#GpwPlSjR} zPj*3u$|Is)N8>(|Q}OOVkMyoVDcm3|{!k4q#+ovVEK5vVhNRF!96H9dm79AgewTp( zDm?Mcfo8;*m@~fJqo>y`o^Tb+>-KTlgH@Z}a}DD94yvFknj63=J6hrq30r z-}4*yLH=~iU0UlZ<8wybNAyEu_nD)SQmwq+b*>!z>yy3%(ht4korlG!#+RiL%@eZ~ zg~r5Yb@UQRkP4MN*~`;sJ`iOL+%^+2WQcM1xkruC7uFu&b^srnIct0HG27on3DmXNa4_;5iA3yKeXpS1WM0#8^1tQjn2wh0l z706b%H>2e%c%Sv=d>E8PR+0X5E?%@ON>hEW?0z-0!%`4SJ-jfNl;Z&IzEMDJPdppl z_rA~T=JwVk&@6*ryou#@_yUsRxbz>qkVDPi&kgIzcJ?Ojg^421p7=G!;xf@3q{f9A zN}ncu#H&G5Uje^BPv65^8*L3-2DlH`yL3LZB%xhpf9;HjUGdrkjW0Sp>d&@%YSF0G z61aNCE18~#i_45G!ftt$$lz&=risFup=A7?TDB!Xap*SiBQMSs@qc}YBMKm4&{Brk zM#o5LXW%iv1@O=>-QFq+{dvb(*<8CTkEit*=E5SSPTs#-9*lb#?NutQ>2Bqu1e@SI z$a1-a%iCY`{A`Bex~j-m3xM6x-5^9dLZozl&lrJz<6?%LJr6v}tyVk&_1^~svs zA*75F)+eKjeQqZqBx<}wr8O*h)?M#2(S#dKI$rPK*5XA}6bG3rIqmucc$<)=2Do&^ vl%1ITEubLiejX1@loJ%bOf`UiZ2I(|MB|jzcTxN^51^SHFulKre(C=JPu0GB literal 0 HcmV?d00001 diff --git a/gui/resources/icons/dump-truck.png b/gui/resources/icons/dump-truck.png new file mode 100644 index 0000000000000000000000000000000000000000..bc2f0126efaa21ede0ea31cee1e957586f0418bb GIT binary patch literal 5961 zcmWkyc|26@7k}=ZI}AfcNMspH*;5g+j%K;aO1oMrZ*5evGl6?)eaxAO8!jZtLZZ&^8r3Zz^MB>Rr-cpinLyJ$9w) zwv^=A#RQx4Kb%~pHvVUQZRVQPa7U73G_lpODt>G`^zF0Go!h@}F8kj5GB9vP>FsV{ z#&Z6dz&F1NLZ`Q0YbY&?)Ds}_K|c5vSmaDL`qnCUvdC`beXa(dIEBAdV$cp47#9DO z6C*8HVBe#F`t?lo0|AIJlO{MM`IkEGUZsGoB-!XGOeM ztcLJBu$2;d;|mUwwefG11~0@Yta?P&s76^MsBiYJPXg+MsKmy?jBJv+1+vPFI_GMH z*P|=Iyr6CPoxc+<^G}V7tX(P0;2F3od4t=WUpG_GAmWE0ALvBi2fE^{9@!l{3!TWW z3yQGSSAi9auCbO27+7Bt54&C4(I3?STOf#z^$vdM~|+`L_+?ocYglg%zqawd>1r)=5H(F ztU%c1bbmq=!eoby)?j=e$DvkI3WD-paU|jH5J?bDxBp5ZRBU(1bLH#Mo8}S_;!52+ z2G5Ms@S&0#*j!7fz zBnig20(U(Muyh!IAef?Um~CidA%jK3XFIfW6YlzqDttJ37=j%j;a`m15#2;)V}4C~P@SGu8^zsmvPaG~?n&k*Qs%%!t} zVH}d!<(U#=bHt zA-Goa@ynnqd7jatU3{I`NwJ5yeim54^4V=X>)th(9rMDPJ* z<*`M@pGnVTQ4A+tG3(~Zt{Fahf4NZQwKfU3>eGn3yH^israxT_+{O&K*D5{4;{HjF zS^~*z9mN8qo64tX9LSX(l7Xs9eh*>^)%Rb%Shrm~{~|f6(LuFdghvxggLLuji;-3% zdg>I8;k7E0ODDT*!9%O(7P1lqB^KFsyN>o;h72g*JUo|hU3nn)B()goA;q&5!Bopg z34BjuEjPRAlN13=t0vbPg>UCScNlU%ZO=pk*+<2y9brZxBGw~6?~(=%uN<0mjC76e z#G^NBTl(1bfSNE}v;cIO>S7W;aS#d8b}@4=+v8(yBUdPZ7wm*P{-na>*o4y&R-k}z zwf8kmm7N!8+^JbB%LPbz0uObbqReap9(@za(#L?$^UHMx%%V9gcBS};X;B|9@X}kK z<-!v4dQ}1`>?CDtf6j?P!GB$&CMFTG6~c}>K9|JOkcZ9v0%(R14XBB|yqC`lr0!S) z6YkR+139pjY+dG$9vm9}`_D`KcBdNJCcC2_SW6fy4{r3?&7>3NlAb@y;=-uCJ7-me zB_FBt67lF{CBpA?1$N%m=#d9F$aOZw*#kyqs@N3)QwxRFqZF2U+3Zm`gtkszxO5sZ z;0MsQWs|@!fe%)e^G2p%iTC7}$z{r1w@PCeEHrB_zjbiwMoZp9m~r^~P=&9w2q$Cl zTAyKXnFP4y=d$?XB6uS(u2c0p0euM6;^qZFYMWq8D)2UtDo#1r;wlF3A+#yw?zJ$q z0%(fRo9^xCf%qp}v|fFBp)omFi)0IG4=^UpBE?CNLoSAM1T$jkrHm#0y)=J=$Qr-` z??u3F$dPwzp1>mh0T=lXF||qcl9Ll~;bK5%4m9}iGdt0tA&=`?BqtE!@4^3BRRhOP z55Sq%uzKL>T}_;XaN%67yX=C}8dbc#GN5X~t6rpjOw0$Ox@dDTSg=Dm73N~~R_4;+ z`iJ`0Kf8wz-EPs9_DHc zyGwBL078tXb8kTMt_E+|`q-Q<@_X2r;85iGXq5T9@{s2$2i*)=7y64QCLo|bim)^u z((my1$_+Bx`9EXHkGY7ae#TJvRwo@>D@LW?!hX*NQj0VTOGCG_Q)oCPjj8FJ^vW|z zyNOo+*?VhY;um!IKXij|F1nb&-MMC3L1|@&h}AU~VjX7x)MQU)6h2>FpGW})Z$LC5 zVL_*lk!Nx$;msl=P?mc*e~BKCh$9SuXRL4Q3e=-%^pWChY~~N3JY0L z3C#Yak0*@1x=MAtp+zfWY6vF%f3c0^8JJBO@PU%WmGPM6rvkedoVcVFfG^_L$wBP# z52d<`r(Gh2;NIvQ5^`;JhPaKaq`}qg(YV+ zB@L*s_0J631Zk0sfn5d7%yq*j&`dw-hcj~mjalXl0Jme*KtqFub#N4NxK}WWtlY3) z$p2B@Q+Oe9O0E?;J0~7!H=o`;+WrC#8XrJlk_ zgLC2fT<38y>6tfF;h0K&CX3l1XiNP>Ru?pJm7T=kO8G+SS-X^f;EWv6oh9I#hKXhxG`e=z=daADy_%N*hz=e1Kjpr4Mpq+ z#$CANVA}EW&(!e7X)Gx`TnXJNQ-2kFo!Kkz*sc>n9a~*T)z?UOrym)V(H1O21Wadh z%ja*CP?*p=WDJ%BM%`*R>LBN%SG8!ZfLS*zuTt}Dz^6WSa;tXmhewpamW&b1H9Q(3 z-x-=ZfIHu?K-3xI;IFfCdvaCQ&7@iR*~eC#C~jK`8k!@Yiq%3enTqFk1KZar8> z55dISFAdKHRHz@%U7YDJ*C}y)3%27TZrthGY-1jXKQ&emuTey|Nllq8+lt3l8@jQz@VS9<~jDFewe;9!e9@-mue8p-T!69IzB zkyQdHU7`;DlJ(ynB1Lou`h8qIo#mj9LLBEEeiU?K_IffSdMSp73R~TIO5Wu`NIrBX zQ`}4DhdC`s>?H1v=%1DZa3L;`OZS2LIoE5<&oGQ&+Qz)Ir7aT!mN5;c8?{A7{O&T5 z<#D5lrA=@SGnGRq-m>?wWhIFJeq88lh5S;)al+bz8v4B~wdHf%mD9aOJ%#FJ!z z$0!$U4Kt*wD~gU6LyJ}#>?GSFmgT2YmuZq@jXbtTTWnOl^H!y)V;qU2zUAyn=xllv zOunVbkwdMTe?SDSO}gFf!UFoxAjndA$dr(SagSTTaOCq3%hts$x(YU6Ex}g-Y;(W6 z(#B+Ft+E`6(?UBT1-boVnSz(^e?i$e53%|)3FW|J)>uQ2F2#9-_t|6 zlZ#Q<6qWh4Bckdz6vBtvV$5gQ=`qlhcD;7hxB*#tFCUL)6{0gmMQdCbKgTN(E~0d~ z`&_&t68@BOzB<023lRmmB@B?(LXn&|}9o1VLt;5W-k zQQw`5_J0loUyL99N#gE)1&+G^dR;XXSEo>Z9IJ2&gLB~85k>P2!t)~(NE)(JFx?RJ zRiiIN;O*VFQic3`JG>|wervNiZ@&=@J99zg%(J5*)~Qgd!d*JcKE#zM#HzV+$rNOt ztx>|nyRO=T>)GAjdXs6E_$1Y|2g{GH39)fv6yEHsNLK$6Jq}{$KX9Wf-rHPgH?%AN z)Y$IzE6k=C8c4Z#*;N7Q+t*B=g=sJ72Q)4q0f1@!i1au zF41yFr#rCZ-oURWAY#yiZV`^HcGhJa z+>O*(>lzMQFE)*yH`75x);sO{m1}=q5iv;_-~I*1d4@Y?Ok7twb34E8IuSr< zN?>8~ZuY3(%z#Jn(Aos($h*ui1*tDRX3h=$z1yobP&ym*wi63cCmjQ>Plp0j)xh@t z5JMNZWL*CC5iAwF>xip}+Eo;O*}p3nA9HI@0f$aKl3@0S>^94ryB`DnKMN(sOnjZb zy=eo|j5wcW1Y@@pQ?1VJ#jFM@fI|pFW~fF>s(L*r6dQ^m%5}9Qk$>|8R`;OYI}6c& zxw|(nmv~C;N^$o6hZmiMLLw>0W^}s@s_{4Tme@6qw!WkMx!o^*BtbiyQkrjvS?x?~ z58BIEquhMsKtO+)-~YCk7uvkBHvXb8q0TLxCBs`gU81k@%M5tKMcPZX4VF5-<=fZ6 z%y31g#P435=3gz#kh8(-kN16XeG}&_wwOV`9-e=ou;r^)!3R+T*8@7V@AtiPe%#T% zR!hg5&uCIp4y~U2t6+7ozeg^BBWO5#S5)pm5xV`Huer_+vE&en_Q2p}#xS~w%JDrRE`E^3e&#EnE@b2eMcQ}`Qj?j=RTsaw(%m%Px|BQZt(PJkW|Z}RD-~>&{kTn{1g47Q2d5hRhRLr zx7$*a)gM>P!P2GnA&YH^{n&)&31@8SOWTGjKj zc*?xt?$@ohm)80A*9v+x!_+ugX|RFXL6bawEkJ_VsWqW>+d}Eei|Xmg+FHB{s7*T zCmTLI^LXTY2bjxt&?tX%PETyw!?3>-{&wYg6^LK92Sh`oFJ}j{^=rj64xzhCu9b0M z%bq^b1iWJv>&D%>sk=27=aN*?5Mt!T2{F>1QvI?nXnmd&tNPgWQf-c-!{1VQNw52S z=)I>O-PMfwDwcPBrIYp1mC79kMLPIJq$OOxo?+0TBwfe2t~E)@JW@KB5q@h$0%&XQ z93tNnvbA|2c6TQr<@c*d%%=cWLrhNTlguQ|xpb??5j(5kxMq8DU>5h8mfwaTzhl zOlh(?n^<%Zy1|_3->9ixR36UAspW$peLhW3RYd9Wfb|Oj^o+?ofqPJwsOKvK)E(q5 zvXz)sR&gk4KOMmN(JFYsvRj~Xn0tNY{s9CPm{vYF7CMSkBcQcE-Tm}vGVlj1`u0~v zcvGPGi8#^?h`6VR;>L7Qm>h>^-c&u5AVF4WfsPk1sVw0bQ#a+&-&iD|oJ>F}AvFFA z1ctMZ)BrCko6u`G|mJ0F=kOt-46}QF7hnd>va=^SG zw=`2X)0Ce#TOuYz+FD>w8j!|1N8=|XVG)9Z@||5A$>)xYS_`-0dr?nkPB|>iXyTnT z_evB~(y&^trQ>*+2(1u1!4GFq+Ykjw{>c)M`66c|0rf;0u_(Jw-X(QI705OC{9hG-vtjWKY!q)^crI(xrsUhaRP7wbb>FQPG@GwaxAiM@XXG= z(q}b*nk?2!`%cq%HQov{)Ooi3I-0_lVlor0t$=Lw>)Lp_HgZjFIekwW*abEQM?1XG z?N+?HkaEI!oAJDsG~w44%ty^aV=Ws}X8wAUz}yd>CxY^N9? zj%fGi%qO-=^cOL5r*%g}ig=`jA+~vtKtomyEEz zLX}89EkvU|brSRod%v@n)k@K8k?H=iB-Cg?)iMS42v$D+83^_TT6O(3v`eKv5g@c5*o~BQjkbd|Z1_ALIjIQ^2C~pl?v^8ubeKGUEFlk%$DV)D4C2d~QAB7( zc^tR!Skw+x1`g>UC-K{x;ONY}=yc$WnH`ef3Tk~jhJ=5YHPMtJY(JF z?WtaYY-?;-t*>r;ha&i=k>KX`?~BxRmPeAci*k^%Z(zMD0x0*D+FFRv#y{HgA4+$> zIM0-U`9<*@KTXKUkIZ;Aaw9B-0|dU`Ff~~d;lUK%iueAU2SUnVgn+^^9L}v~8$vl0 zs-E1p6Wl(v&iM(63V^!)q^l<%JS-XMPv46$G^LFS%W>Gonfw%U@%?x#zOcNY0*4J6 zZPnIhg&(hkgVIvJnvoSr4+Y0VrYNm7pm=Nv4<*mq-h3ht2&X@0)IU%uW(Nz`!m9(w z$9(ws{@rJ8K?WC{Y{{Vz#Q|onXG#-+(3Mwi^%h4fkLa1#;DV=a1*-Z9#-L}celbc3 z;*?J&pA>-4uHp-e$3V|4Md2V3PCU)4OU9G`N!a+4!6tX`(Fv4s*1XzogAWc1y%<^4 z;)1t(1C8SQYzR6`+(cGxNI$ZZx(P0a!@D*F;KqcS((}8Gng~(O z^-8=9LR7uLQ-OCk6*?G1qsu{94z6)ApUfgy285k=d%aXMgxZ8H5))?A2OYeQ>g^Q0aiU%uUO*sE+ z74m^NKin&tR?7phe{!j-;p-9vbI@-HzYi?^$puz4>*94H%%HPW&;b9`H9d;A&!=ZK zLiDTNOI9#))_881lkr4_pe06Me_Or1qPsQw@wuoRdxWmqdG-63#`>3MaiLeG{subY zv3V^^4y+{P!RW9HA0D|NwYX38jIts-N_G5^H|m9;PYU4S7KXe)9(Nd7ui#o=3TQs; zj6(dIt`CId_bfn->NTse#K1Exx-iC@Q->b!@hBR8IhtV0skGXeac>H2GSY8tHBn6; z4Vj#>-8_QymXe56oovG<6)cnUr6n_h-taq*2TK|7_^Oz*qEYA{j;Vm?Uahhf&d_^d z(y%M`ife3+V7&q16^bFn=Wd0Fqt>W@R;byD`*P6Mm1e;lB6aMC;Pdj!JGb>L?*(fj z>deIt&Iert>lFz<5Ju2HPalCj^Yi3Ci=PH`{*v&$EcWZh`g?bMZoXFYOS`z(hoe^s zC_r@d$rmdcy8Nh`HQX6XxT|>bgls$Wq~oXdaGxuC=A*^F-<=);ngcTe`^ZJUPdgJ;WxzzR*f^fDA$sp`{N;ba{jXcwU_5;dUIav`ADcEP#u^XB-){N zkpc&l{O!8^qDAQ&*KREXjSAX^IXm0MXw1rhMx&p5Wz!z$H~#DZ zg)b5-#L{s>4J~5kj+3bx>qb&VY_lz$;b~$s{ahiI5d9~DoHrn%&2vk~UL`e67RS)U z|MrS*zA01k3=*!e*)WAJzWo8YRs5nNXcTr~&RQvWTc;o_E1IkIxH<5|Z3$iIJ{ef< zD&f^E2y=fdr%(Rcp}HmXCh2~XmT*X{TkH)2=CId^hjBV~?dJX0+vpyT;t#nh&KMp4 zn$7!R?urrb)HN-Xv1fm_HTvX_oydx6&Xibmx_#h6Cfq%CMVSz1%M|a?U3Ta`7*MjJ zm?8(a&33yJM1|_7wpqMbnfTo@U6ZdCe21g>zQxd*H5B|lRd$XIc`{m*YdO@BM%3J~ zA*`ZiHvFWv3bhfo5=VDzxVG*jQN~*8wIZ1nBxvw?vSj=G%c!4^d3OZd(xG}PB4n?U zAE&vZmx5-76W>R9_((GLWZs{i_tg@?>X56Y6b5aAH}*H=iC?3M2g z3tjgix?O(<-iA3RW}F~M=pKqw+u0dg`&in8tn6NbfF<7DHYSg#=La&7B z`+MuP&fmZPd&3uWwlcN~zc(m9U0Txsd)zJ##;n`*rIY4AC-XNs<=0=HP2&$=Qa{!j zHr!Wo2>kgg>F@p>g!z(AYlHY}K4`|nW7iIJ+7vcrg$vY(Z=X=Le;hB$_8LbvncZ6X zPY;S<_Mhq5m6)aU#LcD{ovX4GmgN*BgVs7cy$JPxDx38#RR=da4cd&B-LLmQ0fczy z@RZ{@EjIcu2s)PkC30|69Gf}4d6wdGoG1ASW(;yYHs;SHe#S2UI}b(p*&F%>C!|b* zA17z}1sEn4p1JdI7ebMnuV7!51*b1*pNLuYb$hd-uB5|kmQMg-(skoo#^S6en0a;o zmHxWShW)z`H2i5Tk<(WeRxjT86!p&A;1iO&`o~*)H;(?O%Z+o+&B~o`w`Z1TjLL$NR{k#i!~SY^r0u$-Ooo*Vp84Eq>$R&p z2VUqn9j>3v9UJ=X@|Z3OX(v5L+2TD_NW5Lm5Bv^G&fgp@S`@W;u~$DI2vMlvMnsQF z&0jRpYhua2Muh&>+KFw$KjBTes0AKuxr+{D)r-^H)hDlIyd5qdoclZZ{dIA9DmsnO zh9jeE7z-Oc>&s5m)JuxKn>_S%bVWyTgM0c|ApFp9=qqxXp4MnsXdc`7zAuiLTQBO@ zP8)}gnR|9BO(FdM9P4|V$ETSuKRjv8IQRKp975M9%>Sg`f5hNH)!ilA<@eQUN-HbJ zvZ{wDs&&rQhvg;`M5}h&l{;NHU(Hs^zj^4WL_C6B+N0d=n{fSW>CpKunc#p=Gm1O8 z4^;$wyB>06i-^2+iNJhrRQGe2V*dyn125uj1TD(|E1$AOI0p&5x$?->J zpd0b7XjHX^wf)N$2y?;BqTQ@hV|wuMZ=u-R{p~(#$XUEk31F213&wCVWtXr({`K z!K*FUSE8Nv{rtIs;<3|kD>I%GP-@jf89N(LC=FVhhn^;=L*hs{mO4LW@D6AzuVH|9DG& z|6ej5t7vdG7M=u`D-IXfu=;(r?Cxeew*>y(<`Hauk&WRed58mRv@|N;_VAq{MEL1U zF=oWS5sXhgJzrlbUR!3t4)Uq7;x9NrDa9(o#kior3U-F9oHH!V4%yU);g{V?Bg34a z&5^jrW1{+h-7dHh{<_jbl-0l{#a$JXn zd=$D1A>P@L+=X!G=sz@MSuTPN-Ji4#o{9dDs?%S^Hc+Pf2j?R7266=}eQVa237AbJ zP9aPP#?%-g=&b8YZH=J~C#yh`c8ANA4l1Y?j_m!*3E}T-5wd-1!Ue5Hx^uh2_{5~z zF&=)X;h<@k??7g`-%h{mj->4K---1p4-9JPf+&#OEGSRj^{Tp8DgOxHs?nUEH}JKe z*T!khW~J%Gk*(@%nI@L>@>2b7SZC{qaCs<~0E8YD^6dSt(!d%f?=~D1mT2Q)%S+Q;+scU%&v3P6 zKe`E+!| zB-9mDy<@NDJV`y&&M|vd<$L6BZLjjl5#ufKjb~(p7+fUtVy@O7!w+G#wBjmcaxAh zedCK+#d7dgY%_NRnp!Mqm*G{__ssOjnxQO|5opb(R9_i#@?qZiFa4@!j@dUo^34fF zRwNx9qkd=8Qx7|~+bHc`=RWUl`cn_#_JU7CVP-gzUA&#d{P|IFgqaaJcVAt+EgMJQo0#ii&`LTB6t3TetP)%_7j9(@*Uvb8;*)FokBrfJ# zg`g-G+)SyzT>hl}7BqWmB(O0M^oxLlr)Ww3VcL166FAya%Kl_>oyXs#f)EixvwM-b-rN6f9vIlQ z5nmWNw0}?B^LcJpF-R>>9=Wjo(@udYDu%KL+!;;(htCO~R>C9Uxe|Bfpfj1|{I6>F z7k>2Tpy%HVm5l}!Boos*Ee)L|tjS;eh2sq8Q+*I4?HAx1E&#cak*Lu3>p(O3o zk60*$`FY7;Pm3qF@AXJA3#NF%g<+&hj=`79YT-)VuTNi^6A35ViQau91|`jGZW7PYFz))Vjz7KJ;@|1{ep zJ0>Shp>Maw7SAID6XR?PX7$pWKy*u265JIzUcC}__F~5dVQ2jP-Y~j5qSd98qtJ2?N50%@!)%n-IY^SG zNQ>YQs`G!|Xa-ZzTgqx2 ze9)WdOjI%}lHSen5okgCCKaAsl3NWb7!W%%$pa+;N(mR(+{TZq`_{S+)CSw8AlUBO zT~0GQ*6CrM-*^~NTW%}X7dd5X4SnGXS+u}b(Q(m0Co~+1MI0EUVjV`r+ zROGS&JEn}c(%Jv@_1bO6f)m>VQA{3xb5}6Rxb&a%qjt#JfKmo}dDpOrl`=cRlM zew$`V5d4)lhLA)YBD^WNixYdhV8DeJycOc+AzAA1R)kH$`vE+Hjs>*YM5JAQob@m_P#8x{q z!?C_msS!!?k8v`tQR+s(v+E_&kT#wXhE0x2@qvX(D0^&3!2Ib-7Pb)_x{3WAl@bE} z%Ahxfj*61iE3(2uc(N!w?Xk`ul3|q=>nOjx-uZYayz^Ohq9Li&59hyTF3YjGi|DU{ z)%!AT1&S;JO|$Fki;3YkcRbOx_M7K;mw=(!j5x@Gd6G86Fb??CGIMoL(wT#27 zW>97|cxJzrA{GW4x(h{`(7#xAcd)7<2 z1h{7CAbJ%CW*Rm2=P!1~T;I+I!Or@(ojoB@0KYz{LI%9MeL`otJ-1&d5ZZqAv$~u1 zg4zH7Tn<{gh;PD{Uymne1)NHF&IJ=9 zdco<&Q&V5I$-(ck>5o1_a5bCOP9;EAz~xCHgd!t9E~17f$JDgNozxz8MFhb0b-;{1 z__rqtY!a|;y-UOyfh9cI&5`3*-);yJzL@t@Z5O<63tVJQiNI&`t37Az;cDu!b!s<4 zhA)a9ei4R^oLHx;%T=vwp!!_b%To%-NXyxUqYFos37>1&?GPdyzObMrT=@Uiv%9$Y zVOJ+(m=mRk+&0&e19MC9VqS!Lf6+}O1CO~nuJ1L4#pF-Z#|f-JK9>|ifHoLlE1TKX zCIDiCJk)TO+aLbV?O33sTXs?B2lWu(IQMr>f_&+Ek_GV)C3D#Wr7b*FGGSu_3IDwc zAeb~V5Wx$omL2h|InclGph4XQpxrU|mh(MgO~As=R%%(YgDp>W;P4@KFw?qUnhqV7 zT?qxZ5r)B-q?R;XZyr6v{eNoR0Jy8p%R#qswpln1XzlNI>gfabz2y}eC+6R3`{M|d zCCYPX^8-&3m4PBul3RiTCnj0S)sLe#+o=?orhWe)1GcR{YlhQtuS^b48LxC>I za+Kbx+$uJRd-(P9_uU6Y4%o1<*5bLO>kGO`w_2Zh3joq_V*56NP_#7$(S4U*a+oFF z;$P|_sSmuIj!%_=I5uDBp#l8WXYEv;X%tI7SG>6Y>p8ACb1r+Nn0=5!O^Mx+u@$8i zGbC2_1#K{kBYy}@@b1$*6#!u>YM5n I9;Jr;4_)|6(f|Me literal 0 HcmV?d00001 diff --git a/gui/resources/icons/home-circle.png b/gui/resources/icons/home-circle.png new file mode 100644 index 0000000000000000000000000000000000000000..4432e585ab3c40d9d7e6f12121b375ebab500171 GIT binary patch literal 5502 zcmeHKc~Dc=8b1Mo5`pGXTwalKO~)yfW>3f>!AL+B2_n*>@@lzBE+Lw&$%TYPh?XE~ zD~L;rMa0&&TDo9ug;uJOrPNx%*47;XX)D$RthL}{d*_DLsWWe!_xhhVlaud!%kO;O z?|kP>?#B4INH5A$6aau%bX0f(03;}qz*Kkm^Doo>RQTh_N?eX7pccevGNfv>7=mXS zF$A+}pwW6!7oY51k9hXCJeQGQThSrJu^;qRolG8Uhi<3w^75KFr&qO1xh#Ium#5pg zxVh`}+xE(7^-@V`{F3sDprSp^k(H!-n>gm)X1%& zOV2e;o%c+X(DNx0zuf-C`HZ!7SB&3L4_hrDoR_`JCOC6w`S6anr947erumMb$tNR z>>am>k#KdmBy97nC${w8xqYScw!ecvZ&PY|BS~I;3g^sGnJdG(rlX$gBbkflHgbLq zXOr9Rq!)qYZpHH_hcEAWXUVB#3YA*exe2}4;Mc%?>+o^wo;Q%w}Bkg^uVuhuwTiK*32glXzF^2w1uarNx{gIWt`DxPNB}Zd=^0r>v zN&l3t6UDJ7cC6=p5k|5uc*pQ9$+cQ)J$2)w&x_7XL1ZtztGB%>OR0^za3i$)_Vt^$ z+PEJL<$}#&rmBh`=Sg7CSv9b?mdj(sN`sDpstgK@VbvL7(*Y2&z-mO5YcL#9U}}wC zLhC+qjD~1b5?T^p&XOBtSehm(%Y-e2H654WkJR&ogFoeh8Fyp+gV4Ia80LR=VE&3;{8M5ssOaCXEr-81x8%i7E`~ zxP(T7c4RC+ol!0yhu51&S%7>nt*DX7X0Vt#9dmMo8IQ<-AfpLAG{T$+k0>(%GaJ%P zN-QD+)8o%fhEOTT zbd`v!pz}CzPlQ5YFg;a-@`6=7g^0sPCqYH)%{Z!8VgwWfXJ{af5)Bq8QZbZ{iP%ay zPsCP12tJ3dQn5um0Y}LbawbD8F==2|qT0z>5l|`!#X?#9V37i&rv{?}I!^%c6e1y? z&QS()IhY_=$mRz-vr#F4;1mWU^@zD|*hrycA#A{JJ6$VIX zu^N54b;6LS(P7JQlwgxB;E4DWhM;84W>kcK`WsVDIrAUxLFR5lM2Pra1_TND2u}rvsq#eJCV&5v)N)k zi_Q{=S(E$?DotwUfAb~|4-zu6uc__rFa-;+^ znt`dDc|xoalQIp}t1)#b`vRP0$1&@|TOzEOb_npQGs(E4`0OX+P@P&!ii?>>r>Mx6_5y$6r@cmfr zEr9f?M(wqczVYV+7ab=H*D{kkh28gDAjV%FJwIfhc5T!eLx;3xF;YgVXAqj!J|x;qtKQ2$U0V@<647 zj!2L2Y0|!>F5kOQbGJ)BBf<&w@D*xyZmZ9%I)hbmQt#o}A^5CZQ|(sJjzqb|sH>E*uND-Q18(Bl`VJ}2RR0^Cnj z7A65fVbA=gtM@Me&my_Qz5OgTSG_W1aU0?{OYIlB40<*0X$`XZh1tr?cXD)~pk95D zR5RV}>(ZGm7u{2koWm?Kf)wQ}il8zLc{Og+Z5_R{ z>-2eDXC*R2=-E;aKU+^W1FfE6yVO>k9opgIFlNWCd8vfrh|gYy4n_JDT=-~K`Aotq z_o%C*Cu_?p(uc-^vp1xxbG4xESgZM-cDk*n-kThsJZx_>|LJeD1m`fT8e=ob)ZCUU zLBRd=KLbH!>2dQ63UIv^d)9bw?gzkg*P(-?6i3-s7e|UHh+I{FWb?YZQdqc8)1KBH zZybQzq)u~nv+qK`eU&xw&zasbFGXs5N?p|Ke(-R3Io9Bgw3!Jxw0-?kF0a&@@F6;tf;%<_Q_;0LN=NatNrc5BZAX!ub- z+(dD#fx)&7%!U;Mr{Ow3R1bHOQ>H=Jn!(D+g00WJ!p+#9O$Hx8wd0n-6?A+u!$t>J z{cJvtTiw$^{;`$dFeo&D7*KsI2~dYt!?mbGH?&WF+*{PbRN7q%XV`qCeVybAH|mg; z6iCV+zSj2~$k+9I9ifBjyc)0_)CDlXTw71mG^qzNaK|OyWolmS|DgT{GC+}f6nh_q zNVNlp?hc(=8v#{dF49K~P>LX=3Ek*)Oc#OtG3tjAlG8dN*$Ewn^iXUGbEek1APJPZ kkAbij$)61#^0Y4)BzL&?9-x0)FCxs*5pm%kho!9l57%_%V*mgE literal 0 HcmV?d00001 diff --git a/gui/resources/icons/power-plug.png b/gui/resources/icons/power-plug.png new file mode 100644 index 0000000000000000000000000000000000000000..56a4983e93e903a7e7036410d7e8e1c3e40ddef5 GIT binary patch literal 4620 zcmY*dc|26>|NopbgP9QqQ5R{lHzE-wsY#T5-zr;+sO++Dhub1V#f@Z3_PykiZ6@Wm zpj?tt^GXcYY)CHa)HZC2vK30Py~!qj|*K-)=0mrEq*?>q~l*UZ2^WGg&WaB;4(UZO8Ys zC$#VU$Btd*D-VOYg4mr;l3|ZcO3fSl$ZmL<0!ly&-Sj*&26l8wU~NL2_!<@QX& zO@|+yr1!~e-4}ZSW6wa%9qLd#Bd|ry_eq`FWr;W0M+7Jkp%Qz+3?Z@+u=4@|``qqQ zKQ%NIOF|}>>`XQqK_WxM8O6;4&K8WO2Y-U|*w#*yaAA`Fqe+`n1Wa|+Us-@q42Z(} zdXd=)xw`Wmb=1a_=_p)c_imAY^w0IKV^$P4sNEO-eX{RC^`aa*6f=F_e-x@L{#V~+ z5A4-D?Lwuo1qu*2pf4}*RP&rUvkd(VjPs@lm68hxB{w@jA}zN06j>fYDK<@f68ff3 zFNh(`90C0+q#`Q}tV>n>vQW3p6zF*pal<%#jssA?L-+9ZFe2 z#*jK`kl`3h4O|iol0(QfVF8crwPUZIdOE>_FzdDS%T6E%YEBf?aIWGogE2Si?hLe; zw7@~TB)R;7S5#?u>Jv&DWrGm2jG0}xNw89ilQnqu1w?sc>uxUQdFU5=bc}SiSsZj5 zKMtNxlW~^&Xmd;VIT{0ZAQ|o9!|Zu>^ak@E2b1`LRE!$;0;~5u>eW0v7LkXi1;DWW zUmE5p?T9(b428&Twtv>*1q!X46t_p}!uMA;s|1_6(A0cWRwNS{IEq*B3?q1P)RGgR z^`7h$YlOJ0v2kSuT9B8zBu|NQ9(|9Qm7?-cQB@4I@^+RYmxn_XF3v4==ItuuL@1Pj zG;#-*@$V6nw}Z;@`dUXl! zLS&duF3^+!^K)|Rn?yu_n_QrjsAjT?qnzIz!{s2K?714<6Yn6r4jz(T<&O%4GXhsj za^|fS@tA+1JjG-~?k(xmVhoSPK7Py|`EyT_%j(o2wtxSJ+$$aJ@gHQq#5~uY%N#K4 z*j%x=XHHBAX_dJ6GjrIFF+AtT6Vt)QdVRWs>lS^jUby&e0#Q>E@R~jR8oi)5?9*I{@SyDV`g@vP8Yv z!HgSEi`Vas{)N03ch={K9PCZ8y(;t@x{&y)LIt$uf5Y$gH=!N0Ht7tL7w|qpWm&IlYaxcsMFh z*`oTT-;IB5xj{!q;w&+8kp%9z$(5FV{IVi;3f(ioQ@EZgVkVn%esvu;c?#Y+ zOWN-oH-P=#=HB9?(`$fThuSR+HKVVW5{L4eHP)6(_f@ZpFkIm<=ZR;uwl<|FD|iLt z@=85BcBUR2;$-^#yc0hjQ&|x5ZN>@uVbTZQEgH@ZPk5v*zq$k8N1i*uL3Ub>ANXGTZrX%+*i6Qu3p=na+Ov|bF|pyNik_8& zXkV~c`6~YE;UHEW;*M*ShTwFwc#ZI%IDbVg$p$SlEVHeC>_`n;z8Cs=JH2xLZO#e@ zV_v*F_duy0Jq13xPMzAfdpWJIb}a1l()e|%htRS0p5OzM=OK*K;%~3Vc!oi^J&EbZ zs**)&&%0$NqetAG4RMV*=x19Zc0a<6u0I`c`sN?w8K{)hO2bf)NdGxAc~*HZkv_d_ z(PytE9HYwFV!O?turPSNF5v016oe6z>CT_lX;`-1-EPhG@X{BfZEW?5KSw%L%d`Qy zCl=QqzU?V*lVw{YFu6K9C?KECMz;tdHxF0V-FE9=bU8dPw=B*B-PdCGP6xpuRj(bT z#8Sq*)pfdHebfzf5K*`t^KW){zhF?)4}0O8$5q7D#a)+OAw4#s>~aYnCU-+=5AWU3 z#5Co&snDm3@n@Ja&ZLqFOImF9zE?w z&DXGO+&LEB)@W~Ftq4Wa2FW41L5vGidJ|{xSW;r*yaDx6uIMf5gnvp~V{{s5yj@G) z;a#tHfhR%UZZqJ_49{DI7Qy_I_6&4Aj3`idwm*WvZu#0_MHX>jKc|G!i2i#pf&yd57N3`8lt+wq=?Cp_C^ zHnf<*lV4^>-Qy0Vyfiso=HKXB#M9!(T0?(6Icvj1P>^w(@)FP51mW_pJBC&6JkZ67 zDl}VG{fTSjbZR9V+Kk^vx)Dm6_R%Su%wigW$N7eFwSPUXRjAO|Q|}i~EZjuE$mGul z|3&h^&Xs@vz1!@ZsE0)J(tuUv&)Lwi2{3#)5as_{&8Bn^>AkV(smUi?cJyu@INGWD zsd|I>c3!Bx5dHAs6OIpp6W)P~+_WCE>$n3V;T57=+fEu)KqJr258fs_;rmU~xWSSS zcQ+IeKZI62ej9O45DI^bx67k!UGBFBSc2M?p4@EHjwLZ;V@D4CRZ^waq=X8T;S^jED zk)zFtn9}@>u;NG#{d454>s5_SI}PF0g+KO~ZscC*5HDpQOX*u3sX2(oG<4~>zc^5= znAn{t4XSeD$Eg3=`furg>aQFif~S(!rX&XL%R34&Dn0G#8Gklf^pD; zDd9N@5S)MU#nKI!CMl?DJ}!e-Q_8e(i@T{se-56OZr5e`3&){IY9pbO!c!U5Fha&_Q1D47Ut^fdx7G+(P)9?pdN>YC!hairY6VI8MbcE6A|6Rt__#ywy$ahu#4gpB!co^_G zW^eGG{n=^h(QGaB^OKgk-$)?K>E6>cD$$y>J#m{=M*qqY^+U-jh{q?5XB344q};27 zzcc$+o{*cyg|ywM{lf}z|4Cs` z?bl$oHRxGu_vDrWO&btSKdK$>WE^?;Uv{#SAAt1}sO9d2K7J#eFF zfJoE)XNYoz;hFEeHe_<=gf{dnD`<`c_~n{hVXSp!FFGFV6=+lk_U*3KnhMsnR~be~ zZI6R{+^M#eW44|=AZ}~vvdj%ed}zj^m40`)I*L*{?qwXnJBJ>faj)biz}d#Z%2E=N zY#(~JTAUAh@8sJUbD?|bZ??{HNWzkGdvzv>)w`G|6sZTBB6Iw8dnZK~Fq^l$D_T+;Y?N(g4l0oEgUor&LN6l7 zevO;ZgN0GO>LLQxcUQDJm8WMY&cy&`=dX@jXKgd8&&B(wBCV2#w#dpbg`sIBCu7t` zI}L_rzjWLrEwIzh@)8qyfp~xTkp#*(YXvC7$-d1|3l?1RMPTLNv8f>7cDe~=Zf`>W ze1kBm>ql0JaJa52k%%zMb~44WcO??dQ83wMo(945jeeH6xF9_C?(R4^WK{N1zldX% zv6H(|)zMdux(AUeR|CB>o*s3hc#7l=^OUs-hv+0)n8KB?XdTEZPktBi9>{$Wf3J#x%bZ_r zO;P!KU|K&Td5w>nF`QZ4(_CqK?u%~9HZqnS+rD*?+0Jopr;=JSjV(`gni2$}Y2*w`2 zUF=v)Ax#xtxC$ucqSLHD-|1vUF#*CuKw7)0hmOut|Cx&wpn%A}>-ox5GWVNMJ}D4# zifNMAJgKz6*YP6Ovx^g@_-?6rZ0}B=Q}ZP@G~&UDX^Nbz7?PO88<$TMefkUaU63Py z+9TT*k@yFwl{8&Tqt!q9%8-hA#tGyRKg}R$#IjhpF5p;|!XxwyXczJ7Jwz`EL~=r( zXghbd$CF=PS8W_aTmx(SU4AJRm_w??fnirct8rjFpXy#7#oxRZYIvun-O>aiTj9z?Fd@aK6EISUQ8%8L5N|Q)< z98LfBJ!OH(0zjA*N_sN`uP^5J#Hz?55L@~1hF+>}t&S{$y;piUkjJ>fItIDoUz8Pc)vdSc-hXGGvX0K#v%5#^XM|o6n(E4j$WD-9FqlIs=M}Xv z7@}VIbDm^BJYjXstA+n-_Se1Sscqqdb#-^KwZCeE_4ISK!P@xR+hQ=jpPV#}55M6f z*_@)5AS6hN8_$kasd*J6L!#?YWEkn@ier5_zg_!vGJ^$svFDSc(sj>iAyxMM%@bh) zewMToGb0<=r2U3(^=333d)-$SuRncY;ZQ|9{h--jq+0QG5V02Z3VqdxV7?ut4&7;@ zbCTqa1KvTe{lA<%L7sBut(D(eRf28L5bY)f)kzb&=tM`8&>+%Zu5TWGY_>>JJN0Ac z*}fg&YQET83F%i|u89$uSUt5yyz z@gaRM8S=A}KjRqpJ`$2fl_ox?u|s2tYD1T6HQsU2sGOE&OXHgkYm8M*kP5ak@lLc# ztWA8|LABT@Uv+DeQJ*vSoTM6qfpF?VRc#CBICryANv7w|HZwYI9M@abJh4cjV`aog z2(5)Ql@6Uf`V5zSskJ+}y+vkhL&?2uqEMc>g%I}vTNV67X6mj#O-;^`>Ga!E}StKi~pgB9Wt;^E^~^0oICV38)nO1fLyifb#L`#lBxON!-+ zr>CnpFRzb}508%^kBhqL(#^=%H7`8 z)854yi{`Yjbn)_(Vqt;z*gyMoa#d6NXL@Ik-&_EG@cLS~^78ZW@j5y2{`(6LPbF`d zi*~@9O1#6;F<}6|c=z8z&g*0ju)= zk0q5=)HMJ30s}y#HhLAKLMQVU(Jh zxT1@d7uueRq7(~SU)4v2*AyD=_Mnv(SO2{$G?g_>B`j)bVQnQW$jxVCV+&JR3UQ0_*;sRn@rw%Z z30qm8738zVPi1W-e$K_+$pXY_?_^E-t63BE=%W!}p&jnpZ76ZQ%nc z7FBy^FW>*X(6x86(eboE+~gM#5EB;S7vvKW7D0dhGf3aY-2*fc&B@QlBe+Km5{ozx z1B|smdI}TZzW`dq72ItsJYC#%U0kk8v7jws(Uuf2a> zwa1$h7K=9uaSN+G5G+)ANT*sFy7w;^CF+|hhjhQE0R z`~Cm(zu&U>|8of}_P>k#ulW04cKw%K|0@psuLl2DyZ+0r{}l)RSA+knUH_l4i|jw) zl#Mf>ARh>px`%$OK%lkX@}jaLW*7Z0qb@HVo{+kpH}t?@cut`|1im>k-th2%r;3`= zf$wBA)FkxsY>ng?3>KrJD5vZDY38%v!`{hMo}U_Wr!rc{UO#%oLU)9cvI&c=#PDRW z6LS6(BhU?_idRu(&G$HMw;;&I7@HwT%FoZ~Hr<>-+jI#TD`*wPz2QYFT> zc4&jXhBRo6H=D0djp!P#hs&%?+2tzEetLe2<&k=-cvptp^?dV&;NBtw-ow&sU-EVG z)PJd$Fr(Ea)Sxhyj~I<_$x4n;PPngWkStf>7BLliH+qSR&Q<| zDhuA;So?CFV(dDF^zF#VNU7b`15AOGHQsFFV{+G{SQC^Pcec~IKNlN5y)shkC*<@= zDCw-z32vijw}IHeP9~QR8P^txF=WCR>br;N&;B(~Y)DmPP#W{xaiBS1uC5|a)aBz7 zW}cJ&;c?y8W8<-ne=9Q{S7r+GWbo?Ma_iMnZsKoYpyD=uaVINAoD=58y(0*fKZL1* zu`=pB=Jk>zep9KJo;&El7Hm69qj-*=$zTxl>uwaqvpR z7|nbFY^wD7MEpd#&D$}TrgfJF7A*C7 z&5S@cbAM=Qxzo^#35mH{s*4ZKL^MUw&aDp+5FH@RYjr9tz9T~05w$Wqq+H`Y`zUC0 zr7Kh6)|IYD;T{JO@l93(k4@WXxbz#h))%dIw${tw-KAPzw}bUpAG)4zQ=k}TnjNZ$ zrP7e(R~Mho{ytpg;W_h>|FGmQ*(rJqwF72h2quqz`+z%2%;Q^QikOFG+uhS{jatge zi^r5nZkO+|D6QRS;J*GM)?w-Clwme`yx>z*2 zPDHGr{%~#Wl-oiZTMOtELtd)4QQ%_o=p9fDi30=~nnZDaj{U_d^(&to1KK?*80&7x znl7)+7I*H6Q#8a7iyQfFY?deeh@3X z^4sof_{s6{bB&J(%>m#gR@nH(Rh5n;VMmQ?KYMeEG}$j`>`u3R?<*QeGgoHx%YI6Q z*tTm0#?ZEp{8%G7Z!INn?Js%H=}&6xzfQACuGM@Wd}_Be-NWX;^!><5aZlF=gdkb= z7lhjzKT2ERh1JH=v|GD<9{Ik)%%v_;x0OLV<4u)shb*5=G1P9r1BUT1J1v{OH;;p9(;p)21 zOV3K(`efb1Y*goog!c^HbB8|n6|{?1C30FGRq5@ep80ozosH8{0p!H)t*0nO?!2)%u3n4zu1u93)kz5E6B6_lEEy0O_F~#+K~V9%h1Y+ zyBEhETE)1r62a{G_Vgmod$TX~XecLBeIg|$d-=>R@7(Ur_V{aZ-aDWN=fD-Db|KB_ zws@Z;3_=bR$W>3pDI3XMGp@WG%n*Dfo=(8}d(@*b>&>7ostdR*1brK!8B!pm+e~nkUPKD zsDdnPBGqRku{b~f7b}yju%F#g>>J6<{qFBKd<bW932531BJv~xuYXJ|%YFrm8796aPDg(nk{o489MwWR3|7S;}Li7>Ky zsXcRBm$p_U+}`oGG@kSs{(I}!8wwi7jQq;yN3d^(7YRwmNI0Bx@JnK8rYPv>o=$P!VU+U!%kJI7-?L{w0@E3rmXTo! z+E`NQNEXr9+tPWZgvX!9%F1P$g$GRHP3rugTOQhD)Hh|ule_#o6>f{~McBBwxM=ox zq1!8wZxI;Kc*t!k)rYmhX(;#4_T5T`8kLi!qX8^bAKBZZ9?^kA5rd1zng{LDQ&S{- z9{-tKr(sZvFYuH_^Vu%VubDmxFMxtd>t8nW2?=Hq1VsD)GI(rKaEZv?Vudiyf^`%l=1MYB zcdGf$aVh`_PZs$!ozg(BG(GP=$0>rEje~|Sv9jTHjq|2Suubj8MhemlcUU%3I8K0y zHuRw2`uJpZ%>T1y=&E^jra>lU(|saA8lqIUm>m3~3sx7>$VHsb*gv37F&Pe@R>E zN`QT1a$$d5x)IZmz)cD!M&!kB?q_+8*37?4Q#2aA*eN3e&Urjq3(Er5*(wTJzc6~_ z{oyFkUuEQI^D=MyA^qeq+TA(e_ASw_8L&mI3YpS72?xyaZ=}Mq7WRIMPw9jm?se)b z99g&lMzHdx=ErC(95c+n92cqYq<$MvLCZZ3oqG=KuHV=($88r5X-aa+oQbWOtCu(-bmhzNp?$4* zN|>W5oKEDWxL!P1Vo*;aiBM5$fZHbVc_xX!NdFTl(&YK4EZ!w zO{LNQ7${wB=0s{L%USI?d(1A)%Ug2so!|vwYK#XJUSe35u|@9W@q~sg8+1A(GA!If z?k{fN@?i%$seqL`;QCtVOOWI-1)@crRc^aP6iSAMiQ0$oloTSZy?x}=U67bgu^e~- za1r2gk$V7acmMaW$fuiWv?4JlPIgLf7XNt`lPcb_l*rpsQZbSQs435KZ^}sP67jAI zm(h=vZdreZKK|^l2sq3NWO+e&0xP4)hkyl2ym^TJo&(aoP+d=%@pq!jy*lI12h4N|ncoKPC&Io7ym=zj zQ*55TWE^0KPwuTVdz1AVztwMCtzWI10E4YHB;OMt_)Tx#>N;>#pR2v1axNxt_U*}uE^zS4 zTAPzk<6GW_;(sk`xzKB8)qaoT!rlsnX8x1U*ZN9>bAFF;==-!f)^F^h_H(4pxa>Ds z<@%|WI~zZ&HdkhUf5(}0vP)q9p%c{UK`VdsAkv%7D`v4nf|rx)AL>1Sba8b^Z_cpu z@*4amplfQF{EdzUI<@SDF)P1pCg zj8m~Sy-O7Q!(X)^ZzI*@vueMG^pW@2HBYp~|9M>}`6JpFfbu{82CwBi7QyyM4eF%r zf>j^#$^H5K(dmohuMRNj{@(0!>*(@q2vI!aEOsyAFmwpwr_a*xGG{QPwn_OHUt zsgY_gNB1B7CI7_E5IDx9O87JbB0hTm{(bZHqS{)?v(CeG1}0u5yx2GzyH#6lFbqeewKiS=fAyPcbh3|X)bGFq;FyHP&e2d}kYH1G4-UdOhqLPx*)!|BhIC1JO)p$GAZvLz(gBS|^-Nb9QB2WP%{K%)X zCo5!k$Db60K;~7?5imp1^}=ZgonZ_CGi6cw1p=b%|M_hN(xIL>Zb>k7T6Q6`wf{@O*mVR5N7` z)6yS0A@s}W;eIsH0(j5J(-$8!0(i56z_P1wdA_T*>Bwt>mFWT%jYdHYjp(yZpVp*~ zgN}uZC!1}&4LO&)1(T6ixqdS`ucs-@O%(Gv0j{FlFAUt!Go z?8nCE+qp^=dvevbgF$~nwe^!vAjebYPXLZsG}6c5gZojk z6%-|Zdza`o_@rnbk(K zZ;)OeXxI_XRZTo;kk82FlE?e5>kgsS@EVr|^IlxUUEp%Jk9 zQwySS6dGgcv{zQiZvsv}J@qb;s#9h+P!fXAuBWSmgkglP+Z8(o#YWFL2MhJMa*|Re z=&7)8BIik$L(~J#?mtLJNo(e7k>ZalFbl|cV+#Bwx6njueg_4C%(sN2s+V!3`xbid ztMLz&Dzit#18Wa$5uy zTQgWGBjDL1Boh&)Llw=t+YP$|j&N+kx}qa~0d6MVgEkNvV@@a43i|vUo?zNtYhmZ+ zj+Rs4p(UB9jF}xm!QbR_IDcd_JIpU0dmjrKndX<*h_a9oU1TSDYWx0z^vXvoq!R-s zyH3|+W2&$II_=iZk>@+h%vL!`AIjdwHPciN%{o5c)>|0c7D}-6h5qii#)` z7ms8tx$!-#>sgal*fj=^w$llXn{y56SNn?-wblC9S&3Vp1p3R@6_g9yt$ESXXJCHP zF2(KUz`@84NKD1+)>HGzqg$-|&CjZ0<80D{w2!ZT_DLULFE4yRg1LR$cZPyO z>CJUq6SqigB*>SU-}C#28v=)Rvuxfzh+x|Ot{efFjBO*;!?xI{UY9*i=>X%fXz*&y z=;_nfAe+VkQ2esGH^3gJfm=BIB`= zXXskPa^4y=K^pF!18iKt4l)5V!z+e?n;VXnpPt!AT;!?x3(`f8&MQP3J-hNZn$&W# z{eIWtQqS1?eIDV2$In`~#^vYdYZkVV-C_$p`1YG!etLlIh2g-(_YmV7G+sNv_+1#| z@DfsR@eCr)CcQ2n&eO#)lYgr}(kZ#9+WXja$dMkYNU9lcX9^>NLI>&iut34&YH({P zCR8mp|WK8wlApD0Q>G*CrxMu=!~^i$S4QKEcO| z@|GRSk{D_HNwB-5v3pPSd&YHY`&Ku$R8MUb+eRdx3zm@H%+|)nowG~vQ{Vb>K!%bS zJfOK#cVkP|?0icTN`*GlyQo6GSmW=Tk{)onvHpY@qERMjs(CH&t?f10q+Y3CUqI}S z@_NC5x3Xj&NF6JQbvo`+x2zxd!+7)pgX>FzNTG?UQ?Zf)cq&#KB*c%__>d5He~GRl zN5aN~f+HHzS|`|it}>x)=HI83S#iAuS?3k5*#j;gqitAILVDG-Qj$(ayb|B31H7fK zQf8B+Qx=jqGXlC$ITp!v6g01o8F8>Cc66?p4JzjgYVV&fjcA$4{nWH%@$>6yoQqShx& zJHGD>>N8w6XX25DBc~V~vcJCjX{U7Z)+>r&N?H@&GQNz+5feTU$j9MNqZ1cD`N|)P zBl=d)&-J)!VS!G<`>K56{*}qC#ZHYgm!4ohRY*xgqTOX5q27l~orFrjUBqCen(Vn! z62cv`9{RPvUX$Zhu3Pqg-(yn=x7p_dtPi-2k9j#5mdop1EnZ`{?M$0xqU+98B*r9G zK$=^$)I9y6RDk!rd-vG8WuFUQ{m6IZ2!bUOu_0UISKNB}<*${xtxqPj08qLs2{@~6 zr+hS!iop7#M({%XL~QU<)-U?Ip@JOvVVM$1qv;8x**`WySp>D z%lKn-SC;MM z{_8C!R+Od6Npe_x52=JNI|~U7f4NkCy;=GF?yJ|K4Nn87?>>Z_p}OMps!23is^7Q7 z2q>&5Z4)_=6YZ!&cC-l;a;)E_@I6|Mq_@;u23ET|SU!Q$b$Kb?)tXqAW3}u0;JR4- zAob;|t=5i`aO^CjYt14@(P{cj`b7@kmxdrv^GHZR2Ed3~a@bF{eyLe11HYxBr}U(d zh31kGW7nB;v5X~5e;-A0dt@&l#N>x(os7nM<0YD#5B=CDuNC04y;&Bx?ygaw65(?h z@)}-0`cEszFdUziNIP>dvOi_OJR0#7+*S@-CWOp!N%%z9+N=+;T$e)+?mHd7<&8AO z`ws(&Fi%<__)M;JYut@AGelK?i1&k zHBaXr#9#t*Aa%wHM|ykZud$2aa$5GID{GaI?_WM${{ThrfjK;;)qeqgqDpregpIYM z)Cuf0F?jL$1w{N1$k(TtvqxsaiKxL9ZZYl`i3$LQIGgoP?Ky|uX zE+0EtUb^=M6Zf{${#54eAc;^;iEj_Bj`rkf#2U4wzRqBW9Gdu9myxR*?-Lf(p-k5& z0LgIcL8|yieo?1x$jJ@WFZUqL_hdtqb=yJSr45esb71Zy*Tc?U`4alQza)95QHF0F z(x9JWq&L1dn(r*oR)p&OItT293_aiWHzwa(`!J!;9`aepyLa8q3CpCr;cGcQl?&W944b?c3}}2r!sw{XF$lKn-&tyPFe` z4j{P^2CG&yA{c;xtsjmBN(%0AU(+ zG^8fW1<0D+S}LMtcGo-8w7Edinu~zIkB&D-Uu5W-;j_@Bbgr6w@UcFqM%y$y@HQhR zv=~fG+r6LOW1rlJqxYrwwVl<5Qezrsjr@Xg_|Fg;4tQ+3m|ayGlu1V`R%Mvwb;CQ ze2m1;@!dmyd3N~=NAv^$6<8OYWdqg~PF}PcYmBJ(fwlY~Zn+C~5}Y!y%VH5%antmy zsJPG1nG_R6)%wA_?(S|W8*!FLddXC;m*_F)^YEt_jKgg&$H&Q?LNrOb8YszqEvwfB!Ba1eW)<6-$m5?IoZ?my== zeOHO!Z^3$00dxjHFSp-vpFvAmNdxo2g^u*JK$c?=%N$^E4fQCOSL5g6=2q)SZ20cD zE0~uy%zyLnN!%t0=6n%o6RQiT(-rqif);T;F;0Gp!=62A9j!_)Cz5&f%*@glB!1Qh z?M(eV9^i5>AtCuW24k*2Z9PB*0j1zrv z*W8=!f+d7f9j#=-P1#Tt7yI^NNM~mbKTbtvds>6)mXHIMWT73MvNs6r!d}Xpx53p_ z=)Fy7hPqLZ1_4I+8#>4r-n45F%Z*g76mp?rVMpse$Skh_OfT_HjJbWK?;CNC3nt^- zXa6515#Mexv5+h@KjgQ%k)f&ceNQa)yYbX$NN&(v!01JW;Pa>C;%H-BhNR7cmi4B_ z32ppk6=z0)T<7im7=c%_qZ3gBW_}!yDEk^{5-OQ#+mJUB;PFEQ6Gw`t?{viHFzi&& z)6L`a{L}OTe|iC+W+uwS)k~eUu&^-k(QP$nJ7hJjZ1tRr4{iZ87^;A^!9wTwuW2>NB7$vUT}tNT~Wuy;W8uHP^k zEU%)XGS;Qc6s@#4MRGkw`0|$wU?7bm0lx^lwy@apNb)q0$ARjpX#qd0y0-5KhRdlZ zE%Y*tqi7uPx&)9m0XfFf4FsX8VvtCu0-$9gxzqaQHI{9A#!e;*0!}n=E|NM?^$#1m zA%ze>{&Q1L$YB^JOyNltZ-mOv&#Ng@l9@a#a99{}^&G*=s|a)=f{Ta#42gR;imf#Y zXdD*6NhmG67@BL{Fu#Q;Q-SJ(?W2o%hk^G8=|tIg)>>r9SUMBws3WeznlBvIyAddz zlfq!Fg4f@gvvNs)`isQ9T~H@25-P`)^TwI12{z;Ub3txM5A08!yL0}m^s@qND~D-~ zXC$-2O;Oq@j`%skgc9Sr)h6&2t=zrK8Ic;VUF`7S=}<`1q{8Xt$Q*I%XY@R`Y%?sqzTm&JK(TvmGqx61ExNvmWwS+Bw;BZzTNOH^PRV}vkXtV zT9}`Ie#Cq8q~GemY`+TzOAl3l+S0m(yVzDzpV6QS%7r^Ba@X4Oe#`zU?Jn*rMjBm@SP8uXpt-Ado35;O}mqqKex>CbTRYgEqF)47$tAHKk#nU4h?cNoOFX&ErB zl|+X{vGccNw&Wcc%)-6HTnE4yx6x5r)&8<8Kx|$*Y2%o34 zHo1Q8RwFb~rCg(N(6+#BPa+R>RcyYIic0ycj0vUnuvM%S>kS4gfw*zix`rfU^m?!^ zz^7azUD^#NQbT_I4$AD5U4BJ4HOc_)`LN*fjz2Qia_`%Z^|Sj_&TP%C{b|B@}D!t=YiSIr!Yspd6BaU7IuYud$~dS6g0zR-vvzk++hW z9n85Sn=MFA4^X0}IhKi+MBp1lQOCmM-;X}@&%?V^ZUkYkj&1-2w`J54Pe3Zc=jVF? zs%s1uxKwGpDO^Pw0hFN3|LctA z1Hc5f#H{-YCrX1CCFC^6lTP;kRlmDEC$VT7!PaYNjWd1vM*};=vh|7-QFs@2Vzu>D zEZ|!nY3JpRgLva~hjxhO#+Lgh9rV*ZcyB|Omc*QGguU#8hyHdkctuG32g^nm8szD3 zE#=90jl3t+$bb5>SK{fO4554OXwwg$+ia z+7-ldFu!xyTS^#m7(e6*fKO{EtXX}CdmAnn%|7~shY_;4Q^N-rZio}Lx3}M$X0Sw1 zLIEm#R0#I(lZ&?hG?u>x`Gr&u8r*Ae8fmp4u&`Esyb)OZ`toYN+k8idviBiCY%`MM z)`vCUsMdKTAOkogXxE{t9^{>b%|Bv0nm9@7b;!NQ$5{|*L?)EwBGx^&-d%P$m&JOk z35ZW|qrq)`)1TYI`v&^J2T4iV6=rn+^loAW8mTjGKJ=fWK-{3;Pr;ZX`E%_>72 z%1w2BO&SpyJx3b$><75m+O37RVXYX!P$6KuInwUjl1pVQVmlQLw8Zum%ROpt5K4#- z_48@u_q6s(G@z3xvA^2uhvNE8FW3v5t<*I>bKWoX@)xfc_*n1(p#rmPGV2kP=WDo1 ztE5MK#}CP|_pVz&8LI24fs5QkRa%{Y%df9*_7T8&KHtKW?i;dQ15>31Z`gyaS9SK* zJb8$g@g8!jAief1S=_6Tk{UN`i!*(Qhg%K+E-c?v3x{D#Hc|rQij6Be5?}1ET6U7D z>Z@@@NW3*0>NS5crTogro-gWed2t6aY2rQolp6V~Xp=}90tEojA}U5quq55>Gsc-6 zDl{}SZ9~ot3Y7bPUOT`P6HPC|*@uxmS2>^TDN&}7_p#h2YVqo!`R@%$s&!F&@C(ZK zs@^i=s&a8>>-;^VpzTAnvmb;~^s2X}5>JCCm>k))XA9#`sc|V^_2egpnLXu5hSU$&|Pj-AVX#!{GTTcN$L-Qik*o|wb?%CxwAxnExirm? zLpmOB&M<=$F56JFg6<-YuXFOGgjWpUBk)A|{At?pJiK*FcR|yZ zJc>j%vmiJ|@;HGI&85oA_1KRtVB6Hd3^U;MN%RhE6>3cLCB~$L;o`T}GDmiuTH~10 z)Z>p`OgIw>W#~;ia?JS}luKet7geF0shHdD@p%LpxQ^n@HYyz7GHV_3slE3Q{DXX@ z9_5S(0DasuzU5q2q(8!w)ju9n5t2QZPo)QLsJQ}6*VK7jjpJlS;vKYuXYS}36)N~P z4n@(Dg>Ac=?M9)dWLJH?{GvQ4;EH(<2h|hhYpvd?6M<7```kWEb{~y_2{ZA^5G0{k zh{LP>&qbf00nfa0QZ^blSmbk%N!kPy#mLmNOG*B6LmlM43~=P7GD`UT^gQ>OLTUAS?X82y$EJl0%RJj2 zJ(Towmp_V;6`w))rv8meu;ro6$wIE1=b#ZPRja5VKTR{?{(X)fYdoeG0y zEVah)T;BBbZyEpOQrAcJFzq>=lR$QDd(5MEGw%xHY_fkm7ZQ&r>Kt8oeJw$;MLjiK z?z!Z49-GztSW`!CpDwjV{%4#T4|1H{c=UAa{b5?-zW&`u7ooqrdr&uX#~s8>i=W?e z<^7I7v>^g$52;Fau5NpOYa#{p)_m{E0xvdG0d-CiSl?10eB)wOU$RMm;d@e0&6mN@ z&TVG-Iq7~_#wUdTiNiOT;CCQ>_zf5rGM>fLT<~8A@J9$2$ZHJ?kk5_ zjG5Xv)4NC{ycPd4F-XT0`pS>U^V2v~`0KR7bkOV>Zj|}>i1TtT9bW1B3i8rUK%?qD zx%S7^E5`GX77zawbVenKJtw z6^@V_rbZ&xP3_duIcZ?#QI}j#UIwGzgs3$r$1-x0U@oTz#w6jOQ#6s1tN^{){hjf- zoL=oY%|cvgv%WAX&wfwd33tdGFW8G{mx6f>SQ70QmQ7^L)E6?(F5l$ETR#l~FN9=X zWyc(JT-F>APFb0R5@;^v`NTFK=;GCJ`6vRUe)-`mujUo_>#MSS{v*Z5JK=|p3pDoF z=ZEE7Jk|tlJydrwn0i&Xei4s~zH)JQL#me3vjD_)Jlu?n*T{bhc*#DW1wT`Y_a}RK ztc|pCYF>Et??hOT4R#;WdxQD$r<(au`Jk5c+EZ{gd?`u^Txf&gJgjfuAe#E@fIoqW zcxK-7lTWn^|I|yrk`712lM1UCF;=*25D4o-C5wzXo$Psm$czkH_3g~?P8DR7$)9T` zJa~}guaJbiWWb`BgSN2i2TJA%g-jk^UX7TOKIx^z*uoQ3(EA#V^0Tr z>K{g;YL$eiFR2`~0VnP~sQr&yQF_;8o$au_u`J)3gIG4$v*%Sb8zJ?2idfry`UBUE zI4;Dva&&G-8bIEdik$WxEiuPBG{2{w^vDFwQdmKIj5MB9W+J(E5AYy4^AP&R{T8^A z4BzL@pN*g)d0jVOt&VvWxGC$l0Nh;O*_CS5=PiaPf0-Mfvb zKu%H!c5@JMyHy6bttknX!9iR&1Dy`XSxb-VUl}jk^>s~ zDov9HW~XkbQsaInDOIQ!KK@7eWFH|=;ULy7hkod(H%UCbS?8i70fkNjAr)~{~Qm_ z7^RFTF`AdbGw5FZ^h||h`V2S{;Kg2gflL(|MsCR74}!}Y^5+fE2FI+>R&u~V~Mt-_k+{Q-~(U4saoHo36duO=4$41 zNT+Ge*=6!@aS1L%lP}1U+9C2iluB=Ce#UD(gU8V9UBVRr`Jr3-aPfm#(}s0)Qwt`z zhH_N0!4gpQ3Wqk79%KYB4bbrl+xQ~b3;lJIlap;_<3Hmmf8GC`ujlH+K-%Y}^zN1i zbGFeRi+lhBP@mnKTNJd!n2F=*nXEK$apcNugew!f!GEpo+^{*4!$}>Pnx;+F%SBf3B1ZNLcRXkrJwR24Kg49&iEZA zD4hKd@Q01bLOX#x$tGv7$Y)O-6Ui%26hj^U1ES-`;XJv4ndU_6RU^asxp?D5H?pH^ zo+!cyKM^SxQ6LiM{140wO?l!z*={W`9W>HV0d+`FHt0-SyLE*(LXqXD<(fO{IUnWI z9ZcO_>B-kCdJvL^!5)Z){+2;#u?@p?JM<{id_7Beo=9ef5#v4pJ_<0b_nlV>hp6_) z9m|PTzYU!z+vA;?sL7vQ2%6Z=4~Oh-!q{T7ao*(H$GDb&D!&==O{0 ztVq$h+Qp+szLJ8jV>B6l)^GmweYB({hw0Pb_esr}ep39yJJTYXrXe!;hdIZ4!e#F}jnf3DU;?@ye)`q1~wwFATix`QJ+E^xB5Mnhk#ATvgm5tOJ9_cnKgY*`xW z@g(?_9>Vgx=E7*DOeo8P_N&$tV0S?Zn+tmIy+0GW9R}(NJ>0Uv;H>J~2h{3la6#ay z>rq8AgJd{p_47Pj3=6}od>rUC&K$w}5v1%Gj9(!%Nk*9OZVbTN%H5sK25;CjS8ukK zjZF?E1{(|U2)Nwaw|A5LSAPufYTe&0mM_snHBfLFxz$yY(DX=3fLSoPzW>nC z)zOd!Y{u=`ANnrg)sd2*)o61TfcmIQ3y1OZ1NUDJ@NM55i^t)26psqk?CQCrnt|G> z{#?DAt{>zMkY3~5TpN!K$6)p~F40FS!yOq84Mf|O-u%BQ^UGl!a}sbPstuXH?n{d^ zBi=jguF~L2KR~V;cw%6>S@IDwe%ePdnxbfwp3fe2iG$!y8GFEY^;Pv5XX@t{Fxw(0 zhQ{cw!nTbvp(O{S4cI2!E+lURkP&Kl)%|-~ggVAkwT{LCK-me*`B$bspJ_lFDTyb_ zJongcT;VKFmTd_*MIL!tRBwgG5iCio)pQaNruVD$O#>~V-U{^9kP%?WQl>>FN}+m0 zgX84eWTk=pIt?L)nxGZSo1hc;jow@iEd&W?D!V+$Nd$&{llD`aG`a3bu_)d zphDhsAMl=rP|th){y-yYv$%^1eLVpE4LvTcRLRnXw;|!(*Lu>BYBJWgum?%i2IkeiURV}5LcnG4m>TwS1m-b?5|e&@(M!90l|E=M zMPE0=*BWX_9Gt&yB7~-fqEIac`kp^_KH4A30{Cz+p#TxB zM8y=MNRr(+1IKW}w1~9^D97<+#9+_HBg%08*FvovB)|eyxkLl7?aCjIYXo+t^uUav zYH^H^!?4^sf)bN)J26<{n~gu{g@G2dB8AIdIL2#sh8V-{o;w;RmRP%|9_We$<_J6? zO|1X@P!eJ&j~szsVO7*T78WYhz5=39e}y8KYxhw9 zItk__BWyytiVxVTb9qIrP~2PkG~5xMwG_Zyrl<&hv-9>ouqQPPZkQR7WM@0q`Iq@G zJHW411qeYIavpAF8c{xB`q{9%lkyO@%W>s%^>fPegK!}ggt~PdbOrb!?6i^30#}3* zbbL%W5J}e1#tS6Xzg(i%PH+UbBfbxc5Vi0jbk~9#3A{EflFc&!uFH#T53_k+zJ8O3 zl?YQ0$VJzb2Prr;bdCPCm-x5~t*sGoB9IVb*0gg+pSV;ZJ<)mQy?lW=u6)2OKn*BO zaQKiRHwN&GmN+mPE^bXtAa48(NK+US=RB3-0eP0da5W~qM!5W&&^p<04$L-pKQx?N zgs%q#wr}#bFC%8K$cRVb(1nwExD!?N@E~UGLhk4cWTJiufjVx4jMT2uX`6&$k#C)mf8B% zs1u(?N!%w8uyPfxVhgLZ4j_Y3Q+{@Zhq!POrO^m6aYuVx$PA@NKm+I4(zB4W6M${X z-z!Di+$>PIbyz;b2zqvG0iU%^3n%;}*_Xc# zXi>k?Jbq7BOFi-n^Qn^BmA;W6i9zQOuA!P?`<(knFE|&;DwKXgKu@KgK!>`n^(|=@mb)%Tys+lD0M9#BkLZt?v zLqxq*9(K&GFVg}SRDizw`r6u-%gHCQw(7W{+IP42MyXQf<7|8YM09qK2L~qL8cKBA zsya2XUrBB;kaytw2L%c>TWL`>N`|;ZK|AonqF5y*4Wl1ke|iCw+92^jENAw1RR>l* z_`N$Pic%E&M)^*pUXi{ZlQ70rHf2Lix`;FnFIByF_fB9$>D0GbnfjjT{W(4sG%YMF zw2h27Nfs`s8RH#c;rY&yAWQHw{q+Q)M7GPxf!b6CbutfpeJS3NvZcfwX5zm9n>w7A zMh!Ps?@uvdTwkKzXz^qXH^IQXFZ#b z+mT$mzVOj17EW@}E9%?1;z@yXjg@dK#Bpn&K$9s$uv1cpgy9})fBrL~umEx3xcl1I zTWl0kt_@hx%Pr5Z(13bYtQ^8H2;~Lqr1nnWnTYGkxE^u7Q=h!f$U9qf#s|23>AJL-)_D?{;5FY`qT zn)>0Ymd6vLG+%AFKP+7J!lVJP{3+KSI$*a{l_P%vsXV}o`r-nd(o)1 z&R|Wl<80w-%hA#O2j<{@muu+f|EIDnc#QmMy4S=;Pl~(MVWQm zQE>jp?Us{O3*YDY@1A0|J`cAObR2~kipzaOTA(5=#Y+%+=jnzT>!szLzaTi}&tavC zOcsiUf)bu39XOH1%ZOw$V2Dnxx|f3_ChnwugBYFq@{Zl>);I(6AmQ!LbGulQ!=HM{ z)9!?m)A~CTVhk;olZh<)HhU5^?OG$)(jE?r*wu;HRVQqeDlbhr0cle5xtr6=(>LYkge14V892 zpu8O4WHc_6kT^z|08+__;m zHsDYz2hIhiEv&u}?b|e`RKFPnzks0nqgO_e(z@~G&NjMYmX?Q+?FWU_7}uTKwvtb^ z=&x_fhP#r0_+|ACx4-pV0=5?^&W+TC%QioA4!D3SHD9gwUd|aVkA%p#ckJVs^=>u{ z!=76C`RNFBr58gmd4EInt^}yxi2E0w6oR_!b&253zM$P%Fb?FJcem) z+b-5=aFi|@InZ)L{301SdHnrOZW`j_UeMx5LV#%<{PUj7>$%Nrvg!}u2x>?{Mx=ge z`|%)bQu3=!7xYs<7!h7^mW$JJG&iFHh_pDo599v2U{p9>Z|)smX2&D_5~I^kZKc^s z1Pb4`&5psbCIZUvdk7dl@1;#vdT3EjN9!Ih8WoO$506+rfb0x=kn6WIa&c~1=MKgK zVD>*ugb}k?uCaZBOGSd{hem{lzOk!X@qPf?o`T0nDcdj=L^58y05`wyLdXQQZb!c{ zl`{9q3v+1MW}Hv(Q(UUw>vz}S(o(huW5@+)K%oC&76HYP07h8AYFR?YaJl0!6^`LM zlzq;mlxoKNu|0F9hr>Yd&lKh0lcq|b=*XIvGOUl9Hg={$z}L2N!0&Z575c1@2rDx} zGx<_Mc+@^QeG^^xU?>H*EFQGKlGbHltDw9L z0!j7w>Bnz>SEiBxlbE%?Xo4amX#D_Gj*tmLP`k{o6Gc`4}ZwIL2WbfPz zI31~nng*HUF%mq6&n*+Nt<^o9k`mB{!A=5mrEH|0L~M+>4W_71GSPVFmL2;2p%O?! zi`gwpJWauw2KiDJeuQ7?xo74+{pGu-k)1`H*IaEKGlZ8@eiWFA6rBdaH-$dSmh$kc z6c83ZlPbH9ZH+h;D}5GbvP1f4@<$)9TZ5C8~ByH?cISq(y)|jNJCh{ z-RlbwrFiH!$fWDk70FPj3wwa8&USI~)MBnUA)HSyv-Oq2lmdLq(~a%vV*jZFR5*uk zg+-5#5{j*URjwINv`gbhZlMFWn)ejkf(IrtDk^^U#nq$4Vm_1i4VvNC6*8d53pTkK zpMp!3kv!k`!J|_uVPtix0J&5?EQ1S=ZL-k=B0b)O^o7QpCLE_U?HxAII_3gQKSjsiGpAyz>8b zalyPwid)kbiTddyXToVWV{G6g^?J z6^rk7Ea1Vb=mMO-2@M8r!*Ve;QE!K}P@zEs`Rkwt=_p=~hTSbkn=1&Q7yhSmh+T4r zVWF+;O4_<`b#E^f$Hohq1{cQ%YgA?Px_@utrHGy#>mkojcnqvzKcH3_=jM4)88#Y! zpE(LiiL!opi`%Ci`d`4S52t-=>6p)1MK?r3jL)uUI)Th+9cK&Jf!Pn&%RlPd3*GAw z1@2wAcKwECwmc(!{~73Q9X2xh){LfTIjfQu51rZ_nYPkYQ**3s#OuVWW75>|0TDQ} z&V!#bE1tsg@0663Sb>7jFw8h^Vv?lO#J29=T{-Z$vjC})KldFhiNe9pf(y*zg@GA7 z7o4xLkgVK;b+l3U&F(Ia_t)-hEDS^;Qt@=jjd4Hff)rO$q-B8GwxUsgyWDd0%V9Ia z;^%HnvW7)JS|NSW_4@o#4$bV$&LNjG5LYln#WiBnmMuEkhYlsrGCGf;>AMINquafM z`9zfd*AugO4^YE2P`Y-AP0}aEGxX(k>Y{?s@cv8P{BL5xR!CKZ^Lo4i9XHZkbt9j1 zYkWff8i*cM(^)qWi+izKcikEV+Ob`i7pyc5WLAjCOTl~#K4qN`CRk)MfY0?#6u}Jm4jF2InOyyD3&ic@Q;dVZ*W42B>$IWgij8HU<;5aPo(eKXBOHvU zq-M~$VW0JQv2DX+F5Z42kZ)9~ycZbW%Y12R(@UR!LCW|Z9z>?9F?^DT_tz-OepzVi zm>YI^yMxnP3CJP97x=x*d(fkPT*j|76 ze~V(E;@kE%VE}$lAZo0bSW3{uW*CJJiSjY2otKKHZPo{#AYmOO7hY>xqX~Qh0utaH zJR4s~%gQqUkuIdhX6R=B#5T-DpkAMnuUwZTAXZ8Iq)9xo@pFY(J z`x-TsKwsRBb#c6-c>4LdEAP`wMAP8k}cC|68o8=NKt&KU{U_w%35A z6F1Wv*u*ua_k-7@B0khyNW^O@<{);=!|)nO?q$BGxc3-}0$s>hy0Pps(52aVP?&1w zbQq;wG6wtRl8+Wg_J1hudK@PZrs7P?x9W5B6_xw&SXCOpE`GSK&TVXzZC^9V{_tUb zYfS210xsNQKJ`$v@=$N6DIcLcpu+JOqc3>$zlD0fuH!|&|Lza!d7#bQ&}h$}s$E|L zbc<1@jXw*Rub%1^TKMvFk|MKA@u18ONQh;@kidzOl9Rs26S~qLn{boDa!TdxfD^@x z!OxZrYy85ibKtLzE4ujebGVM&zZ7W+_*AMT+5jD%o&H==%6MZhvr6A9$nZkTdakkd zKW|aX;KE&O0zCyR0V08S9wJp;88M;Dt{1#;X?l>`^Vdlt@|b#_Lg~K0r;7HBfU=8c zd*l{te#i}Muw6}dBn0uwDIog!g%4uVpUQBHuZ~Z!Ip?m;RALThdZq|K;z=QowIyE@ zinCa_1_KW;%6EE(wrVuG7O%Ij(^ZUrdDJ^+_XmeY!8StEclL))Sd4@_2?C!$F~Gj8 zG8vH5+T8DfQ|*i*>f*(VQ;|utibxm7iuOnC{v~q^&Y7N0X_;6EiU+!)l-N_=?>}yj||ySS9bgtdMHmK+#KK;B|8nZ zZ$SJg5TG_g#}K|cn^9X?oaHjoo`t@v=@|zt==ssf;jg){Zeb%%$}4sGn6DPz!F+t; zurYp)>?8KU3HHtB6U%%TFVjiJ`#E^2lPyFCt|;3+Q_`X@wz&3vIL@eYINoZULilz?zSp;Yd@s`>ZOWCOU_%9!m>KozO=TRZ6 z%{rJaN}s6pb+bqEkqDRQ;*GS;!TeGetDmU$QH#F&DGfw8`Yqx)oF?io0?Il{yL+0B z;TffPMl!ayZKq2(G+!;)HMNTaK)MR9-XG67DfGQMN0m+yGNXl?b)@LOBLz8=JyQUj zt|6;}=VD+0Ix~R@62I6s$*1|MV>9M%YUIvx;N0Ti%Q_2CqHku5ebCH9naXlD_XsXI zZ)z%>Ry1!zv=T?b6*FRALZQd#=qa5e8WK^DiVv*%E_mfa@@*nQLBhN6WfX(!j|?3D zk%GtB(?_z2v z#+86*5x>1$$Ik4*vaIb5>ZlfImkV|3%#Nt}(rgaVTRQYA`Ut3aKseU<`pi8PsK0kq zPkAGJlsforkB!))fEdy3BPQY0I(0D0B!RTck$@W!Uanr&tG;phC;hn8JXv#N#y%3( zt#kXfK3-_*1`4|Bb6}N5&38?9l*a76wTwd}CP8B7aPF6&h1q!q$D)vW?|-9>a;M~o zyjlYATSrr3{z6*&=~oRn&2g>kxVn(iemcg;ta&oK1WX1=p)zFMTjC@32J)GFBp zc;5j?O&OO7(ZYbLNGN8ujntyjQ+^Y)X3fwQJlvSo7aa*Bx3yv&4~KAcYMXoM!}BZ4 zAyHBrB7H)t(csNcd*RNt*yY@aaB6Z|vEYWZ`5*%0DoB4pB5F;C}lhTB^rUobA>dF!z$rEjp zzPtR=e72R2U@adQfvYl31P>eJ3V#nZ{o~jstlS>8&^HNrSoqR-Rp9!IdY7mSy&`ou z#SdkTGqlog?)ou$+EVh#)iVV-^LFxscmLdtq3FzP^I{Ik+f8o4+ajH4w;ri@?n4?$ z(sR6KKff*gE0D8wMBWiOXy*%8nUT3;Nw$7$fxVD6Q~rU3b>c#AONW1>WDXCf)$6#G z>U_pQHF&;+|mhprEdLVJaUwA!N zWze$XtM(~geIZIv;{8InkS2!@pQf!iehv)gJ~+g+7VV=gpOD~be7A#=*Q+mIl}BLN zeeF+EMMakok7r?2WPt~Yc6SF5h|EFwygDt}wp3*AlCWrBkN%y{{TgoDC2cXSEo@)PW6u7sXyH`Xy*^B7UTglAq%!RnOCdj^D~Aw!e}lcPzQ%G5J!%qG#LSl<4W5^SUn@ zeV1>omsRV|>3OArl+0T2Iwdh8$sw1ggo(fqvE777y#e9s;_qj&rRyl&Pt?nvzV!!# zUUjw-c-@9qwzd`z(mZ;k?Ln#D4_CB_i&hAQ;l%AW?{6>VmFO;G#_H06n*47vuz1wY zAM;9lXlG{X)hhs;=0Pp?V%CMvwYH11Ki0+{A}h~6>=3RKfZdWCW56CrNR0AwGj(mq z#*H>Lvyx{3aJMHZ3J93=IA0e6GoW2t68s6!3SAHhTs8LsHiz`k1kihlb!T^panZ}o z=LYT(K~^FiChSnT-h5A`J9ONxs9@nBKgQl(cYkXx-0wfr{NFvph`LQoK233HYOFKPr0re4R%HiK zsNEzbHP*a4`v)q`i9}{XCv4kBx!^{A<~ma##5=dJJy6T0WN;taZ$FUIN~J(h<{&qjUpHBp590;n~Zet zsy>>yAL)@VH`iP`fN&{9d6>ZlGC*af&i#H%l}$ zqsm_wmT9w$jTY^idA4jZ)f7S`mo>-x8>E3t`lfKl`#iiSvgn){Zq1X2qLPpc{nP7h zq&1zq|BLw8Xt~rU7V7}hy^9IAAGgH8yETsk^c023coFKi$;f;zEpk`Pwj$)95)UU9 ziAD<;PllG&fJ39iXmupQRrcRvZn=F(S`3YbI44YamK=8O< zAVxg6WaTw0P8YF6h0no+ zNo$C}FvQ1og6^drSFR`bnGwj-pY=nn*B zO&_U^e+Sa*H*HsA<1Ox!VdOE;w3g7@HCn0!Ze$#Ab40aH<@_!&Rx%H2-~r^>pfCAP zP4#*MT@*LsXECn()PQ|ceP96OX~JcVXCg#>Qo?q4nMQzCWe>5x{n&e1&w@JpUN}HR z7mFyh@5TFmjCrU>;_3LN#g~#)e?xs%?SV=^T?x6yxZK>U9Rc18Kfu~3i@CK<2+M(KimBz+{x8)a#Nj~`-oSX*0@pUQ}GJph^@yRAbc^17%P z8UwK@DOvKc+luU`=RLB3Z zf;@+OZ_O>gMHJvU4Ft=|%Bq0b5n8GDSPbEsM$FB(N|+YGubzkE z_-^_zR$J&kV$|=$?!-H0z7`{=O0LQH2;Il0Bd)!u>#=^HnH+i?;WDi3```5`kc!)? zJaGTguiuF>mGX~q*)d>|mi; zN~vK8r{Kv*4G;k-y$h}dzkVkb?&cgd%~en}*}Wn}0ZQ#p9V@QN1EN3Q zmJibo9yZhGMc+mn?6F>fMY^vo^VZL&*`kB1sBV!U7O?uLADe~4;i~ChPXj+ie2?5q zaYMD@-K(KaBU#VC$fF1@vm_C+KcuaFrj%~W!A7BIA%q+ZMR>Roz^mI!hNHIp?DcaH zdD(`I`|9AIf+c7Y>0z>*y29DB>^vGkMuLwPy^VlvtR@FPkG9rsB-i-~(eIOVA(36_ z{LnID_U9hP1{vAr`XySFC3eWVSA9PF zL>8?xpkI57s)>Qa=Z)-VI%gAa{Cpsk#Sci_U)ZDbcuev%t4ojVgNqVG1Q&_R3elZS z^%~YhF0u;i{g;qX!(X3F>anQz&KSwyLt^kDRy7qO$qJAf8;?KHxD-83tDP(25@i;R z$IES`dXMgwM1+b#JJyJ$Hdtr%!mUU0o=ICt*K{l26$b0 z;~0Z{uVKQC*I(mY8f*!tH>M95o898LFuX2THLCk(CtW%QBl_%Xw(%GgI;6U{Pg_!n!!hwey|d5 zg};l5|Bmva+FHzm@nOen8ZbDD6$iWV^$*K8L z`^+384FE~nuS1XF{02-7(WNw+Zawm|&E;6oB3b#=!J7SKb#Zw0RC{35Ghb zLCgO=eS&K-(u>XuGHi6$k17KxU|1hl%Y;m9M&%758XZgPMjjp{49?BO%Xx0zXFj(v z1|7qR&tBou=|`22HcYvF!rbJ4osS+Id&Ry|9E${BkF_=Imu3CP(r)Zveq6Xyyv2Oe zuO?z!-)7fdaIX2O5$5CNRl?ew*#@MDe)~2HHUcFtVd7eGLybLXsY3l360MLsl+t@f zF|T~IVJar6(b1xJZeJyi7Lqahn}$_yV04&{ax!e7n!xF(LdrgFZu3P;WQxdq@_v0o z=u_{P^Ap%>>X7kVuM*LCd=rK8-I!4=Mwvf+Pe3LJCrpSd_oi&`YQMwag7K4CEepY= zZqU_kuWgYc2E2d{{hmiEZ?|tlGcg`JrDsGFV>jubM+WT7XMp=wp{KumiVNVw)WfP` zuoS8}hs4C%k@gxVOyyYM6Y#kj&#f_&ObF))d*#Nqmrn$|XTES;BkLUdv2rNQ2Zx%w zZT{_<#eVcuy^3Mcwd=L?!*QNbW^;2R-s%s|d-=i`==?hLYxi-&#@=oAU8PUEXXQ#s z-4Wl9a}T!3=Kkwz1?dYtBqyTFGsjj~nSxith~)G_8gFmr7ZYL%enO|b6#zrLbDQYl z&3v%)+Wt{#Kp1T@ur!+H%t$4Tf?CmjQi+QZ zfuX*Y-cxVD3A4ic1E~eKgy;gzFYKa-7oIm5w1{LGFrrv-=q!DGz{jrEG720m+Xsz* z{Xdv^5>Nxb5aHM;C~y1q`hWlbX=K?kO-+ZM)ZQ&rZ}cB_wKtd(=*8MH_*T%OXI=POU_h`gk(_1W`Wx z9bZ9Oa}L;@-+9uJcLTOb1cJ%Akis2V4?~jr5M!nB{1_sIZZL=SzJ81xplqj5e!C4z z9q{z<`HXZ=9Z;5~L1#nvCf2DegB2445q5kpk556WvX%(Xl|NW(yH@z8?LZ}PdaBo@ z)qcN<&HL3NFQKJIS`4NG+68~AmPqFeLk8ztlXvu~|7>CZ;lnjW&nAf2q7zDL_NMm? zeHRfc`D8(QN=yt6SS`RZ6{Lo9c0>(-q+4T;dbLPOR#uN3T3`j6uTqHHrxF2+n zlMB=1CRW_QjYPS5?75w%v~l{Gy$%zV(y`{6LJa+)6I(S5q5nelqXb&s;i5PUVBil( zB7X&VO8{{bHGJ4}WVCPDVRqWd*qZuFkC9au;q`#lNqwe<3Hn zEO5dGzMlusJ5mXvQ9HGL__``w4vT7K4Xq-;s{6h-Q_T#$b^NWZIIe33@5_On1ZXYqahjh2&W8h56AkIWKvnu!rZDVU|bdo8&oIv-$){ zOQ(K^d<{{+UnUQXgMNaEK|LGgc?Gzo4pl0QPNRrWpYyRCPUW78vT*p*K=e(5{!8`z zsCF4(l1j*?3CQ1jRRMCbZYI`nCn8Brx?IuDeEG{WPYt4j-oAU=HRNx%H%iU33sy@` zaB`R1LGHMiiCxX9v&1j`a%YJVsJ=`8@VMDit;WlWn+HE{hqJ9?+e#*{M=hC2#0?{E z7it1`=W!U0pUK%05ib#x81EA%5=rEmsxzV zq5<8Wrf_RV(d*gLkoC^_eI5=rVe4JDuFdKThpSpDFAD^ zWrxN7wayRS#mF3RNJDf(f?`yLyzf9dQPwcUh-c5ufK|&IN=g#fEoix3s!Q-^ija$w z(nuNs8m&YclZ2Y^NL1V=hc~Rwpdqspi=CkcKr<4kLP~f&$r^YqA)`E-17M~T919|a zTZR%RgMWyar?6BHYTB_dx*DX8SSMN`;Y$vVDI&x%pXPY-b;z$tYEMEuJ;k3Fb59Yu zYAW(n9SqWsLRf$3?yJe?O>G$|UhtZMj4lB$e1T?zKeF27=!^}U>1%q&)lO(Alos-i z+(Am0oVG)JR6_nHofk`fj@D#nNRiPBJV=((ip5Ow4C0A2rdfy(5!>a$JB&0M-f!5R zK(Z`EDA~SbsiYQuW`vxpvmswW-$#xc8z*Y%2uDYxn}I;EA!3l}h)7rO8suJYT}jUJ zVx3^-Jv++ux=<5aRy5Z7^dK)|4SBmk@C8T(wiUQK0$#rvdY8f?3m$mIC?-|~1Sd#9 z3O(7m+}XFuG+kNV`R`06l+EJ~220p?|G9r3Tw=yt0e-6iIt;8HV;pTnl<>DQekYHA z)!UMJR)5C+^*mEVeSR9>!H0qKM~|Y6xRZ5^8#473P^cC`&(D;qGmYBZCgQ4HsUBTT zsB_FdEB10V{;WP%D7h|b%}bY|`{D;x2k>WEqzOaZMC0{czzBHGDe+T#KX{GKy<@0Q^=8960d7C10gNh0%88TIWUsIZYCh0ID5DrJa} zp-7ZS$XNetJ*w~f{^$J8+k4u3KhIkCy2tCj?sb8#r@_Itf{jL_acJ(`Zb+js*W-UX z=d$2$1f5fg@yG0gTXnb6Xm>;BPwkn5|Ic*XP(zKD`HHs}|7X>{orbzJnx`O*=I2kN zP2jKmKGSHfQZ!nhEsdreO`|P!jw>|Sgb!HuYHMt#{U-lSC`k#&-^_E~x%)W&+)4dU zz4EXMjpjA2xqYj#dvpJL4|kL9lF{$&RkJncuD<-=<<%G2{H29ftr8Ku$sV-EEbfY+ z(Akw4Zxi(z-bR|R@8&9*9hVIv3}XC6_Uw%2TC-u@srli;Fi^R#%5lO?i<& zT3aoZyeIB=b$4qT7+i@{@iy1e))r7uFxAr1S|=%~9~2xcpsM=&!$6eiZ9?*d>OmUq&X!wrW?J0W;oiE5yZfGXjeY;<^0i6&Ske0rCySnRyI4)_%Wn}^ zogNN<@ZM2aT-=23U60zfZIY2+&Yz!qAtWS{g=59e>4}jfpXrI(>^<8q1O*k2^=#X= zO}K+b)3}LeANlh50_ViTv#j0ar=ll7NUvP%Q^7n~zP7R-U65uaYs)lCSSG*2y~l z{TY9E$HTKrefbofx3JBhZ=&(I=FHi%l9Bz%y4SR-BgK z`K4Z0Iy!4Dd?!hc6|xD3m}wDY z-|Qyl=4k`%Wj1+7TLfG3j)q^n$o{V2cnYtgv)>2y(Cr!;+DDGuxqq}}m-30vtFCW! ziwxo0sO9V|wF3*COSXD2C@5%npzODG-jR1}Eb@+A!3s1zJqzPDc^JCNHbs<`l|6p^ zcxTbc{@aHeGi!4XoA$oB#Ts>!iRN`ije|BA6c)DFyD`&hDE{|U&xfoRFLZ<@BzEy} zT>kX(ns$_g)ouKvHp4=px2>ee|J*sF941US$nB>(H+YI!(Ew{!e8EI zg#YNNNe`J5tydAqk>obewwRw^vcz*Ftf|S2O`fK>EMNtVmw})CuJQe~_VC*~SL6=A zeg5-I zn`V8QC0$-Es~ZkQ&{k7Bvu@qGodazpNe5oW;wRbC_(_wowe^is&k+Y<(Kowy?@n9G z6tb9?S4^SRx#G#0_jmVcypg?hhJz+gB+XO#{P}B~gh;&auL7?hFBQC4Wo_47S|Jz4 z#LV&>_JZX&UV(vB$6wg}YU*=^+c^P4y` z>w<`)Z-v^i@<+7_SZMPhGQTJL4<7u2v%Z?79aS~dT|F))Ys*X&j=Usc>)EctFPWUG zs;Ur{8I8Q8<8|V;iG%Upg4&T{SF%bcf`k=p_g%Si#bvTTzZ#!)=e0P7mzQtBs-n5@ z104}jQEi)I_q(@~k}4tCfcQqgAN3g)rY!8sR&6`C;3_1lNvHqUjj#GcGX=x0TuH3C zzR~nkO}r%3*N~6Z@51)&+sR_~Kfk=%u~)+BFd zW<+FXOBH;{Eb1zq{1!eo=KlTX&lF2$KkB<3gPj!j1pEEDqwCc^9HxY+vgG@N*W%yG0&R@TNx!~Ni4GqIuJ$kOUaxI`) zZ^y}=#d{cw7cE*%w*PG9DV@R-y=r$^{2a)EJcO;hNPsmDz23I4^7)mu0x~jTE*vzI zEq{I)tqB+2edE-(E6@0SEj>rSYTjj`Eu@pBLm~$nl684Jx~^!f6BgE7vu2G@BaQxV zMPDC1dbEFRuybhaW2kn|tLwsVY4inum#bBHvR_0~Q!}m*^P@p8o+bX-=hsiL-mu4yx05g2c6?vRb(j{i_0K+=Ow7!p*9i)e$3E$~ z!=yNiyigr4bUS_e^iWazwB8NhUmi2Z;&=4#3-uE1W7(HUZLxOmoYMqg zx~Zhcw}PJi9p$HQ+OOzd;V1s@v$v^6>pi|dSxQ8^2pW$qYGdovfvl>{wAx61*oDxr z6kd&d`1iC1RgbphUG0hYy|I_0JPgNYE5#;9n=%hxBHmTdb0b`X-`jZBtXV>DX<~on zxn(@F;L{3^-lQmU9C2pMQk(G;qBS(`!*$7*ihoUfajDt-(^*uJR`>TkbPqn|6PKfG ze0B#e;L}QFu~mkArHBXH)JXOPRZG&3SAh(Z|H?3-@59HB-5L39Vem;tcbJ5FQk0S8 z(CE8GO*11ht%|BD7OLLi-{gK-L5NA{$vm)l~m z7V<|I{M;JSP4#bhkM8#9OHElPBy=9zmioICuaB{ZGp{JLxu4~E$h0i*?{Az&`ddr| zb)r{U6`n{mV;&Ti5MV~OlX1to#5}WP)ST$n$j4`)KLiD7@tyuS=%-{c>t$t)Z+LuK z?$H^r^frEdzZj1{4D#}Bm?7wE((8n7%}`NCe#Pvozf z+DZ`5`Lpem{@%TNag3WDb@AYFA$j{N7eoE77mqd{_B1e98(JUX{+!1^m{vs?a?B?9sL4nZKTS$I;KP6Nd(Te_Ql5q(8HlvpxP-eZER6E1M_l#H@kD zZyPhqKcyr+nDh1Pk%EsQ8~4{U3_Q1PWpcVbOa9;cog)ut7O1O?cX9SM=ZfO}FK6CA z_PVX)6p{W=^Wm)Cq@<+cRJNwMI0aiNBB279hTX()FUd^x(wTT>q$Bmb>Z)iG+jUE%~Q19 zIwP_mFDRxc zcR;6{Y5t$(T!0$uk;jjJ2$ppJ!JSQm`qOB(YaH_}CVmb`5>>V~G(`B&xmc+H^Tj_B zavV#?55&kFjzl84fr(Y;{2w! zB@YIQ*~;KJppRXz;#DP)YkTD`v6cC^*@iboZcgMG$nK?>Sh@cCNWVUZdd8I(@v1h6 zt?H>PTzjd9o4t5*OM`lNsLI571$(9dO4b$-#>u7$p1XRR$Qb?&lo+2R*0 z`|yv!JPW51lTWX%i*|N)LK-uX8LRS>eEjrj)rTj+Ngh8wML3kNBI2jfc$$zrTe`h> z%{kd`-u7S)J4v8uv?Cu<;(fx%qf~y4?bDL8{Uf}!JvH%BNZZXw04ceDKVmP(*njaP z?tEX4cNoCYuZ)pD8td=xKUm;U&idDq_HV}*UdueB9r&)7jvmGjx;?()>i{PPXG-tmYp7JQM-D;^U#U$mS(G<6D z-FljR)%?!PcyStA$=84RE##{aQ}DsFW^&Dat^&&GjHL-6l3O<34ekcZ38ODaLLj! zwVO9@3N>sII3~OtZ>MSM>qn`0PdtZmczj&SSVt)yZPB84_YQ^*e|v8+`t7}TDvJn- zX*62LO&Gdnyo&dJB;64X2_)mff1;jOR$jU0RJ!|ZhJ{8dOXiF=d2ep+h;ZmonEC67FG$*CPJE{C&bDPrTJeCL5@I>G)dT0PfgC)7 zKR&&@Wz1Yg@*_mH#G5zQ6u?K>J-xUb&p0@vWIJ{L#)#lL||=pX!)HGrJKVAFmT5vqSyjvc%L^vlv9FNbW{E+1b;x zp5J@;%BHc7vk?x8i^HABW=#yu%|+I#U%VW%;o#5#Y2FJ6rBcg?+b=>M8U@#}{aeXT zYrV8iA*_mu+_oAdm+4K3ui|rS-I^M>Piman#nBx*c2HZ+*+0*Tw?dk-8Cvm&M*;Im zUhq7}u3D(UdG_DvKr5O*Z{8K+*OBMHoZ`ttnl!UiJ$li}qi`vg9zS_vkhaI-?~6OQ z3=9m2wIDQbB(2DMe2`MPG5_lBFw{Cq?t`nG1S=wE-s|-Vd1%<>%d6hKdl%u*v|vVh z`qP6I3v07%RDnv!;t?}8*Kr)hZWOAAo$%B6Tat>vU!A|iqfj;A^K&E0%w*$=B{L6Z zzlRV?5)I>LwBj{eT=C68RhayTo}cYMi>iGj#l=gyvV=uM!ZsXy#Ry@enT$SUam!QPaJ?j zr0;((UcPJyelV9krDk>sU8@h6{2nx#_r*@Th z`A+d)+sl9l&6zVNZSAaV#_QK~q6x%LPQ3`|{*(EBoWsIGp&`g2@Z4*`W%bJHn8MfvB$ly&AGv099w`KttJIL z&SB^{Z{(kHDO~~y1&N=%?~C$L=xLLGPc^v3vd~K287W}N9b2b&IXm8FT8XkQTxrZV z-)|PF%9M_OIu9@4b*^_t_q3wI0_#QRKW+LUg+-lA?)(g!#N>FW@ZdY z$R0sn0@&uq^ar%?&kgBOsIX$Qto>bxCPu%Tp9^5H6=+geM8rC`HjniSMaydl3gc3zQP+qe}4N-V?=;qPr`;PBp z&;6GWi`YGk?AH=0Q+Kdr>E+s5L-OuJwYM+aPD#<;zkglUK`DZZu_x!y-B63&aQ`rG zxr)~Vpx{3`n8wNpdIxOBRAu7x+RB<5Q$AK_fB5W5RPqu&K0d{H59yT9g4EvsU)W$F zj~~;}j~^p&rj@|2?Evy&?Rh^@W>ltUl~x_*W#2*6e7OnZFk;frcHgp1)5CSBJgb>m z5_W28UMO|$REtqOcJoM6_EuNk^1P|3DJpv;*j6lS1tqgmiF!oBA;j2f{@-I7_VtWK z3%UI++_5RM=2!J8CYI{X!d#pMcSJlP!ol(^U#Zz-!=KXC-UFoZ7=3rJ`)Aqj5|YQR zVv069a3J~D?_ce|!;!-M$hGi`vhtlC8A6S(ZEL$KD_~HG5_d~LA$B&@dc1}xDJi=* zZK5r48SL2V{m6fwj9nF%u$Y)JA8Yod_3>VYz~LVsUgJe+=8s*8jtyy7i^o0$6BKDs zVw3H$XCZub&qDbnQ&Ur2zO^bf9HUw6MDcLyTfwgk239Q&}H=%Mhznj0o~<$Zt=?+RVhNnzipHAYfF_FWBX?+aZIdrXfs z+BIeG@v0HDJ-%Kq?lpO9Wo4z#!_y9MwCCT0QL(GR)W(Dl1u20g?&PemAL(ld2MoH4Xw|$0 z3jjVY$a5R8p3d@}PWOT_As0+jUSKN>O&WT#)Mlre+N`XkL1iN0J2%z%mMjtU9joB) zLh2U@%+h*_$?`r%tsd4Z7R6*4=GBlSg}7 z@+AdUY`Kb5=?jpWC|K_h-`g#7&YU^3pCkgn`K;YKxha!Lw)fn>|90_kt+ost36kHQ z9ei7I`8InR`vS@7`WULZi*Jrp?yd~;N)!f3__O%e&E{w?IGSI>DXNvBs=tItrHzGl zhy(Jjg;&eWFuSYPoOd)G3pJk{?GImS?Y9K7K{AqEWwv^rSU6~LO?`rc+}r>b9-CK-5k zDyrK<8xFj9ji4!t9Qjh8qF*X6Hn5nJ)8v`o6H*4yj(kJWT%YIoUIajR8nB6NFlJd2 zxR9>y&j}VGwJfb;mFm>sSvbDXY5*d}8caH?H*K;!`L$^^GC8{mj!=TV;9D6M`EPgK zFm@;$P;b@0>o(J(3)d24}PMp)!JT%E$s4f&Xt zJSKQad1q~H?JxnB^=@oRRc1@j*}3yP*`ayfk;-A7t3-!seia;i%Em2s_njkXsVmo( z7*c!@NW!OLEe;XwP&oVh0@{&>(0~a?j+Pq2EOghQK_o`TE~sx=_J1foXtW29QEd*B zS{f--x-y&X1B63usG+QVt$(kA$Yb&@n#7wsyEhy~A|Yd6yKWvE8$f+2(h9k_LQcz- z-E8Ivg&Ls?BLMVmP7btX;86_7y>i>a&5woUGD#In^AlA@uKsK4M@@CnKq+}!H1P)r z`LYi6=M68pP-j=pJ%^R`FafvZ5y?^P!m~?lcXZ6W$hUEqD|<9Ar7(>9$n$!MZzdkq zm8<-}c<<2|)Zo!Z4pV|KQyOiPA#|#2YN%SqXUe^E_u`X{aH{We4@db21Q?`!7p1U= zjw=AQ`<;9zujRRa-ThKNF<94vA#rL)V{pto%SoFMAzLwS|yVWaV(YRQ->`{p15yfe`d#g`q%T*%%9Pi1KdZK)RYM0nvqIIUPtz9&xnv#@c73T|==U!oA zYL(=T_*jcXhP(&cznXHx6ShYH!%W7JzU$%P$1CGQFJ9a~0YfYPM(V7~tG9I_v!e6O zVT8dCJojT_c2_?+SC4UQhn>+tb-{bb<#G-YeeT%F0W~$X`vLQplB5_%m(~??@WvHn zgL>k8XVfmaSgDMZwgS6|@xgMk=CiTY9(WZe3}_MJUD*OWiNGvajDMwqPk42AEo4Rb z1>duRgMz})jno3(b`KKkFe%LZQnTsDMFP{qX4eAXj^g(j+X|7t+>rC~nA)XwS(Hv} z)%VYzukQZvejk3r8JleHR5qPA3ROT{bzcW4_t$8CS!xIqv$NVI8(^7ro2OfA0h!qW zmo8>z1^wd#;(ddS@3d=!w4YWw>M00B1J$>?dLA0N5(aGc;1QamJ+7m%}?7wiQ^E(?-+M@Q6Q@SX% z=h5uxcL(EwRBoaM6KlEu}B?=8{KYf z9Pzcazz9fTbRM)Z-gBZiWyE*tBY)aHnkirqg?DH`ABuhY@!gEv#QwR2b8O-0nNB~2wWhw{O~%$$>nfv=#JOu{8kitaNjlCp?-Q>VMEcHR!V$}xwvk7WBs)Nv|$x4)7_H3S5QXi$sIkT z*1yHx-rl<8f4&SiD{lFK-kk50rOY;X4W=u8{L>3~N$W>lEqgA;dfJ5aD$rn|CFr@|P7X z3mAa#R-p^gfNfhhEPpV9u)gdQp89rj0)U^(PEF8m-fMu-yq`vLML%0CPo;13R6DjhVrhKPcLLfN_p#G z1Ge{J>LtFvf91GzYhfF~AQG*!$amz{t#g;iTcyW1`brEAA9L`F04r<)Kg0x^ zID}L#$7|fBL7KjU%YoGIN#QoKdZaDByU5teQ#&IrQ+=U}Us(TrctqR>0_mz1_o8lvAd0!LRxPA* zeL~I;AaD=hLkN7V(Oxb7CXRozP@G750FPHd5vX*!SiF&5vDl$|M{kR z2yg18WzuS{?248?KBZoR4_VXpC4@mhOrmXlRu_B)9f@xU6crPzKQ+=P0KQM!t@4NP zg8P5}n*J~_Q1c_Z(tsiUDlOmB)Ze0viRLGQ)2suL#~k!EobCd0&;_tQk0tU-g6&HV zHvHT8RV4lPbt(Ewb#GN~xvm*5m>S}zl|Z*JGdGV-`nPS9Zx22$=&xKKk26|;L|Yj> zmiaZ01fO-a-2AHiNBt7Cz=!jx;81uD@{)1~?<%gcCAoVamT7wzoeoG);NI@I!j zwl`l~zTq~~3T!3uK+O$tK(XDk>mLi%FOhZoW@({cBKd3>*2bt!GZF27@750Iy1>NP zcpcL6U3|=@Q2f0!4)JjC|K|`1O|gQ!djhX8e&)vv5TDScZi4}|iS-&9z)Mh3EPHm< ze$k?+YJr&?3z}DtoL4f#JQoT4f-aYWt~z~HytEs_I9~@-(AL(b++el)C)c-pj(JtENkt62Qd0zMdR>y6E)h95joR6_m@^}9^; z%BAakeWum5gSMQV{>@#jj`=E%t%?oOItPb8zX`j3{bkWsgfZu%&G+B@`t`FcJ%s5T zP?jh_3#lQetLY5gkkp?}$BW)S;z20eaurTV6WlE*bOq^h@8V;M+B0-?uTF{RQ|dTe zI?9#^bN@Nf1< z2U0s`v>cg>fVlW2w?Jfjoxp1D1Etsrgq-La7uuL{O2>_#mDdQ>3s%$@IZ!^>Bv!#G zb9%hS7do?GsPi0uT8Lk~0Yf*?q9pxk|H*0;TJWee+JcdKBYjQK=CJW?N7{;a%gD$m z>c}v$S?!{kevO?3Cf8H zaG;TC^T0U~MPdQm8yt`nznk%SPKPJx$!&`nW%@tLe_Jzr9TI(1@|G}T0-az1D+0_{ zC%2U%)uv8gh}4h$p}teM;M8brx#l{h+?~6e_BoS?LML23Pw*wDP-4R{KArs5D%{_k z`_aRcNssZrzK4dW*(tQ-A!_Cq2$8O{pMCH*KaE_Y4~0`!-?9)Hc!1@~Cxix?iK`z0 ziqiAtQiryhS z*hi%tM|M?oyJ+s+i?j+Fcbc$%`oT*@1eI3+R@|_NGzpodM|Oph+=1Q+-SbS}mC@Bz z8IGMK_cdlol2#E)%p0y8kLTrX{by#pPJhh|wB>R-x=hW;)fvhxN5qidzP+>imU7@n zI)md;M%$-yD%4OWhKIv5U3wX(WQ6S}(s@>ii|e9ZFydoYMa)eEOYfK#?1-Hk$x+Gp zr)yA*rv%YJ&e5aPxWy~5`PqYpmN+UoU?hAgY(q(buQ?fOoYoZw{tW8P^9`9>6%$9L z9Y^HX&$ydIvB@(zZxc{*l}H`<;#Tu8%7a% zJ9#5^NFFb+oM^hc4=Qucr*u<@TNGTtp3Kq-hki675tQV+P@4g$gU-$hXs(86VrN7% zSgS3mxn+wVj9~SF_NNK-Q*WTABlqvil1v9lY6SjOFBLI!kNN#WiJJ$@nIY;xB5LLM zfe|H@ZT$jh7LuKxX#ViO5}Y1gEMYZ@)|C9CEs-^b6<_`)HwACcLF|i@+eXWY%UqTL zeslBm&vvADM-KJYCZ(-yTDiX7x;&$8w1TQJc252rXl%J}Um+}4EFvMH2QKlW4H*j! z80i;M^EXRV5<2xc@!T-*IAWk^iMfmo?jcZg&3%XT}44N{!0`kF0}pJnzd^MHf%6L zrV~>MKN8=9j!GMt!~jv&q7+9JEU<2!f6s3I4*$X+l*YO-Cuyjy0FNMY5)uX6Xf8NE z2sJz;P~Aai!j-+{Cf$_D$mt*z9xe_8)=mwfUF$qvUs}=CvaPkRUuUKoxCvbb1GnvDGmUlDx z_a+=BTE7{P`~D|E+>ra?fWokUrkl_NJX&Dm#%qQ!G_N#NXyyQ$p(u;ka-9a3_i3$= zKe8;P?!QG>{>H0=bey?K-z(MvozSI#t2v0#$^l z!J=}(F+!eyP4U#|9l{?@+lS75;VdW>|HhMd`j$z>#7m}tIRQz3aFKDZ1N+xR14Me) zIS(3m$^t0MT=e0?hx??M!RgPAzcs4DHo`46^7QJA^|+JHy@sDI`YrczhGirKM9<9t z9RhGcu3XV(0D<=(IG}anglyDCa-u@WB+=;=BQpbiLfNO$W_=FC!2RUNVm(H+wCC`l zDp?U?QNU7BPy+2BrS~X$AUM-&wxj)4arEDTFr4c=+?^Nx7Kte+D#soJ%F801Yxk2H zuDOTasErP^*BnoeqBA5b>Um5a5{no!M@>))2ooB`jCOAXfc>G?zBxLj)OR}nz%0~@ zKkhp)80q@uZEA=u4_BW}$1Zp{(732%JiY*|L-2A9A(e8}ClDJ4+ei%#_|?3%X@_SV zvu-LJjP+8uQ4W3;OMH_S(0od$UUgp|hZE(QI<&zRq4P1xXQOYh;54W};yNXrR&Wgz z2IF-Tv}|)!HSj%8dJA6(=SC@((l?9*N>aiv9eTbtlo3MXfoD1QalV|9)7UI(aW)9J1Cc)N9=>P_@Xr586WR$F9jAHRO9ZBx~jN_IT-xx)hve4-ER}+us@= zMD!gUL`VAzGYdNs*(LaoAXo*9K?1m8kpBGG`uf&B4sOVM20%syx;DSfGo5s-u`x3g zGavpP~Cc%YAC1C=cm_asgiG?vt(@X!njf z*5$y{IxnrnlQ__-S-f&3qM_Ku;L5aDZv$d2O7oijpkX_CD_1@-a?6uC%@A9D#DJKQV)Mj?8mqfV+ST0egV>xnJZej9g^F! z*N_Y~p-`xvv4G9Bp(%|V`c*1&G#q;=*LVm`4P?MeuHLwjseDG@T{6AMQo?a0u=~>T z4eFK>ONqFRHBn9CsXO`sv0+ZfW5LMfqcEo(+kugpqt*fm9JwcrCML3a^;Xx}X2xLZ z?BBni5wb@qPpF=VrDP8eB^s0W?jJ7^SO@zIsxdhAYAB$&|0I^wPi2aXAha>;!Qmr1 zm3zELuVIncvmr{l8dMNS3wo!J1}xDkZLL{I(tNpm&x%(>as1K}=(o~@>TlGYcpqEy zIk}#WGT98`*@@nq?QJr!+wZKisK3-Bt3!w$yq@Q}~LRQ|n zeddEV1;-Cky$&>iOb>cIH6+I$cacN`h8TGnI;eQr8Dt0-?bz@#KkB1RDjJv46g`I- z0I!33UTWn~>OSQ*@sdXy2P-qiE0@-X`qY%~p^TUTJPGsf@IOhpu@F)QkggIT>_aHs zAhW<;vW<>LN@hW%A@-#&qRBf-bnuP$!n!s(R(ELVkvdy+-Q0JDRd5}-GlG>q2%1*2iC@M z*rYUpgFzL(Au0Os{(ADJAW9WYYf(OAptAr0>_wHcPC=nDZhe;EzAClr*i1bSV;xcB z4lOWOla*(Qov$%44e4deg?E~9iMGO&kgGVCE=?hyt63=}i{klAHPrLFJJavcxh-{e zDJ6@Lx293`x(^w#fL_lzM!qggKIo%9kZ8PbZzN8I53?62v5hsdXV-C&{f|(OD+@4k za1SCs5~@cPZr8`*PAP`7l8Oe0J|B_}*V)>1YlfA?QX{AGY7|v#C8B~!GO>O8ZCEx$ zxAzq^4pEk~CY&4J^z|7;$&tMzt zO}2vSZEt4U1#C?|3k@BbP;Ob zJLW?VFQYNL^Uxuonvia(ul}%*gq0*{b{vT_tS~z9Ky(AO=oe?nHk~t3UXVp6(rsdD zh%;dRMCHwjoa^fcx#Dk?%EVL49w!00JVr4wFh!`|^i$m*rIHdRN~O3k09$k(uJYQ2 zP?N8Met5%gFIpyLey?hw31pvfJx>cKQxKR%vedFiK}RD zw<+pNODBQGSXl zA5tfo5%@@Q;;+i*$!$7@k<*4nIxi0gGEMa%z>Wz7vJ^fHm47C@m)7-(%;7=J5pJs}5ZNM(qS_~myT z1urqW@&g!_B72P6d}^2L?7E=`M0?{XlNcrQv1C`UXK3U7P1I9+W>y%W#-Z=5W~CBJ zon8TD0+S%J>(d$4roCj9{Ad#=7AtGo2$ z=?Z>B)Z-AG2WQ78O4t?W+6;xA8$K{(U-+xN#|GIFfc>HCb+j}w_{f=lskza0 zB%=|Mn0CgzF3CU7qw`OQ$2D$coge0nprR7SFP{7_XpMXB+_^}vm!MAd@>v5#bYDo` z_#(7YVbeqWU2Jvt-ad}}O18}rY zh(>#kYM2rAp2z?92i1k{H*eqGo|BU^<{MjmD0Z|=yV6-0aGlTK&00)nqgZUqWu}$; zlP+8e)mtb(fPdeSD4`E|ygE3Cz8fzFut(^s<^F7JY{O*Ich{~+yy?gqK|yukffCaz z9i|p8l`H3L^_olb^9TqGbO4>|Q8c@s0(uaC_#&6otT4+51IL3}Cr10z1*o*CoCVFB z+csrBv1r#z=mQrU!8|$q$|4LOEnc$ZX-gX>K$bx=4JPs<5~oIc{0n*G=oOrVwqWZ6 zjWd2GnbKzG8}h%NzXCF2q}k||RO6W%AOj8~>XK)|Ux$;n_euDbC6@u!x_y4Vb-~I_ z3}rT2@B^Ch$w8wfzCDNnLk}ptp2=!xv zu8DlfPj0gls_*`Dq=c7H?n&m!q@|@%f=Jzsj$YXrbEu3p5;dk2x7jAQt@>Y}?$KpD6+&eTI#G`6nC z=)7>|%&dk*1dt^sK&WM9Oy{5brnKQOOymA%<(SN;w#G4U-n_qG!M|ShJomrPXoAS_ zYkd)WKq0SJ;EEg1Nyh|PuCdXfLyXAS*s5V3XGT?PpSKd$jo7lD%&3*GgoAO;{QK9$ zvI#ASxLC!|6r%wdu09v3@xb+9n$nsOF3NYO$&5&BOO(*SLm`sONDlyipsqXLtI)xV z0&b=L%>GHeF-vUS#*G$a?HzVl_+&8V?B{U`8jt(Nt67DhsfT)VKK8xHs?oJU3EA#X zIGC>)$}{hUH@g6u$^qh{|HG?G(_GSjcH__z=oLmUFsGBfKDpg*+IVEwK(zs*dMgz! z@m&B&<<`a0)G}ESEWtOW+1ilz4?dj{5By0GIhYdNXsNAeKLI(XbF|Iq%34&qAB*s6 zQ1Y=n04e|(bgn78ir}#~ijy z8$Mj4a&nsC_suvNZw(7f>*!^25z*Wi%&wgaXd192z?Fph4beF8(xCe zssLcR;>}neGqB;$d>c=8>2YsKgyCUOU8?JZxj$#0Cwq}1@xV$kQRe*NO=V}syR@7xhnIyEY$;EiO^84qnYq%h3p#;s1qEH0!$%LGMpft!BuqO}#vbh_mvt!%7V~0IR`=si?)Fl~bGVI-3vS+QMU0P%^8@6=i^*SFuNz+>^Ob~KPZC&I;q%Jy z^*cUh974Wz4=#!7ieVT5bhzDchnSz=6I5rv2zX!;2y{dum}L=XUBHW~7p@-ZFC#K8 z?!_<DD z$&vSkCe%XJIM?e%ED<*ctZNpu+mVv=V$6+ZU^jzak z8F975Oj%UgdqHoc))|hfw4?EbC*`!Rf=Ov|7oq@=%)68uhU5a{ldub*;)uZahTROX z4%U>a%!kK@FCA3H*(b+Sif9Ok3sGiA26$nVn3#0RPXE>`S+5hFpsb#R+DI6D_QS6e zPUApV5lSC}J-OXkc_tKXehoqaT*_7+`6HL%Qiw~Si2#4mI}m`)Yb1_BCryrFc7+h3 zslL)0a5gX8nenz5>${ak2t3po?vR=etTQ`CLRkN4^f~Zc1FsN*ah>T^h}YdpGH_1O*WesWE1xaK{VaqC=JZTyTr-7$EXQWEa3q4z66~2jPK1JE;gusaq3A zKeY}?TDnbHDfW_p3v0&FDWp1^OJHax4|WrI<(?xjf&&GG6CpWF|I0NEoQL;`{dp?$15G&J8KIAU>#CS+2XiY8B_rvtg0 zT&a9z2S!d{`j23oa4itWgFg|hd!3GUovfy=Zf-Z_e1gc)>?5PAxNC*P?gVofI~3|Z zn9c&LS3k_7EXfWvml3?fE|5cQe8!U~y<@@GE)qHj<^t08jls)Jav;lB>yjEFDGCX=*#_N=BhcoeaB!`&a0QkZVT92?2gx_f%6 zF%@G%I_2_!@DJGjq|_rb5ChDlV4MVgO}StBhZ*hkm-C>{$WuAu=(h@0Cckb_^8K}m zJiUV(Prr&p_=qp8Th^*)cWD}#A0f^Z^E&8V26%%;Dg%gGW4Z%pU1~(9C%AoWGC*pN zPtTIObO4v%(o5N)n3%bQ;AvnDz_EV-w*x^70tT}p@J-wa%6l|C?qL{MVJ0{Xmo_D@ zfejso5Y%02XST;lFj_MId}hvk%2wnz{0koPJ@;p}n2b)=hLo+jBvjJcfPg3KURS<) z&}8glI2C;wxVX8Ka?$WW8QhAvORi@kS(cwE)Ibu+zw$}S?C0Q~9O&;7Q%g%Re&4CP z)X4=3>ct6(o8L!BkSAB%a0=?s`L-#slY`%D@bqV|P!K-`Ww5J!>5*Uj_^1`& zDs+ma^!Kk*Wbkh0Nzj37abDE6tzRKnRfK%090SmeF)j1h2H5#yiADD;IT%oJGyOK1Bsq=m^%+v5Nqpd9Y7;Bgt*uuS3 zfMS+^4Z0o%?)X$0@XGpJGr33v0yyy2)iVL`VehaVfX*;z{~_I2S;S=dY+O5pM5W`p z1k`~uF)`8H#YG0M2RSq>HdZU<7YCPvWFb1)@H)Dnh*GKI5wX>)PlLrSJ`)0k>dH=6 z<}ZC2ExpYbWGOUeI6wujMC-s~>3?W1vEz9xMgyWB{hNb{5xpuG#hj2Gn(;HuECd*1 ze=wlb6Gv|%8_WO$9V#T)=KC8tBsTLB&C*O<+;Rcm*^)S#0}lp=O)3tf%w-^%40oL#bITnP$jENywNzDd%Txw*L zE1;P*+PmT!#e)Dp;Nh8b;}Fq39>oM_$_N1yadwl^m| z1GHej;xb@}m4IOHtX^uQ0A|hCHoFl4V@PBeEuk)#HBVc8&h3YixD!fOF;mCohvF}s}IR{XG za$ld7HjjDe{?4srP5}PdqWNj+MV`_5S%@2J|=|LMz+` z>1>uB8AX}t%>YHp{M-UQ;CnB<;FWUrJzLN=52;%qdCQ)@{>^yHKD?#Q)#}$!R2kwH zxSamI`6W1%m4fXmgdJXDnq>{$IzT4N5K3!Hy-)f42RF4%YC4ZKxvlNVyxdTLCfm?z zCY+IEFh$$kKXOnf6-emxupryLcno{Ra7!~7LZFp0liRlR zckU#vQ<}*!APv-)*M;Du?*44_|vsZvxUs-g97OVct}V;= zoCNb}75H_3)Jyj$2J|8&tg2d(mM;tH%`dS$qLAmQe)TF6ZA7dCzG2Hh-_Yp} zM>zD>!YMVRa~U{0wojfs@dS!XxbLo9O~%g7*fed$?LFOC<$ZNrCMP9Kk{Wt1bK9^r9(K&G*x zac6=Th^e(n+Dm;Bh{7HF0<$#}X$YUF@<24S_bety>;X-5 zzjb1^rx2}V9eBW9TR^sOE1SHIWTAjuAVBddVZ;j_54V`Y);{Q>Byr=aR;vj^P!HKu92c%EOaiPHwX1HcdNQk7Dy1I4~{oC;D zTXfN33^Br+vbtkKb|9DN7{FO}M*B?e+Pim+k<$|};ZEQ}#1fQQaDq4C$1`%~x_(%Xm$y+xMPdGN7nTyRxjs|Hb0d4@O!hqdl*&2AJPnv{oH2 zJm(HpI&4K+6S4{1H_>m^+IMs%IB!MHooCt*W09VNFvGOcd)Qzcv$kWMs6yDEWwf_F ztZ%VYOxz^~P=p7gu3*cZ$51&P?|WHNObpnp4UiG8_{!Dd=A$1{;ua&3~|Q{p=3aw-gc0u50^tYb@haXUj@0S zXK02r3NxbXl=)iBzz$GpW52AIGBL>GN^oP7A<{xnFxRbGwS~-ezb|s@;R83v_5ntu zzMyTdrZ6t4TSr)wae5ZC_4R_Bz}05>ABsAVL96fYX>w$86s}nVUo!&5u&rW>epx|7i)XagwR&`dhQaNq2BrWy zD>Da%0m=A&YpiSl=EX@vHn*pEW7++fhLMb4rAGAvok(vnxT2`1Y44;kN6ubK|` z^y7uyR-6pcUX@d$0F^uF==OyT51(igM++eEcvVKbPD#e4%KXad_TSU-eRG|&QQKEi zBt7C9xPS$Kf7IeRkzpTuJ2}}fS^T2fQ5PIlBgSKZ>GB={ftHLhCyNpJ!lmYwj%@s! z;VpUE)iMhZRK`MzwWDZ;R;L|MF*4uk(*ZTx_Rf`TZY2ogbj%0lgK9)Z`=AwKfa}S1 zoEQ!Mcuoc8RR1Tg-PLwO$U`^rsheI4*okneb6X7eqJU!nVqaO)iW%W`;4ZcQh>KjKe?n2<~*a49&dx}uLVI)rhV)%@!%wEI201#NU zW)0}xZPGe-HIV!SdiUk{411g4{lra8s5&{aQ!%K;{ij zST%wZBZQF;Osy?NK&=GzOF&jOf($9y&b`-0)M7b^_CmUK_i>2;ICC9~F*89%__gir zg$L?MqKA7bNb4Xu*5`1nAQ}e|_N*ZKH<7Dx3UEIMPE0}?Ss}Ucjw*u|;NBhEv|cxG zh=Iq^llhPrJt1?S6WbPUMiM$G8ZM|ChDrRerHiR$=#<5HZk!*`{DBm>fP4r;xlgEE zfMkLgG$Gdq4N@uGUED*uSw+R#*p+w2Wm#_jg!{C_U!gqMXFY!dfjwFIz36asHAN?( z1OKHt5vS4vx<3nfI1aj!u(lia_F8y(CcD+Rty?sPP+M5$Yb;D?W^w@+M;hI(T>Rqz)sBaxGY`SIWsWpSQI`^7W${BJ!`D(3Fj1p}OHo!XUAi7q zwPe)lCZ45FuGYYvp2c%32}YRV0YB->;*(_J#p=v6RsvJ6o>y3hCbWc!nv(BGUDE80AI_`u4!pSj^0 z_NZd`e&$P+`7cQfi{E@I595JJNaicceos4*iMA&|_uZ{bQpk%f6ie?H;OfV1xDtRY zP+UM@$I4S*r6oilT9rjJe)*K_^jiwM6RsQMX3KqvtADk4HXOK!c`6Mcdflg4R}$2d zl0YF6-_YcCL>d^umYAnmQsXE6(C+L5t1J?KreT_sxj8+Z~v~PP0HetAl=dKIsJ+@YWiP6fVP> zW)!o0AGzw5TowZ$lFDAvMGA=m8!QrRUqEha@y5NhsPIiljM$xbBnG(u_nUBW#mU7M zu!37MiisyLlWL)8=IGK$x>TE@&re1p24>;xvgUDcG+_IZG4NgLb_NW-PyPArqn|}* z(Ke9#)^I^E2N^@A#1dPb(vH$!r^G;5rfSEk-b=Wtrg$Ac-|zJ+dN~)cWbZ z(_d^xW+qP)%yF;r_m9u2@71VO2ZN+Yu6{kq02BF3e@lK8VixK;;}%SquEjX)QaI%x zs4z;Qr2Pv_aHk7(tp<+R6s?@CqN8i|rx_AUP5Tmqk-vOfMe%xq8 zCgSwcu&NH+4tcJn%(tu!N&8HpJ{W{cFtvd0ti#1rNyMj=r$l>gw1il5F}MwHQhpe9 zfgqIe76wfH+~$+#7{$@Ik&1u>D#SYzjF>;IsnI8OFLAfq>tt~cB);d0?-5iMtxpsN z?j~>rQ@#4WVdTz6poQ)|zjE z$Xd*JQLjrQqt)bAoj+-TS0Bb}i3;LkVmEhFpieZDNAu)->X5w=0co8)nTIL;8ZypC zuE*0x5~i2|o!*i}hOD_3ElMnz9&Lfv2aX{bPXbhvgV~q1Jt&m7pv7U3NiK3I>d$L| zCtyE@;jIFYXS;B_3TwU}&MUzXtX*JGEPrd)vuv4!{7&1SD=yyF5=3ORB;p zpPA_9t2ej*{^bVK-If8cfm~D!3|e475i&}!1lX&Fv2ggva9k(I2${7^3stp_P6X=W zYxAq|m_bpDJ6Dm5Du`d80AD8dM%+?BE_uXNh7=LsFPKc+lk#+C?1iR9ZYUu0Vbpc8 z|F5dEkL&qf|M(|O4zl*cBnv;5yOffobs9FD6efl-B)YMTWx3zb*Kx4i-$ZsoW#uN@ zx^ZuQ`g&}Uni&>;*_5piXOoUb9rAm=K7IS+=a0==-_Q5`dEZ>`>v~<+^?Jeid21Cf zXTi?5a-w?oK1jnhk(i4+L+gY6aK}|HJA&U}z3rd&w~X4_S}fD3Z9wnrfhb`fl_o_g zVvpbS z3jJX*9B;P85jk&7N&?yoZy{fqJ9!!~hfJ06@>%j&Du0~Ad1AHpzd3xsaqP>4iC|}>`6{8`X-5o`3*_?+tFVZ z-kf9GjUx|2U4CoXlc`MC22nKfw3GsF*cY(DJomxDNahjg3Qx2H!8(`dBN@!Pa~ZEVYa(-{c9E3bW(9Ej^( zC;T?3&EW0YTbrQ51RWIVAN*fs!$})ogdmBQ){+l3G4H|0p(Taq>3z|1z6tUP!|)Zz zFb|2{10ZZOsqq6F?Tw9ax`v79zlWP!fwCAub{=0~L#i2f5zI>8m6oQQ>~1Mdq>3@` z(Ye=rmQ+XLh}2)qTYUj0S6JJ!@HcnfqOjL&v@>=H#S_hQ6s&21uh^fsCuN3zG;dQ5 zt;H598>c+V%7CmZhs=HgE`KG}^RLvuXjwG{pSyycoQOwJ9q#CVgDa(mngBhEP-*|z z7k?#5>fJ6SZS`nXikGw*9Y~-Q9!w4glKGRv*iDb=C*Qaz!&pP7n*xEyY|^3^gka-O zjkGt`V-1(yfu~b8NMIO~oXeF#-&H~HtkYd}F3Ou{=b$?9Tn+iKH;#gpU}Iv1~?Go-wa22*VWutt2%^8W`LAr9B>(?Fi7WI zXHS?WK1<+Y`{E5Gc_2Mn^iLGI;_@QT0`WTLo0}YrNBRL zL|lQgy_40>X%`EdLb}nU$0k#9XyZJSIgZ_tq2$Uk8d^BK8yC{-s?OVTvFBryJDpn* zr>4VBGp+OJ@<1D$=Z|wtIXR>$n!7WocfX7scR~wWHar^2U{c%K@VC5-PW0}*Q%~fo4t}WXQl3T9?jiu z9YR4(+|4=1FF=^vMedRa6#q#3UblPxI_DzRqk@LDV{;PfyEVQ*fHZY9cMZ|1#htm{ zMrXWKG-OL|Iq3!J5OqAE6_(>(5=HtBe?PVEX%_@KP_L}{ zg03_<_+xRD*Bb8QfRbZx9vdYE6Vdd8V+PD9oI1(2E%yze1YsF~Ci}7~jogA*m&--k zF0$qY*QfR%f6>M(DSuTj0zn&hel`)3n;H*()`&@=9d~*`-?Gmz*;1 zVt?Jqjg+fko4wh+iOtp(aitG{isQlctRyPj3n&#WC##SdF{zzxxucZN1>D&J;D@2u zIhcmEbo!iFq8<{Bc5#b}^H%oy)H-3|FGs$)YJt~-g-AIxb z0<`f?qi9%@uBr`k|88>7C0m2n)YHX5x9u4UMAqfM!Rni&Svj*e*|Uz?8%Gq2dY_p{^bTm3#<%ZK}#rn_?m9gZxpybrpx=bKXXNA0*AGiO(Og zslA|^x_vkMf`}tA^AoRe6W7pL5<=*rLSkI0(Qy2!T2^6I%+Dus#4JizaXRTW5e(wA zZROsYTs`k5zBHA7GyuxY6In6;CA&>K?2q}?yVP^x9;kX{ZRr@?zda4a4~G9v7N6J` zcJxFPTZVHcz)Ok-y-cGj))wBkt;~P(zx-u0|AK>eHJfZo^+T7|t-AsXpP0B_pwj8n zr`Nrxg(9Q~>SdIzrct;rxhoE@SA8LZSo&WCLSF4=($~VD%oo3{OcGzO zrl3>lm{x{0zVSczeEpyfpDVKDNDLdnNEPv<%nOu0bKmOhKR5MD*aa7~rN&(RvRu;H z8{oscFT-PAC`}AYYuf=lwlz8VP${-mbc*az(k8Zt{SHsGxp~cMK|YdZuJWK_J0n&l zQpZRyqmhunlJI9Xavzgtl^i(;X6$qDy{tX9A5-djbM1x=#ma1Qp}*S^*c;cH$wu&E z!BusLGhGDm`tilk1Jgex@le7^HDd-kHs5X)bnkjriXZTKb4N$Ine~gKNXWMb#lI#7 z5n2^B3skM34dYtDb#M(ru3)7{jLc(c znGrW}XUR*h51=P3)^!iSt?8reJH7JM*8%paCg=xBhtZHzf-Kapfr5W@F8I};1 zC~qzsZ`R@Hi(9GI*CJ5a=(;VoY=C%C^YFsbVfNO5+&7rcbQ|d8b@L?;ia#Sgq=vC} zC%&B9RD65Oad<*tBs50~RR!MgstyONIA8lk&_?e$m#|?fb?9;rZ4N8;wOE3A(V*x< ziKZ+1Yrmfccav@xCTq6|ADMH~ovM8IgXHx~fQ&QLqGis$H?v>1LQIny0_@VZVXbA? zIu##$H)!&ir6)msx%YU#!Cm;?rYb+s%>qtl+XA3fscV7Uj&K%=h)Xi5wdYUMrzIZN zmXMY29mFz_{USwSSkLlP^WCbpk{7#AO>`11W`H-w+@7}Ua`9yfDr&F`2_jc&N?O^r z@vCyVZyy~0Wnr?aE|@`!$y7UWN{GYaNrGOusYvWV5Toy33T5Nd!B{u_xNz#CUno%3 z&pWev16uUczct1_Th z+X=O-pv61Ose|wE2EItcy4pN$w5zl~K=@O_?UGJDwqdRh!08yCO)KW_A`8Z;f(nkW zPVE5eXbV;JjHX!IHWk@+bPi~lQzvq(EayHHjStsbgV5G`!tziLnjZm$AC{9owjD8a zA}q~S^IMeUrF2`vwj9@bRR`|`1a$<5CI>FbeW__vs5JH6O{n|#PQ$)D;Qh7{{cB9w zukZrKIZlap8qvjv;&oIZkh#Ybxp#Mt!@kO9EWx1^aGR+YiAF{w+k)S5-|5ZAn@t%w z7AQfCnAmB%b^c&~1A)55&!z?1CR*p58(W&R6V<`*?3=BMA{x#GNKkli%F^lt^8lLx znPEWlW7Aze?sXBbj=pu3 zniwKJ{<7(f!8kqOOnxT?5izsmczCxPL$SC=Me8hbUN}HZ&O_tad0sA!;_phQz$%N$ zw9d<|5MgW%Pn>-KFZg}x^Te9DHzshh9(RT^`0#nERjj}F#il}7+4MC}rNzOxdADjU#aF zPVP@tKf*T=8HAUWPkGS3W<3jB@fi5(NpAGT4qC-92FAA5|5B3)zDJ1ovq2~tUUmmF zhs=ihTJgGjGKJb-p~D)?VVY7|q%E#WbWTVFsXAEB`L>;qdl<_rq;eLq>CNuq^3{|( znE^K2$(p6+z{wEe9zz5~J^%;@=2TLKiBu!M^*#=xX3#8?UfKR-1R0`rm8e3)1LGKJ)eVkVjdm3G6&WI<%(-Fd5k`v;qpym#@REXg zg@(yWq!)DXQS}9h-g-S*PH8qWk3o_p;;wcmdv%Rd=WBw5F3`g+bLMYz8y(81AN%S` z3S7+MXXUla{7s{Us7u-S<3Go((?W~-7{;o}FtdZu&15`f{S-dIo;>XHz7eYd^)!>m zL^dk3W4(Lj>eU*><<+o3%0`;H8ahtxqbmxx*GcfKAsuM(Z8U_Ay^u6kZPBkXJ5J@O)#4KA>Yq)0ptI1(p)Dg;-`%|24dktcIV8=J#cwCnOwt0N;QO<76I+*GK=@_T7NoTHiuz9k~+tUK^XS?)^E+FUJ6oMEB5S-3U{Q|CrUmL&^Me3kkiL9K17U-;E?RXGCpE)JIHni2F z5J*YVRZA$YjiTysES(62z74u~YelS}a99r~*p%WeavR<6K78n?ERF?$@Ge7sM$ z4n|vjNpr~A?)RSX(_So#FaWjg=26};Xuv9T1V?Hh!Mm}VACAQnX zZQB>|=o985nIkbUHzFb?V7uByTzo&+?C9zrO07e;f9@N@*!F5{_Vh(ur4ZCp2~0r} zX4b1o)nV#np>xj?O}s?Su*Z7`+bcw{v#zG$^f7sqg0-*qj-*>uZ2{6%py2|U%B~8C zq}VB#7t-X`h?PnhB>AuL^{3BF|JI>b?;E(j+a<=3V@S5*4E}4uoa4WAr_KgWq){sz zlx?uLe2ZrAvf|9~xij)xOyc51`gZUFH)|Yi*m9{7B^o8LC?_XpX*)z(MF9TtqGwM( zUd9kiEFydQO5*;OS*@%YWa}z~V30qmMDt?)!&|#u1{e~XI$_ei%LB#p7BI8}6k%-k zZGYB$bJ+iU5-f#QrbzXQM5d{O@n~??jVYIf&BjvxDRwQQy$z~rTsq8o_I}(D@hG1p zmzxf$#uc;&3j4t`#^JIAY4=DhhmgHbeaYdOPR_f}`e2`X;23>V{vN6nO*Ef5%fEvkRGJ;Z_sJ5}k!j`1;AiQZH!BlDG{oz^Ymf7-??N|9Yfdt%`VV(O?3@ zKJ_0@O1N{x#R!*jg2fXBj?s1c1feZ&%~6m#H2CkwGC#mh2R6nmA-WPk0>j*y@+Yie zn8zi?mf?+5bppF-?w0}ugoj|~sp8p^J7^*72fKHBA~>;Gcm$wSId5yG<8m)aS_uG) z7OCoAAL8fdm0yzZgrFFT;C2AsjoD#mY}EUuZq@BOt=+$JON;8Cf_>=55{nr&j7s1$ zZRu^|;pqns+}j%e74(HO&A;Yd;vR~xshI)524_(Hp^>0}V-HR6Bp#l5JX6X4_1+uI*m3YVvE1^&Me%!!SRiC&@) z_<4H!diM1j*SCK_Ki`1D9;6PF-COE?5F@QFRu?` z=R|o$&hX-YPK)^{I#z%2iiq~|?aM!X`$qKl_xAPc+t<%0($71x@AQa%{ysBi4DgHa a8!(^`zj`O2@*&SRf``2`^y|07|NeiNg+6fr diff --git a/gui/resources/icons/scamper_cutout_sq_64.jpeg b/gui/resources/icons/scamper_cutout_sq_64.jpeg index d8f4937b19feb3852e3a2b4633393a7c9287163e..730e6d8ef792359eea153ed6e89a767929b14533 100644 GIT binary patch literal 5516 zcmeHLX>=3U6~5YR;|r4(Z-A&>jBN-QPGO`OS%bA9jgbw8um+M4 zVzU%O3&91N(6BcUXgMJPhcq0*4qFMwKNu&48d-vXV z@AvMVqc_oW(JLSwIm|H(1Ofp}#t%fV!gnS0j2pn=coC8S@Jbg5Arp}wuS|gm1lV&| zjzGfqvk|`#!;26PjL8TQYfv{0`zE}!h-KKX#fw=e=5==>=2}sRCRv&yA`I&xhC9m2 zIcIo@j-DGNv`URysWYN2wN`J{sI6KJq0w2@7OTbxLU?s)BK!>Xj&r)}Iz7ePczbfC z=+)F?9+nMSRVsg2Nm2nPt#k!^s(Lc0(kRs`7&5dzNV;limT=NFjNc}|{g?f6f}w2k zmknj=vS1PIVMa_3(UsGGRppvq>#|Vtq4~s+dTYHe=%ZPZsP}pOVQalj&KtKP=7v>r zf)`7-D~gB3Ea06@9&g2_v^4wOov?|Cde`YKfzffoq;;mCdc*L9rFdt%HoEf%7M?v zdCNO8kJMrbV#xazn?9K|*{XUR$hTnuI9p@DXhTFRnU zm`Sxoq1S5>8MG#aQL8oST}Fe!Kx#YeIQ(Ij^t))z4q8?+Xhfsa7_#+)jnb zt+zO7oz_I_Epmc#S%(EeJ`(qV@sTyOYD$oKg@z5M~$bmwmR%kUH z9GGJqsL+2ESBmYSsQxobe(tfd?GVRj0SDucmVBbCburMzKoNqB6#$OekI)QC@Pv%UNLHzqqGE1cL2h5UY9Q{wgdS5Y^Y**Au(=zHIaA&k|7IE zWl7MVbcKTj<>jUElhPC5-dX-c2B#F9ttY0RKafV@Aq0R!4QjhGGb$d4RW{z zu?+vPQHVDq{zV8KM0}1LcedkO9IoLpcen&usH&m}W8+ShM9pK^`51P2LOztyqf8#< z^P_#?xOPl&xRJv?Zyox^H|}JcO8duDVxNasZx{{^D1&k!zzKE0fEQR$VDHC~FjU}t z;WPAec>QwJa-tRkF4QQ70Qi99^?}<1l)=`?ZP=~T@09yUdz z4_c$qhrb69T>|*X->Dy12Vnjl$D2CG^4U=)c^x((DuY<#Lc}oi1YSbnHYc3 zi%pIh`1$e!|w-~ePKfgS83K?Vpj1fmQv&0kSI{sa1%U*OprKe33xpy`0`#ya%6byGMiP1? zkO=SQ&2Uc6-Z<{dQPbgYpO$x`U|L=>AwQsC^64v|*UuktRJH9v_U5-r8^oMbBv9Bs1qyZDD#h=R@fpFPknf1*Pd2MTaf4MrgpizMQdjwmn)5NBle$koUTMw87_d&N|VjOdqF=xp6_;vccF z5{3%DO|E`3v$?`K{{2&ui1|uixx{0=c}@Pt>XKP&wzW0B^jWy+i}Pcao%2-=*tDXd z?a1CSf8697yQa7{so{ke6ZRISXDFN3vZbCg`*g4GzF2pS^#1vzL||IKJ^%31w#z-% zubnz))Qo9;c3s{;>>I6IeZ8{6YHwTBQvJaNdmmzBuUma{dLOCVJoxm(e$$zqmkyZj zls_!24xK6OeW^Nf4_58kKE$|Sz`j=&XC1j{zBYdO@$UPlAt8BE+%f@|+3|QYazRr- zj&A)}YM;|g?6}&ob3=3Q3Cr3%3Hk0tJLcW37(8>{&+UWqmfUJy*{$O3oJYEXoF6~A z;s0TAie?kAUvF*M(zJiyxZHUM-|TBXw`ZK=VBnCr@?+KBPbaQgb||Omd|}IpUw^nL z;pVIBSJeLa+L60w@3Vnk%NI;KJMiJx6Ka=Up7-ETZeGfaY;V>grvEpV?bXdC`jqVr zH*d^r^DSulL!-9z(!%YR`u~l+cNsn8^Ot`jNS8YD@H@L~1HRjvT>$O3`1_pg=ki0! zDw}*9Jy>(l2Mq&f6aI zBk{Zc${jQOql4`68E@T})o&YQKh3P)^l9U0xPR}g3xMXi@#p?^*>m|FFY%G1{ zPbFqyAF%6BYMg)ls@eBV@2QSC=_S9Jk+9|Zgrn(A-v&!(?U29xS&L-mW_1HWZ(UP6 u_II}zPx7x_L+HhGrc~|eWjj3ZhlJmrOiG(jePiU-!)H|XJF~V$&;J{_A-kRc literal 1032 zcmex=LJ%Z3brsR%R9! z7G_o;!OF_Y#?HgR4g~z%+?+gu{6a#4{DOkQVlv{wB2uD)f)a`nQnIr0^76vsN-9cn zDl&5Nav(z(fm+$w*!eg(_~b+cMdU~Z{|_(-axgeBI50CRF)#@-G7B>PKf)lzz{tQ1 z@&W>|vU6~j@t1sE8a!GMV!BF)Ie%)-Db$i^gdxCWs*pwEGqV4>KdsAmmTHK=kX`kZ8{2NzbhkXea3tca=JmOe zhXPu9Ci#C_b9uY;#?_|BzTQ;a_SrXDt0RD;38LqlJzQ28VTbcWmGk+8F^;8~u_MY?OzwxbU zLsq!!>$kFNx;rmhHOU@5cJXYk!jv6Tp72c3U`-HWwD{m5dZyL0U`}iD`S(G;lKwN; z9jxiB+-|et(_^dY(S>pkJuTVgj{m!Cw0gyrHBZimY@2_%P}Zu-d3&iD^MhT}78n22 z48O9b=A-h*$?p=_gTG%rFVULhQsnq{+Fh;VC!XIqR&Vids$$fpsWYB`Rjn^#EV`Yx zY3Y3y&8s`M{P}SpsOERg^(8OwSA7+Gl(ll2_Ss4IZbkNNzo^Bp!qT!<^Vg)UD<)Jj zPAHz=lhUwHtL0UE;@Vk1Gp?9v7OeR-V|7#a@$PWu9#yW-4-?c6HCW2=6>#P6T3fz3 z`+1&8nMD7Z=Qks>I}Ke@>}9h(RrLx_g@}Kx{(Ow#0J}=Nb&A8z#R1YuUiU+R{C(ulXPBSMBYiF-Auyq`|r*(6;(F>y#CJdYX7zR(G*Gfkdpq|6d{d|D5>=ri#EM8yc5r9Ij8xL z*)uzHzwh_`?)`rEyZ7ALl)E%DR`!exf}mJSmdOU55%G?B1pK$8(Wk)UdWpS2u+bsd z=l44KA`TYT`8b#h^G*l~cfPi~E4BrG{GO}g^`89j7NY?PmcRbR63miUXIpmka~Bi$ zWXFZTPbz=5E$QiJt^d)xGZ z{fV#rwk6?`khCUP`lnls+Nyiq#}nq?dAsgzly`4$#fR;iQ!0{byUuqSLVati=WWXC zV?Ul(WqW?0ack1)#;*;3*Th>79N9FZ(zapV%I(`%zrf_z4H69tr>C5Z+PI}mhTLhz z!$ys!);Y%DA2wHz9Sh>$Gwe@T6~q$nm(7c{RBYbUv&uKX9K71o`(b@~ zJseXSAs3R#O<9}1TOvapspO6J=Jl1$A?U&f$u$Yt(KVj8FACYmpIWhTAZ7Qg=*k$w zHpkO}-EVEU`E65Xq#^X!@A`jz8?@_x{W5KhgJrVNQGW)wA%S z(vQ=>?QVFXrskj99LewAY!uyvbxxZQ`Ro^P)0ek9F1BBJXzQK>g!ag1bFi28 zT@UUGWtOZTypvP=Y2w12{;i1~?MhIdVIGuWfi;I>yly$odL5iR?Dm2BgrL;)u#aZe zasuq&T)an*+-&|7fq7Ps+{ek4U@}co)qI1ePGeT0K%=&4rC#KL@MiDmjLl!+bG;q{-k^KkKAyrp3b)pruC& z1;Ixt6roT^9#YD^ewPB*>2wN=P!I$P5NKeXN1(%~Coor}7~(K-0mje!1m5d`MNZn` z4GMY$0e*O7d~ToBI!f;e466Y2P=slp0+(Y7w_7njA|RNH0m<-y9vBg@gVn6CaRG18 z&v52q&LhknPr)*y@xGwHNJ@ug6kHMK2G9WL6`#;$rp1~&8X-#H;@v(e3Wz-cDe%rQ zu_la7^hoK99|#B^<(+^Y$z1{il+{X^yi8CWp2eg`#QrJP%kV5Ez0! zbaG0i)2YH4H93xAnV$z$Nf(VDl}N<`DgswK94x2_0%M%0N~a-Fn&F(NQ>WC>YJy~R zBrZ|047J$nchg`xc{lCi6h4nja)^Rc8MzicLddZ(OKuS@I6;6O$>BZ0@R-BSySY4p z7S+VHgiZ~l&|w&%(c-Ex&v+;4;BTs&~< z(3EHK0nqXF;X_ubuuY^r{tQFYf=hK3OrR^Q*up8fk}a?0AN@*}5FaC( zzoYLiFg-1p3k0LrEuP9D>9EMLaEKQQVezn-zaj1^0J>o@W!S@=Uw0pjJ&MJfmzQA= z&pms-d3R<-LAe^~prcoO1KStB(S1Z_KbKFsqOV=)Ynn)mPd<*{qZ_wUoF7F`2%?JvLG@x^mrrN=>0Ff=U!{S=B`1jRs6 z|9j(s$bw6mJ2%G+ayh%M-Bn+>oLzjt_7L>_tHkh>GZx^prwC))|gaoyr!W|mO`}^Ol6%f|Ywq*!2fy|oKcB51w>*=B z0RuQ#CarA#T3df}+uNAKlV&fAoSwS#vx?wcD7yL_IC3X+xK0zzJ|-P&gJyz zGb&7W6cm{(C#WY9UJt$rK)AI+#dWk4MCDA*l_jU-;i5jAdE~iBhC3+`n zbfWjy``7O5es-SOnb~=EXD32KO@WAjiU0rrB9x-6CIEo$yC4Ai;Jz_*Dz^MT<*cb7 z4U`W)-2?yxfRdHc_AuVf#H)QLmmGRWTf-0-j!uQ)1PZSQ2YM2IHkXu_lE=kiBPd2# z%8`=gEmLxRj(x&o`HFC*fh&MD@a>P_JchSfS(lfYll!jUz4uYcLkqSiUh_9>J2$$S zcVi`ATF-<(QG!FU7NlU#*+gI1+&HM3=1VVBkcZt!2CPp=hY(Jzzg=@sPx z{?LUV!&Kam2aNI2zyn)5ic+bZ;}prwOP+*ifWRl?zf=$04&#D8dEhm1=@SaF065e$ zD^?zOX%%_$4r&o9DFJ2;*viA%0g;oa$_mU1mw^NPAQ~aPH!+nPH4>IOodRGp%Un|Q zzGL+%VL%`(l^GOFKN=W1ugwSf_$sm})LY$)ZxG?7jZ%o*stLMBb zAAF(#X2HLf)%2CoXi`Zd=RX)s`7;|4l!4NW`FM8!uL}`Jr`v|DAzbHM-?ses%9ln) z@v5^_jA-s2e`=J#M;94XGcU=_AjU1)bnpdJCjF)hYSBjVj{ycjoY(;iR|igaC*30r zjYeY9!ZO3MzV~Q z@f{|3XtUSC3|xVL@F~~4xzFU$(xPhUq{km>Z3fj1Pr0dV^5C)`|R$Y zsqkEwDMe*UbL~l|22IjfIVsxZB}$<=UPnE(*uVjGG@er4CFxTcRekJdLiBNFa10+% z7aNShuY1QW1~F#eJjC3JijAglWO0M$q(;1VrH8bOZsnVYFfQ*=*BKcq$-tXEXWwIn zg1Cl7vFefElx25!N?y_V0z?jGrrl#JDM#7I@rtj)bz{Gv6@0 z#lR&6lXUfsL(VAX?Zp{>!E|Qxr6HnX26P`Th)*4FY5hxJd3?;T)q$Aq$;4wvlHewLn_@Uvo>$H^`_%uP2hBI zIn8Qe<+AUSe8#BX>Q^>-L{^s=hK$JqammM#Z1PN5r0Nd*iug72Z1RNEh)Zv0+4E02 zSOU{=eJC(gUVls#zt%CDIqoybxfmr_pZ52Mg6JLi-y|c7RC5Pzm1=MFhQ{-TNv3uBv*|GO`_sf6Rk1vaw(s`d#3BmqLvkh z;kks=IS&n^QT&Bb5rT$r5SQchar1R$RY~#0LA^vt?U{pAAom&jgRg(y1al|UuH`4L zbZDGv!a-A%RPOBnZFTW;56N%jY1OYE~^y%(4yBuqKX(yhRDa$1JzD^0$vE&4A zG*%u>4hiH9k8E?hgAp?O^>bo(wibN9`waezXYj_W=U}>aeN68&Gc<40|IvuxMe;L} zq`hxMoV_=Ic*&H{fTj}*0C!yuvgalSF)-3h)ZoYJ3pw#U2?G?$pH^5t6C%Uf&+UHE zs*(N5Q81z0GyxPPXEJ5lACfDOoGv1F88-dp>&bHh4Do@DtbIG$Vg~e$oWQi>Z{KPp z10xCPKUNs+ti@BX-Gl09shO)vfQ7ZtR2zHiuM}^=xVkuEyG;`&Uu)C(rZ27*v$*nB zPf)B1U~J7+)XHJG?QNX_57|qf@rr3F0yE3@!K2bEY^sq=gcdl2>Rz{Q`HG`&?W3lUODqq8)?5kCq1M~lz&)Z zFQg1BRe#XO&xe|-K|V}d7R{83{MRF})?gN6*!)?Qr7V%Q%9>_e#=e@JX83apMP{6& z4t1aqDbW9!VNd-rcXQ)u|A`4*N1bUoUi!Hd5XO;Fj#1`>NE%+68?q+G={JJ~ub0kO zv>FoI=Lr)7pk?}v3C;(?LUzz~Y2Z<^+fsg-mi>r!m>&K$uzI}@etMHo%Md(#x&X)qh5Emy%!a z?z=PpvirJdn`k>`LR>b!r>Yi;omVOJ44jWQVvWd0qEk>_8ShK4#9p*{tIyEdw1sDp z%Wznvnk1pvMqbQT7Ts!*0`<4&A9qqlhZ27$^B-|-hz~gaNBBnvQIDfa1(9#_5P!DG z`3$Qf2dGCnJrH)%)+GFi758V1FpPM)R*(4>J8gF8`#dYoE}TqL^h-VikoS3qe0-!y zL_~fhAwjiE2Bt1WCIKx|o7^kvCN51Rhe!rLVHij~mqI_3&~+aamN*7i+xUWrewkVJ20F|yVl~k;5=t)^6OhN>?y|Y zWA|?p`Oo72HXCc4M=r*G@`viwkI!kWT23;$P}9%lq3pm|P~iUS#FtQx#7SXa-EG(T zm#Ut{SFOxjm0^Wt5zJyDD7idEJMdE3W#}u8ba@uM=J~r7vh+(2R1eccZs8u?w&GH9 z6=5U_fXJ@y)kM%ipq!}V{4ptJ{3r5Q>?*Z-duY#Jt;6Vab|YV-z3Jf8iUMY6PKvfCzo1bXyb-z^LhYp}=k#YtKFNJ} z0U4rt^<8WH4dmcZdyqI&BmDKxA?^ff|GDcUnt!$&1P!j)w)CApIvT3Pz1b{!h}m93 zmzFV{@m=bPhtPPvP}o*YH%Twy_`edNq7K^swDY|7lVlMSIq)EWqdosSJ#v-=Byrf) z|B7?5!IMmK>^_b}zib0ZF+Bi5@UKb9ldq|)xM6aq^A4Np!$TQso|wJae5N3nN+=`t z`OrRb#ey-<15n1Jmzt{0-JVJ3Z;vF8G%9XoxP}Jq;`}#GTNf$hPH~~gnbWX`s!7v% zww+|p&aCT;I%uLyxx;`KUqxfhkq|w>J4nz6nNFl{#@T_xt>j(D#a>O4fL;`Uujoi= z%Sh-)Vq?hR4^t3Rh78QJFoeT9EbkaK zt|sh^pp}h3GoHAR7TtL}(R*a%&GVACe8x8oFc%C(qTIL?iiVV$Qlc#SjU{Q9Jqx3G z*vh#5^!F$FoJ#l#nqPm<@Lm$%=_s4Ge44fJ-<=d(7&jpvA~`|V_T3pi5}$|;Xb5Hw z#jZmQU&B$t>nuAv@(hgenbYmWoD1Ndo&_c(C}ZhgFWq0Gl|v%%>bxe>jI!M8Ku^H1 zZrRqM>*KW#WR1}8#tpFWRup!XY@J}E$6s>ZBLlj5Ffl=@l+VjcmkX@Tp$DJ6q4w}4vPc?zctjqe@9kl6)PKorkj4= zNTAnVMQ;?eL>g|DqkFH=BE^}}(n3b6qe{WMU?kjRbw!aE9QX3In5j_VRk^FXA&aj| zt4mNh1p(`0q`D+47<;tmhKrt2kaI?E1?eRX%8|#b`saZLb>hBpf&OSTPm$&33k~J7!3$omqNjYk04g|>9eZ7m%Vr({>!O@ zw<{I$e|Cr1u%*EaK)K$+y=0zzKL$7$2&<&5F^@p&2UQqiRH?l8{@3l4Zq;}?^f~(f z8mS~~j?-0jwzk`aJ~$fbYo7zVn3kv$i|JU@^+(V@O_3%A`u23M!g)_yiyV<@;f>R& zz07pkX##`tpDQCF_{3C^!1*I@i#MXx|7F^C?s%p${*E`>{LcR)AuRKDjI=21O*6{y zmX_#1g=XxtPf^};$gsafn(=g{hcpY(*0a_51Z%F#6I0=Sc;G;FkG2tQ`^Up|wwkl; zlUyC(sh()fo~PiburrcC>`!)Jj zx&<`)X{_1mX`1m&vyO6z1_XO1vB;rC@iZbfDOfkZR}k`Hu{*|{K;*_YUjIZ7D~6Y` zBl=URG#6^R2#bA4%MmvpECi2{$-vUkCCVb=N*?M(3jRC3Hw~aJDGFBo=s@`IbooIp z${nIO*q-bp?eU3YfF85!m8=2zfQQOH{bDm6^G8Hd63+);Wrh^-{BeMOP(jy!y7bL( zk4e9UdYyYCbFe?sv>pA;K=TBN*3IqpfxOxJw<#N_mPi3PC%jC1FL|$Yd?`gj^Xg~d zE;58vi4c4s>xn|64_v(l#X}ar-q`OdaTcS>3YJti-!bW^@1Ur?_flKDge1fKb%vef zUVX@IHCO5;xNC+pF$4*;c~`vuEc6((;4;MH!;d&1MqQ~8M15m%*5Z0|i6?}Qj{;o1 zAeZR{Er+zL6^(fYY?JQ!i$S6;@e34@2pPEKW^Q{JvCgDdT*5J((L-J1SaixG1G8I1 zjV58W02~8AAMS0gYbKB0WzP##ggi2!n#ts#9_70 zdN5bFXLS0F|GZ}TA)E8R;vwkj*H3XBwuA$+hpel}&~-5Jg|CsZ)G>CE4=&4*m&qG@ zKi|oGqDTYU_I$t&lu8$YvrJZjzO?qjXo2M8@xUIJpsky%UA2iod;!}aMQgB!ccKMP z_&;0$uM$gF?Mi$p?H)4%I~5%m6#no-ci7!m=L&l6V;!`>34@Bw%7le_NFQM3S$a~>H*~SaipHj~o z?A@9_9oH3}ZHe%A+yY#Y2<7>RrMPa*(o;m;r<_PCxdYD?V3U3sV`5iytPv|K zCCUf;{s6Huz)m)P3i?>c)9){iqq5E@2^*$+B1tWsD}mr8Hp4fS^S+m0=KL+ra6S!a znFS8E?Spq4i9P~VmUONUCWUZqo)oB%@Z>?1=>`9)lw3Wu{@mN#4Mk8#0hN)6T*$-B zFCQ+#lqD0h#%b`f=l6A8IMQ9K0xab6rZeACK1u|_|NECjDgSN;Z_*zxScy(Bgc~>a zv%UZUDY*IVq7b?FH?2TOb2}3=$WUu!y8U@y4bEI%>5t#=BazrVp*M#@J^B z@BMW^|A(3Wvf-@1iU~4EHoD2wZ zhb-%qvZp51fWrMfovV)WAozB$w=rZkydqh4Y<*mMeOjRbs%9mZ?z>B)YCjZiJ8Xf{ z=a@&;el5W223WZdRVVUJYvJF>{v&a4E%>P1%(Xfc?=ltmtJ&Z7)EfFr%A- z3-Py7!euzUVcx(w91g#+|I0=JT3Yw;vU^K*;$9bAG9sjI*(kv~xL}nw6u8gQLF^A) zg9{PuM*da-sgc0&JA(88r2O>D_MLY)yCn`}yC_=C+QhWW5KQdpH_=_ZpCm}5R+Hpq zB^G6JvQGg21=k<*Ush4nU;GG)egZxf%#{QQ$4}tbY*u~S{+gez#njW)Js>?KHyGL;+(Yn@ z?nTlv%?#55UAliSk`H8h?l*XL(PaS*-cBvx)RsXOZL`ed|ol@{{Em&gqcGsl>z&j(=HE zFNl{;e?^3va0D?-ZjJ^ugiU@(scB%#Qn}|4%|hrhe7=DXYio4|iFd#Kp0Va!NXMl4 z3)$Y}SFMLsjDmsIDhfZlp)`~t$ikUGL zqjZ_oQe(S&ILp5J9$#gV)2kuj!vA7T>6#mwsSI1y*cxE~0(KpMfbsqGS8nQ7lu6wY zl|1i$U)A*W+St?N=}9of#3Ig8#lao*=#1X#EiJIlt-`&wa1%K)1}}=#!CG>^DT4o{E_l z@oS1e%Z(mxB^B$daG$vi^U<&A^GikoFTZUFo^fR1l+W$0)Sz!LWfP+OqJG9OUImkag?#6~A~d-7z`wKZa&+81E7=4I;r~ zA@hemUF;G<_5`XcF#1zD%)kc?ro&p;Ljd$?D)T?pVi5H#XRO3|*O42WSsnMpg6YZQ zosH`+z4nr@q^{}@lM#xjGVSUV3>4U)Y%BTa3hlLE;ojHN6;teLTy@eN);?&{m`ehD z>ZlwZV5S0Z01*k2u&O%Iry%JR(&f@r!v{=XfsbKpd(VPciLs027Z z@WEuk=e-rw<+i_=P^wglX&vcF7KzcsN8bQ}4#cXSug4Ids&7ccRXSzmn5CVE_it}m zYbRNgfyy23J&yzJ6x}8HT}yp@83ZNR#QnFg!}ds}QA1PMPYCZ+0|p=X+-RgwTs(*K zj+hovn#u>3tzkYkc&z?|gD64`0Hr20fCS^FUe9tAy{S`j?2KdFq)V|ga{)skkFr5N z#P@0Zct}oXVA+c|uLCokCj8~w`Rz1XAAzxt_#xAjWlSzEo6e;=H@zW0$B$oh@p1j? z&tnFgik^Oy6}_CWP+j^BS13;vAnS~t|!Er%`^FXJp#erLiC;u8Bgpl}f0!T(@o&~E!H z1qhSnbd!PQ9Y?8y!z&nytZCPLnF z-048&A&)llbGw>8G2uv7Nh=`*f|QC68PjAl#uuo{Ed0KSg|_((;iz|LYSumPQ&}zj zZa4FZ0mKpHuZ-GvvS}&D3|OZ!JcFI*Hjn!I*Y8L?m)j`0dMXQ0v>I`4sNpTF#(JJA ziNO{wE37}Xm~nrnHwN$&FW&~YRqvR?Ko&N=f(5CNV3(%j21|zVZ(%+h!}kxSV3AJ| zN6F9?J4hw>^`v7@@VK$rrMEa2Y`c5Z3XIK^dV~!BDjjtN~?2pikHSmIY*T* z?k=i~`g%PWo@)$1P5A_?HU)Mv=tDv5czzB{HnZ#d2Fgv+M`vq-cr7ItK{5juoW`_% z$JaEv`nPS@SCv${3tq9KrTXBXq&s~Z^`CSR;BmNQcoml>e!zc1_7j4)WGrZ^u(2VW z*P`6r)Js-RXZ1e`g31DWm{n#CBmQ|)hq7|L-|2!PI2R_;>EkKD@_-&u*t56LE;;P~ z2VZ&BymKK>E&Y4{V;yOh5lbrX;MX$)#lFazNTb&vzlX~aO)|XOoqsc+ADZ!-wr$}q7 zI0^5oCfM#dzFhj&twoshH4X&zUG_WsU3 zXK}M8d|n9A&dCk{Knx2Fi~s-whZumz!P^pbg%sY5nUT@j2s8sxsg+WhT!Ltqt0ag- zCxcGiwY2baR*M!_!>D;UiEA6r3!hxpG(l` zzyRfkEsRhO;k@4U!pUp$<38xkr3DSSekqTx_;##QD&1eWq3!wDok1xCi8k-m6;Eqd*g^C{-`V|BXSTcgfzo}D$%8*R2(6o!DOqb+)yC52dy8^TJy~~W^SOn&{u^vsO8nH%6LR`b#2n9*du?{Kr1v2HRgZqI}C-5I8I)6>3f z%W`}rCUxnLIMyB5ayl7ot!Uv~o=BPIfr^!h5)WOP3iccT-o82&DoT}Tkwi(7Ou;Aj zov0-vGBKYV#TL?pssKr{EHqOsS&%s|Qk0o0;)=<>K6c(Z9wbPUXi-F$CRb>9IzHLL z%Y$RHnMy`15N#@-94!n-0+ebA!t!8w&?rGV*)j&%#}4sUi>17Xz~B)I_{1kCYqcsK zm70-};gP}gP^y!tbS{@mr7@@s1_dH0n&k>Ds-q}0Q_K{@9Dx#zNG(%oWl9BN=0p>f z=~_OS4E@N<{L)lH;VXKDW<&+32UUlvsB{k+H7$)gIzpojS_Vl*68hT+O(fi*)Ch@2 znXVQ|f|f}X+9{(c#G+U6s&uv7QjSE`sp0{LX~{5-KzBop&2LsW#) z*isga!a&7L3X78{r6jVvq!c!b%l1OOq-?R2If^Pwq0yoWk;F^|$vtF{$IB}bg&!{p zlP+aI3Y1RaNa-Sqh>f!7ERK}P;?hP@e5#hgu0-XdvoceOA(co(=Zd5(DTOXYMHChn zl~A}`F_$7mJy|pcTSQM}vMp3%5ieM&PD9~x%F@sz300*?vN+6w^ZdfY_+*C1@T?X~ zxE$3=VE~^zSEfkUy@p20(j*JCs98J4BHU$+Y zGAVSnRGcVI6nP~whQ)iuu2D+08K_#~mjrc$TEX_TXoXC(EY$QjbIC}Sm{$P`Mxn!& z{fl7Kk%Fn_Gvj5&-qgQn;%xzpI%Htnunitw@GPXhIt)iNgZciG*T`D@lT#qbyGhi z^QXj6z6Dyws6rQO02uqe`HKO?I~<|WRvRV^vb}HTU_aiWr#+_;02_T+pkJi!TJH_N zlu2|Fw&_4!(m3pQEUdcw4mPe~%9D!rSpuZ?#2m`X>uolW;xE@s2e-P#*@J^mOy_cj zF7$oMp8_~5n`~AAC$Gx!pES7i>pjGTj4ER7&zybKJ!cEz@sFQ|*td0#&1;Wa zljoE@x#>Ey+LJz*()OE!Thrl>+611tm;U@@ZIXrMxRqlzJKbjEHK&HDO;;AopH@%B zX0B*-F!moj>MqFePsMK+r0x!yPpBo`@2&1}*LRg0Y=do#=UJYEEV+v(P&xiP$6EEQ z%yy2oS(YUjg6|JD`r5m}zfGo>nw0tZ?QvI~z`^&L`kAc{DaJN^cvkWayD-2fgO!PGqR z5Iz5o*u5Pi2jN-xF+gRru?7Kgy49FIa2O;wI{@SFn9djDJwZYW(1BC4jDw56!{~{E z<~#tf00H{?%JL$tUI~miK=6&U0aw6{DggjifCTg-kV-@E_8AzM@0)h>uVMP5g9qr3 zD~Q8rDU|4@ZQs`E&XC69J~ucMWM0AnJV+3Off=NG7d8{Y?7pE&A{d{WU=35CF~F{@ z8WpjmYxc9pqMwLB4(C0R>9=sak1NPV@b`Y*;0}JY0)!=bkH*hbu= z?k%64RW;u`{>^R!Mo_h{d_M)04;}J3h7r&)VAZ^#GV9Ln*3(gWH8*=w4-vuI@mpgy z8J&$)?&E6iCS0XES10;a?(p7wjQBXE3s&C&cOC&GtNZ*YaO7z<&Ujw@*wxt0S6D+^uBis| zV8&V#sPDLzG~Z=%!oZ3@8>f^k4F5J3V}E{X!hrLN8Fo{#gd8RHxK;Fo))oiB?{cex z+NzvAU-%pQO-~Em^{w-JmtgE$EZ~pr-0_5LWlrFxe0^76@49KnNVGx2^ZwHG7nNOD zKT~IItbK=P$qU1iqNz>Tl=c`?GM-p^*>H5j=_Z$+>oFb4?-lOZZ(tV|T%`3}iD^uB z{iSS~;mNw-=D9tsF_pL&c4_YpM?qj-DcgOh@%dx7ts3g p09TNQP6RG4B%BNQo2%1#(0Wkw<=$AnoXT{Imn1`_jP`IwdM# zTjibl98ZQ;0-EJ{y&0HP0Nlby$G_C^p;0;6~?d53J(IL%oiTfE_-H_B`WhN;~6QOcw zjXw?ggRJw~&@9{X4D+@Dd1NJ&R{La~hl~$DB+cXCQEn<6fKWTsP&!rjrV2vE*ot%< zTZoww;|yG_?};2z#EZ(QIDDZtd$)AusOtN8R5(8qp})DkaVV`sN{Zv{s#4yo1WRi& zH#IrfgH0E`FIUJ2^fB~wVYJKnAao&2lK*UJhpIDVKWb0Hq)I|v4?-o|8&@s$IeUS} z_ea-IIMB*Ed_9j39_?6T6T~14-%lcp zi(QfDF`CE7P*_SF7A6w4Yjrti?Bsiso-BC{F!}iVtA(oMfrY~tjXFkEj-(Yj?X0YA z|L~-tbAaFdqQh|daNEREMh~~}6aPxCXjjF`P2v9LzVxCl6Tq;<)6m=g@THT9al7S0$@o(|+oZn~+e?a;uxl6R|UBRH@}mzE@VEX(+QicB|b z7sHYx1j5mH@(9^#Xu@gM-V$ie#NViH?nCLuy!?+az_NOCNgIB$0!D*Wjv4%H)nP`-;TRQxq_MCfgHin* zL?j?H+5gZ-6OdW(F-0EOc=ztPeWD@mw@a*DsX99enemW%)(iBT*zUdvHSBg^zmx>$ z`Tf`DO@`g99w~DBp5Azx_<5PHIZD~(%`F%`5+bMeE2I%J^>f%2go?*ygyoM3dfu2i zCvIE4P9P}p%X7#sd$dkxNL*tJ+IPsux#m|!3+WqFNRtwO`)%0%!8cOLT_ui}JNsO` z#37rhLQ=ooWKFfAmQ_Ke!ig?lxD94a8j>q&s7o1Sb-RM^LP)fiXODLuy4#Z?h4;ulf?53AWBIrz% z?l%L_!fbfC7L3MNjtUS=)Pep+uLyQRSeXeTT<9J-F&D}p6aEpkV+zm?5r2p6{eCBU zreC~LfmPR66J`Sqh@UGMpva+cC|;-fT}kXE1CR4A1}YHJY*wII7|x#|ft|M)gC=Y4 z>~XqCgPXr@U6TaN{fg~)i6PKCPky+FQLj~jye0W+B^UZU7csFFM(8yz>h4MRE52?a z)HLI-neZq&Zqz%!6)w{1%5O1a%Rq^=myW^NTq=I8Z}Hx2d{|j9Q=OW9G)q0|;=2Ry z-P>^QHhqxn8?d>;a)kSB@ebGVg5zdzL~f`s%2%;m=+93k=%9~o{g&axy#m-JNpA7Nb#yq&|N)LtuF2irNq&DS^}QqfFR}bJU#zqnP6cgzomLj)Aa< zQG4fkQovHjmgoLcTZARBhk1(lQIcZMb|S%J-~NONdqcF#KabFA1R&Xm49k@DlL##(|}XGF4k?lo*;{>x)rq-g0+&#TPwGkk6{A#)oL zAODfNz`|e*^3a8IxApq4Mr8ykjTH803TMUM@2=`m*--Kb?`pS3H%Qd_a!ke>d^fMy ze=U;i6C^5oO%5B9!`nkTynFuTaXLPk{Bwj7e?zaguQ=uJFr;V~iFmk;J-#(9bKGSO zF#~9TLYsZ=!~}O~`|o9uR?@3-*h$ZnuDTvfw7$*bD*`|1;dxr#$|EaKZwAGjwTlE6nW)S2^1wBTQeOkWA?GqHQQMIS(QW{*cH zoCP_GrsaIv_|#jWHE`-9dt2ZS(v1$Sjc9mW{O1WN4r_*rl}@e8JOWR_(v7N3FiN-F zT=((}fK#Iler>(y3aN{diD2+S0vODf_AuqVrxS?ERe+x7DyXNn<7uxEcU{e9LPoO- zq6T>M_C%*qVD-G)-jzw?Q=4$v@C5izzM)9@_wm?lC`N4Mr#exp~u-UCG2HoCF`Fl=ul#2P}&T^^PqG)3e z7Hhl?PMt@HoH`>0JNo6XK8PaVQbJISgyLC(YiC&sKy#Ckqyi2GWB(6C#G(kq{z~Iu z41hOUZ*;vf*?xMw%1x^+EwkH^co2E)Y8?1c z=A~h_9v|$fbokgQx1x-HmG$Rw4^Yuyt;hYlI(7P6zD@>fF9*?bR>x#vyP^kF?BOkb z`N1$`oQ}?L0-7txhew(83w-P_)m+iQXJbDkK^ap zrwK2iY){2D%Ju``OQUH|jr!I|W!!OPn!9io6DV!4hm=v(FBxSJbMxD8C9)rkLCdDu zwMFwsmUMcaNkpO?RUr*L%kit=I1{`m<#sPW{VRaS?n!Bmc7Q1Ek$hh2Fv}5T`?uRt z;=%5HdzA0S!_=mTw=pT;PN-pqGMws{w>?1)dz?TTItxy7=Hn%H)=Ej?XY_XclXUDD zl{23dysL9eDt>vje+F){C&MP}`(R(3Kt2Tv-o`e-RXdVNL=uP;SEsox`pX{V=( ztX03Hh*RwwNOQSW($?-Xe`TP3uH{eHK0>iDq=xr*;ju_+4qPZ%LpVaR9ETM_Z3~(xE zdXubUOMwyt6drn&e}9UaLdJl~*}{S}w@o3fPS z0Ts)zk-lX7pU_v`Agc8*r=j!)CBe6f{|PgF?}V2Zp4I+hq%bF_JMgqIWkJ+;E=bu9{I&3Ajzv^qGi#xZ{rjb-_VVn4Z0UzK z858Tn7ekbQVZ8LI)@M;>4*IQb&HnRaec_~2nrAPb?$jT;ll6-fFI0)QDnw(DUFh2= z^AGD{TXl5d8R2N=j`p4$UofP++@91;fu+VAzBJOd8PAl|E^1x_4hZvs8q0 zOug3xH0^nHOk(=Ni|z2}piQ7GoO`IeK130(=WK}82j{T^!qFh_z>MF@0qBxr^x{=q z;CsR&U@qsYx8!~JA97#Z{$k(jl_w=}MADf?lyh>qfyvqW8`LsvQIN=OXj$Wz2SyX8 zv|=r7QM%3nLpUkJzRLM7KeksoZoOhrE;zUMMrPv=*v{!6o2O*Ryjo{dU5d@aN^nfU zK}U#)o`bUAJ-sr`4_#8Ucu0p$_Qoxl9^Z&>*46Q5;w^sHJ|{cRN4iwDsB6F`5vu3z zw%7Om)oBFJu*zzm%6$gK;*!~}_g*%J(DCc{n?66;fP+#W2-qsJLr$uRK@#|y<9X>FjOn3>%afIA_c*q$%dMQ1~C)=Ar3oQLAv{IP6+{DGF)m;FQ#mv0 z1z_?ef^*`h)wED{nvnanjc&6#2@H6@HjlwVVGHPXFT^J#hRwb}8@5>4gA(sgjf!8z zkpuxcN&j5%ZlLGpBZQ<@uw=LbJKJwoZ`<#@aRZ_n&36Gc%vh@0$b@BOQ8LPFer}z3wGV zQvhJ(CJZ2`$RD=1irxNknA8itBBa3Yk z@~f1upT%E;D`P}=c|@NPoZeSlMgF>%=ydvZ68er-yWLy@WynTL^jav#jJN8ayp}(n z%U*DX!w-gTZXfeFvb(Ll+^DX^;E_w>kW8@hwkfqylF>t@3->?CK^RaJ@42fOYxbd; z4-IWHyjDU&%b4@|pqB8$>#drH;K`1!s}`8ywV*EHMceIg>nH7Ua5MC&Il>5@; z)3G=GX%C8i>eWgP9IaoAv%DXJ{e~Ff$G7Y7{w9yqgM1Hx)tf`kbaQOxsw&Y4J~*Q~ zVv2A{#loQ_Sh=?UDaSMP2L{UA`ruZPLAhvMEY=W?(FAgGW_1C`LA|sTaV{?m{WO~eQQ4w0c%lX{%P1;~*GYq1%F&#F6Bbv(Eu^!8JrP<A% ze91MTK%@}UR5dCl5h$$R#^rlB0t~9ldSUV6>61jjIe{~e#a>77Yk)PyGT96d6&!&c zT5~gzh7Y=RdGf(yunOdErZ>&Jcu9&IA9TQWRQbMK;?cx6l-DI1$ZzP+xw~XJ6a{;)pIbRw_#zM#^x@dUb~t z!r(E$;r&6L zqebxug>RaT-DSYUs8r~w$jrsFH;PmYbUeE2I5Ql5`TffQ=L3+J6B9G>YV z)x+`-B({-aTY<8{lOpwXpL*j@W9;*iK%&;BoX2y-@{tI6M&vZL=YbTs9~Vf+4sT=d z&THXsu1}_~++ZYm1Ftvi-^W2e{oznvGtLh);-b`xQ~u9_mWm zGZQiU?q8$LC~g!HvnL}n)-HOpRkd4~!cBZ&6?=JmQ>hZ>*II7gFEZf2`9N{0u|>z2 zuAy_5nTP^oH+!<*jDl2AYIWhRpZweTRjvxi9@&KpjWY+b8ty@3qJK90} zWQlk_DODDt6O0A@@^sca2|1fL_7uOy8&3_(hUJ-I~=Vf@Hy*xxT;_p<9Y0P-j%pMx~z=_GTD4@6%tmcifoXd=doJ zLnd(4*Da>?O3Qu|Lm*D-N(D@JbV>x_Dwuy9E1ibb0z<BpUNAEUgT&40&T7X(t-=XOLdh<}9|qIV<#zuE%b z_j~+J6Gs6@e%dcop=Ps4kPFQ zxVr1ZkCZOIP=k(MJ;<6-ETn1GQ=tSI_cxti_6tOJiHbo>ZEPg{+<LK+~kjSVZPj1A_`{jj`cOT<+@IZkY;DcUOMZ%j~TTPWXi|gz(lC z3~oRXM+I}&{PPbNMyA@+-&dqaaBr2}65BFp>PYUi?F;1j@atP{B5iiO8=|1}^apJk7`K>(%n$aB1^x&wB41oHcWp_h zt#Mq%_Lw}XOI|)n>V{wsuM!d#P^&cTxsxq@LX{n$zAij$w)2`fZT}!^H9#g~D3~Jm zr0UMP+GE-Qpq7;tWdDBn&d|=|psibCq1TiCTr6|OsH;`{pnOpx@PHLIvMFkZ`pW_A zXgU&(6aW4YwGWsJs8cNmpfmBej=L!S?|b$35L* zfzyIdTnn+%Xp!?<=MwJR%uSR3HBo~BO7m%97Da=%SV+BNJsCmoL|RUsL=T}qCLe$6Ld6M#6))NE+90xr(L-n0tE3Y zaoG>u$-a|D2R)%dXFrg=qS-!*JZ~<^6gk6$9U5a%7Vydc{&0mPiNSv_6N!z%ULX^9 zuFAqVn|ILBvCpk=nHkGdmUh4C(&r)Mr2?R*VLMM=zvPvCsf*q8g)yQK^)(S3eD~)p zMP^0e5m<=_4AAv+iOZxpTn4Ry7LdSZ(($H=ka222FH{$cKLu|_;h&Kw#sfND(rMTY zILXpScS9AjcFb$QBZxG~Oc?mKCi#06O{;iZTTi!M?`mv{L=cqY($Vm0E%J%-<-!K! zQVLniPQ@jPHxY{7(4fg1iwpdw7Md_>$OjKL20x5?Z|RJ6wV4N{Jgwp+C%8^eXu+Rk}Zg6SbNq|Yv3I91(xUFr$R$)Tgdzt ztqETXbMVwh;g!!ZN{wq5FghITVuG~x!*>&J-Bo23yiO-o{y$kSdgHuH&qJS0B&_zL z&zQVEMZ-*)QEm#d13}^f?pcpk>({4$f1fQ1xRgn=polMXM`bqkb8m> z#>GhTWBxf{uF*RQjNpE!@Cls153j}^H`Gt7iQ7=%?SZXFy|wyCaiypka!CXhkhrw~ z_v6RUgEV+f=4lw0*Pj~0$xPdb5a3R6wWb5zO6A9fPhxeI(~x9@mSpX7VWyXJsZEMt zq=bO+56DbZ`_45=*O_o<=7oamj7CiivHv8!rB#bZ0X3{$j?yyJD0E%t@iw8yOfbEn ziz{F{e~6iaaX#-{ddQI~j0@%v#u(N@K~iz}XijY3;QlToS-qYk0;o<;k}yc3 zs@fBJS@0i#KhIjc^1=B9a`=>i{o@?*$x11zyx;;1ewodBT&;0_zNtI)7w+r!{}uO$ z7tzeLJ7wNa;e+f4T7rfL-2-{5ZT2F^{)b#gw9L}27FNpTwEtp0?p4b_iLY!_+1gV4 zT1<|k#B#2fuf+r^c8xKIdDA;6AKH{&Zr7`%Xy5^ijQiSLJdrQ1G`M2&ZLAF*>*~Hm zHBQl!>;Pj{XX*_%LZv_Jp(dD$*miwV4pv=uzlQoKEN&MIKouU6xsRRH5Gq+eKp7QY zOjYQwcI4sR>9YlBzfW4yfpkQL3gt_e?YiMrnO0H?aAK!HK);e?W}(OPMx`)nl7NP9 z=m1H)W^o}&M}>Z)aq(J5^KwJ8Vg@P3{=ETH{(~}@!%SnMt95FFs^ha9p|#o4{p9CH zo9h0uZ&Adlv8|=horwrZxPzAR`{lxbu}3>n7D&TcYGNx--+XTY?8qfz-%eHi4R3yi z)Q>qKnhblnSG}4f%U+^#*517orf-hMw7j`CwZ+8=%0Iiv+t<=@5S%Rs(aa$-=!mrfgfj(uRy+&Aad zkc`%vm2#D~S}^ys{v}9IzHkCzzd83~!!K1Q^%-|ExDEEeDjM})uH^w%JK7C=4)RSEV?cXyNPoM9M z6&!k^iIVEs_GzbM3LoAsj{7-ZN@vAhOSzQnc^B6FBDjR2&0CUWwjCQC&%7S_nesF7D6G)xThXn- zgrK>&vud}Qj_=L~AAeK{QIR3>nC1Mi&1y>PHrVfsZefqjE^N>u?cy!dVjC9U|GrR@ z2yXF$itT}~6hcZKi9xe$RS5?5RhMyu&cyP+k28*Lf>ieH;K7&NH6MPywqMC#QLvrV zL{Cnf``DZm~BHEyl=k7y}=ZZVOrM@h?3BLGEC4b^rHWk*Z z*}LN$#a?Q87IeGD!1m@uBYA1im|@sIAoSF|rTzTt|8GIIYWoHU`>Ba^d^Ff?64g7N*_>q7kDSAV#gOep z6TseESia>mvHK+ibxjMsh>(Tr5h%#@`k%|4IJ6r1(mnY!Djb>GkZ=*vpY#s*_T*PJ2Pq}$-QX*K$=ME5J=Q4&itKPoYBaFlo4rPM!I8dQD`Y;Z3t8-ln%e-)0BcPP!l=a1P*;{?kR@r*(E0mBz>m3gmDA@KNliCAg={Y45t zcKma2j&{WBie)VCZ#AjEwh&3$zhcvzT2Vyd+K5xIFuns4)-#YiA9l_2jdv^6l4O&_ zfi9TutNnM;FT3soDk%IcyNpzKJ4VBKfO6ofbDl>&YV&XMCs;E|mwIFRjny+vAk$af zRj8}JpIvkJxp~0m+c1XkSek76q;i9{n4Pg%2{LYK!!3U!!3j zRk?m*cN;CEi2BbWkfEVef!m-U&89BgTo?f1)vckG`8<=zf$psB&5W4tN=|b(46z8o zKLRUx=bn(+u1xgboD2?add>IT~UUo6>I+v0fSpT8~`9 zFWMo~O~;;czEY@2A7&#=An^4^=aYILfpr*hwDr296Vt*O6(mv5@XTrJg4wVBL-v!> zyrMT4zkYV=p))huHZ^zPI@^^QOHw&K?v z-bJ&F`Z>W6-|gg6krq@N-V@_5Z@I^q=v{_yrV6xqf6H2$(*~Bg-fsqib}=a)%=%PK zN{xZ-H9h6+GHYxy-2QU&VTcnpb$Nl8hm#s@Q!?zXEU;b``n&nfgh!v`yxRYr8f4e* z)@8e=x>FrF>(vD4?IiR}#TvNvsB^D&2>0@Lh(q<%%~8pdRa1HvD69kIvHoc6!1hN$ z9ko%wAj{4>aR=sXU&rS$BRpca($yJAC=ENtuOrSShHvT&;nny1oO*K;ZpAZ@soE0% z|04;S;i0ylPU)HHW5l51IrC=BfedJ7N@V`adicrw-LDTJ411w@)b{#cOY7NxO8-@4 zWDnZc&Df6ZNDthe<;m9Zox;#dGh~?POBg79x)kYxHFfxA#kBTKp4VsTwYwGw_-Jx? z&duvbw~9UM?W@)|#JGN)MgN(_pRZ9ZUyXwZZD(BRJu{Gx7bAi^LAwD98tyGj>Xkb}@> zB`X=ffi4DTWzRT0n{Bu;PR_(+ttV`b?wVuxtJ zq37Ptr2yN=(W^!umgKpUID3Ot(@fc&Xq83+&?u}S;ff*RVLUl&cw{c)6lSTB znRoOLL%Pvs!H2Z3iz;u>rl-OBn&nY@U|X~ays*OHpF=ul5|a--ZWGI=&myspIHp8x zM{TA~HioaxW7cZ^s98w?*q)5JibluE7oME-DIIvVAYP60T!&N=gITSf>Jv@y+s{;- z*My%eJea;$7il7c$v?r*xk76`Wc-=q&b1bJ5&J~|y@Ahr(%}fSFfCw?SU!oxz9(Ns zD_;>O2!BO>$5(g@PfkNVs4fQ~amd5VwvHL1BxfJO#CT4eJ<^ZIl-%cmk=Lq?LRo3{ oPnyUv^4-=NMR7QE1pJtX1tY4;B>5_a{BIx7)iTnoz&S+y7tf%=FaQ7m literal 0 HcmV?d00001 diff --git a/gui/resources/magaox.qrc b/gui/resources/magaox.qrc index 73da28c51..a51a3deef 100644 --- a/gui/resources/magaox.qrc +++ b/gui/resources/magaox.qrc @@ -9,7 +9,23 @@ icons/arrow_down_128.png icons/arrow_down_right_128.png icons/square_128.png + icons/home-circle.png + icons/stop-circle-outline.png icons/scamper_cutout_sq_64.jpeg icons/recycle.png + icons/arrow-right-drop-circle-outline.png + icons/application-cog-outline.png + icons/camera.png + icons/arrow-all.png + icons/waves.png + icons/controller-classic.png + icons/tune.png + icons/power-plug.png + icons/cog.png + icons/dump-truck.png + icons/crop.png + icons/flare.png + + diff --git a/gui/widgets/camera/camera.hpp b/gui/widgets/camera/camera.hpp index 7fdc5b6d1..893d55771 100644 --- a/gui/widgets/camera/camera.hpp +++ b/gui/widgets/camera/camera.hpp @@ -8,7 +8,6 @@ #include "xWidgets/xWidget.hpp" #include "xWidgets/fsmDisplay.hpp" #include "xWidgets/statusEntry.hpp" -#include "xWidgets/selectionSwStatus.hpp" #include "xWidgets/statusDisplay.hpp" #include "xWidgets/stageStatus.hpp" #include "xWidgets/toggleSlider.hpp" @@ -54,11 +53,11 @@ class camera : public xWidget roiStatus * ui_roiStatus {nullptr}; - selectionSwStatus * ui_modes {nullptr}; + statusCombo * ui_modes {nullptr}; - selectionSwStatus * ui_readoutSpd {nullptr}; + statusCombo * ui_readoutSpd {nullptr}; - selectionSwStatus * ui_vshiftSpd {nullptr}; + statusCombo * ui_vshiftSpd {nullptr}; toggleSlider * ui_cropMode {nullptr}; @@ -767,7 +766,7 @@ void camera::setup_modes() { if(ui_modes) return; - ui_modes = new selectionSwStatus(m_camName, "mode", "", "Mode", "", this); + ui_modes = new statusCombo(m_camName, "mode", "", "Mode", "", this); ui_modes->setObjectName(QString::fromUtf8("modes")); @@ -783,7 +782,9 @@ void camera::setup_readoutSpd() { if(ui_readoutSpd) return; - ui_readoutSpd = new selectionSwStatus(m_camName,"readout_speed", "", "Readout Spd", "", this); + ui_readoutSpd = new statusCombo(m_camName,"readout_speed", "", "Readout Spd", "", this); + ui_readoutSpd->ctrlWidget(nullptr); + ui_readoutSpd->setObjectName(QString::fromUtf8("readoutSpd")); ui.grid->addWidget(ui_readoutSpd, 4, 1, 1, 1); @@ -797,7 +798,9 @@ void camera::setup_vshiftSpd() { if(ui_vshiftSpd) return; - ui_vshiftSpd = new selectionSwStatus(m_camName,"vshift_speed", "", "Vert. Shift Spd", "", this); + ui_vshiftSpd = new statusCombo(m_camName,"vshift_speed", "", "Vert. Shift Spd", "", this); + ui_vshiftSpd->ctrlWidget(nullptr); + ui_vshiftSpd->setObjectName(QString::fromUtf8("vshiftSpd")); ui.grid->addWidget(ui_vshiftSpd, 5, 1, 1, 1); diff --git a/gui/widgets/camera/camera.ui b/gui/widgets/camera/camera.ui index b49b944de..82cc047a0 100644 --- a/gui/widgets/camera/camera.ui +++ b/gui/widgets/camera/camera.ui @@ -19,6 +19,10 @@ Form + + + :/icons/camera.png:/icons/camera.png + diff --git a/gui/widgets/coronAlign/coronAlign.ui b/gui/widgets/coronAlign/coronAlign.ui index aaa59090f..07c08c920 100644 --- a/gui/widgets/coronAlign/coronAlign.ui +++ b/gui/widgets/coronAlign/coronAlign.ui @@ -13,6 +13,10 @@ Form + + + :/icons/flare.png:/icons/flare.png + @@ -209,7 +213,7 @@ - :/icons/arrow_left_128.png:/icons/arrow_left_128.png + :/icons/arrow_right_128.png:/icons/arrow_right_128.png @@ -1519,7 +1523,7 @@ - :/icons/arrow_left_128.png:/icons/arrow_left_128.png + :/icons/arrow_right_128.png:/icons/arrow_right_128.png diff --git a/gui/widgets/dmCtrl/dmCtrl.ui b/gui/widgets/dmCtrl/dmCtrl.ui index 33d4b9a71..931dd5678 100644 --- a/gui/widgets/dmCtrl/dmCtrl.ui +++ b/gui/widgets/dmCtrl/dmCtrl.ui @@ -7,12 +7,16 @@ 0 0 471 - 258 + 270 Form + + + :/icons/waves.png:/icons/waves.png + diff --git a/gui/widgets/dmMode/dmMode.ui b/gui/widgets/dmMode/dmMode.ui index 959e005d8..d74874156 100644 --- a/gui/widgets/dmMode/dmMode.ui +++ b/gui/widgets/dmMode/dmMode.ui @@ -13,6 +13,10 @@ Form + + + :/icons/tune.png:/icons/tune.png + diff --git a/gui/widgets/loopCtrl/loopCtrl.ui b/gui/widgets/loopCtrl/loopCtrl.ui index 00fa25bc1..e84bd5c99 100644 --- a/gui/widgets/loopCtrl/loopCtrl.ui +++ b/gui/widgets/loopCtrl/loopCtrl.ui @@ -7,12 +7,16 @@ 0 0 925 - 325 + 344 Form + + + :/icons/controller-classic.png:/icons/controller-classic.png + @@ -350,6 +354,11 @@ + + xqt::statusEntry + QLineEdit +

../xWidgets/statusEntry.hpp
+ xqt::gainCtrl QPushButton @@ -360,11 +369,6 @@ QSlider
../xWidgets/toggleSlider.hpp
- - xqt::statusEntry - QLineEdit -
statusEntry.hpp
-
diff --git a/gui/widgets/offloadCtrl/offloadCtrl.ui b/gui/widgets/offloadCtrl/offloadCtrl.ui index 704402d98..8c26a9998 100644 --- a/gui/widgets/offloadCtrl/offloadCtrl.ui +++ b/gui/widgets/offloadCtrl/offloadCtrl.ui @@ -13,6 +13,10 @@ Form + + + :/icons/dump-truck.png:/icons/dump-truck.png + @@ -557,6 +561,11 @@ + + xqt::statusEntry + QLineEdit +
../xWidgets/statusEntry.hpp
+
xqt::gainCtrl QPushButton @@ -567,11 +576,6 @@ QSlider
../xWidgets/toggleSlider.hpp
- - xqt::statusEntry - QLineEdit -
statusEntry.hpp
-
diff --git a/gui/widgets/pupilGuide/pupilGuide.ui b/gui/widgets/pupilGuide/pupilGuide.ui index 0bdf07b42..0f251c18c 100644 --- a/gui/widgets/pupilGuide/pupilGuide.ui +++ b/gui/widgets/pupilGuide/pupilGuide.ui @@ -13,6 +13,10 @@ Form + + + :/icons/arrow-all.png:/icons/arrow-all.png + diff --git a/gui/widgets/pwr/pwr.ui b/gui/widgets/pwr/pwr.ui index 8eb380bcb..f3d866368 100644 --- a/gui/widgets/pwr/pwr.ui +++ b/gui/widgets/pwr/pwr.ui @@ -77,6 +77,10 @@ Power Control + + + :/icons/power-plug.png:/icons/power-plug.png + @@ -247,6 +251,15 @@ + + + + 212 + 210 + 207 + + + @@ -330,6 +343,15 @@ + + + + 212 + 210 + 207 + + + @@ -413,6 +435,15 @@ + + + + 212 + 210 + 207 + + + @@ -600,6 +631,15 @@ + + + + 212 + 210 + 207 + + + @@ -683,6 +723,15 @@ + + + + 212 + 210 + 207 + + + @@ -766,6 +815,15 @@ + + + + 212 + 210 + 207 + + + @@ -950,6 +1008,15 @@ + + + + 212 + 210 + 207 + + + @@ -1033,6 +1100,15 @@ + + + + 212 + 210 + 207 + + + @@ -1116,6 +1192,15 @@ + + + + 212 + 210 + 207 + + + diff --git a/gui/widgets/roi/roi.ui b/gui/widgets/roi/roi.ui index 9e57af05a..9d388688f 100644 --- a/gui/widgets/roi/roi.ui +++ b/gui/widgets/roi/roi.ui @@ -7,12 +7,16 @@ 0 0 491 - 400 + 426 Form + + + :/icons/crop.png:/icons/crop.png + diff --git a/gui/widgets/stage/stage.ui b/gui/widgets/stage/stage.ui index 4e5037a24..331086926 100644 --- a/gui/widgets/stage/stage.ui +++ b/gui/widgets/stage/stage.ui @@ -7,12 +7,16 @@ 0 0 433 - 294 + 361 Form + + + :/icons/cog.png:/icons/cog.png + @@ -66,8 +70,42 @@ + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + go to new preset + - go + + + + + :/icons/arrow-right-drop-circle-outline.png:/icons/arrow-right-drop-circle-outline.png + + + + 32 + 32 + + + + @@ -145,8 +183,39 @@ + + + 0 + 0 + + + + + 40 + 40 + + + + + 40 + 40 + + + + jog negative + - - + + + + + :/icons/arrow_left_128.png:/icons/arrow_left_128.png + + + + 32 + 32 + @@ -155,8 +224,39 @@ + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + jog positive + - + + + + + + :/icons/arrow_right_128.png:/icons/arrow_right_128.png + + + + 32 + 32 + @@ -192,6 +292,9 @@ + + increase stepsize by x10 + x10 @@ -199,6 +302,9 @@ + + decrease stepsize by /10 + /10 @@ -236,16 +342,78 @@ - + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + home + + + + + + :/icons/home-circle.png:/icons/home-circle.png + + + + 32 + 32 + + - + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + stop + + + + + + :/icons/stop-circle-outline.png:/icons/stop-circle-outline.png + + + + 32 + 32 + + diff --git a/gui/widgets/xWidgets/selectionSwStatus.hpp b/gui/widgets/xWidgets/selectionSwStatus.hpp deleted file mode 100644 index 4cd97eb6d..000000000 --- a/gui/widgets/xWidgets/selectionSwStatus.hpp +++ /dev/null @@ -1,117 +0,0 @@ -#ifndef selectionSwStatus_hpp -#define selectionSwStatus_hpp - -#include - -#include "ui_statusDisplay.h" - -#include "../xWidgets/statusDisplay.hpp" -#include "../xWidgets/selectionSw.hpp" - -namespace xqt -{ - -class selectionSwStatus : public statusDisplay -{ - Q_OBJECT - -protected: - - -public: - - selectionSwStatus( QWidget * Parent = 0, - Qt::WindowFlags f = Qt::WindowFlags() - ); - - selectionSwStatus( const std::string & device, - const std::string & property, - const std::string & element, - const std::string & label, - const std::string & units, - QWidget * Parent = 0, - Qt::WindowFlags f = Qt::WindowFlags() - ); - - ~selectionSwStatus(); - - void setup( const std::string & device, - const std::string & property, - const std::string & element, - const std::string & label, - const std::string & units - ); - - void handleSetProperty( const pcf::IndiProperty & ipRecv /**< [in] the property which has changed*/); - - -}; - -selectionSwStatus::selectionSwStatus( QWidget * Parent, - Qt::WindowFlags f - ) : statusDisplay(Parent, f) -{ -} - -selectionSwStatus::selectionSwStatus( const std::string & device, - const std::string & property, - const std::string & element, - const std::string & label, - const std::string & units, - QWidget * Parent, - Qt::WindowFlags f - ) : statusDisplay(Parent, f) -{ - setup(device, property, element, label, units); -} - -selectionSwStatus::~selectionSwStatus() -{ -} - -void selectionSwStatus::setup( const std::string & device, - const std::string & property, - const std::string & element, - const std::string & label, - const std::string & units - ) -{ - statusDisplay::setup(device, property, element, label, units); - - m_ctrlWidget = (xWidget *) (new selectionSw(device, property, this, Qt::Dialog)); -} - -void selectionSwStatus::handleSetProperty( const pcf::IndiProperty & ipRecv) -{ - if(ipRecv.getDevice() != m_device) return; - - if(ipRecv.getName() == m_property) - { - std::string newName; - for(auto it = ipRecv.getElements().begin(); it != ipRecv.getElements().end(); ++it) - { - if(it->second.getSwitchState() == pcf::IndiElement::On) - { - if(newName != "") - { - std::cerr << "More than one switch selected in " << ipRecv.getDevice() << "." << ipRecv.getName() << "\n"; - } - - newName = it->second.getName(); - if(newName != m_value) m_valChanged = true; - m_value = newName; - } - } - - - } - - updateGUI(); -} - - -} //namespace xqt - -#include "moc_selectionSwStatus.cpp" - -#endif diff --git a/gui/widgets/xWidgets/statusCombo.hpp b/gui/widgets/xWidgets/statusCombo.hpp index c6abeebfe..e7f221266 100644 --- a/gui/widgets/xWidgets/statusCombo.hpp +++ b/gui/widgets/xWidgets/statusCombo.hpp @@ -169,7 +169,14 @@ void statusCombo::ctrlWidget( xWidget *cw ) m_ctrlWidget->deleteLater(); } - m_ctrlWidget = cw; + if(cw == nullptr) + { + ui.buttonCtrl->setVisible(false); + } + else + { + m_ctrlWidget = cw; + } } xWidget *statusCombo::ctrlWidget() diff --git a/gui/widgets/xWidgets/statusCombo.ui b/gui/widgets/xWidgets/statusCombo.ui index 4be82e71e..e3a50fee9 100644 --- a/gui/widgets/xWidgets/statusCombo.ui +++ b/gui/widgets/xWidgets/statusCombo.ui @@ -7,7 +7,7 @@ 0 0 399 - 58 + 64 @@ -54,27 +54,40 @@ - - 0 - 0 + + 1 + 1 + + + 40 + 40 + + - 16777215 - 16777214 + 40 + 40 Qt::StrongFocus + + apply selection + - go + + + + + :/icons/arrow-right-drop-circle-outline.png:/icons/arrow-right-drop-circle-outline.png - 0 - 0 + 32 + 32 @@ -82,27 +95,40 @@ - - 0 - 0 + + 1 + 1 + + + 40 + 40 + + - 16777215 - 16777214 + 40 + 40 - Qt::NoFocus + Qt::StrongFocus + + + open control - --- + + + + + :/icons/application-cog-outline.png:/icons/application-cog-outline.png - 0 - 0 + 32 + 32 diff --git a/gui/widgets/xWidgets/statusDisplay.ui b/gui/widgets/xWidgets/statusDisplay.ui index 149e5e766..79aede094 100644 --- a/gui/widgets/xWidgets/statusDisplay.ui +++ b/gui/widgets/xWidgets/statusDisplay.ui @@ -90,27 +90,40 @@ - - 0 - 0 + + 1 + 1 + + + 40 + 40 + + - 16777215 - 16777214 + 40 + 40 - Qt::NoFocus + Qt::StrongFocus + + + open control - --- + + + + + :/icons/application-cog-outline.png:/icons/application-cog-outline.png - 0 - 0 + 32 + 32 From bf1b7bf121de516a9345a71f75b0fbef3e7f3358 Mon Sep 17 00:00:00 2001 From: Jared Males Date: Tue, 22 Oct 2024 20:22:46 -0700 Subject: [PATCH 18/24] some formatting --- apps/pupilFit/pupilFitter.hpp | 109 +++++++++++++++++----------------- 1 file changed, 56 insertions(+), 53 deletions(-) diff --git a/apps/pupilFit/pupilFitter.hpp b/apps/pupilFit/pupilFitter.hpp index b0e88732e..3095fab82 100644 --- a/apps/pupilFit/pupilFitter.hpp +++ b/apps/pupilFit/pupilFitter.hpp @@ -16,67 +16,67 @@ namespace MagAOX { namespace app { - + /// Struct to perform centration and measure diameter of Pyramid pupils template -struct pupilFitter +struct pupilFitter { mx::improc::eigenImage m_quad; mx::improc::eigenImage m_quadMag; mx::improc::eigenImage m_circ; mx::improc::eigenImage m_circMag; - + unsigned m_rows {0}; ///< [in] the size of a quad, in rows unsigned m_cols {0}; ///< [in] the size of a quad, in cols - + int m_numPupils {4}; ///< the number of pupils. Default is 4, 3 is also supported. - float m_pupMedIndex {0.6866}; ///< the index of the illuminated pupil median in a sorted array. - + float m_pupMedIndex {0.6266}; ///< the index of the illuminated pupil median in a sorted array. + float m_med[4] = {0,0,0,0}; float m_avgx[4] = {0,0,0,0}; float m_avgy[4] = {0,0,0,0}; float m_avgr[4] = {0,0,0,0}; - + float m_thresh {0.5}; - + std::vector m_pixs; - + pupilFitter() {} - + int setSize( unsigned rows, ///< [in] the new size of a quad, in rows unsigned cols ///< [in] the new size of a quad, in cols ); - + /// Returns the quadrant starting coordinates - int quadCoords( size_t & i0, ///< [out] the i coordinate of the lower-left corner of quad + int quadCoords( size_t & i0, ///< [out] the i coordinate of the lower-left corner of quad size_t & j0, ///< [out] the j coordinate of the lower-left corner of auad int quadNo ///< [in] the quadrant number ); - + int threshold( mx::improc::eigenImage & im ); - + int getQuad( mx::improc::eigenImage & quad, mx::improc::eigenImage & im, int quadNo ); - + int putQuad( mx::improc::eigenImage & im, mx::improc::eigenImage & quad, int quadNo ); - + int outerpix( float & avgx, float & avgy, float & avgr, int quadNo ); - - int fit( mx::improc::eigenImage & im, + + int fit( mx::improc::eigenImage & im, mx::improc::eigenImage & edged ); - + //int emitRegion( const std::string fname ); - + }; template @@ -86,31 +86,31 @@ int pupilFitter::setSize( unsigned rows, { m_rows = rows; m_cols = cols; - + m_quad.resize(m_rows,m_cols); m_circ.resize(m_rows,m_cols); - + //Set up for the magnified version m_quadMag.resize(m_quad.rows()*10, m_quad.cols()*10); m_circMag.resize(m_circ.rows()*10, m_circ.cols()*10); m_pixs.resize(m_quadMag.rows()*m_quadMag.cols()); - + return 0; } - + template int pupilFitter::quadCoords( size_t & i0, size_t & j0, - int quadNo + int quadNo ) { if(m_numPupils == 3) { i0 = 0; j0 = 0; - - if(quadNo == 1) + + if(quadNo == 1) { i0 = m_rows; } @@ -124,17 +124,17 @@ int pupilFitter::quadCoords( size_t & i0, { i0=0; j0=0; - + if(quadNo == 1) i0 = m_rows; if(quadNo == 2) j0 = m_cols; - if(quadNo == 3) + if(quadNo == 3) { i0 = m_rows; j0 = m_cols; } - + } - + return 0; } @@ -149,7 +149,7 @@ int pupilFitter::threshold( mx::improc::eigenImage & im ) else im(i,j) = 0; } } - + return 0; } @@ -159,15 +159,15 @@ int pupilFitter::getQuad( mx::improc::eigenImage & quad, int quadNo ) { - + if(im.rows() != 2*m_rows || im.cols() != 2*m_cols) { return -1; } - + size_t i0=0, j0=0; quadCoords(i0, j0, quadNo); - + for(size_t i =i0; i< i0+m_rows; ++i) { for(size_t j=j0; j::getQuad( mx::improc::eigenImage & quad, quad(i-i0, j-j0) = im(i,j); } } - + return 0; } @@ -189,10 +189,10 @@ int pupilFitter::putQuad( mx::improc::eigenImage & im, { return -1; } - + size_t i0=0, j0=0; quadCoords(i0, j0, quadNo); - + for(size_t i =i0; i< i0+m_rows; ++i) { for(size_t j=j0; j::putQuad( mx::improc::eigenImage & im, im(i,j) = quad(i-i0, j-j0);; } } - + return 0; } @@ -211,29 +211,29 @@ int pupilFitter::outerpix( float & avgx, int quadNo ) { - + realT x0, y0, avgr0; mx::improc::circleOuterpix(x0, y0, avgr0, avgx, avgy, avgr, m_circMag, m_quadMag); - + avgx/=10.0; avgy/=10.0; avgr/=10.0; size_t i0=0, j0=0; quadCoords(i0, j0, quadNo); - + avgx += i0; avgy += j0; - + return 0; - + } template -int pupilFitter::fit( mx::improc::eigenImage & im, +int pupilFitter::fit( mx::improc::eigenImage & im, mx::improc::eigenImage & edged ) { @@ -243,32 +243,35 @@ int pupilFitter::fit( mx::improc::eigenImage & im, { // 0) magnify the image getQuad(m_quad, imin, i); - + mx::improc::imageMagnify(m_quadMag, m_quad, mx::improc::bilinearTransform()); // 1) normalize by median of pupil - for(size_t j=0; j < m_pixs.size(); ++j) m_pixs[j] = m_quadMag.data()[j]; - + for(size_t j=0; j < m_pixs.size(); ++j) + { + m_pixs[j] = m_quadMag.data()[j]; + } + std::sort(m_pixs.begin(), m_pixs.end()); m_med[i] = m_pixs[m_pupMedIndex*m_pixs.size()]; //This should be the median of the pupils if the right size and contained in the quad - - m_quadMag/=m_med[i]; - + + m_quadMag/=m_med[i]; + // 2) Threshold the normalized quad threshold(m_quadMag); // 3) Find outer pixels and the radius outerpix(m_avgx[i], m_avgy[i], m_avgr[i], i); - + // 4) De-magnify and prepare for putting on the streams mx::improc::imageRebinSum( m_quad, m_quadMag, true); mx::improc::imageRebinSum( m_circ, m_circMag); putQuad(im, m_quad, i); putQuad(edged, m_circ, i); } - + return 0; } } //namespace app From 4b88fb891240f0d85e000634542366482c7a6eab Mon Sep 17 00:00:00 2001 From: Jared Males Date: Thu, 24 Oct 2024 17:21:22 -0700 Subject: [PATCH 19/24] added bg est to pwfs pupil fit --- apps/pupilFit/pupilFit.hpp | 528 +++++++++++++++++----------------- apps/pupilFit/pupilFitter.hpp | 8 +- 2 files changed, 274 insertions(+), 262 deletions(-) diff --git a/apps/pupilFit/pupilFit.hpp b/apps/pupilFit/pupilFit.hpp index af5d37937..20488276b 100644 --- a/apps/pupilFit/pupilFit.hpp +++ b/apps/pupilFit/pupilFit.hpp @@ -12,7 +12,7 @@ #include "pupilFitter.hpp" -/** \defgroup pupilFit +/** \defgroup pupilFit * \brief The MagAO-X pyramid pupil fitter. * *
Application Documentation @@ -30,13 +30,13 @@ namespace MagAOX namespace app { -struct refShmimT +struct refShmimT { static std::string configSection() { return "refShmim"; }; - + static std::string indiPrefix() { return "ref"; @@ -48,7 +48,7 @@ struct refShmimT #define USEUSERSET (2) /// The MagAO-X Pyramid Pupil Fitter -/** +/** * \ingroup pupilFit */ class pupilFit : public MagAOXApp, public dev::shmimMonitor, public dev::shmimMonitor, public dev::frameGrabber, public dev::telemeter @@ -65,7 +65,7 @@ class pupilFit : public MagAOXApp, public dev::shmimMonitor, pub public: //The base shmimMonitor type typedef dev::shmimMonitor shmimMonitorT; - + typedef dev::shmimMonitor refShmimMonitorT; //The base frameGrabber type @@ -76,13 +76,13 @@ class pupilFit : public MagAOXApp, public dev::shmimMonitor, pub ///Floating point type in which to do all calculations. typedef float realT; - + /** \name app::dev Configurations *@{ */ - + static constexpr bool c_frameGrabber_flippable = false; ///< app:dev config to tell framegrabber these images can not be flipped - + ///@} protected: @@ -90,12 +90,12 @@ class pupilFit : public MagAOXApp, public dev::shmimMonitor, pub /** \name Configurable Parameters *@{ */ - + std::string m_threshShmimName {"camwfs_thresh"}; ///, public dev::shmimMonitor, pub mx::improc::eigenImage m_edgeIm; pupilFitter m_fitter; - + IMAGE m_threshShmim; bool m_threshShmimConnected {false}; - + IMAGE m_edgeShmim; bool m_edgeShmimConnected {false}; - + double m_defSetx1 {29.5}; double m_defSety1 {29.5}; double m_defSetD1 {56.0}; - + double m_defSetx2 {89.5}; double m_defSety2 {29.5}; double m_defSetD2 {56.0}; - + double m_defSetx3 {29.5}; double m_defSety3 {89.5}; double m_defSetD3 {56.0}; - + double m_defSetx4 {89.5}; double m_defSety4 {89.5}; double m_defSetD4 {56.0}; @@ -130,172 +130,172 @@ class pupilFit : public MagAOXApp, public dev::shmimMonitor, pub double m_userSetx1 {29.5}; double m_userSety1 {29.5}; double m_userSetD1 {56.0}; - + double m_userSetx2 {89.5}; double m_userSety2 {29.5}; double m_userSetD2 {56.0}; - + double m_userSetx3 {29.5}; double m_userSety3 {89.5}; double m_userSetD3 {56.0}; - + double m_userSetx4 {89.5}; double m_userSety4 {89.5}; double m_userSetD4 {56.0}; int m_setPointSource {USEDEFSET}; - + bool m_refUpdated {false}; ///< Flag set if the online reference update is used. - + double m_setx1 {29.5}; double m_sety1 {29.5}; double m_setD1 {56.0}; - + double m_setx2 {89.5}; double m_sety2 {29.5}; double m_setD2 {56.0}; - + double m_setx3 {29.5}; double m_sety3 {89.5}; double m_setD3 {56.0}; - + double m_setx4 {89.5}; double m_sety4 {89.5}; double m_setD4 {56.0}; - - double m_avg_dx; + + double m_avg_dx; double m_avg_dy; bool m_averaging {false}; size_t m_navg {0}; - + double m_avgx1_accum {0}; double m_avgx1sq_accum {0}; - + double m_avgy1_accum {0}; double m_avgy1sq_accum {0}; - + double m_avgD1_accum {0}; double m_avgD1sq_accum {0}; - + double m_avgmed1_accum {0}; double m_avgmed1sq_accum {0}; - + double m_avgx1 {0}; double m_varx1 {0}; - + double m_avgy1 {0}; double m_vary1 {0}; - + double m_avgD1 {0}; double m_varD1 {0}; - + double m_avgmed1 {0}; double m_varmed1 {0}; - + double m_avgx2_accum {0}; double m_avgx2sq_accum {0}; - + double m_avgy2_accum {0}; double m_avgy2sq_accum {0}; - + double m_avgD2_accum {0}; double m_avgD2sq_accum {0}; - + double m_avgmed2_accum {0}; double m_avgmed2sq_accum {0}; - + double m_avgx2 {0}; double m_varx2 {0}; - + double m_avgy2 {0}; double m_vary2 {0}; - + double m_avgD2 {0}; double m_varD2 {0}; - + double m_avgmed2 {0}; double m_varmed2 {0}; - + double m_avgx3_accum {0}; double m_avgx3sq_accum {0}; - + double m_avgy3_accum {0}; double m_avgy3sq_accum {0}; - + double m_avgD3_accum {0}; double m_avgD3sq_accum {0}; - + double m_avgmed3_accum {0}; double m_avgmed3sq_accum {0}; - + double m_avgx3 {0}; double m_varx3 {0}; - + double m_avgy3 {0}; double m_vary3 {0}; - + double m_avgD3 {0}; double m_varD3 {0}; - + double m_avgmed3 {0}; double m_varmed3 {0}; - + double m_avgx4_accum {0}; double m_avgx4sq_accum {0}; - + double m_avgy4_accum {0}; double m_avgy4sq_accum {0}; - + double m_avgD4_accum {0}; double m_avgD4sq_accum {0}; - + double m_avgmed4_accum {0}; double m_avgmed4sq_accum {0}; - + double m_avgx4 {0}; double m_varx4 {0}; - + double m_avgy4 {0}; double m_vary4 {0}; - + double m_avgD4 {0}; double m_varD4 {0}; - + double m_avgmed4 {0}; double m_varmed4 {0}; - + double m_avgxAll_accum {0}; double m_avgxAllsq_accum {0}; - + double m_avgyAll_accum {0}; double m_avgyAllsq_accum {0}; - + double m_avgDAll_accum {0}; double m_avgDAllsq_accum {0}; - + double m_avgmedAll_accum {0}; double m_avgmedAllsq_accum {0}; - + double m_avgxAll {0}; double m_varxAll {0}; - + double m_avgyAll {0}; double m_varyAll {0}; - + double m_avgDAll {0}; double m_varDAll {0}; - + double m_avgmedAll {0}; double m_varmedAll {0}; - + public: /// Default c'tor. pupilFit(); /// D'tor, declared and defined for noexcept. ~pupilFit() noexcept; - + virtual void setupConfig(); /// Implementation of loadConfig logic, separated for testing. @@ -312,28 +312,28 @@ class pupilFit : public MagAOXApp, public dev::shmimMonitor, pub virtual int appStartup(); /// Implementation of the FSM for pupilFit. - /** + /** * \returns 0 on no critical error * \returns -1 on an error requiring shutdown */ virtual int appLogic(); /// Shutdown the app. - /** + /** * */ virtual int appShutdown(); // shmimMonitor interface: int allocate( const dev::shmimT &); - + int processImage( void* curr_src, const dev::shmimT & ); - + // shmimMonitor interface for referenc: int allocate( const refShmimT &); - + int processImage( void* curr_src, const refShmimT & ); @@ -350,92 +350,92 @@ class pupilFit : public MagAOXApp, public dev::shmimMonitor, pub * * @{ */ - + /// Implementation of the framegrabber configureAcquisition interface - /** + /** * \returns 0 on success * \returns -1 on error */ int configureAcquisition(); - + /// Implementation of the framegrabber fps interface /** * \todo this needs to infer the stream fps and return it - */ + */ float fps() { return 1.0; } - + /// Implementation of the framegrabber startAcquisition interface - /** + /** * \returns 0 on success * \returns -1 on error */ int startAcquisition(); - + /// Implementation of the framegrabber acquireAndCheckValid interface - /** + /** * \returns 0 on success * \returns -1 on error */ int acquireAndCheckValid(); - + /// Implementation of the framegrabber loadImageIntoStream interface - /** + /** * \returns 0 on success * \returns -1 on error */ int loadImageIntoStream( void * dest /**< [in] */); - + /// Implementation of the framegrabber reconfig interface - /** + /** * \returns 0 on success * \returns -1 on error */ int reconfig(); - + ///@} protected: /** \name INDI * @{ - */ - + */ + pcf::IndiProperty m_indiP_thresh; - + INDI_NEWCALLBACK_DECL(pupilFit, m_indiP_thresh); - + pcf::IndiProperty m_indiP_averaging; INDI_NEWCALLBACK_DECL(pupilFit, m_indiP_averaging); - + pcf::IndiProperty m_indiP_numPupils; - + pcf::IndiProperty m_indiP_quad1; pcf::IndiProperty m_indiP_quad2; pcf::IndiProperty m_indiP_quad3; pcf::IndiProperty m_indiP_quad4; - + pcf::IndiProperty m_indiP_avg; - + pcf::IndiProperty m_indiP_reload; INDI_NEWCALLBACK_DECL(pupilFit, m_indiP_reload); - + pcf::IndiProperty m_indiP_update; INDI_NEWCALLBACK_DECL(pupilFit, m_indiP_update); - + pcf::IndiProperty m_indiP_refmode; INDI_NEWCALLBACK_DECL(pupilFit, m_indiP_refmode); ///@} /** \name Telemeter Interface - * + * * @{ - */ + */ int checkRecordTimes(); - + int recordTelem( const telem_fgtimings * ); ///@} @@ -455,7 +455,7 @@ pupilFit::~pupilFit() noexcept { ImageStreamIO_destroyIm( &m_threshShmim ); } - + if(m_edgeShmimConnected) { ImageStreamIO_destroyIm( &m_edgeShmim ); @@ -471,14 +471,14 @@ void pupilFit::setupConfig() telemeterT::setupConfig(config); config.add("shmimMonitor.shmimName", "", "shmimMonitor.shmimName", argType::Required, "shmimMonitor", "shmimName", false, "string", "The name of the ImageStreamIO shared memory image. Will be used as /tmp/.im.shm. Default is camwfs_avg"); - + config.add("fit.threshold", "", "fit.threshold", argType::Required, "fit", "threshold", false, "float", "The pupil finding threshold. 0 < threshold < 1"); config.add("fit.threshShmimName", "", "fit.threshShmimName", argType::Required, "fit", "threshShmimName", false, "float", "The name of the image stream for the thresholded images. Default is camwfs_thresh."); config.add("fit.edgeShmimName", "", "fit.edgeShmimName", argType::Required, "fit", "edgeShmimName", false, "float", "The name of the image stream for the edge images. Default is camwfs_edge."); - + config.add("fit.numPupils", "", "fit.numPupils", argType::Required, "fit", "numPupils", false, "int", "The number of pupils. Default is 4. 3 is also supported."); config.add("fit.pupMedIndex", "", "fit.pupMedIndex", argType::Required, "fit", "pupMedIndex", false, "float", "The index of the pupil median in a sorted quadrant."); - + config.add("cal.setx1", "", "cal.setx1", argType::Required, "cal", "setx1", false, "float", "The x set point for quad 1 (LL)."); config.add("cal.sety1", "", "cal.sety1", argType::Required, "cal", "sety1", false, "float", "The y set point for quad 1 (LL)."); config.add("cal.setD1", "", "cal.setD1", argType::Required, "cal", "setD1", false, "float", "The D set point for quad 1 (LL)."); @@ -513,7 +513,7 @@ int pupilFit::loadConfigImpl( mx::app::appConfigurator & _config ) _config(m_edgeShmimName, "fit.edgeShmimName"); _config(m_numPupils, "fit.numPupils"); _config(m_fitter.m_pupMedIndex, "fit.pupMedIndex"); - + _config(m_defSetx1, "cal.setx1"); _config(m_defSety1, "cal.sety1"); _config(m_defSetD1, "cal.setD1"); @@ -530,7 +530,7 @@ int pupilFit::loadConfigImpl( mx::app::appConfigurator & _config ) _config(m_defSety4, "cal.sety4"); _config(m_defSetD4, "cal.setD4"); - + return 0; } @@ -547,7 +547,7 @@ int pupilFit::appStartup() { return log({__FILE__, __LINE__}); } - + if(refShmimMonitorT::appStartup() < 0) { return log({__FILE__, __LINE__}); @@ -573,7 +573,7 @@ int pupilFit::appStartup() m_indiP_thresh["current"].set(m_threshold); m_indiP_thresh["target"].set(m_threshold); registerIndiPropertyNew(m_indiP_thresh, INDI_NEWCALLBACK(m_indiP_thresh)); - + createStandardIndiToggleSw( m_indiP_averaging, "averaging", "Start/Stop Averaging"); m_indiP_averaging["toggle"].set(pcf::IndiElement::Off); if( registerIndiPropertyNew( m_indiP_averaging, INDI_NEWCALLBACK(m_indiP_averaging)) < 0) @@ -581,12 +581,12 @@ int pupilFit::appStartup() log({__FILE__,__LINE__}); return -1; } - + createROIndiNumber( m_indiP_numPupils, "numPupils", "Number of Pupils"); indi::addNumberElement( m_indiP_numPupils, "value", 3, 4, 1, "%d", ""); m_indiP_numPupils["value"].set(m_numPupils); registerIndiPropertyReadOnly(m_indiP_numPupils); - + createROIndiNumber( m_indiP_quad1, "quadrant1", "Quadrant 1"); indi::addNumberElement( m_indiP_quad1, "x", 0, 59, 0, "%0.2f", "center x"); indi::addNumberElement( m_indiP_quad1, "dx", 0, 59, 0, "%0.2f", "delta-x"); @@ -595,15 +595,16 @@ int pupilFit::appStartup() indi::addNumberElement( m_indiP_quad1, "D", 0, 59, 0, "%0.2f", "diameter"); indi::addNumberElement( m_indiP_quad1, "dD", 0, 59, 0, "%0.2f", "delta-D"); indi::addNumberElement( m_indiP_quad1, "med", 0, std::numeric_limits::max(), 0, "%0.1f", "flux"); + indi::addNumberElement( m_indiP_quad1, "bg", 0, std::numeric_limits::max(), 0, "%0.1f", "background"); indi::addNumberElement( m_indiP_quad1, "set-x", 0, 59, 0, "%0.2f", "set pt. center x"); m_indiP_quad1["set-x"] = m_setx1; indi::addNumberElement( m_indiP_quad1, "set-y", 0, 59, 0, "%0.2f", "set pt. center x"); m_indiP_quad1["set-y"] = m_sety1; indi::addNumberElement( m_indiP_quad1, "set-D", 0, 59, 0, "%0.2f", "set pt. diameter"); m_indiP_quad1["set-D"] = m_setD1; - + registerIndiPropertyReadOnly(m_indiP_quad1); - + createROIndiNumber( m_indiP_quad2, "quadrant2", "Quadrant 2"); indi::addNumberElement( m_indiP_quad2, "x", 0, 59, 0, "%0.2f", "center x"); indi::addNumberElement( m_indiP_quad2, "dx", 0, 59, 0, "%0.2f", "delta-x"); @@ -612,6 +613,7 @@ int pupilFit::appStartup() indi::addNumberElement( m_indiP_quad2, "D", 0, 59, 0, "%0.2f", "diameter"); indi::addNumberElement( m_indiP_quad2, "dD", 0, 59, 0, "%0.2f", "delta-D"); indi::addNumberElement( m_indiP_quad2, "med", 0, std::numeric_limits::max(), 0, "%0.1f", "flux"); + indi::addNumberElement( m_indiP_quad2, "bg", 0, std::numeric_limits::max(), 0, "%0.1f", "background"); indi::addNumberElement( m_indiP_quad2, "set-x", 0, 59, 0, "%0.2f", "set pt. center x"); m_indiP_quad2["set-x"] = m_setx2; indi::addNumberElement( m_indiP_quad2, "set-y", 0, 59, 0, "%0.2f", "set pt. center x"); @@ -619,7 +621,7 @@ int pupilFit::appStartup() indi::addNumberElement( m_indiP_quad2, "set-D", 0, 59, 0, "%0.2f", "set pt. diameter"); m_indiP_quad2["set-D"] = m_setD2; registerIndiPropertyReadOnly(m_indiP_quad2); - + createROIndiNumber( m_indiP_quad3, "quadrant3", "Quadrant 3"); indi::addNumberElement( m_indiP_quad3, "x", 0, 59, 0, "%0.2f", "center x"); indi::addNumberElement( m_indiP_quad3, "dx", 0, 59, 0, "%0.2f", "delta-x"); @@ -628,6 +630,7 @@ int pupilFit::appStartup() indi::addNumberElement( m_indiP_quad3, "D", 0, 59, 0, "%0.2f", "diameter"); indi::addNumberElement( m_indiP_quad3, "dD", 0, 59, 0, "%0.2f", "delta-D"); indi::addNumberElement( m_indiP_quad3, "med", 0, std::numeric_limits::max(), 0, "%0.1f", "flux"); + indi::addNumberElement( m_indiP_quad3, "bg", 0, std::numeric_limits::max(), 0, "%0.1f", "background"); indi::addNumberElement( m_indiP_quad3, "set-x", 0, 59, 0, "%0.2f", "set pt. center x"); m_indiP_quad3["set-x"] = m_setx3; indi::addNumberElement( m_indiP_quad3, "set-y", 0, 59, 0, "%0.2f", "set pt. center x"); @@ -635,7 +638,7 @@ int pupilFit::appStartup() indi::addNumberElement( m_indiP_quad3, "set-D", 0, 59, 0, "%0.2f", "set pt. diameter"); m_indiP_quad3["set-D"] = m_setD3; registerIndiPropertyReadOnly(m_indiP_quad3); - + if(m_numPupils != 3) { createROIndiNumber( m_indiP_quad4, "quadrant4", "Quadrant 4"); @@ -646,6 +649,7 @@ int pupilFit::appStartup() indi::addNumberElement( m_indiP_quad4, "D", 0, 59, 0, "%0.2f", "diameter"); indi::addNumberElement( m_indiP_quad4, "dD", 0, 59, 0, "%0.2f", "delta-D"); indi::addNumberElement( m_indiP_quad4, "med", 0, std::numeric_limits::max(), 0, "%0.1f", "flux"); + indi::addNumberElement( m_indiP_quad4, "bg", 0, std::numeric_limits::max(), 0, "%0.1f", "background"); indi::addNumberElement( m_indiP_quad4, "set-x", 0, 59, 0, "%0.2f", "set pt. center x"); m_indiP_quad4["set-x"] = m_setx4; indi::addNumberElement( m_indiP_quad4, "set-y", 0, 59, 0, "%0.2f", "set pt. center x"); @@ -654,7 +658,7 @@ int pupilFit::appStartup() m_indiP_quad4["set-D"] = m_setD4; registerIndiPropertyReadOnly(m_indiP_quad4); } - + createROIndiNumber( m_indiP_avg, "average", "Average"); indi::addNumberElement( m_indiP_avg, "x", 0, 59, 0, "%0.2f", "center x"); indi::addNumberElement( m_indiP_avg, "dx", 0, 59, 0, "%0.2f", "delta-x"); @@ -663,7 +667,7 @@ int pupilFit::appStartup() indi::addNumberElement( m_indiP_avg, "D", 0, 59, 0, "%0.2f", "diameter"); indi::addNumberElement( m_indiP_avg, "dD", 0, 59, 0, "%0.2f", "delta-D"); registerIndiPropertyReadOnly(m_indiP_avg); - + createStandardIndiRequestSw( m_indiP_reload, "setpt_reload", "Reload Calibration"); m_indiP_reload["request"].set(pcf::IndiElement::Off); if( registerIndiPropertyNew( m_indiP_reload, INDI_NEWCALLBACK(m_indiP_reload)) < 0) @@ -671,7 +675,7 @@ int pupilFit::appStartup() log({__FILE__,__LINE__}); return -1; } - + createStandardIndiRequestSw( m_indiP_update, "setpt_current", "Set Reference"); m_indiP_update["request"].set(pcf::IndiElement::Off); if( registerIndiPropertyNew( m_indiP_update, INDI_NEWCALLBACK(m_indiP_update)) < 0) @@ -707,7 +711,7 @@ int pupilFit::appStartup() } state(stateCodes::OPERATING); - + return 0; } @@ -718,7 +722,7 @@ int pupilFit::appLogic() { return log({__FILE__,__LINE__}); } - + if( refShmimMonitorT::appLogic() < 0) { return log({__FILE__,__LINE__}); @@ -759,7 +763,7 @@ int pupilFit::appLogic() shmimMonitorT::updateINDI(); refShmimMonitorT::updateINDI(); - + if(frameGrabberT::updateINDI() < 0) { log({__FILE__, __LINE__}); @@ -783,16 +787,16 @@ inline int pupilFit::allocate(const dev::shmimT & dummy) { static_cast(dummy); - + std::lock_guard guard(m_indiMutex); m_fitIm.resize(shmimMonitorT::m_width, shmimMonitorT::m_height); m_edgeIm.resize(shmimMonitorT::m_width, shmimMonitorT::m_height); - + m_fitter.m_numPupils = m_numPupils; m_fitter.setSize(0.5*shmimMonitorT::m_width, 0.5*shmimMonitorT::m_height); m_fitter.m_thresh = m_threshold; - + if(m_setPointSource == USEREFIM && m_refIm.rows() == shmimMonitorT::m_width && m_refIm.cols() == shmimMonitorT::m_height) { mx::improc::eigenImage refim, refedge; @@ -805,19 +809,19 @@ int pupilFit::allocate(const dev::shmimT & dummy) m_setx1 = m_fitter.m_avgx[0]; m_sety1 = m_fitter.m_avgy[0]; m_setD1 = 2*m_fitter.m_avgr[0]; - + m_setx2 = m_fitter.m_avgx[1]; m_sety2 = m_fitter.m_avgy[1]; m_setD2 = 2*m_fitter.m_avgr[1]; - + m_setx3 = m_fitter.m_avgx[2]; m_sety3 = m_fitter.m_avgy[2]; m_setD3 = 2*m_fitter.m_avgr[2]; - + m_setx4 = m_fitter.m_avgx[3]; m_sety4 = m_fitter.m_avgy[3]; m_setD4 = 2*m_fitter.m_avgr[3]; - + log("Fit to reference image: "); log("Quad 1 set points: " + std::to_string(m_setx1) + " " + std::to_string(m_sety1) + " " + std::to_string(m_setD1)); log("Quad 2 set points: " + std::to_string(m_setx2) + " " + std::to_string(m_sety2) + " " + std::to_string(m_setD2)); @@ -834,20 +838,20 @@ int pupilFit::allocate(const dev::shmimT & dummy) } } - if(m_setPointSource == USEUSERSET) + if(m_setPointSource == USEUSERSET) { m_setx1 = m_userSetx1; m_sety1 = m_userSety1; m_setD1 = m_userSetD1; - + m_setx2 = m_userSetx2; m_sety2 = m_userSety2; m_setD2 = m_userSetD2; - + m_setx3 = m_userSetx3; m_sety3 = m_userSety3; m_setD3 = m_userSetD3; - + if(m_numPupils == 4) { m_setx4 = m_userSetx4; @@ -858,19 +862,19 @@ int pupilFit::allocate(const dev::shmimT & dummy) } else - { + { m_setx1 = m_defSetx1; m_sety1 = m_defSety1; m_setD1 = m_defSetD1; - + m_setx2 = m_defSetx2; m_sety2 = m_defSety2; m_setD2 = m_defSetD2; - + m_setx3 = m_defSetx3; m_sety3 = m_defSety3; m_setD3 = m_defSetD3; - + if(m_numPupils == 4) { m_setx4 = m_defSetx4; @@ -880,56 +884,56 @@ int pupilFit::allocate(const dev::shmimT & dummy) log("Set default set-points"); } } - + uint32_t imsize[3]; imsize[0] = shmimMonitorT::m_width; imsize[1] = shmimMonitorT::m_height; imsize[2] = 1; - + if(m_threshShmimConnected) { ImageStreamIO_destroyIm( &m_threshShmim ); m_threshShmimConnected = false; } - + if(m_edgeShmimConnected) { ImageStreamIO_destroyIm( &m_edgeShmim ); m_edgeShmimConnected = false; } - + ImageStreamIO_createIm_gpu(&m_threshShmim , m_threshShmimName.c_str(), 3, imsize, shmimMonitorT::m_dataType, -1, 1, IMAGE_NB_SEMAPHORE, 0, CIRCULAR_BUFFER | ZAXIS_TEMPORAL,0); m_threshShmimConnected = true; - + ImageStreamIO_createIm_gpu(&m_edgeShmim , m_edgeShmimName.c_str(), 3, imsize, shmimMonitorT::m_dataType, -1, 1, IMAGE_NB_SEMAPHORE, 0, CIRCULAR_BUFFER | ZAXIS_TEMPORAL,0); m_edgeShmimConnected = true; - + if(m_edgeShmimConnected) { } - + return 0; } - + inline int pupilFit::processImage( void* curr_src, const dev::shmimT & dummy ) { static_cast(dummy); - + for(unsigned nn=0; nn < shmimMonitorT::m_width*shmimMonitorT::m_height; ++nn) { m_fitIm.data()[nn] = ((float*)curr_src) [nn]; } - + m_fitter.m_thresh = m_threshold; - + m_fitter.fit(m_fitIm, m_edgeIm); - - + + {//mutex scope - + std::lock_guard guard(m_indiMutex); m_indiP_quad1["set-x"].set(m_setx1); m_indiP_quad1["x"].set(m_fitter.m_avgx[0]); @@ -941,9 +945,10 @@ int pupilFit::processImage( void* curr_src, m_indiP_quad1["D"].set(2*m_fitter.m_avgr[0]); m_indiP_quad1["dD"].set(2*m_fitter.m_avgr[0]-m_setD1); m_indiP_quad1["med"].set(m_fitter.m_med[0]); + m_indiP_quad1["bg"].set(m_fitter.m_bg[0]); m_indiP_quad1.setState (INDI_BUSY); m_indiDriver->sendSetProperty (m_indiP_quad1); - + m_indiP_quad2["set-x"].set(m_setx2); m_indiP_quad2["x"].set(m_fitter.m_avgx[1]); m_indiP_quad2["dx"].set(m_fitter.m_avgx[1]-m_setx2); @@ -954,9 +959,10 @@ int pupilFit::processImage( void* curr_src, m_indiP_quad2["D"].set(2*m_fitter.m_avgr[1]); m_indiP_quad2["dD"].set(2*m_fitter.m_avgr[1]-m_setD2); m_indiP_quad2["med"].set(m_fitter.m_med[1]); + m_indiP_quad2["bg"].set(m_fitter.m_bg[1]); m_indiP_quad2.setState (INDI_BUSY); m_indiDriver->sendSetProperty (m_indiP_quad2); - + m_indiP_quad3["set-x"].set(m_setx3); m_indiP_quad3["x"].set(m_fitter.m_avgx[2]); m_indiP_quad3["dx"].set(m_fitter.m_avgx[2]-m_setx3); @@ -967,18 +973,19 @@ int pupilFit::processImage( void* curr_src, m_indiP_quad3["D"].set(2*m_fitter.m_avgr[2]); m_indiP_quad3["dD"].set(2*m_fitter.m_avgr[2]-m_setD3); m_indiP_quad3["med"].set(m_fitter.m_med[2]); + m_indiP_quad3["bg"].set(m_fitter.m_bg[2]); m_indiP_quad3.setState (INDI_BUSY); m_indiDriver->sendSetProperty (m_indiP_quad3); - + if(m_numPupils == 3) { m_indiP_avg["x"].set(.333*(m_fitter.m_avgx[0] + m_fitter.m_avgx[1] + m_fitter.m_avgx[2])); m_indiP_avg["y"].set(.333*(m_fitter.m_avgy[0] + m_fitter.m_avgy[1] + m_fitter.m_avgy[2])); m_indiP_avg["D"].set(.667*(m_fitter.m_avgr[0] + m_fitter.m_avgr[1] + m_fitter.m_avgr[2])); - + m_avg_dx = .333*(m_fitter.m_avgx[0] + m_fitter.m_avgx[1] + m_fitter.m_avgx[2] + m_fitter.m_avgx[3]) - 0.25*(m_setx1 + m_setx2 + m_setx3 + m_setx4); m_avg_dy = .333*(m_fitter.m_avgy[0] + m_fitter.m_avgy[1] + m_fitter.m_avgy[2] + m_fitter.m_avgy[3]) - 0.25*(m_sety1 + m_sety2 + m_sety3 + m_sety4); - + m_indiP_avg["dx"].set(.333*(m_fitter.m_avgx[0] + m_fitter.m_avgx[1] + m_fitter.m_avgx[2]) - 0.333*(m_setx1 + m_setx2 + m_setx3)); m_indiP_avg["dy"].set(.333*(m_fitter.m_avgy[0] + m_fitter.m_avgy[1] + m_fitter.m_avgy[2]) - 0.333*(m_sety1 + m_sety2 + m_sety3)); @@ -996,13 +1003,14 @@ int pupilFit::processImage( void* curr_src, m_indiP_quad4["D"].set(2*m_fitter.m_avgr[3]); m_indiP_quad4["dD"].set(2*m_fitter.m_avgr[3]-m_setD4); m_indiP_quad4["med"].set(m_fitter.m_med[3]); + m_indiP_quad4["bg"].set(m_fitter.m_bg[3]); m_indiP_quad4.setState (INDI_BUSY); m_indiDriver->sendSetProperty (m_indiP_quad4); - + m_indiP_avg["x"].set(.25*(m_fitter.m_avgx[0] + m_fitter.m_avgx[1] + m_fitter.m_avgx[2] + m_fitter.m_avgx[3])); m_indiP_avg["y"].set(.25*(m_fitter.m_avgy[0] + m_fitter.m_avgy[1] + m_fitter.m_avgy[2] + m_fitter.m_avgy[3])); m_indiP_avg["D"].set(.5*(m_fitter.m_avgr[0] + m_fitter.m_avgr[1] + m_fitter.m_avgr[2] + m_fitter.m_avgr[3])); - + m_avg_dx = .25*(m_fitter.m_avgx[0] + m_fitter.m_avgx[1] + m_fitter.m_avgx[2] + m_fitter.m_avgx[3]) - 0.25*(m_setx1 + m_setx2 + m_setx3 + m_setx4); m_avg_dy = .25*(m_fitter.m_avgy[0] + m_fitter.m_avgy[1] + m_fitter.m_avgy[2] + m_fitter.m_avgy[3]) - 0.25*(m_sety1 + m_sety2 + m_sety3 + m_sety4); @@ -1010,11 +1018,11 @@ int pupilFit::processImage( void* curr_src, m_indiP_avg["dy"].set(.25*(m_fitter.m_avgy[0] + m_fitter.m_avgy[1] + m_fitter.m_avgy[2] + m_fitter.m_avgy[3]) - 0.25*(m_sety1 + m_sety2 + m_sety3 + m_sety4)); m_indiP_avg["dD"].set(.5*(m_fitter.m_avgr[0] + m_fitter.m_avgr[1] + m_fitter.m_avgr[2] + m_fitter.m_avgr[3]) - 0.25*(m_setD1 + m_setD2 + m_setD3 + m_setD4)); m_indiDriver->sendSetProperty (m_indiP_avg); - + } - + } - + //signal framegrabber //Now tell the f.g. to get going m_updated = true; @@ -1023,117 +1031,117 @@ int pupilFit::processImage( void* curr_src, log({__FILE__, __LINE__, errno, 0, "Error posting to semaphore"}); return -1; } - + if(m_averaging) { ++m_navg; - + m_avgx1_accum += m_fitter.m_avgx[0]; m_avgx1sq_accum += m_fitter.m_avgx[0]*m_fitter.m_avgx[0]; - + m_avgy1_accum += m_fitter.m_avgy[0]; m_avgy1sq_accum += m_fitter.m_avgy[0]*m_fitter.m_avgy[0]; - + m_avgD1_accum += 2*m_fitter.m_avgr[0]; m_avgD1sq_accum += 4*m_fitter.m_avgr[0]*m_fitter.m_avgr[0]; - + m_avgmed1_accum += m_fitter.m_med[0]; m_avgmed1sq_accum += m_fitter.m_med[0]*m_fitter.m_med[0]; - + m_avgx1 = m_avgx1_accum / m_navg; m_varx1 = m_avgx1sq_accum / m_navg - m_avgx1*m_avgx1; - + m_avgy1 = m_avgy1_accum / m_navg; m_vary1 = m_avgy1sq_accum / m_navg - m_avgy1*m_avgy1; - + m_avgD1 = m_avgD1_accum / m_navg; m_varD1 = m_avgD1sq_accum / m_navg - m_avgD1*m_avgD1; - + m_avgmed1 = m_avgmed1_accum / m_navg; m_varmed1 = m_avgmed1sq_accum / m_navg - m_avgmed1*m_avgmed1; - + m_avgx2_accum += m_fitter.m_avgx[1]; m_avgx2sq_accum += m_fitter.m_avgx[1]*m_fitter.m_avgx[1]; - + m_avgy2_accum += m_fitter.m_avgy[1]; m_avgy2sq_accum += m_fitter.m_avgy[1]*m_fitter.m_avgy[1]; - + m_avgD2_accum += 2*m_fitter.m_avgr[1]; m_avgD2sq_accum += 4*m_fitter.m_avgr[1]*m_fitter.m_avgr[1]; - + m_avgmed2_accum += m_fitter.m_med[1]; m_avgmed2sq_accum += m_fitter.m_med[1]*m_fitter.m_med[1]; - + m_avgx2 = m_avgx2_accum / m_navg; m_varx2 = m_avgx2sq_accum / m_navg - m_avgx2*m_avgx2; - + m_avgy2 = m_avgy2_accum / m_navg; m_vary2 = m_avgy2sq_accum / m_navg - m_avgy2*m_avgy2; - + m_avgD2 = m_avgD2_accum / m_navg; m_varD2 = m_avgD2sq_accum / m_navg - m_avgD2*m_avgD2; - + m_avgmed2 = m_avgmed2_accum / m_navg; m_varmed2 = m_avgmed2sq_accum / m_navg - m_avgmed2*m_avgmed2; - - - + + + m_avgx3_accum += m_fitter.m_avgx[2]; m_avgx3sq_accum += m_fitter.m_avgx[2]*m_fitter.m_avgx[2]; - + m_avgy3_accum += m_fitter.m_avgy[2]; m_avgy3sq_accum += m_fitter.m_avgy[2]*m_fitter.m_avgy[2]; - + m_avgD3_accum += 2*m_fitter.m_avgr[2]; m_avgD3sq_accum += 4*m_fitter.m_avgr[2]*m_fitter.m_avgr[2]; - + m_avgmed3_accum += m_fitter.m_med[2]; m_avgmed3sq_accum += m_fitter.m_med[2]*m_fitter.m_med[2]; - + m_avgx3 = m_avgx3_accum / m_navg; m_varx3 = m_avgx3sq_accum / m_navg - m_avgx3*m_avgx3; - + m_avgy3 = m_avgy3_accum / m_navg; m_vary3 = m_avgy3sq_accum / m_navg - m_avgy3*m_avgy3; - + m_avgD3 = m_avgD3_accum / m_navg; m_varD3 = m_avgD3sq_accum / m_navg - m_avgD3*m_avgD3; - + m_avgmed3 = m_avgmed3_accum / m_navg; m_varmed3 = m_avgmed3sq_accum / m_navg - m_avgmed3*m_avgmed3; - + if(m_numPupils == 3) { double tmp = 0.333*(m_fitter.m_avgx[0]+m_fitter.m_avgx[1]+m_fitter.m_avgx[2]+m_fitter.m_avgx[3]); m_avgxAll_accum += tmp; m_avgxAllsq_accum += tmp*tmp; - + tmp = 0.333*(m_fitter.m_avgy[0]+m_fitter.m_avgy[1]+m_fitter.m_avgy[2]); m_avgyAll_accum += tmp; m_avgyAllsq_accum += tmp*tmp; - + tmp = 2*0.333*(m_fitter.m_avgr[0]+m_fitter.m_avgr[1]+m_fitter.m_avgr[2]); m_avgDAll_accum += tmp; m_avgDAllsq_accum += tmp*tmp; - + tmp = 0.333*(m_fitter.m_med[0]+m_fitter.m_med[1]+m_fitter.m_med[2]); m_avgmedAll_accum += tmp; m_avgmedAllsq_accum += tmp*tmp; - + m_avgxAll = m_avgxAll_accum / m_navg; m_varxAll = m_avgxAllsq_accum / m_navg - m_avgxAll*m_avgxAll; - + m_avgyAll = m_avgyAll_accum / m_navg; m_varyAll = m_avgyAllsq_accum / m_navg - m_avgyAll*m_avgyAll; - + m_avgDAll = m_avgDAll_accum / m_navg; m_varDAll = m_avgDAllsq_accum / m_navg - m_avgDAll*m_avgDAll; - + m_avgmedAll = m_avgmedAll_accum / m_navg; m_varmedAll = m_avgmedAllsq_accum / m_navg - m_avgmedAll*m_avgmedAll; - - + + std::cerr << "****************************************************************\n"; std::cerr << "Averaged: " << m_navg << "\n"; std::cerr << "Average x1: " << m_avgx1 << " +/- " << sqrt(m_varx1) << "\n"; @@ -1157,58 +1165,58 @@ int pupilFit::processImage( void* curr_src, { m_avgx4_accum += m_fitter.m_avgx[3]; m_avgx4sq_accum += m_fitter.m_avgx[3]*m_fitter.m_avgx[3]; - + m_avgy4_accum += m_fitter.m_avgy[3]; m_avgy4sq_accum += m_fitter.m_avgy[3]*m_fitter.m_avgy[3]; - + m_avgD4_accum += 2*m_fitter.m_avgr[3]; m_avgD4sq_accum += 4*m_fitter.m_avgr[3]*m_fitter.m_avgr[3]; - + m_avgmed4_accum += m_fitter.m_med[3]; m_avgmed4sq_accum += m_fitter.m_med[3]*m_fitter.m_med[3]; - + m_avgx4 = m_avgx4_accum / m_navg; m_varx4 = m_avgx4sq_accum / m_navg - m_avgx4*m_avgx4; - + m_avgy4 = m_avgy4_accum / m_navg; m_vary4 = m_avgy4sq_accum / m_navg - m_avgy4*m_avgy4; - + m_avgD4 = m_avgD4_accum / m_navg; m_varD4 = m_avgD4sq_accum / m_navg - m_avgD4*m_avgD4; - + m_avgmed4 = m_avgmed4_accum / m_navg; m_varmed4 = m_avgmed4sq_accum / m_navg - m_avgmed4*m_avgmed4; - - + + double tmp = 0.25*(m_fitter.m_avgx[0]+m_fitter.m_avgx[1]+m_fitter.m_avgx[2]+m_fitter.m_avgx[3]); m_avgxAll_accum += tmp; m_avgxAllsq_accum += tmp*tmp; - + tmp = 0.25*(m_fitter.m_avgy[0]+m_fitter.m_avgy[1]+m_fitter.m_avgy[2]+m_fitter.m_avgy[3]); m_avgyAll_accum += tmp; m_avgyAllsq_accum += tmp*tmp; - + tmp = 2*0.25*(m_fitter.m_avgr[0]+m_fitter.m_avgr[1]+m_fitter.m_avgr[2]+m_fitter.m_avgr[3]); m_avgDAll_accum += tmp; m_avgDAllsq_accum += tmp*tmp; - + tmp = 0.25*(m_fitter.m_med[0]+m_fitter.m_med[1]+m_fitter.m_med[2]+m_fitter.m_med[3]); m_avgmedAll_accum += tmp; m_avgmedAllsq_accum += tmp*tmp; - + m_avgxAll = m_avgxAll_accum / m_navg; m_varxAll = m_avgxAllsq_accum / m_navg - m_avgxAll*m_avgxAll; - + m_avgyAll = m_avgyAll_accum / m_navg; m_varyAll = m_avgyAllsq_accum / m_navg - m_avgyAll*m_avgyAll; - + m_avgDAll = m_avgDAll_accum / m_navg; m_varDAll = m_avgDAllsq_accum / m_navg - m_avgDAll*m_avgDAll; - + m_avgmedAll = m_avgmedAll_accum / m_navg; m_varmedAll = m_avgmedAllsq_accum / m_navg - m_avgmedAll*m_avgmedAll; - - + + std::cerr << "****************************************************************\n"; std::cerr << "Averaged: " << m_navg << "\n"; std::cerr << "Average x1: " << m_avgx1 << " +/- " << sqrt(m_varx1) << "\n"; @@ -1233,38 +1241,38 @@ int pupilFit::processImage( void* curr_src, std::cerr << "Average medAll: " << m_avgmedAll << " +/- " << sqrt(m_varmedAll) << "\n\n"; } } - + m_threshShmim.md->write=1; m_edgeShmim.md->write=1; - + clock_gettime(CLOCK_REALTIME, &m_threshShmim.md->writetime); m_edgeShmim.md->writetime = m_threshShmim.md->writetime; - + m_threshShmim.md->atime = m_threshShmim.md->writetime; m_edgeShmim.md->atime = m_threshShmim.md->writetime; - + m_threshShmim.md->cnt0++; m_edgeShmim.md->cnt0++; - + memcpy(m_threshShmim.array.raw, m_fitIm.data(), m_fitIm.rows()*m_fitIm.cols()*sizeof(float)); memcpy(m_edgeShmim.array.raw, m_edgeIm.data(), m_edgeIm.rows()*m_edgeIm.cols()*sizeof(float)); m_threshShmim.md->write=0; m_edgeShmim.md->write=0; - + ImageStreamIO_sempost(&m_threshShmim,-1); ImageStreamIO_sempost(&m_edgeShmim,-1); - + return 0; } - + inline int pupilFit::allocate(const refShmimT & dummy) { static_cast(dummy); - + std::lock_guard guard(m_indiMutex); - + if(refShmimMonitorT::m_dataType != IMAGESTRUCT_FLOAT) { return log({__FILE__, __LINE__, "reference is not float"}); @@ -1273,15 +1281,15 @@ int pupilFit::allocate(const refShmimT & dummy) m_refIm.resize( refShmimMonitorT::m_width, refShmimMonitorT::m_height ); return 0; -} - +} + inline int pupilFit::processImage( void* curr_src, const refShmimT & dummy ) { static_cast(dummy); - + int npix = 0; for(unsigned nn=0; nn < refShmimMonitorT::m_width*refShmimMonitorT::m_height; ++nn) { @@ -1290,7 +1298,7 @@ int pupilFit::processImage( void* curr_src, } log("reference updated", logPrio::LOG_NOTICE); - + std::cerr << m_refIm.sum() << " " << npix << "\n"; shmimMonitorT::m_restart = true; @@ -1306,7 +1314,7 @@ int pupilFit::configureAcquisition() frameGrabberT::m_width = 2; frameGrabberT::m_height = 1; frameGrabberT::m_dataType = _DATATYPE_FLOAT; - + return 0; } @@ -1320,15 +1328,15 @@ inline int pupilFit::acquireAndCheckValid() { timespec ts; - + if(clock_gettime(CLOCK_REALTIME, &ts) < 0) { - log({__FILE__,__LINE__,errno,0,"clock_gettime"}); + log({__FILE__,__LINE__,errno,0,"clock_gettime"}); return -1; } - + ts.tv_sec += 1; - + if(sem_timedwait(&m_smSemaphore, &ts) == 0) { if( m_updated ) @@ -1370,19 +1378,19 @@ INDI_NEWCALLBACK_DEFN(pupilFit, m_indiP_thresh)(const pcf::IndiProperty & ipRecv log({__FILE__,__LINE__, "wrong INDI property received."}); return -1; } - + float target; - + if( indiTargetUpdate( m_indiP_thresh, target, ipRecv, true) < 0) { log({__FILE__,__LINE__}); return -1; } - + m_threshold = target; - + if(m_setPointSource == USEREFIM) shmimMonitorT::m_restart = true; //need to re-process the reference - + log("set threshold = " + std::to_string(m_threshold), logPrio::LOG_NOTICE); return 0; } @@ -1397,7 +1405,7 @@ INDI_NEWCALLBACK_DEFN(pupilFit, m_indiP_averaging)(const pcf::IndiProperty & ipR if( ipRecv["toggle"].getSwitchState() == pcf::IndiElement::On) { - + m_avgx1_accum = 0; m_avgx1sq_accum = 0; m_avgy1_accum = 0; @@ -1406,7 +1414,7 @@ INDI_NEWCALLBACK_DEFN(pupilFit, m_indiP_averaging)(const pcf::IndiProperty & ipR m_avgD1sq_accum = 0; m_avgmed1_accum = 0; m_avgmed1sq_accum = 0; - + m_avgx2_accum = 0; m_avgx2sq_accum = 0; m_avgy2_accum = 0; @@ -1415,7 +1423,7 @@ INDI_NEWCALLBACK_DEFN(pupilFit, m_indiP_averaging)(const pcf::IndiProperty & ipR m_avgD2sq_accum = 0; m_avgmed2_accum = 0; m_avgmed2sq_accum = 0; - + m_avgx3_accum = 0; m_avgx3sq_accum = 0; m_avgy3_accum = 0; @@ -1424,7 +1432,7 @@ INDI_NEWCALLBACK_DEFN(pupilFit, m_indiP_averaging)(const pcf::IndiProperty & ipR m_avgD3sq_accum = 0; m_avgmed3_accum = 0; m_avgmed3sq_accum = 0; - + m_avgx4_accum = 0; m_avgx4sq_accum = 0; m_avgy4_accum = 0; @@ -1433,7 +1441,7 @@ INDI_NEWCALLBACK_DEFN(pupilFit, m_indiP_averaging)(const pcf::IndiProperty & ipR m_avgD4sq_accum = 0; m_avgmed4_accum = 0; m_avgmed4sq_accum = 0; - + m_avgxAll_accum = 0; m_avgxAllsq_accum = 0; m_avgyAll_accum = 0; @@ -1442,15 +1450,15 @@ INDI_NEWCALLBACK_DEFN(pupilFit, m_indiP_averaging)(const pcf::IndiProperty & ipR m_avgDAllsq_accum = 0; m_avgmedAll_accum = 0; m_avgmedAllsq_accum = 0; - + m_navg = 0; - m_averaging = true; + m_averaging = true; updateSwitchIfChanged(m_indiP_averaging, "toggle", pcf::IndiElement::On, INDI_BUSY); log("began averaging"); - - } + + } else if( ipRecv["toggle"].getSwitchState() == pcf::IndiElement::Off) { m_averaging = false; @@ -1458,7 +1466,7 @@ INDI_NEWCALLBACK_DEFN(pupilFit, m_indiP_averaging)(const pcf::IndiProperty & ipR log("stopped averaging"); } - + return 0; } @@ -1469,13 +1477,13 @@ INDI_NEWCALLBACK_DEFN(pupilFit, m_indiP_reload)(const pcf::IndiProperty & ipRecv log({__FILE__,__LINE__, "wrong INDI property received."}); return -1; } - + if( ipRecv["request"].getSwitchState() == pcf::IndiElement::On) { log("reloading"); shmimMonitorT::m_restart = 1; } - + return 0; } @@ -1486,23 +1494,23 @@ INDI_NEWCALLBACK_DEFN(pupilFit, m_indiP_update)(const pcf::IndiProperty & ipRecv log({__FILE__,__LINE__, "wrong INDI property received."}); return -1; } - + if( ipRecv["request"].getSwitchState() == pcf::IndiElement::On) { std::lock_guard guard(m_indiMutex); - + m_setx1 = m_indiP_quad1["x"].get(); m_sety1 = m_indiP_quad1["y"].get(); m_setD1 = m_indiP_quad1["D"].get(); - + m_setx2 = m_indiP_quad2["x"].get(); m_sety2 = m_indiP_quad2["y"].get(); m_setD2 = m_indiP_quad2["D"].get(); - + m_setx3 = m_indiP_quad3["x"].get(); m_sety3 = m_indiP_quad3["y"].get(); m_setD3 = m_indiP_quad3["D"].get(); - + log("Recorded current set-points: "); log("Quad 1 set points: " + std::to_string(m_setx1) + " " + std::to_string(m_sety1) + " " + std::to_string(m_setD1)); log("Quad 2 set points: " + std::to_string(m_setx2) + " " + std::to_string(m_sety2) + " " + std::to_string(m_setD2)); @@ -1514,11 +1522,11 @@ INDI_NEWCALLBACK_DEFN(pupilFit, m_indiP_update)(const pcf::IndiProperty & ipRecv m_sety4 = m_indiP_quad4["y"].get(); m_setD4 = m_indiP_quad4["D"].get(); log("Quad 4 set points: " + std::to_string(m_setx4) + " " + std::to_string(m_sety4) + " " + std::to_string(m_setD4)); - } + } if(m_setPointSource == USEUSERSET) shmimMonitorT::m_restart = true; } - + return 0; } @@ -1569,16 +1577,16 @@ INDI_NEWCALLBACK_DEFN(pupilFit, m_indiP_refmode)(const pcf::IndiProperty & ipRec } } } - + return 0; } - + inline int pupilFit::checkRecordTimes() { return telemeterT::checkRecordTimes(telem_fgtimings()); } - + inline int pupilFit::recordTelem( const telem_fgtimings * ) { diff --git a/apps/pupilFit/pupilFitter.hpp b/apps/pupilFit/pupilFitter.hpp index 3095fab82..56ad6033a 100644 --- a/apps/pupilFit/pupilFitter.hpp +++ b/apps/pupilFit/pupilFitter.hpp @@ -30,8 +30,10 @@ struct pupilFitter unsigned m_cols {0}; ///< [in] the size of a quad, in cols int m_numPupils {4}; ///< the number of pupils. Default is 4, 3 is also supported. - float m_pupMedIndex {0.6266}; ///< the index of the illuminated pupil median in a sorted array. + float m_bgMedIndex {0.1867}; + float m_pupMedIndex {0.6867}; ///< the index of the illuminated pupil median in a sorted array. + float m_bg[4] = {0,0,0,0}; float m_med[4] = {0,0,0,0}; float m_avgx[4] = {0,0,0,0}; float m_avgy[4] = {0,0,0,0}; @@ -255,9 +257,11 @@ int pupilFitter::fit( mx::improc::eigenImage & im, std::sort(m_pixs.begin(), m_pixs.end()); + m_bg[i] = m_pixs[m_bgMedIndex*m_pixs.size()]; + m_med[i] = m_pixs[m_pupMedIndex*m_pixs.size()]; //This should be the median of the pupils if the right size and contained in the quad - m_quadMag/=m_med[i]; + m_quadMag = (m_quadMag - m_bg[i]) / (m_med[i] - m_bg[i]); // 2) Threshold the normalized quad threshold(m_quadMag); From 191b9aa5cfca7bdf3908fca8c72a3a6af91d89f7 Mon Sep 17 00:00:00 2001 From: Jared Males Date: Sat, 26 Oct 2024 10:51:34 -0700 Subject: [PATCH 20/24] added delta INDI property to control loops --- apps/alignLoop/alignLoop.hpp | 23 +++++++++++++++++++++-- apps/closedLoopIndi/closedLoopIndi.hpp | 22 ++++++++++++++++++++-- 2 files changed, 41 insertions(+), 4 deletions(-) diff --git a/apps/alignLoop/alignLoop.hpp b/apps/alignLoop/alignLoop.hpp index 6b26e73bf..8ea9df0cf 100644 --- a/apps/alignLoop/alignLoop.hpp +++ b/apps/alignLoop/alignLoop.hpp @@ -73,6 +73,9 @@ class alignLoop : public MagAOXApp, public dev::shmimMonitor mx::improc::eigenImage m_intMat; mx::improc::eigenImage m_measurements; + float m_delta0 {0}; + float m_delta1 {0}; + mx::improc::eigenImage m_commands; float m_ggain {0}; @@ -130,6 +133,8 @@ class alignLoop : public MagAOXApp, public dev::shmimMonitor //INDI + pcf::IndiProperty m_indiP_deltas; + pcf::IndiProperty m_indiP_ggain; pcf::IndiProperty m_indiP_ctrlEnabled; @@ -229,6 +234,12 @@ int alignLoop::appStartup() } } + CREATE_REG_INDI_RO_NUMBER( m_indiP_deltas, "deltas", "Deltas", "Deltas"); + m_indiP_deltas.add(pcf::IndiElement("delta0")); + m_indiP_deltas["delta0"] = 0; + m_indiP_deltas.add(pcf::IndiElement("delta1")); + m_indiP_deltas["delta1"] = 0; + m_gains.resize(m_defaultGains.size()); for(size_t n=0; n < m_defaultGains.size(); ++n) m_gains[n] = m_defaultGains[n]; @@ -367,6 +378,8 @@ int alignLoop::processImage( void* curr_src, } + m_delta0 = m_measurements(0,0); + m_delta1 = m_measurements(1,0); std::cout << "measurements: "; for(int cc = 0; cc < m_measurements.rows(); ++cc) @@ -379,6 +392,8 @@ int alignLoop::processImage( void* curr_src, m_commands.matrix() = m_intMat.matrix() * m_measurements.matrix(); + + std::cout << "delta commands: "; for(int cc = 0; cc < m_measurements.rows(); ++cc) { @@ -398,14 +413,18 @@ int alignLoop::processImage( void* curr_src, std::cout << "\n"; //And send commands. + int rv; if(m_ctrlEnabled) { - return sendCommands(commands); + rv = sendCommands(commands); } else { - return 0; + rv = 0; } + + updateIfChanged(m_indiP_deltas, std::vector({"delta0", "delta1"}), std::vector({m_delta0, m_delta1})); + return rv; } inline diff --git a/apps/closedLoopIndi/closedLoopIndi.hpp b/apps/closedLoopIndi/closedLoopIndi.hpp index f6a1760f3..cacfd1872 100644 --- a/apps/closedLoopIndi/closedLoopIndi.hpp +++ b/apps/closedLoopIndi/closedLoopIndi.hpp @@ -71,6 +71,9 @@ class closedLoopIndi : public MagAOXApp int64_t m_counter = -1; ///< The latest value of the loop counter mx::improc::eigenImage m_measurements; ///< The latest value of the measurements + float m_delta0 {0}; + float m_delta1 {0}; + mx::improc::eigenImage m_commands; ///< The latest commands float m_ggain {0}; ///< The global gain @@ -126,6 +129,8 @@ class closedLoopIndi : public MagAOXApp //INDI + pcf::IndiProperty m_indiP_deltas; + pcf::IndiProperty m_indiP_reference0; INDI_NEWCALLBACK_DECL(closedLoopIndi, m_indiP_reference0); @@ -301,6 +306,12 @@ int closedLoopIndi::appStartup() { REG_INDI_SETPROP(m_indiP_inputs, m_inputDevice, m_inputProperty); + CREATE_REG_INDI_RO_NUMBER( m_indiP_deltas, "deltas", "Deltas", "Deltas"); + m_indiP_deltas.add(pcf::IndiElement("delta0")); + m_indiP_deltas["delta0"] = 0; + m_indiP_deltas.add(pcf::IndiElement("delta1")); + m_indiP_deltas["delta1"] = 0; + CREATE_REG_INDI_NEW_NUMBERF( m_indiP_reference0, "reference0", -1e15, 1e15, 1, "%g", "reference0", "references"); m_indiP_reference0["current"] = m_references(0,0); m_indiP_reference0["target"] = m_references(0,0); @@ -436,6 +447,9 @@ int closedLoopIndi::updateLoop() return 0; } + m_delta0 = m_measurements(0,0) - m_references(0,0); + m_delta1 = m_measurements(1,0) - m_references(1,0); + m_commands.matrix() = m_intMat.matrix() * (m_measurements - m_references).matrix(); std::vector commands; @@ -447,14 +461,18 @@ int closedLoopIndi::updateLoop() } //And send commands. + int rv; if(m_loopClosed) { - return sendCommands(commands); + rv = sendCommands(commands); } else { - return 0; + rv = 0; } + + updateIfChanged(m_indiP_deltas, std::vector({"delta0", "delta1"}), std::vector({m_delta0, m_delta1})); + return rv; } inline From 922ae51c9756ec13a66c7d2f0b46e03331b76023 Mon Sep 17 00:00:00 2001 From: Jared Males Date: Sat, 26 Oct 2024 13:48:46 -0700 Subject: [PATCH 21/24] updated ttmModulator mod state to use defines --- apps/ttmModulator/ttmModulator.hpp | 74 +++++++++++++++++------------- 1 file changed, 43 insertions(+), 31 deletions(-) diff --git a/apps/ttmModulator/ttmModulator.hpp b/apps/ttmModulator/ttmModulator.hpp index 6c13eb3c8..2e90fbdb0 100644 --- a/apps/ttmModulator/ttmModulator.hpp +++ b/apps/ttmModulator/ttmModulator.hpp @@ -8,6 +8,13 @@ #include "../../magaox_git_version.h" +#define MODSTATE_UNKNOWN (-1) +#define MODSTATE_OFF (0) +#define MODSTATE_REST (1) +#define MODSTATE_MIDSET (2) +#define MODSTATE_SET (3) +#define MODSTATE_MODULATING (4) + namespace MagAOX { namespace app @@ -42,8 +49,8 @@ class ttmModulator : public MagAOXApp<> ///@} - int m_modState {-1}; ///< -1 = unknown, 0 = off, 1 = rest, 2 = midset, 3 = set, 4 = modulating - int m_modStateRequested {-1}; ///< The requested TTM state + int m_modState {MODSTATE_UNKNOWN}; ///< -1 = unknown, 0 = off, 1 = rest, 2 = midset, 3 = set, 4 = modulating + int m_modStateRequested {MODSTATE_UNKNOWN}; ///< The requested TTM state double m_modRad {0}; ///< The current modulation radius, in lam/D. double m_modRadRequested {-1}; ///< The requested modulation radius, in lam/D. double m_modFreq {0}; ///< The current modulation frequency, in Hz. @@ -244,10 +251,6 @@ inline void ttmModulator::loadConfig() { config(m_maxFreq, "limits.maxfreq"); - //config(m_maxAmp, "limits.maxamp"); - //config(m_voltsPerLD_1, "cal.voltsperld1"); - //config(m_voltsPerLD_2, "cal.voltsperld2"); - //config(m_phase_2, "cal.phase"); config(m_setVoltage_1, "cal.setv1"); config(m_setVoltage_2, "cal.setv2"); @@ -328,17 +331,22 @@ int ttmModulator::appLogic() return -1; } - if(m_modState == 1 || m_modState == 3) + if(m_modState == MODSTATE_REST) + { + state(stateCodes::NOTHOMED); + if(!stateLogged()) log({(uint8_t) m_modState, m_modFreq, m_modRad, 0,0}); + } + else if(m_modState == MODSTATE_SET) { state(stateCodes::READY); if(!stateLogged()) log({(uint8_t) m_modState, m_modFreq, m_modRad, 0,0}); } - if(m_modState == 2) + else if(m_modState == MODSTATE_MIDSET) { state(stateCodes::ERROR); if(!stateLogged()) log({(uint8_t) m_modState, m_modFreq, m_modRad, 0,0}); } - if(m_modState == 4) + else if(m_modState == MODSTATE_MODULATING) { state(stateCodes::OPERATING); if(!stateLogged()) log({(uint8_t) m_modState, m_modFreq, m_modRad, 0,0}); @@ -353,6 +361,7 @@ int ttmModulator::appLogic() updateIfChanged(m_indiP_modFrequency, "current", m_modFreq); updateIfChanged(m_indiP_modFrequency, "target", m_modFreqRequested); } + //This is set by an INDI newProperty if(m_modStateRequested > 0) { @@ -364,16 +373,14 @@ int ttmModulator::appLogic() double newRad = m_modRadRequested; double newFreq = m_modFreqRequested; - m_modStateRequested = 0; - //m_modFreqRequested = 0; - //m_modRadRequested = 0; - + m_modStateRequested = MODSTATE_OFF; + lock.unlock(); state(stateCodes::CONFIGURING); - if(newState == 1) restTTM(); - if(newState == 3) setTTM(); - if(newState == 4) + if(newState == MODSTATE_REST) restTTM(); + if(newState == MODSTATE_SET) setTTM(); + if(newState == MODSTATE_MODULATING) { if(newRad <= 0.1 || newFreq <= 1) { @@ -387,17 +394,22 @@ int ttmModulator::appLogic() calcState(); //Do this now for responsiveness. - if(m_modState == 1 || m_modState == 3) + if(m_modState == MODSTATE_REST) + { + state(stateCodes::NOTHOMED); + if(!stateLogged()) log({(uint8_t) m_modState, m_modFreq, m_modRad, 0,0}); + } + else if(m_modState == MODSTATE_SET) { state(stateCodes::READY); if(!stateLogged()) log({(uint8_t) m_modState, m_modFreq, m_modRad, 0,0}); } - if(m_modState == 2) + else if(m_modState == MODSTATE_MIDSET) { state(stateCodes::ERROR); if(!stateLogged()) log({(uint8_t) m_modState, m_modFreq, m_modRad, 0,0}); } - if(m_modState == 4) + else if(m_modState == MODSTATE_MODULATING) { state(stateCodes::OPERATING); if(!stateLogged()) log({(uint8_t) m_modState, m_modFreq, m_modRad, 0,0}); @@ -425,7 +437,7 @@ int ttmModulator::calcState() if( m_C1outp < 1 || m_C2outp < 1 ) //At least one channel off { //Need to also check fxn gen pwr state here - m_modState = 1; + m_modState = MODSTATE_REST; } else if( (m_C1freq == 0 || m_C1volts <= 0.002) && (m_C2freq == 0 || m_C2volts <= 0.002) ) { @@ -435,18 +447,18 @@ int ttmModulator::calcState() // -- phase is 0 if(/*m_C1ofst == m_setVoltage_1 && m_C2ofst == m_setVoltage_2 &&*/ m_C1phse == 0 && m_C2phse == 0 ) { - m_modState = 3; + m_modState = MODSTATE_SET; } else { - m_modState = 2; //must be setting + m_modState = MODSTATE_MIDSET; //must be setting } } else { if(m_C1freq != m_C2freq) { - m_modState = 2; + m_modState = MODSTATE_MIDSET; } else { @@ -476,7 +488,7 @@ int ttmModulator::calcState() m_modRad = m_C1volts/terpC1Amp * m_calRadius; - m_modState = 4; + m_modState = MODSTATE_MODULATING; } } @@ -593,12 +605,12 @@ int ttmModulator::restTTM() inline int ttmModulator::setTTM() { - if(m_modState == 3) //already Set. + if(m_modState == MODSTATE_SET) //already Set. { return 0; } - if(m_modState == 4) //Modulating + if(m_modState == MODSTATE_MODULATING) //Modulating { log("Stopping modulation.", logPrio::LOG_INFO); @@ -639,7 +651,7 @@ int ttmModulator::setTTM() //Steps: //1) Make sure we're fully rested: - if( m_modState != 1) + if( m_modState != MODSTATE_REST) { if( restTTM() < 0 ) return log({__FILE__, __LINE__}); @@ -753,7 +765,7 @@ int ttmModulator::modTTM( double newRad, //For now: if we enter modulating, we stop modulating. /// \todo Implement changing modulation without setting first. - if( m_modState == 4) + if( m_modState == MODSTATE_MODULATING) { if(newRad == m_modRad && newFreq == m_modFreq) return 0; @@ -764,13 +776,13 @@ int ttmModulator::modTTM( double newRad, } //If not set, we first check if we are fully rested. - if( m_modState < 3 ) + if( m_modState < MODSTATE_SET ) { if( setTTM() < 0 ) return log({__FILE__, __LINE__}); if( calcState() < 0 ) return log({__FILE__,__LINE__}); - if( m_modState < 3) return log({__FILE__,__LINE__, "TTM not set/setable."}); + if( m_modState < MODSTATE_SET) return log({__FILE__,__LINE__, "TTM not set/setable."}); } //Check frequency for safety. @@ -834,7 +846,7 @@ int ttmModulator::modTTM( double newRad, //At this point we have safe calibrated voltage for the frequency. - if( m_modState == 3) + if( m_modState == MODSTATE_SET) { // 0) set phase if( sendNewProperty(m_indiP_C2phse, "value", terpC2Phse) < 0 ) return log({__FILE__,__LINE__}); From cd9e5ef5c2a16ebcdd72f835a8240ed0855d614c Mon Sep 17 00:00:00 2001 From: Jared Males Date: Sat, 26 Oct 2024 13:51:06 -0700 Subject: [PATCH 22/24] updated pupilGuide widget --- gui/apps/pupilGuideGUI/pupilGuideGUI.pro | 22 +- gui/widgets/pupilGuide/pupilGuide.hpp | 4975 +++++++++++----------- gui/widgets/pupilGuide/pupilGuide.ui | 2090 +++++---- gui/widgets/xWidgets/fsmDisplay.hpp | 102 +- gui/widgets/xWidgets/statusLabel.hpp | 47 +- 5 files changed, 3877 insertions(+), 3359 deletions(-) diff --git a/gui/apps/pupilGuideGUI/pupilGuideGUI.pro b/gui/apps/pupilGuideGUI/pupilGuideGUI.pro index 2989d3f7c..535f98b59 100644 --- a/gui/apps/pupilGuideGUI/pupilGuideGUI.pro +++ b/gui/apps/pupilGuideGUI/pupilGuideGUI.pro @@ -4,8 +4,8 @@ TEMPLATE = app TARGET = pupilGuideGUI -DESTDIR = bin/ -DEPENDPATH += ./ ../../lib +DESTDIR = bin/ +DEPENDPATH += ./ ../../lib MOC_DIR = moc/ OBJECTS_DIR = obj/ @@ -36,19 +36,21 @@ HEADERS += ../../widgets/pupilGuide/pupilGuide.hpp \ ../../widgets/xWidgets/statusEntry.hpp \ ../../widgets/xWidgets/statusLabel.hpp \ ../../widgets/xWidgets/fsmDisplay.hpp \ - ../../lib/multiIndiManager.hpp - -SOURCES += pupilGuideGUI_main.cpp - + ../../widgets/xWidgets/toggleSlider.hpp \ + ../../lib/multiIndiManager.hpp + +SOURCES += pupilGuideGUI_main.cpp + FORMS += ../../widgets/pupilGuide/pupilGuide.ui \ ../../widgets/xWidgets/statusEntry.ui \ - ../../widgets/xWidgets/fsmDisplay.ui - + ../../widgets/xWidgets/fsmDisplay.ui \ + ../../widgets/xWidgets/toggleSlider.ui + LIBS += ../../../INDI/libcommon/libcommon.a \ ../../../INDI/liblilxml/liblilxml.a -RESOURCES += ../../resources/magaox.qrc +RESOURCES += ../../resources/magaox.qrc -RESOURCES += ../../resources/MagAOXStyleSheets/MagAOXStyle.qrc +RESOURCES += ../../resources/MagAOXStyleSheets/MagAOXStyle.qrc QT += widgets diff --git a/gui/widgets/pupilGuide/pupilGuide.hpp b/gui/widgets/pupilGuide/pupilGuide.hpp index 77ac3a979..d4e853a79 100644 --- a/gui/widgets/pupilGuide/pupilGuide.hpp +++ b/gui/widgets/pupilGuide/pupilGuide.hpp @@ -14,2747 +14,2774 @@ #include "../xWidgets/statusEntry.hpp" #include "../xWidgets/xWidget.hpp" -#define MOVE_TTM (0) -#define MOVE_TEL (1) -#define MOVE_WOOF (2) +#define MOVE_TTM ( 0 ) +#define MOVE_TEL ( 1 ) +#define MOVE_WOOF ( 2 ) -namespace xqt -{ - -void wooferTipTilt( double & tip, - double & tilt, - double x, - double y - ) +#define CAMLENS_X ( 0 ) +#define CAMLENS_Y ( 1 ) +#define CAMLENS_BOTH ( 2 ) + +namespace xqt { - double rot = (180.+29.0)*3.14159/180.; - double scale = -1.0; - tip = scale*(x * cos(rot) - y * sin(rot)); - tilt = scale*(x * sin(rot) + y * cos(rot)); +void wooferTipTilt( double &tip, double &tilt, double x, double y ) +{ + double rot = ( 180. + 29.0 ) * 3.14159 / 180.; + double scale = -1.0; + tip = scale * ( x * cos( rot ) - y * sin( rot ) ); + tilt = scale * ( x * sin( rot ) + y * cos( rot ) ); } - class pupilGuide : public xWidget { - Q_OBJECT - - enum camera {FLOWFS, LLOWFS, CAMSCIS}; - -protected: - - std::string m_appState; - - QMutex m_mutex; - - // --- modttm - std::string m_modFsmState; - int m_modState {0}; - - double m_modCh1 {0}; - double m_modCh2 {0}; - - double m_modFreq {0}; - double m_modFreq_tgt{0}; - double m_camwfsFreq {0}; - - double m_modRad {0}; - double m_modRad_tgt{0}; - - float m_stepSize {0.1}; - - int m_tipmovewhat {MOVE_TTM}; - - // --- woofer - - double m_tilt {0}; ///< current value of tilt mode from wooferModes - double m_tip {0}; ///< current value of tip mode from wooferModes - double m_focus {0}; ///< current value of focus mode from wooferModes - - float m_focusStepSize {0.1}; - - // --- camwfs-align - bool m_camwfsAlignLoopState {false}; - bool m_camwfsAlignLoopWaiting {false}; - QTimer * m_camwfsAlignLoopWaitTimer {nullptr}; - - // --- camwfs-fit - std::string m_camwfsfitState; - double m_med1 {0}; - double m_med2 {0}; - double m_med3 {0}; - double m_med4 {0}; - - double m_x1 {0}; - double m_y1 {0}; - double m_D1 {0}; - - double m_setx1 {0}; - double m_sety1 {0}; - double m_setD1 {0}; - - double m_x2 {0}; - double m_y2 {0}; - double m_D2 {0}; - - double m_setx2 {0}; - double m_sety2 {0}; - double m_setD2 {0}; - - double m_x3 {0}; - double m_y3 {0}; - double m_D3 {0}; - - double m_setx3 {0}; - double m_sety3 {0}; - double m_setD3 {0}; - - double m_x4 {0}; - double m_y4 {0}; - double m_D4 {0}; - - double m_setx4 {0}; - double m_sety4 {0}; - double m_setD4 {0}; - - double m_threshold_current {0}; - double m_threshold_target {0}; - - // -- camwfs-avg - std::string m_camwfsavgState; - unsigned m_nAverage_current {0}; - unsigned m_nAverage_target {0}; - - // -- dmtweeter - std::string m_dmtweeterState; - bool m_dmtweeterTestSet {false}; - - // -- dmncpc - std::string m_dmncpcState; - bool m_dmncpcTestSet {false}; - - // -- ttmpupil - std::string m_pupFsmState; - double m_pupCh1 {0}; - double m_pupCh2 {0}; - - float m_pupStepSize {0.5}; - - int m_pupCam {CAMSCIS}; - - // -- ttmperi - std::string m_ttmPeriFsmState; - double m_ttmPeriCh1 {0}; - double m_ttmPeriCh2 {0}; - - float m_ttmPeriStepSize {25}; - - - // -- Camera Lens - std::string m_camlensxFsmState; - std::string m_camlensyFsmState; - float m_camlensx_pos {0}; - float m_camlensy_pos {0}; - - float m_camlensStepSize {0.01}; - -public: - pupilGuide( QWidget * Parent = 0, - Qt::WindowFlags f = Qt::WindowFlags() - ); - - ~pupilGuide(); - - void subscribe(); - - virtual void onConnect(); - virtual void onDisconnect(); - - void handleDefProperty( const pcf::IndiProperty & ipRecv /**< [in] the property which has changed*/); - void handleSetProperty( const pcf::IndiProperty & ipRecv /**< [in] the property which has changed*/); - - - void modGUISetEnable( bool enableModGUI, - bool enableModArrows - ); - - void camwfsfitSetEnabled(bool enabled); - - void camlensSetEnabled(bool enabled); - -public slots: - void updateGUI(); - - //----------- modttm - - void on_buttonMod_mod_pressed(); - void on_buttonMod_set_pressed(); - void on_buttonMod_rest_pressed(); - - void on_button_ttmtel_pressed(); - - void on_button_tip_u_pressed(); - void on_button_tip_ul_pressed(); - void on_button_tip_l_pressed(); - void on_button_tip_dl_pressed(); - void on_button_tip_d_pressed(); - void on_button_tip_dr_pressed(); - void on_button_tip_r_pressed(); - void on_button_tip_ur_pressed(); - void on_button_tip_scale_pressed(); - - //------------- focus - void on_button_focus_p_pressed(); - void on_button_focus_m_pressed(); - void on_button_focus_scale_pressed(); - - //----------- dmtweeter - void on_buttonTweeterTest_set_pressed(); - - //----------- dmncpc - void on_buttonNCPCTest_set_pressed(); - - //----------- ttmpupil - void on_buttonPup_rest_pressed(); - void on_buttonPup_set_pressed(); - - void on_button_camera_pressed(); - - void on_button_pup_ul_pressed(); - void on_button_pup_dl_pressed(); - void on_button_pup_dr_pressed(); - void on_button_pup_ur_pressed(); - void on_button_pup_scale_pressed(); - - //---------- TTM Peri - void on_button_ttmPeri_rest_pressed(); - void on_button_ttmPeri_set_pressed(); - - void on_button_ttmPeri_l_pressed(); - void on_button_ttmPeri_r_pressed(); - void on_button_ttmPeri_u_pressed(); - void on_button_ttmPeri_d_pressed(); - void on_button_ttmPeri_scale_pressed(); - - void toggleExpFit(bool visible); - void on_buttonExpFit_pressed(); - - void on_pupilAlign_loopSlider_sliderReleased(); - void on_pupilAlign_loopSlider_sliderPressed(); - void on_pupilAlign_loopSlider_sliderMoved(int); - void camwfsAlignLoopWaitTimerOut(); - - void on_button_camlens_u_pressed(); - void on_button_camlens_l_pressed(); - void on_button_camlens_d_pressed(); - void on_button_camlens_r_pressed(); - void on_button_camlens_scale_pressed(); -private: - - Ui::pupilGuide ui; -}; + Q_OBJECT + + enum camera + { + FLOWFS, + LLOWFS, + CAMSCIS + }; + + protected: + std::string m_appState; + + QMutex m_mutex; + + // --- modttm + std::string m_modFsmState; + int m_modState{ 0 }; + + double m_modCh1{ 0 }; + double m_modCh2{ 0 }; + + double m_camwfsFreq{ 0 }; + + double m_modRad{ 0 }; + double m_modRad_tgt{ 0 }; + + float m_stepSize{ 0.1 }; + + int m_tipmovewhat{ MOVE_TTM }; + + // --- woofer + + double m_tilt{ 0 }; ///< current value of tilt mode from wooferModes + double m_tip{ 0 }; ///< current value of tip mode from wooferModes + double m_focus{ 0 }; ///< current value of focus mode from wooferModes + + float m_focusStepSize{ 0.1 }; + + // --- camwfs-align + bool m_camwfsAlignLoopState{ false }; + bool m_camwfsAlignLoopWaiting{ false }; + + // --- camwfs-fit + std::string m_camwfsfitState; + double m_med1{ 0 }; + double m_med2{ 0 }; + double m_med3{ 0 }; + double m_med4{ 0 }; + + double m_x1{ 0 }; + double m_y1{ 0 }; + double m_D1{ 0 }; + + double m_setx1{ 0 }; + double m_sety1{ 0 }; + double m_setD1{ 0 }; + + double m_x2{ 0 }; + double m_y2{ 0 }; + double m_D2{ 0 }; + + double m_setx2{ 0 }; + double m_sety2{ 0 }; + double m_setD2{ 0 }; + + double m_x3{ 0 }; + double m_y3{ 0 }; + double m_D3{ 0 }; + + double m_setx3{ 0 }; + double m_sety3{ 0 }; + double m_setD3{ 0 }; + + double m_x4{ 0 }; + double m_y4{ 0 }; + double m_D4{ 0 }; + + double m_setx4{ 0 }; + double m_sety4{ 0 }; + double m_setD4{ 0 }; + + double m_threshold_current{ 0 }; + double m_threshold_target{ 0 }; + + // -- camwfs-avg + std::string m_camwfsavgState; + unsigned m_nAverage_current{ 0 }; + unsigned m_nAverage_target{ 0 }; + + // -- dmtweeter + std::string m_dmtweeterState; + bool m_dmtweeterTestSet{ false }; + + // -- dmncpc + std::string m_dmncpcState; + bool m_dmncpcTestSet{ false }; + + // -- ttmpupil + std::string m_pupFsmState; + double m_pupCh1{ 0 }; + double m_pupCh2{ 0 }; + + float m_pupStepSize{ 0.5 }; + + int m_pupCam{ CAMSCIS }; + + // -- ttmperi + std::string m_ttmPeriFsmState; + double m_ttmPeriCh1{ 0 }; + double m_ttmPeriCh2{ 0 }; + + float m_ttmPeriStepSize{ 25 }; + + // -- Camera Lens + std::string m_camlensxFsmState; + std::string m_camlensyFsmState; + float m_camlensx_pos{ 0 }; + float m_camlensy_pos{ 0 }; + + float m_camlensStepSize{ 0.01 }; + + public: + pupilGuide( QWidget *Parent = 0, Qt::WindowFlags f = Qt::WindowFlags() ); + + ~pupilGuide(); + + void subscribe(); + + virtual void onConnect(); + virtual void onDisconnect(); + + void handleDefProperty( const pcf::IndiProperty &ipRecv /**< [in] the property which has changed*/ ); + void handleSetProperty( const pcf::IndiProperty &ipRecv /**< [in] the property which has changed*/ ); + + void modGUISetEnable( bool enableModGUI, bool enableModArrows ); + + void camwfsfitSetEnabled( bool enabled ); + + /// Enable or disable the cameralens GUI + /** IF whichcl is CAMLENS_BOTH, the action is applied to all components. + * If it's CAMLENS_X or CAMLENS_Y, it is only applied to that access. The common components are then enabled. + */ + void camlensSetEnabled( bool enabled, ///< true for enabled, false for disabled + int whichcl = CAMLENS_BOTH ///< Which axis, or both. CAMLENS_X, CAMLENS_Y, CAMLENS_BOTH + ); + + public slots: + void updateGUI(); + + //----------- modttm + + void on_buttonMod_mod_pressed(); + void on_buttonMod_set_pressed(); + void on_buttonMod_rest_pressed(); + + void on_button_ttmtel_pressed(); + + void on_button_tip_u_pressed(); + void on_button_tip_ul_pressed(); + void on_button_tip_l_pressed(); + void on_button_tip_dl_pressed(); + void on_button_tip_d_pressed(); + void on_button_tip_dr_pressed(); + void on_button_tip_r_pressed(); + void on_button_tip_ur_pressed(); + void on_button_tip_scale_pressed(); + + //------------- focus + void on_button_focus_p_pressed(); + void on_button_focus_m_pressed(); + void on_button_focus_scale_pressed(); + + //----------- dmtweeter + void on_buttonTweeterTest_set_pressed(); + + //----------- dmncpc + void on_buttonNCPCTest_set_pressed(); + //----------- ttmpupil + void on_buttonPup_rest_pressed(); + void on_buttonPup_set_pressed(); + void on_button_camera_pressed(); -pupilGuide::pupilGuide( QWidget * Parent, Qt::WindowFlags f) : xWidget(Parent, f) + void on_button_pup_ul_pressed(); + void on_button_pup_dl_pressed(); + void on_button_pup_dr_pressed(); + void on_button_pup_ur_pressed(); + void on_button_pup_scale_pressed(); + + //---------- TTM Peri + void on_button_ttmPeri_rest_pressed(); + void on_button_ttmPeri_set_pressed(); + + void on_button_ttmPeri_l_pressed(); + void on_button_ttmPeri_r_pressed(); + void on_button_ttmPeri_u_pressed(); + void on_button_ttmPeri_d_pressed(); + void on_button_ttmPeri_scale_pressed(); + + void toggleExpFit( bool visible ); + void on_buttonExpFit_pressed(); + + void on_button_camlens_u_pressed(); + void on_button_camlens_l_pressed(); + void on_button_camlens_d_pressed(); + void on_button_camlens_r_pressed(); + void on_button_camlens_scale_pressed(); + + private: + Ui::pupilGuide ui; +}; + +pupilGuide::pupilGuide( QWidget *Parent, Qt::WindowFlags f ) : xWidget( Parent, f ) { - ui.setupUi(this); - - ui.modState->setProperty("isStatus", true); - - - ui.camlens_fsm->setProperty("isStatus", true); - ui.button_camlens_scale->setProperty("isScaleButton", true); - ui.button_tip_scale->setProperty("isScaleButton", true); - ui.button_focus_scale->setProperty("isScaleButton", true); - ui.button_pup_scale->setProperty("isScaleButton", true); - ui.button_ttmPeri_scale->setProperty("isScaleButton", true); - - QTimer *timer = new QTimer(this); - connect(timer, SIGNAL(timeout()), this, SLOT(updateGUI())); - timer->start(250); - - ui.modFreq_current->setup("modwfs", "modFrequency", statusEntry::FLOAT, "", ""); - ui.modFreq_current->setStretch(0,0,6);//removes spacer and maximizes text field - ui.modFreq_current->format("%0.1f"); - ui.modFreq_current->onDisconnect(); - - ui.modRad_current->setup("modwfs", "modRadius", statusEntry::FLOAT, "", ""); - ui.modRad_current->setStretch(0,0,6);//removes spacer and maximizes text field - ui.modRad_current->format("%0.1f"); - ui.modRad_current->onDisconnect(); - - ui.modCh1->setup("fxngenmodwfs", "C1ofst", statusEntry::FLOAT, "Ch1", "V"); - ui.modCh1->currEl("value"); - ui.modCh1->targEl("value"); - ui.modCh1->setStretch(0,1,6);//removes spacer and maximizes text field - ui.modCh1->format("%0.2f"); - ui.modCh1->onDisconnect(); - - ui.modCh2->setup("fxngenmodwfs", "C2ofst", statusEntry::FLOAT, "Ch2", "V"); - ui.modCh2->currEl("value"); - ui.modCh2->targEl("value"); - ui.modCh2->setStretch(0,1,6);//removes spacer and maximizes text field - ui.modCh2->format("%0.2f"); - ui.modCh2->onDisconnect(); - - char ss[5]; - snprintf(ss, 5, "%0.2f", m_stepSize); - ui.button_tip_scale->setText(ss); - - snprintf(ss, 5, "%0.2f", m_focusStepSize); - ui.button_focus_scale->setText(ss); - - snprintf(ss, 5, "%0.2f", m_pupStepSize); - ui.button_pup_scale->setText(ss); - - snprintf(ss, 5, "%0.2f", m_camlensStepSize*10); - ui.button_camlens_scale->setText(ss); - - snprintf(ss, 5, "%0.2f", m_ttmPeriStepSize/100.); - ui.button_ttmPeri_scale->setText(ss); - - setXwFont(ui.labelModAndCenter); - setXwFont(ui.modState); - setXwFont(ui.labelFreq); - setXwFont(ui.labelRad); - setXwFont(ui.buttonMod_rest); - setXwFont(ui.buttonMod_set); - setXwFont(ui.buttonMod_mod); - setXwFont(ui.labelMedianFluxes); - setXwFont(ui.med1); - setXwFont(ui.med2); - setXwFont(ui.med3); - setXwFont(ui.med4); - setXwFont(ui.setDelta); - - m_tipmovewhat = MOVE_TTM; - on_button_ttmtel_pressed(); - - //tweeter controls - setXwFont(ui.labelTweeter); - setXwFont(ui.buttonTweeterTest_set); - - //ncpc controls - setXwFont(ui.labelNCPC); - setXwFont(ui.buttonNCPCTest_set); - - //-----------ttmpupil controls ------------ - setXwFont(ui.labelPupilSteering); - //setXwFont(ui.pupState); - setXwFont(ui.buttonPup_rest); - setXwFont(ui.buttonPup_set); - ui.pupState->device("ttmpupil"); - ui.pupCh1->setup("ttmpupil", "pos_1", statusEntry::FLOAT, "Ch 1", "V"); - ui.pupCh1->setStretch(1,2,4); - ui.pupCh1->highlightChanges(false); - ui.pupCh1->onDisconnect(); - ui.pupCh2->setup("ttmpupil", "pos_2", statusEntry::FLOAT, "Ch 2", "V"); - ui.pupCh2->setStretch(1,2,4); - ui.pupCh2->highlightChanges(false); - ui.pupCh2->onDisconnect(); - - //-----------ttmperi controls ------------ - setXwFont(ui.labelTTMPeri); - //setXwFont(ui.ttmPeriState); - setXwFont(ui.buttonPup_rest); - setXwFont(ui.buttonPup_set); - ui.ttmPeriState->device("ttmperi"); - ui.ttmPeriCh1->setup("ttmperi", "axis1_voltage", statusEntry::FLOAT, "Ch 1", "V"); - ui.ttmPeriCh1->setStretch(1,2,4); - ui.ttmPeriCh1->highlightChanges(false); - ui.ttmPeriCh1->onDisconnect(); - ui.ttmPeriCh2->setup("ttmperi", "axis2_voltage", statusEntry::FLOAT, "Ch 2", "V"); - ui.ttmPeriCh2->highlightChanges(false); - ui.ttmPeriCh2->setStretch(1,2,4); - ui.ttmPeriCh2->onDisconnect(); - - - - - - setXwFont(ui.labelPupilAlignment); - m_camwfsAlignLoopWaitTimer = new QTimer; - connect(m_camwfsAlignLoopWaitTimer, SIGNAL(timeout()), this, SLOT(camwfsAlignLoopWaitTimerOut())); - - ui.pupilAlign_gain->setup("camwfs-align", "loop_gain", statusEntry::FLOAT, "loop gain", ""); - ui.pupilAlign_gain->setStretch(0,1,6);//removes spacer and maximizes text field - ui.pupilAlign_gain->format("%0.2f"); - ui.pupilAlign_gain->onDisconnect(); - - - setXwFont(ui.camlens_label); - setXwFont(ui.camlens_fsm); - - setXwFont(ui.labelPupilFitting);//,1.2); - - setXwFont(ui.labelx); - setXwFont(ui.labely); - setXwFont(ui.labelD); - setXwFont(ui.labelUR); - setXwFont(ui.labelUL); - setXwFont(ui.labelLR); - setXwFont(ui.labelLL); - setXwFont(ui.labelAvg); - setXwFont(ui.coordUR_x); - setXwFont(ui.coordUR_y); - setXwFont(ui.coordUR_D); - setXwFont(ui.coordUL_x); - setXwFont(ui.coordUL_y); - setXwFont(ui.coordUL_D); - setXwFont(ui.coordLR_x); - setXwFont(ui.coordLR_y); - setXwFont(ui.coordLR_D); - setXwFont(ui.coordLL_x); - setXwFont(ui.coordLL_y); - setXwFont(ui.coordLL_D); - setXwFont(ui.coordAvg_x); - setXwFont(ui.coordAvg_y); - setXwFont(ui.coordAvg_D); - - setXwFont(ui.setDelta_pup); - - ui.fitThreshold->setup("camwfs-fit", "threshold", statusEntry::FLOAT, "Thresh", ""); - ui.fitThreshold->setStretch(0,1,6);//removes spacer and maximizes text field - ui.fitThreshold->format("%0.3f"); - ui.fitThreshold->onDisconnect(); - - ui.fitAvgTime->setup("camwfs-avg", "avgTime", statusEntry::FLOAT, "Avg. T.", "s"); - ui.fitAvgTime->setStretch(0,1,6);//removes spacer and maximizes text field - ui.fitAvgTime->format("%0.3f"); - ui.fitAvgTime->onDisconnect(); - - ui.camlens_x_pos->setup("stagecamlensx", "position", statusEntry::FLOAT, "X", "mm"); - ui.camlens_x_pos->setStretch(0,1,6);//removes spacer and maximizes text field - ui.camlens_x_pos->format("%0.4f"); - ui.camlens_x_pos->onDisconnect(); - - ui.camlens_y_pos->setup("stagecamlensy", "position", statusEntry::FLOAT, "Y", "mm"); - ui.camlens_y_pos->setStretch(0,1,6);//removes spacer and maximizes text field - ui.camlens_y_pos->format("%0.4f"); - ui.camlens_y_pos->onDisconnect(); - - //Set the pupil fit boxes to invisible at startup - toggleExpFit(false); + char ss[64]; //for scale buttons + + ui.setupUi( this ); + + + + //ui.modState->setProperty( "isStatus", true ); + + + + ui.button_focus_scale->setProperty( "isScaleButton", true ); + ui.button_pup_scale->setProperty( "isScaleButton", true ); + ui.button_ttmPeri_scale->setProperty( "isScaleButton", true ); + + //-----------ttmpupil controls ------------ + + setXwFont( ui.label_modulation ); + + ui.modwfs_fsm->device( "modwfs" ); + ui.modwfs_fsm->NOTHOMED( "RIP" ); + ui.modwfs_fsm->READY("SET"); + ui.modwfs_fsm->OPERATING("MODULATING"); + + setXwFont( ui.label_modFreq ); + setXwFont( ui.label_modRad ); + + setXwFont( ui.buttonMod_rest ); + setXwFont( ui.buttonMod_set ); + setXwFont( ui.buttonMod_mod ); + + ui.modFreq_current->setup( "modwfs", "modFrequency", statusEntry::FLOAT, "", "" ); + ui.modFreq_current->setStretch( 0, 0, 6 ); // removes spacer and maximizes text field + ui.modFreq_current->format( "%0.1f" ); + ui.modFreq_current->onDisconnect(); + + ui.modRad_current->setup( "modwfs", "modRadius", statusEntry::FLOAT, "", "" ); + ui.modRad_current->setStretch( 0, 0, 6 ); // removes spacer and maximizes text field + ui.modRad_current->format( "%0.1f" ); + ui.modRad_current->onDisconnect(); + + ui.modCh1->setup( "fxngenmodwfs", "C1ofst", statusEntry::FLOAT, "Ch1", "V" ); + ui.modCh1->currEl( "value" ); + ui.modCh1->targEl( "value" ); + ui.modCh1->setStretch( 0, 1, 6 ); // removes spacer and maximizes text field + ui.modCh1->format( "%0.2f" ); + ui.modCh1->onDisconnect(); + + ui.modCh2->setup( "fxngenmodwfs", "C2ofst", statusEntry::FLOAT, "Ch2", "V" ); + ui.modCh2->currEl( "value" ); + ui.modCh2->targEl( "value" ); + ui.modCh2->setStretch( 0, 1, 6 ); // removes spacer and maximizes text field + ui.modCh2->format( "%0.2f" ); + ui.modCh2->onDisconnect(); + + setXwFont( ui.label_tipAlignment ); + + m_tipmovewhat = MOVE_TTM; + on_button_ttmtel_pressed(); //call this to configure the buttons + + ui.button_tip_scale->setProperty( "isScaleButton", true ); + snprintf( ss, 5, "%0.2f", m_stepSize ); + ui.button_tip_scale->setText( ss ); + + snprintf( ss, 5, "%0.2f", m_focusStepSize ); + ui.button_focus_scale->setText( ss ); + + // orphans: + + + snprintf( ss, 5, "%0.2f", m_pupStepSize ); + ui.button_pup_scale->setText( ss ); + + snprintf( ss, 5, "%0.2f", m_camlensStepSize * 10 ); + ui.button_camlens_scale->setText( ss ); + + snprintf( ss, 5, "%0.2f", m_ttmPeriStepSize / 100. ); + ui.button_ttmPeri_scale->setText( ss ); + + + setXwFont( ui.labelMedianFluxes ); + setXwFont( ui.med1 ); + setXwFont( ui.med2 ); + setXwFont( ui.med3 ); + setXwFont( ui.med4 ); + setXwFont( ui.setDelta ); + + + // tweeter controls + setXwFont( ui.labelTweeter ); + setXwFont( ui.buttonTweeterTest_set ); + + // ncpc controls + setXwFont( ui.labelNCPC ); + setXwFont( ui.buttonNCPCTest_set ); + + //-----------ttmpupil controls ------------ + setXwFont( ui.labelPupilSteering ); + setXwFont( ui.buttonPup_rest ); + setXwFont( ui.buttonPup_set ); + ui.pupState->device( "ttmpupil" ); + ui.pupState->NOTHOMED( "RIP" ); + ui.pupState->HOMING( "SETTING" ); + ui.pupState->READY("SET"); + + ui.pupCh1->setup( "ttmpupil", "pos_1", statusEntry::FLOAT, "Ch 1", "V" ); + ui.pupCh1->setStretch( 1, 2, 4 ); + ui.pupCh1->highlightChanges( false ); + ui.pupCh1->onDisconnect(); + ui.pupCh2->setup( "ttmpupil", "pos_2", statusEntry::FLOAT, "Ch 2", "V" ); + ui.pupCh2->setStretch( 1, 2, 4 ); + ui.pupCh2->highlightChanges( false ); + ui.pupCh2->onDisconnect(); + + //-----------ttmperi controls ------------ + setXwFont( ui.labelTTMPeri ); + setXwFont( ui.buttonPup_rest ); + setXwFont( ui.buttonPup_set ); + ui.ttmPeriState->device( "ttmperi" ); + ui.ttmPeriState->READY("RIP"); + ui.ttmPeriState->OPERATING( "SET" ); + + ui.ttmPeriCh1->setup( "ttmperi", "axis1_voltage", statusEntry::FLOAT, "Ch 1", "V" ); + ui.ttmPeriCh1->setStretch( 1, 2, 4 ); + ui.ttmPeriCh1->highlightChanges( false ); + ui.ttmPeriCh1->onDisconnect(); + ui.ttmPeriCh2->setup( "ttmperi", "axis2_voltage", statusEntry::FLOAT, "Ch 2", "V" ); + ui.ttmPeriCh2->highlightChanges( false ); + ui.ttmPeriCh2->setStretch( 1, 2, 4 ); + ui.ttmPeriCh2->onDisconnect(); + + /* pupil tracking loop */ + setXwFont( ui.label_pupTrackLoop ); + + ui.pupTrackLoop_deltaX->setup( "camwfs-align", "deltas", statusEntry::FLOAT, "", "" ); + ui.pupTrackLoop_deltaX->currEl( "delta0" ); + ui.pupTrackLoop_deltaX->highlightChanges( false ); + ui.pupTrackLoop_deltaX->readOnly( true ); + ui.pupTrackLoop_deltaX->setStretch( 0, 0, 6 ); // removes spacer and maximizes text field + ui.pupTrackLoop_deltaX->format( "%0.03f" ); + ui.pupTrackLoop_deltaX->onDisconnect(); + + ui.pupTrackLoop_deltaY->setup( "camwfs-align", "deltas", statusEntry::FLOAT, "", "" ); + ui.pupTrackLoop_deltaY->currEl( "delta1" ); + ui.pupTrackLoop_deltaY->highlightChanges( false ); + ui.pupTrackLoop_deltaY->readOnly( true ); + ui.pupTrackLoop_deltaY->setStretch( 0, 0, 6 ); // removes spacer and maximizes text field + ui.pupTrackLoop_deltaY->format( "%0.03f" ); + ui.pupTrackLoop_deltaY->onDisconnect(); + + ui.pupTrackLoop_slider->setup( "camwfs-align", "loop_state", "toggle", "" ); + ui.pupTrackLoop_slider->setStretch( 0, 0, 10, true, true ); + + ui.pupTrackLoop_gain->setup( "camwfs-align", "loop_gain", statusEntry::FLOAT, "loop gain", "" ); + ui.pupTrackLoop_gain->setStretch( 0, 1, 6 ); // removes spacer and maximizes text field + ui.pupTrackLoop_gain->format( "%0.2f" ); + ui.pupTrackLoop_gain->onDisconnect(); + + /* actuator alignment loop */ + setXwFont( ui.label_actAlignLoop ); + + ui.actAlignLoop_deltaX->setup( "twAlign-camwfs-ctrl", "deltas", statusEntry::FLOAT, "", "" ); + ui.actAlignLoop_deltaX->currEl( "delta0" ); + ui.actAlignLoop_deltaX->highlightChanges( false ); + ui.actAlignLoop_deltaX->readOnly( true ); + ui.actAlignLoop_deltaX->setStretch( 0, 0, 6 ); // removes spacer and maximizes text field + ui.actAlignLoop_deltaX->format( "%0.03f" ); + ui.actAlignLoop_deltaX->onDisconnect(); + + ui.actAlignLoop_deltaY->setup( "twAlign-camwfs-ctrl", "deltas", statusEntry::FLOAT, "", "" ); + ui.actAlignLoop_deltaY->currEl( "delta1" ); + ui.actAlignLoop_deltaY->highlightChanges( false ); + ui.actAlignLoop_deltaY->readOnly( true ); + ui.actAlignLoop_deltaY->setStretch( 0, 0, 6 ); // removes spacer and maximizes text field + ui.actAlignLoop_deltaY->format( "%0.03f" ); + ui.actAlignLoop_deltaY->onDisconnect(); + + ui.actAlignLoop_slider->setup( "twAlign-camwfs-ctrl", "loop_state", "toggle", "" ); + ui.actAlignLoop_slider->setStretch( 0, 0, 10, true, true ); + + ui.actAlignLoop_gain->setup( "twAlign-camwfs-ctrl", "loop_gain", statusEntry::FLOAT, "loop gain", "" ); + ui.actAlignLoop_gain->setStretch( 0, 1, 6 ); // removes spacer and maximizes text field + ui.actAlignLoop_gain->format( "%0.2f" ); + ui.actAlignLoop_gain->onDisconnect(); + + /* actuator alignment sensor */ + setXwFont( ui.label_actAlignSensor ); + + ui.actAlignSensor_slider->setup( "twAlign-camwfs-wfs", "continuous", "toggle", "" ); + ui.actAlignSensor_slider->setStretch( 0, 0, 10, true, true ); + + ui.actAlignSensor_nAverage->setup( "twAlign-camwfs-wfs", "nPokeAverage", statusEntry::INT, "no. average", "" ); + ui.actAlignSensor_nAverage->setStretch( 1, 3, 6 ); + ui.actAlignSensor_nAverage->format( "%d" ); + ui.actAlignSensor_nAverage->onDisconnect(); + + ui.actAlignSensor_nImages->setup( "twAlign-camwfs-wfs", "nPokeImages", statusEntry::INT, "no. images", "" ); + ui.actAlignSensor_nImages->setStretch( 1, 3, 6 ); + ui.actAlignSensor_nImages->format( "%d" ); + ui.actAlignSensor_nImages->onDisconnect(); + + ui.actAlignSensor_pokeAmp->setup( "twAlign-camwfs-wfs", "poke_amp", statusEntry::FLOAT, "poke amp.", "um" ); + ui.actAlignSensor_pokeAmp->setStretch( 1, 3, 6 ); + ui.actAlignSensor_pokeAmp->format( "%0.2f" ); + ui.actAlignSensor_pokeAmp->onDisconnect(); + + setXwFont( ui.labelPupilFitting ); //,1.2); + + setXwFont( ui.labelx ); + setXwFont( ui.labely ); + setXwFont( ui.labelD ); + setXwFont( ui.labelUR ); + setXwFont( ui.labelUL ); + setXwFont( ui.labelLR ); + setXwFont( ui.labelLL ); + setXwFont( ui.labelAvg ); + setXwFont( ui.coordUR_x ); + setXwFont( ui.coordUR_y ); + setXwFont( ui.coordUR_D ); + setXwFont( ui.coordUL_x ); + setXwFont( ui.coordUL_y ); + setXwFont( ui.coordUL_D ); + setXwFont( ui.coordLR_x ); + setXwFont( ui.coordLR_y ); + setXwFont( ui.coordLR_D ); + setXwFont( ui.coordLL_x ); + setXwFont( ui.coordLL_y ); + setXwFont( ui.coordLL_D ); + setXwFont( ui.coordAvg_x ); + setXwFont( ui.coordAvg_y ); + setXwFont( ui.coordAvg_D ); + + setXwFont( ui.setDelta_pup ); + + ui.fitThreshold->setup( "camwfs-fit", "threshold", statusEntry::FLOAT, "Thresh", "" ); + ui.fitThreshold->setStretch( 0, 1, 6 ); // removes spacer and maximizes text field + ui.fitThreshold->format( "%0.3f" ); + ui.fitThreshold->onDisconnect(); + + ui.fitAvgTime->setup( "camwfs-avg", "avgTime", statusEntry::FLOAT, "Avg. T.", "s" ); + ui.fitAvgTime->setStretch( 0, 1, 6 ); // removes spacer and maximizes text field + ui.fitAvgTime->format( "%0.3f" ); + ui.fitAvgTime->onDisconnect(); + + /* Camera Lens */ + setXwFont( ui.label_camlens ); + setXwFont( ui.label_camlensX_fsm ); + setXwFont( ui.label_camlensY_fsm ); + ui.camlensX_fsm->device( "stagecamlensx" ); + ui.camlensY_fsm->device( "stagecamlensy" ); + + ui.camlensX_pos->setup( "stagecamlensx", "position", statusEntry::FLOAT, "X", "mm" ); + ui.camlensX_pos->setStretch( 0, 1, 6 ); // removes spacer and maximizes text field + ui.camlensX_pos->format( "%0.4f" ); + ui.camlensX_pos->onDisconnect(); + + ui.camlensY_pos->setup( "stagecamlensy", "position", statusEntry::FLOAT, "Y", "mm" ); + ui.camlensY_pos->setStretch( 0, 1, 6 ); // removes spacer and maximizes text field + ui.camlensY_pos->format( "%0.4f" ); + ui.camlensY_pos->onDisconnect(); + + ui.button_camlens_scale->setProperty( "isScaleButton", true ); + + // Set the pupil fit boxes to invisible at startup + toggleExpFit( false ); + + onDisconnect(); + + QTimer *timer = new QTimer( this ); + connect( timer, SIGNAL( timeout() ), this, SLOT( updateGUI() ) ); + timer->start( 250 ); } - + pupilGuide::~pupilGuide() { } void pupilGuide::subscribe() { - if(m_parent == nullptr) return; - - m_parent->addSubscriberProperty(this, "modwfs", "modFrequency"); - m_parent->addSubscriberProperty(this, "modwfs", "modRadius"); - m_parent->addSubscriberProperty(this, "modwfs", "modState"); - m_parent->addSubscriberProperty(this, "modwfs", "fsm"); - - m_parent->addSubscriber(ui.modFreq_current); - m_parent->addSubscriber(ui.modRad_current); - m_parent->addSubscriber(ui.modCh1); - m_parent->addSubscriber(ui.modCh2); - - m_parent->addSubscriberProperty(this, "camwfs", "fps"); - - m_parent->addSubscriberProperty(this, "wooferModes", "current_amps"); - - m_parent->addSubscriberProperty(this, "camwfs-fit", "fsm"); - m_parent->addSubscriberProperty(this, "camwfs-fit", "quadrant1"); - m_parent->addSubscriberProperty(this, "camwfs-fit", "quadrant2"); - m_parent->addSubscriberProperty(this, "camwfs-fit", "quadrant3"); - m_parent->addSubscriberProperty(this, "camwfs-fit", "quadrant4"); - m_parent->addSubscriberProperty(this, "camwfs-fit", "threshold"); - - m_parent->addSubscriberProperty(this, "camwfs-avg", "fsm"); - m_parent->addSubscriberProperty(this, "camwfs-avg", "nAverage"); - - - m_parent->addSubscriber(ui.pupState); - m_parent->addSubscriber(ui.pupCh1); - m_parent->addSubscriber(ui.pupCh2); - m_parent->addSubscriberProperty(this, "ttmpupil", "fsm"); - m_parent->addSubscriberProperty(this, "ttmpupil", "pos_1"); - m_parent->addSubscriberProperty(this, "ttmpupil", "pos_2"); - - m_parent->addSubscriber(ui.ttmPeriState); - m_parent->addSubscriber(ui.ttmPeriCh1); - m_parent->addSubscriber(ui.ttmPeriCh2); - m_parent->addSubscriberProperty(this, "ttmperi", "fsm"); - m_parent->addSubscriberProperty(this, "ttmperi", "axis1_voltage"); - m_parent->addSubscriberProperty(this, "ttmperi", "axis2_voltage"); - - m_parent->addSubscriberProperty(this, "dmtweeter", "fsm"); - m_parent->addSubscriberProperty(this, "dmtweeter", "test_set"); - m_parent->addSubscriberProperty(this, "dmtweeter", "test"); - - m_parent->addSubscriberProperty(this, "dmncpc", "fsm"); - m_parent->addSubscriberProperty(this, "dmncpc", "test_set"); - m_parent->addSubscriberProperty(this, "dmncpc", "test"); - - - m_parent->addSubscriberProperty(this, "camwfs-align", "fsm"); - m_parent->addSubscriberProperty(this, "camwfs-align", "loop_state"); - m_parent->addSubscriber(ui.pupilAlign_gain); - - m_parent->addSubscriber(ui.fitThreshold); - m_parent->addSubscriber(ui.fitAvgTime); - - m_parent->addSubscriberProperty(this, "stagecamlensx", "fsm"); - m_parent->addSubscriberProperty(this, "stagecamlensy", "fsm"); - m_parent->addSubscriberProperty(this, "stagecamlensx", "position"); //we need these too - m_parent->addSubscriberProperty(this, "stagecamlensy", "position"); - m_parent->addSubscriber(ui.camlens_x_pos); - m_parent->addSubscriber(ui.camlens_y_pos); - - return; + if( m_parent == nullptr ) + return; + + m_parent->addSubscriber(ui.modwfs_fsm); + m_parent->addSubscriberProperty( this, "modwfs", "fsm" ); + m_parent->addSubscriberProperty( this, "modwfs", "modState" ); + + m_parent->addSubscriber( ui.modFreq_current ); + m_parent->addSubscriber( ui.modRad_current ); + m_parent->addSubscriber( ui.modCh1 ); + m_parent->addSubscriber( ui.modCh2 ); + + m_parent->addSubscriberProperty( this, "camwfs", "fps" ); + + m_parent->addSubscriberProperty( this, "wooferModes", "current_amps" ); + + m_parent->addSubscriberProperty( this, "camwfs-fit", "fsm" ); + m_parent->addSubscriberProperty( this, "camwfs-fit", "quadrant1" ); + m_parent->addSubscriberProperty( this, "camwfs-fit", "quadrant2" ); + m_parent->addSubscriberProperty( this, "camwfs-fit", "quadrant3" ); + m_parent->addSubscriberProperty( this, "camwfs-fit", "quadrant4" ); + m_parent->addSubscriberProperty( this, "camwfs-fit", "threshold" ); + + m_parent->addSubscriberProperty( this, "camwfs-avg", "fsm" ); + m_parent->addSubscriberProperty( this, "camwfs-avg", "nAverage" ); + + m_parent->addSubscriber( ui.pupState ); + m_parent->addSubscriber( ui.pupCh1 ); + m_parent->addSubscriber( ui.pupCh2 ); + m_parent->addSubscriberProperty( this, "ttmpupil", "fsm" ); + m_parent->addSubscriberProperty( this, "ttmpupil", "pos_1" ); + m_parent->addSubscriberProperty( this, "ttmpupil", "pos_2" ); + + m_parent->addSubscriber( ui.ttmPeriState ); + m_parent->addSubscriber( ui.ttmPeriCh1 ); + m_parent->addSubscriber( ui.ttmPeriCh2 ); + m_parent->addSubscriberProperty( this, "ttmperi", "fsm" ); + m_parent->addSubscriberProperty( this, "ttmperi", "axis1_voltage" ); + m_parent->addSubscriberProperty( this, "ttmperi", "axis2_voltage" ); + + m_parent->addSubscriberProperty( this, "dmtweeter", "fsm" ); + m_parent->addSubscriberProperty( this, "dmtweeter", "test_set" ); + m_parent->addSubscriberProperty( this, "dmtweeter", "test" ); + + m_parent->addSubscriberProperty( this, "dmncpc", "fsm" ); + m_parent->addSubscriberProperty( this, "dmncpc", "test_set" ); + m_parent->addSubscriberProperty( this, "dmncpc", "test" ); + + m_parent->addSubscriberProperty( this, "camwfs-align", "fsm" ); + m_parent->addSubscriberProperty( this, "camwfs-align", "loop_state" ); + + m_parent->addSubscriber( ui.pupTrackLoop_deltaX ); + m_parent->addSubscriber( ui.pupTrackLoop_deltaY ); + + m_parent->addSubscriber( ui.pupTrackLoop_slider ); + m_parent->addSubscriber( ui.pupTrackLoop_gain ); + + m_parent->addSubscriber( ui.actAlignLoop_deltaX ); + m_parent->addSubscriber( ui.actAlignLoop_deltaY ); + + m_parent->addSubscriber( ui.actAlignLoop_slider ); + + m_parent->addSubscriber( ui.actAlignLoop_gain ); + + m_parent->addSubscriber( ui.actAlignSensor_slider ); + + m_parent->addSubscriber( ui.actAlignSensor_nAverage ); + m_parent->addSubscriber( ui.actAlignSensor_nImages ); + m_parent->addSubscriber( ui.actAlignSensor_pokeAmp ); + + m_parent->addSubscriber( ui.fitThreshold ); + m_parent->addSubscriber( ui.fitAvgTime ); + + /* Camera Lens */ + m_parent->addSubscriber( ui.camlensX_fsm ); + m_parent->addSubscriber( ui.camlensY_fsm ); + m_parent->addSubscriberProperty( this, "stagecamlensx", "fsm" ); + m_parent->addSubscriberProperty( this, "stagecamlensy", "fsm" ); + m_parent->addSubscriberProperty( this, "stagecamlensx", "position" ); // we need these too + m_parent->addSubscriberProperty( this, "stagecamlensy", "position" ); + m_parent->addSubscriber( ui.camlensX_pos ); + m_parent->addSubscriber( ui.camlensY_pos ); + + return; } - + void pupilGuide::onConnect() { - ui.labelModAndCenter->setEnabled(true); - ui.labelPupilFitting->setEnabled(true); - - ui.modFreq_current->onConnect(); - ui.modRad_current->onConnect(); - ui.modCh1->onConnect(); - ui.modCh2->onConnect(); - - ui.pupState->onConnect(); - ui.pupCh1->onConnect(); - ui.pupCh2->onConnect(); - - - ui.ttmPeriState->onConnect(); - ui.ttmPeriCh1->onConnect(); - ui.ttmPeriCh2->onConnect(); - - ui.labelPupilSteering->setEnabled(true); - - ui.pupilAlign_gain->onConnect(); - - ui.camlens_label->setEnabled(true); - - ui.fitThreshold->onConnect(); - ui.fitAvgTime->onConnect(); - ui.camlens_x_pos->onConnect(); - ui.camlens_y_pos->onConnect(); - - setWindowTitle("Pupil Alignment"); + ui.label_modulation->setEnabled( true ); + ui.labelPupilFitting->setEnabled( true ); + + ui.modwfs_fsm->onConnect(); + ui.modFreq_current->onConnect(); + ui.modRad_current->onConnect(); + ui.modCh1->onConnect(); + ui.modCh2->onConnect(); + + ui.pupState->onConnect(); + ui.pupCh1->onConnect(); + ui.pupCh2->onConnect(); + + ui.ttmPeriState->onConnect(); + ui.ttmPeriCh1->onConnect(); + ui.ttmPeriCh2->onConnect(); + + ui.labelPupilSteering->setEnabled( true ); + + ui.pupTrackLoop_deltaX->onConnect(); + ui.pupTrackLoop_deltaY->onConnect(); + + ui.pupTrackLoop_slider->onConnect(); + ui.pupTrackLoop_gain->onConnect(); + + ui.actAlignLoop_deltaX->onConnect(); + ui.actAlignLoop_deltaY->onConnect(); + + ui.actAlignLoop_slider->onConnect(); + ui.actAlignLoop_gain->onConnect(); + + ui.actAlignSensor_slider->onConnect(); + ui.actAlignSensor_nAverage->onConnect(); + ui.actAlignSensor_nImages->onConnect(); + ui.actAlignSensor_pokeAmp->onConnect(); + + /* Camera Lens */ + ui.camlensX_fsm->onConnect(); + ui.camlensY_fsm->onConnect(); + ui.camlensX_pos->onConnect(); + ui.camlensY_pos->onConnect(); + + ui.fitThreshold->onConnect(); + ui.fitAvgTime->onConnect(); + + setWindowTitle( "Alignment" ); } void pupilGuide::onDisconnect() { - m_modFsmState = ""; - m_pupFsmState = ""; + m_modFsmState = ""; + m_pupFsmState = ""; - ui.modFreq_current->onDisconnect(); - ui.modRad_current->onDisconnect(); - ui.modCh1->onDisconnect(); - ui.modCh2->onDisconnect(); + ui.modwfs_fsm->onDisconnect(); + ui.modFreq_current->onDisconnect(); + ui.modRad_current->onDisconnect(); + ui.modCh1->onDisconnect(); + ui.modCh2->onDisconnect(); - ui.pupState->onDisconnect(); - ui.pupCh1->onDisconnect(); - ui.pupCh2->onDisconnect(); + ui.pupState->onDisconnect(); + ui.pupCh1->onDisconnect(); + ui.pupCh2->onDisconnect(); - ui.ttmPeriState->onDisconnect(); - ui.ttmPeriCh1->onDisconnect(); - ui.ttmPeriCh2->onDisconnect(); - + ui.ttmPeriState->onDisconnect(); + ui.ttmPeriCh1->onDisconnect(); + ui.ttmPeriCh2->onDisconnect(); - m_camlensxFsmState = ""; - m_camlensyFsmState = ""; - m_camwfsavgState = ""; - m_camwfsfitState = ""; + m_camlensxFsmState = ""; + m_camlensyFsmState = ""; + m_camwfsavgState = ""; + m_camwfsfitState = ""; - ui.labelModAndCenter->setEnabled(false); - ui.labelPupilFitting->setEnabled(false); - ui.labelPupilSteering->setEnabled(false); + ui.label_modulation->setEnabled( false ); + ui.labelPupilFitting->setEnabled( false ); + ui.labelPupilSteering->setEnabled( false ); + ui.pupTrackLoop_deltaX->onDisconnect(); + ui.pupTrackLoop_deltaY->onDisconnect(); - ui.pupilAlign_gain->onDisconnect(); + ui.pupTrackLoop_slider->onDisconnect(); + ui.pupTrackLoop_gain->onDisconnect(); - ui.camlens_label->setEnabled(false); - - ui.fitThreshold->onDisconnect(); - ui.fitAvgTime->onDisconnect(); - ui.camlens_x_pos->onDisconnect(); - ui.camlens_y_pos->onDisconnect(); + ui.actAlignLoop_deltaX->onDisconnect(); + ui.actAlignLoop_deltaY->onDisconnect(); - setWindowTitle("Pupil Alignment (disconnected)"); - + ui.actAlignLoop_slider->onDisconnect(); + ui.actAlignLoop_gain->onDisconnect(); + + ui.actAlignSensor_slider->onDisconnect(); + ui.actAlignSensor_nAverage->onDisconnect(); + ui.actAlignSensor_nImages->onDisconnect(); + ui.actAlignSensor_pokeAmp->onDisconnect(); + + /* Camera Lens */ + ui.camlensX_fsm->onDisconnect(); + ui.camlensY_fsm->onDisconnect(); + ui.camlensX_pos->onDisconnect(); + ui.camlensY_pos->onDisconnect(); + camlensSetEnabled(false); + + ui.fitThreshold->onDisconnect(); + ui.fitAvgTime->onDisconnect(); + + setWindowTitle( "Alignment (disconnected)" ); } - -void pupilGuide::handleDefProperty( const pcf::IndiProperty & ipRecv) -{ - std::string dev = ipRecv.getDevice(); - if( dev == "modwfs" || - dev == "camwfs" || - dev == "wooferModes" || - dev == "camwfs-avg" || - dev == "camwfs-fit" || - /*dev == "fxngenmodwfs" || */ - dev == "ttmpupil" || - dev == "camwfs-align" || - dev == "stagecamlensx" || - dev == "stagecamlensy" || - dev == "dmtweeter" || - dev == "dmncpc" || - dev == "ttmperi" ) - { - return handleSetProperty(ipRecv); - } - - return; + +void pupilGuide::handleDefProperty( const pcf::IndiProperty &ipRecv ) +{ + std::string dev = ipRecv.getDevice(); + if( dev == "modwfs" || dev == "camwfs" || dev == "wooferModes" || dev == "camwfs-avg" || dev == "camwfs-fit" || + /*dev == "fxngenmodwfs" || */ + dev == "ttmpupil" || dev == "camwfs-align" || dev == "stagecamlensx" || dev == "stagecamlensy" || + dev == "dmtweeter" || dev == "dmncpc" || dev == "ttmperi" ) + { + return handleSetProperty( ipRecv ); + } + + return; } -void pupilGuide::handleSetProperty( const pcf::IndiProperty & ipRecv) +void pupilGuide::handleSetProperty( const pcf::IndiProperty &ipRecv ) { - std::string dev = ipRecv.getDevice(); - - if(dev == "modwfs") - { - if(ipRecv.getName() == "modFrequency") - { - if(ipRecv.find("current")) - { - m_modFreq = ipRecv["current"].get(); - } - if(ipRecv.find("target")) - { - m_modFreq_tgt = ipRecv["target"].get(); - } - } - else if(ipRecv.getName() == "modRadius") - { - if(ipRecv.find("current")) - { - m_modRad = ipRecv["current"].get(); - } - if(ipRecv.find("target")) - { - m_modRad_tgt = ipRecv["target"].get(); - } - } - else if(ipRecv.getName() == "modState") - { - if(ipRecv.find("current")) - { - m_modState = ipRecv["current"].get(); - } - } - else if(ipRecv.getName() == "fsm") - { - if(ipRecv.find("state")) - { - m_modFsmState = ipRecv["state"].get(); - } - } - } - else if(dev == "camwfs") - { - if(ipRecv.getName() == "fps") - { - if(ipRecv.find("current")) - { - m_camwfsFreq = ipRecv["current"].get(); - } - } - } - else if(dev == "wooferModes") - { - if(ipRecv.getName() == "current_amps") - { - if(ipRecv.find("0000")) - { - m_tip = ipRecv["0000"].get(); - } - if(ipRecv.find("0001")) - { - m_tilt = ipRecv["0001"].get(); - } - if(ipRecv.find("0002")) - { - m_focus = ipRecv["0002"].get(); - } - } - } - else if(dev == "camwfs-avg") - { - if(ipRecv.getName() == "nAverage") - { - if(ipRecv.find("current")) - { - m_nAverage_current = ipRecv["current"].get(); - } - } - else if(ipRecv.getName() == "fsm") - { - if(ipRecv.find("state")) - { - m_camwfsavgState = ipRecv["state"].get(); - } - } - } - else if(dev == "camwfs-fit") - { - - if(ipRecv.getName() == "quadrant1") - { - if(ipRecv.find("med")) - { - m_med1 = ipRecv["med"].get(); - } - - if(ipRecv.find("x")) - { - m_x1 = ipRecv["x"].get(); - } - - if(ipRecv.find("y")) - { - m_y1 = ipRecv["y"].get(); - } - - if(ipRecv.find("D")) - { - m_D1 = ipRecv["D"].get(); - } - - if(ipRecv.find("set-x")) - { - m_setx1 = ipRecv["set-x"].get(); - } - - if(ipRecv.find("set-y")) - { - m_sety1 = ipRecv["set-y"].get(); - } - - if(ipRecv.find("set-D")) - { - m_setD1 = ipRecv["set-D"].get(); - } - } - else if(ipRecv.getName() == "quadrant2") - { - if(ipRecv.find("med")) - { - m_med2 = ipRecv["med"].get(); - } - - if(ipRecv.find("x")) - { - m_x2 = ipRecv["x"].get(); - } - - if(ipRecv.find("y")) - { - m_y2 = ipRecv["y"].get(); - } - - if(ipRecv.find("D")) - { - m_D2 = ipRecv["D"].get(); - } - - if(ipRecv.find("set-x")) - { - m_setx2 = ipRecv["set-x"].get(); - } - - if(ipRecv.find("set-y")) - { - m_sety2 = ipRecv["set-y"].get(); - } - - if(ipRecv.find("set-D")) - { - m_setD2 = ipRecv["set-D"].get(); - } - } - else if(ipRecv.getName() == "quadrant3") - { - if(ipRecv.find("med")) - { - m_med3 = ipRecv["med"].get(); - } - - if(ipRecv.find("x")) - { - m_x3 = ipRecv["x"].get(); - } - - if(ipRecv.find("y")) - { - m_y3 = ipRecv["y"].get(); - } - - if(ipRecv.find("D")) - { - m_D3 = ipRecv["D"].get(); - } - - if(ipRecv.find("set-x")) - { - m_setx3 = ipRecv["set-x"].get(); - } - - if(ipRecv.find("set-y")) - { - m_sety3 = ipRecv["set-y"].get(); - } - - if(ipRecv.find("set-D")) - { - m_setD3 = ipRecv["set-D"].get(); - } - } - else if(ipRecv.getName() == "quadrant4") - { - if(ipRecv.find("med")) - { - m_med4 = ipRecv["med"].get(); - } - - if(ipRecv.find("x")) - { - m_x4 = ipRecv["x"].get(); - } - - if(ipRecv.find("y")) - { - m_y4 = ipRecv["y"].get(); - } - - if(ipRecv.find("D")) - { - m_D4 = ipRecv["D"].get(); - } - - if(ipRecv.find("set-x")) - { - m_setx4 = ipRecv["set-x"].get(); - } - - if(ipRecv.find("set-y")) - { - m_sety4 = ipRecv["set-y"].get(); - } - - if(ipRecv.find("set-D")) - { - m_setD4 = ipRecv["set-D"].get(); - } - } - else if(ipRecv.getName() == "threshold") - { - if(ipRecv.find("current")) - { - m_threshold_current = ipRecv["current"].get(); - } - } - else if(ipRecv.getName() == "fsm") - { - if(ipRecv.find("state")) - { - m_camwfsfitState = ipRecv["state"].get(); - } - } - - - } - else if(dev == "ttmpupil") - { - if(ipRecv.getName() == "fsm") - { - if(ipRecv.find("state")) - { - m_pupFsmState = ipRecv["state"].get(); - } - } - else if(ipRecv.getName() == "pos_1") - { - if(ipRecv.find("current")) - { - m_pupCh1 = ipRecv["current"].get(); - } - } - else if(ipRecv.getName() == "pos_2") - { - if(ipRecv.find("current")) - { - m_pupCh2 = ipRecv["current"].get(); - } - } - } - else if(dev == "ttmperi") - { - if(ipRecv.getName() == "fsm") - { - if(ipRecv.find("state")) - { - m_ttmPeriFsmState = ipRecv["state"].get(); - } - } - else if(ipRecv.getName() == "axis1_voltage") - { - if(ipRecv.find("current")) - { - m_ttmPeriCh1 = ipRecv["current"].get(); - } - } - else if(ipRecv.getName() == "axis2_voltage") - { - if(ipRecv.find("current")) - { - m_ttmPeriCh2 = ipRecv["current"].get(); - } - } - } - else if(dev == "camwfs-align") - { - if(ipRecv.getName() == "loop_state") - { - if(ipRecv.find("toggle")) - { - if(ipRecv["toggle"].getSwitchState() == pcf::IndiElement::On) + std::string dev = ipRecv.getDevice(); + + if( dev == "modwfs" ) + { + if( ipRecv.getName() == "modState" ) + { + if( ipRecv.find( "current" ) ) { - if(m_camwfsAlignLoopState == false) m_camwfsAlignLoopWaiting = false; - m_camwfsAlignLoopState = true; + m_modState = ipRecv["current"].get(); } - else + } + else if( ipRecv.getName() == "fsm" ) + { + if( ipRecv.find( "state" ) ) + { + m_modFsmState = ipRecv["state"].get(); + } + } + } + else if( dev == "camwfs" ) + { + if( ipRecv.getName() == "fps" ) + { + if( ipRecv.find( "current" ) ) + { + m_camwfsFreq = ipRecv["current"].get(); + } + } + } + else if( dev == "wooferModes" ) + { + if( ipRecv.getName() == "current_amps" ) + { + if( ipRecv.find( "0000" ) ) + { + m_tip = ipRecv["0000"].get(); + } + if( ipRecv.find( "0001" ) ) + { + m_tilt = ipRecv["0001"].get(); + } + if( ipRecv.find( "0002" ) ) + { + m_focus = ipRecv["0002"].get(); + } + } + } + else if( dev == "camwfs-avg" ) + { + if( ipRecv.getName() == "nAverage" ) + { + if( ipRecv.find( "current" ) ) + { + m_nAverage_current = ipRecv["current"].get(); + } + } + else if( ipRecv.getName() == "fsm" ) + { + if( ipRecv.find( "state" ) ) + { + m_camwfsavgState = ipRecv["state"].get(); + } + } + } + else if( dev == "camwfs-fit" ) + { + + if( ipRecv.getName() == "quadrant1" ) + { + if( ipRecv.find( "med" ) ) + { + m_med1 = ipRecv["med"].get(); + } + + if( ipRecv.find( "x" ) ) + { + m_x1 = ipRecv["x"].get(); + } + + if( ipRecv.find( "y" ) ) + { + m_y1 = ipRecv["y"].get(); + } + + if( ipRecv.find( "D" ) ) + { + m_D1 = ipRecv["D"].get(); + } + + if( ipRecv.find( "set-x" ) ) + { + m_setx1 = ipRecv["set-x"].get(); + } + + if( ipRecv.find( "set-y" ) ) + { + m_sety1 = ipRecv["set-y"].get(); + } + + if( ipRecv.find( "set-D" ) ) + { + m_setD1 = ipRecv["set-D"].get(); + } + } + else if( ipRecv.getName() == "quadrant2" ) + { + if( ipRecv.find( "med" ) ) + { + m_med2 = ipRecv["med"].get(); + } + + if( ipRecv.find( "x" ) ) + { + m_x2 = ipRecv["x"].get(); + } + + if( ipRecv.find( "y" ) ) + { + m_y2 = ipRecv["y"].get(); + } + + if( ipRecv.find( "D" ) ) + { + m_D2 = ipRecv["D"].get(); + } + + if( ipRecv.find( "set-x" ) ) + { + m_setx2 = ipRecv["set-x"].get(); + } + + if( ipRecv.find( "set-y" ) ) + { + m_sety2 = ipRecv["set-y"].get(); + } + + if( ipRecv.find( "set-D" ) ) + { + m_setD2 = ipRecv["set-D"].get(); + } + } + else if( ipRecv.getName() == "quadrant3" ) + { + if( ipRecv.find( "med" ) ) + { + m_med3 = ipRecv["med"].get(); + } + + if( ipRecv.find( "x" ) ) + { + m_x3 = ipRecv["x"].get(); + } + + if( ipRecv.find( "y" ) ) + { + m_y3 = ipRecv["y"].get(); + } + + if( ipRecv.find( "D" ) ) + { + m_D3 = ipRecv["D"].get(); + } + + if( ipRecv.find( "set-x" ) ) + { + m_setx3 = ipRecv["set-x"].get(); + } + + if( ipRecv.find( "set-y" ) ) + { + m_sety3 = ipRecv["set-y"].get(); + } + + if( ipRecv.find( "set-D" ) ) + { + m_setD3 = ipRecv["set-D"].get(); + } + } + else if( ipRecv.getName() == "quadrant4" ) + { + if( ipRecv.find( "med" ) ) { - if(m_camwfsAlignLoopState == true) m_camwfsAlignLoopWaiting = false; - m_camwfsAlignLoopState = false; + m_med4 = ipRecv["med"].get(); } - - - } - } - } - else if(dev == "stagecamlensx") - { - if(ipRecv.getName() == "fsm") - { - if(ipRecv.find("state")) - { - m_camlensxFsmState = ipRecv["state"].get(); - } - } - else if(ipRecv.getName() == "position") - { - if(ipRecv.find("current")) - { - m_camlensx_pos = ipRecv["current"].get(); - } - } - } - else if(dev == "stagecamlensy") - { - if(ipRecv.getName() == "fsm") - { - if(ipRecv.find("state")) - { - m_camlensyFsmState = ipRecv["state"].get(); - } - } - else if(ipRecv.getName() == "position") - { - if(ipRecv.find("current")) - { - m_camlensy_pos = ipRecv["current"].get(); - } - } - } - else if(dev == "dmtweeter") - { - if(ipRecv.getName() == "fsm") - { - if(ipRecv.find("state")) - { - m_dmtweeterState = ipRecv["state"].get(); - } - } - else if(ipRecv.getName() == "test_set") - { - if(ipRecv.find("toggle")) - { - if(ipRecv["toggle"] == pcf::IndiElement::On) m_dmtweeterTestSet = true; - else m_dmtweeterTestSet=false; - } - } - } - else if(dev == "dmncpc") - { - if(ipRecv.getName() == "fsm") - { - if(ipRecv.find("state")) - { - m_dmncpcState = ipRecv["state"].get(); - } - } - else if(ipRecv.getName() == "test_set") - { - if(ipRecv.find("toggle")) - { - if(ipRecv["toggle"] == pcf::IndiElement::On) m_dmncpcTestSet = true; - else m_dmncpcTestSet=false; - } - } - } - - return; - + + if( ipRecv.find( "x" ) ) + { + m_x4 = ipRecv["x"].get(); + } + + if( ipRecv.find( "y" ) ) + { + m_y4 = ipRecv["y"].get(); + } + + if( ipRecv.find( "D" ) ) + { + m_D4 = ipRecv["D"].get(); + } + + if( ipRecv.find( "set-x" ) ) + { + m_setx4 = ipRecv["set-x"].get(); + } + + if( ipRecv.find( "set-y" ) ) + { + m_sety4 = ipRecv["set-y"].get(); + } + + if( ipRecv.find( "set-D" ) ) + { + m_setD4 = ipRecv["set-D"].get(); + } + } + else if( ipRecv.getName() == "threshold" ) + { + if( ipRecv.find( "current" ) ) + { + m_threshold_current = ipRecv["current"].get(); + } + } + else if( ipRecv.getName() == "fsm" ) + { + if( ipRecv.find( "state" ) ) + { + m_camwfsfitState = ipRecv["state"].get(); + } + } + } + else if( dev == "ttmpupil" ) + { + if( ipRecv.getName() == "fsm" ) + { + if( ipRecv.find( "state" ) ) + { + m_pupFsmState = ipRecv["state"].get(); + } + } + else if( ipRecv.getName() == "pos_1" ) + { + if( ipRecv.find( "current" ) ) + { + m_pupCh1 = ipRecv["current"].get(); + } + } + else if( ipRecv.getName() == "pos_2" ) + { + if( ipRecv.find( "current" ) ) + { + m_pupCh2 = ipRecv["current"].get(); + } + } + } + else if( dev == "ttmperi" ) + { + if( ipRecv.getName() == "fsm" ) + { + if( ipRecv.find( "state" ) ) + { + m_ttmPeriFsmState = ipRecv["state"].get(); + } + } + else if( ipRecv.getName() == "axis1_voltage" ) + { + if( ipRecv.find( "current" ) ) + { + m_ttmPeriCh1 = ipRecv["current"].get(); + } + } + else if( ipRecv.getName() == "axis2_voltage" ) + { + if( ipRecv.find( "current" ) ) + { + m_ttmPeriCh2 = ipRecv["current"].get(); + } + } + } + else if( dev == "camwfs-align" ) + { + if( ipRecv.getName() == "loop_state" ) + { + if( ipRecv.find( "toggle" ) ) + { + if( ipRecv["toggle"].getSwitchState() == pcf::IndiElement::On ) + { + if( m_camwfsAlignLoopState == false ) + m_camwfsAlignLoopWaiting = false; + m_camwfsAlignLoopState = true; + } + else + { + if( m_camwfsAlignLoopState == true ) + m_camwfsAlignLoopWaiting = false; + m_camwfsAlignLoopState = false; + } + } + } + } + else if( dev == "stagecamlensx" ) + { + if( ipRecv.getName() == "fsm" ) + { + if( ipRecv.find( "state" ) ) + { + m_camlensxFsmState = ipRecv["state"].get(); + } + } + else if( ipRecv.getName() == "position" ) + { + if( ipRecv.find( "current" ) ) + { + m_camlensx_pos = ipRecv["current"].get(); + } + } + } + else if( dev == "stagecamlensy" ) + { + if( ipRecv.getName() == "fsm" ) + { + if( ipRecv.find( "state" ) ) + { + m_camlensyFsmState = ipRecv["state"].get(); + } + } + else if( ipRecv.getName() == "position" ) + { + if( ipRecv.find( "current" ) ) + { + m_camlensy_pos = ipRecv["current"].get(); + } + } + } + else if( dev == "dmtweeter" ) + { + if( ipRecv.getName() == "fsm" ) + { + if( ipRecv.find( "state" ) ) + { + m_dmtweeterState = ipRecv["state"].get(); + } + } + else if( ipRecv.getName() == "test_set" ) + { + if( ipRecv.find( "toggle" ) ) + { + if( ipRecv["toggle"] == pcf::IndiElement::On ) + m_dmtweeterTestSet = true; + else + m_dmtweeterTestSet = false; + } + } + } + else if( dev == "dmncpc" ) + { + if( ipRecv.getName() == "fsm" ) + { + if( ipRecv.find( "state" ) ) + { + m_dmncpcState = ipRecv["state"].get(); + } + } + else if( ipRecv.getName() == "test_set" ) + { + if( ipRecv.find( "toggle" ) ) + { + if( ipRecv["toggle"] == pcf::IndiElement::On ) + m_dmncpcTestSet = true; + else + m_dmncpcTestSet = false; + } + } + } + + return; } -void pupilGuide::modGUISetEnable( bool enableModGUI, - bool enableModArrows - ) +void pupilGuide::modGUISetEnable( bool enableModGUI, bool enableModArrows ) { - if(enableModGUI) - { - ui.modState->setEnabled(true); - ui.modFreq_current->setEnabled(true); - ui.modRad_current->setEnabled(true); - ui.modCh1->setEnabled(true); - ui.modCh2->setEnabled(true); - - if(enableModArrows) - { - ui.button_tip_ul->setEnabled(true); - ui.button_tip_u->setEnabled(true); - ui.button_tip_ur->setEnabled(true); - ui.button_tip_l->setEnabled(true); - ui.button_tip_scale->setEnabled(true); - ui.button_tip_r->setEnabled(true); - ui.button_tip_dl->setEnabled(true); - ui.button_tip_d->setEnabled(true); - ui.button_tip_dr->setEnabled(true); - - if(m_tipmovewhat == MOVE_TEL || m_tipmovewhat == MOVE_WOOF) - { - ui.button_focus_p->setEnabled(true); - ui.button_focus_scale->setEnabled(true); - ui.button_focus_m->setEnabled(true); - } - else - { - ui.button_focus_p->setEnabled(false); - ui.button_focus_scale->setEnabled(false); - ui.button_focus_m->setEnabled(false); - } - } - else - { - ui.button_tip_ul->setEnabled(false); - ui.button_tip_u->setEnabled(false); - ui.button_tip_ur->setEnabled(false); - ui.button_tip_l->setEnabled(false); - ui.button_tip_scale->setEnabled(false); - ui.button_tip_r->setEnabled(false); - ui.button_tip_dl->setEnabled(false); - ui.button_tip_d->setEnabled(false); - ui.button_tip_dr->setEnabled(false); - - ui.button_focus_p->setEnabled(false); - ui.button_focus_scale->setEnabled(false); - ui.button_focus_m->setEnabled(false); - } - } - else - { - ui.modFreq_current->setEnabled(false); - ui.modRad_current->setEnabled(false); - ui.buttonMod_rest->setEnabled(false); - ui.buttonMod_set->setEnabled(false); - ui.buttonMod_mod->setEnabled(false); - ui.modCh1->setEnabled(false); - ui.modCh2->setEnabled(false); - - if(m_tipmovewhat == MOVE_TTM) - { - ui.button_tip_ul->setEnabled(false); - ui.button_tip_u->setEnabled(false); - ui.button_tip_ur->setEnabled(false); - ui.button_tip_l->setEnabled(false); - ui.button_tip_scale->setEnabled(false); - ui.button_tip_r->setEnabled(false); - ui.button_tip_dl->setEnabled(false); - ui.button_tip_d->setEnabled(false); - ui.button_tip_dr->setEnabled(false); - - ui.button_focus_p->setEnabled(false); - ui.button_focus_scale->setEnabled(false); - ui.button_focus_m->setEnabled(false); - } - else - { - ui.button_tip_ul->setEnabled(true); - ui.button_tip_u->setEnabled(true); - ui.button_tip_ur->setEnabled(true); - ui.button_tip_l->setEnabled(true); - ui.button_tip_scale->setEnabled(true); - ui.button_tip_r->setEnabled(true); - ui.button_tip_dl->setEnabled(true); - ui.button_tip_d->setEnabled(true); - ui.button_tip_dr->setEnabled(true); - - ui.button_focus_p->setEnabled(true); - ui.button_focus_scale->setEnabled(true); - ui.button_focus_m->setEnabled(true); - } - } + if( enableModGUI ) + { + ui.label_modulation->setEnabled( true ); + ui.modwfs_fsm->setEnabled( true ); + ui.modwfs_fsm->setEnabled( true ); + if(m_modState == 3 || m_modState == 4) + { + ui.label_modFreq->setEnabled( true ); + ui.modFreq_current->setEnabled( true ); + ui.label_modRad->setEnabled( true ); + ui.modRad_current->setEnabled( true ); + + ui.modCh1->setEnabled( true ); + ui.modCh2->setEnabled( true ); + } + else + { + ui.label_modFreq->setEnabled( false ); + ui.modFreq_current->setEnabled( false ); + ui.label_modRad->setEnabled( false ); + ui.modRad_current->setEnabled( false ); + + ui.modCh1->setEnabled( false ); + ui.modCh2->setEnabled( false ); + } + + + + if( enableModArrows ) + { + ui.button_tip_ul->setEnabled( true ); + ui.button_tip_u->setEnabled( true ); + ui.button_tip_ur->setEnabled( true ); + ui.button_tip_l->setEnabled( true ); + ui.button_tip_scale->setEnabled( true ); + ui.button_tip_r->setEnabled( true ); + ui.button_tip_dl->setEnabled( true ); + ui.button_tip_d->setEnabled( true ); + ui.button_tip_dr->setEnabled( true ); + + if( m_tipmovewhat == MOVE_TEL || m_tipmovewhat == MOVE_WOOF ) + { + ui.button_focus_p->setEnabled( true ); + ui.button_focus_scale->setEnabled( true ); + ui.button_focus_m->setEnabled( true ); + } + else + { + ui.button_focus_p->setEnabled( false ); + ui.button_focus_scale->setEnabled( false ); + ui.button_focus_m->setEnabled( false ); + } + } + else + { + ui.button_tip_ul->setEnabled( false ); + ui.button_tip_u->setEnabled( false ); + ui.button_tip_ur->setEnabled( false ); + ui.button_tip_l->setEnabled( false ); + ui.button_tip_scale->setEnabled( false ); + ui.button_tip_r->setEnabled( false ); + ui.button_tip_dl->setEnabled( false ); + ui.button_tip_d->setEnabled( false ); + ui.button_tip_dr->setEnabled( false ); + + ui.button_focus_p->setEnabled( false ); + ui.button_focus_scale->setEnabled( false ); + ui.button_focus_m->setEnabled( false ); + } + } + else + { + if(m_modFsmState != "POWEROFF" && m_modFsmState != "CONFIGURING") + { + ui.label_modulation->setEnabled( false ); + } + else + { + ui.label_modulation->setEnabled( true ); + } + ui.modwfs_fsm->setEnabled( false ); + ui.label_modFreq->setEnabled( false ); + ui.modFreq_current->setEnabled( false ); + ui.label_modRad->setEnabled( false ); + ui.modRad_current->setEnabled( false ); + ui.buttonMod_rest->setEnabled( false ); + ui.buttonMod_set->setEnabled( false ); + ui.buttonMod_mod->setEnabled( false ); + ui.modCh1->setEnabled( false ); + ui.modCh2->setEnabled( false ); + + if( m_tipmovewhat == MOVE_TTM ) + { + ui.button_tip_ul->setEnabled( false ); + ui.button_tip_u->setEnabled( false ); + ui.button_tip_ur->setEnabled( false ); + ui.button_tip_l->setEnabled( false ); + ui.button_tip_scale->setEnabled( false ); + ui.button_tip_r->setEnabled( false ); + ui.button_tip_dl->setEnabled( false ); + ui.button_tip_d->setEnabled( false ); + ui.button_tip_dr->setEnabled( false ); + + ui.button_focus_p->setEnabled( false ); + ui.button_focus_scale->setEnabled( false ); + ui.button_focus_m->setEnabled( false ); + } + else + { + ui.button_tip_ul->setEnabled( true ); + ui.button_tip_u->setEnabled( true ); + ui.button_tip_ur->setEnabled( true ); + ui.button_tip_l->setEnabled( true ); + ui.button_tip_scale->setEnabled( true ); + ui.button_tip_r->setEnabled( true ); + ui.button_tip_dl->setEnabled( true ); + ui.button_tip_d->setEnabled( true ); + ui.button_tip_dr->setEnabled( true ); + + ui.button_focus_p->setEnabled( true ); + ui.button_focus_scale->setEnabled( true ); + ui.button_focus_m->setEnabled( true ); + } + } } -void pupilGuide::camwfsfitSetEnabled(bool enabled) +void pupilGuide::camwfsfitSetEnabled( bool enabled ) { - ui.labelMedianFluxes->setEnabled(enabled); - ui.med1->setEnabled(enabled); - ui.med2->setEnabled(enabled); - ui.med3->setEnabled(enabled); - ui.med4->setEnabled(enabled); - ui.setDelta->setEnabled(enabled); - ui.fitThreshold->setEnabled(enabled); - - if(enabled == false) - { - ui.med1->setText(""); - ui.med2->setText(""); - ui.med3->setText(""); - ui.med4->setText(""); - } - - ui.coordLL_D->setEnabled(enabled); - ui.coordLR_D->setEnabled(enabled); - ui.coordUL_D->setEnabled(enabled); - ui.coordUR_D->setEnabled(enabled); - ui.coordLL_x->setEnabled(enabled); - ui.coordLR_x->setEnabled(enabled); - ui.coordUL_x->setEnabled(enabled); - ui.coordUR_x->setEnabled(enabled); - ui.coordLL_y->setEnabled(enabled); - ui.coordLR_y->setEnabled(enabled); - ui.coordUL_y->setEnabled(enabled); - ui.coordUR_y->setEnabled(enabled); - ui.coordAvg_D->setEnabled(enabled); - ui.coordAvg_x->setEnabled(enabled); - ui.coordAvg_y->setEnabled(enabled); - ui.setDelta_pup->setEnabled(enabled); - ui.labelx->setEnabled(enabled); - ui.labely->setEnabled(enabled); - ui.labelD->setEnabled(enabled); - ui.labelUR->setEnabled(enabled); - ui.labelUL->setEnabled(enabled); - ui.labelLR->setEnabled(enabled); - ui.labelLL->setEnabled(enabled); - ui.labelAvg->setEnabled(enabled); + ui.labelMedianFluxes->setEnabled( enabled ); + ui.med1->setEnabled( enabled ); + ui.med2->setEnabled( enabled ); + ui.med3->setEnabled( enabled ); + ui.med4->setEnabled( enabled ); + ui.setDelta->setEnabled( enabled ); + ui.fitThreshold->setEnabled( enabled ); + + if( enabled == false ) + { + ui.med1->setText( "" ); + ui.med2->setText( "" ); + ui.med3->setText( "" ); + ui.med4->setText( "" ); + } + + ui.coordLL_D->setEnabled( enabled ); + ui.coordLR_D->setEnabled( enabled ); + ui.coordUL_D->setEnabled( enabled ); + ui.coordUR_D->setEnabled( enabled ); + ui.coordLL_x->setEnabled( enabled ); + ui.coordLR_x->setEnabled( enabled ); + ui.coordUL_x->setEnabled( enabled ); + ui.coordUR_x->setEnabled( enabled ); + ui.coordLL_y->setEnabled( enabled ); + ui.coordLR_y->setEnabled( enabled ); + ui.coordUL_y->setEnabled( enabled ); + ui.coordUR_y->setEnabled( enabled ); + ui.coordAvg_D->setEnabled( enabled ); + ui.coordAvg_x->setEnabled( enabled ); + ui.coordAvg_y->setEnabled( enabled ); + ui.setDelta_pup->setEnabled( enabled ); + ui.labelx->setEnabled( enabled ); + ui.labely->setEnabled( enabled ); + ui.labelD->setEnabled( enabled ); + ui.labelUR->setEnabled( enabled ); + ui.labelUL->setEnabled( enabled ); + ui.labelLR->setEnabled( enabled ); + ui.labelLL->setEnabled( enabled ); + ui.labelAvg->setEnabled( enabled ); } -void pupilGuide::camlensSetEnabled(bool enabled) +void pupilGuide::camlensSetEnabled( bool enabled, + int whichcl +) { - ui.camlens_fsm->setEnabled(enabled); - ui.camlens_x_pos->setEnabled(enabled); - ui.camlens_y_pos->setEnabled(enabled); - ui.button_camlens_u->setEnabled(enabled); - ui.button_camlens_l->setEnabled(enabled); - ui.button_camlens_r->setEnabled(enabled); - ui.button_camlens_d->setEnabled(enabled); - ui.button_camlens_scale->setEnabled(enabled); + if( whichcl == CAMLENS_BOTH ) + { + ui.label_camlens->setEnabled( enabled ); + ui.button_camlens_scale->setEnabled( enabled ); + } + else + { + ui.label_camlens->setEnabled( true ); + ui.button_camlens_scale->setEnabled( true ); + } + + if( whichcl == CAMLENS_X || whichcl == CAMLENS_BOTH ) + { + ui.label_camlensX_fsm->setEnabled( enabled ); + ui.camlensX_fsm->setEnabled( enabled ); + ui.camlensX_pos->setEnabled( enabled ); + ui.button_camlens_l->setEnabled( enabled ); + ui.button_camlens_r->setEnabled( enabled ); + } + + if( whichcl == CAMLENS_Y || whichcl == CAMLENS_BOTH ) + { + ui.label_camlensY_fsm->setEnabled( enabled ); + ui.camlensY_fsm->setEnabled( enabled ); + ui.camlensY_pos->setEnabled( enabled ); + ui.button_camlens_u->setEnabled( enabled ); + ui.button_camlens_d->setEnabled( enabled ); + } } void pupilGuide::updateGUI() { - - //--------- Modulation - - bool enableModGUI = true; - bool enableModArrows = true; - - char str[16]; - if(m_modFsmState == "READY") - { - if(m_modState == 1) - { - ui.modState->setText("RIP"); - if(m_tipmovewhat == MOVE_TTM) enableModArrows = false; - } - else - { - ui.modState->setText("SET"); - } - } - else if(m_modFsmState == "OPERATING") - { - ui.modState->setText("MODULATING"); - } - else - { - enableModGUI = false; - if(m_modFsmState == "") - { - ui.modState->setText("STATE UNKNOWN"); - ui.modState->setEnabled(false); - } - else - { - ui.modState->setText(m_modFsmState.c_str()); - ui.modState->setEnabled(true); - } - } - - modGUISetEnable(enableModGUI, enableModArrows); - - ui.modRad_current->updateGUI(); - ui.modFreq_current->updateGUI(); - ui.modCh1->updateGUI(); - ui.modCh2->updateGUI(); - - if(m_modState == 3 && enableModGUI) - { - ui.buttonMod_rest->setEnabled(true); - ui.buttonMod_set->setEnabled(false); - ui.buttonMod_mod->setEnabled(true); - } - else if(m_modState == 4 && enableModGUI) - { - ui.buttonMod_rest->setEnabled(true); - ui.buttonMod_set->setEnabled(true); - ui.buttonMod_mod->setEnabled(true); - } - else - { - if(enableModGUI) - { - ui.buttonMod_rest->setEnabled(true); - ui.buttonMod_set->setEnabled(true); - ui.buttonMod_mod->setEnabled(false); - } - } - - // ------- camwfs-align loop - if(!m_camwfsAlignLoopWaiting) - { - ui.pupilAlign_loopSlider->setEnabled(true); - if(m_camwfsAlignLoopState) - { - ui.pupilAlign_loopSlider->setSliderPosition(ui.pupilAlign_loopSlider->maximum()); - } - else - { - ui.pupilAlign_loopSlider->setSliderPosition(ui.pupilAlign_loopSlider->minimum()); - } - } - - // ------Pupil Fitting - - if( !(m_camwfsfitState == "READY" || m_camwfsfitState == "OPERATING")) - { - camwfsfitSetEnabled(false); - } - else - { - camwfsfitSetEnabled(true); - - double m1, m2, m3,m4; - - if(ui.setDelta->checkState() == Qt::Checked) - { - double ave = 0.25*(m_med1 + m_med2 + m_med3 + m_med4); - m1 = m_med1-ave; - m2 = m_med2-ave; - m3 = m_med3-ave; - m4 = m_med4-ave; - } - else - { - m1 = m_med1; - m2 = m_med2; - m3 = m_med3; - m4 = m_med4; - } - - snprintf(str, 16, "%0.1f", m1); - ui.med1->setText(str); - - snprintf(str, 16, "%0.1f", m2); - ui.med2->setText(str); - - snprintf(str, 16, "%0.1f", m3); - ui.med3->setText(str); - - snprintf(str, 16, "%0.1f", m4); - ui.med4->setText(str); - - double x1 = m_x1; - double y1 = m_y1; - double D1 = m_D1; - double x2 = m_x2; - double y2 = m_y2; - double D2 = m_D2; - double x3 = m_x3; - double y3 = m_y3; - double D3 = m_D3; - double x4 = m_x4; - double y4 = m_y4; - double D4 = m_D4; - - if(ui.setDelta_pup->checkState() == Qt::Checked) - { - x1 -= m_setx1; - y1 -= m_sety1; - D1 -= m_setD1; - - x2 -= m_setx2; - y2 -= m_sety2; - D2 -= m_setD2; - - x3 -= m_setx3; - y3 -= m_sety3; - D3 -= m_setD3; - - x4 -= m_setx4; - y4 -= m_sety4; - D4 -= m_setD4; - } - - snprintf(str, 16, "%0.2f", D1); - ui.coordLL_D->setText(str); - - snprintf(str, 16, "%0.2f", D2); - ui.coordLR_D->setText(str); - - snprintf(str, 16, "%0.2f", D3); - ui.coordUL_D->setText(str); - - snprintf(str, 16, "%0.2f", D4); - ui.coordUR_D->setText(str); - - snprintf(str, 16, "%0.2f", x1); - ui.coordLL_x->setText(str); - - snprintf(str, 16, "%0.2f", x2); - ui.coordLR_x->setText(str); - - snprintf(str, 16, "%0.2f", x3); - ui.coordUL_x->setText(str); - - snprintf(str, 16, "%0.2f", x4); - ui.coordUR_x->setText(str); - - snprintf(str, 16, "%0.2f", y1); - ui.coordLL_y->setText(str); - - snprintf(str, 16, "%0.2f", y2); - ui.coordLR_y->setText(str); - - snprintf(str, 16, "%0.2f", y3); - ui.coordUL_y->setText(str); - - - snprintf(str, 16, "%0.2f", y4); - ui.coordUR_y->setText(str); - - - snprintf(str, 16, "%0.2f", 0.25*(D1+D2+D3+D4)); - ui.coordAvg_D->setText(str); - - snprintf(str, 16, "%0.2f", 0.25*(x1+x2+x3+x4)); - ui.coordAvg_x->setText(str); - - snprintf(str, 16, "%0.2f", 0.25*(y1+y2+y3+y4)); - ui.coordAvg_y->setText(str); - - } - - // ------ camwfs averaging - if( m_camwfsavgState == "READY" || m_camwfsavgState == "OPERATING") - { - ui.fitAvgTime->setEnabled(true); - } - else - { - ui.fitAvgTime->setEnabled(false); - } - - // ------ dmtweeter - - if(m_dmtweeterState == "READY" || m_dmtweeterState == "OPERATING") - { - ui.buttonTweeterTest_set->setEnabled(true); - if(m_dmtweeterTestSet) - { - ui.buttonTweeterTest_set->setText("zero test"); - } - else - { - ui.buttonTweeterTest_set->setText("set test"); - } - } - else - { - ui.buttonTweeterTest_set->setEnabled(false); - ui.buttonTweeterTest_set->setText("set test"); - } - - // ------ dmncpc - - if(m_dmncpcState == "READY" || m_dmncpcState == "OPERATING") - { - ui.buttonNCPCTest_set->setEnabled(true); - if(m_dmncpcTestSet) - { - ui.buttonNCPCTest_set->setText("zero test"); - } - else - { - ui.buttonNCPCTest_set->setText("set test"); - } - } - else - { - ui.buttonNCPCTest_set->setEnabled(false); - ui.buttonNCPCTest_set->setText("set test"); - } - - // ------ Pupil Steering - bool enablePupFSM = true; - bool enablePupFSMArrows = true; - - if(m_pupFsmState == "READY") - { - ui.pupState->setEnabled(true); - ui.pupCh1->setEnabled(true); - ui.pupCh2->setEnabled(true); - ui.buttonPup_set->setEnabled(false); - ui.buttonPup_rest->setEnabled(true); - } - else if(m_pupFsmState == "NOTHOMED") - { - ui.pupState->setEnabled(true); - ui.pupCh1->setEnabled(false); - ui.pupCh2->setEnabled(false); - ui.buttonPup_set->setEnabled(true); - ui.buttonPup_rest->setEnabled(false); - enablePupFSMArrows = false; - } - else if(m_pupFsmState == "HOMING") - { - ui.pupState->setEnabled(true); - ui.pupCh1->setEnabled(false); - ui.pupCh2->setEnabled(false); - ui.buttonPup_set->setEnabled(false); - ui.buttonPup_rest->setEnabled(true); - enablePupFSMArrows = false; - } - else - { - enablePupFSM = false; - if(m_pupFsmState == "") - { - ui.pupState->setEnabled(false); - } - else - { - ui.pupState->setEnabled(true); - } - } - - if(enablePupFSM) - { - if(enablePupFSMArrows) - { - ui.button_pup_ul->setEnabled(true); - ui.button_pup_ur->setEnabled(true); - ui.button_pup_scale->setEnabled(true); - ui.button_pup_dl->setEnabled(true); - ui.button_pup_dr->setEnabled(true); - } - else - { - ui.button_pup_ul->setEnabled(false); - ui.button_pup_ur->setEnabled(false); - ui.button_pup_scale->setEnabled(false); - ui.button_pup_dl->setEnabled(false); - ui.button_pup_dr->setEnabled(false); - } - } - else - { - - ui.buttonPup_set->setEnabled(false); - ui.buttonPup_rest->setEnabled(false); - ui.pupCh1->setEnabled(false); - ui.pupCh2->setEnabled(false); - - ui.button_pup_ul->setEnabled(false); - ui.button_pup_ur->setEnabled(false); - ui.button_pup_scale->setEnabled(false); - ui.button_pup_dl->setEnabled(false); - ui.button_pup_dr->setEnabled(false); - } - - // ------ TTM Peri - bool enableTTMPeriFSM = true; - bool enableTTMPeriFSMArrows = true; - - if(m_ttmPeriFsmState == "READY") - { - ui.ttmPeriState->setEnabled(true); - ui.ttmPeriCh1->setEnabled(false); - ui.ttmPeriCh2->setEnabled(false); - ui.button_ttmPeri_set->setEnabled(true); - ui.button_ttmPeri_rest->setEnabled(false); - - enableTTMPeriFSMArrows = false; - } - else if(m_ttmPeriFsmState == "OPERATING") - { - ui.ttmPeriState->setEnabled(true); - ui.ttmPeriCh1->setEnabled(true); - ui.ttmPeriCh2->setEnabled(true); - ui.button_ttmPeri_set->setEnabled(false); - ui.button_ttmPeri_rest->setEnabled(true); - enableTTMPeriFSMArrows = true; - } - else - { - enableTTMPeriFSM = false; - - if(m_ttmPeriFsmState == "") - { - ui.ttmPeriState->setEnabled(false); - } - else - { - ui.ttmPeriState->setEnabled(true); - } - - ui.ttmPeriCh1->setEnabled(false); - ui.ttmPeriCh2->setEnabled(false); - ui.button_ttmPeri_set->setEnabled(false); - ui.button_ttmPeri_rest->setEnabled(false); - } - - if(enableTTMPeriFSM) - { - if(enableTTMPeriFSMArrows) - { - ui.button_ttmPeri_l->setEnabled(true); - ui.button_ttmPeri_r->setEnabled(true); - ui.button_ttmPeri_scale->setEnabled(true); - ui.button_ttmPeri_u->setEnabled(true); - ui.button_ttmPeri_d->setEnabled(true); - } - else - { - ui.button_ttmPeri_l->setEnabled(false); - ui.button_ttmPeri_r->setEnabled(false); - ui.button_ttmPeri_scale->setEnabled(false); - ui.button_ttmPeri_u->setEnabled(false); - ui.button_ttmPeri_d->setEnabled(false); - } - } - else - { - ui.button_ttmPeri_l->setEnabled(false); - ui.button_ttmPeri_r->setEnabled(false); - ui.button_ttmPeri_scale->setEnabled(false); - ui.button_ttmPeri_u->setEnabled(false); - ui.button_ttmPeri_d->setEnabled(false); - } - - // --- camera lens - - - if( (m_camlensxFsmState == "READY" || m_camlensxFsmState == "OPERATING") && - (m_camlensyFsmState == "READY" || m_camlensyFsmState == "OPERATING") ) - { - - camlensSetEnabled(true); - - if(m_camlensxFsmState == "OPERATING" || m_camlensyFsmState == "OPERATING") - { - ui.camlens_fsm->setText("OPERATING"); - } - else - { - ui.camlens_fsm->setText("READY"); - } - } - else - { - camlensSetEnabled(false); - - if(m_camlensxFsmState == "HOMING" || m_camlensyFsmState == "HOMING") - { - ui.camlens_fsm->setEnabled(true); - ui.camlens_fsm->setText("HOMING"); - } - else if(m_camlensxFsmState == "POWERON" || m_camlensyFsmState == "POWERON") - { - ui.camlens_fsm->setEnabled(true); - ui.camlens_fsm->setText("POWERON"); - } - else if(m_camlensxFsmState == "POWEROFF" && m_camlensyFsmState == "POWEROFF") - { - ui.camlens_fsm->setEnabled(true); - ui.camlens_fsm->setText("POWEROFF"); - } - else - { - if(m_camlensxFsmState == "" && m_camlensyFsmState == "") - { - ui.camlens_fsm->setEnabled(false); - ui.camlens_fsm->setText("STATE UNKNOWN"); - } - else - { - ui.camlens_fsm->setEnabled(true); - ui.camlens_fsm->setText(m_camlensxFsmState.c_str()); - } - } - } - - ui.pupilAlign_gain->updateGUI(); - - ui.fitThreshold->updateGUI(); - ui.fitAvgTime->updateGUI(); - ui.camlens_x_pos->updateGUI(); - ui.camlens_y_pos->updateGUI(); - -} //updateGUI() + + //--------- Modulation + + bool enableModGUI = true; + bool enableModArrows = true; + + char str[16]; + if( m_modFsmState == "NOTHOMED" ) + { + if( m_tipmovewhat == MOVE_TTM ) + { + enableModArrows = false; + } + } + else if( (m_modFsmState != "READY") && (m_modFsmState != "OPERATING") ) + { + enableModGUI = false; + } + + modGUISetEnable( enableModGUI, enableModArrows ); + + + + if( m_modState == 3 && enableModGUI ) + { + ui.buttonMod_rest->setEnabled( true ); + ui.buttonMod_set->setEnabled( false ); + ui.buttonMod_mod->setEnabled( true ); + } + else if( m_modState == 4 && enableModGUI ) + { + ui.buttonMod_rest->setEnabled( true ); + ui.buttonMod_set->setEnabled( true ); + ui.buttonMod_mod->setEnabled( true ); + } + else + { + if( enableModGUI ) + { + ui.buttonMod_rest->setEnabled( true ); + ui.buttonMod_set->setEnabled( true ); + ui.buttonMod_mod->setEnabled( false ); + } + } + + ui.modwfs_fsm->updateGUI(); + ui.modFreq_current->updateGUI(); + ui.modRad_current->updateGUI(); + ui.modCh1->updateGUI(); + ui.modCh2->updateGUI(); + + // ------Pupil Fitting + + if( !( m_camwfsfitState == "READY" || m_camwfsfitState == "OPERATING" ) ) + { + camwfsfitSetEnabled( false ); + } + else + { + camwfsfitSetEnabled( true ); + + double m1, m2, m3, m4; + + if( ui.setDelta->checkState() == Qt::Checked ) + { + double ave = 0.25 * ( m_med1 + m_med2 + m_med3 + m_med4 ); + m1 = m_med1 - ave; + m2 = m_med2 - ave; + m3 = m_med3 - ave; + m4 = m_med4 - ave; + } + else + { + m1 = m_med1; + m2 = m_med2; + m3 = m_med3; + m4 = m_med4; + } + + snprintf( str, 16, "%0.1f", m1 ); + ui.med1->setText( str ); + + snprintf( str, 16, "%0.1f", m2 ); + ui.med2->setText( str ); + + snprintf( str, 16, "%0.1f", m3 ); + ui.med3->setText( str ); + + snprintf( str, 16, "%0.1f", m4 ); + ui.med4->setText( str ); + + double x1 = m_x1; + double y1 = m_y1; + double D1 = m_D1; + double x2 = m_x2; + double y2 = m_y2; + double D2 = m_D2; + double x3 = m_x3; + double y3 = m_y3; + double D3 = m_D3; + double x4 = m_x4; + double y4 = m_y4; + double D4 = m_D4; + + if( ui.setDelta_pup->checkState() == Qt::Checked ) + { + x1 -= m_setx1; + y1 -= m_sety1; + D1 -= m_setD1; + + x2 -= m_setx2; + y2 -= m_sety2; + D2 -= m_setD2; + + x3 -= m_setx3; + y3 -= m_sety3; + D3 -= m_setD3; + + x4 -= m_setx4; + y4 -= m_sety4; + D4 -= m_setD4; + } + + snprintf( str, 16, "%0.2f", D1 ); + ui.coordLL_D->setText( str ); + + snprintf( str, 16, "%0.2f", D2 ); + ui.coordLR_D->setText( str ); + + snprintf( str, 16, "%0.2f", D3 ); + ui.coordUL_D->setText( str ); + + snprintf( str, 16, "%0.2f", D4 ); + ui.coordUR_D->setText( str ); + + snprintf( str, 16, "%0.2f", x1 ); + ui.coordLL_x->setText( str ); + + snprintf( str, 16, "%0.2f", x2 ); + ui.coordLR_x->setText( str ); + + snprintf( str, 16, "%0.2f", x3 ); + ui.coordUL_x->setText( str ); + + snprintf( str, 16, "%0.2f", x4 ); + ui.coordUR_x->setText( str ); + + snprintf( str, 16, "%0.2f", y1 ); + ui.coordLL_y->setText( str ); + + snprintf( str, 16, "%0.2f", y2 ); + ui.coordLR_y->setText( str ); + + snprintf( str, 16, "%0.2f", y3 ); + ui.coordUL_y->setText( str ); + + snprintf( str, 16, "%0.2f", y4 ); + ui.coordUR_y->setText( str ); + + snprintf( str, 16, "%0.2f", 0.25 * ( D1 + D2 + D3 + D4 ) ); + ui.coordAvg_D->setText( str ); + + snprintf( str, 16, "%0.2f", 0.25 * ( x1 + x2 + x3 + x4 ) ); + ui.coordAvg_x->setText( str ); + + snprintf( str, 16, "%0.2f", 0.25 * ( y1 + y2 + y3 + y4 ) ); + ui.coordAvg_y->setText( str ); + } + + // ------ camwfs averaging + if( m_camwfsavgState == "READY" || m_camwfsavgState == "OPERATING" ) + { + ui.fitAvgTime->setEnabled( true ); + } + else + { + ui.fitAvgTime->setEnabled( false ); + } + + // ------ dmtweeter + + if( m_dmtweeterState == "READY" || m_dmtweeterState == "OPERATING" ) + { + ui.buttonTweeterTest_set->setEnabled( true ); + if( m_dmtweeterTestSet ) + { + ui.buttonTweeterTest_set->setText( "zero test" ); + } + else + { + ui.buttonTweeterTest_set->setText( "set test" ); + } + } + else + { + ui.buttonTweeterTest_set->setEnabled( false ); + ui.buttonTweeterTest_set->setText( "set test" ); + } + + // ------ dmncpc + + if( m_dmncpcState == "READY" || m_dmncpcState == "OPERATING" ) + { + ui.buttonNCPCTest_set->setEnabled( true ); + if( m_dmncpcTestSet ) + { + ui.buttonNCPCTest_set->setText( "zero test" ); + } + else + { + ui.buttonNCPCTest_set->setText( "set test" ); + } + } + else + { + ui.buttonNCPCTest_set->setEnabled( false ); + ui.buttonNCPCTest_set->setText( "set test" ); + } + + // ------ Pupil Steering + bool enablePupFSM = true; + bool enablePupFSMArrows = true; + + if( m_pupFsmState == "READY" ) + { + ui.pupState->setEnabled( true ); + ui.pupCh1->setEnabled( true ); + ui.pupCh2->setEnabled( true ); + ui.buttonPup_set->setEnabled( false ); + ui.buttonPup_rest->setEnabled( true ); + } + else if( m_pupFsmState == "NOTHOMED" ) + { + ui.pupState->setEnabled( true ); + ui.pupCh1->setEnabled( false ); + ui.pupCh2->setEnabled( false ); + ui.buttonPup_set->setEnabled( true ); + ui.buttonPup_rest->setEnabled( false ); + enablePupFSMArrows = false; + } + else if( m_pupFsmState == "HOMING" ) + { + ui.pupState->setEnabled( true ); + ui.pupCh1->setEnabled( false ); + ui.pupCh2->setEnabled( false ); + ui.buttonPup_set->setEnabled( false ); + ui.buttonPup_rest->setEnabled( true ); + enablePupFSMArrows = false; + } + else + { + enablePupFSM = false; + if( m_pupFsmState == "" ) + { + ui.pupState->setEnabled( false ); + } + else + { + ui.pupState->setEnabled( true ); + } + } + + if( enablePupFSM ) + { + if( enablePupFSMArrows ) + { + ui.button_pup_ul->setEnabled( true ); + ui.button_pup_ur->setEnabled( true ); + ui.button_pup_scale->setEnabled( true ); + ui.button_pup_dl->setEnabled( true ); + ui.button_pup_dr->setEnabled( true ); + } + else + { + ui.button_pup_ul->setEnabled( false ); + ui.button_pup_ur->setEnabled( false ); + ui.button_pup_scale->setEnabled( false ); + ui.button_pup_dl->setEnabled( false ); + ui.button_pup_dr->setEnabled( false ); + } + } + else + { + + ui.buttonPup_set->setEnabled( false ); + ui.buttonPup_rest->setEnabled( false ); + ui.pupCh1->setEnabled( false ); + ui.pupCh2->setEnabled( false ); + + ui.button_pup_ul->setEnabled( false ); + ui.button_pup_ur->setEnabled( false ); + ui.button_pup_scale->setEnabled( false ); + ui.button_pup_dl->setEnabled( false ); + ui.button_pup_dr->setEnabled( false ); + } + + // ------ TTM Peri + bool enableTTMPeriFSM = true; + bool enableTTMPeriFSMArrows = true; + + if( m_ttmPeriFsmState == "READY" ) + { + ui.ttmPeriState->setEnabled( true ); + ui.ttmPeriCh1->setEnabled( false ); + ui.ttmPeriCh2->setEnabled( false ); + ui.button_ttmPeri_set->setEnabled( true ); + ui.button_ttmPeri_rest->setEnabled( false ); + + enableTTMPeriFSMArrows = false; + } + else if( m_ttmPeriFsmState == "OPERATING" ) + { + ui.ttmPeriState->setEnabled( true ); + ui.ttmPeriCh1->setEnabled( true ); + ui.ttmPeriCh2->setEnabled( true ); + ui.button_ttmPeri_set->setEnabled( false ); + ui.button_ttmPeri_rest->setEnabled( true ); + enableTTMPeriFSMArrows = true; + } + else + { + enableTTMPeriFSM = false; + + if( m_ttmPeriFsmState == "" ) + { + ui.ttmPeriState->setEnabled( false ); + } + else + { + ui.ttmPeriState->setEnabled( true ); + } + + ui.ttmPeriCh1->setEnabled( false ); + ui.ttmPeriCh2->setEnabled( false ); + ui.button_ttmPeri_set->setEnabled( false ); + ui.button_ttmPeri_rest->setEnabled( false ); + } + + if( enableTTMPeriFSM ) + { + if( enableTTMPeriFSMArrows ) + { + ui.button_ttmPeri_l->setEnabled( true ); + ui.button_ttmPeri_r->setEnabled( true ); + ui.button_ttmPeri_scale->setEnabled( true ); + ui.button_ttmPeri_u->setEnabled( true ); + ui.button_ttmPeri_d->setEnabled( true ); + } + else + { + ui.button_ttmPeri_l->setEnabled( false ); + ui.button_ttmPeri_r->setEnabled( false ); + ui.button_ttmPeri_scale->setEnabled( false ); + ui.button_ttmPeri_u->setEnabled( false ); + ui.button_ttmPeri_d->setEnabled( false ); + } + } + else + { + ui.button_ttmPeri_l->setEnabled( false ); + ui.button_ttmPeri_r->setEnabled( false ); + ui.button_ttmPeri_scale->setEnabled( false ); + ui.button_ttmPeri_u->setEnabled( false ); + ui.button_ttmPeri_d->setEnabled( false ); + } + + // --- camera lens + + if( ( m_camlensxFsmState == "READY" || m_camlensxFsmState == "OPERATING" ) && + ( m_camlensyFsmState == "READY" || m_camlensyFsmState == "OPERATING" ) ) + { + + camlensSetEnabled( true ); + } + else if( ( m_camlensxFsmState == "READY" || m_camlensxFsmState == "OPERATING" ) && + !( m_camlensyFsmState == "READY" || m_camlensyFsmState == "OPERATING" ) ) + { + camlensSetEnabled( true, CAMLENS_X ); + camlensSetEnabled( false, CAMLENS_Y ); + } + else if( !( m_camlensxFsmState == "READY" || m_camlensxFsmState == "OPERATING" ) && + ( m_camlensyFsmState == "READY" || m_camlensyFsmState == "OPERATING" ) ) + { + camlensSetEnabled( false, CAMLENS_X ); + camlensSetEnabled( true, CAMLENS_Y ); + } + else + { + camlensSetEnabled( false ); + } + + if(m_camlensxFsmState == "SHUTDOWN") + { + ui.camlensX_pos->onDisconnect(); + } + + if(m_camlensyFsmState == "SHUTDOWN") + { + ui.camlensY_pos->onDisconnect(); + } + + ui.camlensX_fsm->updateGUI(); + ui.camlensY_fsm->updateGUI(); + ui.camlensX_pos->updateGUI(); + ui.camlensY_pos->updateGUI(); + + ui.pupTrackLoop_deltaX->updateGUI(); + ui.pupTrackLoop_deltaY->updateGUI(); + + ui.pupTrackLoop_slider->updateGUI(); + ui.pupTrackLoop_gain->updateGUI(); + + ui.actAlignLoop_deltaX->updateGUI(); + ui.actAlignLoop_deltaY->updateGUI(); + + ui.actAlignLoop_slider->updateGUI(); + ui.actAlignLoop_gain->updateGUI(); + + ui.actAlignSensor_slider->updateGUI(); + ui.actAlignSensor_nAverage->updateGUI(); + ui.actAlignSensor_nImages->updateGUI(); + ui.actAlignSensor_pokeAmp->updateGUI(); + + ui.fitThreshold->updateGUI(); + ui.fitAvgTime->updateGUI(); + + +} // updateGUI() // ------------- modttm - + void pupilGuide::on_buttonMod_mod_pressed() { - pcf::IndiProperty ip(pcf::IndiProperty::Number); - - ip.setDevice("modwfs"); - ip.setName("modState"); - ip.add(pcf::IndiElement("target")); - ip["target"] = 4; - - sendNewProperty(ip); + pcf::IndiProperty ip( pcf::IndiProperty::Number ); + + ip.setDevice( "modwfs" ); + ip.setName( "modState" ); + ip.add( pcf::IndiElement( "target" ) ); + ip["target"] = 4; + + sendNewProperty( ip ); } - + void pupilGuide::on_buttonMod_set_pressed() { - pcf::IndiProperty ip(pcf::IndiProperty::Number); - - ip.setDevice("modwfs"); - ip.setName("modState"); - ip.add(pcf::IndiElement("target")); - ip["target"] = 3; - sendNewProperty(ip); + pcf::IndiProperty ip( pcf::IndiProperty::Number ); + + ip.setDevice( "modwfs" ); + ip.setName( "modState" ); + ip.add( pcf::IndiElement( "target" ) ); + ip["target"] = 3; + sendNewProperty( ip ); } - + void pupilGuide::on_buttonMod_rest_pressed() { - pcf::IndiProperty ip(pcf::IndiProperty::Number); - - ip.setDevice("modwfs"); - ip.setName("modState"); - ip.add(pcf::IndiElement("target")); - ip["target"] = 1; - - sendNewProperty(ip); + pcf::IndiProperty ip( pcf::IndiProperty::Number ); + + ip.setDevice( "modwfs" ); + ip.setName( "modState" ); + ip.add( pcf::IndiElement( "target" ) ); + ip["target"] = 1; + + sendNewProperty( ip ); } void pupilGuide::on_button_ttmtel_pressed() { - if(m_tipmovewhat == MOVE_TTM) - { - m_tipmovewhat = MOVE_WOOF; - ui.button_ttmtel->setText("move woofer"); - } - else if(m_tipmovewhat == MOVE_WOOF) - { - m_tipmovewhat = MOVE_TEL; - ui.button_ttmtel->setText("move telescope"); - } - else - { - m_tipmovewhat = MOVE_TTM; - ui.button_ttmtel->setText("move ttm"); - } + if( m_tipmovewhat == MOVE_TTM ) + { + m_tipmovewhat = MOVE_WOOF; + ui.button_ttmtel->setText( "move woofer" ); + } + else if( m_tipmovewhat == MOVE_WOOF ) + { + m_tipmovewhat = MOVE_TEL; + ui.button_ttmtel->setText( "move telescope" ); + } + else + { + m_tipmovewhat = MOVE_TTM; + ui.button_ttmtel->setText( "move ttm" ); + } } void pupilGuide::on_button_tip_u_pressed() { - pcf::IndiProperty ip(pcf::IndiProperty::Number); - - if(m_tipmovewhat == MOVE_TTM) - { - ip.setDevice("modwfs"); - ip.setName("offset"); - ip.add(pcf::IndiElement("y")); - ip["y"] = m_stepSize; - ip.add(pcf::IndiElement("x")); - ip["x"] = 0; - } - else if(m_tipmovewhat == MOVE_WOOF) - { - double tip, tilt; - wooferTipTilt(tip, tilt, 0, m_stepSize); - - ip.setDevice("wooferModes"); - ip.setName("target_amps"); - ip.add(pcf::IndiElement("0000")); - ip.add(pcf::IndiElement("0001")); - ip["0000"] = m_tip + tip; - ip["0001"] = m_tilt + tilt; - - } - else if(m_tipmovewhat == MOVE_TEL) - { - ip.setDevice("tcsi"); - ip.setName("pyrNudge"); - ip.add(pcf::IndiElement("y")); - ip["y"] = m_stepSize*5.; - ip.add(pcf::IndiElement("x")); - ip["x"] = 0; - } - else return; - - sendNewProperty(ip); - + pcf::IndiProperty ip( pcf::IndiProperty::Number ); + + if( m_tipmovewhat == MOVE_TTM ) + { + ip.setDevice( "modwfs" ); + ip.setName( "offset" ); + ip.add( pcf::IndiElement( "y" ) ); + ip["y"] = m_stepSize; + ip.add( pcf::IndiElement( "x" ) ); + ip["x"] = 0; + } + else if( m_tipmovewhat == MOVE_WOOF ) + { + double tip, tilt; + wooferTipTilt( tip, tilt, 0, m_stepSize ); + + ip.setDevice( "wooferModes" ); + ip.setName( "target_amps" ); + ip.add( pcf::IndiElement( "0000" ) ); + ip.add( pcf::IndiElement( "0001" ) ); + ip["0000"] = m_tip + tip; + ip["0001"] = m_tilt + tilt; + } + else if( m_tipmovewhat == MOVE_TEL ) + { + ip.setDevice( "tcsi" ); + ip.setName( "pyrNudge" ); + ip.add( pcf::IndiElement( "y" ) ); + ip["y"] = m_stepSize * 5.; + ip.add( pcf::IndiElement( "x" ) ); + ip["x"] = 0; + } + else + return; + + sendNewProperty( ip ); } -void pupilGuide::on_button_tip_ul_pressed() -{ - pcf::IndiProperty ip(pcf::IndiProperty::Number); - - if(m_tipmovewhat == MOVE_TTM) - { - ip.setDevice("modwfs"); - ip.setName("offset"); - ip.add(pcf::IndiElement("y")); - ip["y"] = m_stepSize/sqrt(2.); - ip.add(pcf::IndiElement("x")); - ip["x"] = -m_stepSize/sqrt(2.); - } - else if(m_tipmovewhat == MOVE_WOOF) - { - double tip, tilt; - wooferTipTilt(tip, tilt, m_stepSize/sqrt(2.), m_stepSize/sqrt(2.)); - - ip.setDevice("wooferModes"); - ip.setName("target_amps"); - ip.add(pcf::IndiElement("0000")); - ip.add(pcf::IndiElement("0001")); - ip["0000"] = m_tip + tip; - ip["0001"] = m_tilt + tilt; - } - else if(m_tipmovewhat == MOVE_TEL) - { - ip.setDevice("tcsi"); - ip.setName("pyrNudge"); - ip.add(pcf::IndiElement("y")); - ip["y"] = m_stepSize*5./sqrt(2.); - ip.add(pcf::IndiElement("x")); - ip["x"] = m_stepSize*5./sqrt(2.); - } - - sendNewProperty(ip); - - +void pupilGuide::on_button_tip_ul_pressed() +{ + pcf::IndiProperty ip( pcf::IndiProperty::Number ); + + if( m_tipmovewhat == MOVE_TTM ) + { + ip.setDevice( "modwfs" ); + ip.setName( "offset" ); + ip.add( pcf::IndiElement( "y" ) ); + ip["y"] = m_stepSize / sqrt( 2. ); + ip.add( pcf::IndiElement( "x" ) ); + ip["x"] = -m_stepSize / sqrt( 2. ); + } + else if( m_tipmovewhat == MOVE_WOOF ) + { + double tip, tilt; + wooferTipTilt( tip, tilt, m_stepSize / sqrt( 2. ), m_stepSize / sqrt( 2. ) ); + + ip.setDevice( "wooferModes" ); + ip.setName( "target_amps" ); + ip.add( pcf::IndiElement( "0000" ) ); + ip.add( pcf::IndiElement( "0001" ) ); + ip["0000"] = m_tip + tip; + ip["0001"] = m_tilt + tilt; + } + else if( m_tipmovewhat == MOVE_TEL ) + { + ip.setDevice( "tcsi" ); + ip.setName( "pyrNudge" ); + ip.add( pcf::IndiElement( "y" ) ); + ip["y"] = m_stepSize * 5. / sqrt( 2. ); + ip.add( pcf::IndiElement( "x" ) ); + ip["x"] = m_stepSize * 5. / sqrt( 2. ); + } + + sendNewProperty( ip ); } void pupilGuide::on_button_tip_l_pressed() { - pcf::IndiProperty ip(pcf::IndiProperty::Number); - - if(m_tipmovewhat == MOVE_TTM) - { - ip.setDevice("modwfs"); - ip.setName("offset"); - ip.add(pcf::IndiElement("y")); - ip["y"] = 0; - ip.add(pcf::IndiElement("x")); - ip["x"] = -m_stepSize; - } - else if(m_tipmovewhat == MOVE_WOOF) - { - double tip, tilt; - wooferTipTilt(tip, tilt, m_stepSize, 0); - - ip.setDevice("wooferModes"); - ip.setName("target_amps"); - ip.add(pcf::IndiElement("0000")); - ip.add(pcf::IndiElement("0001")); - ip["0000"] = m_tip + tip; - ip["0001"] = m_tilt + tilt; - } - else if(m_tipmovewhat == MOVE_TEL) - { - ip.setDevice("tcsi"); - ip.setName("pyrNudge"); - ip.add(pcf::IndiElement("y")); - ip["y"] = 0; - ip.add(pcf::IndiElement("x")); - ip["x"] = -m_stepSize*5.; - } - - sendNewProperty(ip); - + pcf::IndiProperty ip( pcf::IndiProperty::Number ); + + if( m_tipmovewhat == MOVE_TTM ) + { + ip.setDevice( "modwfs" ); + ip.setName( "offset" ); + ip.add( pcf::IndiElement( "y" ) ); + ip["y"] = 0; + ip.add( pcf::IndiElement( "x" ) ); + ip["x"] = -m_stepSize; + } + else if( m_tipmovewhat == MOVE_WOOF ) + { + double tip, tilt; + wooferTipTilt( tip, tilt, m_stepSize, 0 ); + + ip.setDevice( "wooferModes" ); + ip.setName( "target_amps" ); + ip.add( pcf::IndiElement( "0000" ) ); + ip.add( pcf::IndiElement( "0001" ) ); + ip["0000"] = m_tip + tip; + ip["0001"] = m_tilt + tilt; + } + else if( m_tipmovewhat == MOVE_TEL ) + { + ip.setDevice( "tcsi" ); + ip.setName( "pyrNudge" ); + ip.add( pcf::IndiElement( "y" ) ); + ip["y"] = 0; + ip.add( pcf::IndiElement( "x" ) ); + ip["x"] = -m_stepSize * 5.; + } + + sendNewProperty( ip ); } void pupilGuide::on_button_tip_dl_pressed() { - pcf::IndiProperty ip(pcf::IndiProperty::Number); - - if(m_tipmovewhat == MOVE_TTM) - { - ip.setDevice("modwfs"); - ip.setName("offset"); - ip.add(pcf::IndiElement("y")); - ip["y"] = -m_stepSize/sqrt(2.); - ip.add(pcf::IndiElement("x")); - ip["x"] = -m_stepSize/sqrt(2.); - } - else if(m_tipmovewhat == MOVE_WOOF) - { - double tip, tilt; - wooferTipTilt(tip, tilt, m_stepSize/sqrt(2.), -m_stepSize/sqrt(2.)); - - ip.setDevice("wooferModes"); - ip.setName("target_amps"); - ip.add(pcf::IndiElement("0000")); - ip.add(pcf::IndiElement("0001")); - ip["0000"] = m_tip + tip; - ip["0001"] = m_tilt + tilt; - } - else if(m_tipmovewhat == MOVE_TEL) - { - ip.setDevice("tcsi"); - ip.setName("pyrNudge"); - ip.add(pcf::IndiElement("y")); - ip["y"] = -m_stepSize*5./sqrt(2.); - ip.add(pcf::IndiElement("x")); - ip["x"] = -m_stepSize*5./sqrt(2.); - } - - sendNewProperty(ip); - - + pcf::IndiProperty ip( pcf::IndiProperty::Number ); + + if( m_tipmovewhat == MOVE_TTM ) + { + ip.setDevice( "modwfs" ); + ip.setName( "offset" ); + ip.add( pcf::IndiElement( "y" ) ); + ip["y"] = -m_stepSize / sqrt( 2. ); + ip.add( pcf::IndiElement( "x" ) ); + ip["x"] = -m_stepSize / sqrt( 2. ); + } + else if( m_tipmovewhat == MOVE_WOOF ) + { + double tip, tilt; + wooferTipTilt( tip, tilt, m_stepSize / sqrt( 2. ), -m_stepSize / sqrt( 2. ) ); + + ip.setDevice( "wooferModes" ); + ip.setName( "target_amps" ); + ip.add( pcf::IndiElement( "0000" ) ); + ip.add( pcf::IndiElement( "0001" ) ); + ip["0000"] = m_tip + tip; + ip["0001"] = m_tilt + tilt; + } + else if( m_tipmovewhat == MOVE_TEL ) + { + ip.setDevice( "tcsi" ); + ip.setName( "pyrNudge" ); + ip.add( pcf::IndiElement( "y" ) ); + ip["y"] = -m_stepSize * 5. / sqrt( 2. ); + ip.add( pcf::IndiElement( "x" ) ); + ip["x"] = -m_stepSize * 5. / sqrt( 2. ); + } + + sendNewProperty( ip ); } void pupilGuide::on_button_tip_d_pressed() { - pcf::IndiProperty ip(pcf::IndiProperty::Number); - - if(m_tipmovewhat == MOVE_TTM) - { - ip.setDevice("modwfs"); - ip.setName("offset"); - ip.add(pcf::IndiElement("y")); - ip["y"] = -m_stepSize; - ip.add(pcf::IndiElement("x")); - ip["x"] = 0; - } - else if(m_tipmovewhat == MOVE_WOOF) - { - double tip, tilt; - wooferTipTilt(tip, tilt, 0, -m_stepSize); - - ip.setDevice("wooferModes"); - ip.setName("target_amps"); - ip.add(pcf::IndiElement("0000")); - ip.add(pcf::IndiElement("0001")); - ip["0000"] = m_tip + tip; - ip["0001"] = m_tilt + tilt; - } - else if(m_tipmovewhat == MOVE_TEL) - { - ip.setDevice("tcsi"); - ip.setName("pyrNudge"); - ip.add(pcf::IndiElement("y")); - ip["y"] = -m_stepSize*5.; - ip.add(pcf::IndiElement("x")); - ip["x"] = 0; - } - - sendNewProperty(ip); + pcf::IndiProperty ip( pcf::IndiProperty::Number ); + + if( m_tipmovewhat == MOVE_TTM ) + { + ip.setDevice( "modwfs" ); + ip.setName( "offset" ); + ip.add( pcf::IndiElement( "y" ) ); + ip["y"] = -m_stepSize; + ip.add( pcf::IndiElement( "x" ) ); + ip["x"] = 0; + } + else if( m_tipmovewhat == MOVE_WOOF ) + { + double tip, tilt; + wooferTipTilt( tip, tilt, 0, -m_stepSize ); + + ip.setDevice( "wooferModes" ); + ip.setName( "target_amps" ); + ip.add( pcf::IndiElement( "0000" ) ); + ip.add( pcf::IndiElement( "0001" ) ); + ip["0000"] = m_tip + tip; + ip["0001"] = m_tilt + tilt; + } + else if( m_tipmovewhat == MOVE_TEL ) + { + ip.setDevice( "tcsi" ); + ip.setName( "pyrNudge" ); + ip.add( pcf::IndiElement( "y" ) ); + ip["y"] = -m_stepSize * 5.; + ip.add( pcf::IndiElement( "x" ) ); + ip["x"] = 0; + } + + sendNewProperty( ip ); } void pupilGuide::on_button_tip_dr_pressed() { - pcf::IndiProperty ip(pcf::IndiProperty::Number); - - if(m_tipmovewhat == MOVE_TTM) - { - ip.setDevice("modwfs"); - ip.setName("offset"); - ip.add(pcf::IndiElement("y")); - ip["y"] = -m_stepSize/sqrt(2.); - ip.add(pcf::IndiElement("x")); - ip["x"] = m_stepSize/sqrt(2.); - } - else if(m_tipmovewhat == MOVE_WOOF) - { - double tip, tilt; - wooferTipTilt(tip, tilt, -m_stepSize/sqrt(2.), -m_stepSize/sqrt(2.)); - - ip.setDevice("wooferModes"); - ip.setName("target_amps"); - ip.add(pcf::IndiElement("0000")); - ip.add(pcf::IndiElement("0001")); - ip["0000"] = m_tip + tip; - ip["0001"] = m_tilt + tilt; - } - else if(m_tipmovewhat == MOVE_TEL) - { - ip.setDevice("tcsi"); - ip.setName("pyrNudge"); - ip.add(pcf::IndiElement("y")); - ip["y"] = -m_stepSize*5./sqrt(2.); - ip.add(pcf::IndiElement("x")); - ip["x"] = m_stepSize*5./sqrt(2.); - } - else return; - - sendNewProperty(ip); - - + pcf::IndiProperty ip( pcf::IndiProperty::Number ); + + if( m_tipmovewhat == MOVE_TTM ) + { + ip.setDevice( "modwfs" ); + ip.setName( "offset" ); + ip.add( pcf::IndiElement( "y" ) ); + ip["y"] = -m_stepSize / sqrt( 2. ); + ip.add( pcf::IndiElement( "x" ) ); + ip["x"] = m_stepSize / sqrt( 2. ); + } + else if( m_tipmovewhat == MOVE_WOOF ) + { + double tip, tilt; + wooferTipTilt( tip, tilt, -m_stepSize / sqrt( 2. ), -m_stepSize / sqrt( 2. ) ); + + ip.setDevice( "wooferModes" ); + ip.setName( "target_amps" ); + ip.add( pcf::IndiElement( "0000" ) ); + ip.add( pcf::IndiElement( "0001" ) ); + ip["0000"] = m_tip + tip; + ip["0001"] = m_tilt + tilt; + } + else if( m_tipmovewhat == MOVE_TEL ) + { + ip.setDevice( "tcsi" ); + ip.setName( "pyrNudge" ); + ip.add( pcf::IndiElement( "y" ) ); + ip["y"] = -m_stepSize * 5. / sqrt( 2. ); + ip.add( pcf::IndiElement( "x" ) ); + ip["x"] = m_stepSize * 5. / sqrt( 2. ); + } + else + return; + + sendNewProperty( ip ); } void pupilGuide::on_button_tip_r_pressed() { - pcf::IndiProperty ip(pcf::IndiProperty::Number); - - if(m_tipmovewhat == MOVE_TTM) - { - ip.setDevice("modwfs"); - ip.setName("offset"); - ip.add(pcf::IndiElement("y")); - ip["y"] = 0; - ip.add(pcf::IndiElement("x")); - ip["x"] = m_stepSize; - } - else if(m_tipmovewhat == MOVE_WOOF) - { - double tip, tilt; - wooferTipTilt(tip, tilt, -m_stepSize, 0); - - ip.setDevice("wooferModes"); - ip.setName("target_amps"); - ip.add(pcf::IndiElement("0000")); - ip.add(pcf::IndiElement("0001")); - ip["0000"] = m_tip + tip; - ip["0001"] = m_tilt + tilt; - } - else if(m_tipmovewhat == MOVE_TEL) - { - ip.setDevice("tcsi"); - ip.setName("pyrNudge"); - ip.add(pcf::IndiElement("y")); - ip["y"] = 0; - ip.add(pcf::IndiElement("x")); - ip["x"] = m_stepSize*5.; - } - else return; - - sendNewProperty(ip); - + pcf::IndiProperty ip( pcf::IndiProperty::Number ); + + if( m_tipmovewhat == MOVE_TTM ) + { + ip.setDevice( "modwfs" ); + ip.setName( "offset" ); + ip.add( pcf::IndiElement( "y" ) ); + ip["y"] = 0; + ip.add( pcf::IndiElement( "x" ) ); + ip["x"] = m_stepSize; + } + else if( m_tipmovewhat == MOVE_WOOF ) + { + double tip, tilt; + wooferTipTilt( tip, tilt, -m_stepSize, 0 ); + + ip.setDevice( "wooferModes" ); + ip.setName( "target_amps" ); + ip.add( pcf::IndiElement( "0000" ) ); + ip.add( pcf::IndiElement( "0001" ) ); + ip["0000"] = m_tip + tip; + ip["0001"] = m_tilt + tilt; + } + else if( m_tipmovewhat == MOVE_TEL ) + { + ip.setDevice( "tcsi" ); + ip.setName( "pyrNudge" ); + ip.add( pcf::IndiElement( "y" ) ); + ip["y"] = 0; + ip.add( pcf::IndiElement( "x" ) ); + ip["x"] = m_stepSize * 5.; + } + else + return; + + sendNewProperty( ip ); } void pupilGuide::on_button_tip_ur_pressed() { - pcf::IndiProperty ip(pcf::IndiProperty::Number); - - if(m_tipmovewhat == MOVE_TTM) - { - ip.setDevice("modwfs"); - ip.setName("offset"); - ip.add(pcf::IndiElement("y")); - ip["y"] = m_stepSize/sqrt(2.); - ip.add(pcf::IndiElement("x")); - ip["x"] = m_stepSize/sqrt(2.); - } - else if(m_tipmovewhat == MOVE_WOOF) - { - double tip, tilt; - wooferTipTilt(tip, tilt, -m_stepSize/sqrt(2.), m_stepSize/sqrt(2.)); - - ip.setDevice("wooferModes"); - ip.setName("target_amps"); - ip.add(pcf::IndiElement("0000")); - ip.add(pcf::IndiElement("0001")); - ip["0000"] = m_tip + tip; - ip["0001"] = m_tilt + tilt; - } - else if(m_tipmovewhat == MOVE_TEL) - { - ip.setDevice("tcsi"); - ip.setName("pyrNudge"); - ip.add(pcf::IndiElement("y")); - ip["y"] = m_stepSize*5./sqrt(2.); - ip.add(pcf::IndiElement("x")); - ip["x"] = m_stepSize*5./sqrt(2.); - } - else return; - - sendNewProperty(ip); - - + pcf::IndiProperty ip( pcf::IndiProperty::Number ); + + if( m_tipmovewhat == MOVE_TTM ) + { + ip.setDevice( "modwfs" ); + ip.setName( "offset" ); + ip.add( pcf::IndiElement( "y" ) ); + ip["y"] = m_stepSize / sqrt( 2. ); + ip.add( pcf::IndiElement( "x" ) ); + ip["x"] = m_stepSize / sqrt( 2. ); + } + else if( m_tipmovewhat == MOVE_WOOF ) + { + double tip, tilt; + wooferTipTilt( tip, tilt, -m_stepSize / sqrt( 2. ), m_stepSize / sqrt( 2. ) ); + + ip.setDevice( "wooferModes" ); + ip.setName( "target_amps" ); + ip.add( pcf::IndiElement( "0000" ) ); + ip.add( pcf::IndiElement( "0001" ) ); + ip["0000"] = m_tip + tip; + ip["0001"] = m_tilt + tilt; + } + else if( m_tipmovewhat == MOVE_TEL ) + { + ip.setDevice( "tcsi" ); + ip.setName( "pyrNudge" ); + ip.add( pcf::IndiElement( "y" ) ); + ip["y"] = m_stepSize * 5. / sqrt( 2. ); + ip.add( pcf::IndiElement( "x" ) ); + ip["x"] = m_stepSize * 5. / sqrt( 2. ); + } + else + return; + + sendNewProperty( ip ); } void pupilGuide::on_button_tip_scale_pressed() { - if(((int) (100*m_stepSize)) == 100) - { - m_stepSize = 0.5; - } - else if(((int) (100*m_stepSize)) == 50) - { - m_stepSize = 0.1; - } - else if(((int) (100*m_stepSize)) == 10) - { - m_stepSize = 0.05; - } - else if(((int) (100*m_stepSize)) == 5) - { - m_stepSize = 0.01; - } - else if(((int) (100*m_stepSize)) == 1) - { - m_stepSize = 1.0; - } - - char ss[5]; - snprintf(ss, 5, "%0.2f", m_stepSize); - ui.button_tip_scale->setText(ss); - + if( ( (int)( 100 * m_stepSize ) ) == 100 ) + { + m_stepSize = 0.5; + } + else if( ( (int)( 100 * m_stepSize ) ) == 50 ) + { + m_stepSize = 0.1; + } + else if( ( (int)( 100 * m_stepSize ) ) == 10 ) + { + m_stepSize = 0.05; + } + else if( ( (int)( 100 * m_stepSize ) ) == 5 ) + { + m_stepSize = 0.01; + } + else if( ( (int)( 100 * m_stepSize ) ) == 1 ) + { + m_stepSize = 1.0; + } + char ss[5]; + snprintf( ss, 5, "%0.2f", m_stepSize ); + ui.button_tip_scale->setText( ss ); } void pupilGuide::on_button_focus_p_pressed() { - pcf::IndiProperty ip(pcf::IndiProperty::Number); - - if(m_tipmovewhat == MOVE_WOOF) - { - - ip.setDevice("wooferModes"); - ip.setName("target_amps"); - ip.add(pcf::IndiElement("0002")); - ip["0002"] = m_focus + m_focusStepSize*0.2; - - } - else if(m_tipmovewhat == MOVE_TEL) - { - ip.setDevice("tcsi"); - ip.setName("pyrNudge"); - ip.add(pcf::IndiElement("z")); - ip["z"] = m_stepSize*100.; - } - else return; - - sendNewProperty(ip); - + pcf::IndiProperty ip( pcf::IndiProperty::Number ); + + if( m_tipmovewhat == MOVE_WOOF ) + { + + ip.setDevice( "wooferModes" ); + ip.setName( "target_amps" ); + ip.add( pcf::IndiElement( "0002" ) ); + ip["0002"] = m_focus + m_focusStepSize * 0.2; + } + else if( m_tipmovewhat == MOVE_TEL ) + { + ip.setDevice( "tcsi" ); + ip.setName( "pyrNudge" ); + ip.add( pcf::IndiElement( "z" ) ); + ip["z"] = m_stepSize * 100.; + } + else + return; + + sendNewProperty( ip ); } void pupilGuide::on_button_focus_m_pressed() { - pcf::IndiProperty ip(pcf::IndiProperty::Number); - - if(m_tipmovewhat == MOVE_WOOF) - { - - ip.setDevice("wooferModes"); - ip.setName("target_amps"); - ip.add(pcf::IndiElement("0002")); - ip["0002"] = m_focus - m_focusStepSize*0.2; - - } - else if(m_tipmovewhat == MOVE_TEL) - { - ip.setDevice("tcsi"); - ip.setName("pyrNudge"); - ip.add(pcf::IndiElement("z")); - ip["z"] = -m_stepSize*100.; - } - else return; - - sendNewProperty(ip); + pcf::IndiProperty ip( pcf::IndiProperty::Number ); + + if( m_tipmovewhat == MOVE_WOOF ) + { + + ip.setDevice( "wooferModes" ); + ip.setName( "target_amps" ); + ip.add( pcf::IndiElement( "0002" ) ); + ip["0002"] = m_focus - m_focusStepSize * 0.2; + } + else if( m_tipmovewhat == MOVE_TEL ) + { + ip.setDevice( "tcsi" ); + ip.setName( "pyrNudge" ); + ip.add( pcf::IndiElement( "z" ) ); + ip["z"] = -m_stepSize * 100.; + } + else + return; + + sendNewProperty( ip ); } void pupilGuide::on_button_focus_scale_pressed() { - if(((int) (100*m_focusStepSize)) == 100) - { - m_focusStepSize = 0.5; - } - else if(((int) (100*m_focusStepSize)) == 50) - { - m_focusStepSize = 0.1; - } - else if(((int) (100*m_focusStepSize)) == 10) - { - m_focusStepSize = 0.05; - } - else if(((int) (100*m_focusStepSize)) == 5) - { - m_focusStepSize = 0.01; - } - else if(((int) (100*m_focusStepSize)) == 1) - { - m_focusStepSize = 1.0; - } - - char ss[5]; - snprintf(ss, 5, "%0.2f", m_focusStepSize); - ui.button_focus_scale->setText(ss); + if( ( (int)( 100 * m_focusStepSize ) ) == 100 ) + { + m_focusStepSize = 0.5; + } + else if( ( (int)( 100 * m_focusStepSize ) ) == 50 ) + { + m_focusStepSize = 0.1; + } + else if( ( (int)( 100 * m_focusStepSize ) ) == 10 ) + { + m_focusStepSize = 0.05; + } + else if( ( (int)( 100 * m_focusStepSize ) ) == 5 ) + { + m_focusStepSize = 0.01; + } + else if( ( (int)( 100 * m_focusStepSize ) ) == 1 ) + { + m_focusStepSize = 1.0; + } + + char ss[5]; + snprintf( ss, 5, "%0.2f", m_focusStepSize ); + ui.button_focus_scale->setText( ss ); } //----------- dmtweeter void pupilGuide::on_buttonTweeterTest_set_pressed() { - pcf::IndiProperty ip(pcf::IndiProperty::Switch); - - ip.setDevice("dmtweeter"); - ip.setName("test_set"); - ip.add(pcf::IndiElement("toggle")); - - if(m_dmtweeterTestSet) - { - ip["toggle"].setSwitchState(pcf::IndiElement::Off); - } - else - { - ip["toggle"].setSwitchState(pcf::IndiElement::On); - } - - sendNewProperty(ip); + pcf::IndiProperty ip( pcf::IndiProperty::Switch ); + + ip.setDevice( "dmtweeter" ); + ip.setName( "test_set" ); + ip.add( pcf::IndiElement( "toggle" ) ); + + if( m_dmtweeterTestSet ) + { + ip["toggle"].setSwitchState( pcf::IndiElement::Off ); + } + else + { + ip["toggle"].setSwitchState( pcf::IndiElement::On ); + } + + sendNewProperty( ip ); } //----------- dmtweeter void pupilGuide::on_buttonNCPCTest_set_pressed() { - pcf::IndiProperty ip(pcf::IndiProperty::Switch); - - ip.setDevice("dmncpc"); - ip.setName("test_set"); - ip.add(pcf::IndiElement("toggle")); - - if(m_dmncpcTestSet) - { - ip["toggle"].setSwitchState(pcf::IndiElement::Off); - } - else - { - ip["toggle"].setSwitchState(pcf::IndiElement::On); - } - - sendNewProperty(ip); + pcf::IndiProperty ip( pcf::IndiProperty::Switch ); + + ip.setDevice( "dmncpc" ); + ip.setName( "test_set" ); + ip.add( pcf::IndiElement( "toggle" ) ); + + if( m_dmncpcTestSet ) + { + ip["toggle"].setSwitchState( pcf::IndiElement::Off ); + } + else + { + ip["toggle"].setSwitchState( pcf::IndiElement::On ); + } + + sendNewProperty( ip ); } //----------- ttmpupil void pupilGuide::on_buttonPup_rest_pressed() { - pcf::IndiProperty ip(pcf::IndiProperty::Switch); - - ip.setDevice("ttmpupil"); - ip.setName("releaseDM"); - ip.add(pcf::IndiElement("request")); - ip["request"].setSwitchState(pcf::IndiElement::On); - - sendNewProperty(ip); - + pcf::IndiProperty ip( pcf::IndiProperty::Switch ); + + ip.setDevice( "ttmpupil" ); + ip.setName( "releaseDM" ); + ip.add( pcf::IndiElement( "request" ) ); + ip["request"].setSwitchState( pcf::IndiElement::On ); + + sendNewProperty( ip ); } void pupilGuide::on_buttonPup_set_pressed() { - pcf::IndiProperty ip(pcf::IndiProperty::Switch); - - ip.setDevice("ttmpupil"); - ip.setName("initDM"); - ip.add(pcf::IndiElement("request")); - ip["request"].setSwitchState(pcf::IndiElement::On); - - sendNewProperty(ip); + pcf::IndiProperty ip( pcf::IndiProperty::Switch ); + + ip.setDevice( "ttmpupil" ); + ip.setName( "initDM" ); + ip.add( pcf::IndiElement( "request" ) ); + ip["request"].setSwitchState( pcf::IndiElement::On ); + + sendNewProperty( ip ); } void pupilGuide::on_button_camera_pressed() { - if(m_pupCam == FLOWFS) - { - m_pupCam = CAMSCIS; - ui.button_camera->setText("camsci1/2"); - } - else - { - m_pupCam = FLOWFS; - ui.button_camera->setText("flowfs"); - } + if( m_pupCam == FLOWFS ) + { + m_pupCam = CAMSCIS; + ui.button_camera->setText( "camsci1/2" ); + } + else + { + m_pupCam = FLOWFS; + ui.button_camera->setText( "flowfs" ); + } } void pupilGuide::on_button_pup_ul_pressed() { - pcf::IndiProperty ip(pcf::IndiProperty::Number); - - ip.setDevice("ttmpupil"); - ip.setName("pos_1"); - ip.add(pcf::IndiElement("target")); - - if(m_pupCam == FLOWFS) - { - ip["target"] = m_pupCh1 + m_pupStepSize/sqrt(2); - } - else if(m_pupCam == LLOWFS) - { - - } - else if(m_pupCam == CAMSCIS) - { - ip["target"] = m_pupCh1 + m_pupStepSize/sqrt(2); - } - - sendNewProperty(ip); - - - pcf::IndiProperty ip2(pcf::IndiProperty::Number); - - ip2.setDevice("ttmpupil"); - ip2.setName("pos_2"); - ip2.add(pcf::IndiElement("target")); - - if(m_pupCam == FLOWFS) - { - ip2["target"] = m_pupCh2 + m_pupStepSize/sqrt(2); - } - else if(m_pupCam == LLOWFS) - { - - } - else if(m_pupCam == CAMSCIS) - { - ip2["target"] = m_pupCh2 + m_pupStepSize/sqrt(2); - } - - sendNewProperty(ip2); + pcf::IndiProperty ip( pcf::IndiProperty::Number ); + + ip.setDevice( "ttmpupil" ); + ip.setName( "pos_1" ); + ip.add( pcf::IndiElement( "target" ) ); + + if( m_pupCam == FLOWFS ) + { + ip["target"] = m_pupCh1 + m_pupStepSize / sqrt( 2 ); + } + else if( m_pupCam == LLOWFS ) + { + } + else if( m_pupCam == CAMSCIS ) + { + ip["target"] = m_pupCh1 + m_pupStepSize / sqrt( 2 ); + } + + sendNewProperty( ip ); + + pcf::IndiProperty ip2( pcf::IndiProperty::Number ); + + ip2.setDevice( "ttmpupil" ); + ip2.setName( "pos_2" ); + ip2.add( pcf::IndiElement( "target" ) ); + + if( m_pupCam == FLOWFS ) + { + ip2["target"] = m_pupCh2 + m_pupStepSize / sqrt( 2 ); + } + else if( m_pupCam == LLOWFS ) + { + } + else if( m_pupCam == CAMSCIS ) + { + ip2["target"] = m_pupCh2 + m_pupStepSize / sqrt( 2 ); + } + + sendNewProperty( ip2 ); } void pupilGuide::on_button_pup_dl_pressed() { - pcf::IndiProperty ip(pcf::IndiProperty::Number); - - ip.setDevice("ttmpupil"); - ip.setName("pos_1"); - ip.add(pcf::IndiElement("target")); - - if(m_pupCam == FLOWFS) - { - ip["target"] = m_pupCh1 + m_pupStepSize/sqrt(2); - } - else if(m_pupCam == LLOWFS) - { - - } - else if(m_pupCam == CAMSCIS) - { - ip["target"] = m_pupCh1 - m_pupStepSize/sqrt(2); - } - - sendNewProperty(ip); - - pcf::IndiProperty ip2(pcf::IndiProperty::Number); - - ip2.setDevice("ttmpupil"); - ip2.setName("pos_2"); - ip2.add(pcf::IndiElement("target")); - - if(m_pupCam == FLOWFS) - { - ip2["target"] = m_pupCh2 - m_pupStepSize/sqrt(2); - } - else if(m_pupCam == LLOWFS) - { - - } - else if(m_pupCam == CAMSCIS) - { - ip2["target"] = m_pupCh2 + m_pupStepSize/sqrt(2); - } - - sendNewProperty(ip2); + pcf::IndiProperty ip( pcf::IndiProperty::Number ); + + ip.setDevice( "ttmpupil" ); + ip.setName( "pos_1" ); + ip.add( pcf::IndiElement( "target" ) ); + + if( m_pupCam == FLOWFS ) + { + ip["target"] = m_pupCh1 + m_pupStepSize / sqrt( 2 ); + } + else if( m_pupCam == LLOWFS ) + { + } + else if( m_pupCam == CAMSCIS ) + { + ip["target"] = m_pupCh1 - m_pupStepSize / sqrt( 2 ); + } + + sendNewProperty( ip ); + + pcf::IndiProperty ip2( pcf::IndiProperty::Number ); + + ip2.setDevice( "ttmpupil" ); + ip2.setName( "pos_2" ); + ip2.add( pcf::IndiElement( "target" ) ); + + if( m_pupCam == FLOWFS ) + { + ip2["target"] = m_pupCh2 - m_pupStepSize / sqrt( 2 ); + } + else if( m_pupCam == LLOWFS ) + { + } + else if( m_pupCam == CAMSCIS ) + { + ip2["target"] = m_pupCh2 + m_pupStepSize / sqrt( 2 ); + } + + sendNewProperty( ip2 ); } void pupilGuide::on_button_pup_dr_pressed() { - pcf::IndiProperty ip(pcf::IndiProperty::Number); - - ip.setDevice("ttmpupil"); - ip.setName("pos_1"); - ip.add(pcf::IndiElement("target")); - - if(m_pupCam == FLOWFS) - { - ip["target"] = m_pupCh1 - m_pupStepSize/sqrt(2); - } - else if(m_pupCam == LLOWFS) - { - - } - else if(m_pupCam == CAMSCIS) - { - ip["target"] = m_pupCh1 - m_pupStepSize/sqrt(2); - } - - sendNewProperty(ip); - - pcf::IndiProperty ip2(pcf::IndiProperty::Number); - - ip2.setDevice("ttmpupil"); - ip2.setName("pos_2"); - ip2.add(pcf::IndiElement("target")); - - if(m_pupCam == FLOWFS) - { - ip2["target"] = m_pupCh2 - m_pupStepSize/sqrt(2); - } - else if(m_pupCam == LLOWFS) - { - - } - else if(m_pupCam == CAMSCIS) - { - ip2["target"] = m_pupCh2 - m_pupStepSize/sqrt(2); - } - - sendNewProperty(ip2); + pcf::IndiProperty ip( pcf::IndiProperty::Number ); + + ip.setDevice( "ttmpupil" ); + ip.setName( "pos_1" ); + ip.add( pcf::IndiElement( "target" ) ); + + if( m_pupCam == FLOWFS ) + { + ip["target"] = m_pupCh1 - m_pupStepSize / sqrt( 2 ); + } + else if( m_pupCam == LLOWFS ) + { + } + else if( m_pupCam == CAMSCIS ) + { + ip["target"] = m_pupCh1 - m_pupStepSize / sqrt( 2 ); + } + + sendNewProperty( ip ); + + pcf::IndiProperty ip2( pcf::IndiProperty::Number ); + + ip2.setDevice( "ttmpupil" ); + ip2.setName( "pos_2" ); + ip2.add( pcf::IndiElement( "target" ) ); + + if( m_pupCam == FLOWFS ) + { + ip2["target"] = m_pupCh2 - m_pupStepSize / sqrt( 2 ); + } + else if( m_pupCam == LLOWFS ) + { + } + else if( m_pupCam == CAMSCIS ) + { + ip2["target"] = m_pupCh2 - m_pupStepSize / sqrt( 2 ); + } + + sendNewProperty( ip2 ); } void pupilGuide::on_button_pup_ur_pressed() { - pcf::IndiProperty ip(pcf::IndiProperty::Number); - - ip.setDevice("ttmpupil"); - ip.setName("pos_1"); - ip.add(pcf::IndiElement("target")); - if(m_pupCam == FLOWFS) - { - ip["target"] = m_pupCh1 - m_pupStepSize/sqrt(2); - } - else if(m_pupCam == LLOWFS) - { - - } - else if(m_pupCam == CAMSCIS) - { - ip["target"] = m_pupCh1 + m_pupStepSize/sqrt(2); - } - - sendNewProperty(ip); - - pcf::IndiProperty ip2(pcf::IndiProperty::Number); - - ip2.setDevice("ttmpupil"); - ip2.setName("pos_2"); - ip2.add(pcf::IndiElement("target")); - - if(m_pupCam == FLOWFS) - { - ip2["target"] = m_pupCh2 + m_pupStepSize/sqrt(2); - } - else if(m_pupCam == LLOWFS) - { - - } - else if(m_pupCam == CAMSCIS) - { - ip2["target"] = m_pupCh2 - m_pupStepSize/sqrt(2); - } - - sendNewProperty(ip2); - + pcf::IndiProperty ip( pcf::IndiProperty::Number ); + + ip.setDevice( "ttmpupil" ); + ip.setName( "pos_1" ); + ip.add( pcf::IndiElement( "target" ) ); + if( m_pupCam == FLOWFS ) + { + ip["target"] = m_pupCh1 - m_pupStepSize / sqrt( 2 ); + } + else if( m_pupCam == LLOWFS ) + { + } + else if( m_pupCam == CAMSCIS ) + { + ip["target"] = m_pupCh1 + m_pupStepSize / sqrt( 2 ); + } + + sendNewProperty( ip ); + + pcf::IndiProperty ip2( pcf::IndiProperty::Number ); + + ip2.setDevice( "ttmpupil" ); + ip2.setName( "pos_2" ); + ip2.add( pcf::IndiElement( "target" ) ); + + if( m_pupCam == FLOWFS ) + { + ip2["target"] = m_pupCh2 + m_pupStepSize / sqrt( 2 ); + } + else if( m_pupCam == LLOWFS ) + { + } + else if( m_pupCam == CAMSCIS ) + { + ip2["target"] = m_pupCh2 - m_pupStepSize / sqrt( 2 ); + } + + sendNewProperty( ip2 ); } void pupilGuide::on_button_pup_scale_pressed() { - if(((int) (100*m_pupStepSize)) == 100) - { - m_pupStepSize = 0.5; - } - else if(((int) (100*m_pupStepSize)) == 50) - { - m_pupStepSize = 0.1; - } - else if(((int) (100*m_pupStepSize)) == 10) - { - m_pupStepSize = 0.05; - } - else if(((int) (100*m_pupStepSize)) == 5) - { - m_pupStepSize = 0.01; - } - else if(((int) (100*m_pupStepSize)) == 1) - { - m_pupStepSize = 1.0; - } - - char ss[5]; - snprintf(ss, 5, "%0.2f", m_pupStepSize); - ui.button_pup_scale->setText(ss); + if( ( (int)( 100 * m_pupStepSize ) ) == 100 ) + { + m_pupStepSize = 0.5; + } + else if( ( (int)( 100 * m_pupStepSize ) ) == 50 ) + { + m_pupStepSize = 0.1; + } + else if( ( (int)( 100 * m_pupStepSize ) ) == 10 ) + { + m_pupStepSize = 0.05; + } + else if( ( (int)( 100 * m_pupStepSize ) ) == 5 ) + { + m_pupStepSize = 0.01; + } + else if( ( (int)( 100 * m_pupStepSize ) ) == 1 ) + { + m_pupStepSize = 1.0; + } + + char ss[5]; + snprintf( ss, 5, "%0.2f", m_pupStepSize ); + ui.button_pup_scale->setText( ss ); } void pupilGuide::on_button_ttmPeri_rest_pressed() { - pcf::IndiProperty ip(pcf::IndiProperty::Switch); - - ip.setDevice("ttmperi"); - ip.setName("set"); - ip.add(pcf::IndiElement("toggle")); - ip["toggle"].setSwitchState(pcf::IndiElement::Off); - - sendNewProperty(ip); + pcf::IndiProperty ip( pcf::IndiProperty::Switch ); + + ip.setDevice( "ttmperi" ); + ip.setName( "set" ); + ip.add( pcf::IndiElement( "toggle" ) ); + ip["toggle"].setSwitchState( pcf::IndiElement::Off ); + + sendNewProperty( ip ); } void pupilGuide::on_button_ttmPeri_set_pressed() { - pcf::IndiProperty ip(pcf::IndiProperty::Switch); - - ip.setDevice("ttmperi"); - ip.setName("set"); - ip.add(pcf::IndiElement("toggle")); - ip["toggle"].setSwitchState(pcf::IndiElement::On); - - sendNewProperty(ip); + pcf::IndiProperty ip( pcf::IndiProperty::Switch ); + + ip.setDevice( "ttmperi" ); + ip.setName( "set" ); + ip.add( pcf::IndiElement( "toggle" ) ); + ip["toggle"].setSwitchState( pcf::IndiElement::On ); + + sendNewProperty( ip ); } void pupilGuide::on_button_ttmPeri_l_pressed() { - pcf::IndiProperty ip(pcf::IndiProperty::Number); - - ip.setDevice("ttmperi"); - ip.setName("axis1_voltage"); - ip.add(pcf::IndiElement("target")); + pcf::IndiProperty ip( pcf::IndiProperty::Number ); - if(m_pupCam == FLOWFS) + ip.setDevice( "ttmperi" ); + ip.setName( "axis1_voltage" ); + ip.add( pcf::IndiElement( "target" ) ); + + if( m_pupCam == FLOWFS ) { ip["target"] = m_ttmPeriCh1 + m_ttmPeriStepSize; } - else if(m_pupCam == LLOWFS) + else if( m_pupCam == LLOWFS ) { - } - else if(m_pupCam == CAMSCIS) + else if( m_pupCam == CAMSCIS ) { ip["target"] = m_ttmPeriCh1 + m_ttmPeriStepSize; } - sendNewProperty(ip); - + sendNewProperty( ip ); } void pupilGuide::on_button_ttmPeri_r_pressed() { - pcf::IndiProperty ip(pcf::IndiProperty::Number); - - ip.setDevice("ttmperi"); - ip.setName("axis1_voltage"); - ip.add(pcf::IndiElement("target")); + pcf::IndiProperty ip( pcf::IndiProperty::Number ); + + ip.setDevice( "ttmperi" ); + ip.setName( "axis1_voltage" ); + ip.add( pcf::IndiElement( "target" ) ); - if(m_pupCam == FLOWFS) + if( m_pupCam == FLOWFS ) { ip["target"] = m_ttmPeriCh1 - m_ttmPeriStepSize; } - else if(m_pupCam == LLOWFS) + else if( m_pupCam == LLOWFS ) { - } - else if(m_pupCam == CAMSCIS) + else if( m_pupCam == CAMSCIS ) { ip["target"] = m_ttmPeriCh1 - m_ttmPeriStepSize; } - sendNewProperty(ip); - - + sendNewProperty( ip ); } void pupilGuide::on_button_ttmPeri_u_pressed() { - pcf::IndiProperty ip(pcf::IndiProperty::Number); - - ip.setDevice("ttmperi"); - ip.setName("axis2_voltage"); - ip.add(pcf::IndiElement("target")); + pcf::IndiProperty ip( pcf::IndiProperty::Number ); + + ip.setDevice( "ttmperi" ); + ip.setName( "axis2_voltage" ); + ip.add( pcf::IndiElement( "target" ) ); - if(m_pupCam == FLOWFS) + if( m_pupCam == FLOWFS ) { ip["target"] = m_ttmPeriCh2 + m_ttmPeriStepSize; } - else if(m_pupCam == LLOWFS) + else if( m_pupCam == LLOWFS ) { - } - else if(m_pupCam == CAMSCIS) + else if( m_pupCam == CAMSCIS ) { ip["target"] = m_ttmPeriCh2 + m_ttmPeriStepSize; } - sendNewProperty(ip); - + sendNewProperty( ip ); } void pupilGuide::on_button_ttmPeri_d_pressed() { - pcf::IndiProperty ip(pcf::IndiProperty::Number); - - ip.setDevice("ttmperi"); - ip.setName("axis2_voltage"); - ip.add(pcf::IndiElement("target")); + pcf::IndiProperty ip( pcf::IndiProperty::Number ); - if(m_pupCam == FLOWFS) + ip.setDevice( "ttmperi" ); + ip.setName( "axis2_voltage" ); + ip.add( pcf::IndiElement( "target" ) ); + + if( m_pupCam == FLOWFS ) { ip["target"] = m_ttmPeriCh2 - m_ttmPeriStepSize; } - else if(m_pupCam == LLOWFS) + else if( m_pupCam == LLOWFS ) { - } - else if(m_pupCam == CAMSCIS) + else if( m_pupCam == CAMSCIS ) { ip["target"] = m_ttmPeriCh2 - m_ttmPeriStepSize; } - sendNewProperty(ip); + sendNewProperty( ip ); } void pupilGuide::on_button_ttmPeri_scale_pressed() { - if(((int) (m_ttmPeriStepSize)) == 50) - { - m_ttmPeriStepSize = 25; - } - else if(((int) (m_ttmPeriStepSize)) == 25) - { - m_ttmPeriStepSize = 10; - } - else if(((int) (m_ttmPeriStepSize)) == 10) - { - m_ttmPeriStepSize = 1; - } - else - { - m_ttmPeriStepSize = 50; - } - - char ss[5]; - snprintf(ss, 5, "%0.2f", m_ttmPeriStepSize/100.); - ui.button_ttmPeri_scale->setText(ss); -} - + if( ( (int)( m_ttmPeriStepSize ) ) == 50 ) + { + m_ttmPeriStepSize = 25; + } + else if( ( (int)( m_ttmPeriStepSize ) ) == 25 ) + { + m_ttmPeriStepSize = 10; + } + else if( ( (int)( m_ttmPeriStepSize ) ) == 10 ) + { + m_ttmPeriStepSize = 1; + } + else + { + m_ttmPeriStepSize = 50; + } -void pupilGuide::on_pupilAlign_loopSlider_sliderReleased() -{ - double relpos = ((double)(ui.pupilAlign_loopSlider->sliderPosition() - ui.pupilAlign_loopSlider->minimum()))/(ui.pupilAlign_loopSlider->maximum() - ui.pupilAlign_loopSlider->minimum()); - - if(m_camwfsAlignLoopState) - { - if(relpos > 0.1) - { - ui.pupilAlign_loopSlider->setSliderPosition(ui.pupilAlign_loopSlider->maximum()); - ui.pupilAlign_loopSlider->setEnabled(true); - m_camwfsAlignLoopWaiting = false; - return; - } - } - else - { - if(relpos < 0.9) - { - ui.pupilAlign_loopSlider->setSliderPosition(ui.pupilAlign_loopSlider->minimum()); - ui.pupilAlign_loopSlider->setEnabled(true); - m_camwfsAlignLoopWaiting = false; - return; - } - } - - ui.pupilAlign_loopSlider->setEnabled(false); - m_camwfsAlignLoopWaiting = true; - m_camwfsAlignLoopWaitTimer->start(2000); - - pcf::IndiProperty ipFreq(pcf::IndiProperty::Switch); - - ipFreq.setDevice("camwfs-align"); - ipFreq.setName("loop_state"); - ipFreq.add(pcf::IndiElement("toggle")); - - if(relpos >= 0.9) - { - ipFreq["toggle"] = pcf::IndiElement::On; - } - else - { - ipFreq["toggle"] = pcf::IndiElement::Off; - } - - sendNewProperty(ipFreq); + char ss[5]; + snprintf( ss, 5, "%0.2f", m_ttmPeriStepSize / 100. ); + ui.button_ttmPeri_scale->setText( ss ); } -void pupilGuide::on_pupilAlign_loopSlider_sliderPressed() +void pupilGuide::toggleExpFit( bool st ) { - m_camwfsAlignLoopWaiting = true; - m_camwfsAlignLoopWaitTimer->start(2000); -} -void pupilGuide::on_pupilAlign_loopSlider_sliderMoved(int p) -{ - static_cast(p); + ui.labelD->setVisible( st ); - m_camwfsAlignLoopWaiting = true; - m_camwfsAlignLoopWaitTimer->start(2000); -} + ui.labelUR->setVisible( st ); + ui.coordUR_x->setVisible( st ); + ui.coordUR_y->setVisible( st ); + ui.coordUR_D->setVisible( st ); -void pupilGuide::camwfsAlignLoopWaitTimerOut() -{ - m_camwfsAlignLoopWaiting = false; -} + ui.labelUL->setVisible( st ); + ui.coordUL_x->setVisible( st ); + ui.coordUL_y->setVisible( st ); + ui.coordUL_D->setVisible( st ); -void pupilGuide::toggleExpFit(bool st) -{ + ui.labelLR->setVisible( st ); + ui.coordLR_x->setVisible( st ); + ui.coordLR_y->setVisible( st ); + ui.coordLR_D->setVisible( st ); - ui.labelD->setVisible(st); - - ui.labelUR->setVisible(st); - ui.coordUR_x->setVisible(st); - ui.coordUR_y->setVisible(st); - ui.coordUR_D->setVisible(st); - - ui.labelUL->setVisible(st); - ui.coordUL_x->setVisible(st); - ui.coordUL_y->setVisible(st); - ui.coordUL_D->setVisible(st); - - ui.labelLR->setVisible(st); - ui.coordLR_x->setVisible(st); - ui.coordLR_y->setVisible(st); - ui.coordLR_D->setVisible(st); - - ui.labelLL->setVisible(st); - ui.coordLL_x->setVisible(st); - ui.coordLL_y->setVisible(st); - ui.coordLL_D->setVisible(st); - - ui.coordAvg_D->setVisible(st); - - if(st) - { - ui.buttonExpFit->setText("--"); - } - else - { - ui.buttonExpFit->setText("|"); - } -} + ui.labelLL->setVisible( st ); + ui.coordLL_x->setVisible( st ); + ui.coordLL_y->setVisible( st ); + ui.coordLL_D->setVisible( st ); + ui.coordAvg_D->setVisible( st ); + + if( st ) + { + ui.buttonExpFit->setText( "--" ); + } + else + { + ui.buttonExpFit->setText( "|" ); + } +} void pupilGuide::on_buttonExpFit_pressed() { - bool st = !ui.labelD->isVisible(); - toggleExpFit(st); + bool st = !ui.labelD->isVisible(); + toggleExpFit( st ); } - void pupilGuide::on_button_camlens_u_pressed() { - if(m_camlensyFsmState != "READY") return; - - pcf::IndiProperty ip(pcf::IndiProperty::Number); - - ip.setDevice("stagecamlensy"); - ip.setName("position"); - ip.add(pcf::IndiElement("target")); - ip["target"] = m_camlensy_pos - m_camlensStepSize; - - sendNewProperty(ip); + if( m_camlensyFsmState != "READY" ) + return; + + pcf::IndiProperty ip( pcf::IndiProperty::Number ); + + ip.setDevice( "stagecamlensy" ); + ip.setName( "position" ); + ip.add( pcf::IndiElement( "target" ) ); + ip["target"] = m_camlensy_pos - m_camlensStepSize; + + sendNewProperty( ip ); } void pupilGuide::on_button_camlens_l_pressed() { - if(m_camlensxFsmState != "READY") return; - - pcf::IndiProperty ip(pcf::IndiProperty::Number); - - ip.setDevice("stagecamlensx"); - ip.setName("position"); - ip.add(pcf::IndiElement("target")); - ip["target"] = m_camlensx_pos - m_camlensStepSize; - - sendNewProperty(ip); + if( m_camlensxFsmState != "READY" ) + return; + + pcf::IndiProperty ip( pcf::IndiProperty::Number ); + + ip.setDevice( "stagecamlensx" ); + ip.setName( "position" ); + ip.add( pcf::IndiElement( "target" ) ); + ip["target"] = m_camlensx_pos - m_camlensStepSize; + + sendNewProperty( ip ); } void pupilGuide::on_button_camlens_d_pressed() { - if(m_camlensyFsmState != "READY") return; - - pcf::IndiProperty ip(pcf::IndiProperty::Number); - - ip.setDevice("stagecamlensy"); - ip.setName("position"); - ip.add(pcf::IndiElement("target")); - ip["target"] = m_camlensy_pos + m_camlensStepSize; - - - sendNewProperty(ip); + if( m_camlensyFsmState != "READY" ) + return; + + pcf::IndiProperty ip( pcf::IndiProperty::Number ); + + ip.setDevice( "stagecamlensy" ); + ip.setName( "position" ); + ip.add( pcf::IndiElement( "target" ) ); + ip["target"] = m_camlensy_pos + m_camlensStepSize; + + sendNewProperty( ip ); } void pupilGuide::on_button_camlens_r_pressed() { - if(m_camlensxFsmState != "READY") return; - - pcf::IndiProperty ip(pcf::IndiProperty::Number); - - ip.setDevice("stagecamlensx"); - ip.setName("position"); - ip.add(pcf::IndiElement("target")); - ip["target"] = m_camlensx_pos + m_camlensStepSize; - sendNewProperty(ip); + if( m_camlensxFsmState != "READY" ) + return; + + pcf::IndiProperty ip( pcf::IndiProperty::Number ); + + ip.setDevice( "stagecamlensx" ); + ip.setName( "position" ); + ip.add( pcf::IndiElement( "target" ) ); + ip["target"] = m_camlensx_pos + m_camlensStepSize; + sendNewProperty( ip ); } void pupilGuide::on_button_camlens_scale_pressed() { - if(((int) (1000*m_camlensStepSize+0.5)) == 5) - { - m_camlensStepSize = 0.05; - } - else if(((int) (1000*m_camlensStepSize+0.5)) == 50) - { - m_camlensStepSize = 0.025; - } - else if(((int) (1000*m_camlensStepSize+0.5)) == 25) - { - m_camlensStepSize = 0.01; - } - else if(((int) (1000*m_camlensStepSize+0.5)) == 10) - { - m_camlensStepSize = 0.005; - } -/* else if(((int) (1000*m_camlensStepSize+0.5)) == 5) - { - m_camlensStepSize = 0.001; - }*/ - - char ss[5]; - snprintf(ss, 5, "%0.2f", m_camlensStepSize*10); - ui.button_camlens_scale->setText(ss); - - + if( ( (int)( 1000 * m_camlensStepSize + 0.5 ) ) == 5 ) + { + m_camlensStepSize = 0.05; + } + else if( ( (int)( 1000 * m_camlensStepSize + 0.5 ) ) == 50 ) + { + m_camlensStepSize = 0.025; + } + else if( ( (int)( 1000 * m_camlensStepSize + 0.5 ) ) == 25 ) + { + m_camlensStepSize = 0.01; + } + else if( ( (int)( 1000 * m_camlensStepSize + 0.5 ) ) == 10 ) + { + m_camlensStepSize = 0.005; + } + /* else if(((int) (1000*m_camlensStepSize+0.5)) == 5) + { + m_camlensStepSize = 0.001; + }*/ + + char ss[5]; + snprintf( ss, 5, "%0.2f", m_camlensStepSize * 10 ); + ui.button_camlens_scale->setText( ss ); } +} // namespace xqt -} //namespace xqt - #include "moc_pupilGuide.cpp" #endif diff --git a/gui/widgets/pupilGuide/pupilGuide.ui b/gui/widgets/pupilGuide/pupilGuide.ui index 0f251c18c..eab28671a 100644 --- a/gui/widgets/pupilGuide/pupilGuide.ui +++ b/gui/widgets/pupilGuide/pupilGuide.ui @@ -6,7 +6,7 @@ 0 0 - 1395 + 2222 872 @@ -19,11 +19,11 @@ - + - + - + 16777215 @@ -36,7 +36,7 @@ - TTM Modulator + Modulaion Qt::AlignCenter @@ -44,14 +44,14 @@ - + - 170 + 0 255 255 @@ -62,7 +62,7 @@ - 170 + 0 255 255 @@ -82,16 +82,33 @@ - - MODSTATE - - - Qt::AlignCenter - - + + + + + Frequency [Hz] + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + @@ -106,18 +123,8 @@ - - - - Frequency [Hz] - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - + Radius [l/D] @@ -126,23 +133,10 @@ - - - - Qt::Horizontal - - - - 40 - 20 - - - - - + @@ -176,7 +170,7 @@ - + @@ -207,11 +201,24 @@ - + + + Qt::Vertical + + + + 20 + 40 + + + + + + 16777215 - 64 + 35 @@ -220,7 +227,7 @@ - Median Fluxes + Tip Alignment Qt::AlignCenter @@ -228,107 +235,7 @@ - - - - - Qt::NoFocus - - - Qt::AlignCenter - - - - - - - Qt::NoFocus - - - Qt::AlignCenter - - - - - - - Qt::NoFocus - - - Qt::AlignCenter - - - - - - - Qt::NoFocus - - - Qt::AlignCenter - - - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Qt::NoFocus - - - delta from mean - - - true - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - + @@ -380,7 +287,7 @@ - + @@ -824,125 +731,7 @@ - - - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - - 16777215 - 35 - - - - - 12 - - - - NCPC - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 25 - - - - - 16777215 - 35 - - - - - 12 - - - - Tweeter - - - Qt::AlignCenter - - - - - - - - 1 - 1 - - - - - 150 - 25 - - - - Qt::NoFocus - - - set test - - - - - - - - 1 - 1 - - - - - 150 - 25 - - - - Qt::NoFocus - - - set test - - - - - - - + @@ -1022,12 +811,101 @@ - + - - - - 16777215 + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + + 16777215 + 35 + + + + + 12 + + + + Tweeter + + + Qt::AlignCenter + + + + + + + + 1 + 1 + + + + + 150 + 25 + + + + Qt::NoFocus + + + set test + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + + + + 16777215 35 @@ -1341,9 +1219,98 @@ - + - + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + + 16777215 + 35 + + + + + 12 + + + + NCPC + + + Qt::AlignCenter + + + + + + + + 1 + 1 + + + + + 150 + 25 + + + + Qt::NoFocus + + + set test + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + @@ -1669,146 +1636,89 @@ - + - - - - - - - - 16777215 - 35 - - - - - 12 - - - - Pupil Alignment Loop - - - Qt::AlignCenter - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Qt::NoFocus - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Qt::NoFocus - - - Qt::Horizontal - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + 16777215 + 64 + + + + + 12 + + + + Pupil Fitting + + + Qt::AlignCenter + + + + + + + + + Qt::NoFocus + + - - - - Qt::Vertical + + + + Qt::NoFocus - + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + - 20 - 40 + 16777215 + 64 - - - - 12 - Camera Lens + Median Fluxes Qt::AlignCenter @@ -1816,66 +1726,542 @@ - - - - - - - - 170 - 255 - 255 - - - - - - - - - 170 - 255 - 255 - - - - - - - - - 96 - 95 - 94 - - - - - + + + + + Qt::NoFocus + + + Qt::AlignCenter + + + + + + + Qt::NoFocus + + + Qt::AlignCenter + + + + + + + Qt::NoFocus + + + Qt::AlignCenter + + + + + + + Qt::NoFocus + + + Qt::AlignCenter + + + + + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Qt::NoFocus + + + delta from mean + + + true + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + + + + 30 + 30 + + + + Qt::NoFocus + + + | + + + + + + + Qt::NoFocus + + + Qt::AlignCenter + + + + + + + Qt::NoFocus + + + Qt::AlignCenter + + + + + + + Avg: + + + + + + + Qt::NoFocus + + + Qt::AlignCenter + + + + + + + Qt::NoFocus + + + Qt::AlignCenter + + + + + + + y + + + Qt::AlignCenter + + + + + + + UR + + + + + + + Qt::NoFocus + + + Qt::AlignCenter + + + + + + + LR + + + + + + + x + + + Qt::AlignCenter + + + + + + + Qt::NoFocus + + + Qt::AlignCenter + + + + + + + Qt::NoFocus + + + Qt::AlignCenter + + + + + + + Qt::NoFocus + + + Qt::AlignCenter + + + + + + + Qt::NoFocus + + + Qt::AlignCenter + + + + + + + Qt::NoFocus + + + Qt::AlignCenter + + + + + + + Qt::NoFocus + + + Qt::AlignCenter + + + + + + + Qt::NoFocus + + + Qt::AlignCenter + + + + + + + Qt::NoFocus + + + Qt::AlignCenter + + + + + + + UL + + + + + + + LL + + + + + + + D + + + Qt::AlignCenter + + + + + + + Qt::NoFocus + + + Qt::AlignCenter + + + + + + + Qt::NoFocus + + + Qt::AlignCenter + + + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Qt::NoFocus - CAMLENS FSM + delta from set pt + + + true + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + 12 + + + + Camera Lens Qt::AlignCenter + + + + + + X: + + + + + + + + + + + + 0 + 255 + 255 + + + + + + + + + 0 + 255 + 255 + + + + + + + + + 96 + 95 + 94 + + + + + + + + + + + + Y: + + + + + + + + + + + + 0 + 255 + 255 + + + + + + + + + 0 + 255 + 255 + + + + + + + + + 96 + 95 + 94 + + + + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + QLayout::SetFixedSize - + Qt::NoFocus - + Qt::NoFocus @@ -1886,26 +2272,228 @@ - + - + - Qt::Vertical + Qt::Horizontal - 20 - 40 + 40 + 20 + + + + + + + + QLayout::SetDefaultConstraint + + + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + Qt::NoFocus + + + + + + + :/icons/arrow_left_128.png:/icons/arrow_left_128.png + + + + + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + + 11 + + + + Qt::NoFocus + + + 0.01 + + + + + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + Qt::NoFocus + + + + + + + :/icons/arrow_up_128.png:/icons/arrow_up_128.png + + + + + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + Qt::NoFocus + + + + + + + :/icons/arrow_down_128.png:/icons/arrow_down_128.png + + + + + + + + 1 + 1 + + + + + 40 + 40 + + + + + 40 + 40 + + + + Qt::NoFocus + + + + + + + :/icons/arrow_right_128.png:/icons/arrow_right_128.png + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + - + 16777215 - 64 + 35 @@ -1914,7 +2502,7 @@ - Pupil Fitting + Pupil Tracking Loop Qt::AlignCenter @@ -1922,16 +2510,16 @@ - - - + + + Qt::NoFocus - - + + Qt::NoFocus @@ -1940,257 +2528,176 @@ - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - Qt::NoFocus - - - Qt::AlignCenter - - - - - - - Qt::NoFocus - - - Qt::AlignCenter - - - - - - - Qt::NoFocus - - - Qt::AlignCenter - - - - - - - Qt::NoFocus - - - Qt::AlignCenter - - - - - - - Qt::NoFocus - - - Qt::AlignCenter - - - - - - - Qt::NoFocus - - - Qt::AlignCenter - - - - - - - Qt::NoFocus - - - Qt::AlignCenter - - - - - - - Qt::NoFocus - - - Qt::AlignCenter - - - - - - - Qt::NoFocus - - - Qt::AlignCenter - - - - - - - Qt::NoFocus + + + + + Qt::Horizontal - - Qt::AlignCenter + + + 40 + 20 + - + - - + + Qt::NoFocus - - Qt::AlignCenter - - - - - - - LR - - - - - LL + + + + Qt::Horizontal - - - - - - UR + + + 40 + 20 + - + - - - - x + + + + + + + + Qt::Horizontal - - Qt::AlignCenter + + + 40 + 20 + - + - - + + Qt::NoFocus - - Qt::AlignCenter - - - - - Qt::NoFocus + + + + Qt::Horizontal - - Qt::AlignCenter + + + 40 + 20 + - + - - + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + + 16777215 + 35 + + + + + 12 + + + + Actuator Alignment Loop + + + Qt::AlignCenter + + + + + + + Qt::NoFocus - - Qt::AlignCenter - - - + + Qt::NoFocus - - Qt::AlignCenter - - - - - - - UL - - - - - - - D - - - Qt::AlignCenter - - - - - - - y - - - Qt::AlignCenter - - - - - Avg: + + + + + + + + Qt::Horizontal - - - - - + - 30 - 30 + 40 + 20 + + + + Qt::NoFocus - - | - + + + + Qt::Horizontal + + + + 40 + 20 + + + + - + - + Qt::Horizontal @@ -2203,20 +2710,14 @@ - + Qt::NoFocus - - delta from set pt - - - true - - + Qt::Horizontal @@ -2230,10 +2731,48 @@ + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + + 16777215 + 35 + + + + + 12 + + + + Actuator Alignment Sensor + + + Qt::AlignCenter + + + - + - + Qt::Horizontal @@ -2246,175 +2785,14 @@ - - - QLayout::SetDefaultConstraint + + + Qt::NoFocus - - - - - 1 - 1 - - - - - 40 - 40 - - - - - 40 - 40 - - - - Qt::NoFocus - - - - - - - :/icons/arrow_left_128.png:/icons/arrow_left_128.png - - - - - - - - 1 - 1 - - - - - 40 - 40 - - - - - 40 - 40 - - - - - 11 - - - - Qt::NoFocus - - - 0.01 - - - - - - - - 1 - 1 - - - - - 40 - 40 - - - - - 40 - 40 - - - - Qt::NoFocus - - - - - - - :/icons/arrow_up_128.png:/icons/arrow_up_128.png - - - - - - - - 1 - 1 - - - - - 40 - 40 - - - - - 40 - 40 - - - - Qt::NoFocus - - - - - - - :/icons/arrow_down_128.png:/icons/arrow_down_128.png - - - - - - - - 1 - 1 - - - - - 40 - 40 - - - - - 40 - 40 - - - - Qt::NoFocus - - - - - - - :/icons/arrow_right_128.png:/icons/arrow_right_128.png - - - - + - + Qt::Horizontal @@ -2428,8 +2806,45 @@ + + + + + + + Qt::NoFocus + + + + + + + Qt::NoFocus + + + + + + + Qt::NoFocus + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + @@ -2447,6 +2862,11 @@ QLabel
../xWidgets/fsmDisplay.hpp
+ + xqt::toggleSlider + QSlider +
../xWidgets/toggleSlider.hpp
+
diff --git a/gui/widgets/xWidgets/fsmDisplay.hpp b/gui/widgets/xWidgets/fsmDisplay.hpp index 241a67966..28666baf5 100644 --- a/gui/widgets/xWidgets/fsmDisplay.hpp +++ b/gui/widgets/xWidgets/fsmDisplay.hpp @@ -6,15 +6,15 @@ #include "ui_fsmDisplay.h" -namespace xqt +namespace xqt { - + class fsmDisplay : public xWidget { Q_OBJECT - + protected: - + std::string m_device; std::string m_property {"fsm"}; std::string m_element {"state"}; @@ -25,64 +25,74 @@ class fsmDisplay : public xWidget std::string m_value; + std::string m_NOTHOMED {"NOTHOMED"}; + std::string m_HOMING {"HOMING"}; + std::string m_READY {"READY"}; + std::string m_OPERATING {"OPERATING"}; + public: - fsmDisplay( QWidget * Parent = 0, + fsmDisplay( QWidget * Parent = 0, Qt::WindowFlags f = Qt::WindowFlags() ); explicit fsmDisplay( const std::string & device, - QWidget * Parent = 0, + QWidget * Parent = 0, Qt::WindowFlags f = Qt::WindowFlags() ); - + ~fsmDisplay(); - + void device( const std::string & dev); virtual void subscribe(); - + virtual void onConnect(); virtual void onDisconnect(); - + virtual void clearFocus(); virtual void handleDefProperty( const pcf::IndiProperty & ipRecv /**< [in] the property which has changed*/); - + virtual void handleSetProperty( const pcf::IndiProperty & ipRecv /**< [in] the property which has changed*/); - + + void NOTHOMED( const std::string & s ); + void HOMING( const std::string & s ); + void READY( const std::string & s ); + void OPERATING( const std::string & s ); + public slots: void updateGUI(); signals: - + void doUpdateGUI(); private: - + Ui::fsmDisplay ui; }; - -fsmDisplay::fsmDisplay( QWidget * Parent, + +fsmDisplay::fsmDisplay( QWidget * Parent, Qt::WindowFlags f) : xWidget(Parent, f) { ui.setupUi(this); - + connect(this, SIGNAL(doUpdateGUI()), this, SLOT(updateGUI())); onDisconnect(); } fsmDisplay::fsmDisplay( const std::string & device, - QWidget * Parent, + QWidget * Parent, Qt::WindowFlags f) : xWidget(Parent, f), m_device{device} { ui.setupUi(this); connect(this, SIGNAL(doUpdateGUI()), this, SLOT(updateGUI())); onDisconnect(); } - + void fsmDisplay::device( const std::string & dev) { m_device = dev; @@ -95,12 +105,12 @@ fsmDisplay::~fsmDisplay() void fsmDisplay::subscribe() { if(!m_parent) return; - + if(m_property != "") m_parent->addSubscriberProperty(this, m_device, m_property); return; } - + void fsmDisplay::onConnect() { m_valChanged = true; @@ -108,6 +118,7 @@ void fsmDisplay::onConnect() void fsmDisplay::onDisconnect() { + m_value = "---"; ui.fsm->setText("---"); } @@ -117,14 +128,32 @@ void fsmDisplay::handleDefProperty( const pcf::IndiProperty & ipRecv) } void fsmDisplay::handleSetProperty( const pcf::IndiProperty & ipRecv) -{ +{ if(ipRecv.getDevice() != m_device) return; - + if(ipRecv.getName() == m_property) { if(ipRecv.find(m_element)) { std::string value = ipRecv[m_element].get(); + + if(value == "NOTHOMED") + { + value = m_NOTHOMED; + } + else if(value == "HOMING") + { + value = m_HOMING; + } + else if(value == "READY") + { + value = m_READY; + } + else if(value == "OPERATING") + { + value = m_OPERATING; + } + if(value != m_value) m_valChanged = true; m_value = value; } @@ -133,6 +162,27 @@ void fsmDisplay::handleSetProperty( const pcf::IndiProperty & ipRecv) emit doUpdateGUI(); } +void fsmDisplay::NOTHOMED( const std::string & s ) +{ + m_NOTHOMED = s; +} + +void fsmDisplay::HOMING( const std::string & s ) +{ + m_HOMING = s; +} + +void fsmDisplay::READY( const std::string & s ) +{ + m_READY = s; +} + +void fsmDisplay::OPERATING( const std::string & s ) +{ + m_OPERATING = s; +} + + void fsmDisplay::updateGUI() { if(isEnabled()) @@ -140,14 +190,14 @@ void fsmDisplay::updateGUI() if(m_valChanged) { QString value(m_value.c_str()); //in future provide translatiosn for "RIP" "MODULATING", etc. - ui.fsm->setTextChanged(value); + ui.fsm->setTextChanged(value); m_valChanged = false; } } else { QString value(m_value.c_str()); //in future provide translatiosn for "RIP" "MODULATING", etc. - ui.fsm->setText(value); + ui.fsm->setText(value); } } //updateGUI() @@ -157,7 +207,7 @@ void fsmDisplay::clearFocus() } } //namespace xqt - + #include "moc_fsmDisplay.cpp" #endif diff --git a/gui/widgets/xWidgets/statusLabel.hpp b/gui/widgets/xWidgets/statusLabel.hpp index 81d861c54..4c0c1e0e5 100644 --- a/gui/widgets/xWidgets/statusLabel.hpp +++ b/gui/widgets/xWidgets/statusLabel.hpp @@ -23,16 +23,16 @@ namespace xqt * - If focus then returns, the last edited value is loaded * - After the stale timeout (default 60 sec), the edited value is cleared so that subsequent edits start with the current value * - onReturnPressed should normally be used to signal a new value to set, rather than editingFinished. - * + * * To trigger the statusChanged style, the member function setTextChanged() must be called instead of setText(). This will also prevent interrupting * current editing when the widget has focus. - * + * * Ref: https://doc.qt.io/qt-5/qlabel.html - */ + */ class statusLabel : public QLabel { Q_OBJECT - + public: enum valchanges{NOTCHANGED, CHANGED, CHANGED_TIMEOUT}; @@ -47,7 +47,7 @@ class statusLabel : public QLabel /// The timer for restoring status style from the statusChanged style /** This is started for m_changeTimeout msecs after a setTextChanged() is called. - * + * * Ref: https://doc.qt.io/qt-5/qtimer.html */ QTimer * m_changeTimer {nullptr}; @@ -62,7 +62,7 @@ class statusLabel : public QLabel /// Set the highlight changes flag /** If set to false, the widget will not change to statusChanged. * The default is true. - * + * * This sets m_highlightChanges */ void highlightChanges(bool hc); @@ -74,13 +74,13 @@ class statusLabel : public QLabel bool highlightChanges(); /// Set the change timeout - /** The change timeout (m_changeTimeout) is the duration for which the + /** The change timeout (m_changeTimeout) is the duration for which the * statusChanged CSS style is applied after a value update. - */ + */ void changeTimeout( std::chrono::milliseconds & cto /**< [in] the new change timeout in msec */); /// Get the change timeout - /** The change timeout (m_changeTimeout) is the duration for which the + /** The change timeout (m_changeTimeout) is the duration for which the * statusChanged CSS style is applied after a value update. */ std::chrono::milliseconds changeTimeout(); @@ -96,6 +96,8 @@ class statusLabel : public QLabel */ virtual void paintEvent(QPaintEvent * e); + virtual void changeEvent(QEvent * e); + protected slots: void changeTimerOut(); @@ -154,13 +156,13 @@ void statusLabel::paintEvent(QPaintEvent * e) setProperty("isStatus", true); if(m_highlightChanges) { - setFrameShape(QFrame::Box); + setFrameShape(QFrame::Box); setProperty("isStatusChanged", true); } style()->unpolish(this); - + emit changeTimerStart(m_changeTimeout.count()); - + m_valChanged = 0; } else if(m_valChanged == CHANGED_TIMEOUT) @@ -169,17 +171,34 @@ void statusLabel::paintEvent(QPaintEvent * e) setFrameShape(QFrame::NoFrame); setProperty("isStatusChanged",false); style()->unpolish(this); - + m_valChanged = 0; } QLabel::paintEvent(e); } +void statusLabel::changeEvent(QEvent * e) +{ + if(e->type() == QEvent::EnabledChange) + { + if(!isEnabled()) + { + m_changeTimer->stop(); + setFrameShape(QFrame::NoFrame); + setProperty("isStatusChanged",false); + style()->unpolish(this); + m_valChanged = 0; + } + } + + QLabel::changeEvent(e); +} + void statusLabel::changeTimerOut() { m_valChanged = CHANGED_TIMEOUT; - if(isEnabled()) update(); + if(isEnabled()) update(); } } //namespace xqt From 0a345ac976b9a424be7c8a51fef0d925585aa179 Mon Sep 17 00:00:00 2001 From: Jared Males Date: Sun, 27 Oct 2024 00:16:20 -0700 Subject: [PATCH 23/24] updated pupilGuideGUI connect/disconnect; added alignment start/stop buttons --- gui/resources/icons/arrow_up_dark_128.png | Bin 0 -> 6139 bytes .../icons/keyboard_double_arrow_down.png | Bin 0 -> 5753 bytes .../icons/keyboard_double_arrow_left.png | Bin 0 -> 5165 bytes .../icons/keyboard_double_arrow_right.png | Bin 0 -> 5151 bytes .../icons/keyboard_double_arrow_up.png | Bin 0 -> 5666 bytes gui/resources/magaox.qrc | 5 + gui/widgets/pupilGuide/pupilGuide.hpp | 346 +++++++++++++----- gui/widgets/pupilGuide/pupilGuide.ui | 274 +++++++++----- 8 files changed, 456 insertions(+), 169 deletions(-) create mode 100644 gui/resources/icons/arrow_up_dark_128.png create mode 100644 gui/resources/icons/keyboard_double_arrow_down.png create mode 100644 gui/resources/icons/keyboard_double_arrow_left.png create mode 100644 gui/resources/icons/keyboard_double_arrow_right.png create mode 100644 gui/resources/icons/keyboard_double_arrow_up.png diff --git a/gui/resources/icons/arrow_up_dark_128.png b/gui/resources/icons/arrow_up_dark_128.png new file mode 100644 index 0000000000000000000000000000000000000000..05fa59fd6d89e0d6b56f3376a858dc618e37af56 GIT binary patch literal 6139 zcmeHKX;c&0whog>L}XA=0x?POUO2 z4xmC~H-n7|0<8kl7eO0AKt&W#FVM6i;DDkcuM*V8_3nCax!%3+m&vNsseShT&feeN z`=m~)x7XU)XcIIFg_`Z|=FCFw$;g#7a|ZIe{B4sqa(lMfFHp*YWSAJSD1sjiW26Z& zFb0WMuPQ`-*dWo{NmGi4j1((_=O_hFoBu%YzgAU&iyM$%8 z12 zOH919d$j1;zz0)}P2KF|^-K1VuAWb|N#RiiJ6^1gRb+58-W-+Jot|ZAFAf`hvscmz zZ|Aw*@Z5Zy=4d^CRp4N_Kaui?|ETb%!E^%G&Yv!dy}g2RyJ~q7WLa8jEjiY2c`&fv za7l`{x6{ITcT-w_I>feMzDvb_fbI|utg{GMxW{x>q2rFHZ)+!eWflI=rd#XKOOv~e z8^#xCs8>6jdq(SN*w<#O_Wou~M)z32qME162Va%Xw^N@{v3>WG@`9&oS*vPV4q4=s ztsLj0cdCzUbL~mjsH<>@`Ta@ph5c>X7^kp&Ve$^A@L%0JpM-TkxYOBng%>} z=kN;6m!nX6A$+6~1DT!-j!1xqxFR-;mkVN$5=EhG?d35LCkmEg*f5VTw8IWpU%_Jd zTsv$4g$XcYoZv{l+h#HByV=W+vpI@G=VI+wqiy931V8{wA&guQEtD|ic32fI0~ssD z1T03SB8{@c1~R=dP9iakA>+w-0Oum-#}l!u(HL7XH-f=(cKrx}JlSC*rP3G%fgqE~ z@G=r!B<2x7I-O1chy)@LhiKp=2|_6(#|b5il@L=H&ai|d=Eq3+A|XbJ39&_SQadab zna6zcPY}aoeufuHKC*!DL6Ac+1P~7p1Omcz3yIVv9s&92(7&{h_#q8VV8IemoR|Z< z#KS`A;^`1v&S(3WIB~Qp94?0dN5cX{Rf4PvezD|Qcc%Ae3nc|Sz92?rg^>M)rj#G? z7g=BUrkqiQGu;uy{4?$s+Mi-qDI;1;Cc|08iBr1g?reuuuFv3#ID9TcH6&5E5da9V zaa52)!jWM%fTO_>fFsdhFoI2I6C)sS8kD zG6WzaDvgSxgAfHK(%Ec~2uy=mFXkgv2}Mu$N(se9pg0g@!=WPHkk}xIBU5QK92=q$ zkw-3v%Z-325F1iKaXAcEkyrpB>EsI_9!!W4@>CN_!WnD4-R-bM{M4!{iFY(4jX(_S zu%3Kjocu3UKfVC=l|o83K^qbPfFzIzf&iHYPP6uh#S)|vm6#xaCs9@A%Cs<$U=U&< zWt}1bDmfAh!$}N7QjyqCB#O4fDjmQmEk92)k#^!jQpg#S!U!lpBr`yOLA3D$00sy$ zC^Q^k!vLn~i@5xVg#S%j**qBAsg%3%CCK^-D$!I&`NFYNPg9T4d{rx9Fsi0tK%A)% zBv3reRr!fvO-*qkAt4V&c8`zc`bp0J7o|WXQYjD+0pf@hGLk=v4IM}0Qt3D%2+@gD zIvt|Z;V;o8q6n!B62ohF2#*L?NO`Kb!dR*jW%Z@DED}~`0U-EWOeT>@bS?yNB4}Sa{eKE^swRjG0Q@pUTY_?1 z{FGE%!hcKql)|)q6rpBHhV0MCc2D@c-+$yxxwHNUKOf8OKez${{cVx2;`bX}-{|@( z2EI!9TXlV->#G>}D&=q0^>3pK{nv>R79uZtGUPmHl*{x+&XP0O>()A>CY9gZOFte$ zBswu}K@#KuTCcp+GFIv>LWJ5ALvEex@t=^4~h`cLa9rj)JY^z9z0O0_hFce zk@2OG80GtLz;-=j1YPXzyv9#{Z|G>4r{CHIyLvQM)i8tH(4i@3lFlxWm3l5ZPh|;; zvY4BU_6DD7-DJWkGNw{pLmsbR!jHN|4$iygl5wP5pQ+iYC^rZy%uAi=@9$ucTBWt! z#V<1`dxK>`flqZ=&Ed}1m9|Go13a_KMEzmC&zyz*vioufi+XMcb8LCmsU$v|%N-vjPc^!y?3U!9dR;q8Gl z%zPD+ZBSD)awTa}GTCje%YIn*>k2E_WO4EuZnbzW>i)&f@w%KGDid@C8oABUYDs^dmZk^q z9U3dTA9`i54|=RA4;?!e9PCdWGpVbY$OFP(0^y++mb#YfQgS*=j)D~w(@bwx!7Pg^ z&v~^MXXc)kmTagbt~fStSfA#@GW>zHEXPD`k4aDY@ZB@0-r$gxcuMFVkDS+UcUpEi##fSiL4OY^t%zvMsOcAUBB_SK&D>{^SO2+rjAkt6>oe=_uVTghUrov3g> zW=-Cffpu0!q0dr7&W+1o^v^%E%gbn2a-UH`nLR#Kjy2cH=AKS(#8><%$KIrm^jd5y z{fWhD(nJG|4>!&nJ!?-Jb*cJ2q#Tu;qwe|q*U9$5wmdGcNpWI}rR^S%(u!^cF9B|;2rCiOoQ1EUiR6GUK;pomfWZjYW59l_0X^t?m{1YylSOm4{q+_sX(|g&iGRjT!Nm{S9givFRBZS}XD0 z$1kJ~w)KiOg`N(<=Q1@5pKs0xTV;+4F0D{@NPbAd-7)n&+aCV>2Yut4vRP3!iJA}m zbp-aB3bj7*mOta<*_AK)HTL`KOma0-urIphVY|N%3V5>P`p}s>XKbUR)J&86P(|l9 zlu|7&*x%K*sK;ofG`ACmuC<<8+??(w&~%G0=*_ytLhBa~9G>h8sA3k!V(iU5nqEt@ z4et7*w8OV<^lMk2JvcaYHK?@0^Lv?=Y5Y*472N-5>AKvN8_gM~T@vnQ8enuSPu#q7 zH{nTnx%zq8eeU0SVINk(m5i((C+2{@$GqA*j=m0bOg6x%C$8SuJKQkKn$fmMx31|% zG{@ zc6?`7j!#>QeqcqcZ+*kfZ2GL$w|<^SwNC%Y>-FlLOp+%4rhWYf60iB)^(@@ahK?_N zle4mCq_ww~jGW5vt#{jZK{0dob&Gj~ljl~fiffuHzj=JCkwM8wkfXxCG!W{%w1C^y z*W0Si(=kXJ+4bn;c)fW=hxuUK`*&v98v1AlOH>|8q5kh0pqk38$E+9s&zN(Qy-|*8 zo{v7%IJDn0F*PLzqrT_c%$?Cb)ZDyxM_$W)(5Ar8k;S@YWl;~Ka}69*)KOZk>1pbb t^R;MIB%LKw05i2P%E5DT=FTM4PG3;E$@#uD@)w12ckyyAaSZ?NzW@xUIM4t9 literal 0 HcmV?d00001 diff --git a/gui/resources/icons/keyboard_double_arrow_down.png b/gui/resources/icons/keyboard_double_arrow_down.png new file mode 100644 index 0000000000000000000000000000000000000000..4a2e590cec42e5d463ceab7499c0c9ad3685a370 GIT binary patch literal 5753 zcmeHKdsGuw8lOOf2(3cJQeQ9xmAY-7OrD!a5CQ}nL1aNHE=-aMM99M=n1GrDw_UY7 ztPQKSB2ZhZM_r}TmMyGJ)B;tvLR(pU0+m*6sm2tmXc2lRAY!+tJ)GU1{m0>OXXd-# z_xrx@cYpVu%;w}J@lX2A^n)PiNl8L%3Iq|rBLO1$fLo@1uM*sxMXAe;DX0n7>9tB# zJ_Z{Lbr_79RbbM5UY&e2@HqU$kCEc|I?Bc!s}t;91%D~enifNQuVc<((PsLR*1o$5 z4L+!}@xZplr@w07E#BwBqruTFQ9|U^;?Ar z$3?T7vsTom{9#JktCs`b=ARRbXXj0SB{}Sj-{1K=GVe{2&U`H>IR5DSJw2_mj-$;P z>AvaF0fW%$HM$hz)~ANI2fg^QS$A=Z=}w5r1zGD)rq)Lg_P&8BQY2y9v!-u2L<)N) ztd#sLV_EgIW<=21DO|ViNJ;SfjC9lKXmxY|BEpzFGPAg%Af z`lO*_y66=dSNNX>zFoIz-lhQft#ZG8bpd<+6y6;B*W31xp}oDqC+6Ard&QMcI#aVq zKiFfv*|egb%lc;i%XX2gL~Si499>z{QFq-Xzo6L#73cIM_6_7ovv1pP#l@G*A$VVK zHW$R(@7PYw$sUkwf8xYeFXVnR`KBeVyTaE;TipJ}g%xW<_e>RSYfS8hd^bAHn-6yi zyDoKJy5Pt;fB!yYpRBJ>UNpB0XwIwx+FCAsfiKspsi;CL!>DGp4u}qd1W{%kD$m1= zunfylX@q1~lY62tMj^nP zkeq8Y>i9I8$z-CMBB@$^4voR%@o01=jme|{4~n5sV?@mqjUgO|7{Q3e4063nXH;o5 zFpi1Jv;{^XnGELP2lc6SQt24H#xTkP;DcsHbu7*fF& zrKMm7ZGm2niPvBnWB7Oog?ubtSD?@Lw4;#IuzXAnTn!*A7?VSf5p07ofjBML^O zjKX9i0D{A1QMfWWMnPC?1uv4r#gugBIEW;@3aApzA72#?r2tTD8IOrF=xmT)DWf1f zHl4!bu{adEoF_wgTseo!Rd}Eja(M$>6>JQFzK{ODwfkj$jgA6k<0 zQKJ$B2+1#~GzI2|6R9dSw#9OvOP2S zvhYDOfLIjQDFE=;K`;CmJ%$>!`c$npUr5GFg7L_)X(`xF3eB}^BPp$>JQQIuMo1b%H)xec6RO9ea{!NkDs;bS$9#2PXoL!?;5R#Esa%;RVh@+Sp+@${DEO_q;~e;`dAe!;h0ph~LL_ zJ*I0y3{1%RvAQ19H6aEjs@srH)WXZ$Ry{Aj?a>q^?` zGzXiyzm_EUvwrdivxfIg-Cm!wpjLY@wV~HxO7dAy8+xz;Lim=zYuy845%l652kDk} zklYh#TiF_QRx#MnR?S&BE%#PcDSL*ajaUh-nPEM0z1s9tu5z&VaO1fztGJW71SHB5 zQ9M*;{dz84$JzzWoa3;IhFh$zs>-)3wjDe$mcSYAYz#hMx7odRHpr)SNv^MUPR=eE z?0;uCB%;_-+AR@5md~$D-72u&z1(qub13Tdfufz3YHPan{@wU%PnwCjpLMonEi9UC z9@yph)ZI&Lzqi2ID{5%9xQ4u7uNLhfK5p?3^J<|%n`~}>h@3s>Wg|V~fZC?HY&59|x%v~#8eU9Pu znC`1?Altr};j%=pc5mL*-lpL5yQ`|Jl4u8~gn9ia80!C~xdRxwUglk0_ub#V4XoMf z-g0VH;c#ClHK#2lu{-lkO-oj1NqyEudvxMA8=spCm6c}^?{O@F0k*VOn%DhV4iZVU zzc&~NEsGe^y3y9>QK)!n5D?-C-j>WGEjLc&+TGn<_S&gFyPyyLKT7?~>h*cJsN^Hd z(D$G9I*+>s)#afPwtpuPLVO#Ax7XeY#+SXR;w7;M7iDkw3GyyiEdT%j literal 0 HcmV?d00001 diff --git a/gui/resources/icons/keyboard_double_arrow_left.png b/gui/resources/icons/keyboard_double_arrow_left.png new file mode 100644 index 0000000000000000000000000000000000000000..95a70adad6f704f66a61554f09c18c25a8cae322 GIT binary patch literal 5165 zcmeHKeNYo;8s9*`5VeOMinT(wv7R68W;fX-Bry??V2Bt*#G;N>H=A8p$(PAO!pC8% zwXNuY*6V4lGwNtPJWs89h>nK@tA}T=I#v8+PVj7ww1{I7mU<=l#ltB+hi>CgIA2Rj<*A?^3e z0((}NQfh6xcD(-zHve#mWmNTwsKPr@oBq;tef7R4z^pYofF%3 zXHl}|4a1CUugyAJ#pmo?=aNuEmy`{jy}#_y@oTP?Czod~DQHgmZ`=9Fs%6HFpRL_` zFufvj2OhEOT^IMa@@QlHh&bcK$h*$W@vTFfF3gLVwr=$$P}lo>YHF4#HT7vJpn%Q4 zU8hg~GI`VoEjy=wo-?Kmy|s2*(Sg+!>Wh!uWj0KHwV9E z`F;ew1~n8c;C`=o%k*kj<-SsJSNVq4d5;U1RhHM}D^PU!_)qDpCw@3_{C!mCEMx=_PJ#6=M|~g;5H^iqUie zgE1O9fwE9aO#-J3Qdt@8G^g86gYD$)bRLVl9C<+p6kMBZ;6+x2ZGtfJ%+XFfgaw-TpsS0}FwrD{yKv){~ zDIf^iK`q);H%kjncaGC()5~B2D2(iNo569i(gJOu1s0GJN=mCBw93RBf`AiBg%OEb zq7U9_<+XlW)?f`=|*t-(A2 zSIEWW(~dkA+#Wsc`qa+9pcO16K{AP)8Y4*-w1SGFFbhRmF@jd9NF}&w)S6H?^|E`M zoZzM1Y)T%`5oiV4GpH3hA-GW!`{&}#XW=dY!7v4ZJuevEQ!ozijHear@aHtq1p$37 z84wq;fy)crg?R5}*rOT9_m}+i?8Ps+1d0wU@>2Q^$Tc9>ODXVD;DPQMkn5!scq#Be zcl~T~NuRw=u@3Mn$O~SUPMw#o0WVsSmJFi-c>@2o*8O2Uutd4i=Xnrh@UP*&2-&oG z6fh1FOy;yf-%DQ`B$Z!|lYD_7;msyPN{;Vp`#(}DWGOLe-w-1)$tw{J<{wT)RIlZ} z)#o+c$W7X-624(T{7?A=ZfE{R{lUHO{!{kk;nMntN3Lcd6^(7x?cd#e`ewIa7f87D4W#nQLW!R_6boY7 zS3Yk_(?NtG9C*{H7fny*?Toruoc!Q;qCYPF%IPgOki-^Bwip*hi=fgU`6ZV#5JNJQ zTZV=K@33gFM}Emi{yK58*Z}qf4TEr3(~tT_!@^pt(~`yFz^v7NiNwEsq-a<)V#LB^ zC{j6JY)D4N)BtWoy#%ZSNrM6H<6zj&@cl_8q%K`K7OZx4;dPk6pDYG$Xl0ChQVREbmhpAiXtNrhAJAn@ ykGHL<6QdZ-#KjpN6*udbyt2*DVbspLSiA-skhP_i4FaIB+!9SJ& literal 0 HcmV?d00001 diff --git a/gui/resources/icons/keyboard_double_arrow_right.png b/gui/resources/icons/keyboard_double_arrow_right.png new file mode 100644 index 0000000000000000000000000000000000000000..69219e444270574b5561ae692e90c3be288e2789 GIT binary patch literal 5151 zcmeHKdsr0L6`utJ1=A`~A%vFcT0b9jc4u}Mc6Z$6xdY}v~n)s*1QCH-5i&LqTz=*7n!u&8IC~MFMY&MB z!)D^lEXo(zS(J5i!0B$aWd1Vr2s*y|^h{0CvghoPc`J`U?Ji07&-g_p_2+4O4Su&e zOB(k)t52*m|8Zye53nT%{(_G`w|QLW)o~Gj-Fh^&HucVoO?wr~PC1vDH@;DG%gFdP zT{y2hv(~(PPGn+n%F?K#-tkkfq`ilG&rI2Eyx)4{lKr`3&u8T2x5T%#yzVmhL{ZkH zHUALL4Bq(e~j#Po~zRy8I;579v{zRF~(iUk7xRhJCuYr(l(*bYCukqM_4&Pqj9E-Xwo@|KXzT zsuQzn=ayt>sQ1Ub7fuPt;UJ+)=EY_W^$*?Cy_i zw$`cg_mTN+n-Aex=PD}?WH={rKU*;|R5!z0{ZfRvi94@xp1dGDvcw6p9|So8gG|D^hank%ZdX3tqtwB~f<%a`uh6sw!2 zf40FhWwu}7{?+R~_w2qYs+`^U-sYdYS{prv3*HslQ97qB8ws?n?s(&T-92?iR9R%_ zET?~Dq+dIGV%e8PuH~+_o;{rJcF^8u9fwL(4Naiu+#KkwMTU7KZL>%y#%5$CZi^i> z9fD}$-FAx3XL;1f=5SW6_;&pvG0HJo@xmAbZm=h_xm;SYgPmWTkxdup(`rT>9~Z1~ zlYqd&@)YW}n5|CItrZKrB)ErWsTdU?e7;t^$dHL9+Z-&akSHWLmg43LW#YJCRO4Vw zWR`AD9|d^QigS71PD-UNmrLT3OKgrDDWO)YrMOHglVJdXIg6}3<;JYesgRfF{E&7 z!f83ds?``xGe%6IR1lcTL@`)Qj7%+;t7CAQiWx$sw>o*sO0$p(kV`ngLlbgJA&-s0 z)GSM33KgruC_=$tCX-PiQ=2HY(x@In@pA_Ux{@*v%?eU6fJ(-wjWRh+Uan=I&pd*{Ju=9Bes!1s2I8Mm%Sh-5BR4U|ypl4Wz6LccvByfp5R`9@OAwe-f zSPJ$jAQ0@J7BbnvQoPNPZL^uRVwe&NBM00Du$>r+r*st00#aP2APJn5DYJ2$BnT3h zW4MyUhv01tXDa$OG~7I>rgzEHI479DNHF#8sQK*5-lyJ2Gbd~%6csiFNzuI}IH^LG z5%L6Fy)HVJvgWYh^yq8XemnPwR!}kw6Jw-I7_N>1tq>!pFiOS}n3|%EtRj|Wm{@u^ zyVGXkU6g}O%mF$Atw4JUTA?$9g_=1W?aF20DgePS0>{27n6$58DLga!E7nNAp@~KS z3^`;#T(1orUf?X04jhJkn!#h|d;IjR#rHS^pdOuMMEZ`(H7eJL6c`bBw7W*-8j%7c z0*`jrcP3Zx;Oi7?1^zjdPoIP!^6G1|rgg+7T z%GPjT4C3{Ml%VUuPX~qgm$$Ix2;%>Dy)H4^-FoZd+j->);d9QMd0|RGdg6u3ZI-&_ z?{sWCyX(RIYo;g1KIIR>ALrBc(f%msM-`uiezD-4bIsjfb$&{QZMI8AV?8b2i|NQG zbZnk4w5+RYLu*3-8fU65l#13?9E^j;?y4I2h+n%7k?YkYFe0?a1CWhX)k9pG9)Jkh zj_4X20ulngeQflm0OW|qgaC;DpT~>o5dWQx(NQ81p63frO+ePSHXNBa0jVy0%Pve2 z9r=H_Qcxjk;@H#`ogeQwIUQ*`RpRqaMULNGwy#+VFIOJ#ax^~ha1~fI+ys_veM>_C zLW7lT{4XX=DfD)9Z2-W=b|s9dXoFZyX+;|}`MO{Ow6wcGH<$!dmA15EIW+mY#sJ!r z?O|{R!PKBB1t{O$UdLSM4uOUwn8*YO1MTy5(?uFH%WFEw?^|V%9TzA>K ly{9_d=l3|<3&dW!8nP$+s|U9OR4+p&eM*Mz&7>7;{sW&#UpxQ+ literal 0 HcmV?d00001 diff --git a/gui/resources/icons/keyboard_double_arrow_up.png b/gui/resources/icons/keyboard_double_arrow_up.png new file mode 100644 index 0000000000000000000000000000000000000000..94d39d7eaa8f4207a56ebfda8f3bf030a6e2cc56 GIT binary patch literal 5666 zcmeHLdsGu=7N11ah_wi)P_#0HTD6*Fl1xZ4B}7UPqDGN|qJ_dF8A60SOacjr5FcBs z;;ZiQ{pzBti;K^twW21L3fo#sTZ4f|1f^ZtOhDqk8lt}u1;#rEd?amVL-=D}Y( zVGW$r=lbN(Il?V{o2BYK`6K@A3clLsp>TKTjX_PGS%Hh#6ZV427Hbm{QsfBdkmPJ*(v3kS58kZ^~wz+SPj63n&sp54HK9VLmQjwQjq3?!H5stqy=*mXLVBxRyCX zWSBc+Z{fKUqs#FlJF3T=LhR;F96Zmv_M=LiYb`Npkw1|gOXs|bVi^$ z2#S^3jJPVFu)s<}qt#28t+fs&tW`^xGX)AnVN4+Mw8p^VbC@t?V#${v!XtVEl(h{uczgkw$W zTr5>Ku@eG3Ntk&SixJ~+tX3=A%4Zu)8V*-17IP3DhsR?93zoT9Z^3OWy*ZkM=)jN> zW|c{6v}g@_n8d`DhC+*k$prgwSAII9LeUMcH+QlC_~6)ZBZtdII657tr-#{+SOh>i z6Z%6Ba~kMTPAXwG6q-~-ViBRYME8VHtGfM-g{A_k9JPu=6c9RKY6elcPlZg9D^j{W zND4GsosseaWIttT(dIrO>#5wx9jct3i2(O*+^4L&YNw2Wl|q5Z45~shJ-JN6B;#Xh zgG#H$s9OXT!%VwPAW6tPe-4`GQARK-G3fr`jg^OS^G+yhFkH(PMMiXfo?I9m&F zVo;?LRr7@`HIYj?3Q?9aSH))uV^D%8Q1W;JF0Ti~G?Nyn5-;eP6$zyVP-+}Fs#FLI z6$ykaRG<{HltLcL5(p3h!bd~|F2E@$wF;YPFzIk`oLU{OAvi|8hT0$r$Kq4u5+;w0 zJXuL8z%9AJLBgD()fd{HY@}&*#G4kJWRol8iN!(@D&q1`0TRJ$J_>!21a!9?H|gDK5mD3CBo2$=Nj-d2EiQsWj}hFb^#ittd3 zi(tH%G%kwqQ4Hm>5Fv*2us5i+xyAp>nrt38w&Tc?wPp~%m|E)Ss5gnZ9ZwyP1zM_= zV3=wO3|DoOV8)9GHI*m8>ey1{;d%`Lrbnk-yVkXTAO#^J6vT*80Si~DaTbb*xGXVW z6vGk|LV-XiMg#=jQB^m(*^q0o;wB&oTrIKM&F?exK9z zoUUFm&@1ET>UvIBuNdf+@pE zzh@%=ZZ9ts#xg8oDR~9@N z`nZ8Zr%&*D6DL57NC$%feeVvV(cn@a6NVPA`U{MagPx$%?Rb9mnXAiJkwI5Ds`ky! z*VVRcTLzL8wZ9CqeB+sA=?(%_-`d}wy})z%Ld(vd=4AY;S>h8K=}vEXX^0Ko%!v~X zVAwrNRsb%X-a0ao93LQQ!DCmH%hFK(L95$PT~jr?7`Yyh;}b^ue_Flo{k3)|y!<*z zYK4@dvObbxn~FxFk<9i)qtTEu8L*BFJ`!{yF!mn})3(R*+gmTKsG5;wHQksbqE!@s zE8cb{EZ^FGY_0Rat=g&!413U}trMNz-C;C$n0-1k$9HzQ-7~M>-D{}-$6&qSZ2bVsgxTz78v<}+cDWIqfqPtU43ccG|OG8D9g(f2wj&u7*^ltj*F z2W8UTj+$C|Q`3Q4jW0elxB~1RzxS29c`@0g#*o2~J7_p)(+&y6_Ceb3di?$=IrlF{ zI{Y^_+C%N0%cVX|dJVQX|Jo}sR3C|vUH)gf0|;OmgqKq@pi8c+$Pm%=2PbQx=n~(( zPx)^D7cG0{G!>3szi)AQdP}@ek=XF|zDFkW1_{$^Tm6npnH$L(VbiOSkCAj z_@PqeYa8BE;RBsxy5ySkcSgAX9#B3Vnbale>FM)}h_aO&ddtpr>EG6V*Z@TMwYT;1 w#pS<*jc&QocCLNi;YKg{U)icons/arrow_right_128.png icons/arrow_up_right_128.png icons/arrow_up_128.png + icons/arrow_up_dark_128.png icons/arrow_up_left_128.png icons/arrow_left_128.png icons/arrow_down_left_128.png @@ -25,6 +26,10 @@ icons/dump-truck.png icons/crop.png icons/flare.png + icons/keyboard_double_arrow_down.png + icons/keyboard_double_arrow_up.png + icons/keyboard_double_arrow_left.png + icons/keyboard_double_arrow_down.png diff --git a/gui/widgets/pupilGuide/pupilGuide.hpp b/gui/widgets/pupilGuide/pupilGuide.hpp index d4e853a79..ce0c7e4c9 100644 --- a/gui/widgets/pupilGuide/pupilGuide.hpp +++ b/gui/widgets/pupilGuide/pupilGuide.hpp @@ -66,17 +66,21 @@ class pupilGuide : public xWidget int m_tipmovewhat{ MOVE_TTM }; + // --- TCS + + std::string m_tcsiState; + // --- woofer + std::string m_dmWooferState; + std::string m_wooferModesState; + double m_tilt{ 0 }; ///< current value of tilt mode from wooferModes double m_tip{ 0 }; ///< current value of tip mode from wooferModes double m_focus{ 0 }; ///< current value of focus mode from wooferModes float m_focusStepSize{ 0.1 }; - // --- camwfs-align - bool m_camwfsAlignLoopState{ false }; - bool m_camwfsAlignLoopWaiting{ false }; // --- camwfs-fit std::string m_camwfsfitState; @@ -157,6 +161,17 @@ class pupilGuide : public xWidget float m_camlensStepSize{ 0.01 }; + // ****** Alignment ******** // + + // --- camwfs-align + bool m_camwfsAlignLoopState{ false }; + + // --- twAlign-camwfs-ctrl + bool m_twAlignLoopState {false}; + + // --- twAlign-camwfs-wfs + bool m_twAlignSensorState {false}; + public: pupilGuide( QWidget *Parent = 0, Qt::WindowFlags f = Qt::WindowFlags() ); @@ -182,6 +197,14 @@ class pupilGuide : public xWidget int whichcl = CAMLENS_BOTH ///< Which axis, or both. CAMLENS_X, CAMLENS_Y, CAMLENS_BOTH ); + void camwfs_align_setEnabled( bool enabled ); + + void twAlign_camwfs_ctrl_setEnabled( bool enabled ); + + void twAlign_camwfs_wfs_setEnabled( bool enabled ); + + void alignment_buttons_setEnabled( bool enabled ); + public slots: void updateGUI(); @@ -245,6 +268,11 @@ class pupilGuide : public xWidget void on_button_camlens_r_pressed(); void on_button_camlens_scale_pressed(); + // ******** alignment *********// + + void on_button_startAlignment_pressed(); + void on_button_stopAlignment_pressed(); + private: Ui::pupilGuide ui; }; @@ -255,12 +283,6 @@ pupilGuide::pupilGuide( QWidget *Parent, Qt::WindowFlags f ) : xWidget( Parent, ui.setupUi( this ); - - - //ui.modState->setProperty( "isStatus", true ); - - - ui.button_focus_scale->setProperty( "isScaleButton", true ); ui.button_pup_scale->setProperty( "isScaleButton", true ); ui.button_ttmPeri_scale->setProperty( "isScaleButton", true ); @@ -284,26 +306,26 @@ pupilGuide::pupilGuide( QWidget *Parent, Qt::WindowFlags f ) : xWidget( Parent, ui.modFreq_current->setup( "modwfs", "modFrequency", statusEntry::FLOAT, "", "" ); ui.modFreq_current->setStretch( 0, 0, 6 ); // removes spacer and maximizes text field ui.modFreq_current->format( "%0.1f" ); - ui.modFreq_current->onDisconnect(); + //ui.modFreq_current->onDisconnect(); ui.modRad_current->setup( "modwfs", "modRadius", statusEntry::FLOAT, "", "" ); ui.modRad_current->setStretch( 0, 0, 6 ); // removes spacer and maximizes text field ui.modRad_current->format( "%0.1f" ); - ui.modRad_current->onDisconnect(); + //ui.modRad_current->onDisconnect(); ui.modCh1->setup( "fxngenmodwfs", "C1ofst", statusEntry::FLOAT, "Ch1", "V" ); ui.modCh1->currEl( "value" ); ui.modCh1->targEl( "value" ); ui.modCh1->setStretch( 0, 1, 6 ); // removes spacer and maximizes text field ui.modCh1->format( "%0.2f" ); - ui.modCh1->onDisconnect(); + //ui.modCh1->onDisconnect(); ui.modCh2->setup( "fxngenmodwfs", "C2ofst", statusEntry::FLOAT, "Ch2", "V" ); ui.modCh2->currEl( "value" ); ui.modCh2->targEl( "value" ); ui.modCh2->setStretch( 0, 1, 6 ); // removes spacer and maximizes text field ui.modCh2->format( "%0.2f" ); - ui.modCh2->onDisconnect(); + //ui.modCh2->onDisconnect(); setXwFont( ui.label_tipAlignment ); @@ -339,11 +361,11 @@ pupilGuide::pupilGuide( QWidget *Parent, Qt::WindowFlags f ) : xWidget( Parent, // tweeter controls - setXwFont( ui.labelTweeter ); + setXwFont( ui.label_tweeter ); setXwFont( ui.buttonTweeterTest_set ); // ncpc controls - setXwFont( ui.labelNCPC ); + setXwFont( ui.label_ncpc ); setXwFont( ui.buttonNCPCTest_set ); //-----------ttmpupil controls ------------ @@ -358,11 +380,10 @@ pupilGuide::pupilGuide( QWidget *Parent, Qt::WindowFlags f ) : xWidget( Parent, ui.pupCh1->setup( "ttmpupil", "pos_1", statusEntry::FLOAT, "Ch 1", "V" ); ui.pupCh1->setStretch( 1, 2, 4 ); ui.pupCh1->highlightChanges( false ); - ui.pupCh1->onDisconnect(); + ui.pupCh2->setup( "ttmpupil", "pos_2", statusEntry::FLOAT, "Ch 2", "V" ); ui.pupCh2->setStretch( 1, 2, 4 ); ui.pupCh2->highlightChanges( false ); - ui.pupCh2->onDisconnect(); //-----------ttmperi controls ------------ setXwFont( ui.labelTTMPeri ); @@ -375,11 +396,10 @@ pupilGuide::pupilGuide( QWidget *Parent, Qt::WindowFlags f ) : xWidget( Parent, ui.ttmPeriCh1->setup( "ttmperi", "axis1_voltage", statusEntry::FLOAT, "Ch 1", "V" ); ui.ttmPeriCh1->setStretch( 1, 2, 4 ); ui.ttmPeriCh1->highlightChanges( false ); - ui.ttmPeriCh1->onDisconnect(); + ui.ttmPeriCh2->setup( "ttmperi", "axis2_voltage", statusEntry::FLOAT, "Ch 2", "V" ); ui.ttmPeriCh2->highlightChanges( false ); ui.ttmPeriCh2->setStretch( 1, 2, 4 ); - ui.ttmPeriCh2->onDisconnect(); /* pupil tracking loop */ setXwFont( ui.label_pupTrackLoop ); @@ -390,7 +410,6 @@ pupilGuide::pupilGuide( QWidget *Parent, Qt::WindowFlags f ) : xWidget( Parent, ui.pupTrackLoop_deltaX->readOnly( true ); ui.pupTrackLoop_deltaX->setStretch( 0, 0, 6 ); // removes spacer and maximizes text field ui.pupTrackLoop_deltaX->format( "%0.03f" ); - ui.pupTrackLoop_deltaX->onDisconnect(); ui.pupTrackLoop_deltaY->setup( "camwfs-align", "deltas", statusEntry::FLOAT, "", "" ); ui.pupTrackLoop_deltaY->currEl( "delta1" ); @@ -398,7 +417,6 @@ pupilGuide::pupilGuide( QWidget *Parent, Qt::WindowFlags f ) : xWidget( Parent, ui.pupTrackLoop_deltaY->readOnly( true ); ui.pupTrackLoop_deltaY->setStretch( 0, 0, 6 ); // removes spacer and maximizes text field ui.pupTrackLoop_deltaY->format( "%0.03f" ); - ui.pupTrackLoop_deltaY->onDisconnect(); ui.pupTrackLoop_slider->setup( "camwfs-align", "loop_state", "toggle", "" ); ui.pupTrackLoop_slider->setStretch( 0, 0, 10, true, true ); @@ -406,7 +424,6 @@ pupilGuide::pupilGuide( QWidget *Parent, Qt::WindowFlags f ) : xWidget( Parent, ui.pupTrackLoop_gain->setup( "camwfs-align", "loop_gain", statusEntry::FLOAT, "loop gain", "" ); ui.pupTrackLoop_gain->setStretch( 0, 1, 6 ); // removes spacer and maximizes text field ui.pupTrackLoop_gain->format( "%0.2f" ); - ui.pupTrackLoop_gain->onDisconnect(); /* actuator alignment loop */ setXwFont( ui.label_actAlignLoop ); @@ -417,7 +434,6 @@ pupilGuide::pupilGuide( QWidget *Parent, Qt::WindowFlags f ) : xWidget( Parent, ui.actAlignLoop_deltaX->readOnly( true ); ui.actAlignLoop_deltaX->setStretch( 0, 0, 6 ); // removes spacer and maximizes text field ui.actAlignLoop_deltaX->format( "%0.03f" ); - ui.actAlignLoop_deltaX->onDisconnect(); ui.actAlignLoop_deltaY->setup( "twAlign-camwfs-ctrl", "deltas", statusEntry::FLOAT, "", "" ); ui.actAlignLoop_deltaY->currEl( "delta1" ); @@ -425,7 +441,6 @@ pupilGuide::pupilGuide( QWidget *Parent, Qt::WindowFlags f ) : xWidget( Parent, ui.actAlignLoop_deltaY->readOnly( true ); ui.actAlignLoop_deltaY->setStretch( 0, 0, 6 ); // removes spacer and maximizes text field ui.actAlignLoop_deltaY->format( "%0.03f" ); - ui.actAlignLoop_deltaY->onDisconnect(); ui.actAlignLoop_slider->setup( "twAlign-camwfs-ctrl", "loop_state", "toggle", "" ); ui.actAlignLoop_slider->setStretch( 0, 0, 10, true, true ); @@ -433,7 +448,6 @@ pupilGuide::pupilGuide( QWidget *Parent, Qt::WindowFlags f ) : xWidget( Parent, ui.actAlignLoop_gain->setup( "twAlign-camwfs-ctrl", "loop_gain", statusEntry::FLOAT, "loop gain", "" ); ui.actAlignLoop_gain->setStretch( 0, 1, 6 ); // removes spacer and maximizes text field ui.actAlignLoop_gain->format( "%0.2f" ); - ui.actAlignLoop_gain->onDisconnect(); /* actuator alignment sensor */ setXwFont( ui.label_actAlignSensor ); @@ -444,17 +458,19 @@ pupilGuide::pupilGuide( QWidget *Parent, Qt::WindowFlags f ) : xWidget( Parent, ui.actAlignSensor_nAverage->setup( "twAlign-camwfs-wfs", "nPokeAverage", statusEntry::INT, "no. average", "" ); ui.actAlignSensor_nAverage->setStretch( 1, 3, 6 ); ui.actAlignSensor_nAverage->format( "%d" ); - ui.actAlignSensor_nAverage->onDisconnect(); ui.actAlignSensor_nImages->setup( "twAlign-camwfs-wfs", "nPokeImages", statusEntry::INT, "no. images", "" ); ui.actAlignSensor_nImages->setStretch( 1, 3, 6 ); ui.actAlignSensor_nImages->format( "%d" ); - ui.actAlignSensor_nImages->onDisconnect(); ui.actAlignSensor_pokeAmp->setup( "twAlign-camwfs-wfs", "poke_amp", statusEntry::FLOAT, "poke amp.", "um" ); ui.actAlignSensor_pokeAmp->setStretch( 1, 3, 6 ); ui.actAlignSensor_pokeAmp->format( "%0.2f" ); - ui.actAlignSensor_pokeAmp->onDisconnect(); + + /* alignment start/stop */ + setXwFont( ui.label_alignment ); + setXwFont( ui.button_startAlignment ); + setXwFont( ui.button_stopAlignment ); setXwFont( ui.labelPupilFitting ); //,1.2); @@ -487,12 +503,10 @@ pupilGuide::pupilGuide( QWidget *Parent, Qt::WindowFlags f ) : xWidget( Parent, ui.fitThreshold->setup( "camwfs-fit", "threshold", statusEntry::FLOAT, "Thresh", "" ); ui.fitThreshold->setStretch( 0, 1, 6 ); // removes spacer and maximizes text field ui.fitThreshold->format( "%0.3f" ); - ui.fitThreshold->onDisconnect(); ui.fitAvgTime->setup( "camwfs-avg", "avgTime", statusEntry::FLOAT, "Avg. T.", "s" ); ui.fitAvgTime->setStretch( 0, 1, 6 ); // removes spacer and maximizes text field ui.fitAvgTime->format( "%0.3f" ); - ui.fitAvgTime->onDisconnect(); /* Camera Lens */ setXwFont( ui.label_camlens ); @@ -504,12 +518,10 @@ pupilGuide::pupilGuide( QWidget *Parent, Qt::WindowFlags f ) : xWidget( Parent, ui.camlensX_pos->setup( "stagecamlensx", "position", statusEntry::FLOAT, "X", "mm" ); ui.camlensX_pos->setStretch( 0, 1, 6 ); // removes spacer and maximizes text field ui.camlensX_pos->format( "%0.4f" ); - ui.camlensX_pos->onDisconnect(); ui.camlensY_pos->setup( "stagecamlensy", "position", statusEntry::FLOAT, "Y", "mm" ); ui.camlensY_pos->setStretch( 0, 1, 6 ); // removes spacer and maximizes text field ui.camlensY_pos->format( "%0.4f" ); - ui.camlensY_pos->onDisconnect(); ui.button_camlens_scale->setProperty( "isScaleButton", true ); @@ -543,6 +555,10 @@ void pupilGuide::subscribe() m_parent->addSubscriberProperty( this, "camwfs", "fps" ); + m_parent->addSubscriberProperty( this, "tcsi", "fsm" ); + + m_parent->addSubscriberProperty( this, "dmwoofer", "fsm" ); + m_parent->addSubscriberProperty( this, "wooferModes", "fsm" ); m_parent->addSubscriberProperty( this, "wooferModes", "current_amps" ); m_parent->addSubscriberProperty( this, "camwfs-fit", "fsm" ); @@ -626,15 +642,40 @@ void pupilGuide::onConnect() ui.modCh1->onConnect(); ui.modCh2->onConnect(); + ui.label_tipAlignment->setEnabled(true); + ui.button_ttmtel->setEnabled(true); + + ui.button_camera->setEnabled(true); + + ui.label_tweeter->setEnabled(true); + + ui.labelPupilSteering->setEnabled( true ); ui.pupState->onConnect(); ui.pupCh1->onConnect(); ui.pupCh2->onConnect(); + ui.label_ncpc->setEnabled(false); + + ui.labelTTMPeri->setEnabled( true ); ui.ttmPeriState->onConnect(); ui.ttmPeriCh1->onConnect(); ui.ttmPeriCh2->onConnect(); - ui.labelPupilSteering->setEnabled( true ); + ui.label_pupilPositions->setEnabled(true); + + /* Camera Lens */ + ui.label_camlens->setEnabled( true ); + ui.label_camlensX_fsm->setEnabled( true ); + ui.label_camlensY_fsm->setEnabled( true ); + + ui.camlensX_fsm->onConnect(); + ui.camlensY_fsm->onConnect(); + ui.camlensX_pos->onConnect(); + ui.camlensY_pos->onConnect(); + + ui.fitThreshold->onConnect(); + ui.fitAvgTime->onConnect(); + ui.pupTrackLoop_deltaX->onConnect(); ui.pupTrackLoop_deltaY->onConnect(); @@ -653,14 +694,11 @@ void pupilGuide::onConnect() ui.actAlignSensor_nImages->onConnect(); ui.actAlignSensor_pokeAmp->onConnect(); - /* Camera Lens */ - ui.camlensX_fsm->onConnect(); - ui.camlensY_fsm->onConnect(); - ui.camlensX_pos->onConnect(); - ui.camlensY_pos->onConnect(); - ui.fitThreshold->onConnect(); - ui.fitAvgTime->onConnect(); + camwfs_align_setEnabled(true); + twAlign_camwfs_ctrl_setEnabled(true); + twAlign_camwfs_wfs_setEnabled(true); + alignment_buttons_setEnabled(true); setWindowTitle( "Alignment" ); } @@ -668,18 +706,31 @@ void pupilGuide::onConnect() void pupilGuide::onDisconnect() { m_modFsmState = ""; - m_pupFsmState = ""; + ui.label_modulation->setEnabled( false ); ui.modwfs_fsm->onDisconnect(); ui.modFreq_current->onDisconnect(); ui.modRad_current->onDisconnect(); ui.modCh1->onDisconnect(); ui.modCh2->onDisconnect(); + ui.label_tipAlignment->setEnabled(false); + ui.button_ttmtel->setEnabled(false); + + + ui.button_camera->setEnabled(false); + + ui.label_tweeter->setEnabled(false); + + m_pupFsmState = ""; + ui.labelPupilSteering->setEnabled( false ); ui.pupState->onDisconnect(); ui.pupCh1->onDisconnect(); ui.pupCh2->onDisconnect(); + ui.label_ncpc->setEnabled(false); + + ui.labelTTMPeri->setEnabled( false ); ui.ttmPeriState->onDisconnect(); ui.ttmPeriCh1->onDisconnect(); ui.ttmPeriCh2->onDisconnect(); @@ -689,9 +740,25 @@ void pupilGuide::onDisconnect() m_camwfsavgState = ""; m_camwfsfitState = ""; - ui.label_modulation->setEnabled( false ); + ui.labelPupilFitting->setEnabled( false ); - ui.labelPupilSteering->setEnabled( false ); + + + ui.label_pupilPositions->setEnabled(false); + + /* Camera Lens */ + ui.label_camlens->setEnabled( false ); + ui.label_camlensX_fsm->setEnabled( false ); + ui.label_camlensY_fsm->setEnabled( false ); + + ui.camlensX_fsm->onDisconnect(); + ui.camlensY_fsm->onDisconnect(); + ui.camlensX_pos->onDisconnect(); + ui.camlensY_pos->onDisconnect(); + camlensSetEnabled(false); + + ui.fitThreshold->onDisconnect(); + ui.fitAvgTime->onDisconnect(); ui.pupTrackLoop_deltaX->onDisconnect(); ui.pupTrackLoop_deltaY->onDisconnect(); @@ -710,31 +777,17 @@ void pupilGuide::onDisconnect() ui.actAlignSensor_nImages->onDisconnect(); ui.actAlignSensor_pokeAmp->onDisconnect(); - /* Camera Lens */ - ui.camlensX_fsm->onDisconnect(); - ui.camlensY_fsm->onDisconnect(); - ui.camlensX_pos->onDisconnect(); - ui.camlensY_pos->onDisconnect(); - camlensSetEnabled(false); - - ui.fitThreshold->onDisconnect(); - ui.fitAvgTime->onDisconnect(); + camwfs_align_setEnabled(false); + twAlign_camwfs_ctrl_setEnabled(false); + twAlign_camwfs_wfs_setEnabled(false); + alignment_buttons_setEnabled(false); setWindowTitle( "Alignment (disconnected)" ); } void pupilGuide::handleDefProperty( const pcf::IndiProperty &ipRecv ) { - std::string dev = ipRecv.getDevice(); - if( dev == "modwfs" || dev == "camwfs" || dev == "wooferModes" || dev == "camwfs-avg" || dev == "camwfs-fit" || - /*dev == "fxngenmodwfs" || */ - dev == "ttmpupil" || dev == "camwfs-align" || dev == "stagecamlensx" || dev == "stagecamlensy" || - dev == "dmtweeter" || dev == "dmncpc" || dev == "ttmperi" ) - { - return handleSetProperty( ipRecv ); - } - - return; + return handleSetProperty( ipRecv ); } void pupilGuide::handleSetProperty( const pcf::IndiProperty &ipRecv ) @@ -768,9 +821,36 @@ void pupilGuide::handleSetProperty( const pcf::IndiProperty &ipRecv ) } } } + else if( dev == "tcsi" ) + { + if( ipRecv.getName() == "fsm" ) + { + if( ipRecv.find( "state" ) ) + { + m_tcsiState = ipRecv["state"].get(); + } + } + } + else if( dev == "dmwoofer" ) + { + if( ipRecv.getName() == "fsm" ) + { + if( ipRecv.find( "state" ) ) + { + m_dmWooferState = ipRecv["state"].get(); + } + } + } else if( dev == "wooferModes" ) { - if( ipRecv.getName() == "current_amps" ) + if( ipRecv.getName() == "fsm" ) + { + if( ipRecv.find( "state" ) ) + { + m_wooferModesState = ipRecv["state"].get(); + } + } + else if( ipRecv.getName() == "current_amps" ) { if( ipRecv.find( "0000" ) ) { @@ -1025,14 +1105,10 @@ void pupilGuide::handleSetProperty( const pcf::IndiProperty &ipRecv ) { if( ipRecv["toggle"].getSwitchState() == pcf::IndiElement::On ) { - if( m_camwfsAlignLoopState == false ) - m_camwfsAlignLoopWaiting = false; m_camwfsAlignLoopState = true; } else { - if( m_camwfsAlignLoopState == true ) - m_camwfsAlignLoopWaiting = false; m_camwfsAlignLoopState = false; } } @@ -1209,7 +1285,7 @@ void pupilGuide::modGUISetEnable( bool enableModGUI, bool enableModArrows ) ui.modCh1->setEnabled( false ); ui.modCh2->setEnabled( false ); - if( m_tipmovewhat == MOVE_TTM ) + if(!enableModArrows) { ui.button_tip_ul->setEnabled( false ); ui.button_tip_u->setEnabled( false ); @@ -1237,9 +1313,12 @@ void pupilGuide::modGUISetEnable( bool enableModGUI, bool enableModArrows ) ui.button_tip_d->setEnabled( true ); ui.button_tip_dr->setEnabled( true ); - ui.button_focus_p->setEnabled( true ); - ui.button_focus_scale->setEnabled( true ); - ui.button_focus_m->setEnabled( true ); + if( m_tipmovewhat != MOVE_TTM ) + { + ui.button_focus_p->setEnabled( true ); + ui.button_focus_scale->setEnabled( true ); + ui.button_focus_m->setEnabled( true ); + } } } } @@ -1294,18 +1373,15 @@ void pupilGuide::camlensSetEnabled( bool enabled, { if( whichcl == CAMLENS_BOTH ) { - ui.label_camlens->setEnabled( enabled ); ui.button_camlens_scale->setEnabled( enabled ); } else { - ui.label_camlens->setEnabled( true ); ui.button_camlens_scale->setEnabled( true ); } if( whichcl == CAMLENS_X || whichcl == CAMLENS_BOTH ) { - ui.label_camlensX_fsm->setEnabled( enabled ); ui.camlensX_fsm->setEnabled( enabled ); ui.camlensX_pos->setEnabled( enabled ); ui.button_camlens_l->setEnabled( enabled ); @@ -1314,7 +1390,6 @@ void pupilGuide::camlensSetEnabled( bool enabled, if( whichcl == CAMLENS_Y || whichcl == CAMLENS_BOTH ) { - ui.label_camlensY_fsm->setEnabled( enabled ); ui.camlensY_fsm->setEnabled( enabled ); ui.camlensY_pos->setEnabled( enabled ); ui.button_camlens_u->setEnabled( enabled ); @@ -1322,6 +1397,41 @@ void pupilGuide::camlensSetEnabled( bool enabled, } } +void pupilGuide::camwfs_align_setEnabled( bool enabled ) +{ + ui.label_pupTrackLoop->setEnabled(enabled); + ui.pupTrackLoop_deltaX->setEnabled(enabled); + ui.pupTrackLoop_deltaY->setEnabled(enabled); + ui.pupTrackLoop_slider->setEnabled(enabled); + ui.pupTrackLoop_gain->setEnabled(enabled); +} + +void pupilGuide::twAlign_camwfs_ctrl_setEnabled( bool enabled ) +{ + ui.label_actAlignLoop->setEnabled(enabled); + ui.actAlignLoop_deltaX->setEnabled(enabled); + ui.actAlignLoop_deltaY->setEnabled(enabled); + ui.actAlignLoop_slider->setEnabled(enabled); + ui.actAlignLoop_gain->setEnabled(enabled); +} + +void pupilGuide::twAlign_camwfs_wfs_setEnabled( bool enabled ) +{ + ui.label_actAlignSensor->setEnabled(enabled); + ui.actAlignSensor_slider->setEnabled(enabled); + ui.actAlignSensor_nAverage->setEnabled(enabled); + ui.actAlignSensor_nImages->setEnabled(enabled); + ui.actAlignSensor_pokeAmp->setEnabled(enabled); +} + +void pupilGuide::alignment_buttons_setEnabled( bool enabled ) +{ + ui.label_alignment->setEnabled(enabled); + ui.button_startAlignment->setEnabled(enabled); + ui.button_stopAlignment->setEnabled(enabled); + +} + void pupilGuide::updateGUI() { @@ -1341,6 +1451,22 @@ void pupilGuide::updateGUI() else if( (m_modFsmState != "READY") && (m_modFsmState != "OPERATING") ) { enableModGUI = false; + if( m_tipmovewhat == MOVE_TTM ) + { + enableModArrows = false; + } + } + + //If moving woofer and either woofer or wooferModes aren't ready we disable the arrows + if( m_tipmovewhat == MOVE_WOOF && (m_dmWooferState != "OPERATING" || m_wooferModesState != "READY")) + { + enableModArrows = false; + } + + //If moving telescope and tcsi isn't connected we disable the arrows + if( m_tipmovewhat == MOVE_TEL && (m_tcsiState != "CONNECTED")) + { + enableModArrows = false; } modGUISetEnable( enableModGUI, enableModArrows ); @@ -1528,6 +1654,7 @@ void pupilGuide::updateGUI() if( m_dmncpcState == "READY" || m_dmncpcState == "OPERATING" ) { ui.buttonNCPCTest_set->setEnabled( true ); + if( m_dmncpcTestSet ) { ui.buttonNCPCTest_set->setText( "zero test" ); @@ -1695,7 +1822,6 @@ void pupilGuide::updateGUI() if( ( m_camlensxFsmState == "READY" || m_camlensxFsmState == "OPERATING" ) && ( m_camlensyFsmState == "READY" || m_camlensyFsmState == "OPERATING" ) ) { - camlensSetEnabled( true ); } else if( ( m_camlensxFsmState == "READY" || m_camlensxFsmState == "OPERATING" ) && @@ -1703,16 +1829,21 @@ void pupilGuide::updateGUI() { camlensSetEnabled( true, CAMLENS_X ); camlensSetEnabled( false, CAMLENS_Y ); + ui.camlensY_pos->onDisconnect(); } else if( !( m_camlensxFsmState == "READY" || m_camlensxFsmState == "OPERATING" ) && ( m_camlensyFsmState == "READY" || m_camlensyFsmState == "OPERATING" ) ) { camlensSetEnabled( false, CAMLENS_X ); + ui.camlensX_pos->onDisconnect(); + camlensSetEnabled( true, CAMLENS_Y ); } else { camlensSetEnabled( false ); + ui.camlensX_pos->onDisconnect(); + ui.camlensY_pos->onDisconnect(); } if(m_camlensxFsmState == "SHUTDOWN") @@ -2679,11 +2810,11 @@ void pupilGuide::toggleExpFit( bool st ) if( st ) { - ui.buttonExpFit->setText( "--" ); + ui.buttonExpFit->setIcon( QIcon(":/icons/keyboard_double_arrow_up.png") ); } else { - ui.buttonExpFit->setText( "|" ); + ui.buttonExpFit->setIcon( QIcon(":/icons/keyboard_double_arrow_down.png") ); } } @@ -2726,7 +2857,9 @@ void pupilGuide::on_button_camlens_l_pressed() void pupilGuide::on_button_camlens_d_pressed() { if( m_camlensyFsmState != "READY" ) + { return; + } pcf::IndiProperty ip( pcf::IndiProperty::Number ); @@ -2741,7 +2874,9 @@ void pupilGuide::on_button_camlens_d_pressed() void pupilGuide::on_button_camlens_r_pressed() { if( m_camlensxFsmState != "READY" ) + { return; + } pcf::IndiProperty ip( pcf::IndiProperty::Number ); @@ -2770,16 +2905,63 @@ void pupilGuide::on_button_camlens_scale_pressed() { m_camlensStepSize = 0.005; } - /* else if(((int) (1000*m_camlensStepSize+0.5)) == 5) - { - m_camlensStepSize = 0.001; - }*/ char ss[5]; snprintf( ss, 5, "%0.2f", m_camlensStepSize * 10 ); ui.button_camlens_scale->setText( ss ); } +void pupilGuide::on_button_startAlignment_pressed() +{ + pcf::IndiProperty ip( pcf::IndiProperty::Switch ); + + ip.setDevice( "twAlign-camwfs-wfs" ); + ip.setName( "continuous" ); + ip.add( pcf::IndiElement( "toggle" ) ); + ip["toggle"] = pcf::IndiElement::On; + + sendNewProperty( ip ); + + ip.setDevice( "twAlign-camwfs-ctrl" ); + ip.setName( "loop_state" ); + ip["toggle"] = pcf::IndiElement::On; + + sendNewProperty( ip ); + + + ip.setDevice( "camwfs-align" ); + ip.setName( "loop_state" ); + ip["toggle"] = pcf::IndiElement::On; + + sendNewProperty( ip ); + +} + +void pupilGuide::on_button_stopAlignment_pressed() +{ + pcf::IndiProperty ip( pcf::IndiProperty::Switch ); + + ip.setDevice( "twAlign-camwfs-wfs" ); + ip.setName( "continuous" ); + ip.add( pcf::IndiElement( "toggle" ) ); + ip["toggle"] = pcf::IndiElement::Off; + + sendNewProperty( ip ); + + ip.setDevice( "twAlign-camwfs-ctrl" ); + ip.setName( "loop_state" ); + ip["toggle"] = pcf::IndiElement::Off; + + sendNewProperty( ip ); + + + ip.setDevice( "camwfs-align" ); + ip.setName( "loop_state" ); + ip["toggle"] = pcf::IndiElement::Off; + + sendNewProperty( ip ); +} + } // namespace xqt #include "moc_pupilGuide.cpp" diff --git a/gui/widgets/pupilGuide/pupilGuide.ui b/gui/widgets/pupilGuide/pupilGuide.ui index eab28671a..f3b7a8f9a 100644 --- a/gui/widgets/pupilGuide/pupilGuide.ui +++ b/gui/widgets/pupilGuide/pupilGuide.ui @@ -6,8 +6,8 @@ 0 0 - 2222 - 872 + 2090 + 926 @@ -428,7 +428,8 @@ - :/icons/arrow_up_128.png:/icons/arrow_up_128.png + :/icons/arrow_up_128.png + :/icons/arrow_up_dark_128.png:/icons/arrow_up_128.png
@@ -830,7 +831,7 @@
- + 0 @@ -1240,7 +1241,7 @@ - + 0 @@ -1500,7 +1501,8 @@ - :/icons/arrow_up_128.png:/icons/arrow_up_128.png + :/icons/arrow_up_128.png + :/icons/arrow_up_dark_128.png:/icons/arrow_up_128.png @@ -1815,25 +1817,53 @@
- - - - - - 30 - 30 - - + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + 16777215 + 64 + + + + + 12 + + + + Pupil Positions + + + Qt::AlignCenter + + + + + + + Qt::NoFocus - - | + + Qt::AlignCenter - - + + Qt::NoFocus @@ -1842,8 +1872,8 @@ - - + + Qt::NoFocus @@ -1852,15 +1882,8 @@ - - - - Avg: - - - - - + + Qt::NoFocus @@ -1869,8 +1892,8 @@ - - + + Qt::NoFocus @@ -1879,25 +1902,18 @@ - - - - y + + + + Qt::NoFocus Qt::AlignCenter - - - - UR - - - - - + + Qt::NoFocus @@ -1906,25 +1922,22 @@ - + LR - - + + - x - - - Qt::AlignCenter + LL - - + + Qt::NoFocus @@ -1933,18 +1946,25 @@ - - - - Qt::NoFocus + + + + y Qt::AlignCenter - - + + + + UR + + + + + Qt::NoFocus @@ -1953,7 +1973,14 @@ - + + + + UL + + + + Qt::NoFocus @@ -1963,8 +1990,8 @@ - - + + Qt::NoFocus @@ -1973,10 +2000,10 @@ - - - - Qt::NoFocus + + + + D Qt::AlignCenter @@ -1984,7 +2011,7 @@ - + Qt::NoFocus @@ -1993,7 +2020,14 @@ - + + + + Avg: + + + + Qt::NoFocus @@ -2003,32 +2037,38 @@ - - - - UL + + + + + 30 + 30 + + + + Qt::NoFocus - - - - - LL + + + + + :/icons/keyboard_double_arrow_down.png:/icons/keyboard_double_arrow_down.png - - + + - D + x Qt::AlignCenter - - + + Qt::NoFocus @@ -2037,8 +2077,8 @@ - - + + Qt::NoFocus @@ -2384,7 +2424,8 @@ - :/icons/arrow_up_128.png:/icons/arrow_up_128.png + :/icons/arrow_up_128.png + :/icons/arrow_up_dark_128.png:/icons/arrow_up_128.png @@ -2485,7 +2526,7 @@ - + @@ -2845,6 +2886,65 @@ + + + + + 12 + + + + Alignment + + + Qt::AlignCenter + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + start + + + + + + + stop + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + From 8f3939618c74608e335aaf6005d5ed000803da9f Mon Sep 17 00:00:00 2001 From: Jared Males Date: Sun, 27 Oct 2024 10:14:41 -0700 Subject: [PATCH 24/24] added dark arrows for disabled; alignment FSM tracking; fixed focus bug in statusLineEdit --- gui/resources/icons/arrow_down_dark_128.png | Bin 0 -> 5805 bytes .../icons/arrow_down_left_dark_128.png | Bin 0 -> 6718 bytes .../icons/arrow_down_right_dark_128.png | Bin 0 -> 7067 bytes gui/resources/icons/arrow_left_dark_128.png | Bin 0 -> 5888 bytes gui/resources/icons/arrow_right_dark_128.png | Bin 0 -> 13091 bytes .../icons/arrow_up_left_dark_128.png | Bin 0 -> 6217 bytes .../icons/arrow_up_right_dark_128.png | Bin 0 -> 7066 bytes gui/resources/magaox.qrc | 7 + gui/widgets/pupilGuide/pupilGuide.hpp | 194 ++++++++++++++---- gui/widgets/pupilGuide/pupilGuide.ui | 51 +++-- gui/widgets/xWidgets/statusEntry.hpp | 82 ++++---- gui/widgets/xWidgets/statusLineEdit.hpp | 105 ++++++---- 12 files changed, 299 insertions(+), 140 deletions(-) create mode 100644 gui/resources/icons/arrow_down_dark_128.png create mode 100644 gui/resources/icons/arrow_down_left_dark_128.png create mode 100644 gui/resources/icons/arrow_down_right_dark_128.png create mode 100644 gui/resources/icons/arrow_left_dark_128.png create mode 100644 gui/resources/icons/arrow_right_dark_128.png create mode 100644 gui/resources/icons/arrow_up_left_dark_128.png create mode 100644 gui/resources/icons/arrow_up_right_dark_128.png diff --git a/gui/resources/icons/arrow_down_dark_128.png b/gui/resources/icons/arrow_down_dark_128.png new file mode 100644 index 0000000000000000000000000000000000000000..e23e260153e14424d8a0c5faaf3482f4e03b071e GIT binary patch literal 5805 zcmeHLd05Q(AD=E=N{1sWnI@JnGvB!nU239PMt6#~d}ro688wGFYC6y^sZg@fMLG5% zqFNFvwB(k`v853WYLZd$4@KJzjkpi~-jwC-^$Jb;kGwDtzE5v{WV$2qO@*B3g=|5tUGYLaCZk zyqB9+p~nuikDur2alV6o{P->LFOO=s*A=CId&5H5>9Xp_dm**Wj!b&V?KIh3g2f(p zs5!~SSI+w%{O#4_B7A*X zZ9vJpJx?c3avh&swg1(ApNiBgKUq_M;-{tJQqEcCSxkI*ddsEQ{qn5cC1rwF zI)lO2&uG;eMKb@?jtWMhv^EIc+`QOsZlCf7+3s4i&C#RE#rk5XuRC^!X{4Dl$t$;W zA11Zb$o-(%s)T^4i*fIN{MLlMdGpT?mq}mnjy`+XdgSo>!)SxG@$`9g`*M%u!9_+` zt^>XMaz*Ucim3RyS)?1!HfiOAP<)e5WnC@W8XUOBNh^~+K2#?nt=;&z;^#ud8=VM&g0z`<;BOe8ofllyvfwt zhoW1dqk&IW>|Y;r^G;HJvR%Oe-?M3}gC3v07&NCLup{qX!ns{%k5wyk>^xSOFG@qZ z&NrE{-P?V8K<;>B`=+h2{fX97A2cs}bBIl|x6&^UjTqpK zebT6xqrCUQ=|tBbh7Z?`DSCCH@)k7?MHgoLi$uuk}%0&p73>_PO_G)7&j2U z7=#h<;5;0CjXa^Zz!1Q4)_y_^s95E{u3MmthkBW-IMUik4 zSs0$cU@-6y5luU(4@oX;gJYL1We^%RKlns7qU5C!yal1!h|BJ#tV==%2FW|d?ssDY-)`r zosoe6_hH;o)}M0M7y~N~hsl!gl80dpZL6~dC}6grknr3kPvBp_f3bQqzN7!ZXo zplPDv^Oy@HG7${QDHOqB2wo}<(;hJe-MW4nHm3;&`O2t*nYA%XTG(g*}BnZzSw=~P&NrIJA>zydBqK;n%?mrDeS zC|HKf4+A^`u0VTgxI)j;6v}?Ib<|2kT?IfGmH=Ui1U~|a2~n94<0E1Ce?LV!LZ%S- zbQ%_>lNnetgUH3wX#^q`^e2Hpr*e5<=8O*de@bz};;URnRe<72!1iz5K&uY-IMzhCM4O4k=L@I}U7yXz}mU&O!{ z8Gr4r{~KLKpLdLi7<}kOf&HLArHc;sl4H1w7P3%->ffF-`RPDnDD?=EgAM2f^{KUE zj_DL2)K{=M?)p!Rri`(H%@Y!*c==ee{r2{ zw)dl*i|!zkirN=o)L>AHn^@ zX#ahAO<(Wbmk-)#y}#A}jq5+E?uspX=moLUvfhfarcRyeSW;55 z-ZbnY&L%zlfv;16u&LKVaLm}Fz`BIP z;pn4X_PSZ}5?R?{x1YY!G27!3jB9A$XYjC~Xsx#Pc&37B{UFIJZXoX^t+bpkYfzJA)kEVMi}FEemLi1zm(<>3blN^f_r?r!c_R{r*IWn$)OnVdoY zCdIVJEG*&n+D-XSH%-y9;vL%PHf}d5cGuCsP9sn4Sq^&F=U&??NX1Lq#<=aRI~n|V z`^l=qIXOAgI!(hWCi9FtdcpN@mi7trl8MfeHmAph{lP|Nh8=UWlXiA5+57V4OWRg6 zoWw}U%$=5PpQo7pW;xm{D-kt=8xhf2klor7a|Umb4~6LT#hjVBG@!&zke#8rVRy1t zue!Rrzq)5!lPZC}u|wZ&yzziEpI4`RkI}trTVGFWd2sc^&TppF5HDFcw5OT3tIo6- z&pF&UwJf;0_dfoDfeWiGvLcFay5vG8J`E+s$2W^Tox6Kl?3I z;{vMr#5wrPf?7W2L-VwoEA1Ab(jf{(IRlU#Qt-jSrgpN0E?lqwLgi4LQBd5{(h}|c z@)D~t?b3mT)bDP3a!NZ=dU|^Bw(*8Sq43T0?C&a5+?);bQ5X#8c1vT;pVyB(6IzV@ zz23lQ!u8AdPVHW8sGVh07qfhVN$`t1g(>b>~G}TN`5V>twlHZs+em zPE?k=UcWhvy<$Vi9J+)bdUw^7%`|ZwT9)d!jaCC~xmjqqeV+4_`d&B)hXS<25*sgo~jFTc8mp(I(PkM4_=GOZSZ(SRIo50CvT}06~GcRlIb{17c zHZ=F13Os6UoZyK*RBda0SMi!mLPjQ#aI{#g z!otGc&8L+E$E)Y9y_Je$u`DeuCGQ*BvlXk-rn8u!VLJl+-!zbPud?3NoIme6O*d`B z3aH<|m$%jCK+5aqeZTqjDU`}GL$E*%9~&M|lg0(;oDVF&rIxYXm#~UlSN!-N6Sjig literal 0 HcmV?d00001 diff --git a/gui/resources/icons/arrow_down_left_dark_128.png b/gui/resources/icons/arrow_down_left_dark_128.png new file mode 100644 index 0000000000000000000000000000000000000000..a453b457805ec542d8f8ff3ac5cb5ee4b4fcb7e7 GIT binary patch literal 6718 zcmeHKXH-*J*G_YX1(wH^JXQvcc14xXYXh4v)4Uw zF3t{1l~*Z4AdsaLM>|*WUn2b~%7eevmb51DZ#3N9OXx}y!FYTwixULEg!^~^3=nfz z5QzA3;`W`Y)i9N}gBqJQJG#o$Wg|KG&T+O=KnLX*D-OFCW~LidIJkE0(k#LdlaP8` z@qW(1jYqexnOweZc=@sfwOQ&icC@Zi#RCql13y%Mc5*;rpwntqqMiry;f@P!({lyQ zy(yETbt2f+g>(1Nkj_j={J?nn0r=Y|{=unXsADZEcCA%9Gxu>uV%JHZZ#Z$rX%J<_7Tg_D zcvt2jmTlRx*DADO`Vs^J{f=X6>q4=${TMhHZdT+Gl4G^CcCDY=mRxsYr%kJ_ZP>NL z@#gItG_p5e(DVsIl}##rXg z?=RIEdqsNH3*CIV5nF_W2HXIct`zhMKh4-eMVj35LyGlx@|!8Ht4=+AvDUJpw{~CJ zOqo@k#0T|lzj~Z{eu!7i>KfBbkCT&@p~q8!)Y&ZYuV^<1WgvrP2Lu6J6pF*mJm za=QBJN_s4ze>7L6_D*;BRJ}ADzFV+jlMKA8sy58i?X{$7jsMU^lhxPO&2f}#;lCfS z?>nv_&yBvH(Y2GUbAFk1+6|{Zh{6w5;<#%aq~4ysuC7Wpaef{Wk;K1rXyow^5Qyqd z4p@j@)U8AYH`s*633PN;r(eB*8t+s3VXu~cu2Gf3K<-X{CtK$NZt#Qd~oP*X9(QE{fu-41l%w_10e4OLWJu+ zr(iNZ&F6*jgBHVKGLS$J5DY>E;Hu~^mUN&{T|Ui_O2Fm>^A=};Vt;`Ya#(+g^@VTJ zk;QO6cLbdNiT4Zi$JiIaAc{&Q+Ho0SQuio!B)D{aB9qJDFo}z|1SY{0ivs8f9EN3% zz?$O;2)Zc~jW9K3;8`pT0f)u`pHWdl1VUN}1CUaIrh)0?1k>06k{7~W9FPi5v~i)3;20CspB9%Onvexf zAi=kCLc+v<4!CoI0XHE{swNt5ib7#c(O4A96b(B6C&&Zf3&2X0a-vZtrntosXY<{bLYkaVx=K zi<^Q-W4sSRK-&wvPZr4aeuxo33th~WslXljB@%oVUe{ltn`s*V9 zNZ+q=eUnUce+2$oUH>z=l>a<20wLgwo(Mb-7PW4Zo+ah!TO8~l z3)0V-^7F?)ixSV#TL2zFYouRj>PFSopix0cp^_DblvgiqNP}-|D5v$#|%#DVC>v z_Y+L9ZE0=XdCD%UnDc(|N~#Aom0ay|KGsTooE|ZBU47e&cFIF+VS5M$ozxZT$Xv@u z!(KL04Ak)+YHQ;dkFU$C$%U6eiGl;mTdC|n&*Kf5q5 z%F1bc@bF8+#iuxszu|RFq7|E*<8%*|KL3_C_^ys18 zg;C56xJco}7kUD_@8lc@j-6H=i|Df#aVBF z2N^hBwv;{(;buVdhvhDv0cy^s5#ajPHn#ObP-Wutd4SVf$3kh1XBb z3zld@)SWyFg3fSmaa~3|=|!)m#TH1tbA^z(wD0XNM>-m({h`u!V1vHri|O!f`g=%5 z&@ELSuGeI9XE$ycO^nmf(e_u;(9~SRByT)rSL|2ev!kP}EezB0B1YEOKBD{`#AzH+ z``owT8xR;Ocy}*7{n1L7Q8w<|pHCA6&&3b!X<9!xXcnPTZFz7{rOcJQit_ULT;?mN z5~^=|^OI6P39ofy@rjpQ4u_ETGV+Yv9oZ`$Z~bq0O$glIt}pxL@u^d%+>Bnw81Pi% z5otX}wMY=`pl@kjrLC24dw#R-WFXV|Y(t@y=vBAU@fk%`p1N|_jj=NteF68m4hRr; zckqw5ULI4JYZwM@lz+3Ql3H6HBimi|{eJu!oAnhwx%pdCXZs;|%Q<=5HBCR&2X*eI z2UWdl6{ndM)ky@NZQhwci zO`O=`)CpevMs6M?*LCjU!Ci%TE!F110&`)AtIUo7(< z@y7DjsZ`^1gJyAfJl^UDMo`=k6obj_o!f=C#68ddqjAHugN|zV)X9Cm+qXv=Y1zGA zb)vkcy|cIXfObbG{WK&uH`niUdV27WW7AKcGBk~w4&}5244yb;m%8V)m$6Oz?-!4E zv$ARpbL5QLGDu72*IeBCZYYs@*5^v^y41#$yFF?2$&kX1x5}@^YkQ$u-_KRkqfP+d zhGJKZ8r>gWurp$de0m)vTRpP z8QS*tD7nHX%+J%)Q=M$&MU+%OxuCBrwvRoa&@jMAhm5_MpBhv@W*E9Gt0AD1;#2Kl zrv$t8rfmb@D-z96;uZV{A>olNv8DKkh~+v>0!Vbq_!EnflcfExXEc(l8lhRKsUpUH z6WaRTEh85k5@eZ7r^0@%b23+0TXyd3LdXA5H6!!baswy1M`LNZWMjf9hO= zdSjcqZvLVp8@hTS&%n?}UO@pr(evad9^`P_o;n07N0YO<;_88?MG@N|#u-)l`T3Dp zM5+4E{Rzp*J5UKJeMz zEa&s_*CnCaGwO~KIW!s_x{?Du)=;$e%9YE5caQL#&OuI=avm4H;&Em(J54Do~bo|9(HkH@iMhHrg70TtbE&Y22+pKb#$Ki}9lUim9!P zan7X9&-R^d^vpNN`L{Ba5_kpKv5yc~K$L8imYQD8D zT(2EFfQ2Azzab&uh~w-J1Z8qj-`Ij=N{{8jogHtxT%4Zn3Xe@K+3X%QH}RXg26?+} zN5Oc`ce*0TgQNq$@gIp|Z{2TsSFsyPeHa?ghK)i?LVChCDcQ6H6rY5rd0XA@bEuqt zp1DnBYNjPZL#IrZr!ArwG;gRj(|YvCdy~nVh`PBAd!5wJ+_>ShX=0ciRgHjT_s>3+ zkG(ZIITz82k@HqJx3Gv%KvWGPgxQkb)~>F%MDq65`g+CUT{h1ldy3ywCv3fl-ht1^ z%$#WsT$p{P8*P1m?{AH%Hp0PEN6enEKoJM!t~88A1;)cjjtob*&! z$hbaDHJI!a2JsKqJ>|UJR-|-k;2FdzcLLmcyHC}dRr*X9H#dt!mIkQ}-BD%2i_4fb zSg2a$%Z(b!^F-e#w@TVQkd7y`j)rTzG}N>YJ&p;4vC63ZRRGFY% z#VYP@>F(~9#Vj9z9L^pnnV@P+k0JdfvvP*kR4TP6qTpuvCE_a8|3u|Ko6we>j}*GO zJ$!+>Iq9!*yy>^7%C-du_!E(@Nyn|HmHXdWBycT8p;({b^Ipc@la;G)i<~f~3sd*H zxKT1s{Nx8AqC(%DE0hj4YLu0c5Fs;l-|+wXCh#{FN63N9{jTrz`+a}k>zezTN%ivB z@RO{DECPY}$=S)?8$KtBKS*i#*klRbgio&$eEfOdU>v}SW;0pg5WtJ)Kmf#NF%bxU z-;s?$@=d_<*%1{pTPJUzwHU`TeK0X%8`|rf#Y`o|0>-HD@{!f6WvV$H`ne2!rJ~Xs zE1ZkdueCV!(VFyg)iOov1sXN=HXBw83f3H?e+ngK`e(TN75ny%)L8Dc!wwyJ zl+-*Q5;&J=svNtaZ{~4&X3nmfzUv)Y&jJndy0U4$_E0-Teez$Y)u)0LPEAoY-NzdC zH@5m7&>hs4MIAal=AB;Rt)P{$P9|JiAGjxr?veK7yZ9$^M~_UqjNq+8xVK-(%wO~6 zFX>i~b+|mcu?m5ZNMYI8c{$tJeMuZn_r&fD3#TS)&6aIJCEf;F{|0(cPBE2fhsZlt z9P&bS%U+-!5B{*!T_aOv<%Y&8k*Jk+zp*92PsYzi@gpKCmgCLKQ2vyw64=b=JUSXT zy*h3jvG;Pj&*czRFXNlPpU$+!{$?PxP04n-(qTY{u<7K_EhO{SUW;A3>RewNj&t{> z?;XnL^B6eF0jjLObgxBvYK{-Yu}Wvl2du`@@wZJ^cN!x|57nMY;& z>&0Ap)N(%jpUs<^qa5z*4V~l$4A-^4*|v#&pBl#_Z$EyTQlR1?S%(wO5oD#}l6;$l zza5RJiIJ2lOj>{8Nx5-Sp69()T9`dj_QIsJ(R7`0iCnV=Q5IG`bM4a54`~jfxx@AP z3d5;PQ8S@e9|RlsC;K_O?l1Ly?3w7&Pr6fME^^@^-MbgAs@to zh3N0@My0bOupom?gRuMv4y;fF!rY3_0qJ2751>IItVj#=c+GEUfW@#t`x(3A-8ptp zD9b4!8rqcL;X_Xdqf;1YD@$2(J{1OtfOsIlj|h+CQu!9>1zak8EjHuOz=8`e%mVH2 z?giMfqalEVC1LRx2Ry7t&$SaZorE0lRYHQ3-z;a)YzG*Vi6m3PM;BoP}O6*?;lmv6z37^_SSh zEeq*<8wlL}EAC&szvRB)412k|Q|;OG7;$*c_7-UI_*4d)&SFp(F3Ds(kw^fU7-JJW z14E*NAco8&nqr7#I^CE=B;siV#y3#Tkz5`aNr%KxFgTV4<1mPHvN6OUU`R{?1w+Eq zX&5qrNx_iGAce+Yk|}gL^BV}yXcnwWF#Ox7#83<|6op1MWzfkOBRT<&1~R2%$V3VS zLnoS=5-7%GvN4Ua0L7qF9of+lAY4vX1Q-J0IFTU>4PwHnHeSvaXd)K>r^PEA&|O>> zDx3^VEGX6~46tB_bD`QrLm-bG?Zak=TcE`dfVk(^W_NfxF+d(@5Aq-w6i*~k33w{e z)CW(d8j+|*6b#;!ivPx+&0sO(|2J>(_C<$p)=`+6MH{?6!^=JH>w5p0GnnMR^YvM7f9DVY z@MDng;`aw#Kj``{2ENPrhq`{y^<4~nm-7#G{lC#A`{#}kii98Z;^6(@?uKFpyqA=w zxo)sWd=kHl>dLZU%QB8r02khXHj6(JIqT(D!A2RLv%7=L3)xi)X#EwYGzr+G&U5hR z*|8(U8xO?7^Dx8!;#j;;K>R%Hmn6Rufsp;#+1|#7-}g$u^4b)jnmFEMm~w2tgFQ!I zBS6ZTFNrSl@*3Ct*Yq`3ofo~&m=~)&u}-9LpKIdtFr$0p`|&p< zQd3iNG>#mQd8XDRc}#m|OZnij`O?`3V<%qV>ixSCUW;t7*^K3~fNI)h8R;XdhGK8w zZ)9Drtb7?m6(HJ)2c!);J5MJkuk7sX*Twc&J!>DIZi?NuPr}Z_ zjT0hA=1EF_)Z^x5#~M=cCo1mVCFEhYQE2CPx*rLKp1ry*6bffhDAa%#Ha`xLseRdv z>3Vi;>(hiu+jYuq1DGJ8wQkX6L`FtNWs=Pkoe*t(#RT^Y?9hbM-e+oy86*{JL)DOg zU&2qC8FgO73hq`yH_zS`nCYfecDf;w0ooa-o~%}d8Nc|FF_`4n`e=ca9u~WG`>INV zGfvem@xSC07H$pl^Ba+Sb}ALIsmw#GXGfJBGG&EIOtSjUcVoS!B_%exMO|1xS9gRS zXOgD8tgnCdaF`p zihnyx*VA%1K6?EbK0>m%_YHVBZl$WKt!_~o0*UJG=y;tG@q3_0%Rc;zw|W@Nh37pN zg7$cM=OYspZ38dFqSD%m7*vs5ip}1^x(zEeRMU&klavss6l`$y>-8pS&H=iwrwY0+ z_!!I;Um+`H$k*GX3X+a`Z z5=imdvSk3>f2=CyEMHxHsC#5&WSAalm+=WrmkC_^0Wg9p_q zw`ud%n`_lk#UJk7yJxLu>MjK!CC}Y|>A5V0y-}&W?p3j9*PsK2Cz+3Yo!`^bb2mlO za$Q)m!80urTV&g_Nqw)_h2*NLs$3^3UTJKe@DNy@y3^hs{eYK9(9u?IE1Q5{K%(GE zRnR$S~9!9igmim!=SIctDn5RG<$z+n?dIC`4!wbcP}=d#Ol9(V7smU&t$CQ9 zEAX9y;&xt8^Xb%j%WOB9&FyAmNEGks?-_rv^QP){>=-TlZS**c#nMLNT~uUSTvW4A zrwj%yVz{n*_U!5SG+58-Dm{kT#@6ce>@rln>8RKs5lYIxUl@FJy-!SX-RwK7L+Ltl zTZe?4;a{P3Rv)K^om%r7w(HOj>n0-Pi!NOvwDr5{l^F~cb-oX}7QDK9?dM^oq`(H*68y{&iq_ z$|=)aO4949!z27Ue4=kyvdt;h)E`}C6ae91zPEE?#XxlX&6{$P5_*8XK1)Yy>gCIq zAEc!?L|xCq3|$oLzPo+sxXh}w^W9FCW)&KTW4&<4#2cr}lwC}SbA}GZNKR zn!}0A$r-H9l3}3+-4G$+m}*;GJ@@91t}7p|YoHm9oU=AV{lf;=;K}=MgoNhrZ%2E% zW@ctf9vVI;tznm2{jqcBffpyrBh*69Z>jmmGD)&pRp1Z^tMjoY(3 zje83V3!ULo>%(F*9_lqrc+h8?vj2eg^tAe6UVC{>%`6^it<=)eveJx7HQ%+ncElg^ zyyaTRyywE@%TxOj z+ved__pR5*WQAFQQdmc5rgu~-1+FA4vitC&Kl0G%VJ#)zi12ciO@?g=xGnT8F$Ir&a0&)f{&M$>U5R3<{A{5#}ikf zQkH)h99SEFiq#R?hm<_5v|1=s6bJ;f?^P#Ay zNV804sl*GJ8^@2ilw=3H9g^@gorAwj)~4L@X-+n7Aj?Q0BoK=5zeeAC;IQVG7^{{W VzgiLr!q1QhX9o}ai?-X7{|fI1xO;GNLW%0YYK=yV3JHAkc}jSfJhO=f(sN^ z7MCgr6+zssU=c)#f*u!&3vQGuS^x5Vvzqi;b?{od`?f|i*A+br%-R}org+4E{n_1CZ1C(qq| z^c25OZ)CZ{X`Smu%0;E=uloT&XN|za!=LHl@iuTQ+#M@(Tz%>mTAz;y^0eP-qBNZ{ zA#`WwUR>63BhMfFW730XEWr<@eQC^Gx4y77O!|U*_-Sif*@4vu!0{=m)cI8VN}tS; z#YPavh5AfgwIaJJA@%AHaC7H6ol^eP-x$j;wFjTy6*3N9W9kLZB?j$Yyl>MB>xfq` zy8H1BM^9fFq77_0eG%C0W6iBZ%p|5)gkki@E8AcPrcpPodyV_&wkZ!QJA0---dm@8 zWzzJ#K9{)M(0R&3cWcXdKb&hiXXe>FC*ne7ne={JS#V5Qyx;KI$na%L+v%4P+d~<% zi@-%*#wa^-=2r*2)@4$<)UK~rXD#r==PgHJ*}U(KrfmAvaAfs^d->`6na=iBhLsV* zLGGj{xApVm?+m-0=xU$P`i;TCV<*nE0Q?2aij&7Ln3=X1;1Ax(KW(`D8KCD^$@9s2 zSYmHsR5LhrWsu2}Gy1x*VoCYR9d5wXr*jkatgUr_^=t@#rAm-QNk(=F`d{gtb&}OL zJ+X5D0Fz|`tPn$4OXysQ2#@e292Bn-NwEqA0G9r?v zH5P)$eP=I?mkG7u@VEq2h>9>(IkqbCgC)J0EdO^F8VaHWBB|C2Bl`nQg@FH_tPgzC z%xJ?I>j-B44)+7?x3O!LF)bF0&X929HSRGPt~ky5be@DO;L)|Wd=ibrhe;fW${`{U z1>ut+gzH3t98nUL>ICx~ort_KP)xC0frz=N1_}em3osm*gwnW9d>(|5IUI<>L7X6( z6VVwW@etGrrD8%3aSVi?On_A-A{^_L28xG4(KsX;5p_Z!KA*;eC`1YjAtW9bqQVHx z3FX5?9*Lxd;&JI-5}63W(kT!jQ7Azwj?zwO2&cRIGhJ~cJp5kbFGLi4%)k}5L?Dh= zy`NwUL}-u#(XdH$Cc`j=3_B8GDix+VzgG%IWpb<%HJC&gPj=GIXwpK*g29MIGXI6+(*;^;_$DKsLF zqGjP7x?I9nBp@=>JqqIy;|eQJEmzId}lt=V6owCI}SK zpyqivWR=P10HCj8GThm!mae-3p+&rvx;yHnTM{?0=*TT-{`@<2x_3ZP(OUKdckmpJ zXkKJ7D>Ku4)=O}2HLPQ9%vkvIrebT)x|xeIW`MX7qkG?f!b_TC;wGw=FRN4t z+yl48vgh_2s&;V41ClAc1Cdow=8)xSHEA69K$yZRzj4gmjLA8p-@yem^M&qbTumqK ztgW=tty!j@m=x19$;@oqNNaw`N<WXjS*ZkKE$Xy%}3_@{Z4N;5-}`dIqU$46apX zX82S%N0R3OrsE3cTdq$jW$({EC9XPT91Oe&cF*!U>%IBN>tliY+}1k6J(K*y!^029 zHMPg#a2tbPIn`gOnQ%yXkA8XQwSd}={*)Dx?i>FZQAC9rVd#<;1tPT%y z@aA@B$6X-FCbpKRS-%);QG2Q9UcXL$;^jTRxKTIt`t|FgJ<^Ar5o&?HR|5dJoAw#3 zMpkx{8wvNHMAum?O*B3&>k8X;kr(6JV9{ro7V73;w-5;kSS3lS{AK9X%j!LKH;)N* zS`&wTTz1_mbhaWwH^e%Nx6Mo3Nn$fMreGjwOuk85s_9=eAg^w>uaq+^_=}DLZ-cRcVm$wtzU>v0?Y#X+ba;pu7AB2U4B{LN4ZI3>)T>prb9vGioZCq=gY3-Y8XswQm+uqop zj``To(7dlPVZoKj~?yK$JQK}{3>=+=I{Dt>xclktK|gLE<1I?(z0cjk-pxF!z4_zZ|G6u zESv1dYyA3f~b0$FZ+y~dGbkeU&_l*#OQb}RRZvg)R} zS$VSZYv&smO;gXT+zn>lz1;*g9+4mEr8?-ScPX1ldoi z>OvjVBVG9&H!IXSpngY3$KXK0ji!kW4V~?G(J;W{upZbVt$^+!(l RA*@jYOiy3N!9|g2{{)_}ti1pL literal 0 HcmV?d00001 diff --git a/gui/resources/icons/arrow_right_dark_128.png b/gui/resources/icons/arrow_right_dark_128.png new file mode 100644 index 0000000000000000000000000000000000000000..d6d4aee761637c227b847ea30f0a5a88acd8ed63 GIT binary patch literal 13091 zcmeHu2UL?;w{{Q}M??h_Q4}y%kN|;@&;lqRG8#m|p$Qn00Fe%%h7x5|5D_dCrP>gw z(vgl*R74a6q$9ltq)NT#1jljich|aW*8RWruXXR}VoA<>-hK9d_OqX}&jJ0lwKTXk z?%IezAhjaquzI`{Z!luu0`h!FGVk4HyDx-zb41c&f{GpzFR!Mt@9mfN{W9T5Y>50BQ-#oM{kA4P&4Uu_QJ#8 z`ezRn=L`3*92-;V^1OH7r}Nm$u@e?vx%-aD;g4H!;P-WC97wa_yR#-l*f8{NdZc9tdR9eKqY!*hj!#2WvqESfc`61wffiQ5`Pm0ijF>xy~!ItxyHsnQs& zTFj52YY25kq`efl$LI1mm^&u`fnfWcs;a83sjB)%=pf)ouUq&NuT*xIo9d{Gglu*h zw|cD|mE?O}wn22;gJaLO8#+tAnBu&T*)Jk~^RiWGX;68BZ$L)M=9J6Ab8KBBosS2Q z2bLv7GW{kxbA^~=__21jV~<|yW*k``f1mQ0*8v@2w4H9kT_SmmzwGz2Q(odBzrJ+x zY&0?4C%68-rKX3yvygPzNJt{a+>R7b)v6>t1ghJa=n2y~-{! zU^Azpv^BYQvW#e!_PNxNBjff1p3}S<+s-}m+&i59(mf!<@L5^|{u`&SyA9>uFh(P| z1Q{B9dBaYbyJs$4Ih?#p+JRnYzg`zFP~ z+k541$HZwLMlda=2y(G2d>fKp6lTph%p=J0i9KBQ_8V?&7ooRxw-rVeF45!aJGOk> z<@hdGy{!U)*la`vRMaP&k|){Oh!e?nW)yKZ8+*V}1VT~S&7MfIqR@oRC>B&(Jd&AT zj1;Dl@kl)xf+WFSm10Rf;o(Tp@zByGd03I;$Vg?Sjf!saz<>>fMih3lv9@)Rcf%uD zcICnMa99E<%$h>8!Xxzw+QO=Kjuc^xI7VC&rS3*`kwPkM6jpR3o6Db7JO14S_=HDV z(rEVb5)!ViuHvrJ;&zS}5@3-&NMs{37!l8;h&8?f$+n;t4J)uI7@M|b9N+A)LkgHw0%FDAd`N)Z}04A%?gK1lAu^qY`|0}uqyg5OKNBm zw12z-A+Vs@*t6aOVE<(%jcWcUSby;iK4FFPvm@a3A9nvT`;XXJlff(kL0-*{gyEDnVsVX!FhjWkM93QfV0C=?8dBJ-0eOsaYU}Lw=L21;4Mm4WglM91(vp%G zDI8W7gT-MaSHou6`;Fr01egeIq9w(pv8>l&TI4}609YdADKNkq2eHVjI#P%{&-9Ph+d|FG*H zxc(Lbe{1qT?D~HO*Tz3jj1*hY=(&RPU=$Zm2RKWvH#@1JhFF1rV+)_&0VBWIpD=I& z2hcM3#TIg8vj7<6plK4+IR-WgY}vIztMvV2Ftn4Vu1{07vw;T>1gjsWkcC~TG)rOF z59?jpyaRy{Mrf)X)pctgZKH?RI~NX2)SOZ;LSZ8ZL$#UlN!={wR`jHbd6KnRWcDOi31(QK1Gw$ zIK$~#Me|OEemdE|QJNu|9mb7#u7D5i=ZJEAE8_k@|Kjuoe?R@gKL5kpPJVlRYu{vq zU6CBlfict_C4z8CJeKw;ZtutRWI6Mi=si2m+h1ywMSNU?SSd_)_a2Hp+g39>)#%{! z;sNbMsEo&Pgc>Jek%Lrm%vgxq#UIQh|WTj5e|z)Sv6G z$dRr#R25BOWcSy-LRiYw?-JwY=Ka-KBFcMyP|0BvL^&_|;$e*k`fsmo+Id^TF!MwS z0%T6~O}(CJn{AQ5kIiIgZqG^6o9%`4{yT?Gb4wr|u4DWn<-+}2Y>!4KQ`RRd=kFFK&0IMMehnkb=YKtxHRiB>eOy&+e+@-?? zC>8v8L1>P!EmYh}Y4Gu#^8)N}EXBEIaqq_Rvq~3A7>oC0TP1O9CA? zR5#1*mjLl(E5?vT;iKDi$qQ`U-00`JIpeKPHPzj`G0$h$fP@JXRyyK2dxH(GR#aeW##O^n>FF`dn0tzlkRwR~>(<4GL0mstr&N4fci|2 zVPHl*mjdU)>`eI%d5zpH0JH!?aq}5O@WlJPr;W$e${1(cWGrI5Tm&s5KYrAOY1>aN z_uZoY#s83zmg0n3V+9<0JRDSm7XrDG;0yS6PS5zj1=grYkXVsdQ*Zu^Np|nI{j0!6 z;$}_OhYs;+-IF>1z|t~h%^Z9Xl88ih{m!ekReaUqMb2T@(ZciYy&>Oo_w{wxSEeT} zF49X2g3za^T({~^{{s#^HMKJIle~ySg!?@`>)aY=&}$GET#cs3_dxuIr*W3t6Ae{>D+Du1{nmgV}q`!YHb zl9Q{87uuNeUaSWLI1xINSI=|hEucP7!?&hYlR@Dd0Vx<{E|K~+1&1!RLlPi6fY>dS zfa;M{yb48?Fg? zyLmTJ!u)rDdO=W!KBVa^b|xf(OcdPiS0${24y0cV8xmBSd?y`M08@3MaY*L08VE$= z2LG)N&&ldP-2D1BapIeVCwjBO$n(Y8lM>rkqx$qL&S`P3dDsQm4DVOhVfmHRebTvC z`n~L{H=Ga&TC#iB8z>FWiLbs2*cF^9VXah`D1a;9(QmrjYhk9kza~b)1jhLIS=?li z!>d5tXfxeisb&jqJM{gH`~%$_AVCgVtCNP`bl|tc$mMC4MQ#&j-y@GOY1zF)B6t7% z)Zm?(a5V9_)q|rN}3W zEI%T@TTHcS=Lz#1tooR!m+JYoN5p;8&f3z|WLOk0<(EMLe(qj16BOm?=&cd$ie|a1 zX_!AV7_O7hLK}MaG!MHTrp36oA`XJkS?W7EoLX%19fZ*2>WSV|PZ^Jyk$XPlszT|r zYgkEKa2?zwfGyy^0u(w(04E;gXixxobfWG~FFJ%o|SOl?1pWYBRIkjezuq9S;)3e+AS_t(lCDy9}}{EN7hW9OUP>C2YtfT;BPj zU`}i8M_mZ?{=sDqZ{90l=d7w!nn5>Kz`@5>qjke@pJ89W>2+%1j3JvZG(teNxRy1F zFXa{P08Bzq=~eAj>O1PgH-Z2d``cDZ>>fU+8BA&(it1_Rhhwy4dfyhHAKp`sgnr>? zy>qdtXkXDpwVgVk9IQ}O&7pg&_sLvh^{7bb8>!MoitFs1bD#8##9jT)Qm;Mb62@OK zdn3ae&m$z8WViS=toYrjH6OofwK<-w6wENsni`{rTW|>cS9iP?@3m_`8X77MHP{G{PU3p)Af3E(!I8~K!p%YgW`P`No{pj-TscRK4}@u zka&**Mh7R|+IO|`bhKwWNpU`2=-efUo$-u`CCUZl^E0Zwl`gU>w7u09?J|b|;FvA-@~pes!%}^@yIj4ykDxy)54N3W2b6+LC;JJJ>?Mz1AoY31r!oNLtYW zyH0`j;T}B`_a}@m#XTPUpn&+%j=G9do!9k^ZTUOoszSpzz>JW&6l^WU3^QN9=Y$_K zrxi0bl2+>0pIjIXj{+3BoxOZo0Ev8Bqx4L3lw}t2u%Anc4T!0yahA;9U0L(l;#h>|Bjq4D*z|#%qEgoty$}S&i${>L@ zaK=O}00QhaV=^NKJ?~`lnF$Ot#0m= zHZLo1pByP<@l0iY427E-j-u3rs|`B=uMvi&zdXrv7FwCBEPNvlI3a9&TJc-{55=_2 zJzA2<1J}HOqqgTAICv_Yzhk}uHwx?lL5L{~bFG|~1a#PU=z!Nkk8EpsDz3BT!>UW^2(E{`;b4uNl^;fdTk^g=z#jn;D<9{ zGJ-0AwRSt_#R!4f6rCKZ2s}6K2G@qV%gB~-|JsxA0{PpSkLeTjdW)lA!5m_5!nMS{ zG+o_H+ORjH*b8LbC8TQ4s>8mUJx$e~WvW8kn)lJ9_M%_ z@T{Cl6lAJ{hETn-_j4L`Fj&mWIw;5#qW*GB3^$cfojzTap49ffL<^YPPaY1fMtgpK zZh2A60<>;P*s6w{*?V(SfVU@9!j@(Oq$s`(DVm=lMlG_;jpo@si7eDDzg3;(7$*H*C-6(vMSl3&5- zGcOYaOaoKe@+wo`aus^aH;E>*B))({CQ80SJtkrY;L7X!yQ=P8pnAdeI*sG;4^3O$ z`=e5Pve;rEuFR4N((y_e4I$$?jD=PJl~t^ly+ZI+5RgTjyz|J`mEnw-wAA!#O|V{8 zdd9cx=5uXx4)Y38W7X732g^itbyNhOM7#Me$dTLWajlXs4p#Bq`yKKWQ^eg)PYsv0 z(28_zcQ;T|BlKbQ6Ch?EQl>`h6hb9TQ?y0>V12|I^W!g)G1H?u`}9SFhJifkCVOjq zssLw$3f|tU&!W;tDi0!IR)3*WxWQe4|6tuy3vTYHkwjgL0>Dm}YeDqft_R0Kik}F` znYm#`i%m63&qhH}iA8cLnrkN+Eak?evTUFXdK{L&^;f>TC%xnu;xZYjw-wqL)k}@O zR^c_<_EfuhFC5r!^Vvc5(X+J3UqWZ9pp4y?HtUIZ8z|kLme(p-mY-e=$(*`aDBdZap=&HWOwRv!-c0{@0_)UTTi!6o$F}g20p_(5Z?kT zjy-clU@r=q=&sCPf0ebn4a%CY-lu3kAbbXS@7!bXV}r6h0(*kF2*Yfd$|-99XtN%- zSZ3B+xmp2*?7E#CyK`--hbr+_2!u^6JtxKC%at9?dPg%0_VqemI~?NT){LknF}EgE zf^xt9Hy8%Ihen$92H{@B>bmeL zMvdZWon7B1zzLVa$tPx?eyrBB2aQlsaMWGN%bjj8%JB2ccrRb2!fFh=;~Za=`euw! z?!?wY#%e#wwr$$|>Ka!|Rw`1T)lfdDT3#sMQ9S<54X`2O3TJ9g>alXT?Zy6j_xhFG z(d?FVKR?Yo2Y0d>5)8bC3D2WZ8}DR{$kfH|dI7Co!WL(XcudLezdzHF+MQ0Rk}5qW z<5ar_p?!2_^gORq|NB4@ojCGvV=8Vdlt}8~-39_V9o}?4ZZx=BV1Hoj02UM`s@~kQ zo1na6P>J(h*SrtPfqzrxMEwA`HCRk&{g7x8nj9oxE4i(i)rI-T4}L<6&$kwQeojAmcD}B)^#ygJ%O;KuD1fkt)myGRR_WHaG+76kZh-`#-}CeH;aD3(KJGJj zzI~a7l;`=7bDF7NP(g+!XakE99*%YxEU$w!amKKKaW2L8oL!A>Hf+3(h)E^skWHsttf?!7^FnHuXj z{3Wo_^|+Up*Sq^NM}U9Urt3sQLD{LC8+3TRun%cA+MLxCQMyJK3;j9A?>N$#`{k-Y zI@AOfa(`+9Tm2g#J+WOQt!a33FAsB!Oel~J$AkK->nw2yZPPQEDAdofHOA6stQSNf zz_s>36riJmZk?A#%F;;X8#ARr{W2aWi{W;=s)XXrcs_W;e))DfiGK3k+@~qy1<}jv z0JJJRo8`y7CVC}|d1@3VPhlWW>&tDopsT$8L+42 z3+PHem_u!lTj>T)z#wXC3ym7*Y7cOBHCe<|_fu$i?hul>LWr!A)>8(}NQiLYFs5<&zu2hvx( zC$7}2I4Q0yPBy)~(%7QMHnRb=n2emm+c_OtY;q{v+~A56yA@8S%Ff3xqn!t9Qw~`) zS;etEehD14?EhC0So637$bF{Hf=h}&yb-=DqLV&7+$aFAbwTME(A8QUD)$(um4OGF z)}Dw4pk${CwTbW}}^Hpo^=DQ?$hT<-=w zMuIls=}m`^{e9(Exgd2M8>Fkmk`deCy_4>(=6&M0QpzM?pEdz>qAFLK=Z21a1Q&=CCteUwHHs|+`XlOLOQ9RCwMU`MLfMH}FxM4e zphJ@56;sKA+P1yxKMTTYRDTr&AQC?b0xN&rSKOI}4~vSF;s_C;>S~|JN}E`>&1>do z2KQ8jNz@>b;EA~~!lxVvLWv;8(#JNpuez#WS|y%_3Fa z)<|gicCfl2)Y>0y0lcn0aWtmAuq&EA_6C?e9b+quU@X-D)CZm!Vg zkzH=@V)ZlT9h6O3*S}_8anMIl_=Ek4h)gL!hEDuI{p1HfKg)|3--6;t7>42gW`IPFV*~l+Llc&}K@@NxX#y$%!&<6CK zgNFY_A7Tlh(~7O%vcl zff9ZDiE@Xo&uJ!{u#iUyE6Yoh;3#verxEM+0qsynz_~B614+nq6^YJG`Ys$@O>FUE zKuSKNjtA{}QCWNywESijPve-dAwYz@0Sn}p&nq(J=r0Wiy-jm zWTP!}uF;j*AS0gJc{yB?c)3v$&dLWDkj{plulKfyo7ijaZpb-p-IRwi@&5KCXVH$M zh{=dg#!K-4Zd@1SCsNFj+7QA8A17RAuk#-gmi zT2>UWp&}?EvX)&`5DUoKKoL<9P!W6+u)eqFyyJQ0FDGZ({qFsJ_x|qvZstq%pY3a? zXRQYSfFY0T9e~}F)TfR%cCB_7T*PiqR|GCn1_)w7nOrJDqYzLTFGD~i4iy1F+^tP> zLyW3HgZ?(tX~$&`=8 z_wPh|G+Ve$|EC2)#q>{pf0z_v<#Qy*alzF&k|iyxNW@BA)}XTT4+xQ zvC50fa?mp6H5ZPZRXColvL6{`=eWtzf8Fg?-8s7YGD*dYC6C8GYKtni8rZP9*sSI1 zpD|vK3+_Gu0F8AhhvU!Va6ZP3MVq@S!;M?*Iksl$JRip#y%=K;kh8or?MIi!$)@>U zd(DEElgnS}Z>QTiI;AH^o;kC*X5ZShvSOp+Wbn1dy{D}O?F9QllH=hGFItaJ=z8Y% ztVP3X_u0U*DcXCsBLybWlpP^v2}?#-k-aQ^D$n_?a>|)`RI7bw)?&MQLuDk-jS}3clKXP9Q94 zIwK!hmYI*AW8!N%fA>n8j?%O7X=TBCOB&tY=&y|zBilOYzN#w1PpV`cD@OL*H7O1U ztQ{v_Jv^cB`6$+)X*n#TX>uSpeZsp@iLsI9MH8C~!p62ImUM2W>68UnxtX$K;{c)xZD|2U&zXQ+}{)*2E zYc<#Tt-Rt$Z}eLL-n0LKp-iT;(ZVsI`F?Z7&lLj+MGbdHsbuofe(zKg02qa!SRF3n z`>`RZ*hv6Og@{v}ScVlS0JwU@$pla&q6CFVI4W@?be*gufGF%nSjga$`7#a?fpS;K zk$Ed-2SO_%Ar?&VaMyE98yt6x)B!f{XvdY zj(~J0x)Yh`6Nko73GRBJs~i@w1H5N^fWY3|2oXx9j7=iN#>P6u(wwC7a1w>ZVv)#H z5|v8CG>D3LiBb?plqhV~5W^VWhys$MG9@aNfND&EP`X^{Mj&A0;79+&GCuzkyhQPV z1&j|;oIpmRIFU(WG3iSSh0-Sm1Nq?4-&!aFvE@t(KorvDatQH>K_p7sFCk#)lf7)Y zJZdN$7$PB2h!|5&4OpDKFdrP6^YWH~FZUpuGY*-4RFnj0`LLe%Fz(OLK#iSGIbS8tyqSHh~ zD$Ed4UC4B%v%vWaD4s;26i6UM4TXU_p%{*k#d4<7m@pAx(4C2Nhz=87V7iD%r_d}@fk0G@ z%u@=~Y*LssGMP?gF&R{6XEMv>v(f@YuD~i$jY%Op(S`|8r-h9LgAprG*C_@tWP!!P z=ExC&QYsIWN~7EeYL`H@<)>jjwwz#rQs6C6A{Z!{N@r8ZY$`L5?82t9*fc7U%w&_l z(3irfDE{ARs}~RGI-GJYs=(%t9}*3(sCh{A@Z0cf6gsq&KyYYLum#X?2nsGE8J4G?*xGp~D!d0+<2+6S_hw zQpO78$n^lJ;SR zFZw7(&9DsX&se)Bed_lgI8%4l|KahW-2R6%V9?(u`6hn9)AgOMZ(`t^l)qQkce=ib zfp1d&US0n+y7WHp7!e8fp%;to2j`EPI33$dY71xidIRs(zg-o-W?>Rt88=9QZ9vbd zPmP=@Mq@DHNF|T&GqPQ8%&2j;2VC=QF_D$hXOWU46{|NMz|i+F0)w%rG6Gb84=-F} zWPzcd<#|sJjJwtO^HRTg3&++1Izf(kL#LRmW7#3G$Mn))HP1+ucb1} z?9ahhrUsS5q}$b{QC4X|<`A`K%@4$TOH7@|Oj7*hQL!lu2=UyOeAK6)LY!f)*L*D# ziT0kAkZ`55uUnh{{?6SuuM!g5UeOUt%)`Guk|tG!kslm8eE85Ft!>=Qo~o%AMI(~) zecunf_fig4*VosZr+VW#Z+xbDE?KhVCT$8${64nd&*AmjfW7Ym2sx+S=`OEFtS2zI zSv^(V-Q6KuPAs0d@Kog?%Q0y)EZj*B4zKk%HdGA*?do=u$_-{#wP{D&q4}hS(8&%C zdswU99>#GvZ%qAzgZJeb`mTJ@;(^a|YiMZbiIzx;M^$_00|wP(pO9C&=&Q43o70aT zJ(@?~ae1_Xl@E^2VC2Lu?+cxE{r+X2vmTvy%Da!>=;%?##9V=1>sWvpj?cF`-aDCQ zK}uW@8v3-BjGtOn#NW|!F*Ij6HE8pM)&Yy&rw81RQ8~9_9$m5;&zTvFGc^;#c2`e& zh59KIpS3}?>Elp|WX5C_0jMVX`8>=MY_47G@F3+y;@ylR9dxOIp;4f4>%6H+H9|^H z&)s%@%?QbqmKK`HgQd|YoBOo2waqCH9F4(kms_tH>uH~^@91f~xP^2KY9C>~OSH84 zX61QFCGYo?@B_d9rmBOPQO+U3%=Cc#Jg(!?0V2=BeN6g0N{{T;!E2AN1Wo;E92d}N zTKwYPx*Hw!8H+XmU0s`NgiE(%XTOsi37(_^c&W`f`~q{Yy#ZVHUB4OLl|E;qg}A=< zNk_+04sOGt(JO;z##$x@ZPj0WwXyNhIzZQRe?yEz_P*d-dS(XC2dpz(!+-jcV1oOkPYypw$)CCoi%Ahr|gXz zHyVH%d70CoW9eysHSfOt{LbdBxO<@WrX~2bK>jvkeT{onkCi7Datp7=HfZDx^1ac0 zc`lQDIRorzP>Pbcy$X5WJFRPd)Q!RH`bEbDTjrhJ0HBk1-s$McD=dlVR*bf?#Rp9G zRQ0Wz6LN;|SJ0cLrY74G9o0+AYs-$@*DGA6DfBQjNfKDjIC!J7Cg~L)uyzOW_owaL zs%06&vah*4E2_ZU!LqeMI2&-(C7tzf>lvL|Gk1UXHp#J&>%QkVq&ojRyDg{Aj8$+d zFSPURttktO-%act?>X~#{fs*JvYpwZ)3>`L5u|W5PRGm#&zpqSL?@ieZL$Yv09!6H z>iSn1;q6^ytx4E;(t`bNGldzs#e#Gs$Q)<4?euAP;g+>)!Y(AX|7l~Z#igFQ>-!YV zKa;;BG$_bQUn7$%5ZKhuI{3pi_XIwFQ$%Lc1>$V$qdzd)+DbY*JB{o-@fYfU+izPT zJ0{s2eKMv~m;s=3gOSmEF|Qz@NK*{d&s7J9oq2 z?iBaSv^QZtMn**y%)s5-%&s|U9kyxx#>U3Rl)wX%v-QeT@4Fc39`chP>FBGO`|i@} zQSQ|`tBXm-1~*5Ica8AI>Ez-xS`PNcxw<;`>vuF33&hSlG<6Rdc%7*lIp=!n$=u9B zZ4WaZxkt9Wy+Oka2Zx7;n4Ex37A2=9^p&4D!6w-6dUUEkpnhCe(l3;Ph$(T3#Fm!Y z0jx#jT+7t5b6y{~>b}pf*T(%+XZGvhn-H5Vbz_ZcODp#{D)D==^|G2JZD5j4@0fe` z9$oQAckiy&(73uNxy@M;c3{DNO99#j4*W%E6*RR*M#ezEUD2RtPXo06Fe!ck7x}MYV@c#Kld3ocFbX7&X*6!}!Cr_4P1pw(jyECqBS!AS% zlSUEndy(dmndp&jn^?fsykcogW+=)YVZH;q4~JgFp)2PJU|* zkj+!I=V{{n?WR+$XX|*TYSjgc!>qVxLKm0Z&OIFMg)`36s%r^P0<>m<=O&tHfq}UE z7)u*q4PK|bV&g>Bq4VTzh7<5f&+WK1e_Wdmc-a|uOHGpP<8Hou!VA>++y4r{6Zd*d XZsYn9JB?cYQfu&hW_uTVg(d$3UKvk^ literal 0 HcmV?d00001 diff --git a/gui/resources/icons/arrow_up_right_dark_128.png b/gui/resources/icons/arrow_up_right_dark_128.png new file mode 100644 index 0000000000000000000000000000000000000000..0086eb8488c179d02d9379f79caa80e38a6de5b0 GIT binary patch literal 7066 zcmeHKc{r5o`+tXQbB?7{WT`PJEyk?O5|X8CgB&8u(Jb#UF*BI4BwHzw5=ALWmNtoV zLSpPon=GXbDJogAtB~+}N1aYxzwdRO>s-Iz_rGSYce|ha{yg{nx$oz`o+sAMW}7Tr z1r7j!tcAI$J@kweUDA@!z1EP{06hjn9GnIAv>=49Kaa)s0TF^dz90e&X0rewxc%sM zSGiimuQR<%HyNATOW)2wvx(2fdX2rFTAX0T5&{vr8b0~GD_2TABlRVrl9QxcG7oNC zk`-T4Z{AL?UAOP$d*9{C$GbM3T^<+~6|YZ0ha=)=vmTh!&Gg(4y11v0d>WK(t57Ww zkDYBU`~>4^4#pQw)T>{hPX`tSWNaFA*>JiwiN3=WyhmR4=2rHK2{-wy35ptZxawf_ z?H$otFErsAhqH(6<1g6Dt0%6J^3nWrYwj|-s($x+8m!5RSLQ@HG)+$R-nx0Txu{09 zWjxTZuIum&0Kg8gO-$@8OiccY8;Uk9EYZNc)^6!RTh|Nr8`K980|^U{6yV$dd8!A zf2D%!8B1&z-(KpN6&le59-LV2S>)n5WH|jxtpo=={mx;vIc>3(f`-vn^<@q;4IAOs z!?C}f)iU^O67QjT$~q6OOkQpm1;0BMHD5i_cBcNW3~_zhq7Vx(4BxDK3N3F+So-Pt~a}#C3uqtF_#5n%m%Z({W~9vqvh{%m4aZ zEJHVlJH$^j1a_Wr{3J;tExKiyR6aa5TrpfSyZ4eo<*KnD|F&M`w#@(_=gNla(3xsY zVemLQG$xM@>I8Fqp#lW}{msF?G=?`QK+r)?HrD_-BCJFr*h~YYlP(oQ^)&&#*ybVr z;BO%|4vY|Q2APT6YzWs6ra%B3P(VWjb9}gbO0WTP0ha>3i^OOoVnIdVZGd#9+96DM z{vd*&L(svX%!1j0IHVyQq3_RRQS42(euaR(43J&|fiDG(4hjm=3Bv2}{5{cFGMS9V z;Ltc63erIF_izQYU=)|XS_JV0!xZE*{Mo(&Hjj%CVbbWl0D%D#35_HE@{i+7rGA6w z^1reG@qrGe`J%Bp7&M22{@#KwFbjl0zB=?DE%*-5az@*Od|rS*12hW+xq{W-LogZN z?0p0LeHOxDGSHw8$bnS((5%=Wrrc&hwfklvqQH~Q@m;Wj$o@f7z-IkT)(^gkMi#>P z-VwHVuq-A6{~d&_KO3q_n$P!MiJ+Je6oZKYX+#1IMaJrqPy`UmM3M0X9EzpK zB9lp2EEbRX;ti8Q*~;_h(4cg(IW$iY?aTFCm_tN3Ws9AK0TQQ!`CDS=Lldwd0|TTr zn;Q`P_kaVN1O6tUiP*#v@fZvNM_hFB;bqgu2Jqa{Wur{tu-03lwDmA`FGapm10R zES@5wO7|;a=>L9*WDJNUgSre9k-=a>C5j=TNP2o$6rISV>ERhfBD83Jbo&1k;TGST*N~%8kf2IA4!gqZXqUMVX>d#QSM}O=0UpW(X*8k$~Yq|XwXMmu8PV%q# z{YlqPy8aad|4R91b^WC4Uor5nlz&#&{~KNKzfX)H7ux6rLFd7}{VF@5v!o>5YMUuA zFZ!P^zjOkU$oQJ?$fbCkH9P6)jA+I0Uy3xqI6sJzWvrG_LN9FBKA&ZMv{;T@Uhl z-AyOWwQios4CJ5KlscJO>!aBAi<{4^W!nd2>ghU3l-yCj7JS-<)4KcNt!MW&+heoX z@GCxyPf>5>S=tRDwFbh_+3GwK^_cymL(?ZGr)$&C8lYcJlr_(s>nP4GD43urTwJr? z`18qgHH2GpVKWZm2GRYpO8}WjBQZn*Agu|A{nKmBQe&7haM?J;0%(=aQSgITeH`wb z8BIU7(y?Q5aO~m*&&w*Y@d{Ubl#K67COmF=7Oaimq*@sYHq3`zypplSedf_`(ZKoR zK&DoQBG7f`K~`A*&K)WDSyPgdTW1I7qNFqq#DHlYt6_cm9paHW@I<@cTsw*bI`mSs z#{kUQX#hhYn65F(H@9lGGw5`;0PG`L+x85OcGsFWUl*$i80SU5$=0+6Kb`N0 zWUlX_WSjz|%#F{@l+*U6YnOd~6$i9X-vKzAmmwkag9>Efz(Cnc3+qAm`9WK)u(Y#9 z0lU)DwWJcRW)uXhB#jDh>v8M)DF z@=hg{uwuTy$b0)v$NEC$ILj)p<>)#eEa81t=Z6nDd!ASWkvrZrTTL6Db1N@3t(`xm zfb3j^7>;^t@&z>cPG zf3G3PWR2#p3MVPwjpn)yC*kCQImLaNv86V1dG19;?)l|olCN0LGg7BcC7;~SAATC* zcG2@;GfdkorfqaaQLcQ#=BaR`{LnF*v`3xuG+e6R!0TiFD|)pG)q>_L!gBJ|5#qb@ zot!3zIwQJN<#*hPU!{YNi~-)yn?&@eHo#wNkT?fwm)_RFa^(>wpjNZ=2z zhFNDS=DHOf9?I)n6ILeIfdr;f)ONv5N2_KhRf~BY8v=6WQSR`jlFbi4Y|dGP$yA#< zmG4~r;`y96`?Z_n_QZ|i)7!No6KzKAEMhNkd*%9HrKTs!nR>nUJkl?CuK`?!k|Po0 zceAtlm)YOh^i3VFw}hN5QaYYnv$ZD?Be4s9J`_#fxncZu<60o5uYJByAyT1+$)}j* z`b9hVT?>CDbLGx4OW3+dZ0qh1y90{3`oXN(PnK!A@_^XB_yDh_L8amt^K z5`Cof&ZrsrEmN9|?Mg_he*DxSia(dE-CBA1w8R12;m+i=!O7ptG&yP0d-iN?yK@XK zrO?})I;i86VD)75s3|RcC7`^9iU?zcc~xuatR_CaszT3>FTPP)>J|+V>lX=}&zYT- zIlXgd)b$gq+Na1X`}$$zD$VYdh$q_}9ue1xJ-qEQ-W4ScR$9toWS-;$gReS+JSN;r zbK_E0xfb11Nk|IqlrfTC{LZ%|I*F8Zu4ZL|{+0KwqZdHtuegKna@_6~j%8U%Nmnw- z-rdHHcbfgke!^av;UmRBq`-T=R54PluH7xKVxyCk?uzCi!TDr%FxP%wRXEu&N|u&}t$nbfNeuex^%P1Jkx*rrbyew}8bApqDC z3cw?^V%MV&?tMHfCm`r1`!}U(BR$%#_H_-M-Eu3}De_rT(o)B( zwQ4p(Sq=(Sa^Fjz;(u?s;qM>K%_LNt$F4`a>vp9@te<#qYY97`S}|xAm&Z)Ym4k8(PK+Bkh)9NiZK)1UuPOhUP`3Z1p1 zyq_502YU6>&;98=n^Sz*H?rR9x%MSC0L7v?N;9a1&ld-ZtCjkcY|K5ai^c>}#qTw23gCmpSD)v=bS|F~euG>&9M&&1+4 zx#BzIsUPlL={WX>_<@KF?|t?Dj#lF)vM)zsKTH3D*j2DTuRcyUb)ZB&P(UC$+1D!3 zpjK8}8W3Hgq%&1s5$B>8%D?&G*_JokUcl)7O=&W_i)v2cpO3a_?R7e~2m`xpT-RvT ztZ-)KTQ47N&$RTl<7-kRe4A#CW3pRji?6JCNvjNxKIV0z4rc86rea(W)U(^jP&X8p zCw{=x7YFEHRpwc=fmT16hHF&;1o5KoHR207hD5kngr*O-PcB~{5HgC|)w zU1~2LHiBvC2+Pbm*j7KW8E4%HTWVw4pToV10-eZ2gMAP icons/arrow_right_128.png + icons/arrow_right_dark_128.png icons/arrow_up_right_128.png + icons/arrow_up_right_dark_128.png icons/arrow_up_128.png icons/arrow_up_dark_128.png icons/arrow_up_left_128.png + icons/arrow_up_left_dark_128.png icons/arrow_left_128.png + icons/arrow_left_dark_128.png icons/arrow_down_left_128.png + icons/arrow_down_left_dark_128.png icons/arrow_down_128.png + icons/arrow_down_dark_128.png icons/arrow_down_right_128.png + icons/arrow_down_right_dark_128.png icons/square_128.png icons/home-circle.png icons/stop-circle-outline.png diff --git a/gui/widgets/pupilGuide/pupilGuide.hpp b/gui/widgets/pupilGuide/pupilGuide.hpp index ce0c7e4c9..99ea0559a 100644 --- a/gui/widgets/pupilGuide/pupilGuide.hpp +++ b/gui/widgets/pupilGuide/pupilGuide.hpp @@ -164,12 +164,15 @@ class pupilGuide : public xWidget // ****** Alignment ******** // // --- camwfs-align + std::string m_camwfs_align_fsmState; bool m_camwfsAlignLoopState{ false }; // --- twAlign-camwfs-ctrl + std::string m_twAlign_camwfs_ctrl_fsmState; bool m_twAlignLoopState {false}; // --- twAlign-camwfs-wfs + std::string m_twAlign_camwfs_wfs_fsmState; bool m_twAlignSensorState {false}; public: @@ -197,13 +200,13 @@ class pupilGuide : public xWidget int whichcl = CAMLENS_BOTH ///< Which axis, or both. CAMLENS_X, CAMLENS_Y, CAMLENS_BOTH ); - void camwfs_align_setEnabled( bool enabled ); + void camwfs_align_setEnabled( bool enabled, bool all ); - void twAlign_camwfs_ctrl_setEnabled( bool enabled ); + void twAlign_camwfs_ctrl_setEnabled( bool enabled, bool all ); - void twAlign_camwfs_wfs_setEnabled( bool enabled ); + void twAlign_camwfs_wfs_setEnabled( bool enabled, bool all ); - void alignment_buttons_setEnabled( bool enabled ); + void alignment_buttons_setEnabled( bool enabled, bool all ); public slots: void updateGUI(); @@ -602,6 +605,9 @@ void pupilGuide::subscribe() m_parent->addSubscriber( ui.pupTrackLoop_slider ); m_parent->addSubscriber( ui.pupTrackLoop_gain ); + m_parent->addSubscriberProperty( this, "twAlign-camwfs-ctrl", "fsm" ); + m_parent->addSubscriberProperty( this, "twAlign-camwfs-ctrl", "loop_state" ); + m_parent->addSubscriber( ui.actAlignLoop_deltaX ); m_parent->addSubscriber( ui.actAlignLoop_deltaY ); @@ -609,6 +615,9 @@ void pupilGuide::subscribe() m_parent->addSubscriber( ui.actAlignLoop_gain ); + m_parent->addSubscriberProperty( this, "twAlign-camwfs-wfs", "fsm" ); + m_parent->addSubscriberProperty( this, "twAlign-camwfs-wfs", "loop_state" ); + m_parent->addSubscriber( ui.actAlignSensor_slider ); m_parent->addSubscriber( ui.actAlignSensor_nAverage ); @@ -695,10 +704,10 @@ void pupilGuide::onConnect() ui.actAlignSensor_pokeAmp->onConnect(); - camwfs_align_setEnabled(true); - twAlign_camwfs_ctrl_setEnabled(true); - twAlign_camwfs_wfs_setEnabled(true); - alignment_buttons_setEnabled(true); + camwfs_align_setEnabled(true, true); + twAlign_camwfs_ctrl_setEnabled(true, true); + twAlign_camwfs_wfs_setEnabled(true, true); + alignment_buttons_setEnabled(true, true); setWindowTitle( "Alignment" ); } @@ -777,10 +786,13 @@ void pupilGuide::onDisconnect() ui.actAlignSensor_nImages->onDisconnect(); ui.actAlignSensor_pokeAmp->onDisconnect(); - camwfs_align_setEnabled(false); - twAlign_camwfs_ctrl_setEnabled(false); - twAlign_camwfs_wfs_setEnabled(false); - alignment_buttons_setEnabled(false); + camwfs_align_setEnabled(false, true); + m_camwfs_align_fsmState = ""; + twAlign_camwfs_ctrl_setEnabled(false, true); + m_twAlign_camwfs_ctrl_fsmState = ""; + twAlign_camwfs_wfs_setEnabled(false, true); + m_twAlign_camwfs_wfs_fsmState = ""; + alignment_buttons_setEnabled(false, true); setWindowTitle( "Alignment (disconnected)" ); } @@ -1097,23 +1109,6 @@ void pupilGuide::handleSetProperty( const pcf::IndiProperty &ipRecv ) } } } - else if( dev == "camwfs-align" ) - { - if( ipRecv.getName() == "loop_state" ) - { - if( ipRecv.find( "toggle" ) ) - { - if( ipRecv["toggle"].getSwitchState() == pcf::IndiElement::On ) - { - m_camwfsAlignLoopState = true; - } - else - { - m_camwfsAlignLoopState = false; - } - } - } - } else if( dev == "stagecamlensx" ) { if( ipRecv.getName() == "fsm" ) @@ -1188,7 +1183,78 @@ void pupilGuide::handleSetProperty( const pcf::IndiProperty &ipRecv ) } } } - + else if( dev == "camwfs-align" ) + { + if( ipRecv.getName() == "fsm" ) + { + if( ipRecv.find( "state" ) ) + { + m_camwfs_align_fsmState = ipRecv["state"].get(); + } + } + else if( ipRecv.getName() == "loop_state" ) + { + if( ipRecv.find( "toggle" ) ) + { + if( ipRecv["toggle"].getSwitchState() == pcf::IndiElement::On ) + { + m_camwfsAlignLoopState = true; + } + else + { + m_camwfsAlignLoopState = false; + } + } + } + } + else if( dev == "twAlign-camwfs-ctrl" ) + { + if( ipRecv.getName() == "fsm" ) + { + if( ipRecv.find( "state" ) ) + { + m_twAlign_camwfs_ctrl_fsmState = ipRecv["state"].get(); + } + } + else if( ipRecv.getName() == "loop_state" ) + { + if( ipRecv.find( "toggle" ) ) + { + if( ipRecv["toggle"].getSwitchState() == pcf::IndiElement::On ) + { + m_twAlignLoopState = true; + } + else + { + m_twAlignLoopState = false; + } + } + } + } + else if( dev == "twAlign-camwfs-wfs" ) + { + if( ipRecv.getName() == "fsm" ) + { + if( ipRecv.find( "state" ) ) + { + m_twAlign_camwfs_wfs_fsmState = ipRecv["state"].get(); + } + } + else if( ipRecv.getName() == "loop_state" ) + { + if( ipRecv.find( "toggle" ) ) + { + if( ipRecv["toggle"].getSwitchState() == pcf::IndiElement::On ) + { + m_twAlignSensorState = true; + } + else + { + m_twAlignSensorState = false; + } + } + } + } return; } @@ -1397,36 +1463,48 @@ void pupilGuide::camlensSetEnabled( bool enabled, } } -void pupilGuide::camwfs_align_setEnabled( bool enabled ) +void pupilGuide::camwfs_align_setEnabled( bool enabled, bool all ) { - ui.label_pupTrackLoop->setEnabled(enabled); + if(all) + { + ui.label_pupTrackLoop->setEnabled(enabled); + } ui.pupTrackLoop_deltaX->setEnabled(enabled); ui.pupTrackLoop_deltaY->setEnabled(enabled); ui.pupTrackLoop_slider->setEnabled(enabled); ui.pupTrackLoop_gain->setEnabled(enabled); } -void pupilGuide::twAlign_camwfs_ctrl_setEnabled( bool enabled ) +void pupilGuide::twAlign_camwfs_ctrl_setEnabled( bool enabled, bool all ) { - ui.label_actAlignLoop->setEnabled(enabled); + if(all) + { + ui.label_actAlignLoop->setEnabled(enabled); + } ui.actAlignLoop_deltaX->setEnabled(enabled); ui.actAlignLoop_deltaY->setEnabled(enabled); ui.actAlignLoop_slider->setEnabled(enabled); ui.actAlignLoop_gain->setEnabled(enabled); } -void pupilGuide::twAlign_camwfs_wfs_setEnabled( bool enabled ) +void pupilGuide::twAlign_camwfs_wfs_setEnabled( bool enabled, bool all ) { - ui.label_actAlignSensor->setEnabled(enabled); + if(all) + { + ui.label_actAlignSensor->setEnabled(enabled); + } ui.actAlignSensor_slider->setEnabled(enabled); ui.actAlignSensor_nAverage->setEnabled(enabled); ui.actAlignSensor_nImages->setEnabled(enabled); ui.actAlignSensor_pokeAmp->setEnabled(enabled); } -void pupilGuide::alignment_buttons_setEnabled( bool enabled ) +void pupilGuide::alignment_buttons_setEnabled( bool enabled, bool all ) { - ui.label_alignment->setEnabled(enabled); + if(all) + { + ui.label_alignment->setEnabled(enabled); + } ui.button_startAlignment->setEnabled(enabled); ui.button_stopAlignment->setEnabled(enabled); @@ -1861,27 +1939,55 @@ void pupilGuide::updateGUI() ui.camlensX_pos->updateGUI(); ui.camlensY_pos->updateGUI(); + + + + + ui.fitThreshold->updateGUI(); + ui.fitAvgTime->updateGUI(); + + if(m_camwfs_align_fsmState != "READY" && m_camwfs_align_fsmState != "OPERATING") + { + camwfs_align_setEnabled(false, false); + } + else + { + camwfs_align_setEnabled(true, true); + } + ui.pupTrackLoop_deltaX->updateGUI(); ui.pupTrackLoop_deltaY->updateGUI(); - ui.pupTrackLoop_slider->updateGUI(); ui.pupTrackLoop_gain->updateGUI(); + if(m_twAlign_camwfs_ctrl_fsmState != "READY" && m_twAlign_camwfs_ctrl_fsmState != "OPERATING") + { + twAlign_camwfs_ctrl_setEnabled(false, false); + } + else + { + twAlign_camwfs_ctrl_setEnabled(true, true); + } + ui.actAlignLoop_deltaX->updateGUI(); ui.actAlignLoop_deltaY->updateGUI(); - ui.actAlignLoop_slider->updateGUI(); ui.actAlignLoop_gain->updateGUI(); + if(m_twAlign_camwfs_wfs_fsmState != "READY" && m_twAlign_camwfs_wfs_fsmState != "OPERATING") + { + twAlign_camwfs_wfs_setEnabled(false, false); + } + else + { + twAlign_camwfs_wfs_setEnabled(true, true); + } + ui.actAlignSensor_slider->updateGUI(); ui.actAlignSensor_nAverage->updateGUI(); ui.actAlignSensor_nImages->updateGUI(); ui.actAlignSensor_pokeAmp->updateGUI(); - ui.fitThreshold->updateGUI(); - ui.fitAvgTime->updateGUI(); - - } // updateGUI() // ------------- modttm diff --git a/gui/widgets/pupilGuide/pupilGuide.ui b/gui/widgets/pupilGuide/pupilGuide.ui index f3b7a8f9a..b9639e5c1 100644 --- a/gui/widgets/pupilGuide/pupilGuide.ui +++ b/gui/widgets/pupilGuide/pupilGuide.ui @@ -331,7 +331,8 @@ - :/icons/arrow_up_right_128.png:/icons/arrow_up_right_128.png + :/icons/arrow_up_right_128.png + :/icons/arrow_up_right_dark_128.png:/icons/arrow_up_right_128.png @@ -396,7 +397,8 @@ - :/icons/arrow_up_left_128.png:/icons/arrow_up_left_128.png + :/icons/arrow_up_left_128.png + :/icons/arrow_up_left_dark_128.png:/icons/arrow_up_left_128.png @@ -461,7 +463,8 @@ - :/icons/arrow_right_128.png:/icons/arrow_right_128.png + :/icons/arrow_right_128.png + :/icons/arrow_right_dark_128.png:/icons/arrow_right_128.png @@ -493,7 +496,8 @@ - :/icons/arrow_down_left_128.png:/icons/arrow_down_left_128.png + :/icons/arrow_down_left_128.png + :/icons/arrow_down_left_dark_128.png:/icons/arrow_down_left_128.png @@ -525,7 +529,8 @@ - :/icons/arrow_left_128.png:/icons/arrow_left_128.png + :/icons/arrow_left_128.png + :/icons/arrow_left_dark_128.png:/icons/arrow_left_128.png @@ -557,7 +562,8 @@ - :/icons/arrow_down_128.png:/icons/arrow_down_128.png + :/icons/arrow_down_128.png + :/icons/arrow_down_dark_128.png:/icons/arrow_down_128.png @@ -589,7 +595,8 @@ - :/icons/arrow_down_right_128.png:/icons/arrow_down_right_128.png + :/icons/arrow_down_right_128.png + :/icons/arrow_down_right_dark_128.png:/icons/arrow_down_right_128.png @@ -1089,7 +1096,8 @@ - :/icons/arrow_down_right_128.png:/icons/arrow_down_right_128.png + :/icons/arrow_down_right_128.png + :/icons/arrow_down_right_dark_128.png:/icons/arrow_down_right_128.png @@ -1121,7 +1129,8 @@ - :/icons/arrow_down_left_128.png:/icons/arrow_down_left_128.png + :/icons/arrow_down_left_128.png + :/icons/arrow_down_left_dark_128.png:/icons/arrow_down_left_128.png @@ -1153,7 +1162,8 @@ - :/icons/arrow_up_right_128.png:/icons/arrow_up_right_128.png + :/icons/arrow_up_right_128.png + :/icons/arrow_up_right_dark_128.png:/icons/arrow_up_right_128.png
@@ -1185,7 +1195,8 @@ - :/icons/arrow_up_left_128.png:/icons/arrow_up_left_128.png + :/icons/arrow_up_left_128.png + :/icons/arrow_up_left_dark_128.png:/icons/arrow_up_left_128.png
@@ -1469,7 +1480,8 @@ - :/icons/arrow_right_128.png:/icons/arrow_right_128.png + :/icons/arrow_right_128.png + :/icons/arrow_right_dark_128.png:/icons/arrow_right_128.png
@@ -1534,7 +1546,8 @@ - :/icons/arrow_left_128.png:/icons/arrow_left_128.png + :/icons/arrow_left_128.png + :/icons/arrow_left_dark_128.png:/icons/arrow_left_128.png
@@ -1599,7 +1612,8 @@ - :/icons/arrow_down_128.png:/icons/arrow_down_128.png + :/icons/arrow_down_128.png + :/icons/arrow_down_dark_128.png:/icons/arrow_down_128.png
@@ -2359,7 +2373,8 @@ - :/icons/arrow_left_128.png:/icons/arrow_left_128.png + :/icons/arrow_left_128.png + :/icons/arrow_left_dark_128.png:/icons/arrow_left_128.png
@@ -2457,7 +2472,8 @@ - :/icons/arrow_down_128.png:/icons/arrow_down_128.png + :/icons/arrow_down_128.png + :/icons/arrow_down_dark_128.png:/icons/arrow_down_128.png
@@ -2489,7 +2505,8 @@ - :/icons/arrow_right_128.png:/icons/arrow_right_128.png + :/icons/arrow_right_128.png + :/icons/arrow_right_dark_128.png:/icons/arrow_right_128.png
diff --git a/gui/widgets/xWidgets/statusEntry.hpp b/gui/widgets/xWidgets/statusEntry.hpp index 5a9c1d82b..5fedce2bf 100644 --- a/gui/widgets/xWidgets/statusEntry.hpp +++ b/gui/widgets/xWidgets/statusEntry.hpp @@ -10,9 +10,9 @@ #include "../../lib/multiIndiSubscriber.hpp" -namespace xqt +namespace xqt { - + class statusEntry : public QWidget, public multiIndiSubscriber { Q_OBJECT @@ -21,7 +21,7 @@ class statusEntry : public QWidget, public multiIndiSubscriber enum types{ STRING, INT, FLOAT }; protected: - + std::string m_device; std::string m_property; std::string m_label; @@ -41,11 +41,11 @@ class statusEntry : public QWidget, public multiIndiSubscriber std::string m_current; std::string m_target; - + QTimer * m_updateTimer {nullptr}; - + public: - statusEntry( QWidget * Parent = 0, + statusEntry( QWidget * Parent = 0, Qt::WindowFlags f = Qt::WindowFlags() ); @@ -54,12 +54,12 @@ class statusEntry : public QWidget, public multiIndiSubscriber int type, const std::string & label, const std::string & units, - QWidget * Parent = 0, + QWidget * Parent = 0, Qt::WindowFlags f = Qt::WindowFlags() ); - + ~statusEntry() noexcept; - + void construct(); void setup( const std::string & device, @@ -83,10 +83,10 @@ class statusEntry : public QWidget, public multiIndiSubscriber QString formattedValue(); - /// Set the read only flag + /// Set the read only flag /** If set to true, the widget will not accept focus and will not enter edit mode. * The default is false. - * + * * This sets m_readOnly */ void readOnly(bool ro /**< [in] the new value of the read only flag*/); @@ -94,13 +94,13 @@ class statusEntry : public QWidget, public multiIndiSubscriber /// Get the value of the read only flag /** * \returns the current value of m_readOnly - */ + */ bool readOnly(); /// Set the highlight changes flag /** If set to false, the widget will not changed to statusChanged. * The default is true. - * + * * This sets m_highlightChanges */ void highlightChanges(bool hc); @@ -112,15 +112,15 @@ class statusEntry : public QWidget, public multiIndiSubscriber bool highlightChanges(); virtual void subscribe(); - + virtual void onConnect(); - + virtual void onDisconnect(); - + void handleDefProperty( const pcf::IndiProperty & ipRecv /**< [in] the property which has changed*/); - + void handleSetProperty( const pcf::IndiProperty & ipRecv /**< [in] the property which has changed*/); - + /// Set the stretch of the horizontal layout void setStretch( int s0, ///< Stretch of the spacer. If 0, the spacer is removed. int s1, ///< Stretch of the label @@ -147,11 +147,11 @@ public slots: void doUpdateGUI(); private: - + Ui::statusEntry ui; }; - -statusEntry::statusEntry( QWidget * Parent, + +statusEntry::statusEntry( QWidget * Parent, Qt::WindowFlags f) : QWidget(Parent, f) { construct(); @@ -162,7 +162,7 @@ statusEntry::statusEntry( const std::string & device, int type, const std::string & label, const std::string & units, - QWidget * Parent, + QWidget * Parent, Qt::WindowFlags f) : QWidget(Parent, f) { construct(); @@ -204,7 +204,7 @@ void statusEntry::setup( const std::string & device, { m_device = device; m_property = property; - + m_type = type; defaultFormat(); @@ -248,7 +248,7 @@ QString floatAutoFormat(const std::string & value) { return QString(""); } - + std::string format = "%f"; double av = fabs(v); @@ -272,7 +272,7 @@ QString floatAutoFormat(const std::string & value) { format = "%0.4f"; } - else + else { format = "%0.3g"; } @@ -299,21 +299,21 @@ QString statusEntry::formattedValue() { return QString(""); } - + case FLOAT: if(m_format == "auto") return floatAutoFormat(m_current); - try + try { snprintf(str, sizeof(str), m_format.c_str(), std::stof(m_current)); return QString(str); } catch(...) - { + { return QString(""); } - + default: return QString(m_current.c_str()); } @@ -344,12 +344,12 @@ bool statusEntry::highlightChanges() void statusEntry::subscribe() { if(!m_parent) return ; - + if(m_property != "") m_parent->addSubscriberProperty(this, m_device, m_property); return; } - + void statusEntry::onConnect() { m_valChanged = true; @@ -366,15 +366,15 @@ void statusEntry::handleDefProperty( const pcf::IndiProperty & ipRecv) } void statusEntry::handleSetProperty( const pcf::IndiProperty & ipRecv) -{ +{ if(ipRecv.getDevice() != m_device) return; - + if(ipRecv.getName() == m_property) { if(ipRecv.find(m_currEl)) { std::string current = ipRecv[m_currEl].get(); - if(current != m_current) + if(current != m_current) { m_valChanged = true; } @@ -390,8 +390,8 @@ void statusEntry::handleSetProperty( const pcf::IndiProperty & ipRecv) emit doUpdateGUI(); } -void statusEntry::setStretch( int s0, - int s1, +void statusEntry::setStretch( int s0, + int s1, int s2 ) { @@ -410,7 +410,7 @@ void statusEntry::setStretch( int s0, } } -void statusEntry::format( const std::string & f) +void statusEntry::format( const std::string & f) { m_format = f; } @@ -426,12 +426,12 @@ void statusEntry::on_value_returnPressed() ui.value->clearFocus(); pcf::IndiProperty ip(pcf::IndiProperty::Text); - + ip.setDevice(m_device); ip.setName(m_property); ip.add(pcf::IndiElement(m_targEl)); ip[m_targEl] = str; - + sendNewProperty(ip); } @@ -459,8 +459,10 @@ void statusEntry::stopEditing() ui.value->stopEditing(); } + + } //namespace xqt - + #include "moc_statusEntry.cpp" #endif diff --git a/gui/widgets/xWidgets/statusLineEdit.hpp b/gui/widgets/xWidgets/statusLineEdit.hpp index 95a8cb72b..d7cf694f1 100644 --- a/gui/widgets/xWidgets/statusLineEdit.hpp +++ b/gui/widgets/xWidgets/statusLineEdit.hpp @@ -24,16 +24,16 @@ namespace xqt * - If focus then returns, the last edited value is loaded * - After the stale timeout (default 60 sec), the edited value is cleared so that subsequent edits start with the current value * - onReturnPressed should normally be used to signal a new value to set, rather than editingFinished. - * + * * To trigger the statusChanged style, the member function setTextChanged() must be called instead of setText(). This will also prevent interrupting * current editing when the widget has focus. - * + * * Ref: https://doc.qt.io/qt-5/qlineedit.html - */ + */ class statusLineEdit : public QLineEdit { Q_OBJECT - + public: enum valchanges{NOTCHANGED, CHANGED, CHANGED_TIMEOUT}; @@ -48,12 +48,12 @@ class statusLineEdit : public QLineEdit bool m_highlightChanges {true}; int m_valChanged {NOTCHANGED}; ///< Whether or not the value has changed, can take the values in enum statusLineEdit::valchanges. - + int m_editing {NOTEDITING}; ///< Whether or not editing is in progress, can take the values in enum statusLineEdit::editchanges. /// The timer for restoring status style from the statusChanged style /** This is started for m_changeTimeout msecs after a setTextChanged() is called. - * + * * Ref: https://doc.qt.io/qt-5/qtimer.html */ QTimer * m_changeTimer {nullptr}; @@ -62,7 +62,7 @@ class statusLineEdit : public QLineEdit /// The timer for returning to status display mode when editing has paused /** This is started for m_editTimeout msecs after a focusInEvent and any keyPressEvent other than ESC. - * + * * Ref: https://doc.qt.io/qt-5/qtimer.html */ QTimer * m_editTimer {nullptr}; @@ -71,7 +71,7 @@ class statusLineEdit : public QLineEdit /// The timer for clearing the edit text after a long pause in editing /** This is started for m_staleTimeout msecs after a timeout from m_editTimer. - * + * * Ref: https://doc.qt.io/qt-5/qtimer.html */ QTimer * m_staleTimer {nullptr}; @@ -87,7 +87,7 @@ class statusLineEdit : public QLineEdit /** Is independent of the edited text * * \returns m_currText; - */ + */ QString currText(); /// Get the edited text @@ -97,10 +97,10 @@ class statusLineEdit : public QLineEdit */ QString editText(); - /// Set the read only flag + /// Set the read only flag /** If set to true, the widget will not accept focus and will not enter edit mode. * The default is false. - * + * * This sets m_readOnly */ void readOnly(bool ro /**< [in] the new value of the read only flag*/); @@ -108,13 +108,13 @@ class statusLineEdit : public QLineEdit /// Get the value of the read only flag /** * \returns the current value of m_readOnly - */ + */ bool readOnly(); /// Set the highlight changes flag /** If set to false, the widget will not change to statusChanged. * The default is true. - * + * * This sets m_highlightChanges */ void highlightChanges(bool hc); @@ -126,13 +126,13 @@ class statusLineEdit : public QLineEdit bool highlightChanges(); /// Set the change timeout - /** The change timeout (m_changeTimeout) is the duration for which the + /** The change timeout (m_changeTimeout) is the duration for which the * statusChanged CSS style is applied after a value update. - */ + */ void changeTimeout( std::chrono::milliseconds & cto /**< [in] the new change timeout in msec */); /// Get the change timeout - /** The change timeout (m_changeTimeout) is the duration for which the + /** The change timeout (m_changeTimeout) is the duration for which the * statusChanged CSS style is applied after a value update. */ std::chrono::milliseconds changeTimeout(); @@ -140,7 +140,7 @@ class statusLineEdit : public QLineEdit /// Set the edit timeout /** The edit timeout (m_editTimeout) is the time after the last keystroke when * normal status mode is restored. - */ + */ void editTimeout( std::chrono::milliseconds & eto /**< [in] the new edit timeout in msec */); /// Get the edit timeout @@ -151,14 +151,14 @@ class statusLineEdit : public QLineEdit /// Set the stale timeout /** The stale timeout (m_staleTimeout) is the time after and editing timeout - * when the edit text is cleared, causing the current value to be the initial - * editing text. - */ + * when the edit text is cleared, causing the current value to be the initial + * editing text. + */ void staleTimeout( std::chrono::milliseconds & sto /**< [in] the new stale timeout in msec */); /// Get the stale timeout /** The stale timeout (m_staleTimeout) is the time after and editing timeout - * when the edit text is cleared, causing the current value to be the initial + * when the edit text is cleared, causing the current value to be the initial * editing text. */ std::chrono::milliseconds staleTimeout(); @@ -171,19 +171,19 @@ class statusLineEdit : public QLineEdit /// Stop editing /** Calls the editTimerOut slot. - * + * */ void stopEditing(); /// Adopt the statusChanged CSS style for the duration of m_changeTimeout void setTextChanged(const QString & text /**< [in] The new text */); - + protected: /// The focusInEvent triggers editing mode - /** + /** * \override */ virtual void focusInEvent(QFocusEvent * e); @@ -191,7 +191,7 @@ class statusLineEdit : public QLineEdit /// The focusOutEvent ends editig mode /** * \override - */ + */ virtual void focusOutEvent(QFocusEvent * e); /// Each keyPressEvent restarts the edit timer @@ -206,6 +206,8 @@ class statusLineEdit : public QLineEdit */ virtual void paintEvent(QPaintEvent * e); + virtual void changeEvent(QEvent * e); + protected slots: void changeTimerOut(); @@ -333,7 +335,7 @@ void statusLineEdit::setEditText( const QString & etext) m_editTimer->stop(); m_staleTimer->stop(); - if(m_editing != STARTED) + if(m_editing != STARTED) { m_currText = text(); } @@ -341,7 +343,7 @@ void statusLineEdit::setEditText( const QString & etext) m_editText = etext; QLineEdit::setText(m_editText); m_editing = STARTED; - + emit editTimerStart(m_editTimeout.count()); update(); } @@ -356,10 +358,10 @@ void statusLineEdit::focusInEvent(QFocusEvent * e) m_editTimer->stop(); m_staleTimer->stop(); m_currText = text(); - - if(m_editText.size() > 0) setText(m_editText); + + if(m_editText.size() > 0) QLineEdit::setText(m_editText); m_editing = STARTED; - + emit editTimerStart(m_editTimeout.count()); update(); QLineEdit::focusInEvent(e); @@ -375,10 +377,13 @@ void statusLineEdit::focusOutEvent(QFocusEvent * e) } m_editText = text(); - setText(m_currText); + + QLineEdit::setText(m_currText); + m_editing = STOPPED; - + update(); + QLineEdit::focusOutEvent(e); } @@ -388,18 +393,18 @@ void statusLineEdit::keyPressEvent(QKeyEvent * e) { e->accept(); m_editText = m_currText; - setText(m_currText); + QLineEdit::setText(m_currText); m_editing = STOPPED; clearFocus(); update(); return; } - + m_editText = text(); //keep updated for return press emit editTimerStart(m_editTimeout.count()); - QLineEdit::keyPressEvent(e); + QLineEdit::keyPressEvent(e); } void statusLineEdit::paintEvent(QPaintEvent * e) @@ -439,14 +444,36 @@ void statusLineEdit::paintEvent(QPaintEvent * e) style()->unpolish(this); m_valChanged = 0; } - + QLineEdit::paintEvent(e); } +void statusLineEdit::changeEvent(QEvent * e) +{ + if(e->type() == QEvent::EnabledChange) + { + if(!isEnabled()) + { + m_changeTimer->stop(); + setProperty("isStatusChanged",false); + QLineEdit::setText("---"); + style()->unpolish(this); + m_valChanged = 0; + } + else + { + QLineEdit::setText(m_currText); + style()->unpolish(this); + } + } + + QLineEdit::changeEvent(e); +} + void statusLineEdit::changeTimerOut() { m_valChanged = CHANGED_TIMEOUT; - update(); + update(); } void statusLineEdit::editTimerOut() @@ -456,9 +483,9 @@ void statusLineEdit::editTimerOut() QLineEdit::setText(m_currText); emit staleTimerStart(m_staleTimeout.count()); - + m_editing = STOPPED; - + clearFocus(); //This will call onFocusOutEvent update();

WQvoROGw9JdyqsAW;0gBUILP-e)+DlUrrG}tSJaaN7rMZ=nS?w#ExI+j<-q+ zw^{~gS$JH1AbfbBwqy^k@XmQ#Hs2cnc3u#l z=M|JjuG@pRq@|Ht>H`=pmlpm4F2Ce_Nh{1Es4Vd4XD`@cJ^6`F0WEuu$7221w92Zx z#$cKZ`6!wPQg~b>Rz*ihfqB-^f%1K+R>cy? zN>65}?SMg~q)!&R*QA{Uw#U`W_o9xSf}d+B8- z?G7~U z#)XkqDHn!YwJ2P18n!k9C74G5-ty0i>L!M1p+qMo1OTdKaQj z>;Z_F@5g(kOlsliF?I%SYW-iB%4&E~IF~@n@lhAPMcGxI7P??pb+b@j`S+>V{DCE6 z8|8ByJzl}!GM0nk4CZD|pVam&U0^;6^t5KCoj$B*IPEOB&}OJzHaET|a(eizIccB_ zl4Wnkza{x`m5Z#3(`kk?3W_G3jVEvvxC}3{X5v@ihJ|~!{KH{5)>6zBc|L^Fd1Z0= z`aR*Vf|y*)D4z=#aZX+!e9q}T3+LVz3q;RpW2erQUl_G!q)cii@{-=|lNo+vuOU(p zUKBn%(lcWpTH5EfG!2i`715^VKl;x;94x@gGoF5q-Jm$dZAWftG`+=s&=Fw?M1k%M zUbe@jiT`epEx)HZ;{RYM%9jG{r1xeZ#(M|k2);mkmjvSToj|;W9+2%WL;HMmTU*GnElyq<=qI$l4j`c7t{gf`;pE!<292r~Xk zkk6ZK|Gj(;BA=do_8|)WSMvD+1^+AgEM_+Hr}Fs@E+j!dPoa2{d_EM`6Z4rj9!-+Z z8IdOBb3bl2mXGsxgm0qDw;}`#E5H(qyo8V`-`Z~AK1Z1lM<)DpSq|PS*9F5}a`@HE~g$ZYlA7}QINOV5NTNkN7e?YtLt0@k|EQmBz|DJBA!oAN`dy%Kvk-oiZ$i!#HL+z-Ii5I+dMEyQ?1WYW(TP?PNw>G%Joo4!R(*STD#Ese_ zF*&};8C6pRGeDppiQttpFc3{c?U+?j#M&^Jp|>9yEX1sSinRK%u+C(pyn(^bwZLG9 zDgoCC#bg6p`xSp!mh!xoBrC^Dkw4T9>2x$mG?N#r z01e4=k~UDXDko4n6Xvr^VTW_4x8sE>{Vdzd>bw$5^SEWP>IN?!WA5k7he3jn0Cq)b zpb1ref|J-HX-elC0jyF(RKnV!;_^Kiw-4{Ut9VycTFA!VW})Md5Tu4$(X3-VG(MA; z$gMowLR!*_X-O+dOQigFSc2z%ALV8!Bv|%#e3{8>dxfi+Z+wq@L#G;@G5*L;=~=k= zwx8_iJ?;42Zt7xUu`0M8Cq6^_fls-gQ|u2UL^RP4ap5_{LBa6%aH^lSMsJFCdu^VD zug6rR9NKPF6r+@G-B3@2XltfOAL>nBICzkq<2Os7VB1TOrsrTl%{Sh4UfSqiC&02# zgs^553qG-A@sy+N>J90^=-`H6>V{G*_l$H6RBuWvP2CiT92_WIR(8bgZ(m|MLQo(*u#hAaE8DY(WsOm@&WH zFDIAxvei@Q*+F=~Y^IsHSSx@8JC82003<`FianE)Ost6HIB-0^VYZ^}VFLE2_%jaw zG5XwN-9G>)9DQDdV{EUOJn~q+J?O(h;J_dT{X;P%$Qdq61-h~qMSEcZZEc`>+j)W1 z+Q13`fw+T(zm6-8ZA4qpmsLIh1u4})bU=emv4)oiQ#Z=$=rESSrY;X+B`Q`!Kx3s? z+!@7A1dwoT5HA<1H>5$ZSdtkmjDwAN`I@=b z{rnlFp5f(`O#x1Izv0MG!wZHx2Jyxh$-}4wU!wg1lW>%?Q-9}5k1w!R*onVCV_i2s z4Odv#T~BK*R95Bd5Ic6l=!8Ysa3QdQRd)4y$Y8x4K_J9Dpp8Rs{GS(lkVPTRK(zfS zu~9BAtlkcE*c+Izmka8w`=efc1vnpmGwqau+|cY7K2*K7s2-e{2z(`n9C|qpWp}U zC}Rj3C8`yM^*7a5;O*D1w1UFVt%^SAf&oP1^07RDI%VK*1;V%}!2*jR&@Yx<7eU41 z%P*(NBL=X$=9PwjHvTRc-X1>)_Ek|;b{nSHkScV<;*8S5jl{V{M~w)y61fxqhXc;o zj9}sZAQmZG=dYs89Kj`(5e#&JQ(Y<%7H62oI40O(zt{r$` zc4015x90|AF;{;$9ZpYXVktOq_JLW!$!Xj3$%-*|&}P&tfiQXsl14p2r%p^D%$|%?%LnZk2bwlznlzHr zHtJ{mJe?S^3xgklBMsgY2%i=R_s6Sn*ea0>-V^IBBxAzu=b>{bWQW@~KeN6bxUDS&$p+1BE}KVrVTNm15*n%D_-sxDfpioe(P=SC*X; zh@2gWbjk57H5hK2qfVQ^PS_UfZs6hA2hlS_$Ch?jX!>B)m?Qmtuxe~&&u|s{-_7WM zh!cV69YE0+=CaE!1gBPICp>^GbA7Tz|B`Z;YU4*ld(r@CY@WS)wdgV$JOKT*9zn#! zmq?%W*rgNqU|#$*0NuE7VMvvRPeV7!h(B!nB~=-S{2hjkx#~iEp@G%+dQm$}`)tf! z3xgMq*9^i9p2#Kc5Fqk}c~+{|}IaTKxGuHJ&LrSN@FwY}mu%*Nrn5i8n)12j13BCJ`$ zs~1Knn^p4S{T%*-2%8lr(eZ>&$)P4;F;FLlI5=US*ArhJa?|V1wv7+ z6+KVt?<>VHBlV(a`!kWm9Z(t_-4IBH%ly3*emW32m#Lneir4$S;k7#k3Ks!2>}3V* zrHd@4V-kkO(b+FY!wgz#|5&EO^qR;s5M88$(}lx#2g3`w-ex?fgbVAf=ySM8oGx#J z3RYlSzzQtF|8=ES;P*iFkLiKbtpUtv@Qn!uw(?bgRk;&NfH2CAp&&3mN)ki3tE_dI z!goUzhf^My{Ke}!PW~=LBnC6|>TixCULK8gEED~eoqsM?gvPSB;nxD_%%Op&)$aifE^cxUH zd(7V>tzQ}+1iY)P3P~ZuH-T0N{pVU}7m5ty;|F;1ip6XM??1w~a;@lIRKWKz;DL%5NPvB)++gbOltScct=}b3uDs(oOcvfj7V0#jM;-Ki zs&9RQ`gSx@ABtIFZm5Sm4b=C`n&&9K(?Fsh?VD*;9t-&e3%8Wr9RzclF}w%}bJ}J( zSc>sy=NJ5Ir&K$)QN|*!>_e1$l5Owts_( zXKESlM3WqjpMh4W@uOtCi0vTVaivxH1x2NI;qo~?@!Q}<4Atr1u;kcz2&~REW~=(A zOhTY+0?>YxGw%y}n&`y~3J9{GcX! z2A1D=<9!Z`@vYXSnfP-szE86b8NkmZO0tGo1JZ8+QP2^3zWs&p{33o2F#v^RZ=W^T zd1v))ZMhqdtW%OLdD3OR10@z?+n&~GAcgZaD02}SxC}%Gek0XdJDd3M+nXuao5eR_ zZ1BrMu&tTjj>ySgdwC9DM5-YZd>|9TWD$sr zXXE3?Wu%mSujidHR*UAJg?;VRx>0lxSbhyZ*aEfW$>sa8Ts4P*z$M}VM3LED*m^X7 z!n-Kt(nFWQHP zuPHejUs7uOm-;A+RV#?Y(F;KV2_ZK*`k$W%qv=a$(C=KTiP%Gfh1K|sDZGLNW&5Ot z^$p+q%m?GQ|E7KH|5=jB0qR$@8jM|`3aqUu!K4$`+SHbCCNHI?WI0q=vL4q;U)Mt) z=-J^L`%s`zoo;JEY%bC`$Di;XGnHWUx&qk6Dz*@e-Z)TNiJYH@Zg&9wU&#J-X3awT;1K#ajBgLrg>JPH-r z(b1z+F~CK7^$E*feHx;yW6&_?#kv8ebKU{x?)tvS#7W@L+aJv?AD1fzZu|+ZixRFO zJ}hOt6h?vw2lbv`fT>@;99b$qX4q)GUj%OzA_KSwm+n6_i2)gI|KSITc=u2^Aft>o z$5Y($@$H%7UAW3nQGV*}d$=&bd;+BL`uiSDEjkj?YmTMEx#~IH`3~iHB*L#7FV3{P zUYb$X3TbPT^Z_G_*<7g6zt-?G{Ybnka4^Ab4+DZLceI3L>LozjrC2Xe*cB9&U=m^f>$bGkYFk@rt(CS~we^C42t*RJ7ZI&eZ)mOhtWm*B zkt#Ls_c!NxcArfE^?l!blzlGeIcLtCIWu!+=FHI-)R_~G$uWRqEYo63k*^z990%y$ zt(WVwjXm9NUJ7^V*=#=Bn4VS9_V;4%s7vq*&hz5a3Ossl{4ym?V~K}%vASR>&p!P3 zh56UWhgXoljQicg{DS*k``qsqzSnex-rVj*pXA&gMn`p%x_pKnj8|s9rf`nFs9&-% zHy&)x?AoPx!C;;lypj9&MiMUAhll>0-paRm`9iszyK=;`9yrz z1$q2r6_isD|2pB}8o-m$j2QQl|5MRSbBoZa%$95Q&w4U)J{GCoqtg4i4R2@8AJvU7 zia%yNGODiJuDk0h{NF13&6K>_5RA`2FNVCE5}Bs7rX?filK&HN85ttQ5T#*vt|}lA z_L1cHStS};xc>zH9m^xrKF!Y@|4yH)^ zQ*=BJ*A~LbBOQzMEC<`_I|JCT2&{{Am{l#GNmBklMIUIk?H8JDCl}7PxMmmy2_tx! zF=v|gnQz3SKT!k^QD*u$9w&XEu?$_x=J` zr<2(OdE~9Qs9-kw^3LcHwKznNCEpFv<4);U)HFH!j|)F-`BE!?Tey5w{GEMAaN1dj zv~B{Dvh5U*eni{($rH$DUmhqzwXBEC4U9k3&#{DBle9!FC=8;{SlLwhSfB7C+ zX%5hsrt~;JKdt{W(PcQtd0?OY%enbFUhjvd%C_^~ViL=v>C>R%Ghv;fNIsKGk0lP5 zL>Bv2)Qv*;`waS#ZqPR{iTsS_kId-DiP17Pd1o;&-UlEjki@sl0rPnjnY_?`J>T46 zGNYmZrgHX?;n8OLvt9=stfDq~XV9LUqCmzg`N*yo$1bg%+h5$6j=I38kjS~=cvxqlRbBkzi89#P|EKQ=XGY}vzvi7GiDe-d(*xn zT<4LUqsK9g22pPUR*0VQj9Tt4`4SKH2PX1*Nq5O`|1khL{U66+X5=eZxrpA(k*V1h ztA0TJ6`b&x`NKjPM|Kc#5lxr;h3}%N*A*C15yZJfQ-dmbwb))U$lesF2Cap$t9tNr zK=fYp4>0qx6N`$v+wD{eoL0ywSP?{& z{grrz=zFL9$nlrP3qBh^8vYr}zxwS^{h;#f6Bz}k&tz+F?<22`zhGAn@z>kJ-+zk! zBzIPx_AePD>T&VW>1iwv6%00IsnQ=@o#&30rfpi(J1y)(=#N?lV4{Gf4MAJmYvqpgGcrr7#Y&Y6MS|u zfFYj1=DOPX>ZrNM>g{8H0Zd-y$P`(&+H|@T3eLZqwOTCtCf+V zKHcQ$!Ndsqu_blUT5K1$6w5X&gNpt27Vkw|Pk~61(IDf3g_~d4+nd6;GvN0Znd_i% zzgGRkDY3}a-8$M~Rw;5x@e!`J|A=&KJTfJ_oxl`IlL5v}Bb0W?5Pwhl7}7;(v3k!^ zC`g<7SjVEiR^bAw3Kp_A@D4OI)xB3AnTA6oHD|iQ_RGdDxM+4{$f;4vPK^v1&oWv= z<|GmkHh~cRGD?+`PbNPD5Z|Z6wgP8i4_uHvTW@LtT@N>Sz;qKfgsi_B+c!r5Yxw(+omX1HhcOdGjgxdGg#4Klv2=qVY49 zAO0E3zk1GRgXg}TmDd?4<4OyoTu~>_g^iD^!DOC**d)=F1S1Zc!UCYAAae3U1Px`* zCI^SY*VP$MUxbT%PDN8KzM|ajkBEOJ%KwlfI13I8c7DX&&X1vmexBcx5ahSiOyC)e zFZsLn^^p$k%OJ?X+2LhK|JHqq&zZe9G{oXBH>G_0OZ`Itih8wwW%A00>$vnjHwB$h zN5amoh-T_)Vir&!TZ8fk5yzp)WA?iA9!k%Lcg+$O^#F0St+7hnc027vN1t7u_>uI$ zuc98r)3Yn$>8VxOubZ?&-^1_@lNev&a+r8`-fIr@dV*aQgMhz+wb49)K zJRf5#ip2)1%oPf(e##A5_Y}tZ1fL2uHyUc>p%~bN4p^*k3>OuGTQXkz;f(WC?b*C$ ziIK0_oAxb%yhhpIW;qW>?)$`Pa%u8yr0qi5tvCDDh(~q6mCR3Gf(b=^**Gty=k_Zw z-WBNSaD2edaqPKkq5aw}8-Kk3!w#(?;Mr(|=f8?Fehn44v00P-J$A1=Kk+xlIZ+R7 zomrT1s|rn+JQB!}U1F(!quyvehB*Yty*>YojKS9!^?jL+E_h8i>^t97m$bJ<4l&}P zq#m&03cB4JveJ?+6kxpv^jhObZ+Ci)XNC9${PmDp`1dE|gP2EqpPUau7Msc036#z8 zQ`x7>O|oX@)|l8zjoUz@8%A-83D#(=MbZ#us(y*DArTWGb>!(?=XiVrSPK~YaY9Kj z3OO536uVw-{c>h_vB{^G7A}Gf;cq36W|ecwzZto5w1q-!MLM#A!!VX#F{*xz5E=mM zRq&o1#%RUmPYzZ(7VGa#WYH0x0%9s{TZdjYXQ>uoH2cmgI^`VuC_JcdLGsfiERTtj z9C;V31S)W8{gQ+ER`mS(gJNagYK9QXmYMo>xVekrXEU3&;;1){Nd7trm&k$sqXKfs zjJe}qbp9_?;~it9R6s8Z)=#Uz? z@%_xm*k1T4xvkV~dO{svjoQvv%l)tJbYI>7hBGm|4bLTvKm*%pCJO0o#L@JtVaB)A z$TVxD-`iFybyo+WC>FY|f-8DjmZ?$n3k`aNe0(7XWxKmd4k~vUCFAL1j=`md0wnUk zVC;4kpD|#)KQgio%Fb++Y@<1Q1@67f$Tv2AB7E@z_!N1xBk}R4GYr0uj{Xer?G=LW zk7x#c;2ZzR@ZEuymdBs`k2`|za}K^+KMQ=9g7W}>NB4*C;TJy@9*>}fNv>Eki(y{6=!BiLT-(wh{w&0Jb_B%nYucg9Koc>T+Jlus*9#Z#ZzQ9 zOxH$J)2pJH@8O#GAn}!GYBtXvQxdi12o16S_#@sx(t zm8H1CFE8!+RWN^Clkch3vDy)P#tB=SQfII&Hq#u9vHi8FdR=4js(5v$_Fky5$TjCM zX>>QDw?4JCt(%>(`wu)lwf}&zwU5tuD_h4~xHX*H`GMU9YiogjjD_beur}x0Vq-V=*sX_u@7v5gY%My9AUz;;I;-Hp?2f@{UXvP- z8aI}qa`xEt$zyBBja7;qpI(;Me*cwG`p@n5aG`{@C`aXwr|%kNwxe5gNHg&}(P}~? zIbAJs7e4LP1gj1}-Hd!+XFA0*mFr!^-19vxrmwMEKI%eay?J0;fukuaxNM=QMzX8d z`;Px+ntQV$|E9@*Gl4glP+1NT)&7c~SJ54OdAJox{De%(MA}&m=SK-lPwv@s{*;BW zwnuc6INh3h-P^{Hw69Eh&W@s8l#Iz7;_n}cDsu$O_a&Z(fwLZ-x>beFs`OF~TXnk) zLk8E|RQEmB+V21~mj0umC*`r$WL1-BVM%%QWFmyinlcxZ5xO+6Om+@4nQS(~*o4s; zVt$0y8W($4_^la8@yZRUMo+E185z>V^_#KUP07^-jez8Va!!1i;If6`{1*)@X)DwV zQ|Avp9V)}9{X$dfw+10PZvS;G@s`=u;3PNy^f_PM-m})mFPfu`J|o|@bwFYiTIfL1 z8!H{(BIncdNGxWfd(u7b8Zs^dl?Qy;TxM!KkC!aol6wqgG0h*c1 zV5y65mTC?V*0mX(sT>(t7FCWk1og#WlXp$e8^m%gr~%bOrbp_wIZCR&>dcb8m^KBlyXV=5oI$*M{QJEJwI+cXVM|-fc{hXfa{gT5Zbl`ePmh{2<$HH?4FI z>z19jnK|HmaT5?7xxb{DOQN)fxv$X)L-ti1A0t#UbHG=P{cQ5SiA={x2T3cta_q<32i~c54aHcE_ zV>jrJ)^@dnL;TI%6OrcdpW3>Lxe_OmwtGG#`R_3GUNcP&hVR_Q#0A{9kLH1Z4~T)n7vEq=oKteMj>lb zY{_CRPMl}DrN%oYD|EgHM(cZ@+L5wz$f-`mu;vN2TT3mhb86v@@j$w)$-Z!2Km5D( zQ((i!BJR9%2m*m;_BusmBKZbYhJbahGg7rFa5X)Bs<-e~AjR5c`WaWOIA4lg+fF`3-RtYC`&@yqPUp*Z zdUt?`fYi$AYH&S_>tOug7uUW71;7D9E(VfY?0M}3=VI8^cQMp$-@lNa-{<_plA|`T zKMC@?m7Vyp8u3qp<8fsY8i<*>i!Bwf7xD(GbeJrrQ?M4l_xob69JgMV_8TU5 zv+3dFUig#5{!G5!bp+-twhQwarn>k(!}lC~&{H4}6c6;~H(`qX;(@OIdSN`!-~UfD z1j*q8w=Q`g`>n$9$QJ*yy?CG}pVg=R;(BP3NT$v~nb>SPoqv`J4yFP=PYx%t;B#E-FFzitPr+4t%74q=+K;`HPL}QC z^%YWsy^-8ZKASH$e8YW-2gb(nVS9bqX{?QK6%i3;1_9ATs^o6UMursiJlI$Mq;?+P zM(Du>&60V;@834m7Wn4z#AhU{L%D9&Ql@ykV#zLEC5NA>DyhNV*-{D+z}erJ$aVTS zWrw@^rtGY~dmx^^_3i2E^Cp;#-MFHh`7=3tSfhBl_22kiy5w)v4_WT{!bd|H)Q<$> zDuXve9y*yyQ}Z{2MH%<#8VMSXU9Ea}C{%mq?JwM&fq+*FZ@pkm+6xKv!U22{D<{{e}1#U?>(;NyL*b8Zi9xGj_ESD#WVSdT&Gbn!9GnGk(B|zuCJ{;xqTyA$(0XCKz?&H(lseC?yxc zxuPAlZ((Kib{iN>?-0Anl!S@Wp1x>^9{LAoV@uWdspzg`pSD-?lANkgK z_E^W$(+Xq3q(0%Hl85IkAr!TxLZL)uatvzY6Yd{NzWh^BKQ231($>hVui293Vz>Fl z_O}!J)ir3a)KE|UApPE>1(sG^z6ma*YsJ8Bbi_(uT1x)%fnt(N$;4d^uToRA-EG*k zz$8_)FM`*Y-7AwGTA;i*^?c1L(h7!wNcl%2_#cq{9-i>m5YP*q8Jp(^`R%=3Nteb~FReSDoZ zxBy>g?-*Z?6yWP};VaT1X}o=$9RL>)&Ms&wz}YY3v$Z!>m#+qo&qKV1$8%Zc1@vbAF^+FR zX*Hs&ixcP?S{VR%Fb}&DXT_^G`@|-vS8fuLAV?X|^Tc+gL!KP-AaCylh4Ya3Vw5`t za8|RL3Fxi9ZCh^w&3!yN=ITiM_xToObLRKPE~rrcR8rc7kr?UFE_V=F7tGaM948eA z^YwDg!0prF7Vk|FX>Pt|CxbteyFjcHXl%XOlgh7eeNP_?8IG-cY6Tr;s8Hcy2VN`m zs}7a=9cyOol08Ku@*0NYLeM$%Ei>lys~C|}fFNK38$$NrzjE!?yME+_8=P+By_TB8 ze?6{GwD>3(!=CS>A7oB39frtKQck5yYEN+!*z_7{1t>FHz3YupT|_h%359+kG-gT; z8-$rz&UtekH^O$i5-t6Q8|}-|7Oc}(^xSxEWd1xG3(c3CxZ3WJzx`h~Zt>pN zq{@%`nHr_KG5s3SDE)2@qx2if+q{{KmeiO3g#F98@fmRPcE;zDcl(dePovu#pZ9EH z7mm;T0iS7nUMd`)ALhnq@s7slG!hnwf`4M%IX6C!Luv)%GX>(wjnC!B3C|n7AHMIj zi;#pMTc(ZEii#YQt3M|j<%7U}78f~znWR2It(c2xb|6a~`z0X{< z@p=&5G_(M4S+cP{U zuNZPAbJDw^k^8?|H)?us;*AmOQ|sJ%$zrYSCgg7==n@#{gfe5-jY^dD7TCvJ&rSn| zV^D9F3ajKjV+SasS781O;{ANv#)0I>#QFMyLU{M{}L;HsH20@Lh7K zG1y4zeOu5M)?Gr~<(=NMqv%1weyc$2GI2s%GpZP})T?5E3sjf0xSx%Y(_F-+B8lADeIg zJD;Wf1+p2t{*U?B&iX%c=lu`0zt?AJzck(3nO=mzh_4D z12{CEF#rhgcRz~hcJT+je-b?36AV5)_kFOl@f^2Pcpe130X(Pve}Ly@WuNllxnZa9 zJU}K*agdPU2;rwX1kXz-e*N%MKViiB2M572lO`;#kAg~>I>3tDx z&pv{)Q%2{ub+1Oy^m@MoI~*zAn{U?;YmzRV1qKeuiGw-Zp__sJ&9=V?w#*0c9 za0cI?uN3tx$mw6C1N*Yx=&|Lga_yl2yK~xh7cWzK9c)8`aGl|hafi@dgZQz@rF<9u z_g_|jAN8>xQbWi$MVh=fi2RxHpt6Xv3Yk0&t@ebk6rkVN$6VCMmb@9n`TH;{N~Kc* zsIn33L%K!a=<^;I9ZJ<}f4&5hf9jF!@34HDULY()I=;*%I2LmGe8(8wE+${Fr6*=> z0xz$T%5GO!4Mr2!5KRrLBoz?9_A;08_+6^DT3!AmmYp4sLo^Ocxtzxm4rX<(3CBRP z=(pg@?*OK$Ki;>crQ(WgQLJE`^l1XDS?+t~Jw8Tz66rS&wD0*d<~?4ZuYDnGaVpS#Z!KwV}KOEweLpS z#~7eLu9Stz5;&xO>^@1gS85gACt%BbedKaVxBFlG*p;e%Jkq`%p&chNX?qIjwARP2 zOwrW9$lflOGL9ft`waFPN=5@VJq3aTs1~X_-YPRhsCLYxgw^ zez(j-WM=lhu4zco>AqRFDoD$0^Y>$KwFzO%u}PuqduTVzKbsw6E9238BkO}XvAXq2SC^? z3FT$JO{#gSD+)!5)PfJZhv;6xTW`;fG02Z=yaAA6UZ`ruQpnBjQ;kaP!I_IrSni?3m{8LA%$p|x*EI+9#u z=NW1oykhZ9iu`$(^wE*Fx9Gx%-o=9wyQPn-PmOw*DOt35K*C@>Zc1Zn4{S``0~Qx2 zh>IC?T>XMULS?KaXzlJIo$bs&xjvfr; z#V6*OCW)Wr4$ZBf-DK6_@H4GJ~)pyqkR! za7L`m9tN)x<5&Vp@(W%hJQ}SfJNV8E;c{UXyv!H^@Xu|L{cU`p;bVv8R#85_x{CTTq{l3?mJw#3}CXcgQ%G zjn2#CSBg?T)Cf%j=6Fm<)*+j4d_8@*JB6Zx)`O$4+$kOBN^mnh{bVyuU)DUK3|Z%t zb{4jCoF27ZRaBhVbHz+>Cv$(-5kgRb<=_ys5F%<`l1VaT4_Z;dC#q&B)4S((?|D!g zQlNtMi}UTXkCdPhZz^b04o;UPS*DXh{n*)q>;1!~3JvunPpBR9IvZ(Rmb%endhA+B zKSz(*WY-7U^?P=`zg>S|*RtN%j`@h|cxL3E?-42Rci4hq%A6WzJ|z(Z?UPcDym&x z?4sF1>dmN&7t@XiTl*5l@eko0^Go2soCe-2#=3A2<#EV?DsT1G9}CTtmiQ(tTW&BU)!&oj)m5$i+oe$tPls6ESmf46XR?26HCaMuAP--UR=?|M3!*eA|C^Lf<-%#iTOmYmf;VXM)SA|;!;h#hYI==yK zz^-jJf-rOAnL`%cO~)>P9{pr=Yg|mP_jQq|;=VU|O6|^5zW}G)t?`c5+rWLj$vZ^1 zOn95^>Q}Dejb5z@a%~jf+MAr8Z}=P#>%Ga`4jN`}p_~7<&<)|^c4;O{0YZPAQcmHG>in zhW%f6GVJiF$14rAc-+YH7*P>px-Pv`XK3Mrfw zBrmU$ZdXP)LULEdQFUl8>llzyI|gL_Jz&foBXc8HD2@}DZn#k87*#RG7xI7G@`ZYp zm(wZwvWNN*&(ERgz$EHx*C218#>p8)mxx?4Blku4YSeyuWPSvH;a-(O9(r}PUco;x z*#-Rb3NRhbubvgbb+LhEn_S^nwzE8r3HLY+_jOWAO55#mYG!)yZ) zzQ$3|nw<&M0Km|w`hxwM)5yYstphX`7f~Q%E9kWTP9$8GYA$IJwZRO%$BbKJ>BbD^!nGlR)1ucI;NmME~^22z$Hnnov+>{_8jXg-_CxeL^A^R zKhjiCMOlYNWDP?>x#?gjC`miliTnuB(G#kYtLv8=>=b(dvOylrsqm&*!TQLLAL;pZ zh@YUpn6^XyBD9yn?C?PwN4qwv$O?}DnaBFDckW!0QGEoctydnjs^>uE1IznGbxl%D z>G}r0twVcWu=z<`d%=7(bs>HAD8W*N{0 zBxDpw9>!k9sm{`r7Guqq*ZaJovaOqlTZR1{+HX_7qFUKO|{u<2; z+shk8^qkqLWxG zWJbRKYn!ecDatB(WqF>%ti^~E$S+^t{D;w{W=3C^{*ACki$})aQCXg(p2kNltF zVkYJUv8|xi$yPWEcGs=tPId^*e{#MFCqG}^CnP`NcF~bIiqa zx6Lgd-~uFq_-^|u®cR7>t&y2(GZNKrN-C;jr7kj4`dZVM2b3H>r5U8w=%ylhHo z+nXgsLWvoriGxB@Cj#tlm;`u5-3=}J@pB|a9UgsMCr5ua|I)MSP)-$ZGIx{(prN+x z`Ll1pXMY2F7}wht*|^@tk9QoX%G0mD*En{MYr)nIO0nG`I?E82vz^8I+3zC(*3)Qay@t${I0&j0(j%(zfn0MekQ`N|H zJK+6WG-VUYhlYG;xg+4uv=ViFO0d{K%DFneWF@}Prvx!JgGp3VH&qE*>)?cLJcE3# zlY9S_)4$OBr-sKnnwj4U>^XX2)c^Nz8BctSI+F+*u10++2If($N$N9rMP*SyEE9sd}TG4fNU3~l(g;3*&{DiR+=2vi7}lHRa1thfdSvC zifYpogHcB8kyiCI$KDrPwQU!jI-?ce z_ZNU1_D}B;D}KJG$=5?T-<}Rz<~|*=vy38AE(#u+7n7}p1rJxLWLsw)8>SOLKRWa> zxmf#`f4nlp1AIA_+vUsAM(prCjDH8RVT>^5#8;dw_)B3`iTh{+oP?`S{Hp)6SlYzn!B!xuP6*JO#m{MPol<6{p&O!_;~jTeA> zOD2hmv{j`>-9Mrc>A7ykfs%t`v;;GdpHDvJrk>|?XIV{_{T%-HY>v)4vnR0V2+bZ} z9~LjE9aoxLFGZLB;rH$@mlN$j;|ZA-U1;U8{r&ZFK*uv*`Z`A?aw5$OJ>!f%;u#KE zav5NL_&?KGns_8akOkvv_vkntMg2z?xkn6aC+7w9BydJco$$un^Tb`T+7~CE4XAE? z(AiY`8aKgmp>ts#_CAn`TE1x1Ld+P{a`=dqJ!}2CKfv99HuW3Y6tHUU-|o>5Lyw-Y zM~Ut%YjI>ie*MU}I^6&h7aL!hMBaVOQ))E3l47@W`mGxyHNht5bN^Gw&4TfO^A+;r zaW&c<*2UJEXlfj~(zs@R>-e4SpL4;&Q;du3GTI?GF6yqERlJ4!sqTI{_Yb_pH4)Nm z`7$ogk344lEOI}0yPuWrXB|JlQXqd*#}@7fRgddhKc1X8Wp0(tL2fD%pX1+ylZUO4 zVDr|1G8A59gD;18d3AC(dQ{x=y7;U`ntQ*bSkE(dFVX9LU-#W1iZy=UcH*E}=bF6! zN3Gl0S-K85p?kD%TKUnu}&%4u)(t}gu z2KjJ{U#7$JoC_K}*nUR@_+>3x@Rutw z!1(Xz+`5ideN}6j=OP`0z+HBiLE-#!(YB9>TlfhtbV@vD7mLg}Uusg=;Jt zarqxPcTr8~s55+uXXu=yIF+&6u~`Qy$7}x^X}?Qf5m-<+b00fUxtl?hgSf?_3eMBp zeo+O#rvXKV+4>=xxw%ppP|$-Ny+^atgP;e+ZYb7)2MT)lu`4OQ$ivw>_}M@6*&X+M z71hey4Xm@HwVdJ$e5hnP{JQ;6s`5h!I5jHOSfm&NHB80}7enw%6$M?>qXZD>jZ&V? z=GR3J=tb?uKED3uJ+#gM#fmDh-QY}7LI+0q&zp0ZxLWLa1&yC6hRIm(L)9sf2(Oy6 z3;9~}Q+N27MS^wN=j>stfuq2Pj*V3lCTqaShdk8>+K?_avM2>ccJ7 zWK&ea_q7`mbNtwVKEq_R5fBWgk9`xKOMCQ8+Y7xP?XA`b3D8*i#k@P|YxX4rw_V_Z zO8MU}5WqUWnXuX3?8NYU3??KHk$?YdMiMW2KmD9ABC0ay-~`{hPczwP_|li#tmrrq zl)-HK7{C1(z8%q9w}s==EY%)Y10o#{0|4h75znI*?;nQ4e%Poi9u!sL!&kd1F*ueo zh7ir1rLK&uxB;$*jA|zLo6EG|9kLGFoHh+_^p>*TX>7+l{|>d2>!2mp-RSr~x8059 z)@z*KH*t|uOCufi>fO9Y#I^jaiSjm*qQLdX#Q_|R2z2)f#W)FsD@Y!UVd!-?a#B?B{?$vd{66LIDb}ktEs5KSA_A zeq_tYl~FSf{Hj#r-nXbs4dW^2&0scrFYFp9^_|)GF_B4J$iTOI$Vao@f6n45`w-V5 z@#g$xra=rvZFBN6ge>QuB;`rRewOkC`$5SyTxyUUz0^;PXU2SoM`U~Eh~HeM2JieK zW)$3;FPeF+sspV_c_`XJ5;2OH3rD?D7kya{7xmnSw};#Fl9F3#Vqz z7>UaVo>jaC!}g2=WAnDvofIibJ{n!}+|lub1dflBbqT?Y#=<@X?v&&>2)*c-1uL3XK zRwZigZc|i?{&ezRx-IG+Hs>F9w@vkLg7tB(y_q76BevU~jn9*62qZ?AKK{Y@S8n_H zBNgPi85sS5P%fRm7uFZ7eCH0!uX(z8kpEO#I-5SA{AwG3c0> z@095{mQ{Kti>4hF^IlYlmJveM67m!CmXsM~N~5HB3YXE|dDrluktj5BuuVX@5Yv?i zg_*@XtT4f9Ovx*g0LUo_QY4Vs%El!D67jvto4lC#Z@$uAdSfg|6)Q9O1Nks>R8pqQUA_wwVt z2${yx`&TNrIZpWv3fHUMkWA!J4%c|led@h~tg&|9_Kxw}`GNrz_84+DBgkUpqAcw~ z6EdKG^wZsvhZ9yNFmI8hCd-gkia&|0IEt6Ma&9f5B)q(ampw1*s%jut&$#*9yDs}( zC^^R;EMG^q);$`_ggN3yjpOL-UOe)?P(lOrE#yDd4#Alj`u?NA{oW}}=0v@_jCaB8 zJqfdNaD7bZ`f#rO{hs1VwieDDko-P)ZhLc5NJ}1D86B}QeR8wQK*{0knUXOo6&Z_1 zp{vG|e5_w07B4xE<*$*qT1_t63xqR%6$~wi_g0Ew!|1mT((md*nyJzn`V!=UN^UXD zq)W(48<%GrzG=|8jT|+mv0XYqIM_k{OM3_KIiZ?7oN=9$lcq#n6}*+?*!McHH)_mmS0tAkVrZyWU6c)%if^88+`+hJfL8ZTbH8&TI*eHf(uLJ_@b)w=80VdP0^w?MK6?e44*0?LB;wzAa#h z%$hqG^|Oi`h*kMf|2#Ng02H}`{+bzi7b%sz-%wr8)80d%EEw7AF`(Ld_EW)gejc8x zoxt9WYzKQu=9BJBM-^6P-V;_PxDmXQF=DixD0{^q;<}0=L-00g6o&R}V zjvv}Ghc!c~w|;Am%Kd!Fj>@n2*kLq8b;BG{!n8vi+j|+*2V*-Bms8GuoU@`iD-qk< z`(n>d4^oUwXs*6V$D^xW8^Bpou~i=r5OVSRzZ-4)c#m0^$J#!|450OcE%b={VxDW} zEE%NFSP(OT-|i+Oh~1LES?Y||M)BI$6Q2|O^zP^mmG*A>U*8@^I&@aLo69+0y!ivH zAwp#!1fbdE-E33z3^+x+cboGpBH?qUINcu zg?Qe&$E@!;JU`CIO8Ni#jxoH+Tg^gcM;Jb4TYn7CrP99Ka>_y_Ja?HLyn2&FJ4Wq` z-n3ka0@R+1>KNb${_~ajV6pOS7G=(G*-FF0d(XYzml^p0tv9nm^5wJJ@9$fyKPx^T zlb-PZ13qWurA|MJeeJ{l7x;V!F)L=VBT{|QJJ3`dmDm|RH+F!}r&tH|$LEV5t__}t~l#=`SPJ$;h@@`#48aI32rxpugD4=KMmG2%`c4_kBi!JHrKHcMnUOYW9 zL(xT=&|Ty9kxe$|pAGWR!yaj1Yc#db((|~SlA2iN(pdU=>O=3Re8T(bpYZbCe==DqpVTs#TkF^9y`%PU_34*b498Lhdi#fT?6q0CZb2-pkd5{b2@Ag)Y zgZwsUXi^ z!Ad8u+vrq{GShA7iMMI%wgPXgzaE!vPx3Z_@Ln`SEU7#q4Oab3q|Q|p-Z8q-;@OVS z?mND|de#qYFJf!xIh>(emCKeB0#53-0T;qov~5ngGE=lQ)D-tTjy~4bP*L2|GPxYsH=JRY*5xTD=v@G*dBN)sHTg&;njZ|o=qaf}6QMWo|4sAj}l ztl*P_dyZV_R*zVtSzf#a|6fDo+0m>F$Tm1CHk!4|j2Cj1<5x^D@J4sIRLi0nqD$C$ zHX3cJf^{H^c(m|m|Fg|@BfOxh72)|Mmx9pHt7GJxj*|To<<$SqsP-=0)w9m|Zz<*q zC{F$WvUV-K;mev6BhQ-)lgf-~8wI!9qHlBjCUtCT;-J*&$p3L=V^gP>hfOlM`DT+% z#Fy^BUF9&4k9s)x%UF8~wyQ+iuLN5%+o50hTULGsPo-QsIY?`{H}TbN_tOLohCe$$ z_zWW3=-tO>*u=|PM-?THH|;G?)8~q8@O0bkTtVjrfY*Rx-}8S9bN5H-{+@-%%@s#d z#JiO~5J(5Tb$b(e=NIhu{*M>wWVxQ7NUJ?R^wxsCFg>B~XAZbkDZ8L2jCr%UgbNIF zGs4ylx%tk1ly9hH=71UcLF4)vG8;Gl`oE{bOe1l%UOQ>+U!a~}QLdL1H6|uHAi{t5;Wxj?@ z_e1*wbQ+f1A0Yc6R);f-7ij6mvPX**kmR-o>>88zXp{F2I)8V=9@1KJP48(}Cwvt8sy@lmGQe5}7$Dyakvx1;BIw zXghU}0X;v=kH7U702#jSo-b;BpU~C;gZF*WvW7ft${+wTmbt9hJ0G?X+B>j|swiCX z>_6gBXXDI_JnIU19N@m3R9NIyZH6@4poL&`XX0uI&EH^uMTh0yQ8{K}ssYViN7kUb*LnNwtgo$Nxtv-mmUQyvd_Rfc` zWtEoK$@LWn`_E71dCz^`Fvd9G9}|`y#!IKojl3R;l-wdWR-GiwM{u3c#<4eb%fKu( zJ49w=oDPYNo}FFK8-G0n6H0yH1l2a^47KZqhGOl>@bxjmAgxJ|6Q{ZCjeHuS_tv?^ zMaf+#KGvWjz4qKX@6VL!!UZt7|9Sy=yPXUjttS>G59))msY03Tc6s?rH-&wYqR~zx zvdBiiq^u}ex#9%F*(Prv=>p(F@?L|X{dHXfi+X+qe{idLUzhp&yDG4zXT5jtTY3CC z{qp_%kuIfPBQ;n^47L6f!vfml1WuN$3()%EESbDFc~?=PorW4qAC3KOlXo!>mMV4z z+&xPnQ14CRnTu+&^N|=GUxSA#7&<)rsO4-1^1edBo}2ouw|1zH-y(6zheFV9ZvCXG zfh&shd2;0GZScidh&J~J(eTN99x~h3=>2^Q06gX0_-4U)%O1(mwH3lsD2r#5!*;9U z>A4kst!XBToCwN%7srWMa_v80^jNn20Q<=N-6gXu2}lZTA&vHtFj4^tBTUmu0^(hD zk`o0NFv6{)ixT+!wP|W(+hy?O7NBLA4RvGD@fiBCsnbN>~_ zUq=HgHtJ%^r3NZmsk@QaaBa3dr8aao8Vfg-y&t`b648*+r{649)FM;hK8Z63zq5cl z`0`@BH4iKff^PspG_!02jZIEvQ z_ThlUmn3I0!~e_&lpu6#UGfS5Z)nEIuzpJ9E2|^dujFTKKpUzRtZ#tpdz#AR=_%(3 zqmq-SBNE^?A@2?@3J03^24qDU27<*qe6PUjd@&%K5*gTgG^FV8m%tQW_j*M|SP;RU zJRJl(8*<>fV3Tw=oLE^f@lvM9G!fAPqSaZIFszML98(*5o=kZ)}w;-OJmHv1} zrJ=mO_Nizj-cS~~d6kSOueCp#Jd$TuU!RAweNv82)P?%U&D~i^PUC0q#WZ4uPMJ2NA~v>hCVY$BFPJcKbxkXIPw!IEn#hp4vf!R;x~fvdkP*L8sJ|&i znUj&;wXcTlFP{p&BYgNKhu}NcU0s?ZybFt)E^Lscxu=R1f5*jQ=axoONPWqSZSV;6wW4r^4rHK0bG6&IaQh zp`pT2KAR^2KF@R4YSX(XFsihUbMP7dIK@Va}y4wvSM?d@35 zP&HX5!dEI0S${i;syVjtBKn^hQ*j8&(339JUFb>=gwjfT@bFY-u z8Cco{m)T!G75=pZ(R@pbg#7vTgBLX4zCG>yZVa+WS9Ylr;354k;m7_K%Z{u=>C3IK67P#R$!%$C!pzUA;85wqxb&d*iA1s7_5K z?}^sZXyP0BW9=<4>*4fS%kVDbRy#IhjITh&%i;x%XWHiO% zLqYp`YyUZ*sONJ|9-0h@szZ=_p>DGMsDq0bVjC3fx?jZR9hPQ{hkP+w{xXwK)VZmL z$|nO}P)$mr*`Y-k#1s3qos7lOhy<104|KvZs8>2xl% z8O;^(nS(Ek6zTR5Zc(2i)hIgpr=p!;^KZiDyv7rxFmiwru_>HSEpxJz8NU4wDZjLu znIsK;l>Ui&`-Doj6qJ6-O1D?G^08WI(Ld9@*Tw|ZFRxsndc!T;>3^fHMTWFn0sY>@ zy>|y+GSiIg1>nPrtW;x>cMU=)CQ}eAoJ^}8b6zHQWlgF7#WVL--pv!v2i0NsY?CH6 z56k8SNr-umXbeL!TZ;M4*+0CVQm$QRP-yuuVuNzpUXU~Vx8cve=a{U<+TbXX*r9$ z;Cg82diT)v^||uh*+}U5e!1)J?Bv{aXLe@jx+iq~R_OZK(DnDYcKk+=us)o&)n6DQ zW=fXagP7TY;A4Y#nq$OlzLxz%%wnUrc0Wb}h5^50Q`^#u!}21>FT{i(NFtEEhp!_C@fCru5a^@KqBxu{8N?w9DiVqTcjH++Z^K zvF1kXvUC~Ua zssaxeTpA;#_0D_7FMu`IW>grEiwqE^T^QTH39xN|+{EWTntHvot1EH604d8(0+8*j zKlXfJC_7BFv6-!SB}*WjAVh+LB2wd~!X%~(r~WyLF~sszZ{;)>Ink`W0R%6U+`be> zgLWMQ9SU}s6*Eg5^R=kw07vgw{xZ$IsR^apvr86s+nt?=F{N~}PvULXkFcx>r3wW- zADt%glIb+bZXAWZy_+Me2FMbHl;u$C&N6S$b&ws$^FEy8{{{*a27VH3YQ%G0{i1j6 zQ`>s|Ojee2@tEbo{4*Z_mH7t9Ub-)@Kxz|5oMz9~G|kJ-V0|2I+cY)X3Gw>tBe7cV z&)n16irI8_a&|Zk7OV$u5+C?ML78`+^w$GmZo+*I|Mh1${B4`S25lTN>2pW1ND?mR zgm8IK9;O0(vW(sdJ|pe702?^1*ywQDS%A~d0H+WB-QjeZ<3nr|)r>WK!j24|#{jwp zU5qXmYb<|bEm3p>uF_2N2Fc5m7=v5l_noE=0BO+ zrZmPi5Cl z;OfngkYNvRDGPqqGd^^3w+GO5kWC9q_^B;Dd*}PZt?E0>udgLn-@*C%A{|wHY4jYc z{X6^fVO+S?aw)x7mk3bRv(c}oE?3X95=cH=t8$<`qp6Ud(_-MH^YonC{B!-IL+S!QqQs; zF<7~L6MrD-@E3XN*S-E#Yi_Zcv&hgKJ+Xc_b7E;UeV6R`tq z1HjnZ^9#pMP4mo@l>7?*;WpvK)3-NMky($@w?uU*4)T101P*oTKhnOhwld{$jgdRQ z05#wW?6s`hJDW{b#(2s1$w#8;Us!d_c_Pm5v(<*<2Z!4C59PZ!0px*$X4l~lo>%p# z8P@%*yEDOBAu7t=_}GA)UyN2Yc{;|clbMCSM<};`$<6nHyoUrZ~J?AzUTHM zX`P%YnS^iyD=KMNNewn-W{a?$F1g~LLyIKOrX&06cyDLXt>i_uUa&3Qdga@U*6KXE zdaXJuyo0PCCEt3^ec$3ZH{ltc>u*Vsy$O=&E8j;QqS0bkzV5|RV~17H%Bd7`U$$FI z-tV79uaQDzJMR3LK>!U#C(>S}j<^x3vJtxdZyKQ&lFzzLdI7gaDK>7sfY&P)@sV5= zbGQK~iCct|+l*5DVWo>v)}tboc%DCOmtKxhB{_)t(96EO)Cy`R^s?oz`aVQ2hrAM| zmu^syr&$j=7u8(Qp`Xv}9(%BWD3_-A7XT@6a|(bz(vsl0D-?;BCT8psXOFx9`G z&i!oer~CJ_qv^I*u6ZN{gep4hHr=+sp4vrJp={|Z z%eJ!S9I}MP;ciRFyuXW*aSSvzDgv!q_Mt`dhKCgf$FjuN{GdbkoX!>rY9MT8za_&NM%+ zBJjjnx|Yh41FWZWa4 zU7m;tHUC$-`40fO`41}Y!-V3---S@7A2vytX)_^+$Yj~zuC=<{$G~4^d^*EE2+S;N;ej{m1-n)cyf5iGy;D$Q0yVv?RCQ(A%Jt*-#;(D{EJkt$OI-mW7U3bW@1NpxYc#!{m8pg+ww-(@ojIuie z|2t|py=-UTk2TnqwF0-d^*P~h&Qx!cF0|&!G!S{=%s-P%A`iD3$sLzzUra*IMhhTK4}e7*Vnj}Jz}E4mIe6og!lT`r3f?%= z3Vf-?zWF?FR@j)rpY~KSmIbA(_OiD8a11f0Ulh8V>WbnI(~{6f_doZ~&a zSkcds_Mc&k^n-OK?l0_hET%*>bHft-a4Z5+C_Q0wr2PqMCBJ>7y@)TOsT-_Vx(P$- z1dx576;EX(KzV6*TH`&WuTqVhqbZ_DyBoLin#$R4kaT*v}Gsu~Nfu7_WZYJ6F%scNPIE4POuig13NV5&)=<$dF609X?d1o^&@($^)P$ zks-I~I{|Qr$?c&1L;}*#YQnYs5&J5&ns~8K+pqAPMjL1IPqKxUd((|*IS+|rMuuE9 zJ2K=xv71y!l|66=+}L{J8$@40CQE=PdjMQK(EBQE9U;EibA6891cyCWqL}P9{&Dh_ z0ZrhQX+*tn1L`X{W(?|3-O93`2k&TNTY22KB3c(Q2t&&1)WE+CF zbYF-QqOXGmRd{#!cP-r2dB4HIgiWl0naeQ^ zd!}!uib)5PKBI&YJENF?)<&zh#;R8qZ*F^Ot4?&f<}k>EYhME;j2G5-bcAF&o3eZG z3LcRf!uP13#i*Y-0?2--v3}r;5~;w&sKEI*FY(4ZV^!YEbQ&(=K%WcwW9Gf7sZqcp zHDhqz)_xFaKeGh%W#)^LW8~_o?TWNF@JJa?u(U%cvNUJh;N!To6%S!wJ^Q%%A?&t% zC@Twwt=&|YvP6H3#XLH%QE+3xcUAfWAjVi;NQ2@48m#G_tQJ&OssVCN- z3;BxrYpg%B>S$&ZuQcb^)2XKP?LvPnJzpfMAw0dAv6$FQH7&99Es`irsn__bMPJFS zLFFn-sUO&9TA8&igI0^T)#>66Q1ZCw>6=YFtUa_+q(a_-;Crmv9t*W=Z% zd6)455Gou9QWJpd-vZ;@sX#EBM!v(vEt*hjTcD(FR5>7;Er=*_i+v6lI?pH!M|od3 z2JZ-tx0gBEpMR68Oy9VWA0XKxNbYLoCYFA960OqO16Cw;W7OT=HOl?YZ|2vj_+NWK z%nzdUg<;Ie#Mrz|OQ?xRPL~ePlK;h-q$m@jXxt=BSLWu$m37|PL&fq4c!_1^R(PlT zcR0M*kx|bbex~UF_^5mZ2nW%ZU{zAmcDv&NJ(#xK=BTC!tM`eTeshsCV=L<-)z{f8 z@6W7tRE4O?uMuikpb8~lHgKUj^;&n*BlJ9;du|i&7Ii3iS|bJCrB)xUu(j?Kxg=Ft$xH8`Z0v2)HKHajqC>><-hwdaRdd02fo?LrSKR_ z2h6G|HFtA7^TpB~o^|E1NXsinV7a-R zSQclwc`R1Fw(VbA`C!K0{Em1uwYF^)9@e9obVm=aePYHYpS^}4=^8XdfNjqH6Vwyw z!%-*_Lp}zPK^;9y z88`b#&LIU+D5g4ce{J1@6ZkIDz6ZDZHa>)J<9qXMuK(GO&|$Q`u1*q5DFn?O(gr2o1>TCZAJS^7NypwMx+zNw}F&xL3Pxe{WV~vYk7M@IzD6@-R5n+ z+k@1@^s)N5KAqSn_&V3AbD6N--4AT*b^2J~Yji3Zsv-dlZEvuPn8c}yebgS~LH>SD z$2=5br#yovD#7a$PzkD$l(ftt%qUVo1o|FHmyR6Jbm0eL>9NeYz3~fQ(PdNd+fBu9 zqNHg>TlzC;Voi~;uf-x`H%2eCr4cXU#T+HQ$-A7KoiVMNF``y@7x{N}+`<33L*<<= zrXH_sfqkxzrkh&g>Eu*_R2~`9)S`Hd=`m9Hr}p6Zvc~B#LiwfxgZL*W7sqSgNqhw+ z)UHR&k`rS}S5o_o^M@ipkk8#tK5x1gFv&RL-tFBT59uj^~c_NUZR*Upb|is z4Jam{&#IgqPv6(7rveB#SQpQZ!Go=&!DJuBkRE!ZKOp-y-vQZ?Iew9c%Q3hRToZQ& z*KxcQdhRfHO+5`Sq6NU);%w-VA$Kn1fr_~05slw#>m*jQY6`=I=*G#Eo5`^(q0L}- zUUgD5^+NXZ1@l9=0!5Jy#TS?pGmsbl^P`xoc3KmGptkNNSY~l?lB8wc042#=^+rHa zN|gLl1e3y8uth12GvQkmQq_NQJ5XdAkR6*=3UJej3AqFGYXxg;)ut08)yG%Hin|4D zRbLi@y=Kzod%kz!)lKzrUn)W~d>_Sn}z zv6=S)((?uiEkpFR`^_0BO1$nr2sY-HceXYYP-!3iFs?TG>4%_kzhc=l>*5!_s@dXC z8gcgG9^W>(Y;cZyGhy!Z@7#>Jg*#1OrZz;=z=HY%VKp*j4osUw>!vL`RE{rT+r9yy z**jnjMpUaoB)^ghsOVJ4+=!cs;Iu#XIW42%W3>;f9a}j&QVnLk$MM627^JZl=ME2$ zX;Bes@H*p=@EgZ7{Q(G>eM-FV{T^ImMm`?RGtW-4vm|;)-mQ7!(hW}}79b~oa`us^ zjLE4dIhmpkWAYLWK#KJsl#Ay4v>gI1D=65XULc$oQ<5`b#!4Dx#=|Wk{HG<+OT8MN zNvvWTIYdGsGHvp7$JK;8ZpUjFjA8KmXU#``|DZ|B-ldjwdXc+gfXqMZ&siBT^oB(B znhP>`*eBRC?za0oYy~B$Vs!gEl6i>Qa4C@F>F2u3B)o8+}1#8hPed!w(0G3~oSpo4M z>yiFQz;DD*=B-}M^y*l|Gaoy@P_F_)__=Oq!^~cRgbY|&Xlh-&7$V5HWt<hC z%<@Vt)G$eTKlSgmT$gZ5886q4KJk!$G8@;?mX0fyZS*&W+-UV1T;E}M=fXwni`N*8 z{7{!t_(zxAe(XcprfF9^39SAqHFDQF*_xUu!l!QKD?3vQ4g{!BFiqBEzxfyKkHX(l9r#;x%7v$Pr4|%Sf(<-HL!I}rxKiZ%|CRl3 z)yD%hd#1CuHIJ2Or z3ENRqlUc*YE2qYlO{TkHE4?aW=YKr)o61%$qqR>&+P{iEW0@3~hxRaauOk)qfD$)Q zLjXu!9GjyNKWB+iPdVSRQ?UYY9Vta?-wkvwfAq@xru8_c&3O?3HgA#RvML?I!p8=T?5Z8tRIGs)(M)Q#V%%H)0+uc_pqPGMByO zCH)RLznTAA_#ZKFuWtqkWY?{#HD2pQ+Lwd7D7`W~r%~*6V`IY&+R=5DRo2?YI;n&p zVD@@Ww-4&{xc22p`*ErPYShfpVH$retvi23guHw_Wu%2REy@Brxb%X>Bpx-I%Dk#jZJ3Y8Y#! zi1Atbz0PKzrtnI8e}|9BI~*pfmsj4ca&k@B?;WNAc*XC!sk@GcZh}61t0pGBr!3NjdKo`A31r#^xueYxc;UaFLr0q4}4F9TjwBK?oZgDX>oc%49iK;)O`7u14&G#gRGejIjVMD}LuqZ^d!_9k7Qg<2_4B9Pw3wH~f zGG7CaXZigRj{W|il7{+|p$h9y@*Mq8*Zx8#l!UYQjLK%!T28H>&kp*3hho~QiN1%B$Db0sb;jLl+khRFh-GRsY~i4^f(T6zt8mRGR(Nnph{^= zFR5{7hPt*Gx{j0kCDWZ&Yt#JnCsuYY3V?Nftw z>zLXUtADE2CX1_Q0sjExEyu77X@A_>J2dvhc7>-7OK!JGU4pX!g2KJDk@IJY|S;p*hGiMe=7Yd2%RrspQLgBG1b$N-jOeYz*th`7wzo_?y6i*(=1 z($&c~6VDL|I|OUs!isLSY>a-6GpZlQAm7PsVs#DfwJcNN$cF0V*K(MR(U%bFz`5K2 z1c(ahv@TU&0sHmZhwkF^`-!oz0A5(jwxj^5k&LP9{#<=`w(s>f7t^WM3w;_#9UK934|*acgI3=1jiM`7asYz~}X8@)cay^{KuG z4o~(SQakAFbG{g!?%ONg{k6;wp1FO0wMlYOK;n3u)iW?jz5zfEOZD90uw?D_-5`J6 zypr*ANskg>hr*t>yJt ztFj`IJhiYO)?yY*x?=I3I`6r}{h3X3Di&GArjt2iyD)fjwSOb(Z+X4xFy71z-Zc3) zh5ik;P{qB$o3Z{)iGQ;tZ*C3VRP*NB#aqu!EIlN5Upw~MlmmAf|J##et-poKn=j~j zO04w+O62_#ooR;tEO}BHJfek7y(lV;-0O^T6laCVU?N3g} zT55e`G^Gnwwj}&6)@sT)(S~(MfGBy25ShhhxVocs3>!nh0Vy>#)#xDTLmx~K*`_wbZbAt?R8i!Vp(vAg*`>Ld5*=gfOMIyhuVr|F8ZxoU^% z>mYIM7<;_J?ZY!4Xu0QGOT=nQS74%#bx!L8w2>NC47VLY9=_tIw)AaQ@Uf`&n>&M# z^S`=SUrl5gw8HJnj2UE@rtP~ja;D7TtA#aj46tSH4N(LVD1wxF5E2}l%H~U9wNenj zh5R-{mEUG)Isez+BK}{3@8saj9{?8m8@^}&%{q_1FmoX#cgP(%RE{FR!1I&glk;wM z$!~SdcbIExQe-(_TRNV#eEQImAOxo{o}A~dzmwrAPO%+@A+3<$L0#&IvVq?!LMgAqDJg`>g-6kt0`;*D}i_UjV!K9_Z*;Lo=UEE z;-J?N6Mv(?Ia~+a9Uo6~-DUegxx)vwpR3b|3g+T6rg*Ygfe~f#lw5->zbmbopoJad zg9yA|9FNs301oHQwHyyC+ZTrNgKkDNp5D2e1GDn4bARnW+24rsey+daq^6eha<|!A z2>cweJ`m%;LONHuIRm7)EL5<*wBf0PtcLuR(n_c%%ryO{%AE%-nT;clewFD2_m#2q zDt91DH?`Y?c87B!f3{df4_?FWw2qd!qv*)2KI;Q1Kp!FvYkcdx#>E>q1x+vclW+Q7 zS~7&Ym!=EXXBMONT6KPAHY*G3>}21WWI$#QYC}#iS5eR(mp<8?s@wy&=goxby9b?} z6LfYUEw!H&;!Bz+WmI(iQHj{l$D|ZP!dH5w4SWmM@Fr0WAYb@L0;B`8D@(-HT zD%YJ3)!_4Lkim}6+9FM7qVbB629r!g=GIJ^?P<;IxY-hNg7O)B4U{$UmAk7Ukd`;= z1s=+e-qv~I0~trAheX9zw}hf%L1x6vT>0>9d0ys(NO^3eoU1=Cb5i8_0g>_^k@69d zay{iv`ZMc~SN@1eoUcU#9F3Kh-46HCNl|U5m~L@WAUnpf{uFw*ESH?0!@3*bZhTI( zT{e)XSzujVn5Rl-IMhjtglTAmcP(iMHxZF&AYo1)*t!b0Qq$-wmx__I4KE;hk*QW-Xn!!J!p&nxt zS5rnA?FsxQ6uF^1!xgvVZj$M#ZkVMmNZfj8m<8JH6nw{04@ZX|cf0C1JNo!06G&5yO5q;GWiPk^$}H8b$Dd167LFg;7Y0GKZ`Tp68 zZIInt+cCmhWe9|fdXe-W-89)>)|33rY-W@5>rGjz4JMFawgztClncB{oEB%~jD^UM zPon-ZJIf;uJC>)xyvyj9d2g#f0f&_s7NwalSh=<%GlI%)+BA*q=lffQg%;Xp@wDG{ z3pa(G& zU@vhpuo$c>)%(!UWFQf~&%X%a3s*s+`%kU|b+WmA#ro9U1uKEQJ|&d^wD7)xdd#!8_7;mL7Va}+Jrv($`mOr~-?d82N@ zlh<-E_2Al$S7WnRW^hn-xPPQIg}jd1-QHKNYu_rjv$-lUFE3&7A2Dpnap?wZr`Sxw z-DnGEX4W~Wd}j>2O2QV4i%AWhJy_2$USn>FU~MfSSl-^DQf&}#+h z74CR@hZQq_TRV+&v)U=4qO9m5H=7wt=QB63=`N9^^#1KI|MfMJ7t7pGl&M|m=-$0D zN2%|#;S_S$mz1;ltpk69Wgz*dWrnLK5m!7pq%;oz*s6z`AG^pFhd^_9{~y@us(bc_ z4Ke3?TJD{fk*DO|*)X0ywq$tsA2K&E`kcRAadXJ|;oN;gKK?RS@8`LNJx`InY4GU6 zSc_77@B|^Gnk80q=Uh#oAJ$X|G&Re8&2p=`dK-hC+Qb16)|7vi=(s8Z^xr~C3T8HyMVd4E02OdvNDs(S^O8hLXirXAM=;DUP^Squ(_2L%l zjq2n#PI8CX`GsyLLT^MSc;d2Tawz>mQl*eeG;>%EKI)8&&p~Iu4mv{w2XsF?xk9}* zU9DCW5korb_FMA5e>eO64)%TH-!pHU%84|3rD+b&xV5#M2GU zN(+o9XzrNNDzU!&aip@o$kQ9=hBWH#_8TQeup>C})E~9ut_;Enr3SdXOq4;st^>k# z#x5o#x8t$6E-|mrjoE>ezA|LRY3-N$+%23AxWo4DgX}t0!nDudvWO}i6IRP^`SwVr z)IG&|o4TWjKb**G+=I>neV!PM{K9!{AFH>+#L}c=`6Q^XlwC^SW4jf;gVTHm3I&L# zk1uwY%c4j>quqMfzO%{~jdw>rszSjVXUOe-(KtWdp~dbBsRqT4|5X7>3Ms!&1#nhg zW}g7Jn?FNo z>k2*|{Ga3Rv=jbo{0#uoA^vVghG+4&$7Mf@ze1{n_>=tqdHlT@!QU0qQXH863H;sL zY8_?pnJOuAtB9o$&W}=)>^$<=g;&P6hBcfpa0eDRNJ=1^9be zjiF|4)L)Os*>NBfAah5?5$v0LyoGsp#LS)_viR&HeD?1WpJ21!fnf8fJZ_YSz!gwZ}TguMmk%47pz>(q=l7lr?h|cO$o*zpi_*{ha&f;@y zi@^OsllakCBw!cgP0ucsQ~|td*B!^V!SQ%L=w@B5%a1Qd@c9&$M2Jt-5BX8N95DP_ z3F}~y=f^^~>Lek;!n@tr9StdC+;b1BP*5}8@YxXXW1;(AIzD|-x!Z~BPYivp*O zn|VM!!^)q;-|8s-JYZUKQkNkvrf-!`~zP zcDEtG!OA$-;~~Re;#9*Q*^Hz3(BDSr-+%F)Dz+rCt;ly4~i3K=5|( z4jz9S@pm2kT|4FffWPzsKZ(CA|B*dNfW_p!d=a$4BuZdK&QZ?fmz%RtgjNvWU*h(0 z!$!bV>A0!cSNUKJvj$8BuOHK=oA~=#So=9agYB=C@noyuD(vrXc2bD{s6H*+DvJN+ z9R7vj5Iqt8okW$8e{bLNKjGh~KK(wK!~c5tcPrmPmVXZzXZXL*@DIa)-Z8Gn10Me; zcjDgzF}SHv?tU{X;NLMS2>&H~0ou!+3;6e7l!@UzVA&4Z&Xd3J?f*ibf{b*>>C-5&i1^@dQ{tW}EJB$oE;a|M}`qAs+e>M0Q5`PB&q*KoE|HV1{TUTB1KUK2) z-}gV^|2+Jg!RGbx`uN{>kmLVf8~#22Bdk3C|Hb3~#LoPWUF!M&Ny9(wc_=vDAF&jcSgc(!=x88F`AM$k|c z-!Xo7#<$`fZBf-pPyd9yW%l!J1Ht%u)<1B0TwI=826ZLvUlUcP3yv)p#ve3&8!Tz^ z@jg^bsDF)I2kB@5pWR2xr^;YnUCI06-Vwate}R@a?Pjl;gbDavVktn{RH^_%Ndxyl zk@34J>;G*1w22vnKWTsO<~zvR-@}eI{Mq{HeuNXGH{NaWClv~=`?c|VZvAwatqxc} zovri&T0f0f0Ww$#d-DMM;b}n@#ye1Jeo-*{Uc2}cpqWn98-<|pQ zf2XfM8Ss<%%j#>bm%Jrp_V%wE41wZ|pRu>2_`7+t2>$k%n8Tmi3GFT8e=mItsRB5q z$lUqx$v=Gw6O&-`;zkb&%D!ZATgYOyBN-#0P)l+_iTa{`zQ%VcA0i zd;9NZtYdF~`B%eVv2!YbzX>MLVY??#M?&N)v=znQ)%^Z{gTL*65`X`Rz8y(|Tgdah z-G5f!{`QDtv?c>u8x%;z*kfi9OZqw&nTVD-EL72S0^AAQ6yRfX_cTQfvW5zl1y8A=M??rC4j>kg= z%@XyXd(mS8>qV>G5-A(upTFzkpFu?M|KIsX_5@`=f&Z+${^|AA2~T+Z|HANZa((^l zt8)%p7ys*DU*+L{qbUA4(1BHM_SSmjeKA$QzsdU{eEakAKI$L46=N#&j}=Ny1O}a% zY+j)}F~K^>%KNt(4F4wY2lq1kk8^k4?(xs+LiFJ6Z~QCocoV+Tb$`I{U+h+MHp=ji zT}jnK*Y-Ey3f`B{mf@ej>*Ak5{O|B@_Vyki?f+(P|K@SS{%58CiM`zzUl;pKx>YFb z%HEFpyYJ%|dDdPVeAds}+r?A?|7zL|;al);$Xma?9bJFjY6hX_e=`#T{EM8VGq}#> ziQiiXS$q4fBMkp$Zx2@15ZT*z-s&q9{M}Lkfxmli#*wH0|9AfGXwIN`@*5q)zL`!UTc?~d=E1TH*ViE$>gOH@m_nUWfJJ@^TX1OqVsP;A; z$F5R`6z{6EPR%cNZ@!2F#fKEfTJI6C+YTu#^oshc*s*iJ=KpR_gx>5^{X;haJ`eAv zzn(j`7TIr6`ue45LEoak~8c-6x9XKs+e!Q<^MVtNOFPm#ewY$5CkCgx9Gi`UW zN?xMAa-$0e5{{A)y1PxrRD5QkcT3zo5RJOjjwXE#Emvn-5B!|{y`s$~&<{5ncXxZ6 z?ppre^fN?r)EO$mYaaW~&v7w8;KW;Ll`fmBUdUyDy2r1s&EH`@Tv7CU3Vu{6uO|f$ zA-k1`k@`V%>ti)@iCrX0{<(p#6ItJXk(-5aEOeeEBbhiXAv&_*tDS7(utX2}*DZ&1 z2a<{cd`tu5nKQs7esY^Xzy=4KE&W~0!+Aw#IOoGy?L=W*B??McTxOw!+`pochG-4p ztM;eTzQOnE&hY)|_Lm|jGJo{rRjkQ4$=WjjZl;}w?l-^7MH@WGrb!ri@Mp?-=XFB< z`9>Et{KLmzka-KN<*|^`GV0)iPuxU=({{`kqFv#3I}?>d9E4KOktB!g3%qb&+VmSs zw^Nl-NR4m(N%(?TtK?OEde?)0iEL5QkT4R7;AP%`DYA&v5wciB*iy5eD2Q>KqN*n8 zmpc#p80r|WK!E*0Emye}(*JhJhFx zn^jlGuy6dWCnilfLQHle1!-q^${7YP#HxRtcR!@!GfOyGDOmIc78MT{DDJMqeQkTV z6^{i!|0N5bGdWDMDm#A#?y>FfwvqxM+_B0Bw$kJTpw*ilb|5gG-gT%k2PB(>+Zl(U zhl#E)Qi$SQmUZfSrj~c$pbF^~K&|EPP)M?-&_j!^CJ;u7i*T&?-SvxJ|? zICs5Ir97=uQoO0y8N-LE{_koGZW^6&P_mc$vYUey z&tY0kL)qe2tWh{$)c#&%hdqdos80UVEJlNn>Ib}>h~kO(DuC#OE;N}%7N`<2Svl*eEf%X@`>)KM_Zn&UVRHs}zU zYdYotJ;exK%${{PP+BBr2OiwMXGnM~bBA9*ZJ-d(L19Or&=5*L9hHR-EC$f+fXHuu z-Yo-iA#B#L-4m8$2B%!G6na*#3{b)CTR?{MMBD%KLK)?!t-~kHiq5&2>55m%PZh0m zc8OrT=iH@;CyT~ZNTMcHm$KGSj_5j@r}C3F#~qE3O(*B5XJ;b7gX%6NYvQYDrSQ2-<+nf4kg^eQ&h z&?`}~Z!REJ9Q`Y+mdE@<{Ujsz9sAf$@jteD`>Rm-Sp}<4SpWQfFYaGhKHL0xo#O*pUTNQ(;%*xp$@jED}H89i#D`ZDTNB1x>VC5>$K#CLuit|Ba`fm}ca*#z%lEvv53> z&>}|JA@{gWRmqv#5WDZT}ipL11Ov$*}J#iAA+2xgViCMHJt_L$!aVwI7vnvDSa8nY^R$;%`PT8RNFKFA|z|ed>OLLwY<{ zh<)C;z3AWD`W`7Ozi04?1$x=EOy71qn+0BYKb7d|zT?+VPXi>*0>0{|dh0vq`#++9 z^k&E1jdjvdB}`O2oH6TUIg2}2JC1|UBYu;khwl=(@@8y7MCA9#=1Yi*POfP@q($Km~lSuVY)9@jToAE7vhvl0>oxAHrPEJ}>oSkrS|DKaY zwH;I6!zc!o2BR$2SLup>wu6@e$YRlPxJLYbx#?>6m8hc{?7?{T^gUqqi%E@o$_3>xSYZSuOZo>@dLJ;(vdjUjP&6x|q z7l`>49K_<|PwlX!0HU?r9~%Y4@a&W3c?Zb0Barm7mB`zJ;WBZ21X}0mH*Ee8f7Q?o zpq$x|&RqSkb7a3C5l*3aj8hh$nLa+cP6or9!8JlgHdB@hYY~!Zv3o^yf6(ugtVUqu>DBNwR7)o)B+HTef1p(%+j@-fTw;@y4v#lJX- z%1rvE!vtnN3!wXx;$YJie=`WM{=7z4jr#j}2|6!qs~V%vgZ9ETpkLc`UJ3%8o57W@ z8!TPJe%-~UBFQ_VC8C*z*t(d8=ZzJ-JqWUPQLNRrN2kmeq_P%tr}ZJD-hUI8`*eHu zG>y8kUoc{EUZxHldHIsAc*l7)S7-H_cIDH3R{BT#`%iZcKIN=lw+udZ)*rzW*`Ibh zj|^KBZ9T`;AtVgjiVOZ|WMeB$QWU#mZR4xrY=Aa1wyz{(lnZ==a|%Vn|45p5&8@X z*KLXH1GK+fCK#@8H(llF@nOF62pJ{p{zvr4%Dr5}uTn-jBe^OgxebmHsJ&~&Hxw{O z)_Y;*pX9Y{`BY{A4;VY~q6rD3xbc{WJ}yPpO69T!IoHuFHlJi(m^+%OA;=mUs} zt>$zY#TS9x&=&5u_H@@kb>BeN71pH~v_3q*>BwCcsMU-4D+RmHFRZ_}EkFxwbD|aT|?`MNd9aJYqR<{w!gh{46Wn-qyYrRi*^W z^L+kh-W6%Zj?R(F=QuP&ve|KRuDpGu{92^W;z+qLQl}^7PV2ww|3=>Zto}XrIHs50 z^9^lsOVpj5uYV!YP>kiNUR?8`8Wi1`a6#fs2VHJAi?6Flek52fbN3~^xKkaE)k;bb zI8FRC*@<_%ly?0_Y0!M%StBn;dh4ss8u?!%^?V(TY=IJ8%Q|mwL9dHG^waooYE<4; z8ez(v64GS?YeUn0GQXY?AOQ|xz0UG(0?lKKW%cc6kD9#O!hi>ZNZ-DBLcYA)5*Zei zcZagoCVBS-df3ame^JUjBci+jP=$o}9NRcyd3K~cKT>`qQeHrLJ@QV*A8tEyT(Mx8 zvfQ{mwNE^CWb{;~mkq(rn#?yjrZFCSmbz>1XQIlQpZXo#*!_L-1U2@J%@|D7N_W?j z@lUPc9<}$ImV<+*@sVj4=lIKo1Ma9#S8V#Nz`e>HW{+Ym&p}ep2q`RiH`Iutthr&FOT_tAENZScYgRRt z&IH3qa`M--*M)r43Mr6}oX!kAW!fi@e0=6TKe4kfGq!2n4cg&x_a*-EvB6`J6pv59 zS`-*+g2&&1a~=;fb8VFy5Io*dU8XCBeBm4E7d$TXk4FSuu5I;QeraH=*xWSuDz_|n zY?c9u4L`6(I5h#UzYx6BsXwW#lDgDz_BKYVw?E$CCH+=^HIhD<8Axyz9xrN^cGGeD z6)t`hPy%S{_{w|77t>WeK+zprwe^Vj32sW)iek*#?fMP{V+zWwGr@Oq*e z_!IRGHne%6`{#2Ql%+e#um?4|O*qq@spWg$k}`(6Lw^L>HAPL!4`Ky8-jY3!- zV#D)MBOgiN95hx4vTZ7s#liN}Bnf9=T$ojvf4WCbVo9=kw2eNjmDWi;UE0hb0&^9k zC2Ol{q-NF*I70PIp09|mu=?6_zZA?`9!+E5D#1D5>X6-Pdq3414;vD6_LKX6?dj}# z+wyz1FLe8j$YK6W_Q^sjsEm{q9S}a>opNryoV{?DTx@R!>*Y$=CyyS=c%b$2$yzT* z=>eq@p@+YW0wU>xU3SXR0~Nr@^HL-sJ=CWs5yjy5O{GI7bV&-EU+PKWGQo^JQf=N& zH~6vXI;qJ0o>>c%EDm*mJxykA-ns)&ra{iEE8!IOZL1&}_H94ax9Nh*OE6zU%^vKl zDn4joO$n&U8JJMrikud`K~F4$VV1*GJo zkh-L#j}GselKyVbTS^7~EG5NSuhdkg%ompOsVTHWJL~aJS=@yzpmp=k4;ZI>Y-_$i zk8eIkyeykWlCQ%Z0raAJ{Ng*k9{+_c=EN`CQOfAdf%{v1j=K7?*%ne-QKYOQD(gF1#+#Fw?vmwiqOB>wzAIfgG85O$=ZKMUC z5Cy1+3++#xN*eicfenl+iMt13OOT+x;4f6w<2Y67QxmYmj}|JqmR75z<5>6*w#3#IDVyiAHED<`ctI}{bE{;eY7TB6 z(Xw`fI@~b6f2xoc;hG_fg|;PbUz><>7^f~!Cxns2TE5`Jf#15V>i86ZXoIzi+Qgk` zOqCi_=+{Lp@hN*LsoQ&s8wjh5wa6>pJXwi5WKG6qkF1fnCuoIb-xqG$k(ve?>PYu( zZBYsQ^9O3xV-8i?{gJxC`QDkE@{Do*=`EAEb%Pev#SUdD$GQ1=?gQpTs;)~DYc`Fw zvRB(N@ZGw^kDH!XSlxWdrsc64=1H)>jRI-^RX9#Sr6IU^M)n){2q&MLVMV0N4TG^o_xUjzX2+){mLy*8>2@6k+ifhPVx5mS@$kEjS-2hekLSa-%n~-hLZ196 zQeGM<_c|+A=R=buV*9dn^oh*w zVkP2AvO^8aAXeVYQz?bK^t{{v>5enfEs>Cdn8$fe2?6MiJVHcX@WM92!~><>fRA*> zVlbkAN}^=`OF7GaCyhW7d_f(%Vx=mG(O%Wxw11%AOZA&Z9DnuC4fmWogP_5vxLB&r z0&(F~=35&;s$eozB`#L;xSj+bp}1JgZ~enWM_fD|j7{tMbp!6&A)>pa&o?c<{ z7Rq^8=W0w=gx66O-0mM$WqW28MPlPX^l`U}TX~qIweGcX1qg00K_pRDxo?c(uJ@xb z0kXmb$d5fufV^2N*tV2T%C%VLKI9vDrR%5@hWG%?W(`<0Ho+ozMB$V4D9}65qs=Z5 zH7nJki5gn*qUL!XnW#}Z!xeSOkKrhW`s6l+;dTOMsQSs1)|+s)DAux-CT~%y$v|2c z=)1jg@;ZwR?us!ehqz6?k~vp(z5gPB@a-&rGPm$J)EDHV>F@7+?XAHkUsgKQN;e-~ z2&jXfSrQ?K{-lLHx5}b4)7zS=;(?TAstORy^dKcQREy@ZA*`(k(JrDFzAX82l zVUN%LZbIl+~I9rtK;PIboFObS(PEKO@0Yvv=Cus|tl@CO&??^6>*6l$=OhwpD=vKI?iU!#HS)*HOP-!n&Rg=#AIsiG zj=u$lFt@8hR^TrVW^?#(&Y-J4uGIhH{TBtPeA{&4ZQ^?oTzb22Lk*-$5-Qs=_v)xnek1hk2_+6~tkqfS-4JhQkjZbRtwk`R#U1R)@| z?KL!AZrzTd#2TzPQ?#+aH#CmT?rZr-d z<|4mR{mSbIusN_><1UG+LdLofxiYaTi~~uuRc0=q(IZ?Zth736En6>#%pe|vn{viy z5}+jadtByReuwc%1PlHfpKI#!nFfh9@zm8ftCSkQ+M+)PT|J$jv6h<*dn-B`=Iw2nSp-`0E%GQ(0;v?|7{Wz%!`QLR!Y6rU* zV(`eK#>3)CE;D)#Lz9~#668Wuyx$z@Blkg#*4bQx*j80!qmlJkP)s|dfs3bciD5su z@kmwwAwrdlDB3^CjnBrCDrl7kfxNV`DpdQ`qvkX)uhApj1@r-EUXYSZ&O=>pyp=S` zVR%Z;knSt8BrnWUe-|mGK&a1Dfgh_ipunaAW=-Z;FukWAFrv@ zD}9Pn@5aTHsor4Eg0wOG9;4s1s%ne%pXcai9`TDsnmm6?_dk&lj2FsM#-OPR=uFA4-;%lH1kXUOk1`kZuY0~SiMKW7c|XhbHks>#A2)GO|WEQwSFZN-PCou;L$DY<3(X@|M9Eg&t#&^ z*L!0H5DXG7EM+KT+N?d*Gv8EVZiyiBEG=uA0A@aeSQ)m{mMG+@{_(UVSCmW(o>u0H zRY4J0$CKMn;Do6gi(r3aT4Dg>h&( zdfFXP2R%*hOAVu^Csq16dioa!1c2I0pRb>uHs1dKF+G*b6i*iiB-2Lme*Jast-S8d4%+{F&l7U`5m^gBJq!r zI|hiiowD3Bl3n~^uFZTOgsgqAPWH3-TK`ne z10>eCu%cC+D$9QF4=*s~fgyu+@&lYCz3TPKjThQ0E`H?ImwJ^x zixr!>@VK)eT=ctN|A?zIbxKh^S`R~dCF){S2!I@>XHkdq3>q9sf5kI z_RVDXvfAU?r*|8N6RTH7upyVsf>j1}(p6OEbkT zL78zrcmBoC)Fzj<&Yd))F8Mxm1@(sJoj>(Olh0TLw7p8!bKk!inxQ=x1aFQGvOk4qt-|1f`|1D2AJA0DIDOz zofoX13f=Fl?;tc`_j)uDIILLQZg;WecEw<0mmQPo=3U z?zecgsee5Egor(!;-Z`-9qf95y2zm$^!j|P%Ee>nX&wvP-*R{F7ujF(@#=PH2G8+n zRe2qA)+L_uSe6;tEKyD@+yo<6*ipcZq8FRSkO=lTx0Jg^V26dh%e*|aHxA@1JH zakm}g2mv;ZJv}S43~`C?)JeZ9Cr0L4qPcDsPhY;+2#D*vrqNbm$I^WJ$2Q2=&x{YA zTqL^-m~15FwXxevv`geJoD7prCfZuIxzAvGCwAW0;7Cwg=6g0KLw{))Prc4*5#S;^ zDKw6l=x%Kw+!5#t;bZ{U+XFcY*9rn#bf1q!FuD_erVtSSg0c``2 z!6Dk;_fT~w^k@5f2y8^iE$Gku$BCUgI@&hC2?!BAI#quL+Xcss+q1CZE}Vr-=Frvg zq`iyW513{dmY&tj2V*mrkRPkleKNwQ?PvQfqdGgGWjDP;;gj+RZ9I1`*~X=9R>oVu zZQ58#f?IX3YOp=CCKkK=b&V~thTB;s!mDF5wo-I((bQ20H4&sFTpB+b5^`Zr^E<%f z?rxv_Ymv3}fvX_aTh5+xGg-8H&X0!tW^Vxz(UrX?x5S)@@AF*C71pik8dfQ-6VxD* zXFT-Xch@pT6m0z^^6qFsXawsE#Bd|yv@vHm7azzI`z=>vp$-eJa(&?o%>}MS9l^}{ zQDUpsweIo*0u-y~qD-L(fI1pOPa8v1FBYQJXR#0+LRI%fxda_svcRc*mS?vGnf~lp zh2?&fJFQn6Sg(%ha=qG2^4HGm)rQ=9HJ;fBItcuK;d-?pSg%qq$E*SUh3A7`ia&Y( zU;IBiK;vVA>QnpcYE9;Tp`=J;r}1V{g4WU6%mVH8{o&b$HTR2=x zWTRATFv%_^#>0eovS(@iAWrASTC@S`?EuhD@2|^`-(W5E9|gIlxCCunA$g-?En71K zPLj75S^X*VqzIHduig%wEpfjk3lcj(h$`D^xL|AhN&ej0(zy7lvTjgYtc9FdObSMy zi>9|WG{CqreLMl4WHeOO^__cQ7eKNQBU zde^@A$Xw`b)VOH_#0GxLCb;HZwhCz5-`;S;VtTl#!g0o;aqSNbHipGHtlfx9_xKdi8eq4 z0NTJtjRNBVUk~5JuJQhB-SvBD>`(iL>>k)h{nz^I6(-tCb(})b2s@8k9~xX@L1kTH zAtH`I>=D%S^wRndTh_I7j-+j|*@|d=IIUN^{>*@Fy3I8dos)nIih&!-7`5qAsBQy4*U?rl2{IF@i%ot$mT@NlHVt#LB#75}zPHq1Czky{|{aHoRP znJbNJJ1*f)$k?SviJ~xT_8l0oZM^#ev22|p&in_dN2ja()O9AH2fc}i(ntN@jCWty zzLl4kiE6nzaj+zwlc%_GFZ`mMB|WS#*4xf(e#~vb#pI>sF4v|vR(7i0^m<)V%dCWX zZjgj`Sx@*T>DR^{&V?g{_wg*&pLw(;RMbCwNBV$8Q{xUSyS$vmDug+Qxxefp@7g>@ z^?p-EX*4!hSTiA1{Xcad>;^F)v-Te+^8wiAH11K@bY+26D|s2TaBut5fqpQ|cu)Kz zbnafq1j$qbS`6}xjv;nxu)tM8Vs1^@y88!5W3pyLaLjCv=b@a7Onev^Lw%u`mf4&u z2F=&e?;Odn`t)S-Sz^o7rz(yOuQd9e!PTeFBu~@nXeJl( zYyf;t$Zf3kk2Hm~I9-1RKWcz(`OKaH?)1ed<_)FS_`A@3eS*MhK08FRIYo7;@sOPb z$(kybl5xK5woomiV)R|fLY9|p^4UVX!C@6|h8^__F(tdNS@_3VTU9MF-}XPMk2etq z9_FZ3ciCRT8+Ulw%qD2-%+FP`(|)UGFU*&;CsW-)UU`o%zDoUnc+&O6k) z;8K^|(49$?ut&PoK1^5Kc$f$2zG{bWa9{A*_U7|L`wmZ^0#6I5%anA--A)4nD(4MP zRtt*!u-mL_N;*TdakAzC=Cg!TEW&x}_0K7pY4bmP=H8{ zoX#GK;Q^aMw|T4lMn+{&sPhn}ntY*$HDHz|Eo!Xuux^u{H&|nw7W`G7 zW|{KC)2HTOy`dYZ^jHy4s}%$F;vLojbyb(39&y~dppLc7m;Sn*HZo69>Iz=FAe`D@-bu##@j>sek6NW$u$YrgUOw@gJ0j%ZEwtHZNlND$o0ow zZJ9S|FlS7H+8sElVO1tchmGU$c)pQfMQXGSE7p(P`d$688~x)*?)1d%BGC41yZ{It z7i)Qynv@0*pQBQ2_6NxibTiQ5_)-pV%!*}2)7F|4n^LG&?VPs>K{)56{Bg!w@6%jxD#nv8u)wnP zgmQN?R}1n@m?45Z!zzvsZYpXVCG*5~(T`dkPx4vr)e@M3Yp5<;cqo9)}i(}!xqJ(f@c(&h^Xb{rUMnQC7zl*ewV;2kHvgM|bdiV({Tpb~mHiD```r!QLTe{NkWxu52g0g}=6 z$(O{9W9miedE!Y4pqh6HgvL{&M%%xB#2J+E9k`#T^J(?TvijsCmS7|=(`k-9pqW9> z#V)F}FR1I!AIR~DhgHT)9aceo>P+}Y8!)NkF_ghpeKHg8|2AvM__N>juv_K^ zJsWEsNJ|4hmm_k3E(IuSKOwLuptp_1j`MoLl6avO0QDna!HLDnemW?%ff8KA)4g_Q zW&?<(frTfQG(C?apJ9CE7EG1p!pAlSzUHf@ziSv&%NnWQXi5(@)33CKns|#FM%ZXD)dp>yhc(GY>9r zJ4fqUX7Ow>wBzE*vscFlz18$FsV5tER)({BaRh3>Mg{h*4CnCiQ)mPkj0 zmt?N;B-C^QB-GO1NT~8IBcacD7dj^^xnkc z#$R|5L+3nzAT_+6-Z}nDhG$VX*njclN7@W>wM#TUNDLN#wNri8QTTYOe6UW(Qa2u; zhj4sE5j!~vZuTWRr88laOapSr>P>0Wirgsb&&p@lO6>gPnk`_q zQxw7jEfCJc63o4*y+4!2snKHweycELER2g9TpyTw;Pc-Ojc?Eh7YrYRm}dTvKN)j}o&ydTphblZ#m5Fv$%jId}S&P>?J+n8P%U#fu%oy$~g{-)yeGQb=&{=fK=kwL;g8X13^+?d8Jo$SN zFNsdPR9JW0fQa?kd4K39*q&4+Tp|QMb?;lFum}uP7Hw5ga=zJfPH}Ar9j_U&9m}&A zEH?}uMw@Wi1UJQ!4^AHACQ$(OZkqTuJ-N)CrZ-?BA|(cZi3Z?lm^jTCJny|Wke2@e zDY7ZV?#_cIJbVR5+b`T#->^W^dSYy5LEp&!QPgn3LzdmKfeFzXyXeZ7N_6kk- z*!J?N)8?3ie$2qRr^fbvcH$1a zAHhg!OULA-!X?n+I1wVzh!~(!2#*^@!X!w_!~O>{JQ)e$lWZ9yxLT82RG3X5Za3Eo zfd(8>@!c5e??-+4K+9oj@xo&-dlravi=S_q+ZuDw-P9)sk2a!sL)grt+_k)j%(aVo z7VOX`)@>q}zLpU`$$>`Ae0ye2WcANY{ApW;`H7!Cor#=*7LQK+@NlMn;#Z3MW%&cB zGEICi^`jG?rNGVnZf)Wvh$;7nEpn6n;hPk#gA&;`AuC6-c9kWwB%a&=1!0lDZ~t~3X>=?UFeZCU7H0^)$xpPDc+led z&G-1Jo6822riSD+oGyKlh7k1(}gS+40|IdrkEe<&vG;GE47JF0O$L}@Whmajp! zq}I*`A_AkIVkYemxeX%2etd}N(Da)~Gb&%9=ZJijm47-JyX9_bDpk)Bkv~B|4v#DX z<7OBK0|R&lJW|9=fV=%7ekwcJ!RV&OEd|w=5q<*1LjJZ-m;E^KU0K-d)<|Ii1($*# z*;l_|9uC2Si$c(ohm<*ZzFLskG$^-!>g^@-AFR!r2|$<9J>CYED^%sr#1wFFy6bj z!+0kmR1sY!!d#P8;3D_bE)r)qnmDtCG=5t_a6ez$U5Mmwztr_(#G%yLn(&^myeH+T z1TuKBKalQM)3CNfYrwT(c3U0hT&(frPqQV+qlYR(gZ6|dWXmdQEY`Xedn>iE8JF}L z+QN1>9*S<&b5NHkGxciQKdT`5riQz`#@TAMUXdb zxT$=pnIKpBU0XWdy~**u#Of_B=}(H~*p=^7IWf0;Vs)R`<*(T=`u$etMo#K^X}tTZ zzwE#h+U=k%0DP?F8!!^P`fADtDV&TGiz@b3u~kl3owS;6e=E{Y%WJ*FJ@q>;6{~dI zY75?py!vTKyxiW5hl>4=^mVVIuFY$92^HN46HnJ$KEyad2-A7U?A%Sr9(}z;%d$b> zsnM$pJeX>H=Ea;D+={yT@d5`+>QWaMyF2+vZjT0GmZkK^^@BcX#QR9vccoxpag5)N zf{-Mi=e3)t@%NkF*B&b}(C!zoUDipw@q`#pdGgJQ&sgg#K!{)lQF?81wOBOR>xv6|{9fZK;8gpL$}Mte927`1P9&=&jEI zVc-3#SJ(4x--q7fLlFPpWmx%h(0TQ z!SFZc>&yj0q=q$?yBnc}R;8_pjAQR$9LIGvjwgQW;Wh`+rn#Q>iJ$A$#H?mMk_DHW zkh{?jvQMNTKmD_5C36uV7QIEjcxfszI4U-p!LV88zHLmHtiY& zvqfxxU_-vn3^Y@-6N5FKDr@T~yDM#?#4rp5WQsn4!8`Fe0mmfJGJBK2R(K3|Y|CQ^=$=b%XaTc{J&-l4rI{hf$s z^>_6s4Cg{QgT6+G>-f$(I=qaBSVR%seMV2@(TuZtRkeH`YuTS4mb*+l0^i*u0`w;w zq_^L|K9*W4B5?KMLyL9TVLDh;747ip6@JIxv7Qc3%?F7Wl5O?LyDc(}ATjAr{ZojT zd_elgSqnL~?Aam}_?JC@L9>OiAb!t%W5M{rnd(*(&5!-!n6tCthz^{DMLa=4~u)T;bj=2HYq~ z9OORl0$I5Q@@`EVCMH*PZ~Pb+^k%1ai}Ahu5m;J^`oFuhnJO~O?C4DuKfpSRS;Q#U zLDZMV-OfkRFpnBglt9l`XnQT~u3G~3-bAzKP>qsKBre>j2u*qtANqOKA(u11Q9F`@ ziKjhz#ahpXs6!yT>#y}<`d?E20p#6^uVlQ(T2M8Hj%M|ou2^{uK;D;DXK%>^L3$y* z$@m*5D`%P>1~ZZ{{O(I$`mO7SMz1@E)0cE-Izd|e?KkvLykRRU^6fJLDm5Kx@ensH zCx>#K4(DoE0V>^KWSyEb3-aXx|6>zsxM%s184!GDCe;YlMM)WJyR(PTCq`+Z8z#Fg z?a$G;1A`ya)yAIsfzc#+5iy#!5-3SV#nW($)W?8MllmI-xHpHMVzI5?#n*UiXhufM zZ%;=ZuX5aF8b1SmF!QwWg1|KW096vK9Wzcug;PU%q^F z*TWeK;QVm@Er&!PE+Dmuw54I)z=xT|`R~5C%HD-=ac8T}WBGL!bgDC4bp+<{EBeS# zCpx|U>kKk7Sr5LCv*WGJ@9$~fpZnw}`YF@9fR}Rp1){KqG@`PL&Znu|%ZlS@AktlQ zT-VTM7r1QI&6^RB4G4yC;yTr%c|&HidNjyxI?fNWS-;a2^R=^ew3ZI*W9JLr(=aR| z*DopDqMlTTS&PgtjEdAFdg#pxx9|i^v3mf=G}zTErxorR9rYTZBG4kyuk@_1`?$V!U{@FZ-5+3Np+O1-j z-!Ilk_nV64N-Cz4dj2h3g110mykZ@n^AX2dC!o#P3VA36m;*0$=H_WK3%agf z{q~o!_d2&%;@@Aa_YZaPzMFr4ir!z<#d{R0#?zno8PHd8m zz2BpY_s#zO_gCQ-H6>HeLqF^k7(cTsP97~eg7j#SC31v2YtV<2Y2%z+IQ(X zefxVzzCpCPjn?E?a!UU!8)hzwl&^`DPobRWA3inK_gV9NCYFz9-=W^ZvU=L?w=7e5 zA)X$_p4G5&v+|PcU#1Jbe2ZMJCvoCS;) zj4L1Oj4#1#g&QrHz42WLvjv&fvJht6?G`CtL^)4f`1?p~Khw07PRQm}2<{IHV7ZR7 zT~N$|%tP_(H@D~}sBtFWAV~ZH+u6g)W zNWeKJ04JBs1;D)fBM(fRX%%A*1~?-(@W3evfb$0Wx>HLAoXU*>&WzPL;5?R%PG69D zBvO8WvXAc@8Du$I{AED6ofpRkW@1y%(bxU) z8tX>cqRk#%wRyL%;<4S?Z5vfEgL@-IwmcXx_nghYiXG>R@z_(V59V-u?7F$_!(xj6 z<sq4ShgyVh*v4mHsq-JcyZBmkXZQyB&S~o2qmBEKVJjiFJjlv zwOe3vTWY7qe*bZ7@A-Q1F|^@^d>c~Uyv$|0hHN=6b17x5_srTztSGZnQel3g(OLQB zHyrZ_i9N0^gxCBxeqMO(%8)lpe6xACb7?S-=SJl7oTj|*k{rVg8v?98>R4maC}g-3 zAL*Lm+K}{a=r?QFO8b`@`s{;TL%&o*w{&V~>vbENBe8Zd4TavR^GkE(MAx9De$o1Cqe_r18C|3B|=iDX3r{A2Cw`;jZ` zdy@(WWb63-D($c8%=g#q9+%`Hv)C>)5t!z^AAl*me(L>8fz@V6by}|}7abS5BUX78 zQS?+V=^b+2tCB;yQK?`qjPzCPm>Q&sD({r79P^d$P~}-vHisDZ`w@bsuE!HbB!Vc; zQN2Q+OM>Xqd2Zs@IU*j;zIo^Phtbu^m;Bwv(c4GAe2-?+lZ$JU8BUVW(Op)a%pt+v17+YzWxrUvgLM-h&NA97j4g zzg?;Ri;bW^c7iFfln?2F=FVWGx5=T%f`;h#W=gT%cg?jw_sdo3{?IJt(6qZ;9CDXs z5f*E;CHj>4f=*;pXqwhWalYbjHTSvQ;foTKpqG7Zcbh$t++_d0!K7)e_Bpj#E0>*} zJjYGhM>I_pKxdbnOwwDLVN-R1+ft372cSId7eapH+>uB=^?s{aIojc0;r3#?IS{qi z4YNVH$@bb#E-I@U!*4tTj5c!UHE-Lq2_Q8pC25c)l}LeU@wEtuvwYU$SnrGI*!yPL z0j&zo+QmiSTUj4$c3e!vklkXG)#sYvcpDP;H*-X<{S}v7nWOeQ2<-D@Ixq8Hq`W9n zzCBVtB~reQa>)N?Vl90ezeeh$BDb5skmj0E9YBLKR=C#bYdeIt?3KKC^KqyjEZ#va zAU+D+tzj!uWDe%FaxkrMD<@WE6)_*OzPvQj$l&-x;|Qu3>nVfYT*F<<29 zWv?A`^rC|fhW~+R4wF}#fW#5-9m|7ZWwpr><)Xc$JN({pwH^?n3lhSdLNl@?&&8>0+Up13BX3CK$@JBy z4k{ptDU_sStvV>*w=^2ZGXD^h(@))b#~{gHlzi|T8%T@U?ysNa`1C`%FPdKN%)fSC#hWuqJc=ZrvV5k7o4TYj zf<&|z4|RC`G25DSM-aRy(WXcx!m(M%Zy?>OnhO)3 z@vFO*Lh+6H&GXc1Ye5P;T`+qRVlm}22^*Bt1=pOXB_nxAtHciD^yzrM&@=Xp+7i>$ zAirb1uN%i-QV2}2KesjWhsyfJ23dV+iG?q@lL*68BgJYY7_N=ANK0TH!IEnO!^@7{ zqhBsHf3MC*^P_1gUu%Eq??#kv^lO6l3OAg)Ggz8(YD6D<>m>cCrUvP{9lua*IB|(< zqzFo?rg8;)03x0~MEFvDYL-z->V6Sc-JlhXLxv}R2<^{0na*`)^$dC|)}s8bGTut+ z67zl7&byz&w}U=udb2(`%cwkM={V#5u4Xk?N^@EJ0^Q4}4eolJ(fSPjvb%6&GwMrY z80|WA#8K#PwLwtAcr?kGEm;J^tTuYMc7^LUoagDM?YaP0!%hsO;Rf^9>>fVO@yB88 zc8S1p;wU&Drg<=qSSu%lJ2I90$FFOpJq_|}KJbvQc^)Tw5{c)|UzX#WSBQuTy71GkpoW^6jd!*I!RdBsLw>VH=8 zM~~zB>k2t5u6%KFn&eWK!ZDr&!%V0eflnEw2%<1K|u8R-bu^X_ z_s0?o9F?1OS>K9$l*M zNT-bJ&5tX?COUPSdCqv1b0PAs9af|r0gYCXW4<5vZWBSvsSPuud_ODwyagUoIJN2q z?2P{79{o7v;st6Wvm6~BS{m;Y4i%K`-9K}`Gyl%jvv*JPd)@Va;NejI^u*;N^X>~T z7in~NYi^RreK0P(rtT4?4JR(Lq(0eha6(oSjnUv5S1W7hdy_D(SGSxG-(+=X7H_lQjKD?+(hETH~}W#V>J#0vK-M+8!GemvDGQjZU6eS|-a zoL-!?I?x!22lb{9EBHk@VOS@ULF}{o)Z=A5*7|^HECcx5t1`y*xI`@r>(w1^Y032~ zR=CW(Ty?!gq?sdum^tK}H5ZikqoyPq7ka@`TxUSyeIQY3-*yJxF4jaqe*ygVTh$4E z!BRM<5_I2zU=vXZ8b?B*Fz>}$wVBp_rMvROkWA)fZV$*H3u%7>0tq^0`O3~v7FV(c zdG9RCpW1pMBWDTjNx`H<_xjZRf}0tr+*6)X6OwJ|>ja`YWGvTNHMs9TM^oB{M|B5E zcA5LGUK)vbIhrO&wQ;}t)T5r9>>ByugT83oX?XJAp09)u>D$t8$!X>F?W0CdX#WW} zNQzC4ODgoMPvdn@w2g7!n<38mHvS?V%CVJ@Nr5a!5>I8AJR4rbf0QP6S$*14{RAGG zc-q1?>eFX5@I;k4yV`(7JucRJsU&jLEXjnWvAS*O{arbfilEvU=IVZW{VkW?6uItKO@(sFN^#t-OA?# z*fv)=N2V|7ITEIfx@V3w>C#N2!l49y_Y4ZN!~K3qjynF-Clng(@ zS5#c@^*%sXISnD`da&Ln;F%tS1TR1o@_T=(pP6|AxVzu~|I6z|rk{TL>8`G>uCA)C zuFkFh)&8>6m$S=1cP~*hSlztKbS)%P(-l0Us788SJ<69lj`a0oefpG=NU#5CAdM-H z*|{=t^;90@>2xN(xkI$QiCDSX9W{n2h-8B$57m|24wqDx$%u096V6w`FvNrp)Ma$*FT6#XFy`f ziwXHSP*|HP948t}8~A12mJ#BsNYiiuMru`e`)vlt4Afy3PFs2q-A6;6Ri%6}sShQ}!�>-VS?qsHl zL~D(%OHeYuEhvaqoLu@y()?H+zWqA3NWm5FZ)YjgDX8Ys*t;VwkWirqN|A@EB zf1cgl-xCi1)9haIu1fvP?4BRI+~n-O$6o$7vwI6@Dl-%ZZo%-rrEg|jxh8yTStt~bYdHk0m6dQwqGIfh+$lFjq$cEgCV#)_1}#D`$b zSU$Ek`IxwDXc@zNg)L#mGuRRmpKf4Ic*)xoyd5DBJjc4P56~KLix*3U(#Xt3?!!7V zCH8k9jf%5e-cO}wJ6dxczZY(2FDC6Z&5KBq@pzDdCh9ZcSVC%M^1}sM;w62V&u(nBbc39zWE$FC4wrU=01x}`bLcFj_TV0sFrMb*_ zK-HrX^jYE#_6^$7n!G(4G`L5gU#gJwuAjb?-tbX<2NkJIrlJwKiqdZwKR|2qR5= z)R|^OJYx?ty@>o>q(L7k4f+xgYWgQv?iHrTAv6Z`=Ei+37T{jRKC$?`pgN=P>$a<(-r_rOn2iVM3s6#Jp6dlb zF8wV~#`U?r^+S?=6PV0i&x>qs=Q6{O8O)Pc8zuL@T9jFb@u$@-`$84Pl|LN6wZNY6 zO*A#vC^@n4jPxU12)(iVLb#Ld;|z6e>f(OdQwwbJvR))Ft_n;<$amO+3U#EoyjgJ^c~#eN;q2KV*2e`z8seUn_la`;rXZOit39YI*J z02efL>FNYDDHb4R|2eXRNmvzz9UG>wtAdjrrKd=gBLa`pe%gHj7h1j&Y>{PjL>4pF zg|l82*j$&Y0-W;=6v(K(tk%m^!E<*AcT2n0M^)~UfG@IfoN;dJ$;dRQ&&}>8FyhzU zmh_u=UUl)O%}M#V7GUDT4dIugv%w%r!?ltfsuFFVpfol?%4a^>2Vkjn0 zW{@(hB#bd*O(+bORK5PEe?3|zma2t=N3-F?xvRur5OU!J%rK*vE@s=-FaNNtM6s|; za5pXmfwucbd@b}l?8{Sv8_z6?Ev9ejU;5|vUI+|OelTM){cH+(m?c8#^SkyxvtuW| z+I4I}K>x=<0NWG|bEVpX`5yJy^DYN`?1c=F7Ii;(cfG8^gUE%9;0*)GuwL!o6dLM+ zH^uhm_x5H;X>QCSP1DrOqy@(1#Xr-}ZWHpyPkbItT?Py7aJ`<+mv!aX3DKn4rJ_E% zuWj#Xqi(qCY_Z)mXw9AXmPw7}uKyCD70&GUH30)p3ip=OBkFvG-}G**h8ce0w(MHI zgs>OUSG4$fej-%c`uLRSo%L}#(4UdM<)6X&=r={fdqN|+pcrpQH{nK2mF-U`Vi5g+ zCkfEURX9h`)zRz&*+Rs96n67ZynkLDz9h_#9Gw?4_#=X#BV2-s-P7L#)a<5#;J{I_ zdM3>f~BCk-y3@F|b;fBE$H)wkrgzlci zxRar}WAI$gqz??G_a*J+fs>#(qHsl%rxtca2J275fTBEt&Z3T~f8Ir=ei;25Zu2;} zlBa$~t}mBt2cV?}C>CqRR?^ZvtU4P2syXa>0;s#1(eV&Ar&~E9lu0*}4)MOMe-i$B zCXowjC^h7ifLls5eq|whGUIHEt_M7_q2FGS#zR@O=N6LZz67U`>B&qTd_@Y5Z4mqF zhLJUoB4RhPJ@vu=!VNbay5Jvpn2SmDU4==?QApE|OqQcxZ z7&kZ(m1F`pc20D)i3^Rc^~gKX$INn+prrgf*lv|FWbS zXrjg6AF~rgRW>~ z2zV~jGv0R~yrx`f1$cB$xJ?!8biJAf<17^_lB%ha9=0f&YV!I(4UXtzUL?Xvi8~*1 z?fbe#gJh^*ydZIt#3oO>4CYGJ%|Gmrq7r_J>}PP1dkCpI{Q%?P<-xhdLc~>C?v1>9 zU*U0ZkL|H<|H!|1%#8OjRngR?#a#3*uomhMddsgAm!;VPRVME#ay04|q0IK>N}P*r zix=R6tqgR=4uDe`{R1ii%}=2Rj`-&SZc7iG=a0et&fmB2;&apkqYoQojqamQ_-Tw* zSaI;FOyiMMAXZe4@a*#bra5dDk&0iQ%-eyy6-`zJTibKl+SVk`kyrh1M6RWfr>Z|b zRQ;?|s9=4--^#(XyUYAceDw=X;_WithN~a7arIlP`W94pH@KBQNAV}a>K+Q6vs<1` zx1?{&rkm3*XVWd|Z-TUhuH$hTS3OGaAEcq+^rTSwx7l>}QbJGW8h$lY>0zWd(g)yL zWnH)yG%ytL3-K~J6txj@Mc#D1jC zlXc?4=&;1{SfAwtaE;CXX>)~})g_D9O^5zs^FP}>mcP7xNYE~Eglscjtm5yyN3$-; z<=o+O%5yn4Dkt7jh1W=3jKX}Ny?i$KpNds}Ro?>@U9A2@wxa{dg8g(j!v%B3QjnDa1e*Jx28oRaq21UhfPx7~h?LcAJg`(lLVa)6?f2y&~uR~0Y0N$8J)2AXCu%Kq+#om&8`S~Um4;WGA+9D*W^A81_w>TpjYjYwUVo0e@M3;zp`ntwuqIjuiX@!|=brA|8hS$tyO5-}|t}F~GQ6nltmIIeo%Ux%9A5 z`kYX@f^?4FZT*iWzLz3o8s8gGe!ni1k9VTEI%<#Z-G_soa%}>mo~pP}z4-+TqxB|r zA-}lyRJq#Jp*^Y_=6p;k(EN3z@j4RK3$I$nPkHi$;`k>s;x82@NUZCu8xTGBgW7Yy zPka?iow?ikVfibfecFkyZus%l;f~frVT`n+beP+A0g_*QMSgANxApJY?VoM#I$Ze$ z;VBOa!mdsr4SWa@_v;!YIhOph79;t~D=J>yuN(f@FR!i_Knm)7yW!6JA-?0Lf@Coe z#DdMtVX}Wg6Gs&4xnWR5=z+|9Nv!7{X)X_eLA+yeeefN5$9*+lRfGYnZ+Fobas&3y zwNPSCJ9PWQ zxQphmO%5uKFPjlxRG1i4?Cwzw`fyGkDsi9Fb=!mMaQos*q&f4={T|0+r``9G@Ye~;f!jijVqfZxM%_#NLBzfH%3-yM+#{sVr$%M5|XZxbXC;P)l2 z?G=7+yzf8Y_pZ4){4QM+#&1<*=FcKHb0~V#2p&eA8?CP=%9m-=!!`TgVz_fo*V_KW zcyU+9)^$hmcdNPy{M~~4?Vu`BJ?lpBcaO^s<_?clc79<468TM*MBqj}j$;VU+np$s z?_Dqz57zGcl zt>=V0V1pic`=-G9ISl=Ke19~%D~A4aeaU}2K~kHn@8@9alpFZZPPS^*rTOLUC!1Ii zSg9Lclsrz%&5mTbyOJ=9I^|=r%sZ-|y@28S2l7LntAMV!au>aO0*fiPSS7YZPLEcu ztvf54*bWB7v^tUhSebBJPvCIaT2;u0c?+wGSYd`R?J~wP>cHgE`*}^VFeA;F%XN*$ zyJw8d*ppMI$P5R zrT+kWjo&B7;&r+fP>K?76Q%s{HF#X~T~mv3EEZq3rnb-g{Fh>VUW$LRhT1RPf#1F_ zCSHxt$4_FbgNG%yDzE(4rR>R2<37|#Wr^3RDp|MVPc-$Dz1W5q?nC;KVUktf`?SfQ zs4rKv1e|R`m!%kMR6zkgwzcP$xfI?oxc*c^wnNY_B*gu07cVCuxn_m9pTHzjB&U;N zLh<@bU^^+eSCjyElh(x16I&Cw?P^EXy3FFR*N;s0_@eGw9-5d3l6*=6rnUWe8f|@n z9(B%<;wW2FU$HpiUDf?ciza5XV-SrO)eRAalr#+3{J^?jqju(-Mj|g?8SGI%6qd6p z8X5XRG}U`^H)cC3mO*=k+q0J#V~6W0=Ii&Tw-H&9wTh<1Gtat<&7MxcM40paQw#04 zy87pGXzu(rm;RCTM*J@8FXufICoP{!k8mJ7IviKmhrNb~T)6v!$&{I%NctJg%# zuM+nfu7LThI6CxJ`L!@PDwgVA6lr`~NUy}hWt>_3#&Quzr15%XGO9eaj;qgwXRqxu zPn#o?@8Z4m$bGb4378Hyi%GAndn{|Io5rttbF=++xNDW4^qtQVSp6y3Glis$?=uNv z?YTn{Alh#up1IDlrpG`hfxI1G6Ny}<=vgvU8rV%So=os^bDrH)YmS3BMb%*PpzP#n zNuT;nZdA|8rd!fOv+3saaiqhe9jr&*hMC<&Li-7+d>AkTo7~3`m(7vq#F?0JPZ9*m z?I(n3CVW$^qw>X~(8G* zXIyI2z)ifvbL?mi_uDYBL$*J(+Y6AK~ZL10Nsy=Y+4mR2;}lY(Hfd zg$*`_l0&yLeNglmxmxQtCjyTVt0=d7%JJ8Kfv)(tY;GI*rE}7@+2}+39OP%YR!^1= zIycJ4d=B=>LN!gdn()JgIW)ecC}*naOGK&mr!(^(m9)M#-28>1<|8z3N@z~t4i~Ko z75xsWEPVomY5q8x5wG9r$$_COIRB`w`reQMta)G8&^cxw1uCu_!eEa=;LK)-6CAG$ zbtvGXuZ`6gVI=6%Ck}cu>D-eua%0&&bi{Q{M=pOsC_OKfev@?0zJc3pS^5yzQ^p@7 zXa6-Z5Az9^&+7)^IgDQ{u?lCl)B*3)1@1j~m!I~&S^hfU7j=Icuy>^C9!fq}z#qCI z{?QwTt2?H3S$*Z&aTB6R!XW=HKQgm>uK@$<`d-mG;HXH`JCx^&tj)%6+3=@cog;}B zOvap}td`a866me{`9MxH{e@LPbwB$LUi{7XCw_TJex&hHefNvtyGnf*&&YRi-Q--W+HL z4(T~R{==1#tLkYz-ZrnQp|c^jj z2*?+i`KMl+RVUU~$3K}@-LSTyCh zo~^O?kKOC{;5byTZq7UCcC#S1-Ot7+sk&wIch?*z!jBvQvWO#0!< z9^mh)`Fgy*6IZiIKdi@f^s;kQXQYucyPeg~`w(|T06H!;VCQzE#%@4OD1esy0JFz1 zFF3YU|9LHoWMM3ILVo%x46zK-W*VgUuc=1;Rz>l)NV*$XnZ$pBI9@HgfBRh<>f0uD z$-8@r`^XMTqIzcdiDWgC&-`Zb##WMO{EEW7x-FvdKNd1|-mKrftCU(l5srq0>VmCI zrWy$ZH4c}-Dw39g3X%W-LC_BdN z?G6W}%!YGWe%SA2mkqwCJ>h2x?J#H!(&4$o70Z(YjZ;*1t|$><$u@xZ1ZZgdFN8|s zyK2G^JfXnYq!o!6b|^({~HS})x@ zPcdfkW<2aasyoU?7Kf1tAe&XuM_{enJ_rrF$~{2w_Bnn%u!-bmA~&`_ta=SkZLa>e zUUxY17BwAK8|(2uT)+anEISA;3R$RM5L>!0?&urx2i(PaMdU2CsqHUcv5uq=H9=eKXGc@dI4gXnOjk?Yu{K%Q1(9r8q>q2A zk23*ce}WWL>>k!wwK#?rP3{TSE$zFvrVodeczpYP_`6(hLahpC+Tr;H-t?LD?xZ)y zpZ7UW4lR)+3RSWnu6@fQZkdzA#aPB=_ea_9;9}kWBd?av zGhp!24&MhnFko+N9!d++zlC--QybUvchf(1v`3L-qg&o>Ztw!hdNyS4t6<0)rc=%c z=5rF=|wIpNW8=q^qKrC z95-6lZG)`d{;w=O)mFY%SI~cG$;9Kh!_RG#@B6vAO$!+}Qx${0-J1A+EUKEca3@5r z4p(u3pzR`=)++z6@EwCkwav?;P^zHk4H-;wWlon*c4Ddpn@B9E4fGK|j`WUNm)`t) zX3n*wcm5)m9vY-YR~Loymw%q4vE#_k%opQF7I!Gn=YDRy-}qw&O2+#F1OZKjN&bOneW1MQv=CBtL@um@FS9dPQLC+Dpx`(FN##&Y5&5{Yr9MI zOGsr<$;1;GT*)TO)~~b0=3V*oz^Fwny}yQ9u7&~IR#m`ldz`l+wM3d;phH6OXc!Cf zvFK$g^+7K?P2Dzc?sNe6)32Mmm5$nRPu8;*QQ0$`W!JZl4Ut@N1!$C+Y7yQJC6OJr zDvj&_K6SAQx0e>#M9m=B+!uPnnp&G~r2z=7b79jokK2bv^SjUvW9R)>bb3EL#qIw< zj_#I!nxoU*Kg*@B+C*CP`$|w=>3@X2-7i%Bi%|aSq4IZ-)_V3|)AvmiLiByrV2{9y z_*L*jJp4r4M$=iA);icIkmqtyBERff+HY0x8x4L%y16r|#q!MdHx>;onu_pdi?RtztZB z>3TMwKa7;|C>3h8a0H~3lsC8jE%XatF7Uy^_!zxn8Pou6FynUYvN8;@b>VNCZ?o>n z&8wq1At3sf=g8lJwC2*RQ2r~S^x{yucc}c$q%-{Rzn)L+^`ZH6Se2hoyYuVkld+xu zgY_a4oJENKuZZ|U7S2r*@i`A>iTEm9lQy|tY)>;`BK|*HFGR={QGW8IqoIRFf89ZD|`rALIyKSer2e_2oa z?*jMp<(n`+oBR2%+4+lQJz0C-?NL~Ql|pE``Akuy{HVn_PU-L%M{V9%BYy8r=mHVH z?-UjKdF{9Qu3UHb3w325((L7X{lw-E_CveKE#qcBX}K6W2VleuLV8hV&m@{U`*9B8 z5FzRgm2ihc4}$0*eyfvLX}E9^{5Dk7R-3d#aIX~2bW`jJqn3+Na6>JI%RIPzbB%Om76%i-K9k!RZ&bq z0kP3qw^pG-r8AP--3lpF7h#w&c$woWKi0#ZxJJbElFS*dt|K)BLd= zrBucFv@3h$5Nj8?NnSlA7AO<3%B_PY*ukn9EAY$R9Z)~6H3I06(|z|bNE4!KmHT$N z2lR53G`ZY-+9XTFYIh;e>GMPSVfsYL_ut)-Bc`oB%A}jqTZYm-vgwxe=Ara%q4X}H z^iHAlj-<2lQDD!mP2I0?mzMr519{#dpnMY!&f-KRidO*Y4loh7(|vz6y-V&_D;-%U z+#BB%K~vyE`e8Z|=D`=-fy_clQdNee4z~?gLfdHuBc{des)VEGLjG_#MK)UAaNFM* zKFv^vrK8Z@(@5D=#RG?nEIQo1>%=|s?K#}GIqUL&S za`trnRQ?!gG&v&GXm>b)L{xW3*mFEmMV#`|9NE|8G24{79@{qtg(!vl#VVJ2e>AK- zzGVFeq1n_ZA4hHjq`rz{_vfw!6p=Q!%}?t(6KOlE&q<(IYKG@4=*Ne$@eQqc3#U7p zucdg|Nuht(OyNEbf>W!K7%D^(-(Ya-Dw&4lZr4`s^R05?Jy>^Lv)bR!6e%Sq*32p8U4D(_(d)srT+nryPFLJ#tXSJKw zM@VFg2|oeFs|A{J$Hh`%>@Q;H0BG+aRwI?c?%gSXDSKC8hS|5dIB3Zs*WJuFur+{D z`GtT!L~P#X@fyz93d*VXc_?tg%o z9;w@ncvBS*_c5NM@WKZI@Q{Q80jPhY%6-3Yy;uES?Mi4+L(5=?v7g|E#9Slp7%IJ6qPrMyc= zLPp(AMgl2CJkNyC5cBnRmQdxrRC%i6t$mo-Og`~$7F(uvi~I9x5t4XXZE10a?U*O3 zEHew-Ob`&Nsr5c;(zG!i#Za+N)RbQZrrDlujK;Vh6vGhv_Cms*T z+uPD?NPaW6;(oeUNXc@bd3%c$i#X$}j1`OFwFMY)j~&;Hkw6)+5gNn;<{6LjyT8jO^)2BaGgu~ED4HT)4qay)6SBblb@1ZHYH^i-%0f&B{WhjN&u_z2I zt;8c+8fm&5+DN|&knV?@bMnGRZ{*V71?d>-eD60i`7P<+Wz$@_kWIIwf6RW{l0GWP z*SGs*%QUCsq4Zy~>6Y}Xq4aY>THh+FLq?WSumhiNN&ina-JD(!E)z=sE0kUvq*Z6H zw=(rKr+*!)=fQ0Gmh_rX`a9Aa=~KBqW@J|%6c2q$>u?u+N+vSoCfl5?e!#*k3}0x+ zv9QHhC|L>wVHo};y-$ZlT5EucLqx-3O{TwAAgnALM~-fH+X`24x`?&JUNn7b$G)$m^@_2cjNG z1|LPaYFIq03y})@xw~@ZzQM5U{$=H!E^RPq2CLeutXdOR3f(1E-rVy|^;+fb)EDrl zcM#eo-M?nPZLZaRJ6)%-bL`7Jhp2qYUDm&8zJE45wx@2J9b64yz3g;@_GJP}m`qiC zzo+%imB%?}kEt`4r0*3Q9Ht8FziX@t8y zTgGc$uTVriDhPVC4jElj@O%61bO!`I`kd!bk7iDnZm9K11e0B#>UXxC@eSh&rk`P& zyFoYP$hh(KT)H8Y{!=JDA(Xx|l)f#L{-02Kcqlz2ls?d=ScdNJ8j5!E6I}dFIR4Yq>n4hk#rtqJxN!&Rcr=_NqTQWM`TF) zBABcv>8N`(SI$U!{Z}fNC25h!Q+ud*K+<AA z*O!J!dWCI1OZ7;dI7%eFn-#2Bvb*n8ym_>HDO<*q^jg#-_2^*h0qb+nqhAC)I$diP zJ=(Twk3J=Y>i>eIKVwe2i?7R(@h*#V=^aDq?Lz5DD1BHceQ+p!U?|=8TCUCyLg{Zv zhy6uPm9^M=8GEmZNz2!WsS(+~#PllpKo<>Rn0D>L?IlJ+;H^W8NU+=0!wtJbE?!8B zs&Q@=xiPH9CH%twhm=kzBoXP;SlST$Y5~#n^x*e#eqGtkKX%Twi~Fc)Eb?YFHKN#U zOD^Ypi~Uwxf!-_mhW@Y}KIX-~AN2hyntZxcI|V$y5b1MmX#@4urjGn|6y=g;d~?@! zX^tJpNTUuV2K(68mX=dNWM=Q3xT9cT!`l5L*SC?;uy)TYhNlKC8L-7=vB=DMv2(j$ zU7Nq=sLo}<{$#v4KU(?irF*4y&2Elg3^)_dGs!t#c_zAqnWo)N@FVuemPqnWS zVugY=S{dM?=^=_Kcz9u~KlB@EJQkIT>9MPPts!SAw8JYA_}FzVjMgR}wr@Bb(<#&-5qU@hQoRjpFRzP4 zu2($yhP7uznii0VCa?829V(j6CsE>`a&jQj_%<)6;NIYA4s(CL4JgqRtr(*{`C%l^ z^zJ#i9WWz}1w3y&;xIK(k{fY_+}~it&my90*AchT*0J8~Xm9K3I5XbOybF)_kJtL~ zw!yuRmzee1cgX6$Q6l}H@N{Aa65Sj=wiAa?%v;eu*i3R15Pu;@0e{BH zkx>=}oblxb6!7IzPXVvrlB0mPb_yt9q9%C;pNWssA7Dwb{xqze7-@RN{MZBRCWGLL zoWuEJ6!ZK>sP9YZ^xam0#&u-fg7mdK1@jfmVvt&IA^&aJgt=i)%g;+crdF6>1MLKW z`{M~ZM3fm~o3D|{h}7ImOF<(-x5L$*%#2)9!`EONUlUE-?8z5$kdzZmO*Mio=rp9? z>`5x1mG;|pq+(-$CjJOOI2QuY)~7AnI`6r-6!=s{W04SclTHKM@I^4^b zh_tvbi5;o4t&mP`z9;mSXTLO3PIk`CUe1CgdN@Y#)7L2f>z z{Hme)xifeQ4d`Dje6NAuOeEEXzEqyue|wBzMT~Hy@fMg&ofxq5$YLP2Bk+vmvCp*QDgj5{@V?IZZ%EL={;R>p#8AzzNa(%ZYOCU(CVMV5 zi>BE&-E``(tpkZi=U%L)wVP*zqaAzfL2lOBW+za+H?SG4m$->xZ(HI{2-L5bGBxY`}P|Db(IA>`3MvN(}CMTtq)%B%U21=9m%+r3;{lmvssMt zFjc0P?g(C9ZZFMl`Z%c3eP4@&8fLViNM+rsglcGWM+Kl%&9NKgMX##(9bA=VPclC1 zZLoDZ2gbsry7XmteX0A8juoWd4iY6iqctUPh+4Q+d-YVfR8(%Hhhq@Qujjsu6UR}f5mB|3a;qY@+@#=f)I@5i47n)BM6%cwnsmrJ7P-;% zUB!<|-Z7nS)+XFvDvl9}|!epwu2GWwMaH$OZ!-D-!=@$5s zp9rJAmC~ECA59@YqcZ1%x*Q+0?eiEcSTel+Rl{?um~45&P*`Qe^~Rtxra~#Hia)b5 zLe}!)PcM_^Oo&3bpNv7Scqh+zhBLg;lxH{RU2UK320sZtdy>yI%-k(C^DWJx8&oqh zWhXu}IgMS#BVSOV++O(Sz~T48BaJ7B6U1k)6tIz|fAW_nEe&~f<8u9Sf4^P~+nc4n zhw2i#!iW1(X6(X{Pux-8df3DO3) zIH66bvp=xYYnv0+I%tT3Quowo^CXbQ!JwAA6Pbp=lIf5R{5fx}kM6;jJrer{F#HAY z0oA*wVA#)CiuvQni^4s8MQ#QUdm)o%yHeNHyrl0GJz zZcbkmN}rxhx1qxFEd2G%Pkcg2p%2?L}hDM8uy48!PrI zz@2;eSmBDZ5!{E=bhTusWYYsGP}ww{AM{kqLlnr-TW#ub$uw@>wVGqoN|*7#6pd`N z4QJUFhzySYh#^C~sWPLj=BebH5_i$|ekkr^b&M(Q8=rl=wN24TV=v?@w-sM{uNIN> zikAZV*J?`9ZLO$l`%n}ivz4f9wQKdoL?5HvF}C)1)F#iL;I6xX?;($|7sMhLEwG85 zIc*+o9aKnzdEry%kp^fekhOw!Vj3EnX5M++y#oX-l7s2s`9R>sAhka<0P{80E>Tvi z)-V?Ko?ce#XN7T@%s|7to|5z*V|ff{_E6f%%5!eji@x7iScM(#i(h+^y+{?uCyr%Y zbmSv9B<|3p#^UDE>3%G3+sZci%H_F_08!?i{y?*rL-432hJtF}gk&I_ zt8L=Eq{`gwK^~gY3O9=VQ&{Rex&VW{lx3KwWqPW+Fx1tUBuPZYEe*SXSLWV+-)xQa zDZ^O1TaRXlPBmUF(XM={>7O3Ky9F?w3`82atpj*U++gJ-@73yr+$TQD(W$!9T?u+z zS8lXhoBTcF&~61XCe)h5%357#yxyHC;UnI{4OGkP7pt>{+&3-+G?r>AhM4jXnzS3; z;t|M)?nfksntZKpYokc+*Bj*tZXLs%e$-^fMmh?hx%qzO=6)`mW)Py)sHq~40cv(9$g2q4 z|3h_r9q`%Q_};JA!T3fRZ{U3zV?jo~%k}_=P*-HNGSB7e>KtZfAkFxwSl`%ar=qix4CHq%bdv;N>9nA zThf(c%OZxm!{vDxouAb&}T_``?-&iQWF_a#gO}C^^Bfa7MW4ZI^la|}! zmi)7f%3UlAl3-aMlUGRwjrLiL|6>sz2P_ft?o&Xn@#P{$%!4QPL-G}CkeTM3$v<`uld=06K({ue%$Ktu(Mad;5+;3x?IEppt88KWle9_1#7=kEA2lH| zhxBrRJEHq>o=Wadm&)iHbq60rLcgS1nJPrWWiFa*>)6}p7@Jdicw^#)oE~N@!ks6He99h zPk^r0mpr;2V;BO$Xli5fGeSiL;@cgrjw0zdOnGjg9k8}2+GnK!Y_5eVYkW<&y36F4 zOV|c$zpf!8(4jmvPz1sWXmYIW&nPQB91cjS?oVZ z&{kYSKCfRU%k6P#j{iNu5!;My@sUva~XO$X`4r_sS zu+rA19+FaPrdy3lNT8W8Nt5N_(&=P_k?!3BIl6;*s~Jxp(MWkuKUqejqd?nYDI*OY zTx_dK%&T?Ardi5W22`-?A(_r^nFU;B^o!yu_js!|?G#eKc5DWz5iP_G0LIeFkbAar zS`VAn?rgv_DcG1o^;{3$i>$U3KgC@|i-ugoL+|od|GsYoM+-FQSaJ3}gL-N+*FeJ~+@sJD*AUQk(NwNnKMiK^0 z!xVL@a#^J528Ja$w76-WzZf($FiWpwwMLB@MN5C8C234zcfX-Eu`;PRMP|Rnq&}e3 zU0+DM))l&%YhVNo3`t&GoPnR(PU`N(wcV&mk~TYlX9jMs(#qaGO%U*k*TdGz(dq%MTBO!eo%5%se9tVU_PWwOthgwi++b-J(VW`<+Tema-_ zFqD2IlwJ`^zaOOKU)3B+KNc$UUMT&1C>;x>RezWx<@9wUD>d z@`#x{poE9*2InrUs*Kmf0!!fbbj(CsT34@!Z(2a2_Yew9*-pIY9i*gd7rM zk2saEDajc!+KBWTRQ?N4kEumRfShwtDO`ct4PSeIE&23|99r4!r zHkP_F>Lx0#RjMM-cieyWAfM$v`M`Ad4!51D4HZwU^IdMVLT#>=Ig{xo72U>bw`P2{ zw-fgX_jcfOhDO&q!FT1LpexVtOgwop><=Fi%sB(&fXxE~BQcKW6?hHi-IH@|a#%*( zL0|kk%f-nT8%V;N?$gjXJ^3qYVZ*4?=)^rGk&Q|3Z@P3h|HFg2tAR>9B@eO`Cz&+e zch<)?H-J$A?E8P(I&aSQ8bo>K&v$!KT;sXSvSfsj@uAd4x6#wkwhL%5RnfqgqKiYi zw%^;gA5HCc`orspFMOHcU+q%-8m0_Igll^@($ovIL}uFcJ_MES6Ckpg&kQZbXKks- zqhP?u6~;Hj$af&R7O}KVV31eh z>dA{G?`(ivhb8CwrT@pe9oX+k9wO1|t*>dCBR;qm*Dnu^(nnaO>D@^`Snm?eZp z2h%7)NN8N_IMlV?-O9m#T*SqrMd_zu4-0GnrsM1sOtmKr;cYGr0~f8|#dD~sOMO${ zt;sZ%Pg6lN>oo>_eKXOZnQtn(HuL1Oe#njqnwcCla|F*OGq|x@IZ&o#@mmevk;+nu7*%0{{)N6Hos60M5qaTRhGI}pZ0w|1+_ycnlmgQ z)718F-0%5A5T3?|tBEviMK6W?dqit24Auqo&xI-jn3X7FTENQlEw4A%M**MrcMFXvumHC7XM^ywogawscICJR?f}t$ESRk;?{DT zYp?Z`K2B|%&VF20KI+hU2IQo9KUiiXv~B0wfAWR0&!-5mjQ&S?mWs~K#l#+}!LDcV zb<$r-etP2koXoWPpCr{Z%O49!h^5N{3+>6sof= zROZuAdO)a5Stwl;N}m)ezk4Wu=TQ2DP??pX^ev(Em7(-+L+O1&X_pN-)0|!xO5Yty zKNc!q8%p;JrKkT)`P)Ke?g^#03Z-ujrEd?_QyWT8q|DEq4`6fG^k?Ik$@_;J=LkhF zoq$l<|9&Yret$H^ipu1-`@Uj{?xoS>VX|9o{ya`&yeiivU$GQhL2@d^hEOl7nQMD) z9g_RSHC5Hx^sCC;*_X6~^{L_ciJP9K1rBQW(Xuun#Jj$OY9d1gwGC5+)muGqQ?9Q`|VsnPE zX*=X`KTTgYNw~u;u-`T}i{EIfzDnF`UbC26xC8Zv2f)*I4*v8z<8)zH1D%3RX6`H0 zR_5;2o8_fH*JSPf>)fP#|G`}P)lmAmQ2IX7+5P+AO2g!160RBGhS?Ugrf&D7g|R^s zzWz^Yo69_0`vn}_@G)(&!EF4EkNqFgxYyN3Q#IU{WV>-#7HW`&5T+Q_UjNXFP*bjV zWs0T4%M#fsZOp&L2BmxZ7;nPrWXD`sz|p|k_MR6nof{6Xll~1nOYc+9Yav9A=aRw| z3dyxu)n?}15QVd?cz|8gK(G8Jn!Kzq+W)emx(jQ$8j#C22cffLGT9Ds`NE}xPQ65vKok9)8!a+rOiK8LfLH#1Vjw_2Mj_!8`@A~Oo zq}L!~Mh-2k%EX;Y-xS>p4`ljr3?`IVes%nZ!f{7bubSUI($vHUHN-=@DKhhzqAAA} zk-J&lJ$Qof3jv+ zpT#x#^K1JwSI0kIqsAhW58z`x^?i}Rneq9B$0c{|c6?&j&4yIIcB;3n39r+1*jP%Bvj3pnG)NupM1OTdLstBZy^^I>v&1 zzo@7g^66fT5BE!vK3kQ#2TonzIrjmOz^?2S3tdkrjLVX?D)n}9M2uv?=VxsL9U(|? zogW%8ci`&Az*ND=fjQ0-%Rh6I$9KUCVQJ)*`zVl<9Vh17{-ai z?Y>B5j46%krw&VZ!a@h(5P~`hGeW<`z#r*#M%5I5BVMv*RHWCrd}?8XIOQ=4s2S`F z$sRX0((C!D_EGu@VFWhQ$|ddK^6>2lJ6Kc#p^ z^0FdmzPN4=ZC%6{0?yHEqOC}Jn(&tuL8e|lAXaZ-`uB`48Rk%+MHIqN zKZczp<55B@>A*!-_mS*63nnQq2JBZQ{*-INK3}S3sLK6mv;;-glNzlZ+QCUx zj8d$oam*T#Q$L@Z9FA^Q?$(X+a;l2mbuYzgt(bVOK6bMS>=t+&ys(4h&W&8@ACoo! zxt5IaadG&p-<*+vBoKE;R>g6$aim6vLQ7D`1O$Vyf=R}tN9#1nzI&-|U4^BZG64GB z-|)(bB@d5rX`$gIaQoJ#nb#=XG8tx5ftH{}#H$ZQ?&`DE3Ab?JHj`dkGta8P~9dbk(t6X@+b3+m=)$hx_1F@3YuYPABBD<| zqi~PV*L&#eRjkRW zM$``#yGFn0LvE5KHmpi_!fUpL=D1ruBF6{MxGR@FK9s&7l>VPk`j?^fS)p_l=?p)e z)cP(hrt{F3j2}#DU99JoC{j6o8Qf^BMG|+c_{MRTT*EG!HO&$wK^zkb^T2BEnk;ua zAPo74gc{^Ro>=Q{V3NfuTkGqPb<`e#8qMag!eJyc6luB<(=@o{mt_Jo>KUkeLTHIz zZW!_ZD0|r@B-1`H%pf3faFJvKZRHwcNUA&EX`kwDJT-$@Ht474(qpsf*7U`sL*8lu z|ExZ>mMEFkr_>}~70-O7`lMlr1)%9IQ!aF?HunS{oC$x{LyTs|uSFI$<&LgBt{HI9d>JDC#%8xX)kU|XF zL7NZyWD1^S{Fo;myYVF9f;6EmES-8;*nKnZzkLX7((JqEKys<4Mgg52xo&eu3lJYJ z`h#(PsW@>9EjL_Y_}6~Yru;?&F^;0C$F*K+CP=7omv6;umUQHv^1d%x9$dem^aKq5 ztPKqs6r8lH_y(8^5rwhDLajFC68YR;?MUAXXwk9*kFg{gtXA$=Vv+8bqm5DQVUALQ{dJ(BwEo$OBJk$fL&ne*EO9z0 z2{Z<`kVL|tgd>^9#{E3~W>!JH(~72lyqm6HwKv>7A&)W^+cF!9Hd$^u+{^g=33sWd zR#MOn3)X-9*GSpjNZz7_PA#g>_kL7N>I`vMdyJ_5sXZm#-aQyBYG1E~muL(ch;OoJ z>kwYxTVvf4;o2PP;Su^^;tVpx;@vo7Vt(hx%~U6&;DMNd>_vawXNBP%xtH!-mzNp5HzkbY}qehYmN=?27{?#FgvMxPGy%!;VciXHC7 zlW9XT2vCTkKrs@(M+N$&jB$3y8KLg~**W7FyCuMf-3 z*mI0;ZX(`;mr8xShZ8Q~s6*;*5hG(v=uOQH{e#%#%7ATCo8u*}aO7rTdrRVO6$}DY zYYG;-KaYZ*QWf8RBHMPSA_0{?VV(_$0XFkRF()_#L>&&62}tG_CU^Hz=CHGQ7nm{KFB})J73$PEjKk42%K1V&@{w0_02&LZ$rB{a1;r!Rg5ASYg*Z166b0e|m zrM>ZQAYxEI*1yifH(?|=W?!xNFPLqBu;Tuj%;Zd4-!moy?komxR)^j7ktq?tPqJ z?2CC+&f_EVeD;jR%4X6hyrhzf3r^s&UM6o@$!p%}t4OcA7x5J7Wx;e2RwBKgQYrV+ zy^u%BLf~dPG~Q<)b~Sb!+?0-w&k_uOFZSy8-A1C4%!KlUfCk>vN(uU4t^g*%&W@yKQ)7OJHtJ9EXS| zMLV|+qzh>zYu}LlL>A}a?i?9U@oV0&2C?Zq--1n7F-_b;EHb8CLzUY)~^BRuGtJ@`BRhS=$U7z879o+n3=eAbrUHc~) z*ph1ZXV(X)+0 z_0vVQ{VyzzG_LJ;kPu^&~YzGbfgsZ9fU?rE8mvsch2VB2S-f?lM#laYI3n z9eK|3i*`2Jxb$``J3J;9og{Li*k%a>Ipsr!=m;(M$-z}Y=Gc7hV61Yb8uny2so%qG zQNkWqRbpEJ?pDtCOKHPAs1x#H__()H-1Y~sJ}vEBtjzLyoek`8i%zkX-j(;&Dna}z zp3?&$JoqKHOxO%t2HZDz2K2Za+3xUTGL+Js?sZEpz3%2*TF&tqDdBt4A$uK)bg|vH zm9tkBrGE*88}MhdR80YCwaI;IF^Y#q7YWs0HCP5`ETf3A$Z{oQ6YZxzRpOdaWeuzR zBGT9Z6Yl$g&d4?nC7E4+E-W#cSmCPom&A|xmNT(9ZtNq^+eQxL!?E5_k<^9YcZJ)z zOR>85bW=djXyTu`W34JL+W*Ybev!uSX%#%jun(Lr9*`PMD`r9Y0GBwO<$c>qSR~_H ziGgUVHADXQ_Zjk`#!=AsOv8g1irkySG~T2r^H-JmrLh*Dai=o2RR*K^W#Ds1Nz+u^ zAKndw0X}VhgOU!(E>l;XK7GeTJ?<0O@YAFCR1*mK5|bb2le-B;;T@q!(=lL3@9sos zykIIlo=paxitUl6wIt@g%OCgFaYDibkA!CYJKz!6w0&d(v35--xWyuV#3p*fCekMu zn}{@u1jG&iqAD_TogJ!J>uwZA;NMa1e86HA^HG~L)J;2z+BML+t_-QA*vX$Sn)GG~ zrnqPBQ>&S_*y`PmXL8b0a57}>r5fsO`l=3PzrFnh`jaN|0Ho>d&&HS1mof{2d7Egj zt%TqrO4;_1!XYbfS^RR=Pu{XyF@)UHtcjG0uOFOTPeqbl!HUdtfh-aQzrr$_t12@G$b} z5A4DZ60m{=Ao+kH-#9<3>h<;*4DB|BCa4+9MmNah@3Z(j;Q(j@P3Z?F^c$B1`l>#ToR29ny`LAd*7I$KX?@7? zbALZ%b#8xQ(sFi1;OW^d zf8iy3{^oQw-a1-xbZYw@uh9&xDz;Zg=~ZedTz5$6=-T91?8KuB`+gwBWE5OGR=Fb5 z*uOv$(;h=8nH-ASQFAmh=v~(kgK}x7vIP%zz8>{#R2c2^t{z|qgA0@>i>4aQGNXqP zdRVMdJVd3+Oi-$d%00ciWAkJNAJ6i0rZ%8tqvJ>jOUQ6c4i|5|Rh3*c-|vgf0w-E8 z#d$Y7DmBBw8h$}*XQYpBDbnj&QxjaT8}sSJ#oPB(6|BEpK-cGH^SmTV5FLyq&%*S4 z5ewlg?}v${p-{Yqf0{@Ly3il9EFU|7!3F7#@4EtPT%+1?AWQ)P<-!ZT6D*CqDS9TF* ztBe-naQdh8B7TJv;j=`DnNCKe*EExG-I}TJB@j|(W#{pV^@`T-u+}w#G*aRlQEgLs ztAFaL%^|wqV9(y}rUvxvjz4!Z*3wy}Q+TNDkFky4NaJ5*w1Wk|tK8&0Mh>bx*6QPG zF?oAP(@0=M>GNr%@eGxJcA4Ps?7Y(OXYq`fk1L|0K(jmW$0B1z^O<2|=EV~1%q5yt zS8Zi!Y5jib$utK)iLcAAzZ6qmP2QBjl(?`k7GF?;Yg@^}?gz1ol$O?=8B31QIO}55 z{=<^{W8xYEna0;e#?O~oq)KLyrS8cgYP*|FG$UhGXM#(aprVcm(PaPjX~DdK!{5-p zWU3Joz;OwdKYdOR{-MQmy+kcJz_<; zlMPKg-clazv&8Ldg_hUfn`udl6<3A_wm{5-eO3@}LtPGzXe6hZ{t`=KdDK zz$&BLphrcT_G2%?jsMX&vYR8Cp015-bj2t!^pPecrOxze*?b`ue3H+ku>(uKd^Z0=l_xF&*M>87Xq_8M%}RHY z?zhH_f|T#BI~x)FVyuG@#~%*Vq>TbvR>i14#CxV9G#wvqn$sGa0{u8OBc8U zk#*c}!BdvsZ(M3As^pUkq4IxK30WI9Igi&j>GhL(o!YwF6g168_tY3voJBsbD-?z4 z+W|Q-W^p2uZcTriO*g0i8cN?9N>2`@uOYpO^OD@Rfvd5$YY=i!9OBE1-Q(NJyYhCi zMB``s-7XrAwH{q0^umfZ4}xSoyGE=m!^}pCfM6(l8bcWZ>kTfDpmyjdDLw5ksNHxKy*Lksv2t$w;{N##o?H{GH5VH`~fE51mB`&r+4=@?%H^q*MR{&$gZAz!0!rRR#Io96wYz*URb zW)0%c;iSBn)tWwFN+#W$j*<>r7dF%fqgi|K&q-k;IR?S*+^a>~>Vo>35>}1TUQ7T- zn5YJqDLbllA}Oq%yp=MC%VZXLriSJJ#NHPq1{bj$Z82r=w*2&-GI-ZyO)*Y8$(phR z?mKMqQMzBUre9)k6;A_r8p5yY7?G?Qkr+G*29Fe_TVd-*(ZpyO8J@mTfZ4@fSpT$8 zV5-&+<}mw7&S+33dM2f>@}+GtPu}u?m3~M+l(wJbjOkXoL#0Rf(qggHy+|)oPw9u! z_LH13PnnoWD7`PGvHUr`Pt90nFFM_j8pb#^V~ypSS|DfLUbM?M| zeYoEJH>&r!!-INVc>$!XT7v_|)As>5kC*@_YGO~{m3%)Rg7%trWLmKV2*BlLk}|^# z=T&TL9K#gSqRdiMU!>_%C8RKyy{$Cq&8e)uiJOGdNUxi;_GzEZ{Kf(~65-sn{~q}S z`4CwhlaQH7spd>Cn@cUzIH-jYYJvJR0+C*~S+*BPIbb5c)~LI(mb$P-MqNEAsZ%M{ zo|s^Un0?a&B*-hM&L><(&uFPS}=H#rgK?+)9jB2{4Sf15wSD<9)H|U5RAAR zygmI$Jj2~u(hrByMUA=q??U;7q5Qi;`7V@xIh3A4I?OQxdn^lJ^05gTXrwnBg6wu} zv#UlEKh7P^3pe;kp=jJ_tw70wy|~FFCfbvqGqQHUfM2rP0R_P}baxEsnW-Qto<99X2Z^fX`A&eC`h2IxyYpt#B@Ua&x@XD%LMsd`7|acM~s5; z)?(52Ifsa`{N(SYms(~(gH99X7XvQ#;9BUs9|a}MKTeh=%LDplYVB?ML@=-3Ak)pE zX+N(%^7G1yX6Dti`p(a*&kt6WUIWa|tLb`AdyDjvX+PFIYBHTRBkl=O5Rn&2WB)*AFeNHJubAvt&je*(T?T!Q(y zo#ta7{0yZL|GzGzn2}!f(n|j z=*ViHIu8?dw@kgVSFYmJhIayolV>A*Q`=|Cn- z6ATINu^VOOWbZ)c`h#_z5k(bkoeotjR1~D^U`?|4-$y|XsTRXb8^RS_6t3XwW-W}S zeppa|R(Cv~Q>DLC{F6gPLMKUgQr8h)%Y)jZK`m9$%8u~$Tw}}iMa~g&ikfD{JQOg^O4N84)4P3lkBT5mlxUb{qr%m1nZN zH4Twi%Az0=$Wn2nslbrS4btA4Y##kNYEG|!^gLaP?*mVy2?xhcbMnuubJ%BMNooi@ zTzAnT#V{aOXc#Ven_=i-3s=QlYzJCYZ#_@8*5jcoTz4?69vjB`Ywo=YwqqW)sZvFU zh*H)tusqUurzXm`EI6jmTOWPbeyf$J1h7nwGAh}@aMalGb(cRn5ZsZtc*>7J&9 z##?oT#=Dyge;aMdiLa)l4PZZG?Q;q}h1YA-oy;Yhwo)f);Q)ewNR%oEgBnT6V+BIDTbi=vr;GG*2^T5sY zbU}mH_Oi@tZRoinytbADBmC2^XmxBfyQTF5mgOEB#PUGlcaDH2aUxq}RlF8WaLC~% z-pN|>yuAy;RQYIZMQ*&k>~MGRQWX1VD^zjaJWs$q)LGxpYi(gU*{qWu@=U*iZW}uy zt!b-&?ivoB_!C&xk<0by9n4oM5TclE0N-8h3JIT+A!xU@3~a~l4a@0pKiYt| zxo`Pphz|eAgLqyl3u3yjDml4KgSbf$w*{>5$hbBsz{!*GxG@ml)uRV-SQf++0}wA) zy8>}g0OIc~Lm-w1AdUz?9PU9pX|4xx{UkMakpuDX ziZNhVe7wqI@m(|}1MyBWgvD0N5Qr(u>2Nd1(Lg_rxZ;SGj=fhb$39PGFbj!nVU zE+IjT!I|XC-a5yZ{U*6C~Og$3B~)uwDurV^A#b)N+krD!K{Ux_4o%4{ z!`NbWhGEQ@4a4{+9FS5r%`>ymji9obXl(*OqtV+fz$le!3Yk{7jN-~q2Q-`*bztpW~GbX^g z?KiO&_n|&_$^n4DgGG&w=^-`CZ?Y_BsZoWW1-g>fJNJ%dwz=2%O@D!8@6HE>84kbC zgj~8TlGWlpGR^5@a{0c3k8&C5Z?ox^^cGYc)~28*Aw>qo20Mh$ko`!^ z`Q+up{SNYV5DWLd4+p7OFsA57(n532znb;U6(elaCeJN?P87%>PkP={O5TBd4O_uZ zB)QM6WZ*L5+9i}>MBRrrnDzZcX!A6E*vEE*4=lo;1TQqf18LAde zi9fp2M7&CJK7$$ri8%@{o{y=a(-7tH06IrW1D(3N85G;zPNBRf3i z`~AfLI0;x-Xs%gsqO7l_e?Q)2Lr%eU#f^V?nqIaJE}^+RMWZr|W#>P%+OLoBQsZNC zW0^0H_Al7~kZqBJb(j)0t8;N=&dT)ZJh)xUkjQfAo*LS#%%D7@Tljmab4nApT;+s@cF%f=%vBXIuD9*d$ml=HdWmnQ@EZ$P$ zZr`6~qi-7!uv*X&Le#iGO&1W6lG@PmKz5MXd@1nf=Z6uc#tETi= zY7GsvL0mbX<6`rp^Ou=RfW|I8P{mS5{=_oozSuj%JzLXT)G@=@G;CC5#t);(cwCqnKZ4)MSz)Z#t1$al z^~07^e^4}eMim9?m#}Ab^*QWWo!?JHUh(&bV7#d#pXSF6{DsaG3OLCX+DdC~e>9j! zsd1y>L~gmTrg6+F74=(cuf!{j&2B3wF0-(1GcK3jg0%EATVJyGU-{iD!^9Uz2 zMroenF~?~Zowc!j?lRA+FT!l4UT#jCc;Or&rQ4ROll6j1quFjpn%1k?_<|8#w}}G$ zNfes?EI!_|JpSftwQ+Oc-rfLt510H!Eg;x1zyy#L|Btjc0k68a{yoNT!e9z3i_ZPLk&-=W29=J2}J9FmDIcLtC*>f|IJH+z)m~AGKyBFX% zJ0DdMU~zdZ18$DYO?no4TBx2*h~vCnGr(mW}@6cv@4M zt6AwoJN|;i(nmCPJlDF5Ce4@_Lio9r@|%P3gWe-#Z!gqaHs{mIRah+&83;r@fQ$0M-=qy9d+$R1e? z>}?)qn`U8(+SpUAVS=53t&+VhWe+iyo8>BI4L-U6-f0XVL+(Bq$sGcw^H1&sd*OV# zq?=a&b)f6z`b?`dKAzHCbIHU}d4(sX$UR|G@8{C)_SF6u-!h*crv}J|6e)XcUV^nI z!Hu?+1SMfUep$TlZNtaj$z?DN3?q6cgGnJ~^78U*9Zf@S_Oh(|S&y5BO608AuBR8m zn?%B!688J$xPjLChnmM?$;ZK6cNA`gt`aMExSU zUZv)PWezXhz^=h{`@}jfg+vw(w55M`oGZ)6FSMIxYx>SOJ)W6x(`_`dnlEBWJ#!=t zKO1jJ(}&I4a+*jnlbxtJuVQvAIVu1gSpaATfUVMO{DtN%)VX4+ay93y{q3KcUeUp| zQ57~yzDbv9m(-WJA&h$io(?r&p4J?nhMM&)QxR`O|7BQOF${_H4-=WAa4cVnCI1R4 zCScib(~Fz8*f+e!?`T0_ed|+(u0hLPR$~oE$A94_@>vGU3^a-|;cqf6u%s+r%s^5+ zEMDSkOO0lWBOS6{)Q62wZu46;%b4dy$0zE!NEGrE&2*0vLBIN=tMUEc}uT zdb1|n8zU_(Ss|+>b8}HS0o|ld_n%+9ls+Yu3m0A{*bU7>oc5M3jdf_BRr{PK?sQS8 zUVG`VkC+KNjVaO|`mUxcR=SF{>usC*KUH8_3m^}goHCrZU!db{>Dw#e5j|hRHd4fq z0ZrGP_iL57Wd)B9ENw^)atbw6?1slgm0Gtv;?+aXsHu3uYW~fh_>vxcjGTvR)Y_&*Uj811qlh_HhI7zrgI}`Ie zZQ7@n71zbSHI)g$=Swaf%VowmmgTmETkoOeq$l@piM_w#_J-eZxAAzo`R67|4JMuW z7whIbNOGm)3KnvgUlqcMNO%*%w%#ne^%?cb4O|mEQbd>YvD{%9()#oP_36Fi>7!VO zU966!Vf^~~@gM1p#0!s=1k%%C>0?s*(vaSMm-v)=!GZ_;n=>HSI(|BbbN3Dn=|_BQ=i5ceO{86 zr;UFZ2YEB;9#+rB)1a*@$?!lq^-RPLVe!{S)eO6qv|N@*ACTbQBz1`_#7x7)E-ANO z@x!qiYvQiOl00mJInKegE)$G>YF(5)NQ#jk?-Vw=Y6bX0e^Pg~D={AlhUu&v%wOyd z`|bv8mIr%+8(y`BysPI^e!pkSlwo^4kAoVm62C5Zjabaq; zIKaKry5>#q;^!~(rvHVX>*r0so}U}$O}~Mk8|O{Gk)OZLoBmgRZkjj!CVp<7H~nUQ zZkadz7JhD>H~m(AZksp#w)C_+Qq%89PwP%i?c zihB34{c8HccxrlIdfKwo^kpQyO6*mEIDK=Zpoh~3($fZ0(+Ax{>I5^kR|=ElPylzU zPwFB}QYjkhuJTC>eUc27YxhYjd{SIV_TF0N!6w3C>ytaxri^WygNB_rpR@Iqu6Q#P zxb)~_vPZ{sSWg2TVm-_^;kfv_b?kJ-Cr2d4uhRv|)*Ik@ln?98G(|XZVPft&ZRw6( zmSi;~p3)sdv1F6Fl@vykk&jMoma7%gA1zHRTDKv?8eAounaqz?Bo@7m3qo(k98vK> zncd3Gb<_+8yM}p22y?)s)EjQ@ujBEW%iaEbR1U^EmIIMjso}r_(_9 zZs0wP8f?vbkxO${yDsdu3gH~${VJrM*}0mfl*7Q1%FJZOsOF0^xAmsf?J)9=6$ARyQXMI^H zTnG!(gUoK?GZ*-9N=mmjky`F5 zz0MI+PQ%!K1mvX7u4(GTHS{#O{#2Km(f-(-kjTue7^ts#lP9*M3>>1YO=xbDK%=0z z-|cvTE>GZ}4Z=SZhKpnBmW-@0=(uYRm8zAjn&R|ewmnA}nxuh^3gL+}vNZY?oyARC z94-+7@$sKa&ElxHy;Y$3O84qjVw5fUhrI?k{kTLUsk+i@*@F;EzGKwjBPQD4_npDp zF?A%Lm&bnlZNw*ELrpW{Ym8MTzw-2)5!aBSJ!RvWbBf!CN@MMd$T)FL?V8?^Et{k# z)}^W*8A%H94O%vv61#8I#1p5cMpa>OH(=s8mi#W|#qJ$7v2Na|sw~@?Xru58ZwTd& zXX3@Wc<SxuOOe|XgdM?wO_*`B4iow*2?T?}Sn#??JQqh!}$IkeG*`TpS^~G=Y|F#Y`KcUJ=$qM0wHgL%?x*)LC>=_Se_x8o@UUf*cc0Q4sGmuDa#c2`K zdl{M~8$mn=&>PYx4JI&^(?v!uK>3XMibpxBqIbA)Qow9APOgm*KGDEIAJLB>tC7#pO=F&uRBjN)_ z$w_*@mCLJdSFS{QcXbm9wdu8zJv*&Ux^j%If3ew@Rqh`=O+#=>`t~lexg&q|#ZcYG z4C5XYmMJMqjqm%Q)YR|Uk7uSMBilC1SdKxcHgXNw^cUOT{2;U4ZeKLEC;vvyI1RTc zPwVBIiq_S!j^9Wk>D}pibsy*CCN`BbT|}Qi3S~@gW{laSxm;V`=WBEHNP-$jttX^6JzIqR9@;6OlnL-Zz=)aD=^XGYes{G|u3ZY5M#XnnE5$3$Xr^-uCJG42jGxBwtqtnVBl}j3xcm{EGqXN3gX; zHUhA<6gU1C8f2(46tf$dbc_xP2n=Ut&*5)anE9>IB)uVKVu9ww@x46U}P-$ zAj}dCTk9gJmf148G{F*F8f&WQIo7-nTrzTJkjxp#?ugH$TH1THTQi zIuzWHT5Pv|F(%*^INmYW-KDIYV!5}pLs063$8o|=Ggqmt{H`{;Bl%4+f(uR6_v5%h z$>j3fjbuywH+aO(+01dZe5;jM)H-QbH}hGOyqnoRs? zYjNC-rWq2~wWapm*g|%P4m2T+*S7WTgq5RRM;g7YG0ovcrUqOJp{SeETPY_Uony}8 z?1_v{Iudb&Vf64VH6BAh( ze_oSmDby#$_7s!7Wjk^Sngwb+YKH4Q#f&pK zsZ3tOXJ+}#7or<&RuFRzOFW2UV)$U`S%F*Njt{gRz?&H9* zd_DNX*hTl5>AokNLbjXnTlPb?I?Z3J%s-$<6z<*iOMa&0?xo-c4bNWd)}DZCLTC$E)JF#aFY z`me9c^84ey7`kPHSjYKPShH8x@cYQ_s{NOd-_E-wEY-0H>2IVdK6|EdNVN|Hs4i1x z__}m~W0+d`x-h*wV*|-QIl@S5-XO~bSj_KB!HTnU={MZv02W zieG$z0giPXX1$LmhwfHK%)~|&9lN*M{TD41*lwhUEt9KVay7C*FnIHm=FMkPZBKLP zuQdJFArK>60PcPaUJmq^0xb=`zw&N*C<&j**+7@zB+Bkqn(eUj(9_q#rU z2j1`MSff)jcr?ua)sJ7}-rGRTz-CKl89B47JYL)<%Y{v#sb*W z>8}&c`7^okO}ISSUj%ABC38IT_H9>CWSrw~AYkjlb5}^qN_KQ(PzVlarbf8$FR`V2 zEpi|dvTA297ZaAdl9dA1J^n}vC2&mO*fkfc-8t&&G9~|pi@II)w74CFU*$f!SIy|5 ziWR0zLoFq4;X0AC+Qqk0+m=zw&P#j20htF^5Nd>!-OLqhd+;$TMyE_SW%f8$SCFnhKFZtCgQpDKy%-j zNq1j48uB7%HR4!1-+gv(D@cYY^b6d_Yg|6{g)v2smQw+G$l2TR%b(|ZvZ9%|JG_)? zXGVXp8fl~_{D8;tIDff9Q1q?yfT&M3F#~o_g<;RI>OxvPb0|C<-Q7>7)GXXTVx*+l zACS>MY?z=@S5~y?H+^Nr0;7!{88=6mg~ctHAsUkv3k~I@)mPAQLgxaa`cp-k1l(=k zOaAlx7`tUtpQCjUioQbKOI>FZc%?6K=v8KStvYnT8U@C)5h}@ZYKHp-(7YyiH`pI7 z2X%esXSrLs_DIf2nMXC<93mWuhiuQgd--RcjBev6>#s&c z8>G9t8a)wJKIgzec_O;_j6HSNSZ1`-XLfhWm4NK-ZA8SRkAIiXA@9dLGUxNxw1y(FLc-Q(wFXfI_<-UF`>rE= z)yshkQl6qZO0p#7h$j#Lf8yw z)}M-PBzLnG*;u&U0Q?@gI_sX+0kIKi^2WHp1}j(5gn7# z7v*!53*jAr4`c8+Y4EOvy7UotXUV6@jD99(sAaB5&vDk{_MCO3e+_4gR2!+TKEv5T zk%J(FMx6cR$G+C(B3q4{3L1x{yQJw)@MTslNS;RjFe!7{Xqj?lvacf6R5#=>ttIRh z|J0+evg|pdFk2k>lby20YL{dXB$N(A&{ZKc+9Juj-SE1EHf3=%wOtZ+_t3 zEXC24HvRe@QCZwghx+Pv5ea&FX$C4GWm1OED#T-vW6jSeV#>^P0O>WFEDja%Z{FsUCU&Xht`_f_w6D&&fFwm zYZkWqc-BcH)JBi(g-dM+T%Tghs?RR;|5YAU$l0w=4|98-=xFvicQ4SfG|+LoWk$Gx zjt9T+bPRl3WllKT%3@B$jNCHe{0%vV%NLS!ENvw0rdwS`mv;}BuTaKKzV|K+@>OM{ z@>N`|!yqwJic7xw4e}-EmK+k~OC-qmg>;ZFNjYLV3FqZYSg6Vh@)e}XH=l+10h2EY z-0vUctBlAu9(bTN0e1rD!G*2L^YsK3E*3GqaX(Q;GBlbQ5~`Edd!BZxTA4|Q<)D)l zb`5VO8HO=*nGW5EI2wE(VYkK*jQ+#lhBMUg8AB&L>KQr!bd;eh6jy@@40Vb_cabXP z8LBL<^+&$4<)jCOK6r^|=s1#c#FP=vF;s*JRkxwGo>P!!e)3tSR5Y6nBEi)i>C31h zBK|Z7hO!;M$ZZ)94aT!*@#H*1XS-5mB*SbmR3x}>@ur`#-$Q>#q&IL#quE4OJX2wCOi!C_z`z;49lj zBrvo+pAi7J(NCc7l9?T-__3HULhabRoxPFlcaOyToF z;rm%2rz()6#PGdI*>?}*lzDP4DP&)&?Ar%&6fs$goLvGrjh-C4fK45t@Ljvwlhf_V zX(-_97QSZ=^FruWR*k(1!t>!^Vz%V^0ir@?48O^Hbsm(pmBfxZ%{p-=fjKh zd76cCCV7Ub-m;y^Ed*-IghPEsAAQ@GR8RP4)gpWY7zwdz=y{T~)|4PXc+$T!D6>w?T^h5o)VHiKGftCND)A#lA}n-`E{j zND8(gJnu}4OR2aY#;de;KSG^l>G)$~-+hHlmRcC0w%J#F7yTl>1Coxc0C-W-MkYPh-fVh_xTlarByC zUB0KpGr8H=GBiq7&-5z|Id~fWo6NVZTHz}SRj3M8P-4hlt?zw0A}x*c*&nv-Rs}kj zBDY9R165E&Rj@o)TOKsd=eed(WTWzALLNm-<5Y$DpN1;<`_9iRur{f6F$pu1^W&?zE8 zrcY5#|x|J8s>SGW{r?~e+BqV{9 zdFCD~61+}z>2sB`lT8r`#PV!vd1#nE&tCiGb>J4|S*L!LJc^i3iH?mv@d9b|0vT!L zm|88BK$coxJUO0g|I2nNuwVsv^6kHm5AG5}Hum<{B!YwS`us?GfN#0RZ{>u>?<`%7 z|BYo|ZTv;zjD~%JLU1#J;0zm$fBh6MsB++fpni0r7t}bC^e0Dg_gtp0=8UcLRujq?FjtvRzp4YXNH-u`_M9v{`>V` zYBk{UttNhVXf@(cwACoCR%4K~8pYLW^cz|YLDxLlbE%6+5XQgTyfEgIlq05-a84MF zgss&WYHKxuv{n0;4cd{v>WwDoaR+`#WdGM+NcpPjRzb`e1fc8a!8fq>Z2+c)AXC`f4$Wg2E{|NXn zNi3@k(*<4Dq;N2el*#dZHki-GXp+O7obsHFa^O^8vi8G_NfUpHJ5hR=GE$L|VlLhOmQ3B}bWR5BK3mf}#-rr*#e z2)dcIUJ_kIf+W5rD&?J!lq05-a8449goSFrP+OZ2q_v4imf1lP-K4plaDp_$p@>+j zk3kai#feXALYwfcz3TkDB-$j2cc*(vC?ZKL3E)*8ytx2=OOV7p%7G+AxFqrT2Wy9{ ze{h$qTFaSHjzY-pmmGi17%FzSF0PwOtx87P5S+^|c2wKqp=UkzoH~ZtDcqJZ5YO)l zzKH=dEWShy+Xt_#=+h@a=0hkfTt-xXu4H>(zak@t_53?3nuBBp0=9CohOA}!CGTL! z%lw~mS=u-S_|u%Af^PI1UM>>3gJ4AR`?!H1|KQn1zC zfXJpCUmco;*W60OYSz3{0y#pNk)t9K$fN+??ZJx+;0pu79j!Q;hA+HHmba!G&pZ zKIb}j6`1$zEnS`aUiXv9y8MV|Z(s53^-EhCR8C56R-Dege18$hgg5cfcDAP))^m4GU4)_dykEmnRf>|YRFb74)bRR<~zmVV3D{Hx)c>~ z#lBt`<)jB;-259ajBzCCPr@i8oD+r!6RJ)_EkmZvzSTss^lcDY4QXyBK7?9t6%lb& zAA=$58^QP8Ci!;LEu5K2JBtM0xi16KZ7UaqY>KGetl!In_j&MZC+5LdfK3gt|3KA? zc0++OWS_gxZnzAF0+yeh&!N`=xgR+y3D#(vumLl6u=*PV8VS3LvL=nyPa}=oN)qYy zVR?4IaNCOAHX5nGw^@Atniab?OQwnFS4~7Y)kGAR|6Ajw(nUPiL}q)b%qK~I)XiR7iC%)W_4vW%m))7~;5T@lY++g|1~g#ACS0)xtQdWlto zEzs5sHn&Oeg{nNNkaK{X6922Z=@!bnedaID%8R>9xc{Z@8_E?C<#z_~J`aA@_w(Sh z1Lc3V4j+9Al;6(%O)8+#Q@&v+zfst?50qDVY?o1Zpu96SXWWG+Bp8d+^Q)dCKDf;i*;}dhUyJ=f53zzP<6BCzXunvqbra z|M8TUd2D}b$@9EQlqX(;HE?}rxZGdGbr;2sd=@2IPVaz#Y>;sD<0!S^qK zR|kZ5Tjz|P2g-Zi3VJTebs4Y`-Xy}S1K})ZNm({35MD0Ae;K;@ZgLh_UKGmNH&D{& zGym(%JmF4+?-mGGM1+qD-~%4~_5yfiK)7~4Nf?&<;@l<>ZvGF(d?WWyRU^ec2Xbu2 zZr7{s6mNAqQC_muQ*01O{c@Z+GH`1?g=#|9ywi5=Av+X@7H3z_8aFCWs+f&@&_Tzw%`H(VyFQO9X`*VQ?s7k@zWhH2?_Lfb#OK+;~l=%dgy6ehhY; z0{p4RRnSd)Q5i~lk%0GPxvFQ<9cPU8GaP`JCmV9*_B4q?_fPBg5i=h-YvNvgW3BI> zjf6=TfNp1H@$^Xv8uJIq%Y&}tjv?-E3AuiHHp^HA*Q zCKRt(tXUcuho7;-;@XE}*}~1X+OiFS$Cpss^xO60sjDlNswtkfwLow$0>~@_$u;H` zR#1sW&#s#Ps1Jpo(Qomoo zRT-eV15{%vU(q=8bYzO2G;72K;K_<=gZ0hO%?TO0l>xvE&2k3?&34TX75PbkD%&^@ z)wp9G>XrbtXMk!hK=l=%76ho#0jjS6)mV|o)fb>vZsnO$wMo9jz5TXoX922l zr#!Brz?44+sDT1hUjeEtK(z*_#!d4jHhwRUt2{s*5}>*Tg$6a6{mZFGRe%~Fpvp!S zaP6GORU4p21gPc$R9^uq9-vb?L~HQGbLqURQR`t>9#A^Ku%mrq&kY?h9fz!KR}5jMudZO)lN+YE zC!b%=MM|`pl7nx>xS6RP!CrIi5!N%w+ICKm$2TsuJ-o3oy#E;|}A{}&(he(qm_l1Zw-Q5-vG5K((_ogtzo=-NZ1 zN|CcdL=D~jGDON0nHeHQiX0LmvOw;@5b0B7Qi#aTxylfcX>{KSk@<>j79z63t~f+0 z75U^j&x3J_tPGJ-MP3e(K_U28h^$a#VTdeM44_&84=U;LNHKHm(( z)#iM;x|KfBI>%1}M5VxwTJC)X^Dqwzk#c?6KSYX%sMl=7-*JQQdPL^z-X0KD3w*Nx zZa#K#h*aszC$IY=N&})kA-XFdQn%}V5fH@%zBqsnQUSLhL~8Zr_7Euxh#K)X+=&5^ zdSJy@E10oyr_5IV=bC$sO4B(|g^t}*i(wD76 z#PP*=#Hh?Y|BlbA{@q<15X~0&d#`y;lJ-uW*wC;sru{ zQx35re+-dM;kqW_uiA96}KoyL&%|p0aqI$vlZDhMCJ!v zmUq=#`P$22an}Z1^MtE7r|9EXG)wjg_8h-eYlO$re$1iQ)* z(Xy_wRfyhtGtUZnQtpa?c&QMtdD+)qtMD!xB3+8S8Y1%*c_u_U17bsTNdz$tliMdC z?h@i_LXJjd?+lT+BJCkktH@a)!m5I&SQJhaV!EzIA$ohMkIWMI^Z?$Z$UY%5Ly-v~ zQWX$sXN_}jVj3RoKPJKdy!rBqnvhrEsMvJi^9WWZ7suvo4iMzHKk#??za8(A64ANe1tD>EKqEicomoI5kJs%O(3C6ZMIlF}BEPYS?&LW=B##S-EaNT(L~@GV z%Zq)*oJ6{R$T6TuRX{Y(eJ>=#PtOr$eB*VinEPWu(5XD@Ui2*JQe<_A%va>i5NRV~ zS~`KmYlH)ZnB@)&SZ)#Qy#{+84?^4#a?K05%mZhTuU~hpQLx-?WqHr5nBmS38B5)n z3S~;3XMI-9!2I4Y)6py+IITl(98DY}AKage<8)%fQcu3Q)PU6HLAsPl2N-t=AoAP& zU8qZYd?l*g7cVG#vOCK>zhG2h^e_uIA77l&g`2f2xBZ^= ziQUuS-v!@*h^ylwR)73)vF0$kcNR2r9|$-58}6mc9gS>^gb$5``?+{Ez$kxJ$X~7e z*}}JMUnKllBz!P;h(^o*o-e;s`A^J$>&fmP2_F;5KQ5BKXC(dGk@S5c>8Iz@eSLTG z<*9qi{yYDzC)*hb7w<5P#;TA&cFd;N16ng|hz6g}o8JSK)X_?s9Ung9SLr zRF0p%$>+=Nlh4^70`@A7$iOlJdqgW&!Oy*F0m>e-VWQOK7a8^Ko>;n!0Ud5nv|{5FDTWC71t%G)^t zcTpsNZ6y3?;o{-1+p}g#SJLmC#rR*`0 zvTx;Xx*Q$1MZ&j7!gu7uUjFp*(vv}~YPKu?ttb2a2wnF?(*F?&-&+WaF5AlwE_o2y zm4$EFVy<4w(X~N7>~)7eUggVk$gYXx$wb1J6~ZdVHtCZ`UQYIhg>TubBK&(XlKxU8 z{6aqL>raoa^5t`6m*l_oWKW3TdO4E*N+kTBNO+5Uy?U}+7Q)6CdTo`_EjvU){5R}SKJ4K_IdVF(ujRk>WS@!X$cK^ikMd#93;J@=DQ_dY zD*vq~ds`&`Q<3zjy#5k_nHZ_p9+B{#k?`|*Jf8MYwj7k~;{3Os>~;CDr;*-XG_H`o z4&=Y}WcQ1dKQdBIl;0ah(szl3cP)fXzd{*pDr0%R3|~GSx5}3nk}WFa%f1w`*{?;y zuSCLIgg!01_B*)-fjf|WIUnoE4o1RbBUQRKg66tN*Vq*a|0NQ>J`%nm6237K{%a(B zQzU$IAuM(b>q_Q-!?)Bod^_hGzMcFH-)4Tpw}x-{R#W(v-6+D-(nxsYNO+S-c+*ID zR3tn)65cElJ~N^QEs=0*Bz#sRJiZYA3V$~%(EXKfLxnQ+t*YFsqD`!QSxzg4!w!?- zd*ATwm2dd=&*9&?L-{rz_vP~M91c6I{QJJ)+b!Sl?T^F1Rejgj-=^`tT>d%3VTYBU z{DyC>-|+3k;orJL`R?mnnCZh|hn0V5;afIUaAQoS+xt4rm#J^ffAgj%`tA7qH*=?k z;cw2Htgn9i`8Ry~@$hfmp*))b{xW~}91c6I{QV2xvg-?OjOy2?p%Uh^>g#xRdE~b8 zqYC-5GYVnj(GDKRz}Ml}rqH&sPY=&Gj7GU9k=tRoS4<8{?&|a0<)KTl@@$THmZ9UY zD_|B_ddVL<8B%5rD%0)li?n8SW32S6GEdPE1X1w#$vUcUnV#aJ+t~wjWGx0qe$Ktxp}t)?<4aj+CJX_}Dvn zmQj*w*W?i!WS8kD)$VI;2jPf0|4kk9lF4WA@4TYk_BIla=bwLWt?ME-B=ok=&nI>f z0$zzX@}ob3;+pBtMufKgr~i`yG|%99FnfBQ8~kPv3mQm;K^G&Z?@ z9V2(1deZ|6JYLE5K)ov29ejos)3_Naky-+1qGlTRx4!@(x@Ky#cHNCM;aKgPNuQv5 z9b?H|$ec)X{bI%*2-2NOnY%UF!$nKg@wC6tn}gt0uIfV)_uYTvo-vU077+0?$vVkg zogg!JyiQ>TWG#=nYl=kA0ddLF(Rb(SSgd>1${(RPTbbKq>o11f!{@IbdVm%zRrq0Q&eU>h)k9CX&gO>KjfWY=AtzJ^H?#VGl#qLqA zctVvm4U#@rTK9xrv8aXZ<2*4>|J~Lur*M`%eXgz(HGoC{!UIls0#Khmvl=WjE1IOY zs$(-3vDWJ1z^3~2xk&NoYAz5%Yva0ouo>#Po^@5rx9r|cI0t*aWi zP;4`9?g-b3{rO%d&C(}x!{2c;gr6%1uwL(UaqD2y5ZB1Q%6+lCzD_Z^S+0KkDz_KKFpKAQyH8@`@+9!&XLw>A zj}v8rM{Q`>1W%D(ZRpM3tGnxR_gPUL?z75PaDo@ypl2D9t_gy>Gpev?188Vfd$~qTm_Q@ygwjl{~NYG^=oubZP zUb^nr(xxxbuje0!+>=Yz4!KvYo@g(8w=2S=kt|5FBbECaANA8)!z$nUls=8T&reRV zc_@29=m`?3m$KLA!;fd*&s*um*`J57;E&Ar9KG2i^5MnVXCv^VLO6R_BylO>uX~@$ z?)$R0%y`Wr-rie|W!Gzryv7hupM^o>BL5p+WTP{WaU{~Mm1=FYZ@B9&RdVKtD(yzE zj_U=Xk7$?xRwvTOaM$Q5v`q{Fu-r&Hr6Qgf&trzJzGfhH;jc>sNMoVJ37{-7o@Vtx*bgQ1ph zwS249w?+1?%6&Zz?1-O|DW2?TefA9z)9k z>B$K7{K3>zekKpV5M(s!e_DwS%h#zCH4P}SNY;WbKlGrn{Kuk@A1w_rB>=ed?8@nW9sL=Sn7OE%csWxXQA zDh>KD#AV=oZGAuc0VX-{g+~%%mwitrS}hj=CW@E$AAaJO<@NCGUzJx1)2Q|-dAaj^ zq}G&G?epCE!nt_1G4>{|zWm?vyG!!B9QhscpqJl;dHH2$hjwX3=3Xk=kowe`lNp+v zk|lUR6h(9W2j%TcZQj1f*;s#@r=K%x({uLa33Umr(AOVwtzJ1{J%^MTFl`%yIe&A^29K7X#RE?7h-Mrqx~=8mft&;1DW(n6J0{XIG2%7LTedd)6Z(C`PFm|~ z`(1dlo~BU#Kkm$zZz|rD-NJOU2%@qF8!1V#!{UQzQBJ<@ z;03u=qu%TyZph8e$m;sxT=o zqT}g1Mrd@vBhf9h?1AWg^guMY+|Q_-a$ZEMdH}~r2rpSbDp&6ILfHPelz^9W4kgwp z13Kd_DaY{lo$EQj*K!A6?QQ4&>)m7|-s#^H4CBLxMX}!E=H}2!!o$Xf8kNC6T8E;>u8?>qT03FTWz{Y zLWsEW0BpgfsW1MtKE+-_FvL@L7&hL*lA_xE_j+Ip;A=)fi4e;I*1Xp0>b3t+c{1EE zF9P+lMY+lO6y2qIhg~`;&$SjP_Ty{dbMZ_GS2sN2%5ZBF9crAuwuur{VSD>v#K>?Y zOUQjo{*S#CxZ1f5$PO``lD=FwcNPbY;=$2%iG^x|L+;mn)(%Jz@V-&U_59Xxjri&K zH1AS(h0h?oif|(RP=$tQssOLA`N?oU#OeQQQPI?iyi`*1;RSLe*!n1n!cuZKVOMH& zl-#QCk#tnR%3c`jP)DMy%LM)eXN$70So5s~^_uKlGiSd2Y9O|tMHf*|+L&INcO2|( z^y48;Dx1i#ab97nU0I)Q#s>?;!nbnw`kPdJ-%0n~qY>o}mWO1quabr}j-Iy6-Npso z8YP4g+NRXcU39vbeSF3CHkxEoLS($b+sF3&#%gyWXG$K}QuXFe!Q3rKi`}EvkT_MN zFR*&hAd(er{F?qUnv*BC_XeQ%4~bvB4p3IUbg>6O8Gny-u+s=p_o}u>&x6OebwlM7X+Ary0oH=xFUFW_J9*_ z<6%uu9$fW1<8*v-IT^ym7u>w}!`X(@&-pjr#frqU>l%Lfws0kid41|#cT!sNU!~We z_op=R|8SD@QsU25x*=r4@eh4sa-jj)Lkly>lX^|IhtE5bocXhydR4tNA3>{_aRofvMF468<@p)4@Yv0u@(3SX9S_^<`vLOQ-?SDoHkcRbU8%dZFCfPD$XrmX_b+Bb28iQAY*PRS1Rp+D?H`9VG&Kwe^qsa@j3D-S zUhp|{lS}|L>yW|i7V*+nFZXA~>4X;=&LgS*Y9`xmG~6n5T9c-}^i_X})LCNHiLir? z*zP&aR{eX_TkW8FpuysYWqU6e?1{tVQEpk7Y$ zR30%~vv6d~s43~qrlvNjyWeA92=-~Q`?lHa#ObMRHc7NE0{aTEj|Aa?pxi6;m@FX zD3;`$0gd>BY%%YjO-=PoTvONn)?jL&eMxCNJ!*qQYEV3RS ze{9g*^&wr#_*X-h!Q*deSkatUZ*k^)xtnwIT3)Tvi3GeD8kHl5ce$M@JI~?e_pQ{eB%iaJ2Gu)7QRB?4vYj@zmGQFyN30TAiCJfdmWR*?7(x>v$ z@dGW?f`+!6m|4ffx zx@|vQ$J;ftpV8x)v}`b*2`hI@v@b5JXR@Ta^|xv-)%B_MX3gnWaWhs)%8e>b>c)-L zxZ|#81yOM%&ICnV$QqeZX*mZT_s66Dmbqn9Z_@~_;}+q_JSdwU&-}xF=Jpta+aE7u ziDkgm>tr@>4aM=ZS|(^>kwvH1S{Ha(>h1ScE`Aqpzbiw&WPo`F6>2KAw%YH3b3}g} zy8wc@Yov@d*Tpe^4XG^W$X z&R{`UvuJnQELwlJty|G<9`%F{ZG?9|l8N3}@*>bCYSzS(SUe=NB{tx(*oD`ip-k_` zI@*<*9$7IZwQ}MUQzyQiZ}ssM4SrUs-n+-!7Jew&#I6HiU>h3~M-^XeHF?l-G^l9E zw2b7$;!w*Lp40Ue<6P;VHEbe;y=U?6_=<7ar1hNeK?7H0$IO_Q_`fy^)Xl*fZw&Wb;f8&|}6ntS|Pyo_rjkl0<1g?BqO!x(w6(^k1wx_3Wf zU^n-3Ki>HxVohYOu277g0d~84U#1Dy^tX)dlo^}-f*Q2xZ5-V+J5wnMH(H~~=^cbt zRG6NzfCMvkHnnuOu^24i8TsxY*1FI%ggbm9kDX2BSKT5q)z z1odAWUoeoMU_mmGeFJsMDZDaj6aZ9m>R6>bUlcKJ@+N{Un(o=A4S!(!RK!6rwfqx z8n+#$FZ*}g3D`E&SI2wwchIp>m1~tYj0vriUEd9&J<6HZ-Fa2%Yz^{9UcBARq=$o(l#4&=g{7U#mf+3I|_C%YaP z{~pj0%;NC|x!xOO+A=<@zpds$`>J@&^h){<6i1UTTrbx8%DSN`>EmE~TN|l*i@oFj z2&AXZsH=IrmH9qaylW;`wd~BnTXcsypblH^R0&M1<8SVRiVadriqt2+4XR6rBtxoG!v0wy%`~VkE5o-vmL*p zxIkv>?vThi;q39SQ}flD;mm4a9QxnPoKm;ZAw1r=xzcD4eD8nSJwJb~>5rIN=lNxG zykBA#?@aCTGnT3|W4Cw}hXc*wS*djGIP*CMRPD^M^eFO3E<_{qpWe}@z_VCVzNTmN zPNQBHqfai+*I-4g!vSoJUfjA#E>mlBBK1z5gR9+*YySUn@a<>C!PV|neur^zMeFgN zgI^VFYx6Lnwn3(?_xEHsDe!lgDzqM;93opY(seWIju~1Js4Tk?-`U@g);-?pF!eU%?mO6oe*1YPWpuO6CU)ji{8|9qKTSP{fDgl_*@W{< zOOaZU{rkD>8!0xbM6x)t207QyxD8%w0jw!dc-#cDROx~S!hy4WKv z6|6+8cF$iY%6r|qYx&LfCEHZQk~fg=ksS^9a=g%Dcgauvz~oKI^Hi0St8K444N|^T zhva_f5}HY?{egv6y7^ZLYGj4&=z+ef_`W5Va*#ik)EYK+z}7IbClKj;WCx0NKY+UI zaticu5xk?4t{^Grhtq|)*Pj+kQI>pP);bA|ok3q8>BVHfw6CQn`>1-b;qWDH%wj>E5nnuumJFbLje_^=3&V3)>ZTOnXQW8vS8`0V)V;wrmPj#EgeFVAV z8B^eR&C*!M9(<~c-P_TKa5T+$>PTu`X7_f*-02*3Q zb=!y|jpotb4vm4cnrG|8HZ;X+rp}5bZzRp#$z9&MAfij8rdS{3iTjoA;xlav;I^mp z_K^&=&7v=tA#VcC23fNa&X6oQo26!Q{B18Rq5yO=4VbuMV#w8=u3&F&rR?JE==AEb z%ko){znO2$gLDZz<7aR3XVtnbk+W(S{7zN=EO?ym`yZoiT0@N`>tz98#!R-ity!iQ z0l&XBlZ2nOzq^%lAJGE-&E?zlKcjEA*L&WZxW>E>)-J8*$yX({+$tf`eU--4Q=5BN z*u2izr!6y;Ss5G8B%M3$v|%;+$F|hy988*OboouVX==Zj(I-7`gIBAYr2AVnIp2(9 zmz|?_Gf7v2Gk%BPnZK&#x__VRcT6>D!g)i+U}nT;my<{9udw=N>*zB=1P}Zxo*f!f&2p5W?`Xy!su_J{S;__ z^-a;kNlJ|}q+hCod-oJi{Q;hO_pRYn$C6{MVF$I+smHybJUbMb|1yhoa^8Lf$vyn6 zBu5jK*t#XQLZj>$RMF?MJvJ_HoCuY?e`hsLZqr@v>IRgT(Q15Grp626dpW-7ixJ{f zVICrO*MK|YL@g>Xv9sF!fglaV?4f(|a!I7u{Q@%-M=TmaxfAdeRmL&;r5mF!!`?+O z?y9aWOmDcCo)FWLHhr15gs~2`t!M>Tc8Y<>FoVc_90#jjlkWMRH#Q@&-`*UUG@GImNz>>)}3TLK6gznyg2)-Ncf6;xF>sgKD;>F843R` z67GnEkBWphj)c#Ogy%%UAMvb$_wg5Jf0Iw|$sU>yFV5~132#j}y#EOgwsOIs1qspqrlVAG^*3YRc^VF8?vle~4%9__irw3u>uwGt>i%MvcTYO-HQRsS zHjt&pGS7#rs2;QC3h7TX=v@}l7xgi$kw{JTYqkP_1p&aF!`WXA2^wuVKx^O{0LHn0 z+4og5G}LZ<81ObBtJQj4b-ZR#EV+^nOL|`Ij%-Fz((zgG3>VQ^Eo+;!3RR|rK`YsY z>$rBLmaFw9JISs6T+E-yez-UBp6b(nXMk=w5}tZ2T{XXKmW?GJ0#Ci(5bociFkjS= zK6RY7(l#_`pJn>|a<)VAuxuhW?IrCr9Hr6tEog4X!q#s$jQ=80v+DeB*|>0yI!I>Y zE_j&fN~XB(Wr_=AWgu(4TYWV1NRPK1+Nh% zAJm4Qie6C4R8dMZLqb|Eiy^5Vl-Y7$Gnq+yC0xRgbo^>+GQ2R8wC7F`mRP7iNmlcK zxv=JhEv(rNNr$0$((t<-nf#TF5xDKg_#Dg3GKo-W(raPtTfR6}l4c8rZ)N;ysisYF z(mVB=3ExwV_{>S$bux?$3Y>5GRXgY_(DbG1kXibz9UWZ|AsLGklJN{708y94kLQKp zjy0`gvusYx&8M-O967I%oKHg@7a$HczrHt2&I{>7yqwoFqd8p8izR30<@^cAkn@^| zoTq8;R8G!cLcH9aYvo-#w~B3oqDcN@`)p!rw3wJsde8Vz~@*6ee8E z)Faa>)YX{U@k%WDAJc_%$GIjm%-plZy<2QCFOz>YngJ*n=n;3A$DaCHF^Ya=ED>u2 zSCg4(-Tp`N^Nh@k(|T*A=!c9~GknN5K}jM=q3!;XhN6hJg*?GHCcqyn#atoRrPmQeTpBaW+ z+y|YJOR~~!agDHkg*NZN7@?wR0yN2o?l@g%CziWy=_BY_L=K)ZCAM1qSGy@^$Q^sA zq77nmW3Cwo;O?aL6mvcMiJk)aT$Bg1CH_4vjII~u6 z@~v=Ho@%k)*~#2t%g8KiOr@<0}f zs%WDjEE_P5bhxG+Q)-m1<8s@QB+zAi@}K>(rqUc~`g3>w*>hP9OM+?AZ|)Wfi-^m; z9gLuUY*&3>>8XJ#$x!|KL6?fL5ce@LJ)9QMBK)&FV?W676q45dV@G00!E#!%=F z;_V|bLut(+Ft-rvxSILHEF*5~DrZwF+|rN!#JRRy80#}nMDg3HU%t%`-?DZ1S#Aez zE|)68Rby3V(s>Lo;FRocnS1MV#x=9gA9gL2&#xS3jp+*IynnhsfP6F&FHM(nHwk*e z2ZivBk#KV)d_yE0g?TWNzI!A*GZG#h32z<=&x(ZGLO85(7G_+_nNi*Ks$r+=PzF{V zdfA$UH<3F^H3t@Hq9dMZWoC&DISDRWOwYo3p9<@k_gwWL&2Zldy&3Iy<4q6v&T%1I zWI`nV09B%9ear50LB__@C1W{@*H+C;$zA~0wNLe%pG#cH1r*DY96f~g{n*BW56>6A z^SO_1OIvB)3D#?|gcXMo^=XutPZL(7;l(Rh>ViQ2r4SCuSN-oC2fzQdIa>aAj+#%u zHph>B4(J%c_CygCPglBs?vF|oyI};u+k)yH#e7bAMDKe1{13DH*t5E!7mNYfwHS+- z#t-f(ijhFFXPW&OFs5mbla7GJIvyi6tN+~f7Zx<`_q^8N@%s6m{3`d{_h;Z%4)eO> zB;Fl}>Ar&k91wHDDX&8rBx>kh^xOg}37;0~)^&!)aPzebj7Nx9_uEX8nKnL^X1Svh0bl8zI=sM+i`88QpKM9dj;w;HpLm4B|ESw) zSEcsfJ~-5ZCipHxZuW(zjP__eV&6Y38OgRaOl-3To3lg-PBqls7XvHI{C8?Il>HH~4D$p{2qrDX8OHvn^5ace zIbPCRG5_+u&{~ zV7pH=|7q=Iwc8dbGBB}Q?uzM{Y3x2hphG3ZW=F0_ft-vBs`RCHgm_Ub}-NB>iFQ+O_t+m%S4$8 z&n!~sSc_xLa@tiJgRi}JmYl-Owp%`CpJ+A9VjV5|l$nm*$H|N{d-)RMZ987=)=5mc zKK{BtF>(2)LJ2w4KaZeJ*Ls}O@;EDV#scj?SG4gZ7>itU#8@aLv|~bX)u__+0MjTT zms3r3RqV-TQ>gJsFiq~@e}K+fH}3M^#@XDBM#+`7+JeP>(X?LfT=VwQc)1evKWzHh zXh=gkKe6b$q@SHFWamMNc4iGQVsr;9seLg#r1y$-oFZA~xbG*wf^fR1mwWi0f~h=o zGx<0y_JnGhflM(eZXQ#q`@g&7!pkmEVwt<}j~cwN$?{9o*|5Vp%!Ox(I-D)5c{~$_ z$&9&RpY2NxD@uF+UYNg(3SIHFoNag>GP_`No|$_pO0gxleEQL!+`qCAmJ>dXuzt(= z)wjwBobJ%npZtB@K;SCh5}z-P*qzMSPacxK6{8BXY=UQVZIaIXU%A7_#dvLaj_wrOP@}O8979*J^zO)2p%x0Q_E^&moK5CXnngjxhB@} z6y&lhb>{TChY7*XPh%Z76MD3gm^-0OW@(8m0yE(2>r)@vyxp{Nck~=F!)s`LW>&GD zOi(RgX{q|~vRH>!=i}|v5QArqgKSMlsZtAEocuuGB8y|0i%n0pM)ntRhp|e_Nn)gb zb(y}vH=`RXRzRE-uajT>p&;xp)apl*{OE8SLd zTVR~Ex|&a0_shNunE3U$!TW9M>+0s zre~82TNe7*h7$y9y+pdTe5i4D|KeP~R4{dOnYYfC*%W)N*jFu;?%0!VGRq;6;D4%h z&?sUZ+Pj-&Q)Ebw@7qvb7rT6Mw%$A$MCq#&OYTO3xk~kHP}&x!R`aV>@pNN(R>wti zZCt}W)6Say)-C$?&CQ?V)-f;hTFWlX6QQq@D_cMCRoYV*uKOybULR^4hey$bM2GtS z#i8QTMEX=n=x^CR)IS2eO0vMG;B)I6Igxs~nUrK*^P)mZ-f44J?BZpm{ysRz3?k2G zKeKOpwPxnD(+&IFv}XDgwkRvKK#n1KTDCy}1_uPFlA zE#`8}ZhhV&4(`k7$lH*cOyoqwD4DI71wh>x*?Nw$WmD%LzoWXEp-e5uj+W{e=HGyY zEGm4pwOWS5Kz`RIC?0!`s^MCvk1l(}+TdIv?s%p34feQ-K|C!SiG+d17u_V@OfI(~S-zulCxeccn z_yd%S7T^xoc(RoZKsfjKX$u^5J&s!YkapE>%b4-(3Dzw_5hlbzp~=jv@RwVQtYeo3CC-PP3jpU`L1(G zb_KYAx-Sp)M?%^r(Q%$8b~ZF5QY)SHxkgR%CjJ|GE~_(Hk-j4P4B+{FX&hM0?MvfT zt|{hzW_Lm)ZhzCJFAX?2k(GLkK}_eSngHDY*}sosKQE8=H)@y;!Xe1F&W@ zhB57D<%g@B9?EXVW#<~JG8vpmy^t*qQB5cjJ!N?GqT$gw!=qK)4x(eDqB z9y&aF^6+Tu@aS2EsAxXp)m%aNRejkr^HHOD*>I{dg}kEbiQ!+*BX6htSrP8x>a;E|T0gY^7_>Z=+?)U7X}g&yUSk!CC3V75 zU=RLW4aX8`*=&^e6YB}y^Dr+i`E6y+l$={XMw?@>VM~Z9Vr(5NR04e@9fRQQLOe zFd;Nm+xEsWC4<46+{kZjY|LSmw(!p$03DG0))UyS%;aWz&shv70cqlMlRkaERGD+oi*HKLl|zb^E@clPni?Mf^7vB7w3 z%%24k8*{@#`?*~JiMf77(h<%L;ceey+k>Z2e<21$DZoGdD!mzU7{|6{I)Ec_;Ts3xY?bOmU6N3V$kQjW z3**iBu18hI7p)zUXkS+xZ+~tmzAK~6%&5z4w{d36OXBzEu2A6I!J>HaW0X`5P+8cH zOj2L`fg}81iMrOL@B@Vh4EC*rJU+gU>7(Maj(&6y9=bZSK&KzUR2N;2)|FyoaNCa% zq5N_iQbyxHO=RhElTKx_l|fZPftT5J-osr>)m9_#w@!SHn@vFe_+Gr-l0Gipe+As# z=t)kiUXDdSv9s<7%v;^ziPSo~69@dqmd5uzmb);XGt{m$9LT&e`#521f?+S z{)0gB7cOYje&HQTqJ6it>L>{H@Dvu~acW2W$#8!%-c2iq9vX0xpKjT=Ue8r6%JCl| zX@5CS&Mg8ofuPPoNWU56uw?679Ah6>KmO_XqE&1loid;%#Pm>Yxn~%S->W9Vgon!} zelT%ie_O8K(!+!g5S*VySS}lJ-l1*PcafxrHs-F`T>+(Xd;xXgnK^ zg8q>KFTb%izH4K3;W8MsWh9E$rzP@D@or`_3G|CoWkCaLcZI-4ksIkc01sI zk6+?u0YVv3LFHxCp)E~v8zk@ita+^C77=_e;$&V^`r%co?q_w!qJ63dG<$k?v5FMU zLp2iZ465mG4pS8v6mhE*GbwdLhgVc;lVTB&8cxG|X%tf=aVCXCO57ceuV_0qbNZY< z4E%?|kB@NBDXj|2P{vN{&-!jHD}}a>zsm?evWL3rKX6BK{~V*stbx+*<}^(9GGM%& z$fxgnJn3hBHGPX;kj~cb+<3{CU(S10|D*gpto$?RtCzcPL4Z8I7vWS^>yY{JwoM=8 z3g=`>Z9F}qKC@S!4)K=i9O-tk@j8~QtGZIjiZ&21fSy(cJIlr6x+T-fICwd&)a}68 z8OfN9;215oA1YNMDzBS2tt@*3ex~dKU&{VhdEA00ZX05-xMya1lo*%|v%dfV^R0*t zN|w8Js#LcRQ^>I-Z_y(+=*{7ESCKJ0k>vk}y*B}`s=E6B6HFi|a)P3wb%-@;@>*-6 zqC`;>NX)rrA|bWR8FtgQioRCTD9%_YFn$;R>TRylz>)6oNz$U zI-F}n5EY{${6F8l&$&Y;p!)uv-}8TdJ}tTX?7i2X)?Rx}d+nJ49xzX5v)L_1wDHTC zRmm|v^3-#;&naIL42GlXG+sbea0b?rYa8`4D1Nc~fE?%}j>Sa;kn%p8mn`)6TZr=# zbS6Nu7~7DsQ?VN?DLk9opaVwHR^s26h9w*;@#YKK@&!OEZ?74Jn2ruen0BC$Hr$U! zUjD6w6@#48jXz;hJ-3VqOzS9k`6O(L<~wd;P2Q7B_z6DT)8w=+Wm=L?3poUTy~!_f zTDKuPBnPd!`D#ff+x*H(sSEy%mMHlK-z~n{dIOx6W*{ZoQ{Uq^X``;6pXaoGhcVa* zU&5zr-xBU{*NO7*9Iu}(n`)G}%kzYeDSoj#$w6Yryd!c0rAf|CwPV}o3_L{b3x>;H zuJ^yQI9KPap(Sb;Yu?}kpr_RpkI@1199)LUHen`FEMQ~M*JhmF|x$+{F^ z>*p6Zt@Sh*jHpF-e3JJvt3Ak6W4?dyPjDUB<%elT>dR$W=bbnb_sH79*idKI&NIN4 z+Jao2pXQ)!PbOjmaxx?81^#o^ei!jRIkkMXxiy2gHe?{{fLzRn@-{`WnbbV39=+D4 zO6O(*i9iDV!;CD3LLfeF6bc*;p*9yrQFi(&&yRYa!|59RlfR*302;W9TkLZ%;H)m{ z6IBx3Dez4holW`vxCW8I$4%II4#Ea~JykQJ_XwmPn4!N3p1G~)ymbHc{Kk)*BSs40 zzQ8~0Tn>VY&MEJQfK-2ysdwliu!r|hRDzx=T!~*~MuEqhN|;VObC%k8yf{bMxnxV> zr_m|OQ-M=z37BXMhGj^VzRU!!IhJ0@=SRE}1p@mpba$1PP7@{I8ks?yJ02jBlbDPH zEbsC1Qy}i-uRr}?mA%qyDgVZKTO6%*dL}C#G?@KKVC1EcMsTrhK^!-v0GJ5Xt8S zWU`%Ezcb~uwuMqos6XN<4nJF#z4!cMzLT5Nf>Vrjth~OsN%?>i339!~D2ij>4$kYQ zsf9U>D8URj=EAoSGN}z!^8Chk%>C67?PFHuw2$cm*?-dJ3>&l5eASIsrPvbq-yWa^ zR!k6sYiCbXW7!A}*Gh&^nHZpjF}`Wo9J*P6-|M0d@ZUx=ic$xY3+rb2sJ zt!wt39hRqNeFdDn(>jv_ulzNH8{C0oT#7V&isHmI!}5E1#s1waCZ5A?Jg>O%U3JvL zvr}((PfLSF4GZL7(WY%>cRYDc>ke=t+TA|@3cK4dE*a;Ap{K-1nZw#M7UL99&rgFn zFzhU#zn*){<*y}=H9Sz0GDAAf*D}7Q;jze~HTn-_+$7dP^%`t|77}ib;j>_#_!uQe*Ze-_bnN}|CsT6D8KD}O1F7UNpc%J>ez2; z(OWAeXNy_0-qH)w?4;qB;4ojJMVa-f^eL6XIz$Kvt2ECyW!-eujJ}(F zrS`k`2cEHnu{5bw=}`BV z@dqV>LJIwY^ZWnh|NnY^y5mFl^qfL=PjdRnAwOr+Q_|^4%0D}uE>imBZs{@I(g&y0 z;=hvL?v~ymoxVr;1JY^jrsTSlQvEUY-|CiLmQI`g%GTZMKRBH(Qu^E7(mSNnWy&9rPT#8Zy86`kC7vbU zN~g_wE$fz^-!1)MxAY&nrEg57MSoCpVrq>IB|KiN1gE{RV#{QFzUc;x&qwV8)rn3J@wtwP8hL9pQDSo-%_MXaU@0nLjdy@q49NXT# z8SUL~voBG0wc1;G#@B1_Obf6p0l<$>G~>%`?--k%tM*&~JRx~EsSJ4p{?gziX@OI}Z;$KRy4K^i#j2*Y!iu zHP9J0sPp~wg0YSjDL8@r!}@Ja{lQv-96d zrwu(`)-651Tl&Fn=|7~?ro9`xrKfjGPwAFEJC$~i9J&2??YG2Pg}U2x4et6QFZ~t< zvx?7RJ2f5iU$I^Ne~#DP?b!?r6G6>#v#Z6=N-w7kp1FUkPQgC8AO0nYJrZ-rEp+afhn}GE z9juitOB%n8bBHqP*1ApH{A?=D8WG!5BW^!c9^8pvwxPQ(}rJ}pH3ToRi4 zhToWC(z0ZR9#C^t?^GgK78fvsANvpJNJh)7+oc^fC1hgSEs1&;7IB{|))=k0py-;z zW%$RA^SsldxRP4T&&R16Z#_*ax_Z3ZJaq($bBzFV1v*lEdZ%jsyyaIPuezw(sXH^M zyTY7nrtUSnyUkaQus(T>*HAe*jY4uEDamQnEh_1#C(7*Gx~y@$@X=c{MboK3cPYs$0MzcAI@)>&q7v)FF zH${*9aZ#o7yN=EW)BH{%|Mv2)hkuoQ;U74g!aslRv0rSOz_2Hpae|EZ@c~qZ4utr4 zf9B>1@X>4xu97vJI?g|Xoff>Gwph|lT!{j2 zLD{2H_PgFjyq&4?nzn~4S98-nCf_^?R77ud6V`Z3?W~R$X##`kw-T})?=8Usvc)}H=!3sx5HOt8akH#gN6O{g5T zh~Y~Q=;s4Cg)iCg*40~h2X76$hr;>H@YmCees~vX_MMjBv(sc^M+r;xNsKbm;qq=n z@VS6{d5TZM(^7n?i(f;6S_4TC1ehC|Sar2$apfTA?bx}(89uL$U4!=eF* zCVzFTl&e@Y11a!-jN1twzlu#`x8vYy=3i8Tf{ian<3G0F(N_2$jx~`HVn5=ZXeUu@ zE(o($`p=W4_6}szCL4ii@!ZgH16SMszM#+|!jvb!M;GQ87wx_O z>p0KMHvfLDHC{9lhA0T%UpbWc}Mw`+i-^;TcGVOFAqVvOvftJ zfZiRD7X;z`*wkJ))f|8f$J+B~YsqkIWq}ME7}V8@k!{m*Z0G&<+@Zgf^!MhQY=5u6 z%k;Mu7-4@a)n7@)ee}1K{w9fJVCLT?ifv-#xvyDhM_Xuz3mSp9LKwhFrp4q5sIqpg<0B8c!*WNxNa0)SaCbZloEyKRUYMR3`+)0RXMV=7TuO3PIDl1V0Mi5@e&qw?v?&Lc;?lMWW^12I zmiB+9ZYHD$TMU1%zTxM66Y%Gb?z8`YBI|4S|E#{@SN9LUw%$b{2FJK7x0$%70rtPF z*kF^{qr~_fD8LmfOMkX(NzKym{4mHFLF{q`fjUj3ha&HBgoTOWPFirVh_g0Z@M zm(~}wa5`jCc{gR|!E6By{N81Gj#-N$=QHoQM=9lXEwfVX2dyi>Lg-ozg87U;G6 zH2&pn9lY&(z`HaX-al)$YW|+6?mmC}WWzgm>)>731K#t4vc@}n>)`Ft1734ByoK<$ zTY)c6kL^C*L$cw;whrFaJ>dPD2kkS~SN!)@^zXnP@NUY6_X3>GR=`^^ru%ruX2WaQ zI(Ug5@IKDZ8tUzNY zM_$(aeF7J}rRy8Ut4kcX{& zPE9FZvLv!eNR+%2AVC$!ynBHtDR|U?s)>k}T!^)DK9F8HMq=+Fg0!=Rr29!38k~KA zRKDKAITtweWX1sh=djtyD-b9AnIo~`#relD=|(~5e?U^4{KCW2@?Ls;1N#`?dia-M zd}HZVFutZEHb1_{kLz=MpC6qX-(eO~KjVu5$ByqWaM5;r4;;$){>ncY;~Nr;@9o1f z#uvQqV(x18!=*JG%y<&Ie|c&F+**;?v}ocSv`Tuyr4j$!_jCjMr*R@jdgm0ik9Ez` zWr#FZ9!T9m*4@y4+FM(`MePm#rrK-Tvi5HK`8PDa!YymBbj#c8pUb|p%*-bn%&ec` zwpl;avt!3+tluLZ?}j=T*A%gc^#M1|t>mf3gdtQ)uV4S|m2FvjSY^JM_Sz2GqVc^l z;~Q$Pe#_eX(H6C5UJF8hv&Xhau#*#GN7#$u@%;G}q){6vy%<%%GDLB%z0A`$U6R0- z#dn#ocz)ZFYVqo+Ryk2q z>7Q=o)cgkX{fT=7EN-sW7rNf5Z2yyeG{!seBmZwIVssj&F@Jjz;xH5!IAucGl+a8x zejZH|xToUv*q%nu+TE_E2jIBJG!aGgYcbIiu1GAT!IWj~%>&VI$c~|sp5TcDj%uO%eC~JYe>9)R&_gC=vRT25`5a{A=KMnQz2Etqs3IBj z`9wu8^SS&xea>ekN1mn#J7v~8i-V)Ev7KHNVIFDgY+Nf`8{r6C@n4N znG8Z2ecIuDX*3s3%R{Ei3L&77Otl9PW+_!Z2#XrLINiNPg`&GygQ3EmG{A&UH9!Uc zM03{qrZEqgE0E(|H$I6LSHyVVW8eB`v797q&r|x?a2{9L_d@{39Ij}5Pk~ekYKorG z>SWQ4(i(Gwi&3DpH5yyGAuojt#qW=Uu@!JRPOB~asG4Z5?h`*WK^!jTd*Ri+%=i7A z#G3C0&G)1&pYPh{toi=XOpn4HGT)QUeAk#yiXNf)ez`O?-^n<$C45ReUfe`y@e5#!lmk;a2{EQLI8aqOnm>03USE2d`+#=g1* zV1F1aW!N)bP^4$F%bJ*0sV;+VtsdPq3&*7^p|LQuNq<9B5(=63$AEUHGPLHJm$@bE zY@yJ*8sr!J6OM+#2Ksw$Sb`R3ae?(+uL>>sPeG7f{Z^4^dtX#d`RBnNCRYJKH!>-I zaiPLq+TOg8s#ogQ=>&nScor-D16A)H)9_JuZ79r1>bjKnPNBa8Swi|OY(wAv8x|9N z`+_Ud`u3OpZuIT9EkNIX0b>gI*Unk`k*ROr6ROoy-!A%}IPhSJIN4&zi7;HS>HDyk z4kZ_BaXC>z-t$jqWhP8isA9~q_8t;NhEW8}aOs5#E#nx+yn7CwB*-PBM?%pE@%Orj zDH6`1hY+CYz6?hDj~W(&#FcF8bQg{PTn0UD{$K=GInZxn$3u2Gtsq*;>ylrXh&at3 zitcz{x!!{I+7bxHHI%I@bO%4>wA2`qbQ%#nUUt2@BG-G$^+v-Abhz{0%a7)EMB`3X z)9At5Hty#pzK0LP#3DD&HJys*FWuAPJ-NGXtIKK&GIOW+SksFMQsP7_{_RYE)*#pD zVjMKCf+#3XS<4ZoQ(uPo6s>s6nLdbbk%||bR>guPR{6t{%n~D)@~5-RwpYFkneG$C zYj|H0h@wJY&Xc`7%KU9ZZWLgpkufs9d8_i>ZJ3NvZthBC$#b1eM6@un0` z2dM;sFC3vU@+_jBX4YxF*Bl|;d%$4m0g&%LDiiW;r2Inz$eYXx?t2U0!ePDVAD#j{ zPJmgq*u`3^i1&IV_g_xSeug>+ONeI=s66kjd|YJ;3zDxfUg$GZH4m69TGw2=XwzHG zqU~627VQK6Xwj}`+i05KW}1_K%%I=#-HY36aL1wXwGu9b`z0km5jZQ0Zo8f(0|ITI6}s36 z`d*X${v5KW+wAydWS?NOpRw7q`Q)ENc1Q;Yhd=hA{a0bZ{gL|u8)~!t{^?RX8)~^+ zv$=DS{o#J5%P*_SfZ*G!d`lB3)u}pN*Q*1q$2bB!m6-KC4F?XKtHkfQS^VAzvN2@y zy@A`x;+haQFedAtscyw-MNae26&^T#YzanB=SExuK+>Dr3g*u^rPy&=PEck-e1&D; zD*cy;gUGWS#Z#d?SLdnfPl(~nQ3OB4p>;qmVZ?$+ha8Fz(4ZKx)ivfdVm9{I0l3ot?g`Qat53@6CKScd_E06sa|A-@GRqCmcb= zE6(&CRR}htjVf*_4@=od)6saDOACg1h~&Nj1IyFA2FCb^_q5ymx#L{-GmWA7bE3SQ z%P;83z!^69f~?PlO^@42Q)pYAj$_*MN*G88-hSkr9Z_C}yObi4L}RY5Ixpw9{);Ap zxDR#)307`HSFj$dl<)sZ2Xz?h{TTNETUAlErYG`&%Mnc_o)_Qfzal9nU6hN>YQ<@p z5ta)dSls)c;N@Rc8qdwa#OwNrnQc4}#HFsKl5Ta2rGB(X36F<}9yj0peT%6@BmzNJ zVH!$~#nrT#r``W3}Wf}!5dq{%%!$bG;x%?e7g zHbvU>MXcDN6yecRC#R9Sm+YEw&er{vIeS=JkI|ccFnZfvUADj7hv_kG8?K>SyI-o8@t|EWoOA0BIul=o zBynE<3Ie+S0i3GD}`20OcrA&qxtoMJ%MvcAPeZ<{8vV{*}}8{Fw^z?K-Wab+pn09W@!E z>J;r)dR>C3szWM+rK|FuD_>I8{AQQ;Z1X(0>%61uyy~NJswgx@T+B{g{VirFvHh=<-D_w3edW_r%_d->c$@qrUnR5O+7ErN=-e6Y8v2k{peY*#66l z=D6-hej#Rou&obUm!!X7_s-b@RLM$^`T~y#TKfynD;r z!g~TpPuLLRSL4>YEH>D`zQ~Apuc?rmxU>?zX8nYT$(p}xu=2J6pUA&@bs?x`?^AjA zZxC^5VTyzJ1d05KVn!@t(kPjabr_ub9bsQ=2A96x*hru=? zwI?*A5^Oy{UaKxLBdA{B{{+A${I-P1O(UcNdcE;gg*cZQ)FBcmT$k~lev3?vig~qY zp3G6F0)6P+olm9pb=~@N>qndI58K}M=k@zC`g3uA{W+OTt??Dq2>Larh$#s=cL>>{ zYeD~h-T7Fme@N%G9L=AGF05#8s49KfwzeKOn9wX@OJ3|@4O6n-|GclO*eQWv*2~?+@pU3()}CU3%o_- zXZG)%S()R#ya&9IU#9mh)}_+GeRiiz(Itgn)c^FIp71~71&9#-i{$qP|7pDv0esiM zzqn8MxAX%4ml^OI`+$F80N?iC=@b4Q>$Cb-sR@#SM{^aQRu;M~Lf+st7Y`TB&aYCR zpcSbp+mWqPG9mf-BR%o`iBGoz{v-?k&9{4l@BaqynzHd`%0^Q*%^juuKc9vqX3Tg0 zs!3cy=^?c$6Ba(9Yw_xlHThxumZx!TO!&;U#I-MuYbY`72fY|Q?T9(DCM=fn! zTiNv0*-q;llxcoUnl~c;KF6O9^R&STe!20Rmg-O9vBmtUnmw6+lTY!F<*!x$nkk98 z+nYY$$+_-KdS~NMJ-_PD12Eb;t?%&Z&pA2R09rK=A{Doc;*%S1R?XuDDE%*pAjhcBevD(8j|DUhg{GrGvR?%yh#*r|l87K8$G&&ivP zQiFi#p*)*4j5K%vR-qJLSYTdWDqkOPpRH^xL$Bzk#;tcqJDQjBOaIaM)GFteh0(-c zm07;JJtwC&ac(hc`s`6@KA6BZ3OTc|P@G)0zWTUag8$bjgWdcd zO;r^iG(Kdz2tL4frULI{KebO~1gk>tdB&#_sFQMum2B)Swok!uBo#bjwohiq8V~9m z6V8j~Tvyf1EUO2*(Sz)9D70JmF%&c|vOSc5Zm!1JLS6o z+{o+l+%rbCP0tzIpRHsN!D3+YM9R$tTXOuFus>DJ8wMaJKlFnkIp!m~@e+Q!PW4*< zCOuh_82L(==TGNDZ}iyXiVfl96m{bW7bzlv=C9%zr{y56l6SDVX5dXh9z#WzxT4JU zrW7c^Y{D(e)B?KR6-5*&GF7Wh)hYU*@<=0-OQ>7V?-JK@i>O>r8WmfMiamJG}V0SXi`%Dx!%v4^d~-JhW>Ok>5u-4H{HpwIMN6sj_1m{Kz_Qctv$Z`;-rpw;FR-B{M&{%)%|}4tG=^aCtAX zZ@5>b;nrKY_1)o)?*r~N{lWbKncTu*zL|kB@mTH#E#L;TfJ;%yfx#xPJ}b{n^57hK zWhSpIE3YK^f>GsV=~H$J&uc4#v&*mKiNa6Yg1>2(t6 zXWr)>CvzjzIi!6Q5Fqws5Gi&W`q~f7e;g4u2>FG0;5Jf zv^aX?q=FdERM?92%(4HzId5=2NCbuuQy+g3X6U=B4>atB!M)PPaU6$e;P0K-G$E>w3#0)G3O8#Z;`rC~gesHCAiWrV3rkg;9-)0oLnaY(plu3Qo& zgvV@F`Wpsk&Zgy`jo{GyL1Bgwv$`0SqQ9m{Q^oIecL&qmLS2Df;D5wm41V-k|HQrf ztN-`S)<5gp{nfu@v-R)Tr@#8;>H0VcdS5E`YCQjtLi56VY`^%}A&L4;-nb!(16E){ z)Ku#P;eDHx6JSzCh!@K-cEPpIys<+%Uk>j-x`t(h08?5{Ci7zz0Djf6fOo>VMSxE) z5a1I7|9v-cVnGNiw^NU}+Wk$S2fSPcr2_b3|G=4%j>^-J?}}E?ywLQei3W3$2go#( zl2OC`d;9Wi`Va(r$@inu_s6*!tazCdl1Gs=d}26WgFK1+qh9G=zmol5AMXEpyZ^Tl zcB7$`wlbg$cHbOkbBKe$1F;j5FY8RQ`r_X1kFvvR-tXRCnd;{IzoV)lg4=v38e{JN zhp)8FEn)%`8N=UiyDv6%gbse#aq{zZo5Q_$s-%(p2j?E0TV{8dO0f$;Pc%H3&Y#BTT?*9DOKDIu` zm;V`14+5%<)IQemENE>T!d47ZykO>9J*d(7KdJRM^p1EMZv477wNhaus~ETcC#@ys z48G!S;xdMGb)o+Qwl+VQ@k>kmQ%Jy0jT_HD$GhvC!m*Q`VW&3WQi>Zw9b8z=WM|gc zsq65Ao;sto3D6M?8>Wf))Gk>0wGj-%Ce6GL7J*7a4R8x1ZV%>^>rcmCvZsB6?eMrU zr^If@Uh=QpZ2A(~E71Idt*G$NbmKccJA`>WA}0nXTG-4zcL@^ikvomxbL08(N}^v^ zI=2`N_TM-eJEqNl$dXlWhl6ZYX>oNl^ zgkt5qu*z>jxgh{?qotOMIs>1QMV~Pzet^d^v=$cFqL)w-tt}_`1*lNj?_J+ z(;l*;nCS`0{c@P4O#RV?FLtlr%l=xs>GMAJ*Go1h++UX)8)_3x^?E-WO#JGFEoiT) z&-TvGXfNL{uw$Ilp!Sl-k(VYw0sYvcM|&pNRKEW&dA0=fC*Pl=6s(AL)P!UXkb?T> zF+YJDJC>w+vuWaIAw&$4C26m8dzL<9Wog({DAUmzJm^j29eI3@2ezJpy?f*5a=^#X zIOAw8I$s9zb>{~`66ME7}!MEq(j&Y~i?dl?G#gWM25;+E!kSFn4w3l7_o$$q`vWKviBD_5 zqj$17BqEBrF6L;M&8Z~E9xUY4o1D)!Q0LkXA1La7Yb`@f4Tx#pF@n>`1LWfM7cJfB zcc?rAml&r9IA^GNdcU{mgL!u%c9wr~7ZcvRpiuoKepyh84jX7@+_uL*1)6A3B*B@h z^|Q|3$=q|WpO~S`#rWSGOv!vY7SNXf@-I67WY&?M@y_kx%1<56A-~Yi`Wm~CK`*<$ zDH@m*aQ>6FxEw?$ntnV($*^2dj zk3F`T^}X1iqW6ZkWPNWFG_9?F&<`NetTcS}oGx%CW3gitGWKery4L%7t@o$=leOMX z>y<2V=S)7@^TDqBUMai~J!AKx2sP?b+DZ+zrY%$;cpO6raiJ)l9X_pxq@&Z5P?|Z)3uu3p0MMr*Mq5lSw-6x(A zLM`BL`=uuvyEcn&uTi9Te4A%;dcn85m6L&Q$FMx9!G-jsO#`&_G}bE zc3OUms@T7eXO+S|{ElYcR1D`-2pY`ki|d627Cr4|xs~^)9z37;N%%N#Q|-qH z{=}*FJ=#08)8qL$xrS6VE(itK0Z6uuiZ7}9{%t(`E%-RRh)(Q9mz|ams2Yi14&Ssg z(%dmZT-h*s9<6{5JFVxN4N3orvS+6W1&cY_KltQxw(3ucOEkP9Ly0;V6O`!evoTK2 z%%DSesdtI|9iHol4rTK*4{KpF`I&2Ijiu<1pP4|B-sw-3&FO{y?5~^*`eXSSjVBy# zSuotMJ{I&aNZ~8$AJTrtxpe&+@s^c*4$dXX|H(T33GuK7TwOyv(gG?Im5zhJeA!e# zBDn|0S1AA3lhSF8BjhFT;-8>?`27HVuj={zc!Z)P=VtfvXxw<`GWA`H94xLUNPC*5 zD@9@9i`J0J9vIs9CUsc!M8~E7$3Vzf&c_MKch+U_$1L*5`;ZUJv+b5y<#p<4{9+6O zXH7OT!iw0H5%b!rHbCdzX?l}|?-dr`SM-YSYh&kt>%%t|<}{7UY3#_tb?#YOT>sl@ z;rfckx#9Vy-8@;F)Nqwev>xo!eHg(6!*&E5W%BQ*ivHWx>3zK>YFRVbN6!C%zE6DF zj^8-mX$mxcm(iD3Eb@ z6s_%!0w;`vh8cOG-+4F{JjmD|!vDYaw*G1Se?9gMtpBANKaOqvjbAsKyRE-Lf26>N z>^c|;eBU+DHJ;$}A3u46#f3RqEGt_j2ay}nrT+GVA#=U%hdT5Pq6h!0`$71S_eH<+ zaeK1od{}iv#(o&_AqO9NrKK;1b1^AB7hkT{T!6;?(D9!5u%b75aCi6p@Otd>E!hu! z(F5T_-sk;~-|sR0+r#Z3l*rf(J1|g#5|R3F8pJ^dDDlY$f&A6qJoJGN_F#w*>|Bxa z0!irO&kB)*R?`C8=RUN*(fIvp4|-ubWrXfpxStiVOEV^kSPklbA9SOt7e2|J8?Vz` zKl`Tfy?}0rF*WUn^x{q$3yzGnodLZV5mL@QPuwDUp>reXH_;nA3WMs%2}b|a>-_w+ zD`S3M`X4htnfUV!&(GuQ`<R${V zxQQzpeDT*v7L~?e5m;)hs_lA!_AUcXF*&K;a*gZKLK_QoJUQWc-c(&qL4x z8`&Z|tY_a92B<>E*djAS3LVAtRQ5hUyZi_J`Qv+A*`Fz@ux0(Z4i0~7=V!;Q?ay29 zZgGD;Lk!v4{xl1`WWg<6uao=ikNC6M@FNN<_7!~j-6rC$2x$BcS3;__V$>Qru2=ob z`ghcs)ZV*-j)_v(E&B?Y;<*;O@!JhJhy{^)9~y5!8+L1!ssBWJ2fia|DtUL{F0YznMBe)GCcRt>f5Zor#&f(Hq8__y7s?)7O5+yAuVp zhx-}tx;MLxcW)W6QhRs-GE;iI57|^O-XE^$Hs1dMR=?w|d2sXi+|T+RYx>&Hc=x5i zX2v_9`*_QFQ9C`}=MkFH<6UG^!FVr!z1w(at?F;QhCjKsqYEVTqp}($9$Tf~mHHij ztc~Ap!Z=HdO@nIN-?CXw1TaPJv_&4!pP-2Ots+O*B2Bi4A;Ccr^IJuBF-5LyfE}Bx z`iiqY+45E!R$95In?KGw;G?x7bu?H-dhMP5OxcGL`M)I3Fn5MU*HZ_mlRFe$oF8iL z9$@y)_Xu{{@B_x$(^AQ)tghTLAvS*R%y77}wX*|L-CW1O0!} z%5Ht>|CdX4>!$zDqiT2kKLgCt{|DAa*bt*UZKMBzTKwJDAs<*J@6?cxn2q2rlgUih zRel)wWs~J!MAOpgNv zc~-xry&sB~cxc4uY5xT&+QiSHd*KGeM`R8Iuk{zYqK24R#{}vFf?wrUF zOyxJEFMs>pe&zbBUkc>9&CbxLG7CSDUJKqiHPB;5~_w|&W&GH*|J@-)Gp)mhv*3 zDbj;o*Etg2GZy#L7j>+#ANpP2Cwg69ULnNZnzg?2X|{Vd*r{?8NbAP;dQ-aJ$A!F! z{4w`pKbM>FT%%mzzzH{Vk&Im|zIJ>a9(dXSu9sIVZ^D*;YQlT-H@F6WgFPb^EBp30 zSlO%nk$76cexA9i|Mg$0^R%uTC8dpfLwkx(E``F<^dbkPe> z^-sWDWfa6U`q8U`_=4yAVxCVjIib*}OO~O6_;7O4d~}Av&gwHkvbrbid0cghcl+&q+kF+v)&0@o zp7y%B$L;vD?3H(SAOAOCuRCQ$|KtCc#-C-szuio~bc)#PGDd&)b3$!QxQ}f6RbaxE zUNc}Ss>$6fA6zH4HUk|3e})t{k!i1+K*v+|x;-B=_9(R%>QD_``sVC)-+8^?d0O;T zfG3hZ%%p@ug$Q>bR8%hQZjZWQ@D}06X6$w5CPiC}ms90G)!~-5CtrLvI3F?|moVpr zkr!tF#r`)S&kPT`{%h8Yo}}{bCxAc3y6h# znG9Kxd2i=&X1S#=`j5OUif}3C$B_|lkz27bR_=Q9T<;65Ki5wN@c-jbSI;lwqJ9~P zlh-=Ks+Ky#BCDKXC#`iWUTS$Y9T3f3U6;%2*cafBdja)ReIRsK z(FNQ!$$_jGe&w`?x6uv_rynlm?O#{%PV5Xbe!YLnfrAMRnWjYiQHnsF5ojEXj8f#L zXBb7My{#^^w?ǍM*h{}M_7xbfb)_d6M@!!g(7ui`_MDa-4{*N- z-hC7hDm$$gfb*SCgk;`CYYGLpw0%%Pf?HS|Ef4Z6uOCQ*a|j*A`FBBy>F`@m+YYY? z4TJ*pdDX0D+)TiipN06LW*;8*cS@071xsNFFtHHi9U0&B(3BueU@+@dSgq&mX}IW5!q;m$^fs{f|B70ai{71Qt3S?{%< zA8{^fkLG^NO9T z%!{THyGCKwjuWGTw~9ORilJPPE@CHCiy5rKFP$5#{$Di7iTv&EWL21SUIPzr))|t! zO+2sI+>TQv5B$XU6cid;~Eo)JKy!%{j>H7UY?EdNQLp~=Vsl5Mck}AU>}wuF>=K?8+!44sNIw& z!_h7R@>K!k<|_+Wvuzp&Yi<1djFTksjUhwn{nwMeL^A115j`slHN<6xw)|`f^OL5O z1d%ZI#!8dkgi>xA&}{K^;ll_y?VptC+pe~BMqwr=3m#X1`{ z5YHH5Vy;X_yB&;)B;2h&>04U&kZGeT2!5t+=F`dyy%Z#90|~1+|n1ChQ4HX zb>3njhTs+i`f=`J5MefxKX|AkXeWdAr|7fzEyH*kr%}*%FNjs_rx{*PMJasAn%}@* zwlDuMJYMqOUe+%kb@lun{N_YNtk+`47|ND%c9C{9xwc(c37PH7pZUV{Jf#lUG-{;A z>k^NhGma_3iDjoT>LHg=^P4LRau=*M|E4P$`qFbg&!Z~_UT^csxaH&?`<7_ZZ_lt7 zKTE*13CRP)dYSf=EjzFNAY{!vubk<>)+gFHobA4aXI5Q+N3dbraa^(Yi4^M96mlt; ztpNWOA2&ir*TOwTnkp$a4z>;7@@DSi)^x?kZr~cR@6~M3dG=_p=UFnwGWa`k2wCFX z;eWO;eWVp~q`Cf1ux=b__aQ+A6x=_X-#w1Buc)aJ))L6M3NoEE)o0)P2LTCQF*m+1L{-)ns0 zRNbV2XJ}&8nCp-aby|ufGGzLG4KnlfapS8n8&icza_5lJh^Y`K`rZQOGu}9f>;?fn zG>xyBa7{-t;oeU@Q8K}85L{hqog4tYkxb4!Xnaj*FXV@2ZmP`zS8Bp@f*;B`)8^!m zQ>YoggzZ`AUb{%@4pZPL)8YqC>)Vj4Nc=+f_UhO~?QPlL-O>+3js9>726m4ky6ChX z0um)p;U9aBu`c%e0stiiE%a9sR=H0sonp1}clkt)1=Xz%H0$ zbAKxGqrlg#1g2v`^1r#;nOT4P-s-op?M(gmv}J_hM`u}l;HtGtv3~j z-R)a{JkI^pl)|5-;-)-8d#Ur(;KTpo`FrkD{hq&HJ-QX=@8r3f-x^S&kNZShc>Y>` zFXFw3M_eG5AU4IAywZ&k?-OP>GH=5mg^Je;J2zYi7NTxIDE)CkBzHsSp;oUn4!QQl z*jXG{T*!UVX_+rXijU(G9*I_iRh>Xt4y0s5P}2E-2JQIc(Nc2STT0wtVLT##HL zh~9_V5bt1P;nkkjCq*zJ&B5nqg3td5K2ww&|6%jlb*csB*W{(oD}(<%&hzTj{-B@C zzf}&I#}hjr7ZQetXN{iF zdCr}^_jcb~JZ9$ybFw89bYaf)L-T}Y9GvJHv5L&S`|u}{br)apyj!}Mx!VSvS%-9H zyL98sL;COjs9lGnZZ8%@N}rYbPU5y7V~J%?Ho7W!Ih4>&%Q%Rm>n%zSWe0?OgI>3a zA792RS7rP~71UVIZ^UwV9(nq7*l;u^1dT_;ium!!U-O)ne;8U`rw^)7&tK$gA}Ghl zHlQw9!cwKA^lKNG13Wm#y*jii7mr=uKK536Q*#eB9-!zw3`6M$NY5rMZbRwWq}xaf zgwk!K7n5!a(u+wiCA~OEFO84&NiJ2=tMSQ2Jy^4xnrr#pVq4SYAN-t16|dBlG~k$Vea0cOK4)ACKycCpSILEA!}I8SR);v3)Ejk=Iy65je$p zPOCgJNHCp0&28R9q`%#1q;h=+k^XjK5#&&EBSi>$Ib$fFiSjp%q_@d=I67+M`CjyB zLi`Kz_I2YbT%HY4f--XOC2gGW%np77S9UFrj#6i@L2Z<9AP9v!uT zg(ei>@op0Tlb)Yh|K2_qBrg+Nm^kW!Q{Xm^hXAF?pVe3Ppnsdw&%FC^77+~fGnQRn zqD)9z-};%mDG{!tyvQlsuYRUi{rXQ0o=d-8CZ`=~nPVm3Yl<|-*uG#7dT@yfhnQY< z>OPAKBYYSX92KD8aIz!u(Z!L3)Q5-?$LbP0!s5b8Q~i@!R{8#mK>2=HFUt3&lrilo zKF6i(p3a+Q3V_kOk5hVnhH#L&3Z(7><7u5{su#QO{dJeH}t()a2rK5<&k6X%~8 z4U89E{wEzBaE`4nlT*GrlDo!@AFNlAAgE9o|js@RC>|5&R2kW)!TSH^6D#L%ofk(AD|ZneJ@vPU*jCu9s&X;Pudo z__yfvH*ZcN&KyH_C=W%vm5iC;VAv>%R(u>AE4CifCj-NQ0I-wSW_GNiJ$8l(VP0nX zufBW7`HYADb~Qd1DSboyEA~4*6$Om25`YxXY8sq?O8rWWy2$6$uPmDO)y zD$Q-)Sa9j#mFwHZ{EN?C9~%~omX8d#ijUc|*Ad)@YnmAqU%a5sE2#25Iw5{aLDz{M z|3nif!^pnXRad&S8n(K0LG!y^v@+!pBm9x5DQ~Os=2bPf6&xSW+wOQTZ`&$_$PWxt z-gy)A09*rfNhVN2a(nX?<+`qPadqyzy3+al)^bgkAi{40c7ed27$3dciQed4t11>x z`M|`S59E~Qwp?fWu@p~Zty{5}Cp+hvcMk0$CJ!@gb+s^cP4XlX)iA~DYrKN$c(iOo zjmJO9Wbk>3{am2W1sjt8hWYiD@Z4RrU?cC{@o#deKCRcMGV`fyW753PJ6njuf7^ia zu5&DpH?PVM&?xy&%R^rgfrlOhVY2$U4*$3JvbL?O8@Fd8_;Vipe3Sn@{&5M+EEVAs z7Gn@W0A3Iw)@)P7ej{kyjQHgUy6|wVO(haG8DeV7`p`V+)GR zJ!RM12&4(-LBupWZ|!fVni#L%y7KjbcB=q~gY%t>^Y8dGTF1Z#fxn8_xXBq-JHl_5 z-PW*Hna_8%&EqSBa7}kJ_*KqJbD8v0w2(m)Wf|&Y-v3kh>vy6&;ZVraiug+DsnOzM zJr8N*Uw%?3!w>vLFXyUvR`Uk!gCpsw);-``E&>awG!i8M!u*gfaz zf7$*1EF~vHxx3madg2?R5ENL=t(2 zLEOz|NEfJ>&n}rCtyn*0CszgLq^ee|We2zOv57rI#OgrHG!zboXEaU!Bi_Q}5_#y& zhAb7GP1G|Eku}Cq$v7&5anv)8#f_`#ybtTV_t3w@jxqdhReWe9F%4w73`*ztr!vQp zIQ}Y$6L3{}Hr5b{9}C56FM+J1RFVAmXBMyG)#Cc7$^h19)GDMuC-g)#Q zuZf{9MB&5qgRGIOit_uB+ItsnZ zyBH=XV(nU1kMje>*6|rXIN0fnb3@z1fC-9qynNGkDZ|0>2OGn|&}tf5b&o~4EdLK0 zE4aEa$Gd!S&`2AN)LTtkW+UgM8p-heI65b7qIk31wDhO3v~*d}63Rf}H!&Ci&-VRz z(A*YV7r<^La6Ee7vYd^>-)ZsOx82e7vZ}}}o<0r5yPbmidPeU;O*yX+E_+@mS z8&7HPz=-#9G(Og?D}6SD=Cl;Md&^`MnFsZrz2-yvU(~t3%N4uRX4oD42_v~3k!v?? zqA};Xxr6Bn&e3vneIzGO)z#FfkKMmUE1q;(RzR!t?DVLpw>Vr+*W-1YwyE$XXbI*w zvVvn~xQ_uayhcd=}k|MqhCUP={$OaqDCkjIPGQP_x`3?4^4P^qm!)5%BR zp_m=<2>c9$8s7xzZAR8<3H~iArgyqq9vP%=#h4}f-lURxbEX4gEpmNTvFl%lC>^DQ zi}o5cU+=g7O*k$~!g{CWep7#-YOkVp)LXZyzQ|4NvG)}$E6uz9XA-QW-K5A`HQ-tE zo|_Do5qokn$4<*YO6fo1p~(rZ`qQwn~*yVU5y*NI+s81dd-N0e^(M zpKD_NYmxK_^fr1}b!W`)O!P`VMk?B!<`-E3vZC?HBQi(zn}NJTr7=w5hsLnumX6_2 zGlnRdGEUkNtf0nHRJG})`1NKb^_=ko41(5t#=x{{eQBcQWDSkaZDwfyw3ilmT-$gV zNM-w3wBmiI<&P9Yt=|&lpTXKxEa%B`Q#*KoJct1A46`eY$BfgWIFwpN3of|yk;orD zRh)!{M#DMnxpX49-xVO-Dn3WUH@wRwGRu1tKLp{>d_LI6f?4$GW-hg% ze|EAkGKI3hFuSZL>gqn9MO}-vYQatXF2GZsal*U|MSAgQ&ITCS8wS93ff$vp_v##4 zBVMn9Ah0Q^)28&j9L#1L_&0LREqM_$WaysGPjhza{UT%83-BG1Q$QjA92IXR(|)JR zYk?Y*t?OX8{U*$kJh4{ZD7qUht_+qIfw<6<_vdovAypNEEpgq@u` zn(``?$lpyl2E}otwX=@Fh820kKjwc7Zg<5*gI9)l-NbPH;Sxy``41_}R1OGodLJ*< zi0G2e)fDIKw6>~0jHD9(jPYcJEHv6!`Q#thObu%03NKrqhKHt=6V(bksM6vf?S(G9 z#-SG%W{Z#=V+(;!U**OdQdB&7?=};aUuMSfiu#)z%3&uvOT;*WOhq{LT}&vhSLm&a z#G^a$D_Yp)mhyLgq_iz}9nx>}7X?#x=5KkMH?O%3OXs0X@}W+}(kUo2vI$nQ49s(8 z-E5A68K8Y|`HJ;yqlZa(SX4Q)>T=LP@S1vC6|&?`GQ<^Pi0cOG9o9a@4~pm;qy^8L zfFvX}f0yyY;rhR}&p=|2%Y!z$~yu}Fqz zb$SZ;j7}`?gUtn6~VE5mAMs16Hp5ALOTCXq+*Gj+St~972f#{b!TA8Ny zpAGD8V~DjUkEBG{gXW-G=WfB5>PW zY1>A;yy7Z6)T=mo*nh|J0ri0Y9t0Y@P*Eg)T8Z?D2{<+7m^a2B{p3sYrJfR%lyC*I zQrVT-BfljZO~Tug)s_I}6^lHRl@!|Ez-}atiG5^^zw99 zU-+lCQa#dunmZZ*Vzw*?dINygQmwl9PM(;!QxAPG$vbFD={YiNv>1odHA~KSor|8c zQ&t;J8D1aZY=2zkTvLk%j=|DPYW!qAw?t0VRT0*Mey~*Yoz~qz6%r+GVv012PV-N< z2@kJPxPtTXHk;RZ`LCRn;6s@T=%+#xZRRRaUu#5fi-rfqYni(18CfV^4^0+_ub z9?IgOBHQSIUC>~Lp-wAft;I;z8L)S{-ndl&GFZ?)c5RN<9YgUEOuoff9Kv_i30WdZ zM`lu*FW`2afBCJVPLlY*54xz$oV(Wb4v%`eQo`-I=7pm&4q~HE3FiK{bkfZISQde~ zcbr+HDrZ!fxz{Ik(cFm%`>*{o_D(y5Sg|xprpKF*PdlB~>scTZ-aEA4hilv%wj)Al2z7B7xye8{LeZ^)>M=kVe625r3LbbT)L)_cR^r<84A!}FO9|H&789!2R2`niE_Zb-hSlJ-+IpQ`!v z1f$ZjR%=5g+4TE^l#9r#(>~#OEcD;N59%M);(RM+_<^Son^qJ}eXQDLh zXCSUc*Z{#(5ZnKfD)0$A-NFuO=5vm&of!9C68_PA_LoQqi%Y@x-loFNwE-}HiXmGo z{U6g(TAs7#sl5R#y&5_wPF2uL|Dk66U__J`3%Xg+I5#(HEAf_q_f=>@GjedI3GJ8c z5OZe!owCM+rU7lYp7TrQGL_FVm+fWzh`z49Y#YFCoxKdA^Zx~I{a&X$$EswvAgbIGmhq;&^UG{xoP9r zTLH`eD)sx@k8?s6m(5sWH{(IZr0oYLjCOZUKxy*jG20@fk^;;73Uz;7#ive-{2>iL zE6eti;kNuQedQV|>71&^#n9H2Z;I~#dodWBz~LTulw95&>5QQd{sK-q;J+``fN#rreQZ}IKb5}mM>m?4p6 zRrDV+T3$sr{t|<$XAI>lB8C*WKx;7VI>XK`>->3IA5*%*P2e-mK4gn7bmgNMxNdCX zqO8B+dhNV3r0i$-b=rHm%ej!xQuML~b*>DKdPDK0z)xau*9qP!@=87qGo+p_f2Inq zz4W6h=s}gMzdg}cgE#nO|pTk6u-D13zxOa0)7!QnXI*T zp_4mMswzIvTjC9Wyd*kg>Z>nec?a1djD@Hl}v&OFij6(iaIj$dI7$2$|8$u+$pDf|TDr2x0<(ir0#koB%1A1}QnV zI#R)H6+J^G>&8((7bU5Ml5~KB?NAbE*gb}lbcmAFLP<`8kentuGLRP6MmQ5&FEf}| z+a>8jh}yh@uHJ(Hf2ybmTImKMt~1M-vF$w&5iy9K(SZ(vh(rf$GpC129Ct0#|iF1$YF}T-^zr1U{Xio+3jaTcB%Z!MUCw z)l7IrA^Rw%{{eNn^fXJE%6p|uhwv2wXo-`kpa^4%5<;rzr>LRRn#U9;GvYRF4V{_t zyFO`5=d~$)jZ^1AUAFb+F>Xh6W?SgYWhpYVRAgpVmmynci_Ac^tXPWMJnK4oXvKWU zOsyd^m4RHkQQJCmD?w-GWo~{UMDl$~RmB~z&D$0w^dOYb12!Z#A~IITd(s%i9P3VF z9_dD7Lh&+1V@xy6>P+IO+513aYM>Y)llscfL}Nx5=QPTtq|pETW+=?f{3AgUx<9(u zUr&+F&XB;2QXT}REC3SvHyFKXT3Q^0{AlFGX|Onl<6;vnT?>nvXLLu`XzzP(!PG=c z*VR>QbXpGP3(hb(x(_tnybFVkwRJRK2{t8x5obCg2SgGOb&iTC$j74^jI6fH|DUwGXJwvaOq>|5;4doz#R&Rao+zwHew z9O3mYZ*V`nVX`>8d`;0EBz!= z@gde&qePe8G^*o*MK;%)waA4=iJm?#m_l@-r^@@tY6NoE!Oe@@`1h``+HlByBPYbE zsH@Sf8}3uu@C4afqN^(-@tOvRXW6YoO0U> zvN`5XYnF=VYIxu^<|`YC!>>|b6E%|~&5Ih)XY#jWvN?EPrX50sX()gmt^soHEpl3A zRV0x<_YUMB*SWWWzdHB60Pn2b&m4T6B<;bM9~^wI7{mmhXSW%27Czf^&mSgUhUrZ1 zYRc%Oq8rRfidlDP#W3rSsyRF?bQ;p!pnzGIt=wBITVrs}s&?|vd`<07jnnYo(?w1U z|D6OEzVZBOFM9aK z)5qCGD11=wKyt2?lB!JlwX}q&Z#BGSNSFsc_ zOyokjwu^e_Ffq7ab(ip=cfFtcD7Sl+FLq}jeV+ZvjUbMJ=U8WPBd<7;SJo}=cki6UFUT_QsT#h-%0K@fd+!1sRdx0MCqOVFI7tf{FV$FMo778#iY6kO z7y@T>0;!@<6-}!mtyZZ_6ug1XL>b4iw8hr8YH6$0wpwj#6%i#6L%>!=tcq6<74|qP zct@`P&v);0W+o79eSQ0D-{<+~d0@^t`@Z(tYp=ETT5Ip5>YV&j<5!pJQ<}$_{A|bd zU1{snei6Ewn~srx@(8w*e{vJJU=^Fh7;Qq&r5ng>kH{T=QsnrPb*RVTPe8&%2qW~t zn}mg%(s$U*J4s&4@-lXn_NMus_?fAIZCifk9C0dha@}L&8nGaKI+Mw!wSG@Ft+uPP z{7VK6)jk`%LK^XY0!dXtoz(iR%gmZ}o;=P+k}MQCIo`5te{{T6m1b1T}jo5Xv4F zSZ42Bm_787E2a07KfVst>nttiAb)c>@lmAeO*w?dMW1|r@1pN`VgokvW$=rG2_CRh zBsILW7|vmI>S#LKrxcsNY3Jisa^-F?jr26a`BS2Qg-HP%kq`uy*0bb%j)oAV9WUCE z?^}}XzxPm}9|RR{fU1o&d&Ozq`@+X7mj#{GiUZdz^2cKVge zT=SWD03XYb{XEN$g~X2~{s#Uo_ZGa?J9C}bX*UGBFPguzM@s`)oVhK_s!_+ z2P6e)k$*6M%kE%)a#}vSX65@_YXK*2Iq%Ad94eCg%DCMImS8fF<)36SmIwO;zyE zYwSF4Xe!)fe#>IC@sh+`YvKsP^zBOpId}`_Rdf!&+i9f0|L*!=Ys-no)WlUIlmTJd ze(SWVV6iHZ)H%iJfk52J?=ok`zF4NwPkB$J#Xf6&uxa+`4dYnk#0nI0Z)?|!t=wW& zNT~=3h09~B3Ke^vp%(^&3$^V_-RZ+@19iTfcnWX1S@e1MaN_UMC%bSv!RbSQ8)%yy zZXBSZsbQ-Ifg2Y>0dhwNzJ6ZzG5lpUt6!E1~MlvLLzc=lGVrQ2;e^_FJFvH_J66ooV@t+$jf(Y-~YGC%U67X3GD~n z$xW!+52b9##W3&^A4>DFU8vVk6}!nU@Lp`eP_Yhg=*h*QxIKTvs$Iu1?Ck8&Tbo;? z*VScOp?FecShrV9A>L1XR|F%=PD4@QC@E8^eWcvn_DAuuXIGR*u%@q!BoJm3=SzEo z&X{_LPP=N7WIL25sX<3Rw2?l*jI%kn^`imQ+Z8P_(??d-*Y@Ru6o9B$)|$I0r3Q1M zVe!92a$tXjrzEllB6r{@DJlRZB4(;iyPnk8Ejr=1T29VzGTrstbud~b4 zIn3WX>_W0i?(=PV{jFh-gEMR_Fo!D)Wvb}plV!fe3~By~!(DB5Gt_?QJOm?r21=ku z(Hy?oISeOGRvlBUf5Vh6dtN^M)_QQiL;WmL$Dd>N4i{JrjX#&vfSSojsZT zw|?t$nS1Sx;lh#S7irOD5p60J>($-^)#gHTbwi-|ZGz#UQA(u-{NnG}r#1`*0;wSv zY}$pNVb_OPX1yoFtp9N#h>;p_iSi70d5(8^_I?~I*%fLyHDH{QJ(ql-OFlr!?Iinb zedcKYAw2?A44xI2L(iG_f-l4QV&-s)Xb+#nHJ<=I%0X_B(r;4wE<6SDfq(zb{}X$e z7nl7v+RF@?Dkw?N`afkav(F@T`~SC>>Dj;h-)=8+@GdO$x!G0PWky}Vd<6C~--pPW z{t~`83zHG}BvNzsGJlrr#RC03<#Y5&3;Dl@-+jAP-Tz$j=?k`sPvLie_B{cjNBQ&^ zC4DY__aNK)zsB#Lu`|<|VM*ntqZ_~Lq*C0vQ4xIAndM~d^}U3SOIG?OOqjsr3~x{% zw7~WdqXWiD7Kxw(;i43_LZLc75I17&41;56PhYgN520A2gjU#sroy$>Mmli+Pfmh4 z(y8xGa$Bl;PDdJLq4EDFW@Py%Z$y!!2_))cIa zS9-Cn<)Ldwz(CQBYSh;Bs~rWU?6)p5XsxBNmi^Xn4 z#km9qY5hD@J}|H`Qzml~l*Cw~u}kU?C*XBDlRy_i$WQ?O)LQ0jnzvw0A1@WDEdxmI zJb?b-0&?NE)uC!SRL#qG2}n3@X{fYiWvF!GI+P==&!Yt|j2_@&86t^0wRfGgD_E)R z>lJ3ux0O)pi(aA`lQsCkJ{LEoj_&eqG5zWiOyC<1>|;*h2UuJeVRO^FL= zx0_kn_UHE|48eiA)Z$-3BEu)0sAaJ4UgU&x`-h4tl}BHHnU zN-tf?hpCL^IL3A9O7#ESzk+9LY!xFJc%rvp6(flZDu@)Wx)Zm%tKmHr-K>V$g7Lbg zhz0yL(Tu=W*%`MH3B=hdTiY00qkJSB)6`{dnrJQdTnLZ@e?@(#Sf&YfKAF{`ooms?R_D=j7oDbo#$k9=`0{&m#}ta-oo%&Ewy4e*C@O;L8TqQI6o- zY0h3`)RR6E>E#V%QoU-!aYVxpFNV%vyR63P)^L?CwGSNmv8mog8-P1oy_yRi9%z8X- zX{hvg*5--OndPj@RKrqrHnwtIQ|kP_xZ-S#)`hE9fY(x`2isRaY>YVa>fvN8lDfRE zcNj8<&1_TQX7iF(SJt{lXZ@&=e|nB)$&wahaBDHrEuay zYgKU7TgJ{gH!+^g=5m0}GQ32*Le>G&y53hYU0;$H7khKErq6lt6v79hao}CexC#ukAm9o3=IQp@hwK`_+TSSvyY(bX=s$9SA5jDV* z@;b30#xou>NY#R z%!rvl(;utd{{`=fg7`JJ?Ypw zlJuwiM!zh%Iwe?G>I2W#!Iw(a|+uhM>wVw)kt6WlRIuh<)V)^&;t!lCp*QIX2&VxOZ~wFYuGixE0tAywavw$w#{(Q z=}R!p(K=AQGj08oiM7J&^7AWP$ZUOgD+}i8E}M_0^tr%1B#|ySy*So8&=pmzi>q(l zMa^5y9w$TZn01!(0LuD1)~j_{3Bw)ao2wep6V-fxc4r~E!!ZJAaaszk+aw%^VEXNv~UvIDbgNtwI#dyc-K zF}?a^O$JM`PW???U(sUg#i&GX>j}uOm$=@>gpu)C?Yp7)1L{%s8+#7VwoszlTA3ud zXX1SU z!E;pl!NdmbAnVG|)eDMU)^gUAp!(){ZXztWA!-&f-6o<;J<>#+Mp4m@558jDwUjViI*l61Ul3FIg$Uyxc2% z#;bjvV{{}XpQy(+hC1dGXlnxXp}3uZv-Yy~Toa|(}(`ji#aPoGvv2k-JL zbqS%iuZV=x63-Fj^p1kC!8e|@?lCA5H(o?bJ`UPQSe3%z{>~2!k^WD1XBmD1Y&{ z)a6+fWw!i%Zr@Wb^G=If4<&xhE!mpOgPISdW;I%E&F}C_ka?fAiI^9xi@|T_SXS%% z!l}&n3c^VBFx7*@g|Fa7h4miJa5yu=mxhza*hO#?ZA4fE+@I3>6m%dfi{w}kDQvfS ziKrH{@J|+F%6D{W{q(KKlbLV_Q?VY9E_C6{`c9xxBa#`^m=LgmY8c4lp!NEa=-t&&QoeJ)0XV)FYhq0Tx~a0SvO}ir#R>E;+Ydn^=tomB zQlQqc(Gaoe8c{-d6nC)hQuVlbeDSc z35V`^RQe_xR#o|WW~G$U?$=N!-m4&e`$ztIX{vfEyx^0fFjT2+9N0~?+ECkQ9x}7s z`b~Un)>R_`$t6kr0w^EAGhM~EfS1Y=Z=Z1p7z(B;Jsg|3fS*(SUlr30S-ICDpW7Au zjRtp2c#pVEGIyK?gvsX?guk))Tc05R+&4i1e$PZsOn;q5^6-;$R_^NDfTGBH-w^d^ zs@>>=TKr|k&LUE@sL$@e-EAl78;Mm_pLlBUl6tHs{h$JUj%iBtIcj+Al8fH4tXX17 zB-JP66~3G9r@^prn5fg?Qfrq-j}^b_dC61RcE**2+D`jWIZlPJkAr<|vTu8OwPlDR z_F2Vzt)7JIMQXs);WT^7eO83v0wQzWDO#ZJ_|T=?q&X#Jl1*`vVO~V0y|jbVv57=v zk|>#XCLOxp0euELQ+I%*-xLz021NeA*0G~*#Y&Ila|-5xXbzgS}9hIxsxo2-9NsO zt*6~YPo`6;0pI&Q!)x2m4zI*zIObidx?RcJ_j#!xof_6#t$n%Y*6wy$R=z@(t>bJX z) zCgqqc^Aa!Vi)@Y+=Ie|l2T$Dad1*k&%lKGjcIM&aO8OXMSO@A?$ z=8Rj@66J&11_866h-p$?uL+fNAF~~=R^o9K&5?_lswGb==f`&lV(>bb@@-8xt#?N* zv@Pc`CyHZ9yuc|;V9j}-7GYpRs5pSuhOoc#1vZ2aSAsfnDVGlq_cJZR`md{4?mIsP zjyNVnv2Ea-!rohs?fi|SU`^rXjuMLSa7LRduW(PQ{E zUTsG!p+6dy`;O<~)cHF#+W-^R!N}UjX1*V19v5u5{H zdZ(~i2Az=)?!uh4eSf;;tnHWaBy0OWIfH%cgB!hV8xv>66rWD*`2DPBg7}-p3}W03 zKaJgWiFw_wKJi{iQJAAk1J5`izv0w{mFYQ5x!boe;|ZsxxJ#2(P@%gt=^Q!%VI4#t z3Wv|=Yp+bQe!%RsjISNJ>^M74z!hry0kx$U^B?w-RWHfq25VK>J)YlLDN7(6f^}?S z!v$xWMLFn4Q{tF#;sP|4BdDm`nThz9p6&F@cVMTlGmahG>7Q)}8yC2!mouck^@;VP zaJ$97IMNq;{o|OGi4aTk9*bwo76Wq7hMv2}Q&Z!%JgUHmbd1mE;8C}6LF zs+CvFF}cP__n?Gr!+Hv)hVAthgz?UkbTs0|iz&Djs)k-t5`OtdneRBnHZsbgIZs`8w%Vvx!<7=07b!PiJ2A2H)XF3EI0i zPT#%6bi8fj#xW3Dqe^_Mi#Mq`g7O_-;;yyNhE}%t-;JJOU@pVEiClq$D)&NN4cW)n zClga?aC=kjThTqRtjD+s+S5^Kc0FCz%P+NJ=>0w5HXd+by#)ms#GTf*ezKKgPmaE! zBYLW*h|kft#QTiG8cT6Wr`H@DJ6aEB9L2zz7?jsq`@$5ATCRgsLD4bYJC_>R*Nn>bPTr#F@l2I#*A~_R zx{f^(3+Ojqk|{z%gsK>^hTW`M^;Tzg0<6|hY^^!k9y6{nw;^`<#VH$3og74LrsNov z3;-u*yu4;Gy~J-58EB zTZI>&;?E<&ffH+vLmI6VtV?DPG8)PXdF9L`LM3kM)DulpBZ9r(^rbYdE+dYZSD?y~ zq30D}bg$)5%@e$*>->3KU`aOJF%Q_M{27f7H^(()nS~4|z}96Y^JMT~<0fW4)N5uf z&6&yD)zLan)BVtBS50O~4*$oTY%xDM5*$90wZG7-dI6cB@{;|eRv0?6SohoOwh;ui zwPuMJ`GgT_b7lyxI?*EM8J7Y!(X!X>$WT#8LcwGNf^>a=GWH#taUY) z60kpyT<*ozlBKcCED$&7*9*`C`qh0Naa?IO5)6GDD4(}r<2H;c+7!hE znOCuriP_p*0?TT6k}Kkm_)VbaC(h!&l4LKdlN7Ozuj2Kk(r3&7gKey#nK{Lytj>Jz zHygJmCl|}7PCkYdPVS?^ew=Sxz^O^hdtN zHzdj@0vb>rLODFO?K@H55}&!zb+>f5hZ$wo&y}%m$OSCj>;29q&r6rX=#cXNxA*+W2>Q zz!IchgAJzt=0$$f{{Y2-D@hJIxQEi;@{AozD_p!WLn&R@wQ_&z`1EGO_YOZTcA`P*$hkODig zh|#>8nG^~$_KCU_uSIo1%dt{f4;aN1i~EjHiF84kFZpy0=*BwBO&`g7wVb?$;!Bhb zjjXck(q|YSd+#%3;Sk#`U-L8+iIQenmUPs148htKLMGqY{AiR^Ev>goZ27Gfx9G09 znJ2|>W8~O$6Q%O}iV_(^M{Q$`1y0c=&!e@(HV2W*NKk;~*Jw&ro$&FNtsMXD&1WJ{ zxH#%X6ZVp|F*<~^nH(R9)f00t&54>k!)~vW9^n=WwvvEeTc&f2kV{7wV~ATnl=%j? zZl=c1h+BoOhDLNMbUTGmsHV@cBi6L4;$Yn zR>Iq6n-8Ioe&9rXwe@=m2lR53z?Y9MT2Z`bkQ8`v^VLOKb<4q=^lM% zDDLm1ZpV}YdbaWr;6f4#`-AV^+NUDmS&B^+aF?M0%q3ZD^tt`uopkYJ@??a^sMwW{ zAr~!@gQkdZOk~5f#BehX>4dLpK|SsKdZ?I&Jji^&@B={=snOzrs!4u$Kv0LTV^lj@ zB-K8DQxotvbv%@tD_qIGl>8@)q&G@Dt%hCLriD1~f8Vxw`9QZSELi-VbS5A&ufe{H z9n>u3v4aX(0XwM4>dp=Z`W;r7%5PmtSDHo(J{Sh9H2i;%^|$L910dAx?an$Cf=ySPqxxoY*d)0ht4 zlYPZ*#O*F8kFD43cWbB@TVENvc8ms?WcJ`&i=#--5+`_N=bVbQv`xyJSV{wr?I!jW z2jpYF_?aj6HdpdsO8%3H{n{iuktcn@P2^Jb#GlA^p3R;SR$?z^z^*?x4bR%lZW?R> zreS%uU^fZkz@IV=4aIPFKW7TsX62^f-Yz=@gI-_?8jk^6QUlKTS#IO{p-YY_`70#* z{B*1nUE|v55Z@}Yt^LZcg;NLNW9;N7dFHXDAbvhtSn)B zX46V7n=(^(0wcSKk+F7ODrNXNat2qc;YjsSRI4PWemlq%P+m)7{qb%|tdt{Hs^~j@ z{@Gc8I4WY6l5e{u5gld5xxqhp6NA65f@V`gW-YR?S@ArBuNs!!3etE|1%x;=%TeUc z^su~-P=pnxtB!_Pqod`rc9cbaXmh>ZbTsFe%Ms>dZI+_tCEZ})lk|QX6(s%3*^(VL zYOTK?sGT)(@On?gdOLmj)7iKOh|~&(tl(B$DZ1V{FSy`VVM`4Ns<{Ot$4J#Gdy%!Z zTMabi_7p{4_I=2TndTR5cq<#|%EotG9X%Z5Y)(NHE1>GtNZ|sXo{+bfMd#SU5*xsZ z%i);RaRjg09Nnj>iY2$g1}*TmiB&E zYc~>D6kCETi{jlak?X}7h1Vq>xZvSp;XFH)epx<+93(`)h8n~g({BKNGVzK9aSY@( zvAp#yjvS8U82tU{Kw{lmDoFnKB84BCSL$Uc-~DpbpVw*?X?h55ODqFG*|@DnJ;yX` zb6$Y*%37S6`>5IKvV8mB+<5^Z8#ppR5o||95Ur3-L)sKFK0TKI0y@O}{5tEeL6`yT zeMhX5$IXH_dS`x=ogY%Hxv!Tx=tBV|4R-*Q81}7an4@=&W{$G5iss#}s$kat&&}5% z5T0%4>&+woH|DF4NSbty|Ec-<)6>k?F)aS==d0VQ5{W~L27m4)Fiw}r+8nKg-M_?y%Zq<}Lx3VdDNjW3|S{4qCct)<_AuDXIFyCV@U@P5I z2Y+~f)tW25Xjk_%kP3aw;w$fIYoGE5DlJ3jO~yY)5}V`8T8DA?XzAl>?N`fF8@DDF z4sLH-=7qv05+a-k(O;m+oPfNEma~3*{TV3e?0z5N(oDPBBDGV>qE%9wBsQCm?CLq3 z@RpOxu>r5td7B$x=Eguzv>CFH`K`rgl&Xx5K>L>fnJx_8($5SL%Qd{9pd$y0?f83` zdm9*l9phY&!f2w$5=!okaMgzl##``7?{I7rhE|Kc*wU@ufn#g1?b#WtJF=DYimq#E zcK4Yk1IYL$OWQWeqszv6`C>Q$%O*>{-r=hDFz);ppE19Hg>Pm7XgL*Nk99JW*HAqJ z4b(~Wf+M2X!eSXNKBoWLy&~n8QyaI3RNGIyEa0UMs21lPNciylelP3KMyZ>YgqI!a}JxE zg(p`O3iB0EyKlOfM}OZBwe6PszAKOB&#YbOZsrH9{AKX@M{eJ=mt{yVh*aA3XMT!SwU;bFW)2<3GqB{P1r~);^H0+++p(oFW%(!kL@9 z3kWafaVK>J#K+02BGDM0RO{d|)=|6_YK})tI-K0QLIJ!gt?~gGg$Q2SO42tUBEnb4 zZqZ?L&d>bA(m{JV+09?f-ndRk+Q3#xC;gS2^0S)~Tp0ENQ&?-jj`R4>+@A|Y`z!Vx zjvB)WR)M0?HYpmd&QGkplJ(b6G}={=aBH-5f|9a4zh+Xp_CkbgcRppNG;Buv=1PK{ z$QenVElKOcOtI}Z$Ea2_zs7ufg^r**n`KUexn!pG_3%}X&ZdzFH^XD>^ksf0%(Tbp zYt0awxue+@0APkrMh6m{PoRo*G@G*t^g^lDwTh^TJgg0IQ}sw zg^R<9P}p6IwQXE(Z_ZLS5B{b}XCU^)OoeyROL02H_dstYd2LxYNcx_|*u>xq;1|vW za;f8~QZ3DlN&s%#hq}_E`Olk^n++St5lg0SbvT2&)UbU~VVS$C1LZ(h5ZJLR2;S0_ zX*LHPL}y(<{4Yqe%6%2ghWipFM7}-JmomA5jOGcbllkO8LFja53E{0O0O%JfmU-K} zL}DcInw&%T4wBX%XOn(NVP7eb+114I-u5y>ME1~3+(L0H0Rfohsx^_;An<%a3psu^UZz z!REeN0N87VZum0%2)>w{oF9B3RukdEm(wH3EW74p(NjkdW}v1Z6t9NSW1ZF$SCZfa z$vTd{h_wE5z79{0ZovYmK6E1-+8T4mSBTLWC!oR+7U9oAXt}Hexd`tnK2YVAL6w{B z`?gh%wN;L!%J!hjF+r7wxGF2DvfNf_&GeE*2L@F>)?<|esWN#>NaRy0KI?Mp^jy!c*Qtxjp>xfeh38Qyr1HhPSnS)Z0Qq)iDCpuYV4lazmSi>wM1C!GA8*em~a>4SU9uk*g-$QEg) z2Wr8}m(g~&?G!EIPw0LYKi37=k{xpVNlu!!F3p^4$JIl+bgiV1-BJ1wmp*bw=@VS~ zkv4tn(t6?$~f-G##>io31`za5b9)H@Wv);)1np>Hlf zE3S@Jbn=vqjz9M>`_i@Jlklh*s+VLP?klF1fFP&UDfsIv=95b{sxf~*baAx^0-G%t zU95Eo@hJELF~Jl?4D4tuj*iyqZc0v&wQB3Y^a~opOii|>8Gqwdo2$$QXgrGMX=o(* zy<+oNsRGJz+>*S4S{Ir$^rsSJpE=IyiG5Z#Os}#p!82+%MbaeO~t6Zz-2UHX|9{N>|4_hxoIHW6Mmy`r)MKz@t(9VLP02f&k_vPU^4TkaOU(@S`XH>7!fyoAk+ZLK7H)}u0) zqu~o4C)~{Yp;H%N0%;)rA!hnG;}x!FvXgaX2W({6vBiB7$Ca658JDvGk#WEp^W>|v z-?b2UZhfShnbo(9Sbl5;qbExJgm`>BdX@#z;o3UOryt$-km%_sG?CoT$2Zzu1X|0P z18QYL(fd)N`81qvovARK1_wq@DDjTqQYnropRuIV5 zUMS;(HReZt>W2Oraz2ovyPH8@$?d(%G#S{*XP#2!4^`%~q)tB%Kl%@uz|Efma8ELK zvh~}pz^`?fqqr2vT5$TNX|A?T>Uu=k&7Kvmm)};!+tfG7);F$OeUDwS!}^rnJhs29 z?+ZQD*KX@8?q1*Y9oDDp=2E}Dg4&bSy#mfM6XhV22G&9F8;MP+v&4anW9&|&O>r!oz6GlNZO;rx%z{FWxf#b zv9Qbgh&R!W+Pb zK zezC|3$yP#s%UIx(_b5A?`g9&T@A8A%Nu+BcM)tHvDN=>+wD>}5zckh zihsq}VIVp$998&NjJ*dJuB%q;-6!xu`;Z}b#aIb%-LDwa?G^Bc-Q;;R6h4$R>#lQA>GX4IC<}iEXXCa!$iU!X zIMea@%IY5OHHp7ra}m3Y=op{z%9ZzQ(c{Z;^r{9(s74kxbKLB$r&Ptny}AuuF~^;ku^Qumm+~?2Nk{~ zSqJ$`QTBc!aU)-=xUDWs3(sC8zTG`;W2vTxds5z`M%^vx?n&uu?^Lm??K>_%{({}_ zmK*>mw{ap&eIDYxxr)ob?Nlp>f*@d1yQ@w@H4DeL)Y zV(g5Tc$?>W5(EDfzqxx;_UBDC>_rPXm2sAz_64WpJSuu8&p+-4zZb2zw89+rIr_Ke!cXhp5>h`y|2BNot$#!P{{48*Ed0E{{-m(m z$tZ^hBgGua%F4zg>}w+s4wprzjX+4m*+^BoNiHNWLd!XNM&=-Rg>^xez0d*5>hnPl z)j{|P&4uwEa>cWA%B9g-x& zE@?={GN~&Rzm?kXtEOXY$?T-~FyF88fd^ zlnZZn#Rt?|pNV-7=dOCQ<3+-YD0B{tnAsb0V2#gwJC{Y)kC}B%COEm&8FlH$pln(G z!dlXqaO(8FbxrDVf*v5+^bC zX2yOJV?SxVqBf4;!#Xc@0`Qsyymle1TI*adbxI*;^^?yem<=XTj2+vQKZfqFshd%& zfHuELEDJqwc?rzW<)vFPH--}{;x9F)DPPYNFkS1ra{mcE3pJ`jF^XSv5Ni7nugv4O>- z5(7iEPvN($6B;}3y9VC25nZv27KhphA^R$|am(_%;i~s?4!6=IT8CRaq2G@!Dn22( z_nyZm_TFQ7?GrfM&eJAhce%ruh^z$|XJ>g9V13i&BqodHma7|&i*@7iu6X5o>(kSy zAX$@GmZ(i$Ua|>DZAwp6O{rl`_ps%>up0oHL%;P$t&6ZLgW2lDuB>nRG0Nt4i+~>I z?BQ8SS(BIlhxdt|a>9RYJlOL}wV?i|_lc(V5Vroi;=zu;oB4ioU_Jw&owt6h$R7B7 ziapY@zN(yT68MwFou{`VbO#?4K#LPo>sRcQQb>6I*(=H^c6~BIp}A|*-13eeVx6Pi4G{>SIiJ;`=|t&pGjSZ6rBbb&ElqMLUa9RRDXFCP zUX36WmzKW82T|cs+cPchNXl36{x@pQ&X)hL_iM>OK zJeueFnKx#x*0p0+l#3EGc~CI$=>7tyJ-W3}v}bApR9a$=PwxZR^#7%U&EDFO1slMP zfbQVawi>!KznD_yHc=f^pUI-@xJ?8NVsgDSpix{MQGNXW0ItM5LEH!dKnS)dCTuO>zR!3?I}f^-rJ9|{ciVTKDqelC> zlsEnHxXwM1^`uGO(0gsE_zS`S<~*2xP5$H&npFVk#iq}s5E#%6ZQ69#CGrnjb-9;% zSPhyp@sYHclzyB3wZ2)79lX zJjvG6oLA3HdG!?AdZGtWM|t{15~N>cm8HkpXIr0rKY5$?lk(qh7i@GibdZ<4WwyFN zWCJZHJCUa05PvzP@1j(eKXKSK0vhMA>!1M^yAJ-SXY3l*)gyN8V{+KF9PH}A7_r1m zvMz*vY}n+(wokdq%_15&cAIq)@-gu9VOb7kd|ZPB2r`fWbs$uF)})@XPshSrT@eSA1~1F2R1pJvqlfr87uL;ut|;9=ol@rDf3y^NU>q3Ar|TeFT}lpJzS?g#MlL`7)6x z%y(JrIg!HhpYEBMN>|aj_RZYcX4!0)a;YrlJ8h79Z908Ge`wDLGJZ!D*I=CD1EO1LVE6 z*+$mYhqEg@{hSZq;+P54^}{PBVem0Ym&4KINp&+USAoNBOQ`fTipE5^y{^U%ynFWTnOm~l^B>y+p*k;EZl2+G`5af{5ij}bT6s4&(*BFo<4YY}@CPG*H;?b5#} zu=}m20}U^A#YFQM+hgW$BD2#;>Rvc{xH$oQaq73uAR=C8=BY2^Y?m`nzifw$NY!B|4Y`|7A7~h z)`Iz}AM2$?7K?`Bbmz==wd9CY#&tvwG4YY)2$XM!${#OzDJr-L5Tee1ZbZWWKp^YvbV8!-?hCtId%A5%>wqNU8Qb=_5F=YDzYi zH4)l~kX>Byw8Hdf{koda193b$g~Px{%}=NlN23!}l{Md8o2x3Fek_mw^I`;&j-tpp zw;Y8XrZ`^^A;7GeV@)&K_N~3Ged_%|99iN)hcQXOx6^>0Qv4g9}%nuxk2RTNhTYc*GLN z=@s+rP8>$~*P+`$R&w#ekg5(j;<9FQ?zzq;>FZ23aD7B$G=~;^vX#>T<2!@}_m!p^ zvi{`0oeLd;*fzBAeWH46XDq;{NbQ@UI3DJ}<#;9sTAw_Tf0HZCiJbH-F#B>2^bL}O z{DQYO9?ZtxXAJFX80hlI50neDOF0*b$@7W< zQm}6QBkL(j?inj>P1D!$6Dn;2+>IsXgsto8Tg=v;YF@AWUgF30H4&Sr0;!oQ?-kk7 z&R&OR$TUfxT}xSc$Kp#6Uu@bGrxExVP)3sHOeA7n3&x4jgL3$6?R8LaoC!=2EwMZ$ zaPI?K*4r?9gc%s$V(;qT^GNs{^yhjO+4l5jH!9sB{i*tw>Ccm6)VI$` zfBLZ__dtIpQ}_QC{oy|Hk9A%0vv!A=-^?Pj+XSKDSR%&IgK+W)qO6O-ilkalKwz8> z?*uoclgB#%7jy!x;2KU4@HkkU>F~Q-i{9N$IcE6eeShXK2Cy9CKk|LeE@BZJv0Izv}v z!gfWXyPCn9)(7LxJgq^mWNrVm@g6jP`|-}{rEO}^uQqlc?^LV83&wla>g~o`^2?sb zYi{W_-rrfJ-)9={#oHBOy!A}BKhJKw>o))M@gDui_Tyb#Xvh1f4c*84t8U}%z5RI0 zHIF^a@A{j&jrT!6AlPS^-)puj!g#;2VVm(5{0rlaJiPsQm$Th4zY9L;KHjIS5-phD zzr4QP{8noodl+wV_wg?ABX@m<@&07HB8>N2pKLSU5+A|;H~8TXM(tofdXa?Bu^(+> z?QFjvT|=ci+>gHV?7zwnA8Y&eIrpPW!I~cSqt}}L7xyD=Mp=${60|)qt1dRDSxy9> z`4nboi2DhT-3Z1^w{p$5yTD2Ce-;v-JP zt92qic#A!brm5ldOnmY9p7`RUxI*6X#V8n9$5&tniHY`Q)yR9<fdDtUP|2hW2yrLW{; zju{R3LFCY9>|KLmz%k}L&P!~x%GzgU+PSo`ntcPL!(?JK0_3vHE1^NfWj^1HH?VxT z1^F{sfuh4v_AZlrU%c+y(OrQ!F@wv^@1fQ>8aD9bQ-34=S#z-VVDk+FV zBf2S6RpI2(73Lkl1A-z;SZw^=3XsSU=ge4)Nk5$780oc#Gq-K%`;(T76xH-~T z9BY+4m*hxlatjNpMZq9m&=^v!Q{Yafn8$fR5^9?XWRh*OEqv_Bnp1*loK`e+knhaw z>p!TXS24`gve;SD42)f&KP#U|g5vu(J__i0XXd$}f@kxwE10jWy~3vX67HBb%dJVr z_`!=k=opWEg1sv16On)T*j?GUf*r*w8yPQzMY_g$@9E}|$>mnn=uR*T(O61b;M9!f zyMj-$Z6&Y(GB@7KZzT0l0sZ3jmUj2~_NDqPk7#$~n2ME1_)GrP@ZC$^xK2Nbm`a68 zf4rEtQ0Xt0>ti9On7>gjv)}QW(pa@CXwO=bH`;1a50&d!;iwa&)wfv$=5*J zndda(t`SRFe});>r6kP3OgnA(Do*Q666QX@IeZJX{e%C*DHm6G@JD9J%N!1Y;^V?Y zqZKWo_^)ii?#j(J;)ID-j>C3mUd3#3Xo+Fs?Sk?-G;b#?q>}F>nJ+kd>LKM|a#fca zH_AKx>%I$jwroEo|iDE=JHl1m@z z_-*F5hF`p5M>MnkmxWVTP9)x4wN6-Wm`)v3RpVDxr;;t?9LL9IedK*2?=8HK^WP`& zK9Tnp|9uMYlX#!#-mjg`FQ2CHX_EhG2EX;mYlP^0ouaSxiEC%;HF?cVdJC2Qz@{dy z6=eCUM85t+so})6_wr*Z3L$8zE1S(;dPrW$fH%uYWkj8IQfbVHOkIiV@Fx4U+`;VSgeyQ)(^HsHlqEI=0leVDl2X^pDZanBiB z4lnEBkqdRjM{G5gOV-h(PhaO~@E_ZTm#8`$I-=DtUPtjd6>qLjUMsBAQaF<;A{Ab6CV6g) zK3+H}oH&yPrcKn_1Jl(b7XNI&%>0{pps^Z$j6J=gh5yg4n8g2gRZLe(sB~nr z{!_w8eRsE3^WgSfa{_)%w9;&j(?fC^h`rHzUpd4+-w3gZNaxVq_sKfNeFYo03bA*x zh+VIbscSV2;j6kFV&`MDcU6bd2%H(ReoBNR0~+g`t5$OK`Y@`4h_3Oo_XVcv3uEg+ z?LPoHxoI_kD>|DP=`j1qx*3Pw398iy)!M=A=uTirwAYsOSNM|KAHATSzxeeWm$RX;Wh3GZ($@GH<-O0-i!kzc{f7D?gl zpwZ|+_mZg~Ck>d+oW?36OeGGfRf|mjHR2^eJuws|E>q!R?4=cG4bFU9%jO;U+gy@$ z-+3xrwG^{td-KoE>?6APr#-Qdn3+fo#6OzU^qd#RQ^X>!gg00!XfbSw{ z!c3$J{GTR>0hpV|Tv-37@3d?E1avxm5}8oSV+D_d zWEYLSdOVq|{U{MV*P7KT6P1s9T-?a6cWL?E-HCerrwuo4qZZAu!?>HBMV7E<7#8YZ~(*_Ut>`K#Y6S-xgPqJ@2}Y99byY z<^s@(5k7(xFN#B+5CLIG@r6vtmMlrAs_!&$D(r@(NC;F1r+ zc`F4&FflUpET;Jl00`=p3ojL82n%}I)1%u+f0qpkdQ)q-Pfe4$&5SZ8_MZSxH>VG^ z8zLpM{oOW)qU6u)K7U8hMtUeEbNW&4{3!{=#Sh8yU>`zv68}ehu1>xVVNvIB5PYOl z!4=%C5ZlwVNTMQUeF{N8^nale6(;SQzP-k}-wY`*=PiCyv zpEkNr5)CW+P-4E-`f_1zxF7j3_rZW>n~M z2+1yQYlxRabiUsuqT>ir_GpiIq#6#)KshGK8kWKv8h!CZX!MON#qF}RUPkg*C12cQ^64bkD0ys;$-_wA zL&-HZSq3~?kcAvrKJcHa&8dre086yiT(lzCHaarT_`5;&hLOxY`jUAo`2KrQwb|5} znXNhd=v689q&HUvKOSjt{divdhB6nw;j0`=2l3@?=!W0Bzg{*7u(jq$DB8RXs;W4< zeJd3Ip=K?0G+2BzGI>|%>T&wOl5V?$hsMEghf~o(q^{#=#ottl&9t;80%fsS{ByaS zYGh@obV8Yzz+8)%;qkL6s))UbH?!*p8zs5laj@KuY_m`f5T22DzFfobY+Rc2KkR5F zo}fR-ejxZ#J0#P`X)f#z1x|STE#*4Dy53mV zr~o)!<0b@|K!IIlVa^q5KMuubB4s-qW$jrc-4Y;aZwlo!Jz{dy<4C)pxG-?wnbp_zPO{r1K{d(lqkL_bbrZ=Qg@E1Xcsz19HVo@F@w?moKl%qXhZh@IdJ*< zo2H$;oV8@0hlS7!{$O^uovy(MI@t!LZ*&b_B59fiJGwV`@AeIP>0j~@dIIlkfhjld z3xEp{YS)7O4XvObLK8`#bf7f0n%_ED6XtPrGxUpDQV93Sm^(JuIbGD?rqoX7Yw9G* zND7g0Y%>MjRI=FMex?9+FWInOO+z!!W6CaBs%hin3=Ve;mDc;Ru_{Kw6f{&*#knQ+&`48;vKAJ@`aXwZx*5j$ zKc6jC0%0o^1TyOb9g1_*ur=Qg+7IOxrcIjS=Ld|rmMR#y9-&#>p zNbF&m8qrSfnwEe>l*UEoif2Vat>`6eVC7YMg|J~qMiRvFcOhS6hl_rrA0YQ(ML@4rSng8`n@LgXj_8l)X8%y_d-M+%QNMpZ z*N6JRd6wtb_q!d}cSBI0mG>_eM>aQ)j9Yo1WBUcG`gm1buiobwJNf<+O^+i#mnD9b zC{2#xB!0|bB>z*q^e`&j#xq~0@E4IUxamlVj|Pk}^4#LYhc!2a%cFk_PS3tTl*R#Ldk-8peM&@$uG@%=5v1Ih5S0@h}?C?w4AQ{vPR{{Z90f9NV)k*5wKLoIm2- z-0dtMPL1`Fr}ZYV@6`|K6K$*z^8t*#2vWMIrBXK`9J-)0QV0P!A1oTjk}kj!l0B)F z5>f}t#$JB2Ff~#%KsGI(X=6xWPzeLT{W6eG8))T>gR~ba(291dE6PbK$E~>B?eA=e z!(0Zp8KthMBLh3u#dXSH@3Y?9WoQYfE^hJp$QpCx3hfBDP6tP{--Hi5gT1P4hERq- zNKw<2Q2c6jGT)9NboDHKV%%$p*`lt){_>x8rgpCogYEMn%(ti-FVR6QjU2bwV;dr! zPSKGT5uRUd{d!tC0{d$(wz)9+T@Q8$V4PP>Y%a;3<%{}!9lgWZTxE8Ku3&{kqMlC- zZA!u|<5ts5vCzeww?lcjc!Vy^5+OpdAo^qhizZa&>sw4eb(T7s3CNoH1*Zi&&1fje z{K(e>aMUxK?$Gb){Ae5hi3G>`MB8lrgi3GJYdCq$z5FQo);rzzTl6c!Sc2)>J}-v~ zrXN)h{Z_25xG?MvWH_vuLzYM_*c@ux8`5JDB$Aj|tcUzqgnv?1v2M4CXW_$6z3pVdgrukhxjBmuElg$ODt@se`&#+S+3NWLe|De(z}%i#brfcN|)u9_wZm<4>ogO)-t_7#J*ct5KMgRau~7xuy{^FSqr=H_pk3x> z*OM;uYg>cjSt6bwp}Bj6=h3^&+uMw%ts1Ij>Pgx*VRt1|lHiXo{S31ZJeMl*GMY(C z{#UObfsEzO60|=lZ|vAzqB{lt3<^^R)~vJ62C=RZg_C2wY}vY0HcZY;i31X{6R5a4_{4L(c78>*!euri zArwVe*APY|otWu`!IHN65^uqq$9jbey{9mdh6{QQX{ZQI=}vI{(7YxE?_ZR@i-F7( zN7|q31}g@W)a5j!l1ecSM%+vNrT}-Blyna60OjSbqc6tC=bWhBIfv+ zs%@qvWD3XLf{>1>Sf~EdDa^w|ZFS5i#Oz9_m_c)=V@DVdotHjKF9&~A_fZ!II)CPw zr(T3vN+mc+@> z{R8{W7#K=p$j)T@{2Q7hpe)Ta8Yo2l{uO4urD*-RO@*lnYtD!RTweb$W1eoOFQUB# zS{sTTVCR`C!igt2Dyhf}4D_F|E+S;0K<-VBu#G}F8PVcc&QBt>TzB*y;;g+1YG?Bu zkecupgx^mSk^?)1D;C;#G1KU>ViRB4H?bI(s=Ebm#PTgtp;w!;pbluWWE3;5LbC-% z0q}C|8%*1Kq4PC6h;M;vXZD9b zAzfx_(95F2dibrhqVI`*B>N>o4U7*@ zR6YF5n3Xt1RZn`>M?SPA_I>3QnGt8knb^K6tAJ*Lt+N+Pa$^OSMq> z{{FS~Gy2!2_veLv4y>i018cc|%8ge+2s1AP{j9A|)XonE9G#na!nIeQc#i-z2m^^H zHQmHrg5AbPwtvlVqqogUM!!@zI64MK`l8)eRliO1D8Nu z^6g8He@;7&c?|}|-#E-qEwi%1`~XUnzg-Lu^o@D?98Uz8Rl~yQ#;Ml8sS39%pe6W* z%)1rci|(_01|=4(4_t$2bG4qh`NZzvC<+>}Z5dHqkBO;xnNcMu6UxNz5p&pXID^Lg z!*VjA_>WltmYd14pX1AO?B@z;W7_w#-0AkrCuz5lMz_YRTgfvfiUC*0U^TJNX`G~0 zYD>UgUFq+jE!|718lMF_^3(7|exYFpC|7dD!38kAT4hu2}~2cRr(0Ee7*uACKW^ zqcbxv&kQHVPjvdA&M7`C_|=;$KH^AvYd2W8ElDPRW**fbR2u>2p;@!1U$n zX&qtaJte}IUwP|b^Hq8XW@Hj3wMfYvsc`ELSBa?AZka>zpYqKdu{c21tW$VLhC{p+ zT+C{wB9y`4SvhQ|IdCET*x?SdyE3=>D4yBV{F!ZoY)lQVgqD|#7MUj67n|2fDKSi& zJJp}lak7U=V}k&`R{MfP_jbUt?M!>=2z1)~Qc_~~{%s4P+VF=F!=qSV+)+vZ0+=(#`m@)bEfFBmWK2;)?V6$6eyR$ zv}|@k|J(Nw`Zutlos1d`Zv)?ET4@QJRGOWgu(yOg0=X~5oZ6VN-4<81iI?Ck~iW<>{@&P>RE(5Czs?a#@} zG>ff!$$s>rN0}NfMIGd1YLK=?vtW*IXM$fb`{%fQ^PG?jC_V|A^hCdi=OBwvcA_%J zhIW-%b~jZtzHRygjcE;@6RxkF@jB0H!fLBC2G?JrDNS zEzYxM7JDa^HEVL*3dc(UdXH<+;AJ*2yW8im_kTe6W!`6RfPR?_zrpOih-hy_=g6E#`gb@T zCfh#_>&(m!8nSmgxb=bm4dDXjR|5(=z0aJ4-GnD9of@?IrfydB@d|hTUNqvTn(n;d zU7F*?nq!56D>1jS46&sC-I?+nlllA=+{}>|{OkUEWIDgbEsx%2+Wx5jktndza4P=x zNa{9wPqx@jc`ZOmY>+wqSEv7MoVpex%S84%INUQ>QS&N{&;;|imHNei?Lc`wBXAXs zd7R~?%a>$F7HeRUTfj9wEU4aW%W2P~9+vw&E6u2$b=%g{Kd7gnTRofSxq7527N3mG zh`l1U6P{0~bTD+$IvuSsf98{yyqT+?=;F|uDg}fTyIps<&!lldu*y1e zIt8L&t}vO7Af+?2U$86=mTXaME@W-`G?c})-$QBxB+Qrzwz-eZ8KRxns+xb0n0eKe z@5sCsROG8gJ2QU_zT9JPf>DwE=BxJYK&K5)3;aYn=HI_?iWB-b$sk>3=##o}id=pZ z=1Mz?C_bEa+Zt~uLHvXBiK6MVa>yj#m7Wo56=G?CP|R=^pFpJtcHc27{lcadjd5*s zL#2ChoOh^1m+YnJYs@?hztq(VkukRViCLs+9RuxTy{rrvBnW67i$IFb1ecP$VpgsK zSsoDfJ!{23ySXtjGal5$tTjs?*|yH;zUBm=9Kiks|3T2-e=ZZYM1W3baicTy>mci| zd_GU_+sPN-&N2)$ffxiwZig$xJxUD>z^>WN0t^yG!uNbFX9Qj7D z@=_vGBS9X|h|7tWlw|lgzBA-Y1~FtvopE{0?&^2ji!P?g+?_Ps)Q}&3ldXZJ{CoDW zxd=V_Hes^+_7m-XP`>v5!!vYNbeob75S#MoC zBdH<7WPXwWAmRxKj)6AvrBK_0^oZ85duXhQmWmYA(U(4_lJ|Rd*JW|d9q4+P9;eDz zm=8cA{T}3cS{+GVVL2ENW36_w>Mv9kuaKHq26yoz`_Tvrj}oPLiB5Xc#G#5>D>GlA zwjjWVZX??xbGVNe7BY4RS!<@-T+)EbffB_IsBpgefn+PMNjSwT2$loqgP~Ud(k8#d z4az9=louc!KTPjv*Hc3(&t;%-G4c?n5-Wb48p{t}=EF+8Z`zxw?`k8uAac^(KopDXV2L{3cGb z5*rW)m@;dla`g%)r`Y;qL)Q#1R(Bp_F$rm2(T0OtUrC*4x$TF}MA$RS^#Nz!uIKyNWv)M#2PJwO8oUrY- z4Bb;h9&Kc0148C$hHZ{t<-VazxE8Od({)0c(81NP zA%l;AuiQfzs5cdHgaRz{RF&(&WMrK9nCA7)4O z4@)&<8h|iSTGFEU>6JWZYpg{J9*VD`_cCbWi21&X=}LF|KbBNjitFrlC+vqxNYG*B zuA%rZ7?StkN=#Nf_fqEe;MQ-jHKoNjqg2se?K~=hU!Au1CrQEhhQo~h z_U70<*vK0PQ$Oj}`kkei&;@cM=Bib#kK{?Ldo5C?YNe1S34hE6^Jsq&_kgDm2jDXn zrk~1+o%qO{X*qap*pe?iv|Gu#a&KtSJ?$Y7vz7@0EjakocBr>>BmepOZtEV`P?G++ zm2iOONKA*$;DEe~Q;bE{C2}lAN!Fn36cedsvk0}VmX?7Puo85LB<`zN&TqK(l~DXj z%d%K`^W#8fHr4apVi1vfKXj!}dtxqrcr|rb$_#xbsi4+~G6BRB?E-H*xr!rt7IK-c zIE68ym6xLjOW(>BsA73_H^jXbUcAK6q>Gl1{ujAZqY$qk%IWrfPA=41K%ZfH+ibXCmq-Wt21CzZ%a+Mh&etMxJk%=u!~JEn+C+E|;x zJMF>1i=A(AsBNruoN>;-X5Te}Ox*I}Sve}yHcz|bRga2?4`eBf#e?-N-VojJVG^Im z@ZUDy_Y$5SoyAkO9i&V9EtNFuWsYI_#EOb;f+HbJ~9IfUk@+Fb{8G4qC9Kdi?jQ9j>!8el94 z{eR@W33!y%+5ewNBB`QJP}Epyjhfm-ttJ&}BA^op@QhAu+-co#$GTCNQCbCqGb5Rf zqqx<+t*yA!rBauwh@u#Fa0RSOwN=`>JmVGxS9v}u$9|PE$R$)<5rn;w$XFgwCxAZCPwt(bM z37@;&#)5rO2;2Q`m&`8_7lfM3xReR4cbA1EF-n#y<1ed?D@D_DPGTEVa*`6NjT(Xi zN3@!i+`G1(v{xu6a;4BDZ)s=^W+^&h@8dPX!dI!%9|)O69>K)J7YsR$(s~$+JFbSK z0Xv!%!7Ht1_0qlI6!#Cy%Sd0&;Y+0!fQBsR@-?D!7BPZUqNtWccMy9JK64} zwAmL;9>rwn=AN|%ST3ZqFeFV^tyf1+x&O}aBE`xXE(xQ0V=ONWA zjG;(UEi?4v5CZWAWOQ~FuD>!TOu0|!FuG(udQAx|wH}dn-lGy}PpVvMUDrxy{`%}+ zOeM#lcwx4isjS#&W(xyQfS(=)0Ir8U1#5mMS;6P*AmxF(w1pU3b~0V+quMrAd*_1?m~W{zK=)0&H$O`? ze*~&>pNR;%?CG7~M=jzV-aj9v3vt*xH__FJC2)kDcPT~!9?nYYo%~iSk1H)IHpOSr>EWy`?;Nfh^^(QrnAn=U4`|AB& z-l1laAGhm2>Dz$a?wvTvE2vf7to43ja%pjXq5o9nm5V+?1_h*&>}{-<8s}i145^d zYqyJ{d&p+w)d>Iwej)EW>gyZc-effa)O_`qqe42C4Cc7rHl~_hnDY+A>`j9Y20got z4*2^6+K=`90V~|}jQcff={r05!A?=?rfyUU47hd_#{u_iVj?1`_Y<8lB43oTDes2d zVcR|UfK$>!wBw}CgC;to6{9+ARyTd!Zz%4}*(R|fHYj(5)!&>shi!%M-YT&oI=pdt zY`vR~8{EsxlU6L(FFcEEupvFSIP*uE0IvjWTWErUWj_SVb^hSGPQHhnIZKG-T)&}Z zWGU;*IV5F9FCSj&TyYPNWK!i+vc#{M;6-ZZ37HWz3x6~eAJ;hDVR30IIF+W;ojf>m z>fLl074E|gEk7@qM++y-mVXf4M4vX3;|?=XF*w>m1Dcm$ zwo;#sa^^o2%upz?Ay%s?QX~E}4d7^$nI^???>s6H8$bo}+jU6x2n2r(lIwyWWag{7CN&%n>@e}Ul^wcXTb0la!*_kRz& zmG}CvJDW)wUR{jh7Itq)tZA{nJsE(=i@w#q`4V_0(yGf&`@KDQryXzU6%1FfgJ*Z&zqcIJ#M9e%Krn8Ne$5!OL;_#RHOjJCx~ zeEhN~#KOI#dF};j(h{i81hQ9=R6vqt=I#wD^f7M$PuU&7sQmh1-g?!Mws(4!zHwJ+ z6dt(?JbJ6H03uy$^6;~bS5PGQ*b}e)e)ydgPddRcrIQ*q*kFg*DpbB;J|3&4D#IRx z>NE2AzchXqA4>gcu%iGB0k;wPo*do5_6FNtN%jx}X@8VPG3TU^59RD0k_BcS8dis3 z7VHFdt<)8EkJ2D#>F&z6YiqS)dmws|PJsEzT8G7;;+mu++e?(UWWQI;vg2{Ua3E;h<{~#Wl_PzrF z=ccbVi&BgtiC5_+T*2UG`oT`q1taq~MaOYAq{=j;ia7uiYVX=FdRj52|4fBtDEJi* zd_K`hN-u1mQaaU1Uc{4~94ZB5om*MBXb=I4=Y@gs#q#maX4};i3Os^(fB!b$!JuWn zRP!Mn$=oC1rtQ3EZ-pauBh~2Dk<5cy(B%#g9k+B0uO)-cf7?pZm$qPw?_LHwm}bn1 zT9(6B(jF#Bdx$=Wji&EWVSnmiRshb{nmMzSAY;)VQC!X9Nk92l&2xbZ{?0P+u2nzF zZ9mnG>^W4Kr>Dmpl5j*0=m7vvjqOzcX%RTP!|_Qm0BZCn8d#E$nSw-(?4SW3a1AXed)Dmo#Is*qh#IdqVwzx zHFz)sIfk_H#8#!w~a$2mi135Jqbf+ zd~sF4IWaoUZ0Ksgv}VA;A?NyK-u>`J(Q{sq=YioQWTRFyBIDH6Y6Q9{X>Q;211GVG zH=a(29>xDi)mio(LcN!#4Kt+T%(QVw0kg*&aWB{Fr#rjvT4}j%$q6!sCdfdRCTvXK zqj6_WTWR~|{hh=@QrkBpramKURB19Z-4SGzLZ3Lz1b&me@1+|FYsFL?|<0TmG33^ZW|g*4MnMWJ&O&tBKB02 z!!K9KcRNLI__O59$4-9`>^`3vP^dmLpn>GiJ*WQLcSF4Mjk~`0;cehcX6SC4;Lv5{ z^UAn4!O#Ohw^(YF+vtAj86A8_2i-vz5ALKJ2Wyd{?If0D_uU}bT;iW4_uJWxFILWG zx5cVd5bw7BxhL~|Xa3=#$Z>?Bw;r@Dmxu{dUdB0b8gJU^S{T7jDgnV>)7%vxM?%aKO+sS^bcIO_-(+>8n)}4DPPdnPTdQM19qI@I2+wdE5=hl~; zR&myV3-so?b0=*V{nka=4G;2qow#8^rIXP4ZZ|`-DRUL6i-|ln z&wxEW;*Hzc#J3Tb{b`L@LiM&YM1CyjivfGs$Vw-^PW7aRFVNY)#J|kTPTyDg^w2hb z8di8e(E?Oj@M3*U#XI$r>2^_S;Z{ul4oqKdaFPj=xxD-%#7g06OD%s>Mg#Mn2KVIL zWUkW*QSs5^K+WG!Y{LS~;op}$O0D0pAmk*q6#>*14BfV5!xD~R8MPx*{-}B9aMfoh z77d-#|JklKozY9PM9u}b^h&+ur*^P1*Lh{{k^c&o%}ad3^R9;%$yD^-?~0ck{(9P9 zP3yGOjF1>p(~R-_M8~q*Q^9f#ML)W2+=N`*A-Y||`=O3nBPYOXH}i=2L?m-|g*$y& zC8fL-kTe<~@!}Z{735YvDgDj6g}E{K9iE#HJ#!4l{P6PAbwzmZyjSg}kFP9pxzec* z4iBx$2*J!+HoyY%@GyCp>FZF4?+w|PzU${-1qI+3=e@CF2(ELFwSVPQH0fvT16>r!)I3YOX8k`D7}Iq& zU?*1|mKjh@Lzb_x+oDYd#>3u1(^Ii^B8I~Q{u(JDf$)Yr<~1^n;>}c@L89-wNYn# zPM)a$j~lP8Tl08FJM}iFubQPF5>3?5ITAj+UD3|33fwEXr38I&>Tar;Wqz+W27IUP zcC+K-)XlExR633wukcH!h1A}K?`_s`^=h!WHFIW&YmD6#SEG$1849QWZstV1zFlQY zA7R{RNLRB{O>d4EFDO^j{Iu~pHsaI)^Kj}SLiUcHNCWEF=<(k2yT9yGp<}0L$bJn+ z=&*T*&2wD-@Uf~3r{*ZV`w92aQ%vRFrPS4&&def%DpR$;Hy}s_fck@8m7Wnu=z)o| z98S-_-@aa@Wa}lq`_1cZ@^XRARb42u|V3K5s=n-mz%ERn8uggM<%+d2aqoq-{OJ-F3Q z;-8dem!Ajt}*r&Y&Z zWK+1-T{g0sT7dOPIMAe8vw57{5S>ejDKIW7OR=R)h0efVuA$P{JtzSyBXwL|!n~J<2{6-vm07h+D%ka|C#bu=nvU?iMpamddHJP-qj}Tx3 z2<-LGvfKl{d{RUXfs*}be}dSoPPJiA>opXf6CO9o?!KB{3SIm zoZQCv;~K-b#(;Pu8CPfY4w^g7AJmv?kb{3`RpzeFua^jw{L#@loYK--YjnxWdY?mGJ4U~uRlqs?RGtU3wf&;f!v@1r9 z9yB&&QIOxF@uHlkqzsk82UfWwG+bxKR4R)Pui4hk{IrXRk|0&l5z3RnCfB&t1CS7! zfLtvY_$xYTP!z2px6I;M>Md8%fl}{!r^=lLxMwd>x8ZOl^OaCsd-R9iYgbvFp{Pl8 zhM|LVK9tK)x$_fi*WTy7Ds|0>>@j(K@oTLglb+~G} z!zP1;3vBKapzwkNh51n}vBy-4A;0?##0#HuH~ad#)Z~By-@v`a%%A+wG*#0c)9*Xp zMf&a5Atvg`w4JCzFU>?<`%ckB)q96*DooUDP1LKI;uWFK&-w_ovSIA5I2zq*i0(50 zUhBl0^uqcqeLSA;E2BGU-7>76Z6c+|J4s~UM#pM=2509^B+88Aq|t50%W8;cS1P@* z+r)}8H6fHeQBhT(%F1j}EpVGoMFkKD*D~Mcy^3KIiY%x0ycy z%ZqR5l>s-up%1*(ZGungo$GdT?WJlk-jsO5$qnDa}nEtL3IpXQPc$3uVVfx5< ziOH2G@HJb)S4@@r2eMc2S4Yk9TucOoCSp1Q?5(^)D%6>cc;Di)`S<83;h&CT$l+c7 zg23AP3*JG_f+uhEr+h%mS_GrSI+)_4jt?zXJ+hYLoe)EanA?KSQ_0NKDsL~-V=gMA z%lnWae?#zL4|x5Ak6#I|;VLP3eT1VoC&hci>)Yh`X7I|(k8VlIPIU^*va-E z7Py6x7k`3E3-f2_vv|L9Tt2=F8ezK3w*s})xQKeice$Tw!dQ9UDSgIwf$Y!$3>~Ae zX+g>n0pbAa=`8bpL9I@F<0Gt~f@2z4hMdI0XLKWWnl@g}RQQ+kwQO-o4Vl=19B+8* zHDk${Ncsfo8_zc^G8c_kT_&#JVv}J`J2({1JfR=&7DsW+uaFIZ;DWRG(Ly4;?;n1{ zBdsLOZz^drEHhRVK9mq=SmF-{I`gL+6P?S`Mr^*}P5l+*!4N@D*+2ZlGxofSjlgG) zteC2?|IDJkaQa>~q;;d)l#LypeU!Jnz7dXpj-~k5B-xlS*s4yi!in955xFCmmVLh@ zJz6)tAM2$?ZAy>++!=T@PoKL@`_)7zlitc?=)CSF=(*d%9I80T$+6QjYC_cPTr^9L zTDXE=LRdntL@dh0i7`P5nX6GWryH=n7_uuuK(7$|w=z40k^AdP;#)h33F3t>8vRrg zIp=;etSi>&C-wVT`kB5|b`yP__6h+9^#X`v%awAG$K%vj^zJcn1UHMyll*U5djdwc zNUNSkIRyB)?uYP&Pg)P~u_SxB)ZQT0Orb2XX4-rOswlC+o7VxiBi76f-X85@isvzR zI!|zuTI$|5nn50!Kr_=932p?wcsI8SCX9$%;(EWOgkcC?y{V-; zz&J|M|a3l&d~$ds6%@|9>fn6J2~JyQ2?9l%IDWEh3LJC2x# zn6XY!3fFBV7w93FP(w*V6B`4n)o=;U`Iat%&6J;@culbomPzjVoE&0%sRGRuWIvo! z+Z_7uhfh)?2cVz}7zUbrcpRA@{76Px zhHbd3f$kHk2>puSIGiJjaA`-Mks{8>X50hfu_%5fAh-{yD+*#IBl%*gsX_4wCzR~qTUj~b<9Mgq`}1}n!=^_ zONcLR!Iw7k<(*3@V>v{)X|0nS3l1u9{$R~LEa)Aa$`~8gd3qnId)u2s0efbE4A>K} z(z~hV3T3ZyQ@gsQukb26TVs)3)}7lS2LCa=At+2$OMgZU!Tu)vffoNOEHHl;7;BLzl8Bz zAPD6(dVjyM;NRFOV-OeW=3iWtbI5$TcC48_fq$D2p>h^ z@fR%F^FF~ah*9HF_C@vHE#^}h%2zn_umj!!EcPzxXAV8g z-3h#^WP*ZOHlefv5Bo(qwstmp@-fRHfHsH2vqs=`Z$9)x%+mlG3a1nMIF~# zv&f<|`LznYRg(%6XSe;Q%pMhBy1%dnl^wGQ>eUKk0L3PUiS7&;0&FDJ6KlrF*i&t+ zd&XGzIn_`SV~Lb9XW;(45Wd41c#&)kSk5p{Gw;)?1H-Rqf1I`a`WBj9O!<(?lV0r% zynsga?VA|;Hqj4bPB6yTurVp@rM4y%X(dZE<|4C#>~LhMmYwK@o`wTMRm`yR8{L+aED`nt|1&tWAz&AU~ zHwS+EE=iDgydCu0Z6K@}-k(xHnbqCD#t1Mw^m{LMTRg0K%VN$&Fb>-E*(eqV6)iFBabMkN_I7L2+fL#oa(8h4) zg3{KyPr}XRxtB*Lk;H#8Bc(N=J9>AK@;@5x5MVFP)pyO4;VdC70rQd@SO4bXRlZi&J;(&@qGs z_*hZKD<$dD_f@#1qmII{MTp?&4=L>M?|8I`v0aU;oXjos#S~l`6l`2|=~^UCX~*{5 z0v3BNk_NRVL!0k3yzfnVN;|RyLXoe@Qt#g@#JFTUhLj+Rz~4*G2I+oS#F2nc$&(_v z`m*oHmog!wK-v7z&5R}V-z1dc4byfpTQe`YtG?u-l=@KP0hhi`ax9Df6)g`n)=oPB zJgcYKMzprrF4;d*g~dl)Ma?}Fzaxc=m#qyoPAI+9v!Q34IoNCgu;EMuU*6h%VGZ*6 zg()qKmrRTv?tY6v7E6Fw%L`N7>0gMiJIRsYvYWQET0~2$%jop<#lnGr9ooab{&+U7 zG*#`fynAgQgWb9N&zgz1@Ddy^PIDeP8peLfgw#^NHOTv9dt+$&y z_T%Wu)?IC=A|p0asdr}2y7r?kwr#(V8k{C(wAB7WKsD|e7adPv&?Vlk&uZeeZNVW@ z^is^sxJj69X=Ut|uIg$t0)M>j-8Ipqt%5acGNDI+Ez0LR-gUf0xW|L>p$VHER_!cp z>d)>{xft|SWu`AM)z(Zbq{W>}nC$+M()AJSD~)byNKH5stA@n1;s*_3Xt|Lru)T28 zi%w!+8seqGyvVJXms;~OofkLGR!)03b45GdahoV=1N3un5NDFk)}{-V#~#w=>4oTu zoo-q;3BBvx_X|aCj-HTjq{VL}()4cZW`lic4At)wIA+Kszt-+~zKhM7)xHjlD(sBluPr6!;~bp`&ZeFrI+l zN?4w05`Ab^*%xArzRM9<5ZjJPpaja(smE_obS8M8%tfGYm>41UeV$Wx{ zA(F7l8w}wJ(K@p*L938A(}_>753bC%&s(hZ(6+XI<1K82GgxxTrGOIcm2;L z07E6czQx}3Jihf#f5ux$dZ52uA3WS3O>OIFvAk{W3=TYDI8mbwC+Q`A4;pe<$K5W!l&Ny{aP-h zDU$E~^qNW3v;zdgYb~EKIRg2<%B{oCbwzjijsvme`_BXUj^pEVeaQEP(Mu(^FK&Ju zo{D#PUjqBe7u0%7kK(P}P zXOT%(PF4iQR+2DFO1&V+>}R>H-9_SVD|Jjt?|JPwsj`~jWpc9UD; zcs$}5(`z+ft~V{oqfJ!>GCCBEwr8g3U#{=)(3kgaO8%55YzZ zp}jDg&Zp+~NZoox9m~vBGxM3t%lHS$ub)mRT@Ug=kD(HLv$m@IeG0-qh_?#zl=Ad;Og8^Z#nEz&EKwjnRe=#cGq`qsrnA!{m zNu^WCV!Sgp-vA-K>P6xR-BF6j3&w;e`>L<_{kKSU(>YR6*BMIluGUK$BR+AnTT@F~ z>%IU5!VA7Y2i#OHW#p>g8rWF!3om%9e+0k~>+vB&Wv!)O7>daqQjo{y=EJ6!?7>@e z-JxD|{~s?C!g`UNk!wuaTXhNYcVHu}O&3?hmZD2X_b@khpiP2W-U6fu_?Fb6ks^78 zu*1G;ZW^62mBC=)fXa_O}KtS|kg8jNY>$dNzj4YUw646~V5442?z5r)$wK z56|~oXXVsy-S3ffL0pQD_w~%n#upXesZiWW?oP&Febt(J-gw{S-!nfBseP`9yew2y z!Cw(SLHkb!pi1g?9x{$sv$>hl5A>u}M^a8%xm#wUT5jE8xmR}bXCfXg0Wwi;{#xz* z_&g!7&(3hIhOl6GHn-Wh+2B2HIxa>Czn%qUXMad7k@RGA+jG%vKT#Ac;6^*G(qQFF zeu*Wa1)!tOTwbqE#+RV(u8qB7fS%nKQnY-Bp`i7@6x~@cHDLUhsbCbLECHQ0I5hGf zS7&vJfIwotyvYkD$?Q1BC?81(t24r_pI{|X8I3Nw$>^e-v_ThLmbG!hU_~-Ai=%r( zF15PoGqk2EY7w$#z6)6f`dRM&>MUz7kuFMUql<3JP9tlvE_yhde7+nmvK}M>V>ey& z?6dN^Xhds*K@{t$i_YI7T{N$KW}h~`K@Zim)0kO+*|W*XM$)B!*7FfWctzO<1d*s=ZguQ_r5>DK&R@_*a4T7(7)qJ@rY6-oErn*$}o&pIka8 z&?i@+K=ig3orh-AL!X>{1_Sud>XR$z%NFXBUd!BW+T_EJNSkb7Nsn2f0yr3*vi7W* z(i`BfBQCvAlJN8iEv)Sajm8@PAcEKkLyQ`_kvBbjC9W_|;xalxyoRO5kizCe|1Khh zVx)38@RIsafyk1pr|nnZ-yC6EMev}qrsji7oU4qzqi%CpCm}g?BjeORILH&NXe@QE zx<%bWvw<7o-}9W47z#Ut`U}ZklEVKGi5vHm)7>57U%*Il>Usqe@=*EwotJ8F< zrSTKz%FB6(q;kzhlp0PhrFoDwaWQf%TrzZ}1EqN~O7q?lr&5}iVjc3;7h^n`{-rf~ zO%>;ZEQOjynlm>TNplt=7irFt2hEL(FZ))gafy>r03DdzR+502D0JN^-Gj{lry`4& zcz2~&K40q3QmH?~D98GaNgFZa{DS&Z?JYo@7StcS%mEhx!~wsPNab~)djwVlCztVH z^_qZ*v(`;BI_@fbo15XS&1-8-z|XtY7fJgn`EgQ!K*foXjIZnZWzA6_Y*U0%5|&P3 z@Fm{h$Arg<^F^Cebf~B;Z~R&pXh4*RG<8{Zx}8!+le~3&(K7r7UINX>7cM=lU#Bru zx(0Kcj9&66Zj7Y9AViw40i99P#;w^Xf4L^ZcNAJW-1IW*BH<{TN#;ekp`9f2vO+KM z_uI|+j19a*nx-1PNB6s#j8j3V&A`oD3e%L?=U!Xh)_k{pL5gmU{V9@Z4Ox4^)DR`4 z#8i1#Q%p)k6-o@}*G;>zEAhe_Pj;)f7#eyGC+Fq3= ze%dKiZo_g`7>QYA{`vxW53DM4+o5+`yVtuUL5qRi3%wS-!OP4uX0N|xbwPybzj(+t zytt{&**8!iOUu1_j-rvhJ2;NT>WCT~_p3~j#|AbK5jS#+LSoge5g5m7!+ zP&W;-o7st;6U{15dR%${x85@w~K*)$u=Sq~l2 z`0d3oV`IIC$lN>q0PiM~u83uqBhU=*mNh(iVjtO~BfKvdX`q?pul#*7Na?h?O08L_ z_v|pSmhtz3&lHdYxb~%=c!F;q`&qA$zGeE!-uDLjNgQF`TR*A8y}pNj^1=y>*y<<$ zsr{^r=}T|@MAoie`&pwKHh8z(*G)y)L9dyD8OZhd?1+D!rPJHz8r3A!(h;p0>+O6R zgOO|>&6gtOq?I1zl@s;+R9EcnCjds~6j zm#J*IB;2=_6XrNC^}~U{-_I~4d+@MG;ODHVOqkJ4;LDxXNla29_@(?{d_ILpWPHR^ zv+4+Nn?+e;$IyyT79;O|kQpie3*aZ!E|Q*Y(iN9i`i8d>WGzzhBIz17rEuTdU7evu zW0^t{Vpr1c2q~R@8@0izQpSt9B~AUV~yN7 zM!;PQuf~pMwZTnP>z&@SHeVgwAS?mIXpy#LHU3w2`0YJ}K|B4C;*CsOK(h>TelJgUeYnqTkWI%u`G z9QovhXjH-DP+{a$XkJo!K`+$aVuh2?Wf-l}3>O34=LG29r1^cJOH8A9~vmO zPEuiCDU7x%lm<#u$LEXRS19fzSCH|nnV2oJn|KP~K~d>zvad}IVV<0DN)= zCLp98V{I1Qf2PKKwd0P%M~uF+(FNKXVsUaGSX*gl8Mm%)6Y zvD_cD7^=m;<1068!>MPptEf=xRE*5r=^TL#IpA~ zvVtt?Kt)1V++?%oP+LKxJT$wrHIgM5F|<>pSKh*VH@))Eqw{*Dv6KBB8`l3&uk5x< zdm8m*ujapiO0%y5MooiMti0HbP4T84!_H;$P0ndax%|6g_auJ?l=XI+pxvuXix;L$ z@AUn=29pkkc)LijiX(a3nWrA@MlbPhVC22)@Vxi?Oke4}NP3`!=1pe=`BQ6m!-cID z07sjBq-}bfcdeLnukI(MrM?WS2x{~1gju2OSe_1>Ujm0?Ul{yT=bCbp-qo&@wvxVfl>L(ClMHko0{Yrcoxy%@1l_LBdvpQ^$cMz7c!^I&pVMgmLzv7 zIX!`0qKSAv!ijm;A3_}&VyqO=vNqW<#@XblUIeeQsnWtpoS?)=dPEX`b-hnCnRu9@ z2OPu@N9bHU(CvKV{pqI~YgZ=z^xR<|O@CEpywn8=DRCtUCuNeP(x3ON;YmQwT%)Ic zn{@TNJdFFeG4}+X|3&-B|kJ!(UiwOL+O)z z&=JJdw+_4t&$hIz3dQY2`7%9Zs`R^1VOnAR^b_EtTi4(5j{2$aS8mM9=`=ojoQ(qufbe%qQWafn(-z+xI@;dHhcpaooDekM~YBuqnS) zQ$oAu+<<|ocaTw}^Ar0Hm%uT%>GGTX*|Sq@DzbCsePTKf-P4mizj2c1sn63F8yxm8 zzB54+i|9obN|_kM=l4HrrWv8@kAW?o^NtdL{OPcA2SH$!a4~!E=2b)AnqYJ)n=?Cw z8vXT@RQYrp*!XUGWL134!|~;z)W|9$XpEm!@9!1*eoeqZyN}3R!JHW}Izz~y5Nu^0 zT%;=-H<`;f;;Eg7Z!ie&Qv;jwgN1J0;rzU)qZhythke!$)Gr*uXHDK`iFPAe?o)3LB4!#s;eOF$5q=WqFBE)dD?<8#b> z_?8MceX~MhMbdXx@e?lnJLe{&5oi7|T_(J!bacb}xxrTNXjtvsw}cPQ%!SP9k3krh&>*Z;>{X{awJoRnHgJjt)D_YZ!(cc|V<3gqta^&vNN zVTIobf(@!m-p>uHuk(IE=G-hlpOHVDKML-8sY%=~BqrkxN^uOIf6yD5d_7D#gOdnSY>N@S)bM8RN{E{XOl5k50VLrG#nitsX{5 zlP#&5-V`i$d^(;KIpan9K` z(zEh6yk-e*2+K}2R(w?K3?t_kj|=YfERF};-griAM-Fey-U|6iJ?U{3xrf0M7S{1i z7spT?%CF&*$eVzggG-{XpS3YmQPMB^(!3H@h`E$Mp7^H8@OQ>Xf$_FLb?(^$|D4`< z>UkH$tldV>6DQcn*3%nLJMYvBIF8E1Om95>g6JeCA!n88jSTM`C-IDVK6}!s6Ky=s z>5b=Ic=4ImlVN(}#7XB+c4wxJ=hy|Ov$JEKCr><;=O3Bp*u;rvqQ%4c+NYFFB4(U; zV5WRtDWfW1N%h&i=r-TZcalc6%#`1(Z}HCh?6>TfQ=Q~7c4$faC6rxf>pRy;jesC?c+Lca^MIhm-Cs@Z+C8vzjly31YgudUtEl|&P%cK1ELl1-6*ymEi4llT~latVWj8T`iLMr zxi+ku^VZ0tZk5-X8G>Pekfs@~39i#olM3f5*@d+GJgP+nbm2K}xBiT*8zr$jj3eC@ za`GaW>yI-v``eE5RxR^mBsCeFnrX(OVUgL@_*OHRg$$-K`)|l8&+j938{Jjwz+Cp+ zWnZiNFx<3Za-I4z?Gp849&OTC?i#C?JXuBmnje=wk^MeXe0b*4{Q)GoxkTkyIy*q6tewY6e!GxPbfPYA zB+fND0eLf;&o9M#ufdGW*GjLQ%=#6x)9)<*S4__TeE(`bLoH$4AFce&Pg5s;4UL7B{ty6b>O{eN0DCSD@dwb0q z{U)YRCuhg3@rvtBJ4xM^1RE8ThuJnGgI})#b+gU2s9L~>%;MjvyV6{4=p^0;aonb* z1nfg-Q_@~~NMI(OANMa)y~v!?Q$Yx?lY1I@2=6Pirj6i3aMw422tLB`fX^>wegz{pb#iT{t&0;9 z&J`yzTk%c(oy5^RNHM}cmjj83XN-CKA!|NBz(%L(Bc1Pz9!8&Ma_tHI<^0aDiKf4+ z)!&uHsp{_v^_S)R@}m9{7Qs`0Cst1-9zYL_yHRM8iUB)eoJA7@pI~~OAWL$ZURLZi=Zm2tb^%gz;wO<^FRh*^=; zGH=&0@|x|`ne)W^q=nNVHdVHFGlRg^f0eoYj%+mHo8zB$MdzB0lT`v*%4A&H3iPavpkFW^0>&cjb(uhJ2d$43W6{JlV77&zW2oskgSMCb+f2uu zLZsBj+&_K1e#lIW3l4Efu9-WFM^0iNau(`c;UxN-qE8t_YNKA)pqJ{U(f1ACT$Zml zVaU=ndAs~FzyNt%6k$L>ZOLo-j%7Rh4}ODrVL!%WQpKTVY0}C~f8vy?#>Jebb)xod z){rjR8>~cSRG~cYpn%EHv^4rN!#PCo#v)f>9rlQ?GZ1H&gspbjm};`o%$QoGnYFBt zS&TW)e@y3eYk#Md;BS_8h2m}#)lt5<`mC0q?Wx>hREXU21$^|@KXqAx+f{S+&} z+dC_`oG8BhT6A|jm#Vx6KT+W~-1G^R^XoO>qYh@mldlm=96aL+l484_ZuJviCnox0 z=_N(Vq?u2Den@b>0ckFq)k?qEPs%pcWH&f(go=3V8fP6VP6@ zuMtQ^$tUvBFeBsP1+HfgBPH1XQ?cgbQ>zFhV>b!x)hY4!(87*)?Na0v@a9Fgj@ac2 zsoYOdg-g-xQB+=;JT_9d$X%5~ZR(d;aagA8GXm|uqJ@LoZ+GeJO&>Y&3TD(Q@46RU z!?~hS#NRJ_3!SuhON@{R0p^`ii%>`VZN<3?7M#PKEg<-kxK+GIWMWv`rTg0T zz)4yUOry_g6ZJ4tho|7}LMpeK{llnOU5oBCrO3I8d~6$#n+VLu5yr@(SHoowYKH>ra{po!2RI313xtgIt!M*e59{Zo76YTU-2e&jCvO9mIoR5P&yl3XDE;%_igW4g!9l;* zQ{htHjYEW5^NhZMo?$HC%a(#LcsNApblNJw-p%)^+%e~a#SfVsc{?TPxG5=JG&8TB zuAw+AmrTFkpn+ZbF=YfRv61TCer+7Hdue2ar^Cv|@||@oe)iG-yN8+nyP4UhLhtVX z3dV8aO+4uqgmvB!hTwPBj>Gm}YLga#-kbMoh;{|1l z*LxN;%AR1lX6dt!{(Z~#&l{NU*UP`N{qjNV-FToHH~rFy%USBsN4I}vhYkEwOT2p1 z=d^%(cxDh7_K@!~<7-QqGP?lq$I$P%Mm%j;4>Ystvh(Aneg^MmQ#lok*k0V=eS!vR z?3IzseG-Y0%$-K{V;2E=hX&vsC~*y7hy6xa6C(H+o*dk zcQD}BwniO*xI6Xh1Dk!Vtt!HtZ9hT{X-T4~*~G7#e$entB67M-&qpIDTbQKQF>YH^ zo)ML5X%Zq>`_j%*#1rQ6cVa8lnFs$NkVfU+Xn3x-Cwgoa4?lW$+$Mj$b*;o~zOKxE z><8>GmFI{})H<3-p<^})c&100Ys{J}^Qg+0_QW;RX_w`ug_7+Ym#}D5Txx2dV@3jA zWcT-hh2-%s@t&6J4u3cP9N_fb8jvcT)b54vwi9u`nmYHzdSlRl`MT#`U(-%neYhXs z_UBkuiEJ4S2?qE5T_t<4pJ>Fp_<(@xKs5(=6NXwcn|Pfivjehs!v1;{j4iYGF4duv z1uFJ`Nlo+`q=H%gZ}jD&`;_qtzONmCu}Io(ZlhDI2Vm&I8$Ereo#+{czothV-NXjo z&f7gsUT%tV>IT$!9YfT=yrZZa92NVO0Fv&H1J5UJhC}}Ny&_o&YigK}46yZ#uhE2c z_pW|)G>?k@VYpEn&;+M;Tr+k0>Qpa9dS1=H*61yj2p;+v$=665a`!}I&{36MK) zcV!Vg8xQcY%x4vdHjC`o(;fgOW}FLem&sX0?G&Q4C2j=10Q_cEPrNb4_GR` za5`>jK*54?o*%!Yl?fVdyc*2Fiu7|d@E&6~ zqt!sGA>;A|pdD~{YKSADyN3aQHv}h&Zshe9gMa3+|J2}b-KWRkj|5-LdZcK+%~&;v z+YjtxzF{IvbX+(gb*2{nqLGHc4QAYkV>{Y0QuK?N$ybc_b?y(|qRIQlQ~gj~kI|kE z#{%&yRPzY3opVjR7A)>qK)ay$AW`n}?wEgSoH=lrMU_v7#N82fD?crd>` zc(eG`-~+aNyl$`Y{@UpBUr)dLKm4B>Z&}arJ_v&UH{*@gZ~1t+b(M-(Zsa zpx?X~k6d_aZ3uTPee#xnl$DD92siJ^sYMZ4bR+#?EWE?1kHaZ;J+Z5Q)LQqkB6TPJ zA<>)}4lv|E&4IPcuTzQ+*qEgpae^hZ-L!5(<8p=4#cq15aA5EVr^;#sib`XBW_|49 zUr$}nN9wS%D9k}3s_N!)!bE?U8Sk9mlH?77HED}nrGs)j6Qw{MDcxj@;1Qyl;$73p zS<1qC2ty;LQ%wGtPjy)<_raznv3gz*`?njJ?&Hb`#-1MYP&Ok1v)m^hq%VV!aGN)E^2#Yv-D!wLC zmo4lUr;XPJ6Y+3OV8Q#g+K*MCvwp5A81Hn_U0~ zUD294+m89ra0)Ybd~t2jhLpe0Hg`<`!xSZqcfm2Nt)7AGjsL!zA^_qs)|Ci8-_Vtv z%?tj=_I^QI7`$j&PPB7Cw5DAATNN31l~{I2f~vUB?dM*j5oO-P6}U^g*sG5?R$?COTiFTw6e-M?COPV__JZE(Zp z@Aaaq3FHr)?$_`>w`1(T}tW# zO>tGx6vM~dComD{?=lQ@#wFTR`92&#)61aCYVcKaOP8ek5w|p)Ii;*QRkn)_!<#*i zfjGOJB{^qh}lMf(ja z3Of+SN|S!jni!sxeqW?JaEgNZ%#x>rFVc=e(wsuhoSkKFx{I%zyCrzIjIu>%S};ix zmf8BL>*IL+H<9fO-TzQ$&0ihX0;t!S)Z=g`>|FnMIltbOtGc>U3m3dwd3Oox%h~gCL4Ev+CHk#YBwMwZc6}#CzTAu2?QSa(WwRZ|a2y4*5kNr7%*%VTbZnc5IQ#SW5oZJ2@Yotx?F<~x z{?>$$GjL*?GjPfjXJAJM%@(O`&)>3TYTMbfdx^YYb5|QYEQi|zv_ zLJCtLg>jI=EH&;7yi4GOW`151sDMxYVaw>@ctX40e!cS9=cT#6Fr>saDg74OBO0L^zgIY{y#+zmpuIq>0vWEwD|gy zvzV%{p@$>j9sjq`!#34hNDoJnQKVJx-KTx!EilWCz2j@>;fj6!Pw8RtRejUL=Q|b9 z_kT-ZO zEcx~qCdkeWCF`VjE-HtwR8Abwsl zCn%D$AK2(#I51^6i}{gvIt%7ei2orvkeOH=BOZat&3Vl78M|>F^Vo*Y=JqeDqx+8S zm~Aq(`1hH#Z{8-lGtQ}On};g#tzM8VYu~(`bA9I?%gxdX0X@iEgBcsny3E`g+k6r? zGa37UGykK|FnpFLmAs+Te}prllehyjPqDRyn=N<8 zt3&PHCK#t<)Hb?Acki)ab@49bnC#N%L4>)}bvR~!^uirvTXEwHu&>~+mi{I7m0w`T zcuDq^wb)mdx(n7~UujuiWi1FmR{dvwjnqIpHn)47RLeODJnK-@P0_`;KhXI(M8~xD`6JNHtXJT4=M$th=GZxWTf9>$p%uW4u!|UTyqMFu_3;4PR$y zG{jCKnV6yJBV(JQb@ejk#~rk@a#=`hT3)2wm&4?Zi=?N7BKuBhbms=gdcq63$|BBv zn=~F19O*>-9ay1CQ`BFel6yBG6o8mqNaJ4V6o&acL4XL7cBNxJ$d%zY6lmVCq&-^J z9Di$bOUm~(r)AV*HWFACDk}XfvI$C!UWgb!e$4Z74GS+1)uEsr<=%CwI6d3MkI*rr zc7193M-Gq&83Yz<~zv))Y<8ag|98CH9hPa>W1#)lv7)F zO5RS<(3!mmU$>c>(g_sQLFHg}vx>5sKd*q}k&IKEg3eEq&H~jv?=HZc#bmMSQt;Vl zW&4`herYL}>g@)mvxYCjaHDmnPALtP7XkhIEe+B|7h_C`we8d7Y$ z_oi^E=TKw#-i}y(BsP+rD*24pNjp9FHsQ6SCG7<7-r@GC+Iy4G-~!p-`R!FtbRVw; z&<1=VA7nYtv*!uw*KqtUH&2NDGIQ_4!>mt(`}yMURpVParHDIVK?NL{vVrZ5C9%mk z!ZxQq=6=bYU)`ppSvT8EZd_U-rzX4(<+(SeG2S=;KctJfV={btOHz@t4(VDWy1|)W zci}*NI`@-N*f7)dEC&z-ek>+}vDARS~?t4jzqRe@Ch^-Af-nB|9!p z*I$7*$5!ah)Up~$EqTBjxlk!2AQUtng3b6YR+bvKY;RZif>eQEccEf*2RY2Q?C<&J z!`0vqJ49rK52b(>1ZL@<9^NdxDDx zvaYE#A*?Ie5SM`3%1KOTeA)f^V&P@enZ_eY%I=&`Pn-OA5lLq&((Y<^l2s}=ivPUv z-x3cghBFGmYuoph|9Hi_sTc6c!;!Y^1S8J+ox)+I3Q?&pmFtJBOdnsxfw%H-(_eL; z@bOj4M#&2n(E&4WtMvZ;nS9jtN}X#?Mnh(HJVbW9Y%NZkq?>GylP!L3MQQGDc3jrp z)hz8TocgO#;5e2FdqAYd-=hrfoc+c%wqH_J5eUOyf|V%YKG3i6zQN!El&$$pzk3M!`QpYQ(;FFV%F?03}B zn6eT0a^Hd-se=;$4jR-O~dAilV& zMTq)Fz_*%D$$ka_!k^POs*p-AEQ|d?+w=Kzz=2`q=!@>$D zIhhwfQ$lwD*?7tMvtofiligp80BMi{P=lRZ6&)gyYq27VKaYSP0r&(*!1YgJqCW_{ zvVBS=WOyBYiKH)PhEAzvT@XnFJ{LdE*P}IuWd=2H`3#YjbCrQSVBf-RTEvmDriHN& z4K+w%pIEt}q%=0kO}!GS`&1j6gd$+4?_eFV-H{p8>@{s`uE*Is!ZA>)cM>wAx~Y>0 zX+@90D?;{Fc#GhH#CM=Obi7DF4Y7=`u>fLFI)t@UifDW()2n?|c3x1?D!i!`BIyxd zI;>inY1gb;l(Tr*@-`zkxZvH(f=r?JsDJ^``{%e~S?8^jF~HxN`k<99tET5;HQ7UX zSG$UY4PPXtsKPjg;|mBR^MRA7<}=Z{OTn%mne%dFP)zYkJjOUpR91tprZXQ^iI3cq z=%)}|Gfd7}*w;Rl21JueB3KM?KR(8S*iA?x=BnA_1*0=kX7f-mq zzHQcNKUmVj=g~ut^`*_{NShbMTE^qtIIR>0>sFpCei-RjEIg)Iu~68ulJXk!a@hL=?UrVhm~$ z0+BR7tTFoIZBXz4?cE_6*I>|Iu z>yU6Y{x%VUc&Bhcp8<|&O~<-Ed2Y}&&Dr?>VfdPvJbxJYeB!l2=dy>AH;@U@xPA+JQ6?cg5 zjV&GLBhE%wWFO$u%siYSj9Dxe{Qh=_^9*u2^Dlw`-|_C@#E2B~$)x$n455S2+3jt8 zKD+^Pn~Ir0-t}($5~=ntYqiBegL>5X%C4i0X1|Xric^Y};?eMP@d7W25*g+W+p5y6 zF0Uvsb%WqIMKn9tL(=}lJ|Z0eH>u?76w6ktKp-!@VI&nQMh2f(6E*Ch#H;30a|Q3& zJ9rBCQN9nQ`s|ag`qPsslxr~X148cFUKeqNp?tG?AbJR+w|WRPL{uEye$3$tH^lVWmFNlxz&`!wO=x%i;lvb%S5PN9XlXD$m%2-$mz@(joJ2j zbd?_(9Yrcst-)n*ijrmsC@e1J!ZKBj{u`%0NvfmOR2DZ+ECHsd;_AS{PMAb6V z2bSzSK7XY>TUU@{^ET#cEe-Wous#dBLa0+U7iCZ+Jt|jGZ|*nJfw73ICCgl0Q8R#;+3yL&?>7J9543$jeMJ&W?d~nb>4s zdJmY?gt2iKX=K|74$~LUqJ=_W%Dg=TyYT=>y$Bw@{g}mI9;n$5Z5H^0?|k@m_G6Y< zKR`qJ=Jw-_v?Tkk&^SMcSlGMWAZX9@2JFYz4#R%@;->&gUQph=C#|9QL4JEx6y49; zZDWDrpS7gV1r9PcH*-q_w4fj%7g0F(s0d>=6&IwP&kwMlgj3I%V{az#AGRiG-54&= zvqm&1qNHR*PZiud<#T$eb&Ev54$Cwapq%V4Arw?x<8>iqc^8s(l}Q-^H=7s6P*x|XH2EL zY)l11pf6jqV^Wg4TIb&@8s5+9nqC7^&+8?bSRGFO*n+l5T;;syNDRc4F$ZkN2ny&4 zeDziKCVY3BkHve}njtZVJ`IYxVCQvTZVzGQg9XB=hzz_`(wMPQb0x)|oOiC!?1W`aH49jMAEd*Lg>i$J``*j5HyZDqZ$6lpO7Q$MtN_ z-=JPg723;Vy`*BsW~8!s@XE#wldlpiy{%C{@+udG8|{RfwW_%iSaWo}I6i2?rHm%N z#PuIoaI!Amx6JNNpU&L6n9T}mqT)-_hM6yBXaqBaf?8Ii+Ysu_bOEkH1$%mje6$fI ze4V$qZ7nuVI8(?GJ=UB3VXt;`Fs*<52&Ps2Nw06udpQbd61iS5H#>Ovoj;1_)^F^} z{Z0z`Aj*o~3^qJU-}HA`x04KLp=ZNm4mBS3a=dpEicS?)a4A-rUl2|bi=n-_LPtFZ zho7+3;4_^W!fE`q5ogR=)};|=ByRd_t^yhkI=HDpHQw!;7&(Jw-8_hm??u3gmBeAC z9c4SRI(4qTRLD^JH~h9Q+t0Y`cg4_LPGUoh_&;ZY5hwL@+P31NcqfX76(|iIcBQ2F_xy9>=;~UJ^=FDv;`@8&r{w(7FL$MP zI#b`H)ton<#A5RAb{-pR{{Ke*PupDF|C@xfTi*XacLe>v&CEhKsO7vbN$jKlc0bmJ z)a~W@V&x0reO?Wfyo_hLK~5u4!sRqR#c;Kov2 zSyh+@gvG~&X;^2b;q4iA7%A`XYx|gngBXUtt}^`hKhpnKHx>7P&^PM;-ueCy?yLV7 zlUUsUW32zl#}GmK0t3E%_ji|#HLfwv!2Z#rrl7O0^JbYoEKs$$%-n;T>@Xab2WJ>gAdo z>;a=&JMU;gTcZJ-(9r4IDf9bonew`M+mpY4LuViu_y!*BZB8_J_rNKP*?@hdC7zrl zBAN56!VoQTXq|Tx3T!K~pZG}YI$QUZX=T~ykXj__M!l1$VO;K9O6l*iNYi@f^6!x( z*M=jh*@S)wm->NnVmMfju9r!OEg{9{Z~8L2C#rsfHnkF}w8VL2z%FN{2Ea@ga(3sX z7VMLpc#n} z?S=%qwLu&~a70B#j5}h&qAY>#K<+fHxQ)x`$he}Tqcei+kgz1^xBxDI8;A;Z4Hy)G zfIzKjC>zzFV87JhjcN4)^@t7q|_OnBzXny7C_D{M?> zt4GJs9$l;MsOLyUly3-mU`g4UsvfsUvs&Q<^(T4Rtk&<06=p94R@Q8CjbA8Dzs6su z-30!c&F%z$<)GlB;V)~!5%`M*smrLS&@3hVbtkA4$6tN+G|gYK{T9z(yhWO{{gIP} z1Y-Ix^Vb4)NIZYNh9u%}XJZ_WmA}YOGc!wB2RKc07yZeE=Zp>!=EOMdF=mn3$a&zf z!qLKY;JK_;L4pREm4Cw}waE1>-*O8aOyoZ?=T#YT4l^)!JTe1{Y*xQHV+^OXeE;f}bfYokL zS~s`4#=c2b_OpHw`B|%0eg_3IZ+Gzt{>bDE^&L{dAK0Vys7-jT`Bsg=kKJGDw|K^t za99YsMs+1h;J9n`J^0#@hcbR`{{~E7nEBy#fmvcGXNjJiC9dTx@jH8#_$>=4zs@y^ zZ%3&$MzlOVPe83mi_Hhv(~9LsQd`ZF@m%v6{G=* z!b}0d#e{4sue)LJq>5+@ZiIA?7utU(tzCmk8PlFc5@lW&RAmqB)ucW4EIJQjLq)1qV%Pty8?C-vDji8P4vRP%QSXr?V zlt6zxM*1(f)=hs@c5L*|dMhFQG2C7BhrKVJ{{n&bWpg3(d8@b$Vgkk7^kP{Kyt6T%2cDZzJsV~E z;H$E$WCu<>H%olt`822yfpEeT&mV2s*TjkEm^@mF5y-zOP;b#NkiTokt~9p;2n#pMQ*(ZAT^KrO*KTpqx9s=>Mr zM(B6w>tLM$r(`^+E|2QH<+UJy6F2e{BXk4ykb`yYjj}P=!}dkqVm1O?@r0@Bib*&S zxgCP1R%OA5%Ujwf6DF%4P#i+}5df>g|Qw_M_7jkBYxd?W=Y_$X*q4RVPmlPr07Y>U< zS@Jsd27_*+A-!N*e1V=0zzbW^!+{)`_ba_w-B#T)9wLHp@YjMl&Io;qF6smN^|w0* z@uq9l-yjC9nKA)+&YyIYrIqzP_pS?C4{%J6SRZ{c-j`)5z*a_OO;hi;)&6N zFq^nt;A6oQ`@Paa4TfdcI#r7Jl6GX!uDNhV08Z^V3q&T-M5*q