From cc18c82622632bd2bd715ef4aa3cada2a56570ce Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 8 Dec 2023 12:55:58 +1100 Subject: [PATCH 0001/1335] AP_Follow: correct defaulting of AP_FOLLOW_ENABLED and clarify a closing endif --- libraries/AP_Follow/AP_Follow.cpp | 2 +- libraries/AP_Follow/AP_Follow_config.h | 2 ++ 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Follow/AP_Follow.cpp b/libraries/AP_Follow/AP_Follow.cpp index bb7dedc03aae7b..274ddf4d935c22 100644 --- a/libraries/AP_Follow/AP_Follow.cpp +++ b/libraries/AP_Follow/AP_Follow.cpp @@ -539,4 +539,4 @@ AP_Follow &follow() } -#endif +#endif // AP_FOLLOW_ENABLED diff --git a/libraries/AP_Follow/AP_Follow_config.h b/libraries/AP_Follow/AP_Follow_config.h index f5aa2dae54d465..2621dd698fc99e 100644 --- a/libraries/AP_Follow/AP_Follow_config.h +++ b/libraries/AP_Follow/AP_Follow_config.h @@ -1,5 +1,7 @@ #pragma once +#include + #ifndef AP_FOLLOW_ENABLED #define AP_FOLLOW_ENABLED 1 #endif From d1ad9ccfbb1f6988539f8c188401aeebd1305760 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 8 Dec 2023 12:59:25 +1100 Subject: [PATCH 0002/1335] AR_WPNav: correct missing include --- libraries/AR_WPNav/AR_WPNav.cpp | 1 + libraries/AR_WPNav/AR_WPNav_OA.cpp | 1 + 2 files changed, 2 insertions(+) diff --git a/libraries/AR_WPNav/AR_WPNav.cpp b/libraries/AR_WPNav/AR_WPNav.cpp index 1ab6c817d86fb5..66b4041dce920f 100644 --- a/libraries/AR_WPNav/AR_WPNav.cpp +++ b/libraries/AR_WPNav/AR_WPNav.cpp @@ -18,6 +18,7 @@ #include #include "AR_WPNav.h" #include +#include #if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include diff --git a/libraries/AR_WPNav/AR_WPNav_OA.cpp b/libraries/AR_WPNav/AR_WPNav_OA.cpp index dc7c8f29be3af9..0ecdc22c95ffe3 100644 --- a/libraries/AR_WPNav/AR_WPNav_OA.cpp +++ b/libraries/AR_WPNav/AR_WPNav_OA.cpp @@ -18,6 +18,7 @@ #include #include "AR_WPNav_OA.h" #include +#include extern const AP_HAL::HAL& hal; From e4a27943f5b692ad331c09840960f0c408169599 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 9 Dec 2023 09:46:44 +1100 Subject: [PATCH 0003/1335] AP_RTC: fixed ms value from AP_RTC::get_date_and_time_utc this impacts the ViewPro mount driver --- libraries/AP_RTC/AP_RTC.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_RTC/AP_RTC.cpp b/libraries/AP_RTC/AP_RTC.cpp index d695e57420ad99..41d9f5b2944706 100644 --- a/libraries/AP_RTC/AP_RTC.cpp +++ b/libraries/AP_RTC/AP_RTC.cpp @@ -229,7 +229,7 @@ bool AP_RTC::get_date_and_time_utc(uint16_t& year, uint8_t& month, uint8_t& day, hour = tm->tm_hour; /* Hours. [0-23] */ min = tm->tm_min; /* Minutes. [0-59] */ sec = tm->tm_sec; /* Seconds. [0-60] (1 leap second) */ - ms = time_us / 1000U; /* milliseconds [0-999] */ + ms = (time_us / 1000U) % 1000U; /* milliseconds [0-999] */ return true; } From 273e0795d05bfe2edbdb9bae9f1c4a062d191eb1 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Sun, 10 Dec 2023 12:32:27 +1100 Subject: [PATCH 0004/1335] Tools: ignore the error from brew update --- Tools/environment_install/install-prereqs-mac.sh | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Tools/environment_install/install-prereqs-mac.sh b/Tools/environment_install/install-prereqs-mac.sh index cba654a6de3d7e..69f647c1b23c24 100755 --- a/Tools/environment_install/install-prereqs-mac.sh +++ b/Tools/environment_install/install-prereqs-mac.sh @@ -103,7 +103,8 @@ function maybe_prompt_user() { # see https://github.com/orgs/Homebrew/discussions/3895 find /usr/local/bin -lname '*/Library/Frameworks/Python.framework/*' -delete -brew update +# brew update randomly failing on CI, so ignore errors: +brew update || true brew install gawk curl coreutils wget PIP=pip From 4cb0a922b2f6819b7ee89fa6fd5196d50a35af5c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 6 Dec 2023 13:01:36 +1100 Subject: [PATCH 0005/1335] AP_Airspeed: correct spelling of configured --- libraries/AP_Airspeed/AP_Airspeed_Backend.cpp | 2 +- libraries/AP_Airspeed/AP_Airspeed_Backend.h | 2 +- libraries/AP_Airspeed/AP_Airspeed_MS4525.cpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Airspeed/AP_Airspeed_Backend.cpp b/libraries/AP_Airspeed/AP_Airspeed_Backend.cpp index 412b337eeb65c6..fc36421419b867 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_Backend.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_Backend.cpp @@ -58,7 +58,7 @@ uint8_t AP_Airspeed_Backend::get_bus(void) const return frontend.param[instance].bus; } -bool AP_Airspeed_Backend::bus_is_confgured(void) const +bool AP_Airspeed_Backend::bus_is_configured(void) const { return frontend.param[instance].bus.configured(); } diff --git a/libraries/AP_Airspeed/AP_Airspeed_Backend.h b/libraries/AP_Airspeed/AP_Airspeed_Backend.h index 2deeb427c09c34..58ca025883a7aa 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_Backend.h +++ b/libraries/AP_Airspeed/AP_Airspeed_Backend.h @@ -59,7 +59,7 @@ class AP_Airspeed_Backend { int8_t get_pin(void) const; float get_psi_range(void) const; uint8_t get_bus(void) const; - bool bus_is_confgured(void) const; + bool bus_is_configured(void) const; uint8_t get_instance(void) const { return instance; } diff --git a/libraries/AP_Airspeed/AP_Airspeed_MS4525.cpp b/libraries/AP_Airspeed/AP_Airspeed_MS4525.cpp index d6e4c456a32e61..ec91bf8b4b309c 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_MS4525.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_MS4525.cpp @@ -62,7 +62,7 @@ bool AP_Airspeed_MS4525::probe(uint8_t bus, uint8_t address) bool AP_Airspeed_MS4525::init() { static const uint8_t addresses[] = { MS4525D0_I2C_ADDR1, MS4525D0_I2C_ADDR2, MS4525D0_I2C_ADDR3 }; - if (bus_is_confgured()) { + if (bus_is_configured()) { // the user has configured a specific bus for (uint8_t addr : addresses) { if (probe(get_bus(), addr)) { From b49152bbe6724a6eec4d42716f56c85aa0b7d242 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 3 Dec 2023 16:43:00 +1100 Subject: [PATCH 0006/1335] AP_HAL: mark new accept() socket as connected --- libraries/AP_HAL/utility/Socket.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL/utility/Socket.cpp b/libraries/AP_HAL/utility/Socket.cpp index a5beacca66d054..1bc4503b2da45e 100644 --- a/libraries/AP_HAL/utility/Socket.cpp +++ b/libraries/AP_HAL/utility/Socket.cpp @@ -391,7 +391,11 @@ SocketAPM *SocketAPM::accept(uint32_t timeout_ms) if (newfd == -1) { return nullptr; } - return new SocketAPM(false, newfd); + auto *ret = new SocketAPM(false, newfd); + if (ret) { + ret->connected = true; + } + return ret; } /* From 98e8b9785c0cefc5761c470cbc1a6c728cb83678 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 4 Dec 2023 10:11:48 +1100 Subject: [PATCH 0007/1335] AP_HAL: added close() to SocketAPM --- libraries/AP_HAL/utility/Socket.cpp | 67 +++++++++++++++++++++++------ libraries/AP_HAL/utility/Socket.h | 3 ++ 2 files changed, 57 insertions(+), 13 deletions(-) diff --git a/libraries/AP_HAL/utility/Socket.cpp b/libraries/AP_HAL/utility/Socket.cpp index 1bc4503b2da45e..eef8c53ad558fa 100644 --- a/libraries/AP_HAL/utility/Socket.cpp +++ b/libraries/AP_HAL/utility/Socket.cpp @@ -52,14 +52,7 @@ SocketAPM::SocketAPM(bool _datagram, int _fd) : SocketAPM::~SocketAPM() { - if (fd != -1) { - CALL_PREFIX(close)(fd); - fd = -1; - } - if (fd_in != -1) { - CALL_PREFIX(close)(fd_in); - fd_in = -1; - } + close(); } void SocketAPM::make_sockaddr(const char *address, uint16_t port, struct sockaddr_in &sockaddr) @@ -79,6 +72,9 @@ void SocketAPM::make_sockaddr(const char *address, uint16_t port, struct sockadd */ bool SocketAPM::connect(const char *address, uint16_t port) { + if (fd == -1) { + return false; + } struct sockaddr_in sockaddr; int ret; int one = 1; @@ -163,6 +159,9 @@ bool SocketAPM::connect(const char *address, uint16_t port) */ bool SocketAPM::connect_timeout(const char *address, uint16_t port, uint32_t timeout_ms) { + if (fd == -1) { + return false; + } struct sockaddr_in sockaddr; make_sockaddr(address, port, sockaddr); @@ -194,12 +193,16 @@ bool SocketAPM::connect_timeout(const char *address, uint16_t port, uint32_t tim */ bool SocketAPM::bind(const char *address, uint16_t port) { + if (fd == -1) { + return false; + } struct sockaddr_in sockaddr; make_sockaddr(address, port, sockaddr); if (CALL_PREFIX(bind)(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)) != 0) { return false; } + reuseaddress(); return true; } @@ -209,6 +212,9 @@ bool SocketAPM::bind(const char *address, uint16_t port) */ bool SocketAPM::reuseaddress(void) const { + if (fd == -1) { + return false; + } int one = 1; return (CALL_PREFIX(setsockopt)(fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)) != -1); } @@ -218,6 +224,9 @@ bool SocketAPM::reuseaddress(void) const */ bool SocketAPM::set_blocking(bool blocking) const { + if (fd == -1) { + return false; + } int fcntl_ret; if (blocking) { fcntl_ret = CALL_PREFIX(fcntl)(fd, F_SETFL, CALL_PREFIX(fcntl)(fd, F_GETFL, 0) & ~O_NONBLOCK); @@ -238,6 +247,9 @@ bool SocketAPM::set_blocking(bool blocking) const */ bool SocketAPM::set_cloexec() const { + if (fd == -1) { + return false; + } #ifdef FD_CLOEXEC return (CALL_PREFIX(fcntl)(fd, F_SETFD, FD_CLOEXEC) != -1); #else @@ -250,6 +262,9 @@ bool SocketAPM::set_cloexec() const */ ssize_t SocketAPM::send(const void *buf, size_t size) const { + if (fd == -1) { + return -1; + } return CALL_PREFIX(send)(fd, buf, size, 0); } @@ -258,6 +273,9 @@ ssize_t SocketAPM::send(const void *buf, size_t size) const */ ssize_t SocketAPM::sendto(const void *buf, size_t size, const char *address, uint16_t port) { + if (fd == -1) { + return -1; + } struct sockaddr_in sockaddr; make_sockaddr(address, port, sockaddr); return CALL_PREFIX(sendto)(fd, buf, size, 0, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); @@ -322,6 +340,9 @@ const char *SocketAPM::last_recv_address(char *ip_addr_buf, uint8_t buflen, uint void SocketAPM::set_broadcast(void) const { + if (fd == -1) { + return; + } int one = 1; CALL_PREFIX(setsockopt)(fd,SOL_SOCKET,SO_BROADCAST,(char *)&one,sizeof(one)); } @@ -336,6 +357,9 @@ bool SocketAPM::pollin(uint32_t timeout_ms) FD_ZERO(&fds); int fin = get_read_fd(); + if (fin == -1) { + return false; + } FD_SET(fin, &fds); tv.tv_sec = timeout_ms / 1000; @@ -353,6 +377,9 @@ bool SocketAPM::pollin(uint32_t timeout_ms) */ bool SocketAPM::pollout(uint32_t timeout_ms) { + if (fd == -1) { + return false; + } fd_set fds; struct timeval tv; @@ -373,6 +400,9 @@ bool SocketAPM::pollout(uint32_t timeout_ms) */ bool SocketAPM::listen(uint16_t backlog) const { + if (fd == -1) { + return false; + } return CALL_PREFIX(listen)(fd, (int)backlog) == 0; } @@ -382,6 +412,9 @@ bool SocketAPM::listen(uint16_t backlog) const */ SocketAPM *SocketAPM::accept(uint32_t timeout_ms) { + if (fd == -1) { + return nullptr; + } if (!pollin(timeout_ms)) { return nullptr; } @@ -391,11 +424,7 @@ SocketAPM *SocketAPM::accept(uint32_t timeout_ms) if (newfd == -1) { return nullptr; } - auto *ret = new SocketAPM(false, newfd); - if (ret) { - ret->connected = true; - } - return ret; + return new SocketAPM(false, newfd); } /* @@ -409,4 +438,16 @@ bool SocketAPM::is_multicast_address(struct sockaddr_in &addr) const return haddr >= mc_lower && haddr <= mc_upper; } +void SocketAPM::close(void) +{ + if (fd != -1) { + CALL_PREFIX(close)(fd); + fd = -1; + } + if (fd_in != -1) { + CALL_PREFIX(close)(fd_in); + fd_in = -1; + } +} + #endif // AP_NETWORKING_BACKEND_ANY diff --git a/libraries/AP_HAL/utility/Socket.h b/libraries/AP_HAL/utility/Socket.h index 70e4a1cdea1584..0ebc128d72caaa 100644 --- a/libraries/AP_HAL/utility/Socket.h +++ b/libraries/AP_HAL/utility/Socket.h @@ -69,6 +69,9 @@ class SocketAPM { // start listening for new tcp connections bool listen(uint16_t backlog) const; + // close socket + void close(void); + // accept a new connection. Only valid for TCP connections after // listen has been used. A new socket is returned SocketAPM *accept(uint32_t timeout_ms); From 64d649fbccf5fcf14356c5cfaee4491fc983f245 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 4 Dec 2023 14:37:54 +1100 Subject: [PATCH 0008/1335] AP_HAL: fixed SO_REUSEADDR on bind and use MSG_NOSIGNAL to prevent pipe errors in SITL --- libraries/AP_HAL/utility/Socket.cpp | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL/utility/Socket.cpp b/libraries/AP_HAL/utility/Socket.cpp index eef8c53ad558fa..9b9698eb797638 100644 --- a/libraries/AP_HAL/utility/Socket.cpp +++ b/libraries/AP_HAL/utility/Socket.cpp @@ -199,10 +199,10 @@ bool SocketAPM::bind(const char *address, uint16_t port) struct sockaddr_in sockaddr; make_sockaddr(address, port, sockaddr); + reuseaddress(); if (CALL_PREFIX(bind)(fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)) != 0) { return false; } - reuseaddress(); return true; } @@ -265,7 +265,7 @@ ssize_t SocketAPM::send(const void *buf, size_t size) const if (fd == -1) { return -1; } - return CALL_PREFIX(send)(fd, buf, size, 0); + return CALL_PREFIX(send)(fd, buf, size, MSG_NOSIGNAL); } /* @@ -424,7 +424,12 @@ SocketAPM *SocketAPM::accept(uint32_t timeout_ms) if (newfd == -1) { return nullptr; } - return new SocketAPM(false, newfd); + auto *ret = new SocketAPM(false, newfd); + if (ret != nullptr) { + ret->connected = true; + ret->reuseaddress(); + } + return ret; } /* From a77331e725ebe396d73181cc3b83d7f2db1aae76 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 5 Dec 2023 13:51:03 +1100 Subject: [PATCH 0009/1335] AP_HAL: mark socket as not connected on EOF this allows lua scripts to properly detect a closed TCP connection --- libraries/AP_HAL/utility/Socket.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_HAL/utility/Socket.cpp b/libraries/AP_HAL/utility/Socket.cpp index 9b9698eb797638..faab14d3d20341 100644 --- a/libraries/AP_HAL/utility/Socket.cpp +++ b/libraries/AP_HAL/utility/Socket.cpp @@ -295,6 +295,10 @@ ssize_t SocketAPM::recv(void *buf, size_t size, uint32_t timeout_ms) ssize_t ret; ret = CALL_PREFIX(recvfrom)(fin, buf, size, MSG_DONTWAIT, (sockaddr *)&in_addr, &len); if (ret <= 0) { + if (!datagram && connected && ret == 0) { + // remote host has closed connection + connected = false; + } return ret; } if (fd_in != -1) { From 0f0aed66b794f09b8025c1c658bdd8a6fd96f11f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 4 Dec 2023 14:38:37 +1100 Subject: [PATCH 0010/1335] AP_Filesystem: fixed fseek and open of directories --- libraries/AP_Filesystem/AP_Filesystem_posix.cpp | 6 ++++++ libraries/AP_Filesystem/posix_compat.cpp | 3 ++- 2 files changed, 8 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Filesystem/AP_Filesystem_posix.cpp b/libraries/AP_Filesystem/AP_Filesystem_posix.cpp index 039e0685df98a4..5a6169053472da 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_posix.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem_posix.cpp @@ -58,6 +58,12 @@ int AP_Filesystem_Posix::open(const char *fname, int flags, bool allow_absolute_ if (! allow_absolute_paths) { fname = map_filename(fname); } + struct stat st; + if (::stat(fname, &st) == 0 && + ((st.st_mode & S_IFMT) != S_IFREG && (st.st_mode & S_IFMT) != S_IFLNK)) { + // only allow links and files + return -1; + } // we automatically add O_CLOEXEC as we always want it for ArduPilot FS usage return ::open(fname, flags | O_CLOEXEC, 0644); } diff --git a/libraries/AP_Filesystem/posix_compat.cpp b/libraries/AP_Filesystem/posix_compat.cpp index 3ec501ef393bc6..f12f146012d5bb 100644 --- a/libraries/AP_Filesystem/posix_compat.cpp +++ b/libraries/AP_Filesystem/posix_compat.cpp @@ -170,7 +170,8 @@ int apfs_fseek(APFS_FILE *stream, long offset, int whence) { CHECK_STREAM(stream, EOF); stream->eof = false; - return AP::FS().lseek(stream->fd, offset, whence); + AP::FS().lseek(stream->fd, offset, whence); + return 0; } int apfs_ferror(APFS_FILE *stream) From 11ea2cf5c1f5a28ef1899a3cf3914b8ddc29016b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 4 Dec 2023 17:18:47 +1100 Subject: [PATCH 0011/1335] AP_Filesystem: added option @SYS/flash.bin useful for speed tests --- libraries/AP_Filesystem/AP_Filesystem_Sys.cpp | 10 ++++++++++ libraries/AP_Filesystem/AP_Filesystem_config.h | 3 +++ 2 files changed, 13 insertions(+) diff --git a/libraries/AP_Filesystem/AP_Filesystem_Sys.cpp b/libraries/AP_Filesystem/AP_Filesystem_Sys.cpp index 31d5265f358f3f..9eadd7f607b407 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_Sys.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem_Sys.cpp @@ -52,6 +52,9 @@ static const SysFileList sysfs_file_list[] = { #endif {"crash_dump.bin"}, {"storage.bin"}, +#if AP_FILESYSTEM_SYS_FLASH_ENABLED + {"flash.bin"}, +#endif }; int8_t AP_Filesystem_Sys::file_in_sysfs(const char *fname) { @@ -152,6 +155,13 @@ int AP_Filesystem_Sys::open(const char *fname, int flags, bool allow_absolute_pa r.str->set_buffer((char*)ptr, size, size); } } +#if AP_FILESYSTEM_SYS_FLASH_ENABLED + if (strcmp(fname, "flash.bin") == 0) { + void *ptr = (void*)0x08000000; + const size_t size = BOARD_FLASH_SIZE*1024; + r.str->set_buffer((char*)ptr, size, size); + } +#endif if (r.str->get_length() == 0) { errno = r.str->has_failed_allocation()?ENOMEM:ENOENT; diff --git a/libraries/AP_Filesystem/AP_Filesystem_config.h b/libraries/AP_Filesystem/AP_Filesystem_config.h index 75f3aa001c224b..63cf31f2084f69 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_config.h +++ b/libraries/AP_Filesystem/AP_Filesystem_config.h @@ -50,3 +50,6 @@ #define AP_FILESYSTEM_FILE_READING_ENABLED (AP_FILESYSTEM_FILE_WRITING_ENABLED || AP_FILESYSTEM_ROMFS_ENABLED) #endif +#ifndef AP_FILESYSTEM_SYS_FLASH_ENABLED +#define AP_FILESYSTEM_SYS_FLASH_ENABLED CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +#endif From 436c60c7de0c22092bfe348f3152f541082d3d0d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 6 Dec 2023 07:26:24 +1100 Subject: [PATCH 0012/1335] HAL_ChibiOS: defaults to 50 socket limit makes for more useful web server --- libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h b/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h index 7002236e2eda90..5351ff63933e0f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h @@ -57,8 +57,8 @@ #define LWIP_STATS_DISPLAY 1 #define ETHARP_STATS 1 #define LWIP_IGMP 1 -#define MEMP_NUM_NETCONN 10 // up to 10 sockets -#define MEMP_NUM_TCP_PCB 10 +#define MEMP_NUM_NETCONN 50 // up to 50 sockets +#define MEMP_NUM_TCP_PCB 50 #define MEM_LIBC_MALLOC 1 #define MEMP_MEM_MALLOC 1 #define SO_REUSE 1 From 9065baa329ff7071d0054ec0cd1b1bb2858b5cba Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 3 Dec 2023 16:43:29 +1100 Subject: [PATCH 0013/1335] AP_Scripting: added bindings for SocketAPM --- libraries/AP_Scripting/AP_Scripting.cpp | 15 ++ libraries/AP_Scripting/AP_Scripting.h | 14 ++ libraries/AP_Scripting/docs/docs.lua | 45 ++++++ libraries/AP_Scripting/examples/net_test.lua | 140 ++++++++++++++++++ .../generator/description/bindings.desc | 13 ++ libraries/AP_Scripting/lua_bindings.cpp | 120 +++++++++++++++ libraries/AP_Scripting/lua_bindings.h | 4 + 7 files changed, 351 insertions(+) create mode 100644 libraries/AP_Scripting/examples/net_test.lua diff --git a/libraries/AP_Scripting/AP_Scripting.cpp b/libraries/AP_Scripting/AP_Scripting.cpp index 347a7d440fd2d2..82c6f220cbf789 100644 --- a/libraries/AP_Scripting/AP_Scripting.cpp +++ b/libraries/AP_Scripting/AP_Scripting.cpp @@ -53,6 +53,10 @@ static_assert(SCRIPTING_STACK_SIZE <= SCRIPTING_STACK_MAX_SIZE, "Scripting requi #define SCRIPTING_ENABLE_DEFAULT 0 #endif +#if AP_NETWORKING_ENABLED +#include +#endif + extern const AP_HAL::HAL& hal; const AP_Param::GroupInfo AP_Scripting::var_info[] = { @@ -287,6 +291,17 @@ void AP_Scripting::thread(void) { } num_pwm_source = 0; +#if AP_NETWORKING_ENABLED + // clear allocated sockets + for (uint8_t i=0; i #include #include "AP_Scripting_CANSensor.h" +#include #ifndef SCRIPTING_MAX_NUM_I2C_DEVICE #define SCRIPTING_MAX_NUM_I2C_DEVICE 4 @@ -31,6 +32,13 @@ #define SCRIPTING_MAX_NUM_PWM_SOURCE 4 +#if AP_NETWORKING_ENABLED +#ifndef SCRIPTING_MAX_NUM_NET_SOCKET +#define SCRIPTING_MAX_NUM_NET_SOCKET 50 +#endif +class SocketAPM; +#endif + class AP_Scripting { public: @@ -111,6 +119,12 @@ class AP_Scripting int get_current_ref() { return current_ref; } void set_current_ref(int ref) { current_ref = ref; } +#if AP_NETWORKING_ENABLED + // SocketAPM storage + uint8_t num_net_sockets; + SocketAPM *_net_sockets[SCRIPTING_MAX_NUM_NET_SOCKET]; +#endif + struct mavlink_msg { mavlink_message_t msg; mavlink_channel_t chan; diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index 40ddb7ac9c35fa..4f70ca60671fc2 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -452,6 +452,51 @@ function motor_factor_table_ud:roll(index) end ---@param value number function motor_factor_table_ud:roll(index, value) end +-- network socket class +---@class SocketAPM_ud +local SocketAPM_ud = {} + +-- desc +---@return boolean +function SocketAPM_ud:is_connected() end + +-- desc +---@param param1 boolean +---@return boolean +function SocketAPM_ud:set_blocking(param1) end + +-- desc +---@param param1 integer +---@return boolean +function SocketAPM_ud:listen(param1) end + +-- desc +---@param param1 string +---@param param2 uint32_t_ud +---@return integer +function SocketAPM_ud:send(param1, param2) end + +-- desc +---@param param1 string +---@param param2 integer +---@return boolean +function SocketAPM_ud:bind(param1, param2) end + +-- desc +---@param param1 string +---@param param2 integer +---@return boolean +function SocketAPM_ud:connect(param1, param2) end + +-- desc +function SocketAPM_ud:__gc() end + +-- desc +function SocketAPM_ud:accept(param1) end + +-- desc +function SocketAPM_ud:recv(param1) end + -- desc ---@class AP_HAL__PWMSource_ud diff --git a/libraries/AP_Scripting/examples/net_test.lua b/libraries/AP_Scripting/examples/net_test.lua new file mode 100644 index 00000000000000..e40f4d59aa9d0b --- /dev/null +++ b/libraries/AP_Scripting/examples/net_test.lua @@ -0,0 +1,140 @@ +--[[ + example script to test lua socket API +--]] + +local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} + +PARAM_TABLE_KEY = 46 +PARAM_TABLE_PREFIX = "NT_" + +-- bind a parameter to a variable given +function bind_param(name) + local p = Parameter() + assert(p:init(name), string.format('could not find %s parameter', name)) + return p +end + +-- add a parameter and bind it to a variable +function bind_add_param(name, idx, default_value) + assert(param:add_param(PARAM_TABLE_KEY, idx, name, default_value), string.format('could not add param %s', name)) + return bind_param(PARAM_TABLE_PREFIX .. name) +end + +-- Setup Parameters +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 6), 'net_test: could not add param table') + +--[[ + // @Param: NT_ENABLE + // @DisplayName: enable network tests + // @Description: Enable network tests + // @Values: 0:Disabled,1:Enabled + // @User: Standard +--]] +local NT_ENABLE = bind_add_param('ENABLE', 1, 0) +if NT_ENABLE:get() == 0 then + return +end + +local NT_TEST_IP = { bind_add_param('TEST_IP0', 2, 192), + bind_add_param('TEST_IP1', 3, 168), + bind_add_param('TEST_IP2', 4, 13), + bind_add_param('TEST_IP3', 5, 15) } + +local NT_BIND_PORT = bind_add_param('BIND_PORT', 6, 15001) + +local PORT_ECHO = 7 + +gcs:send_text(MAV_SEVERITY.INFO, "net_test: starting") + +local function test_ip() + return string.format("%u.%u.%u.%u", NT_TEST_IP[1]:get(), NT_TEST_IP[2]:get(), NT_TEST_IP[3]:get(), NT_TEST_IP[4]:get()) +end + +local counter = 0 +local sock_tcp_echo = SocketAPM(0) +local sock_udp_echo = SocketAPM(1) +local sock_tcp_in = SocketAPM(0) +local sock_tcp_in2 = nil +local sock_udp_in = SocketAPM(1) + +if not sock_tcp_echo then + gcs:send_text(MAV_SEVERITY.ERROR, "net_test: failed to create tcp echo socket") + return +end + +if not sock_udp_echo then + gcs:send_text(MAV_SEVERITY.ERROR, "net_test: failed to create udp echo socket") + return +end + +if not sock_tcp_in:bind("0.0.0.0", NT_BIND_PORT:get()) then + gcs:send_text(MAV_SEVERITY.ERROR, "net_test: failed to bind to TCP 5001") +end + +if not sock_tcp_in:listen(1) then + gcs:send_text(MAV_SEVERITY.ERROR, "net_test: failed to listen") +end + +if not sock_udp_in:bind("0.0.0.0", NT_BIND_PORT:get()) then + gcs:send_text(MAV_SEVERITY.ERROR, "net_test: failed to bind to UDP 5001") +end + +--[[ + test TCP or UDP echo +--]] +local function test_echo(name, sock) + if not sock:is_connected() then + if not sock:connect(test_ip(), PORT_ECHO) then + gcs:send_text(MAV_SEVERITY.ERROR, string.format("test_echo(%s): failed to connect", name)) + return + end + + if not sock:set_blocking(true) then + gcs:send_text(MAV_SEVERITY.ERROR, string.format("test_echo(%s): failed to set blocking", name)) + return + end + end + + local s = string.format("testing %u", counter) + local nsent = sock:send(s, #s) + if nsent ~= #s then + gcs:send_text(MAV_SEVERITY.ERROR, string.format("test_echo(%s): failed to send", name)) + return + end + local r = sock:recv(#s) + if r then + gcs:send_text(MAV_SEVERITY.ERROR, string.format("test_echo(%s): got reply '%s'", name, r)) + end +end + +--[[ + test a simple server +--]] +local function test_server(name, sock) + if name == "TCP" then + if not sock_tcp_in2 then + sock_tcp_in2 = sock:accept() + if not sock_tcp_in2 then + return + end + gcs:send_text(MAV_SEVERITY.ERROR, string.format("test_server(%s): new connection", name)) + end + sock = sock_tcp_in2 + end + + local r = sock:recv(1024) + if r and #r > 0 then + gcs:send_text(MAV_SEVERITY.ERROR, string.format("test_server(%s): got input '%s'", name, r)) + end +end + +local function update() + test_echo("TCP", sock_tcp_echo) + test_echo("UDP", sock_udp_echo) + test_server("TCP", sock_tcp_in) + test_server("UDP", sock_udp_in) + counter = counter + 1 + return update,1000 +end + +return update,100 diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index a37476a5252d93..d2c25274b354a4 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -536,6 +536,19 @@ ap_object AP_HAL::I2CDevice method write_register boolean uint8_t'skip_check uin ap_object AP_HAL::I2CDevice manual read_registers AP_HAL__I2CDevice_read_registers 2 ap_object AP_HAL::I2CDevice method set_address void uint8_t'skip_check +include AP_HAL/utility/Socket.h depends (AP_NETWORKING_ENABLED==1) +global manual SocketAPM lua_get_SocketAPM 1 depends (AP_NETWORKING_ENABLED==1) + +ap_object SocketAPM depends (AP_NETWORKING_ENABLED==1) +ap_object SocketAPM method connect boolean string uint16_t'skip_check +ap_object SocketAPM method bind boolean string uint16_t'skip_check +ap_object SocketAPM method send int32_t string uint32_t'skip_check +ap_object SocketAPM method listen boolean uint8_t'skip_check +ap_object SocketAPM method set_blocking boolean boolean +ap_object SocketAPM method is_connected boolean +ap_object SocketAPM manual close SocketAPM_close 0 +ap_object SocketAPM manual recv SocketAPM_recv 1 +ap_object SocketAPM manual accept SocketAPM_accept 1 ap_object AP_HAL::AnalogSource depends !defined(HAL_DISABLE_ADC_DRIVER) ap_object AP_HAL::AnalogSource method set_pin boolean uint8_t'skip_check diff --git a/libraries/AP_Scripting/lua_bindings.cpp b/libraries/AP_Scripting/lua_bindings.cpp index 1ff491ed740785..a3d574e8ed2fe3 100644 --- a/libraries/AP_Scripting/lua_bindings.cpp +++ b/libraries/AP_Scripting/lua_bindings.cpp @@ -15,6 +15,11 @@ #include #include +#include +#if AP_NETWORKING_ENABLED +#include +#endif + extern const AP_HAL::HAL& hal; extern "C" { @@ -755,6 +760,121 @@ int lua_get_PWMSource(lua_State *L) { return 1; } +#if AP_NETWORKING_ENABLED +/* + allocate a SocketAPM + */ +int lua_get_SocketAPM(lua_State *L) { + binding_argcheck(L, 1); + const uint8_t datagram = get_uint8_t(L, 1); + auto *scripting = AP::scripting(); + + lua_gc(L, LUA_GCCOLLECT, 0); + + if (scripting->num_net_sockets >= SCRIPTING_MAX_NUM_NET_SOCKET) { + return luaL_argerror(L, 1, "no sockets available"); + } + + auto *sock = new SocketAPM(datagram); + if (sock == nullptr) { + return luaL_argerror(L, 1, "SocketAPM device nullptr"); + } + scripting->_net_sockets[scripting->num_net_sockets] = sock; + + new_SocketAPM(L); + *((SocketAPM**)luaL_checkudata(L, -1, "SocketAPM")) = scripting->_net_sockets[scripting->num_net_sockets]; + + scripting->num_net_sockets++; + + return 1; +} + +/* + socket close + */ +int SocketAPM_close(lua_State *L) { + binding_argcheck(L, 1); + + SocketAPM *ud = *check_SocketAPM(L, 1); + + auto *scripting = AP::scripting(); + + if (scripting->num_net_sockets == 0) { + return luaL_argerror(L, 1, "socket close error"); + } + + // clear allocated socket + for (uint8_t i=0; i_net_sockets[i] == ud) { + ud->close(); + delete ud; + scripting->_net_sockets[i] = nullptr; + scripting->num_net_sockets--; + break; + } + } + + return 0; +} + +/* + receive from a socket to a lua string + */ +int SocketAPM_recv(lua_State *L) { + binding_argcheck(L, 2); + + SocketAPM * ud = *check_SocketAPM(L, 1); + + const uint16_t count = get_uint16_t(L, 2); + uint8_t *data = (uint8_t*)malloc(count); + if (data == nullptr) { + return 0; + } + + const auto ret = ud->recv(data, count, 0); + if (ret < 0) { + free(data); + return 0; + } + + // push to lua string + lua_pushlstring(L, (const char *)data, ret); + free(data); + + return 1; +} + +/* + TCP socket accept() call + */ +int SocketAPM_accept(lua_State *L) { + binding_argcheck(L, 1); + + SocketAPM * ud = *check_SocketAPM(L, 1); + + auto *scripting = AP::scripting(); + if (scripting->num_net_sockets >= SCRIPTING_MAX_NUM_NET_SOCKET) { + return luaL_argerror(L, 1, "no sockets available"); + } + + auto *sock = ud->accept(0); + if (sock == nullptr) { + return 0; + } + + scripting->_net_sockets[scripting->num_net_sockets] = sock; + + new_SocketAPM(L); + *((SocketAPM**)luaL_checkudata(L, -1, "SocketAPM")) = scripting->_net_sockets[scripting->num_net_sockets]; + + scripting->num_net_sockets++; + + return 1; +} + +#endif // AP_NETWORKING_ENABLED + + int lua_get_current_ref() { auto *scripting = AP::scripting(); diff --git a/libraries/AP_Scripting/lua_bindings.h b/libraries/AP_Scripting/lua_bindings.h index 8eef08bca35ac9..797a551b205f46 100644 --- a/libraries/AP_Scripting/lua_bindings.h +++ b/libraries/AP_Scripting/lua_bindings.h @@ -14,6 +14,10 @@ int lua_dirlist(lua_State *L); int lua_removefile(lua_State *L); int SRV_Channels_get_safety_state(lua_State *L); int lua_get_PWMSource(lua_State *L); +int lua_get_SocketAPM(lua_State *L); +int SocketAPM_recv(lua_State *L); +int SocketAPM_accept(lua_State *L); +int SocketAPM_close(lua_State *L); int lua_mavlink_init(lua_State *L); int lua_mavlink_receive_chan(lua_State *L); int lua_mavlink_register_rx_msgid(lua_State *L); From 3446ff78d770ae7929ebdedc2565cb732bd7c7a8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 4 Dec 2023 17:19:15 +1100 Subject: [PATCH 0014/1335] AP_Scripting: added isdirectory() --- libraries/AP_Scripting/docs/docs.lua | 5 +++++ .../generator/description/bindings.desc | 1 + libraries/AP_Scripting/lua_bindings.cpp | 19 +++++++++++++++++++ libraries/AP_Scripting/lua_bindings.h | 1 + 4 files changed, 26 insertions(+) diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index 4f70ca60671fc2..b8f7c806b84feb 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -3062,6 +3062,11 @@ function scripting:restart_all() end ---@return table -- table of filenames function dirlist(directoryname) end +-- return true if path is a directory +---@param path string +---@return result +function isdirectory(path) end + --desc ---@param filename string function remove(filename) end diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index d2c25274b354a4..5d6bf1b39e17e0 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -812,6 +812,7 @@ userdata uint32_t manual tofloat uint32_t_tofloat 0 global manual dirlist lua_dirlist 1 global manual remove lua_removefile 1 +global manual isdirectory lua_isdirectory 1 global manual print lua_print 1 singleton mavlink depends HAL_GCS_ENABLED diff --git a/libraries/AP_Scripting/lua_bindings.cpp b/libraries/AP_Scripting/lua_bindings.cpp index a3d574e8ed2fe3..ac7b4b83349f8e 100644 --- a/libraries/AP_Scripting/lua_bindings.cpp +++ b/libraries/AP_Scripting/lua_bindings.cpp @@ -720,6 +720,25 @@ int lua_dirlist(lua_State *L) { return 1; /* table is already on top */ } +/* + return true if path is a directory + */ +int lua_isdirectory(lua_State *L) { + binding_argcheck(L, 1); + + const char *path = luaL_checkstring(L, 1); + + struct stat st; + if (AP::FS().stat(path, &st) != 0) { + lua_pushnil(L); /* return nil and ... */ + lua_pushstring(L, strerror(errno)); /* error message */ + return 2; + } + bool ret = (st.st_mode & S_IFMT) == S_IFDIR; + lua_pushboolean(L, ret); + return 1; +} + /* remove a file */ diff --git a/libraries/AP_Scripting/lua_bindings.h b/libraries/AP_Scripting/lua_bindings.h index 797a551b205f46..41adfd859659ea 100644 --- a/libraries/AP_Scripting/lua_bindings.h +++ b/libraries/AP_Scripting/lua_bindings.h @@ -12,6 +12,7 @@ int lua_get_CAN_device(lua_State *L); int lua_get_CAN_device2(lua_State *L); int lua_dirlist(lua_State *L); int lua_removefile(lua_State *L); +int lua_isdirectory(lua_State *L); int SRV_Channels_get_safety_state(lua_State *L); int lua_get_PWMSource(lua_State *L); int lua_get_SocketAPM(lua_State *L); From 1419042fc09457c2bc0b232324a6b729a7f85dfa Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 4 Dec 2023 10:12:07 +1100 Subject: [PATCH 0015/1335] AP_Scripting: added web server appliction --- .../AP_Scripting/applets/WebExamples/test.lua | 9 + .../applets/WebExamples/test.shtml | 16 + .../AP_Scripting/applets/net_webserver.lua | 694 ++++++++++++++++++ .../AP_Scripting/applets/net_webserver.md | 91 +++ libraries/AP_Scripting/examples/net_test.lua | 37 +- 5 files changed, 818 insertions(+), 29 deletions(-) create mode 100644 libraries/AP_Scripting/applets/WebExamples/test.lua create mode 100644 libraries/AP_Scripting/applets/WebExamples/test.shtml create mode 100644 libraries/AP_Scripting/applets/net_webserver.lua create mode 100644 libraries/AP_Scripting/applets/net_webserver.md diff --git a/libraries/AP_Scripting/applets/WebExamples/test.lua b/libraries/AP_Scripting/applets/WebExamples/test.lua new file mode 100644 index 00000000000000..97a5cc4a9e086c --- /dev/null +++ b/libraries/AP_Scripting/applets/WebExamples/test.lua @@ -0,0 +1,9 @@ +--[[ +example lua cgi file for cgi-bin/ folder +--]] +return [[ +test-from-cgi + +working!! +]] + diff --git a/libraries/AP_Scripting/applets/WebExamples/test.shtml b/libraries/AP_Scripting/applets/WebExamples/test.shtml new file mode 100644 index 00000000000000..96546a427fe521 --- /dev/null +++ b/libraries/AP_Scripting/applets/WebExamples/test.shtml @@ -0,0 +1,16 @@ + + + + + +

Server Side Scripting Test

+ + + + + + + +
RollPitchYaw
+ + diff --git a/libraries/AP_Scripting/applets/net_webserver.lua b/libraries/AP_Scripting/applets/net_webserver.lua new file mode 100644 index 00000000000000..fb0076717ca850 --- /dev/null +++ b/libraries/AP_Scripting/applets/net_webserver.lua @@ -0,0 +1,694 @@ +--[[ + example script to test lua socket API +--]] + +local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} + +PARAM_TABLE_KEY = 47 +PARAM_TABLE_PREFIX = "WEB_" + +-- add a parameter and bind it to a variable +function bind_add_param(name, idx, default_value) + assert(param:add_param(PARAM_TABLE_KEY, idx, name, default_value), string.format('could not add param %s', name)) + return Parameter(PARAM_TABLE_PREFIX .. name) +end + +-- Setup Parameters +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 6), 'net_test: could not add param table') + +--[[ + // @Param: WEB_ENABLE + // @DisplayName: enable web server + // @Description: enable web server + // @Values: 0:Disabled,1:Enabled + // @User: Standard +--]] +local WEB_ENABLE = bind_add_param('ENABLE', 1, 0) + +--[[ + // @Param: WEB_BIND_PORT + // @DisplayName: web server TCP port + // @Description: web server TCP port + // @Range: 1 65535 + // @User: Standard +--]] +local WEB_BIND_PORT = bind_add_param('BIND_PORT', 2, 8080) + +--[[ + // @Param: WEB_DEBUG + // @DisplayName: web server debugging + // @Description: web server debugging + // @Values: 0:Disabled,1:Enabled + // @User: Advanced +--]] +local WEB_DEBUG = bind_add_param('DEBUG', 3, 0) + +--[[ + // @Param: WEB_BLOCK_SIZE + // @DisplayName: web server block size + // @Description: web server block size for download + // @Range: 1 65535 + // @User: Advanced +--]] +local WEB_BLOCK_SIZE = bind_add_param('BLOCK_SIZE', 4, 10240) + +--[[ + // @Param: WEB_TIMEOUT + // @DisplayName: web server timeout + // @Description: timeout for inactive connections + // @Units: s + // @Range: 0.1 60 + // @User: Advanced +--]] +local WEB_TIMEOUT = bind_add_param('TIMEOUT', 5, 2.0) + +gcs:send_text(MAV_SEVERITY.INFO, string.format("WebServer: starting on port %u", WEB_BIND_PORT:get())) + +local counter = 0 +local sock_listen = SocketAPM(0) +local clients = {} + +local DOCTYPE = "" +local SERVER_VERSION = "net_webserver 1.0" +local CONTENT_TEXT_HTML = "text/html;charset=UTF-8" +local CONTENT_OCTET_STREAM = "application/octet-stream" + +local HIDDEN_FOLDERS = { "@SYS", "@ROMFS", "@MISSION", "@PARAM" } + +local CGI_BIN_PATH = "cgi-bin" + +local MIME_TYPES = { + ["apj"] = CONTENT_OCTET_STREAM, + ["dat"] = CONTENT_OCTET_STREAM, + ["o"] = CONTENT_OCTET_STREAM, + ["obj"] = CONTENT_OCTET_STREAM, + ["lua"] = "text/x-lua", + ["py"] = "text/x-python", + ["shtml"] = CONTENT_TEXT_HTML, + ["js"] = "text/javascript", + -- thanks to https://developer.mozilla.org/en-US/docs/Web/HTTP/Basics_of_HTTP/MIME_types/Common_types + ["aac"] = "audio/aac", + ["abw"] = "application/x-abiword", + ["arc"] = "application/x-freearc", + ["avif"] = "image/avif", + ["avi"] = "video/x-msvideo", + ["azw"] = "application/vnd.amazon.ebook", + ["bin"] = "application/octet-stream", + ["bmp"] = "image/bmp", + ["bz"] = "application/x-bzip", + ["bz2"] = "application/x-bzip2", + ["cda"] = "application/x-cdf", + ["csh"] = "application/x-csh", + ["css"] = "text/css", + ["csv"] = "text/csv", + ["doc"] = "application/msword", + ["docx"] = "application/vnd.openxmlformats-officedocument.wordprocessingml.document", + ["eot"] = "application/vnd.ms-fontobject", + ["epub"] = "application/epub+zip", + ["gz"] = "application/gzip", + ["gif"] = "image/gif", + ["htm"] = CONTENT_TEXT_HTML, + ["html"] = CONTENT_TEXT_HTML, + ["ico"] = "image/vnd.microsoft.icon", + ["ics"] = "text/calendar", + ["jar"] = "application/java-archive", + ["jpeg"] = "image/jpeg", + ["json"] = "application/json", + ["jsonld"] = "application/ld+json", + ["mid"] = "audio/x-midi", + ["mjs"] = "text/javascript", + ["mp3"] = "audio/mpeg", + ["mp4"] = "video/mp4", + ["mpeg"] = "video/mpeg", + ["mpkg"] = "application/vnd.apple.installer+xml", + ["odp"] = "application/vnd.oasis.opendocument.presentation", + ["ods"] = "application/vnd.oasis.opendocument.spreadsheet", + ["odt"] = "application/vnd.oasis.opendocument.text", + ["oga"] = "audio/ogg", + ["ogv"] = "video/ogg", + ["ogx"] = "application/ogg", + ["opus"] = "audio/opus", + ["otf"] = "font/otf", + ["png"] = "image/png", + ["pdf"] = "application/pdf", + ["php"] = "application/x-httpd-php", + ["ppt"] = "application/vnd.ms-powerpoint", + ["pptx"] = "application/vnd.openxmlformats-officedocument.presentationml.presentation", + ["rar"] = "application/vnd.rar", + ["rtf"] = "application/rtf", + ["sh"] = "application/x-sh", + ["svg"] = "image/svg+xml", + ["tar"] = "application/x-tar", + ["tif"] = "image/tiff", + ["tiff"] = "image/tiff", + ["ts"] = "video/mp2t", + ["ttf"] = "font/ttf", + ["txt"] = "text/plain", + ["vsd"] = "application/vnd.visio", + ["wav"] = "audio/wav", + ["weba"] = "audio/webm", + ["webm"] = "video/webm", + ["webp"] = "image/webp", + ["woff"] = "font/woff", + ["woff2"] = "font/woff2", + ["xhtml"] = "application/xhtml+xml", + ["xls"] = "application/vnd.ms-excel", + ["xlsx"] = "application/vnd.openxmlformats-officedocument.spreadsheetml.sheet", + ["xml"] = "default.", + ["xul"] = "application/vnd.mozilla.xul+xml", + ["zip"] = "application/zip", + ["3gp"] = "video", + ["3g2"] = "video", + ["7z"] = "application/x-7z-compressed", +} + + +if not sock_listen:bind("0.0.0.0", WEB_BIND_PORT:get()) then + gcs:send_text(MAV_SEVERITY.ERROR, string.format("WebServer: failed to bind to TCP %u", WEB_BIND_PORT:get())) + return +end + +if not sock_listen:listen(50) then + gcs:send_text(MAV_SEVERITY.ERROR, "WebServer: failed to listen") + return +end + +--[[ + split string by pattern +--]] +local function split(str, pattern) + local ret = {} + for s in string.gmatch(str, pattern) do + table.insert(ret, s) + end + return ret +end + +--[[ + return true if a string ends in the 2nd string +--]] +local function endswith(str, s) + local len1 = #str + local len2 = #s + return string.sub(str,1+len1-len2,len1) == s +end + +--[[ + return true if a string starts with the 2nd string +--]] +local function startswith(str, s) + local len1 = #str + local len2 = #s + return string.sub(str,1,len2) == s +end + +function DEBUG(txt) + if WEB_DEBUG:get() ~= 0 then + gcs:send_text(MAV_SEVERITY.DEBUG, txt) + end +end + +--[[ + return true if a table contains a given element +--]] +function contains(t,el) + for _,v in ipairs(t) do + if v == el then + return true + end + end + return false +end + +function is_hidden_dir(path) + return contains(HIDDEN_FOLDERS, path) +end + +function file_exists(path) + local f = io.open(path, "rb") + if f then + return true + end + return false +end + +--[[ + client class for open connections +--]] +local function Client(_sock, _idx) + local self = {} + + self.closed = false + + local sock = _sock + local idx = _idx + local have_header = false + local header = "" + local header_lines = {} + local header_vars = {} + local run = nil + local protocol = nil + local file = nil + local start_time = millis() + + function self.read_header() + local s = sock:recv(2048) + if not s then + local now = millis() + if not sock:is_connected() or now - start_time > WEB_TIMEOUT:get()*1000 then + -- EOF while looking for header + DEBUG("EOF") + self.remove() + return false + end + return false + end + if not s or #s == 0 then + return false + end + header = header .. s + local eoh = string.find(s, '\r\n\r\n') + if eoh then + DEBUG("got header") + have_header = true + header_lines = split(header, "[^\r\n]+") + -- blocking for reply + sock:set_blocking(true) + return true + end + return false + end + + function self.sendstring(s) + sock:send(s, #s) + end + + function self.sendline(s) + self.sendstring(s .. "\r\n") + end + + --[[ + send a string with variable substitution using {varname} + from http://lua-users.org/wiki/StringInterpolation + --]] + function self.sendstring_vars(s, vars) + s = (string.gsub(s, "({([^}]+)})", + function(whole,i) + return vars[i] or whole + end)) + self.sendstring(s) + end + + function self.send_header(code, codestr, vars) + self.sendline(string.format("%s %u %s", protocol, code, codestr)) + self.sendline(string.format("Server: %s", SERVER_VERSION)) + for k,v in pairs(vars) do + self.sendline(string.format("%s: %s", k, v)) + end + self.sendline("Connection: close") + self.sendline("") + end + + -- get size of a file + function self.file_size(fname) + DEBUG(string.format("size of '%s'", fname)) + local f = io.open(fname, "rb") + if not f then + return -1 + end + local ret = f:seek("end") + f:close() + DEBUG(string.format("size of '%s' -> %u", fname, ret)) + return ret + end + + + --[[ + return full path with .. resolution + --]] + function self.full_path(path, name) + DEBUG(string.format("full_path(%s,%s)", path, name)) + local ret = path + if path == "/" and startswith(name,"@") then + return name + end + if name == ".." then + if path == "/" then + return "/" + end + if endswith(path,"/") then + path = string.sub(path, 1, #path-1) + end + local dir, file = string.match(path, '(.*/)(.*)') + if not dir then + return path + end + return dir + end + if not endswith(ret, "/") then + ret = ret .. "/" + end + ret = ret .. name + DEBUG(string.format("full_path(%s,%s) -> %s", path, name, ret)) + return ret + end + + function self.directory_list(path) + if startswith(path, "/@") then + path = string.sub(path, 2, #path-1) + end + DEBUG(string.format("directory_list(%s)", path)) + local dlist = dirlist(path) + if not dlist then + dlist = {} + end + if not contains(dlist, "..") then + -- on ChibiOS we don't get .. + table.insert(dlist, "..") + end + if path == "/" then + for _,v in ipairs(HIDDEN_FOLDERS) do + table.insert(dlist, v) + end + end + + table.sort(dlist) + self.send_header(200, "OK", {["Content-Type"]=CONTENT_TEXT_HTML}) + self.sendline(DOCTYPE) + self.sendstring_vars([[ + + + Index of {path} + + +

Index of {path}

+ + +]], {path=path}) + for _,d in ipairs(dlist) do + local skip = d == "." + if path == "/" and d == ".." then + skip = true + end + if not skip then + local fullpath = self.full_path(path, d) + local name = d + local size = 0 + if is_hidden_dir(fullpath) or isdirectory(fullpath) then + name = name .. "/" + else + size = math.max(self.file_size(fullpath),0) + end + self.sendstring_vars([[ +]], { name=name, size=tostring(size) }) + end + end + self.sendstring([[ +
NameSize
{name}{size}
+ + +]]) + end + + -- send file content + function self.send_file() + local chunk = WEB_BLOCK_SIZE:get() + local b = file:read(chunk) + if b and #b > 0 then + sock:send(b, #b) + end + if not b or #b < chunk then + -- EOF + DEBUG("sent file") + run = nil + self.remove() + return + end + end + + --[[ + load whole file as a string + --]] + function self.load_file() + local chunk = WEB_BLOCK_SIZE:get() + local ret = "" + while true do + local b = file:read(chunk) + if not b or #b == 0 then + break + end + ret = ret .. b + end + return ret + end + + --[[ + evaluate some lua code and return as a string + --]] + function self.evaluate(code) + local eval_code = "function eval_func()\n" .. code .. "\nend\n" + local f, errloc, err = load(eval_code, "eval_func", "t", _ENV) + if not f then + DEBUG(string.format("load failed: err=%s", err)) + return nil + end + local success, err = pcall(f) + if not success then + DEBUG(string.format("pcall failed: err=%s", err)) + return nil + end + local ok, s2 = pcall(eval_func) + eval_func = nil + if ok then + return s2 + end + return nil + end + + --[[ + process a file as a lua CGI + --]] + function self.send_cgi() + local contents = self.load_file() + local s = self.evaluate(contents) + if s then + self.sendstring(s) + end + self.remove() + end + + --[[ + send file content with server side processsing + files ending in .shtml can have embedded lua lika this: + + + + Using 'lstr' a return tostring(yourcode) is added to the code + automatically + --]] + function self.send_processed_file() + local contents = self.load_file() + while #contents > 0 do + local pat1 = "(.-)[<][?]lua[ \n](.-)[?][>](.*)" + local pat2 = "(.-)[<][?]lstr[ \n](.-)[?][>](.*)" + local p1, p2, p3 = string.match(contents, pat1) + if not p1 then + p1, p2, p3 = string.match(contents, pat2) + if not p1 then + break + end + p2 = "return tostring(" .. p2 .. ")" + end + self.sendstring(p1) + local s2 = self.evaluate(p2) + if s2 then + self.sendstring(s2) + end + contents = p3 + end + self.sendstring(contents) + self.remove() + end + + -- return a content type + function self.content_type(path) + local file, ext = string.match(path, '(.*[.])(.*)') + ext = string.lower(ext) + local ret = MIME_TYPES[ext] + if not ret then + return CONTENT_OCTET_STREAM + end + return ret + end + + -- perform a file download + function self.file_download(path) + if startswith(path, "/@") then + path = string.sub(path, 2, #path) + end + DEBUG(string.format("file_download(%s)", path)) + file = io.open(path,"rb") + if not file then + DEBUG(string.format("Failed to open '%s'", path)) + return false + end + local vars = {["Content-Type"]=self.content_type(path)} + local cgi_processing = startswith(path, "/cgi-bin/") and endswith(path, ".lua") + local server_side_processing = endswith(path, ".shtml") + if not startswith(path, "@") and not server_side_processing and not cgi_processing then + local fsize = self.file_size(path) + vars["Content-Length"]= tostring(fsize) + end + self.send_header(200, "OK", vars) + if server_side_processing then + DEBUG(string.format("shtml processing %s", path)) + run = self.send_processed_file + elseif cgi_processing then + DEBUG(string.format("CGI processing %s", path)) + run = self.send_cgi + else + run = self.send_file + end + return true + end + + function self.not_found() + self.send_header(404, "Not found", {}) + end + + function self.moved_permanently(relpath) + if not startswith(relpath, "/") then + relpath = "/" .. relpath + end + local location = string.format("http://%s%s", header_vars['Host'], relpath) + DEBUG(string.format("Redirect -> %s", location)) + self.send_header(301, "Moved Permanently", {["Location"]=location}) + end + + -- process a single request + function self.process_request() + local h1 = header_lines[1] + if not h1 or #h1 == 0 then + DEBUG("empty request") + return + end + local cmd = split(header_lines[1], "%S+") + if not cmd or #cmd < 3 then + DEBUG(string.format("bad request: %s", header_lines[1])) + return + end + if cmd[1] ~= "GET" then + DEBUG(string.format("bad op: %s", cmd[1])) + return + end + protocol = cmd[3] + if protocol ~= "HTTP/1.0" and protocol ~= "HTTP/1.1" then + DEBUG(string.format("bad protocol: %s", protocol)) + return + end + local path = cmd[2] + DEBUG(string.format("path='%s'", path)) + + -- extract header variables + for i = 2,#header_lines do + local key, var = string.match(header_lines[i], '(.*): (.*)') + header_vars[key] = var + end + + if isdirectory(path) and not endswith(path,"/") and header_vars['Host'] and not is_hidden_dir(path) then + self.moved_permanently(path .. "/") + return + end + + if path ~= "/" and endswith(path,"/") then + path = string.sub(path, 1, #path-1) + end + + if startswith(path,"/@") then + path = string.sub(path, 2, #path) + end + + -- see if we have an index file + if isdirectory(path) and file_exists(path .. "/index.html") then + DEBUG("found index.html") + if self.file_download(path .. "/index.html") then + return + end + end + + -- see if it is a directory + if endswith(path,"/") or isdirectory(path) or is_hidden_dir(path) then + self.directory_list(path) + return + end + -- or a file + if self.file_download(path) then + return + end + self.not_found(path) + end + + -- update the client + function self.update() + if run then + run() + return + end + if not have_header then + if not self.read_header() then + return + end + end + self.process_request() + if not run then + -- nothing more to do + self.remove() + end + end + + function self.remove() + DEBUG(string.format("Removing client %u", idx)) + sock:close() + self.closed = true + end + + -- return the instance + return self +end + +--[[ + see if any new clients want to connect +--]] +local function check_new_clients() + local sock = sock_listen:accept() + if sock then + -- non-blocking for header read + sock:set_blocking(false) + local idx = #clients+1 + local client = Client(sock, idx) + DEBUG(string.format("New client %u", idx)) + table.insert(clients, client) + end +end + +--[[ + check for client activity +--]] +local function check_clients() + for idx,client in ipairs(clients) do + if not client.closed then + client.update() + end + if client.closed then + table.remove(clients,idx) + end + end +end + +local function update() + check_clients() + check_new_clients() + return update,1 +end + +return update,100 diff --git a/libraries/AP_Scripting/applets/net_webserver.md b/libraries/AP_Scripting/applets/net_webserver.md new file mode 100644 index 00000000000000..fa45efe780b467 --- /dev/null +++ b/libraries/AP_Scripting/applets/net_webserver.md @@ -0,0 +1,91 @@ +# Web Server Application + +This implements a web server for boards that have networking support. + +# Parameters + +The web server has a small number of parameters + +## WEB_ENABLE + +This must be set to 1 to enable the web server + +## WEB_BIND_PORT + +This sets the network port to use for the server. It defaults to 8080 + +## WEB_DEBUG + +This enables verbose debugging + +## WEB_BLOCK_SIZE + +This sets the block size for network and file read/write +operations. Setting a larger value can increase performance at the +cost of more memory + +## WEB_TIMEOUT + +This sets the timeout in seconds for inactive client connections. + +# Operation + +By default the web server serves the root of your microSD card. You +can include html, javascript (*.js), image files etc on your microSD +to create a full web server with any structure you want. + +## Server Side Scripting + +The web server supports embedding lua script elements inside html +files for files with a filename of *.shtml. Here is an example: + +``` + + + + + +

Server Side Scripting Test

+ + + + + + + +
RollPitchYaw
+ + +``` +In this example we are using two forms of embedded lua scripts. The +first form starts with " Date: Thu, 7 Dec 2023 16:36:08 +1100 Subject: [PATCH 0016/1335] AP_Scripting: added poll bindings --- libraries/AP_Scripting/generator/description/bindings.desc | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index 5d6bf1b39e17e0..f269643e1d512a 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -546,6 +546,9 @@ ap_object SocketAPM method send int32_t string uint32_t'skip_check ap_object SocketAPM method listen boolean uint8_t'skip_check ap_object SocketAPM method set_blocking boolean boolean ap_object SocketAPM method is_connected boolean +ap_object SocketAPM method pollout boolean uint32_t'skip_check +ap_object SocketAPM method pollin boolean uint32_t'skip_check +ap_object SocketAPM method reuseaddress boolean ap_object SocketAPM manual close SocketAPM_close 0 ap_object SocketAPM manual recv SocketAPM_recv 1 ap_object SocketAPM manual accept SocketAPM_accept 1 From fec0ec79c56e3f8d82899facf2da2c1dbfc56259 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 7 Dec 2023 16:37:56 +1100 Subject: [PATCH 0017/1335] AP_Networking: make lwip debugging easier --- libraries/AP_Networking/AP_Networking.cpp | 27 +++++++++++++++++++++++ libraries/AP_Networking/AP_Networking.h | 4 ++++ 2 files changed, 31 insertions(+) diff --git a/libraries/AP_Networking/AP_Networking.cpp b/libraries/AP_Networking/AP_Networking.cpp index df2f207e9c5abf..76c7e95b5f081d 100644 --- a/libraries/AP_Networking/AP_Networking.cpp +++ b/libraries/AP_Networking/AP_Networking.cpp @@ -292,4 +292,31 @@ AP_Networking &network() } } +/* + debug printfs from LWIP + */ +int ap_networking_printf(const char *fmt, ...) +{ +#ifdef AP_NETWORKING_LWIP_DEBUG_PORT + static AP_HAL::UARTDriver *uart; + if (uart == nullptr) { + uart = hal.serial(AP_NETWORKING_LWIP_DEBUG_PORT); + if (uart == nullptr) { + return -1; + } + uart->begin(921600, 0, 50000); + } + va_list ap; + va_start(ap, fmt); + uart->vprintf(fmt, ap); + va_end(ap); +#else + va_list ap; + va_start(ap, fmt); + hal.console->vprintf(fmt, ap); + va_end(ap); +#endif + return 0; +} + #endif // AP_NETWORKING_ENABLED diff --git a/libraries/AP_Networking/AP_Networking.h b/libraries/AP_Networking/AP_Networking.h index 1359b3abe55723..5c3b52be73551f 100644 --- a/libraries/AP_Networking/AP_Networking.h +++ b/libraries/AP_Networking/AP_Networking.h @@ -319,4 +319,8 @@ namespace AP AP_Networking &network(); }; +extern "C" { +int ap_networking_printf(const char *fmt, ...); +} + #endif // AP_NETWORKING_ENABLED From f603f045b532d09f6e47a4ec747f8da0c9d8a881 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 7 Dec 2023 16:40:20 +1100 Subject: [PATCH 0018/1335] HAL_ChibiOS: make lwip debugging easier use ap_networking_printf wrapper --- .../AP_HAL_ChibiOS/hwdef/common/lwipopts.h | 17 ++++++++++++++--- 1 file changed, 14 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h b/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h index 5351ff63933e0f..7ff155ca45fd13 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h @@ -49,7 +49,6 @@ ----------------------------------------------- */ -#define LWIP_PLATFORM_DIAG(x) do {__wrap_printf x; } while(0) // #define LWIP_DEBUG #define U16_F "u" #define X8_F "x" @@ -58,12 +57,24 @@ #define ETHARP_STATS 1 #define LWIP_IGMP 1 #define MEMP_NUM_NETCONN 50 // up to 50 sockets -#define MEMP_NUM_TCP_PCB 50 +#define MEMP_NUM_TCP_PCB 200 #define MEM_LIBC_MALLOC 1 #define MEMP_MEM_MALLOC 1 #define SO_REUSE 1 #define SO_REUSE_RXTOALL 1 -#define DHCP_DEBUG LWIP_DBG_ON + +/* + map LWIP debugging onto ap_networking_printf to allow for easier + redirection to a file or dedicated serial port + */ +#ifdef __cplusplus +extern "C" { +#endif +int ap_networking_printf(const char *fmt, ...); +#ifdef __cplusplus +} +#endif +#define LWIP_PLATFORM_DIAG(x) do {ap_networking_printf x; } while(0) #ifndef LWIP_IPV6 // This uses an additional 18KB Flash From 39891d3161eb0162c5e06f91c3284abd7d6fdaa3 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 7 Dec 2023 16:41:23 +1100 Subject: [PATCH 0019/1335] AP_Scripting: improve web server debug --- .../AP_Scripting/applets/net_webserver.lua | 88 +++++++++++++------ 1 file changed, 59 insertions(+), 29 deletions(-) diff --git a/libraries/AP_Scripting/applets/net_webserver.lua b/libraries/AP_Scripting/applets/net_webserver.lua index fb0076717ca850..8ba0a14e92a40f 100644 --- a/libraries/AP_Scripting/applets/net_webserver.lua +++ b/libraries/AP_Scripting/applets/net_webserver.lua @@ -168,7 +168,7 @@ if not sock_listen:bind("0.0.0.0", WEB_BIND_PORT:get()) then return end -if not sock_listen:listen(50) then +if not sock_listen:listen(1) then gcs:send_text(MAV_SEVERITY.ERROR, "WebServer: failed to listen") return end @@ -202,9 +202,12 @@ local function startswith(str, s) return string.sub(str,1,len2) == s end +local debug_count=0 + function DEBUG(txt) if WEB_DEBUG:get() ~= 0 then - gcs:send_text(MAV_SEVERITY.DEBUG, txt) + gcs:send_text(MAV_SEVERITY.DEBUG, txt .. string.format(" [%u]", debug_count)) + debug_count = debug_count + 1 end end @@ -250,6 +253,7 @@ local function Client(_sock, _idx) local protocol = nil local file = nil local start_time = millis() + local offset = 0 function self.read_header() local s = sock:recv(2048) @@ -257,7 +261,7 @@ local function Client(_sock, _idx) local now = millis() if not sock:is_connected() or now - start_time > WEB_TIMEOUT:get()*1000 then -- EOF while looking for header - DEBUG("EOF") + DEBUG(string.format("%u: EOF", idx)) self.remove() return false end @@ -269,7 +273,7 @@ local function Client(_sock, _idx) header = header .. s local eoh = string.find(s, '\r\n\r\n') if eoh then - DEBUG("got header") + DEBUG(string.format("%u: got header", idx)) have_header = true header_lines = split(header, "[^\r\n]+") -- blocking for reply @@ -311,14 +315,14 @@ local function Client(_sock, _idx) -- get size of a file function self.file_size(fname) - DEBUG(string.format("size of '%s'", fname)) + DEBUG(string.format("%u: size of '%s'", idx, fname)) local f = io.open(fname, "rb") if not f then return -1 end local ret = f:seek("end") f:close() - DEBUG(string.format("size of '%s' -> %u", fname, ret)) + DEBUG(string.format("%u: size of '%s' -> %u", idx, fname, ret)) return ret end @@ -327,7 +331,7 @@ local function Client(_sock, _idx) return full path with .. resolution --]] function self.full_path(path, name) - DEBUG(string.format("full_path(%s,%s)", path, name)) + DEBUG(string.format("%u: full_path(%s,%s)", idx, path, name)) local ret = path if path == "/" and startswith(name,"@") then return name @@ -349,15 +353,16 @@ local function Client(_sock, _idx) ret = ret .. "/" end ret = ret .. name - DEBUG(string.format("full_path(%s,%s) -> %s", path, name, ret)) + DEBUG(string.format("%u: full_path(%s,%s) -> %s", idx, path, name, ret)) return ret end function self.directory_list(path) + sock:set_blocking(true) if startswith(path, "/@") then path = string.sub(path, 2, #path-1) end - DEBUG(string.format("directory_list(%s)", path)) + DEBUG(string.format("%u: directory_list(%s)", idx, path)) local dlist = dirlist(path) if not dlist then dlist = {} @@ -412,14 +417,27 @@ local function Client(_sock, _idx) -- send file content function self.send_file() + if not sock:pollout(0) then + return + end local chunk = WEB_BLOCK_SIZE:get() local b = file:read(chunk) + sock:set_blocking(true) if b and #b > 0 then - sock:send(b, #b) + local sent = sock:send(b, #b) + if sent == -1 then + run = nil + self.remove() + return + end + if sent < #b then + file:seek(offset+sent) + end + offset = offset + sent end if not b or #b < chunk then -- EOF - DEBUG("sent file") + DEBUG(string.format("%u: sent file", idx)) run = nil self.remove() return @@ -469,6 +487,7 @@ local function Client(_sock, _idx) process a file as a lua CGI --]] function self.send_cgi() + sock:set_blocking(true) local contents = self.load_file() local s = self.evaluate(contents) if s then @@ -487,6 +506,7 @@ local function Client(_sock, _idx) automatically --]] function self.send_processed_file() + sock:set_blocking(true) local contents = self.load_file() while #contents > 0 do local pat1 = "(.-)[<][?]lua[ \n](.-)[?][>](.*)" @@ -526,10 +546,10 @@ local function Client(_sock, _idx) if startswith(path, "/@") then path = string.sub(path, 2, #path) end - DEBUG(string.format("file_download(%s)", path)) + DEBUG(string.format("%u: file_download(%s)", idx, path)) file = io.open(path,"rb") if not file then - DEBUG(string.format("Failed to open '%s'", path)) + DEBUG(string.format("%u: Failed to open '%s'", idx, path)) return false end local vars = {["Content-Type"]=self.content_type(path)} @@ -541,10 +561,10 @@ local function Client(_sock, _idx) end self.send_header(200, "OK", vars) if server_side_processing then - DEBUG(string.format("shtml processing %s", path)) + DEBUG(string.format("%u: shtml processing %s", idx, path)) run = self.send_processed_file elseif cgi_processing then - DEBUG(string.format("CGI processing %s", path)) + DEBUG(string.format("%u: CGI processing %s", idx, path)) run = self.send_cgi else run = self.send_file @@ -561,7 +581,7 @@ local function Client(_sock, _idx) relpath = "/" .. relpath end local location = string.format("http://%s%s", header_vars['Host'], relpath) - DEBUG(string.format("Redirect -> %s", location)) + DEBUG(string.format("%u: Redirect -> %s", idx, location)) self.send_header(301, "Moved Permanently", {["Location"]=location}) end @@ -569,7 +589,7 @@ local function Client(_sock, _idx) function self.process_request() local h1 = header_lines[1] if not h1 or #h1 == 0 then - DEBUG("empty request") + DEBUG(string.format("%u: empty request", idx)) return end local cmd = split(header_lines[1], "%S+") @@ -587,12 +607,14 @@ local function Client(_sock, _idx) return end local path = cmd[2] - DEBUG(string.format("path='%s'", path)) + DEBUG(string.format("%u: path='%s'", idx, path)) -- extract header variables for i = 2,#header_lines do local key, var = string.match(header_lines[i], '(.*): (.*)') - header_vars[key] = var + if key then + header_vars[key] = var + end end if isdirectory(path) and not endswith(path,"/") and header_vars['Host'] and not is_hidden_dir(path) then @@ -610,7 +632,7 @@ local function Client(_sock, _idx) -- see if we have an index file if isdirectory(path) and file_exists(path .. "/index.html") then - DEBUG("found index.html") + DEBUG(string.format("%u: found index.html", idx)) if self.file_download(path .. "/index.html") then return end @@ -647,7 +669,7 @@ local function Client(_sock, _idx) end function self.remove() - DEBUG(string.format("Removing client %u", idx)) + DEBUG(string.format("%u: removing client OFFSET=%u", idx, offset)) sock:close() self.closed = true end @@ -660,14 +682,22 @@ end see if any new clients want to connect --]] local function check_new_clients() - local sock = sock_listen:accept() - if sock then + while true do + local sock = sock_listen:accept() + if not sock then + return + end -- non-blocking for header read sock:set_blocking(false) - local idx = #clients+1 - local client = Client(sock, idx) - DEBUG(string.format("New client %u", idx)) - table.insert(clients, client) + -- find free client slot + for i = 1, #clients+1 do + if clients[i] == nil then + local idx = i + local client = Client(sock, idx) + DEBUG(string.format("%u: New client", idx)) + clients[idx] = client + end + end end end @@ -686,9 +716,9 @@ local function check_clients() end local function update() - check_clients() check_new_clients() - return update,1 + check_clients() + return update,5 end return update,100 From 8f2911d0e281cd69134a2622480329abbe91f2e8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 7 Dec 2023 16:41:47 +1100 Subject: [PATCH 0020/1335] waf: fix dependency on lwip code --- Tools/ardupilotwaf/chibios.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Tools/ardupilotwaf/chibios.py b/Tools/ardupilotwaf/chibios.py index a827af26f777f7..0262eeecffa021 100644 --- a/Tools/ardupilotwaf/chibios.py +++ b/Tools/ardupilotwaf/chibios.py @@ -675,6 +675,8 @@ def build(bld): common_src += bld.path.ant_glob('libraries/AP_HAL_ChibiOS/hwdef/common/*.mk') common_src += bld.path.ant_glob('modules/ChibiOS/os/hal/**/*.[ch]') common_src += bld.path.ant_glob('modules/ChibiOS/os/hal/**/*.mk') + common_src += bld.path.ant_glob('modules/ChibiOS/ext/lwip/src/**/*.[ch]') + common_src += bld.path.ant_glob('modules/ChibiOS/ext/lwip/src/core/**/*.[ch]') if bld.env.ROMFS_FILES: common_src += [bld.bldnode.find_or_declare('ap_romfs_embedded.h')] From 28885dca4c07a11198e8340bb6887c5d99315cc0 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 7 Dec 2023 18:54:50 +1100 Subject: [PATCH 0021/1335] HAL_ChibiOS: adjust buffer sizes this fixes issues with TCP accepts being lost in web server --- libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h b/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h index 7ff155ca45fd13..4cd1e61bee89db 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h @@ -62,6 +62,8 @@ #define MEMP_MEM_MALLOC 1 #define SO_REUSE 1 #define SO_REUSE_RXTOALL 1 +#define DEFAULT_ACCEPTMBOX_SIZE 20 +#define MEMP_NUM_PBUF 64 /* map LWIP debugging onto ap_networking_printf to allow for easier From a4fb05de9567033175c0a510a7ea61f593a0536f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 8 Dec 2023 12:37:54 +1100 Subject: [PATCH 0022/1335] HAL_ChibiOS: increase LWIP windows now getting 6.8MByte/s with NET_TESTS=4 --- libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h b/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h index 4cd1e61bee89db..94f839feaa0f7d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h @@ -64,6 +64,8 @@ #define SO_REUSE_RXTOALL 1 #define DEFAULT_ACCEPTMBOX_SIZE 20 #define MEMP_NUM_PBUF 64 +#define TCP_WND 12000 +#define TCP_SND_BUF 12000 /* map LWIP debugging onto ap_networking_printf to allow for easier From 26d814880e90e5ca6e56231a85714a56f669a7a2 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 7 Dec 2023 18:55:02 +1100 Subject: [PATCH 0023/1335] AP_Scripting: webserver improvements --- libraries/AP_Scripting/applets/net_webserver.lua | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Scripting/applets/net_webserver.lua b/libraries/AP_Scripting/applets/net_webserver.lua index 8ba0a14e92a40f..284dae82017954 100644 --- a/libraries/AP_Scripting/applets/net_webserver.lua +++ b/libraries/AP_Scripting/applets/net_webserver.lua @@ -168,7 +168,7 @@ if not sock_listen:bind("0.0.0.0", WEB_BIND_PORT:get()) then return end -if not sock_listen:listen(1) then +if not sock_listen:listen(20) then gcs:send_text(MAV_SEVERITY.ERROR, "WebServer: failed to listen") return end @@ -682,7 +682,7 @@ end see if any new clients want to connect --]] local function check_new_clients() - while true do + while sock_listen:pollin(0) do local sock = sock_listen:accept() if not sock then return From c9c38300bd72aa5cbf936275af2d92b36e079f1a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 8 Dec 2023 05:29:01 +1100 Subject: [PATCH 0024/1335] AP_Filesystem: expose APFS_FILE structure allows scripting to set the fd for sendfile() --- libraries/AP_Filesystem/posix_compat.cpp | 8 -------- libraries/AP_Filesystem/posix_compat.h | 9 ++++++++- 2 files changed, 8 insertions(+), 9 deletions(-) diff --git a/libraries/AP_Filesystem/posix_compat.cpp b/libraries/AP_Filesystem/posix_compat.cpp index f12f146012d5bb..6dee4f1653431f 100644 --- a/libraries/AP_Filesystem/posix_compat.cpp +++ b/libraries/AP_Filesystem/posix_compat.cpp @@ -30,14 +30,6 @@ #include #include -struct apfs_file { - int fd; - bool error; - bool eof; - int16_t unget; - char *tmpfile_name; -}; - #define CHECK_STREAM(stream, ret) while (stream == NULL || stream->fd < 0) { errno = EBADF; return ret; } #define modecmp(str, pat) (strcmp(str, pat) == 0 ? 1: 0) diff --git a/libraries/AP_Filesystem/posix_compat.h b/libraries/AP_Filesystem/posix_compat.h index 5fa0fba3caa8f2..c899d81332ee98 100644 --- a/libraries/AP_Filesystem/posix_compat.h +++ b/libraries/AP_Filesystem/posix_compat.h @@ -20,6 +20,7 @@ #include #include #include +#include #ifdef __cplusplus extern "C" { @@ -29,7 +30,13 @@ extern "C" { these are here to allow lua to build on HAL_ChibiOS */ -typedef struct apfs_file APFS_FILE; +typedef struct apfs_file { + int fd; + bool error; + bool eof; + int16_t unget; + char *tmpfile_name; +} APFS_FILE; APFS_FILE *apfs_fopen(const char *pathname, const char *mode); int apfs_fprintf(APFS_FILE *stream, const char *format, ...); From 9358bfce344cb42c352f93e93e6dbd7d47afa2eb Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 8 Dec 2023 05:29:48 +1100 Subject: [PATCH 0025/1335] AP_HAL: added duplicate() in SocketAPM --- libraries/AP_HAL/utility/Socket.cpp | 17 +++++++++++++++++ libraries/AP_HAL/utility/Socket.h | 4 ++++ 2 files changed, 21 insertions(+) diff --git a/libraries/AP_HAL/utility/Socket.cpp b/libraries/AP_HAL/utility/Socket.cpp index faab14d3d20341..b27a3195d0a661 100644 --- a/libraries/AP_HAL/utility/Socket.cpp +++ b/libraries/AP_HAL/utility/Socket.cpp @@ -459,4 +459,21 @@ void SocketAPM::close(void) } } +/* + duplicate a socket, giving a new object with the same contents, + the fd in the old object is set to -1 + */ +SocketAPM *SocketAPM::duplicate(void) +{ + auto *ret = new SocketAPM(datagram, fd); + if (ret == nullptr) { + return nullptr; + } + ret->fd_in = fd_in; + ret->connected = connected; + fd = -1; + fd_in = -1; + return ret; +} + #endif // AP_NETWORKING_BACKEND_ANY diff --git a/libraries/AP_HAL/utility/Socket.h b/libraries/AP_HAL/utility/Socket.h index 0ebc128d72caaa..a7bbf45e5ba1cf 100644 --- a/libraries/AP_HAL/utility/Socket.h +++ b/libraries/AP_HAL/utility/Socket.h @@ -81,6 +81,10 @@ class SocketAPM { return fd_in != -1? fd_in : fd; } + // create a new socket with same fd, but new memory + // the old socket gets fd of -1 + SocketAPM *duplicate(void); + bool is_connected(void) const { return connected; } From 241323eade953a1d826fdf38334011de791e8ec6 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 8 Dec 2023 05:32:32 +1100 Subject: [PATCH 0026/1335] AP_Networking: added sendfile() this allows for scripting to offload a file send to the AP_Networking library, reducing CPU costs of large file downloads --- libraries/AP_Networking/AP_Networking.cpp | 77 +++++++++++++++++++ libraries/AP_Networking/AP_Networking.h | 15 ++++ .../AP_Networking/AP_Networking_Config.h | 8 ++ 3 files changed, 100 insertions(+) diff --git a/libraries/AP_Networking/AP_Networking.cpp b/libraries/AP_Networking/AP_Networking.cpp index 76c7e95b5f081d..95856166fd17f5 100644 --- a/libraries/AP_Networking/AP_Networking.cpp +++ b/libraries/AP_Networking/AP_Networking.cpp @@ -8,6 +8,7 @@ #include #include #include +#include extern const AP_HAL::HAL& hal; @@ -19,6 +20,8 @@ extern const AP_HAL::HAL& hal; #include #endif +#include + #if AP_NETWORKING_BACKEND_SITL #include "AP_Networking_SITL.h" #endif @@ -150,6 +153,9 @@ void AP_Networking::init() // init network mapped serialmanager ports ports_init(); + + // register sendfile handler + hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_Networking::sendfile_check, void)); } /* @@ -282,6 +288,77 @@ void AP_Networking::startup_wait(void) const #endif } +/* + send the rest of a file to a socket + */ +bool AP_Networking::sendfile(SocketAPM *sock, int fd) +{ + WITH_SEMAPHORE(sem); + if (sendfile_buf == nullptr) { + sendfile_buf = (uint8_t *)malloc(AP_NETWORKING_SENDFILE_BUFSIZE); + if (sendfile_buf == nullptr) { + return false; + } + } + for (auto &s : sendfiles) { + if (s.sock == nullptr) { + s.sock = sock->duplicate(); + if (s.sock == nullptr) { + return false; + } + s.fd = fd; + return true; + } + } + return false; +} + +void AP_Networking::SendFile::close(void) +{ + AP::FS().close(fd); + delete sock; + sock = nullptr; +} + +#include +/* + check for sendfile updates + */ +void AP_Networking::sendfile_check(void) +{ + if (sendfile_buf == nullptr) { + return; + } + WITH_SEMAPHORE(sem); + bool none_active = true; + for (auto &s : sendfiles) { + if (s.sock == nullptr) { + continue; + } + none_active = false; + if (!s.sock->pollout(0)) { + continue; + } + const auto nread = AP::FS().read(s.fd, sendfile_buf, AP_NETWORKING_SENDFILE_BUFSIZE); + if (nread <= 0) { + s.close(); + continue; + } + const auto nsent = s.sock->send(sendfile_buf, nread); + if (nsent <= 0) { + s.close(); + continue; + } + if (nsent < nread) { + AP::FS().lseek(s.fd, nsent - nread, SEEK_CUR); + } + } + if (none_active) { + free(sendfile_buf); + sendfile_buf = nullptr; + } +} + AP_Networking *AP_Networking::singleton; namespace AP diff --git a/libraries/AP_Networking/AP_Networking.h b/libraries/AP_Networking/AP_Networking.h index 5c3b52be73551f..5ed32329244073 100644 --- a/libraries/AP_Networking/AP_Networking.h +++ b/libraries/AP_Networking/AP_Networking.h @@ -188,6 +188,11 @@ class AP_Networking static uint32_t convert_netmask_bitcount_to_ip(const uint32_t netmask_bitcount); static uint8_t convert_netmask_ip_to_bitcount(const uint32_t netmask_ip); + /* + send contents of a file to a socket then close both socket and file + */ + bool sendfile(SocketAPM *sock, int fd); + static const struct AP_Param::GroupInfo var_info[]; private: @@ -311,6 +316,16 @@ class AP_Networking // ports for registration with serial manager Port ports[AP_NETWORKING_NUM_PORTS]; + // support for sendfile() + struct SendFile { + SocketAPM *sock; + int fd; + void close(void); + } sendfiles[AP_NETWORKING_NUM_SENDFILES]; + + uint8_t *sendfile_buf; + void sendfile_check(void); + void ports_init(void); }; diff --git a/libraries/AP_Networking/AP_Networking_Config.h b/libraries/AP_Networking/AP_Networking_Config.h index 5d32334510dc55..00ba6d50c1e60e 100644 --- a/libraries/AP_Networking/AP_Networking_Config.h +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -89,3 +89,11 @@ #ifndef AP_NETWORKING_NUM_PORTS #define AP_NETWORKING_NUM_PORTS 4 #endif + +#ifndef AP_NETWORKING_NUM_SENDFILES +#define AP_NETWORKING_NUM_SENDFILES 20 +#endif + +#ifndef AP_NETWORKING_SENDFILE_BUFSIZE +#define AP_NETWORKING_SENDFILE_BUFSIZE 10000 +#endif From 1e1255c8f0ffae5464259115852dadbbb8a339f7 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 8 Dec 2023 05:36:19 +1100 Subject: [PATCH 0027/1335] AP_Scripting: added sendfile() API on sockets --- .../generator/description/bindings.desc | 1 + libraries/AP_Scripting/lua_bindings.cpp | 37 +++++++++++++++++++ libraries/AP_Scripting/lua_bindings.h | 1 + 3 files changed, 39 insertions(+) diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index f269643e1d512a..1b2f7e0c4ec6d2 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -549,6 +549,7 @@ ap_object SocketAPM method is_connected boolean ap_object SocketAPM method pollout boolean uint32_t'skip_check ap_object SocketAPM method pollin boolean uint32_t'skip_check ap_object SocketAPM method reuseaddress boolean +ap_object SocketAPM manual sendfile SocketAPM_sendfile 1 ap_object SocketAPM manual close SocketAPM_close 0 ap_object SocketAPM manual recv SocketAPM_recv 1 ap_object SocketAPM manual accept SocketAPM_accept 1 diff --git a/libraries/AP_Scripting/lua_bindings.cpp b/libraries/AP_Scripting/lua_bindings.cpp index ac7b4b83349f8e..8264233e137c14 100644 --- a/libraries/AP_Scripting/lua_bindings.cpp +++ b/libraries/AP_Scripting/lua_bindings.cpp @@ -19,6 +19,7 @@ #if AP_NETWORKING_ENABLED #include #endif +#include "lua/src/lauxlib.h" extern const AP_HAL::HAL& hal; @@ -836,6 +837,42 @@ int SocketAPM_close(lua_State *L) { return 0; } +/* + socket sendfile, for offloading file send to AP_Networking + */ +int SocketAPM_sendfile(lua_State *L) { + binding_argcheck(L, 2); + + SocketAPM *ud = *check_SocketAPM(L, 1); + + auto *scripting = AP::scripting(); + + if (scripting->num_net_sockets == 0) { + return luaL_argerror(L, 1, "socket close error"); + } + + auto *p = (luaL_Stream *)luaL_checkudata(L, 2, LUA_FILEHANDLE); + int fd = p->f->fd; + bool ret = false; + + // find the socket + for (uint8_t i=0; i_net_sockets[i] == ud) { + ret = AP::network().sendfile(ud, fd); + if (ret) { + // remove from scripting, leave socket and fd open + p->f->fd = -1; + scripting->_net_sockets[i] = nullptr; + scripting->num_net_sockets--; + } + break; + } + } + + lua_pushboolean(L, ret); + return 1; +} + /* receive from a socket to a lua string */ diff --git a/libraries/AP_Scripting/lua_bindings.h b/libraries/AP_Scripting/lua_bindings.h index 41adfd859659ea..3c5d9528c8d1e5 100644 --- a/libraries/AP_Scripting/lua_bindings.h +++ b/libraries/AP_Scripting/lua_bindings.h @@ -19,6 +19,7 @@ int lua_get_SocketAPM(lua_State *L); int SocketAPM_recv(lua_State *L); int SocketAPM_accept(lua_State *L); int SocketAPM_close(lua_State *L); +int SocketAPM_sendfile(lua_State *L); int lua_mavlink_init(lua_State *L); int lua_mavlink_receive_chan(lua_State *L); int lua_mavlink_register_rx_msgid(lua_State *L); From 9f08e5d317f3dccefd7185d6b55e33d554547d51 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 8 Dec 2023 05:36:31 +1100 Subject: [PATCH 0028/1335] AP_Scripting: use sendfile() in web server --- libraries/AP_Scripting/applets/net_webserver.lua | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_Scripting/applets/net_webserver.lua b/libraries/AP_Scripting/applets/net_webserver.lua index 284dae82017954..52c5dcce27870f 100644 --- a/libraries/AP_Scripting/applets/net_webserver.lua +++ b/libraries/AP_Scripting/applets/net_webserver.lua @@ -566,6 +566,8 @@ local function Client(_sock, _idx) elseif cgi_processing then DEBUG(string.format("%u: CGI processing %s", idx, path)) run = self.send_cgi + elseif sock:sendfile(file) then + return true else run = self.send_file end From 9beea49c3cbe73454639679d37400297f2624cef Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 8 Dec 2023 11:19:07 +1100 Subject: [PATCH 0029/1335] AP_Filesystem: implement stat() call for lua --- libraries/AP_Filesystem/AP_Filesystem.cpp | 24 +++++++++++++++++++++++ libraries/AP_Filesystem/AP_Filesystem.h | 19 +++++++++++++++++- 2 files changed, 42 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Filesystem/AP_Filesystem.cpp b/libraries/AP_Filesystem/AP_Filesystem.cpp index c0ab14b9869049..e62ec5920827c3 100644 --- a/libraries/AP_Filesystem/AP_Filesystem.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem.cpp @@ -333,6 +333,30 @@ AP_Filesystem_Backend::FormatStatus AP_Filesystem::get_format_status(void) const } #endif +/* + stat wrapper for scripting + */ +bool AP_Filesystem::stat(const char *pathname, stat_t &stbuf) +{ + struct stat st; + if (fs.stat(pathname, &st) != 0) { + return false; + } + stbuf.size = st.st_size; + stbuf.mode = st.st_mode; + // these wrap in 2038 + stbuf.atime = st.st_atime; + stbuf.ctime = st.st_ctime; + stbuf.mtime = st.st_mtime; + return true; +} + +// get_singleton for scripting +AP_Filesystem *AP_Filesystem::get_singleton(void) +{ + return &fs; +} + namespace AP { AP_Filesystem &FS() diff --git a/libraries/AP_Filesystem/AP_Filesystem.h b/libraries/AP_Filesystem/AP_Filesystem.h index 585a2f5e2eb2c9..b139713a751f59 100644 --- a/libraries/AP_Filesystem/AP_Filesystem.h +++ b/libraries/AP_Filesystem/AP_Filesystem.h @@ -82,6 +82,20 @@ class AP_Filesystem { int fsync(int fd); int32_t lseek(int fd, int32_t offset, int whence); int stat(const char *pathname, struct stat *stbuf); + + // stat variant for scripting + typedef struct { + uint32_t size; + int32_t mode; + uint32_t mtime; + uint32_t atime; + uint32_t ctime; + bool is_directory(void) const { + return (mode & S_IFMT) == S_IFDIR; + } + } stat_t; + bool stat(const char *pathname, stat_t &stbuf); + int unlink(const char *pathname); int mkdir(const char *pathname); int rename(const char *oldpath, const char *newpath); @@ -121,7 +135,10 @@ class AP_Filesystem { load a full file. Use delete to free the data */ FileData *load_file(const char *filename); - + + // get_singleton for scripting + static AP_Filesystem *get_singleton(void); + private: struct Backend { const char *prefix; From 2822f507c131c2095c4fd7823ccd3c62674226a9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 8 Dec 2023 11:19:50 +1100 Subject: [PATCH 0030/1335] AP_RTC: added time and date APIs for lua and fixed a bug with the ms time return --- libraries/AP_RTC/AP_RTC.cpp | 111 ++++++++++++++++++++++++++++-------- libraries/AP_RTC/AP_RTC.h | 9 ++- 2 files changed, 96 insertions(+), 24 deletions(-) diff --git a/libraries/AP_RTC/AP_RTC.cpp b/libraries/AP_RTC/AP_RTC.cpp index 41d9f5b2944706..77c763b528e0c0 100644 --- a/libraries/AP_RTC/AP_RTC.cpp +++ b/libraries/AP_RTC/AP_RTC.cpp @@ -94,15 +94,8 @@ bool AP_RTC::get_utc_usec(uint64_t &usec) const return true; } -bool AP_RTC::get_system_clock_utc(uint8_t &hour, uint8_t &min, uint8_t &sec, uint16_t &ms) const +void AP_RTC::clock_ms_to_hms_fields(const uint64_t time_ms, uint8_t &hour, uint8_t &min, uint8_t &sec, uint16_t &ms) const { - // get time of day in ms - uint64_t time_ms = 0; - if (!get_utc_usec(time_ms)) { - return false; - } - time_ms /= 1000U; - // separate time into ms, sec, min, hour and days but all expressed in milliseconds ms = time_ms % 1000; uint32_t sec_ms = (time_ms % (60 * 1000)) - ms; @@ -113,32 +106,104 @@ bool AP_RTC::get_system_clock_utc(uint8_t &hour, uint8_t &min, uint8_t &sec, uin sec = sec_ms / 1000; min = min_ms / (60 * 1000); hour = hour_ms / (60 * 60 * 1000); +} +bool AP_RTC::clock_s_to_date_fields(const uint32_t utc_sec32, uint16_t& year, uint8_t& month, uint8_t& day, uint8_t &hour, uint8_t &min, uint8_t &sec, uint8_t &wday) const +{ + const time_t utc_sec = utc_sec32; + struct tm* tm = gmtime(&utc_sec); + if (tm == nullptr) { + return false; + } + year = tm->tm_year+1900; /* Year, 20xx. */ + month = tm->tm_mon; /* Month. [0-11] */ + day = tm->tm_mday; /* Day. [1-31] */ + hour = tm->tm_hour; /* Hours. [0-23] */ + min = tm->tm_min; /* Minutes. [0-59] */ + sec = tm->tm_sec; /* Seconds. [0-60] (1 leap second) */ + wday = tm->tm_wday; /* week day, [0-6] */ + return true; +} + +/* + return true for leap years + */ +bool AP_RTC::_is_leap(uint32_t y) +{ + y += 1900; + return (y % 4) == 0 && ((y % 100) != 0 || (y % 400) == 0); +} + +/* + implementation of timegm() (from Samba) +*/ +uint32_t AP_RTC::_timegm(struct tm &tm) +{ + static const uint8_t ndays[2][12] = { + {31, 28, 31, 30, 31, 30, 31, 31, 30, 31, 30, 31}, + {31, 29, 31, 30, 31, 30, 31, 31, 30, 31, 30, 31}}; + uint32_t res = 0; + + if (tm.tm_mon > 12 || + tm.tm_mday > 31 || + tm.tm_min > 60 || + tm.tm_sec > 60 || + tm.tm_hour > 24) { + /* invalid tm structure */ + return 0; + } + + for (auto i = 70; i < tm.tm_year; i++) { + res += _is_leap(i) ? 366 : 365; + } + + for (auto i = 0; i < tm.tm_mon; i++) { + res += ndays[_is_leap(tm.tm_year)][i]; + } + res += tm.tm_mday - 1U; + res *= 24U; + res += tm.tm_hour; + res *= 60U; + res += tm.tm_min; + res *= 60U; + res += tm.tm_sec; + return res; +} + +uint32_t AP_RTC::date_fields_to_clock_s(uint16_t year, uint8_t month, uint8_t day, uint8_t hour, uint8_t min, uint8_t sec) const +{ + struct tm tm {}; + tm.tm_year = year - 1900; + tm.tm_mon = month; + tm.tm_mday = day; + tm.tm_hour = hour; + tm.tm_min = min; + tm.tm_sec = sec; + return _timegm(tm); +} + +bool AP_RTC::get_system_clock_utc(uint8_t &hour, uint8_t &min, uint8_t &sec, uint16_t &ms) const +{ + // get time of day in ms + uint64_t time_ms; + if (!get_utc_usec(time_ms)) { + return false; + } + time_ms /= 1000U; + clock_ms_to_hms_fields(time_ms, hour, min, sec, ms); return true; } bool AP_RTC::get_local_time(uint8_t &hour, uint8_t &min, uint8_t &sec, uint16_t &ms) const { // get local time of day in ms - uint64_t time_ms = 0; - uint64_t ms_local = 0; + uint64_t time_ms; if (!get_utc_usec(time_ms)) { return false; } time_ms /= 1000U; - ms_local = time_ms + (tz_min * 60000); - - // separate time into ms, sec, min, hour and days but all expressed in milliseconds - ms = ms_local % 1000; - uint32_t sec_ms = (ms_local % (60 * 1000)) - ms; - uint32_t min_ms = (ms_local % (60 * 60 * 1000)) - sec_ms - ms; - uint32_t hour_ms = (ms_local % (24 * 60 * 60 * 1000)) - min_ms - sec_ms - ms; - - // convert times as milliseconds into appropriate units - sec = sec_ms / 1000; - min = min_ms / (60 * 1000); - hour = hour_ms / (60 * 60 * 1000); - + const uint64_t ms_local = time_ms + (tz_min * 60000); + clock_ms_to_hms_fields(ms_local, hour, min, sec, ms); return true; } diff --git a/libraries/AP_RTC/AP_RTC.h b/libraries/AP_RTC/AP_RTC.h index d03846bf6f29b1..a35887532b5473 100644 --- a/libraries/AP_RTC/AP_RTC.h +++ b/libraries/AP_RTC/AP_RTC.h @@ -61,7 +61,10 @@ class AP_RTC { HAL_Semaphore &get_semaphore(void) { return rsem; } - + + bool clock_s_to_date_fields(const uint32_t utc_sec32, uint16_t& year, uint8_t& month, uint8_t& day, uint8_t &hour, uint8_t &min, uint8_t &sec, uint8_t &wday) const; + uint32_t date_fields_to_clock_s(uint16_t year, uint8_t month, uint8_t day, uint8_t hour, uint8_t min, uint8_t sec) const; + private: static AP_RTC *_singleton; @@ -70,6 +73,10 @@ class AP_RTC { source_type rtc_source_type = SOURCE_NONE; int64_t rtc_shift; + void clock_ms_to_hms_fields(const uint64_t time_ms, uint8_t &hour, uint8_t &min, uint8_t &sec, uint16_t &ms) const; + + static bool _is_leap(uint32_t y); + static uint32_t _timegm(struct tm &tm); }; namespace AP { From 90c12d4db33e094752a7c5e2fcad49994292e6ec Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 8 Dec 2023 11:20:59 +1100 Subject: [PATCH 0031/1335] AP_Scripting: added stat() binding for filesystem --- libraries/AP_Scripting/docs/docs.lua | 5 ----- .../generator/description/bindings.desc | 21 ++++++++++++++++++- libraries/AP_Scripting/lua_bindings.cpp | 19 ----------------- libraries/AP_Scripting/lua_bindings.h | 1 - 4 files changed, 20 insertions(+), 26 deletions(-) diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index b8f7c806b84feb..4f70ca60671fc2 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -3062,11 +3062,6 @@ function scripting:restart_all() end ---@return table -- table of filenames function dirlist(directoryname) end --- return true if path is a directory ----@param path string ----@return result -function isdirectory(path) end - --desc ---@param filename string function remove(filename) end diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index 1b2f7e0c4ec6d2..6f77cc8124a980 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -816,7 +816,6 @@ userdata uint32_t manual tofloat uint32_t_tofloat 0 global manual dirlist lua_dirlist 1 global manual remove lua_removefile 1 -global manual isdirectory lua_isdirectory 1 global manual print lua_print 1 singleton mavlink depends HAL_GCS_ENABLED @@ -832,3 +831,23 @@ singleton AC_Fence depends AP_FENCE_ENABLED singleton AC_Fence rename fence singleton AC_Fence method get_breaches uint8_t singleton AC_Fence method get_breach_time uint32_t + +include AP_Filesystem/AP_Filesystem.h depends AP_FILESYSTEM_FILE_READING_ENABLED +include AP_Filesystem/AP_Filesystem_config.h +userdata AP_Filesystem::stat_t depends AP_FILESYSTEM_FILE_READING_ENABLED +userdata AP_Filesystem::stat_t rename stat_t +userdata AP_Filesystem::stat_t field size uint32_t read +userdata AP_Filesystem::stat_t field mode int32_t read +userdata AP_Filesystem::stat_t field mtime uint32_t read +userdata AP_Filesystem::stat_t field atime uint32_t read +userdata AP_Filesystem::stat_t field ctime uint32_t read +userdata AP_Filesystem::stat_t method is_directory boolean + +singleton AP_Filesystem rename fs +singleton AP_Filesystem method stat boolean string AP_Filesystem::stat_t'Null + +include AP_RTC/AP_RTC.h depends AP_RTC_ENABLED +include AP_RTC/AP_RTC_config.h +singleton AP_RTC rename rtc +singleton AP_RTC method clock_s_to_date_fields boolean uint32_t'skip_check uint16_t'Null uint8_t'Null uint8_t'Null uint8_t'Null uint8_t'Null uint8_t'Null uint8_t'Null +singleton AP_RTC method date_fields_to_clock_s uint32_t uint16_t'skip_check int8_t'skip_check uint8_t'skip_check uint8_t'skip_check uint8_t'skip_check uint8_t'skip_check diff --git a/libraries/AP_Scripting/lua_bindings.cpp b/libraries/AP_Scripting/lua_bindings.cpp index 8264233e137c14..8020da37e92c0e 100644 --- a/libraries/AP_Scripting/lua_bindings.cpp +++ b/libraries/AP_Scripting/lua_bindings.cpp @@ -721,25 +721,6 @@ int lua_dirlist(lua_State *L) { return 1; /* table is already on top */ } -/* - return true if path is a directory - */ -int lua_isdirectory(lua_State *L) { - binding_argcheck(L, 1); - - const char *path = luaL_checkstring(L, 1); - - struct stat st; - if (AP::FS().stat(path, &st) != 0) { - lua_pushnil(L); /* return nil and ... */ - lua_pushstring(L, strerror(errno)); /* error message */ - return 2; - } - bool ret = (st.st_mode & S_IFMT) == S_IFDIR; - lua_pushboolean(L, ret); - return 1; -} - /* remove a file */ diff --git a/libraries/AP_Scripting/lua_bindings.h b/libraries/AP_Scripting/lua_bindings.h index 3c5d9528c8d1e5..6bc459dc27bf2b 100644 --- a/libraries/AP_Scripting/lua_bindings.h +++ b/libraries/AP_Scripting/lua_bindings.h @@ -12,7 +12,6 @@ int lua_get_CAN_device(lua_State *L); int lua_get_CAN_device2(lua_State *L); int lua_dirlist(lua_State *L); int lua_removefile(lua_State *L); -int lua_isdirectory(lua_State *L); int SRV_Channels_get_safety_state(lua_State *L); int lua_get_PWMSource(lua_State *L); int lua_get_SocketAPM(lua_State *L); From 168bc4e32fff622df1dc328324334701da443d30 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 8 Dec 2023 11:21:25 +1100 Subject: [PATCH 0032/1335] AP_Scripting: added If-Modified-Since for webserver --- .../AP_Scripting/applets/net_webserver.lua | 158 ++++++++++++++---- 1 file changed, 127 insertions(+), 31 deletions(-) diff --git a/libraries/AP_Scripting/applets/net_webserver.lua b/libraries/AP_Scripting/applets/net_webserver.lua index 52c5dcce27870f..a1cac978c0205e 100644 --- a/libraries/AP_Scripting/applets/net_webserver.lua +++ b/libraries/AP_Scripting/applets/net_webserver.lua @@ -62,6 +62,8 @@ local WEB_BLOCK_SIZE = bind_add_param('BLOCK_SIZE', 4, 10240) --]] local WEB_TIMEOUT = bind_add_param('TIMEOUT', 5, 2.0) +local BRD_RTC_TZ_MIN = Parameter("BRD_RTC_TZ_MIN") + gcs:send_text(MAV_SEVERITY.INFO, string.format("WebServer: starting on port %u", WEB_BIND_PORT:get())) local counter = 0 @@ -212,29 +214,110 @@ function DEBUG(txt) end --[[ - return true if a table contains a given element + return index of element in a table --]] -function contains(t,el) - for _,v in ipairs(t) do +function table_index(t,el) + for i,v in ipairs(t) do if v == el then - return true + return i end end - return false + return nil +end + +--[[ + return true if a table contains a given element +--]] +function table_contains(t,el) + local i = table_index(t, el) + return i ~= nil end function is_hidden_dir(path) - return contains(HIDDEN_FOLDERS, path) + return table_contains(HIDDEN_FOLDERS, path) +end + +local DAYS = { "Sun", "Mon", "Tue", "Wed", "Thu", "Fri", "Sat" } +local MONTHS = { "Jan", "Feb", "Mar", "Apr", "May", "Jun", "Jul", "Aug", "Sep", "Oct", "Nov", "Dec" } + +function isdirectory(path) + local s = fs:stat(path) + return s and s:is_directory() +end + +--[[ + time string for directory listings +--]] +function file_timestring(path) + local s = fs:stat(path) + if not s then + return "" + end + local mtime = s:mtime() + mtime = mtime + BRD_RTC_TZ_MIN:get()*60 + local year, month, day, hour, min, sec, wday = rtc:clock_s_to_date_fields(mtime) + if not year then + return "" + end + return string.format("%04u-%02u-%02u %02u:%02u", year, month+1, day, hour, min, sec) +end + +--[[ + time string for Last-Modified +--]] +function file_timestring_http(mtime) + local year, month, day, hour, min, sec, wday = rtc:clock_s_to_date_fields(mtime) + if not year then + return "" + end + return string.format("%s, %02u %s %u %02u:%02u:%02u GMT", + DAYS[wday+1], + day, + MONTHS[month+1], + year, + hour, + min, + sec) end +--[[ + parse a http time string to a uint32_t seconds timestamp +--]] +function file_timestring_http_parse(tstring) + local dayname, day, monthname, year, hour, min, sec = + string.match(tstring, + '(%w%w%w), (%d+) (%w%w%w) (%d%d%d%d) (%d%d):(%d%d):(%d%d) GMT') + if not dayname then + return nil + end + local mon = table_index(MONTHS, monthname) + return rtc:date_fields_to_clock_s(year, mon-1, day, hour, min, sec) +end + +--[[ + return true if path exists and is not a directory +--]] function file_exists(path) - local f = io.open(path, "rb") - if f then - return true + local s = fs:stat(path) + if not s then + return false end - return false + return not s:is_directory() end +--[[ + substitute variables of form {xxx} from a table + from http://lua-users.org/wiki/StringInterpolation +--]] +function substitute_vars(s, vars) + s = (string.gsub(s, "({([^}]+)})", + function(whole,i) + return vars[i] or whole + end)) + return s +end + + --[[ client class for open connections --]] @@ -293,14 +376,9 @@ local function Client(_sock, _idx) --[[ send a string with variable substitution using {varname} - from http://lua-users.org/wiki/StringInterpolation --]] function self.sendstring_vars(s, vars) - s = (string.gsub(s, "({([^}]+)})", - function(whole,i) - return vars[i] or whole - end)) - self.sendstring(s) + self.sendstring(substitute_vars(s, vars)) end function self.send_header(code, codestr, vars) @@ -315,13 +393,11 @@ local function Client(_sock, _idx) -- get size of a file function self.file_size(fname) - DEBUG(string.format("%u: size of '%s'", idx, fname)) - local f = io.open(fname, "rb") - if not f then - return -1 + local s = fs:stat(fname) + if not s then + return 0 end - local ret = f:seek("end") - f:close() + local ret = s:size():toint() DEBUG(string.format("%u: size of '%s' -> %u", idx, fname, ret)) return ret end @@ -367,7 +443,7 @@ local function Client(_sock, _idx) if not dlist then dlist = {} end - if not contains(dlist, "..") then + if not table_contains(dlist, "..") then -- on ChibiOS we don't get .. table.insert(dlist, "..") end @@ -388,7 +464,7 @@ local function Client(_sock, _idx)

Index of {path}

- + ]], {path=path}) for _,d in ipairs(dlist) do local skip = d == "." @@ -398,14 +474,19 @@ local function Client(_sock, _idx) if not skip then local fullpath = self.full_path(path, d) local name = d - local size = 0 - if is_hidden_dir(fullpath) or isdirectory(fullpath) then + local sizestr = "0" + local stat = fs:stat(fullpath) + local size = stat and stat:size() or 0 + if is_hidden_dir(fullpath) or (stat and stat:is_directory()) then name = name .. "/" + elseif size >= 100*1000*1000 then + sizestr = string.format("%uM", (size/(1000*1000)):toint()) else - size = math.max(self.file_size(fullpath),0) + sizestr = tostring(size) end - self.sendstring_vars([[ -]], { name=name, size=tostring(size) }) + local modtime = file_timestring(fullpath) + self.sendstring_vars([[ +]], { name=name, size=sizestr, modtime=modtime }) end end self.sendstring([[ @@ -555,9 +636,24 @@ local function Client(_sock, _idx) local vars = {["Content-Type"]=self.content_type(path)} local cgi_processing = startswith(path, "/cgi-bin/") and endswith(path, ".lua") local server_side_processing = endswith(path, ".shtml") - if not startswith(path, "@") and not server_side_processing and not cgi_processing then - local fsize = self.file_size(path) + local stat = fs:stat(path) + if not startswith(path, "@") and not server_side_processing and not cgi_processing and stat then + local fsize = stat:size() + local mtime = stat:mtime() vars["Content-Length"]= tostring(fsize) + local modtime = file_timestring_http(mtime) + if modtime then + vars["Last-Modified"] = modtime + end + local if_modified_since = header_vars['If-Modified-Since'] + if if_modified_since then + local tsec = file_timestring_http_parse(if_modified_since) + if tsec and tsec >= mtime then + DEBUG(string.format("%u: Not modified: %s %s", idx, modtime, if_modified_since)) + self.send_header(304, "Not Modified", vars) + return true + end + end end self.send_header(200, "OK", vars) if server_side_processing then From 18044a9644436f4a83576ed6ac4e7031c60f223e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 9 Dec 2023 13:06:24 +1100 Subject: [PATCH 0033/1335] AP_Scripting: added a home page and ajax support --- .../AP_Scripting/applets/net_webserver.lua | 163 ++++++++++++++++-- 1 file changed, 148 insertions(+), 15 deletions(-) diff --git a/libraries/AP_Scripting/applets/net_webserver.lua b/libraries/AP_Scripting/applets/net_webserver.lua index a1cac978c0205e..c1bac7e97a7775 100644 --- a/libraries/AP_Scripting/applets/net_webserver.lua +++ b/libraries/AP_Scripting/applets/net_webserver.lua @@ -79,6 +79,9 @@ local HIDDEN_FOLDERS = { "@SYS", "@ROMFS", "@MISSION", "@PARAM" } local CGI_BIN_PATH = "cgi-bin" +local MNT_PREFIX = "/mnt" +local MNT_PREFIX2 = MNT_PREFIX .. "/" + local MIME_TYPES = { ["apj"] = CONTENT_OCTET_STREAM, ["dat"] = CONTENT_OCTET_STREAM, @@ -164,6 +167,79 @@ local MIME_TYPES = { ["7z"] = "application/x-7z-compressed", } +--[[ + builtin dynamic pages +--]] +local DYNAMIC_PAGES = { + +-- main home page +["/"] = [[ + + + + + + ArduPilot + + + +

ArduPilot Web Server

+ + +
+ +
+

Controller Status

+
+ + +]], + +-- board status section on front page +["@DYNAMIC/board_status.shtml"] = [[ +
NameSize
NameLast modifiedSize
{name}{size}
{name}{modtime}{size}
+ + + + + + +
Firmware
GIT Hash
Uptime
Arm Status
AHRS Location
GPS Location
+]] +} + +--[[ + builtin javascript library functions +--]] +JS_LIBRARY = { + ["dynamic_load"] = [[ + function dynamic_load(div_id, uri, period_ms) { + var xhr = new XMLHttpRequest(); + xhr.open('GET', uri); + + xhr.setRequestHeader("Cache-Control", "no-cache, no-store, max-age=0"); + xhr.setRequestHeader("Expires", "Tue, 01 Jan 1980 1:00:00 GMT"); + xhr.setRequestHeader("Pragma", "no-cache"); + + xhr.onload = function () { + if (xhr.status === 200) { + var output = document.getElementById(div_id); + if (uri.endsWith('.shtml') || uri.endsWith('.html')) { + output.innerHTML = xhr.responseText; + } else { + output.textContent = xhr.responseText; + } + } + setTimeout(function() { dynamic_load(div_id,uri, period_ms); }, period_ms); + } + xhr.send(); + } +]] +} if not sock_listen:bind("0.0.0.0", WEB_BIND_PORT:get()) then gcs:send_text(MAV_SEVERITY.ERROR, string.format("WebServer: failed to bind to TCP %u", WEB_BIND_PORT:get())) @@ -175,6 +251,13 @@ if not sock_listen:listen(20) then return end +function hms_uptime() + local s = (millis()/1000):toint() + local min = math.floor(s / 60) % 60 + local hr = math.floor(s / 3600) + return string.format("%u hours %u minutes %u seconds", hr, min, s%60) +end + --[[ split string by pattern --]] @@ -316,7 +399,25 @@ function substitute_vars(s, vars) end)) return s end - + +--[[ + lat or lon as a string, working around limited type in ftoa_engine +--]] +function latlon_str(ll) + local ipart = tonumber(string.match(tostring(ll*1.0e-7), '(.*[.]).*')) + local fpart = math.abs(ll - ipart*10000000) + return string.format("%d.%u", ipart, fpart, ipart*10000000, ll) +end + +--[[ + location string for home page +--]] +function location_string(loc) + return substitute_vars([[{lat} {lon} {alt}]], + { ["lat"] = latlon_str(loc:lat()), + ["lon"] = latlon_str(loc:lng()), + ["alt"] = string.format("%.1fm", loc:alt()*1.0e-2) }) +end --[[ client class for open connections @@ -468,9 +569,6 @@ local function Client(_sock, _idx) ]], {path=path}) for _,d in ipairs(dlist) do local skip = d == "." - if path == "/" and d == ".." then - skip = true - end if not skip then local fullpath = self.full_path(path, d) local name = d @@ -586,9 +684,14 @@ local function Client(_sock, _idx) Using 'lstr' a return tostring(yourcode) is added to the code automatically --]] - function self.send_processed_file() + function self.send_processed_file(dynamic_page) sock:set_blocking(true) - local contents = self.load_file() + local contents + if dynamic_page then + contents = file + else + contents = self.load_file() + end while #contents > 0 do local pat1 = "(.-)[<][?]lua[ \n](.-)[?][>](.*)" local pat2 = "(.-)[<][?]lstr[ \n](.-)[?][>](.*)" @@ -613,6 +716,9 @@ local function Client(_sock, _idx) -- return a content type function self.content_type(path) + if path == "/" then + return MIME_TYPES["html"] + end local file, ext = string.match(path, '(.*[.])(.*)') ext = string.lower(ext) local ret = MIME_TYPES[ext] @@ -628,16 +734,23 @@ local function Client(_sock, _idx) path = string.sub(path, 2, #path) end DEBUG(string.format("%u: file_download(%s)", idx, path)) - file = io.open(path,"rb") - if not file then - DEBUG(string.format("%u: Failed to open '%s'", idx, path)) - return false + file = DYNAMIC_PAGES[path] + dynamic_page = file ~= nil + if not dynamic_page then + file = io.open(path,"rb") + if not file then + DEBUG(string.format("%u: Failed to open '%s'", idx, path)) + return false + end end local vars = {["Content-Type"]=self.content_type(path)} local cgi_processing = startswith(path, "/cgi-bin/") and endswith(path, ".lua") local server_side_processing = endswith(path, ".shtml") local stat = fs:stat(path) - if not startswith(path, "@") and not server_side_processing and not cgi_processing and stat then + if not startswith(path, "@") and + not server_side_processing and + not cgi_processing and stat and + not dynamic_page then local fsize = stat:size() local mtime = stat:mtime() vars["Content-Length"]= tostring(fsize) @@ -656,9 +769,9 @@ local function Client(_sock, _idx) end end self.send_header(200, "OK", vars) - if server_side_processing then + if server_side_processing or dynamic_page then DEBUG(string.format("%u: shtml processing %s", idx, path)) - run = self.send_processed_file + run = self.send_processed_file(dynamic_page) elseif cgi_processing then DEBUG(string.format("%u: CGI processing %s", idx, path)) run = self.send_cgi @@ -715,7 +828,22 @@ local function Client(_sock, _idx) end end - if isdirectory(path) and not endswith(path,"/") and header_vars['Host'] and not is_hidden_dir(path) then + if DYNAMIC_PAGES[path] ~= nil then + self.file_download(path) + return + end + + if path == MNT_PREFIX then + path = "/" + end + if startswith(path, MNT_PREFIX2) then + path = string.sub(path,#MNT_PREFIX2,#path) + end + + if isdirectory(path) and + not endswith(path,"/") and + header_vars['Host'] and + not is_hidden_dir(path) then self.moved_permanently(path .. "/") return end @@ -737,10 +865,15 @@ local function Client(_sock, _idx) end -- see if it is a directory - if endswith(path,"/") or isdirectory(path) or is_hidden_dir(path) then + if (path == "/" or + DYNAMIC_PAGES[path] == nil) and + (endswith(path,"/") or + isdirectory(path) or + is_hidden_dir(path)) then self.directory_list(path) return end + -- or a file if self.file_download(path) then return From 583c24d833924f142313f5d3266a2df85a00103f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 10 Dec 2023 07:05:58 +1100 Subject: [PATCH 0034/1335] AP_Scripting: updated docs --- libraries/AP_Scripting/docs/docs.lua | 144 ++++++++++++++++++++++----- 1 file changed, 120 insertions(+), 24 deletions(-) diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index 4f70ca60671fc2..777eb8c8089d95 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -457,46 +457,77 @@ function motor_factor_table_ud:roll(index, value) end local SocketAPM_ud = {} -- desc +function SocketAPM(param1) end + +-- return true if a socket is connected ---@return boolean function SocketAPM_ud:is_connected() end --- desc ----@param param1 boolean +-- set blocking state of socket +---@param blocking boolean ---@return boolean -function SocketAPM_ud:set_blocking(param1) end +function SocketAPM_ud:set_blocking(blocking) end --- desc ----@param param1 integer +-- setup a socket to listen +---@param backlog integer ---@return boolean -function SocketAPM_ud:listen(param1) end +function SocketAPM_ud:listen(backlog) end --- desc ----@param param1 string ----@param param2 uint32_t_ud +-- send a lua string. May contain binary data +---@param str string +---@param len uint32_t_ud ---@return integer -function SocketAPM_ud:send(param1, param2) end +function SocketAPM_ud:send(str, len) end --- desc ----@param param1 string ----@param param2 integer +-- bind to an address. Use "0.0.0.0" for wildcard bind +---@param IP_address string +---@param port integer ---@return boolean -function SocketAPM_ud:bind(param1, param2) end +function SocketAPM_ud:bind(IP_address, port) end --- desc ----@param param1 string ----@param param2 integer +-- connect a socket to an endpoint +---@param IP_address string +---@param port integer ---@return boolean -function SocketAPM_ud:connect(param1, param2) end - --- desc -function SocketAPM_ud:__gc() end +function SocketAPM_ud:connect(IP_address, port) end --- desc +--[[ accept new incoming sockets, returning a new socket. + Must be used on a stream socket in listen state +--]] function SocketAPM_ud:accept(param1) end --- desc -function SocketAPM_ud:recv(param1) end +-- receive data from a socket +---@param length +---@return data +function SocketAPM_ud:recv(length) end + +-- check for available input +---@param timeout_ms uint32_t_ud +---@return boolean +function SocketAPM_ud:pollin(timeout_ms) end + +-- check for availability of space to write to socket +---@param timeout_ms uint32_t_ud +---@return boolean +function SocketAPM_ud:pollout(timeout_ms) end +--[[ + close a socket. Note that there is no automatic garbage + collection of sockets so you must close a socket when you are + finished with it or you will run out of sockets +--]] +function SocketAPM_ud:close() end + +--[[ + setup to send all remaining data from a filehandle to the socket + this also "closes" the socket and the file from the point of view of lua + the underlying socket and file are both closed on end of file +--]] +function SocketAPM_ud:sendfile(filehandle) end + +-- enable SO_REUSEADDR on a socket +---@return boolean +function SocketAPM_ud:reuseaddress() end -- desc ---@class AP_HAL__PWMSource_ud @@ -3111,3 +3142,68 @@ function fence:get_breach_time() end ---| 4 # Polygon ---| 8 # Minimum altitude function fence:get_breaches() end + +-- desc +---@class stat_t_ud +local stat_t_ud = {} + +---@return stat_t_ud +function stat_t() end + +-- get creation time in seconds +---@return uint32_t_ud +function stat_t_ud:ctime() end + +-- get last access time in seconds +---@return uint32_t_ud +function stat_t_ud:atime() end + +-- get last modification time in seconds +---@return uint32_t_ud +function stat_t_ud:mtime() end + +-- get file mode +---@return integer +function stat_t_ud:mode() end + +-- get file size in bytes +---@return uint32_t_ud +function stat_t_ud:size() end + +-- return true if this is a directory +---@return boolean +function stat_t_ud:is_directory() end + +-- desc +---@class rtc +rtc = {} + +-- return a time since 1970 in seconds from GMT date elements +---@param year integer -- 20xx +---@param month integer -- 0-11 +---@param day integer -- 1-31 +---@param hour integer -- 0-23 +---@param min integer -- 0-60 +---@param sec integer -- 0-60 +---@return uint32_t_ud +function rtc:date_fields_to_clock_s(year, month, day, hour, min, sec) end + +-- break a time in seconds since 1970 to GMT date elements +---@param param1 uint32_t_ud +---@return integer|nil -- year 20xx +---@return integer|nil -- month 0-11 +---@return integer|nil -- day 1-31 +---@return integer|nil -- hour 0-23 +---@return integer|nil -- min 0-60 +---@return integer|nil -- sec 0-60 +---@return integer|nil -- weekday 0-6, sunday is 0 +function rtc:clock_s_to_date_fields(param1) end + +-- desc +---@class fs +fs = {} + +-- desc +---@param param1 string +---@return stat_t_ud|nil +function fs:stat(param1) end From ded1cdaa2a6f625eb22cfbf6aa09d02ba918e9f1 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 10 Dec 2023 08:06:22 +1100 Subject: [PATCH 0035/1335] AP_Scripting: fixed webserver warnings --- .../AP_Scripting/applets/net_webserver.lua | 26 +++++++++---------- 1 file changed, 13 insertions(+), 13 deletions(-) diff --git a/libraries/AP_Scripting/applets/net_webserver.lua b/libraries/AP_Scripting/applets/net_webserver.lua index c1bac7e97a7775..ac9df70379b864 100644 --- a/libraries/AP_Scripting/applets/net_webserver.lua +++ b/libraries/AP_Scripting/applets/net_webserver.lua @@ -23,7 +23,7 @@ assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 6), 'net_test: could // @Values: 0:Disabled,1:Enabled // @User: Standard --]] -local WEB_ENABLE = bind_add_param('ENABLE', 1, 0) +local WEB_ENABLE = bind_add_param('ENABLE', 1, 1) --[[ // @Param: WEB_BIND_PORT @@ -62,11 +62,15 @@ local WEB_BLOCK_SIZE = bind_add_param('BLOCK_SIZE', 4, 10240) --]] local WEB_TIMEOUT = bind_add_param('TIMEOUT', 5, 2.0) +if WEB_ENABLE:get() ~= 1 then + gcs:send_text(MAV_SEVERITY.INFO, "WebServer: disabled") + return +end + local BRD_RTC_TZ_MIN = Parameter("BRD_RTC_TZ_MIN") gcs:send_text(MAV_SEVERITY.INFO, string.format("WebServer: starting on port %u", WEB_BIND_PORT:get())) -local counter = 0 local sock_listen = SocketAPM(0) local clients = {} @@ -77,8 +81,6 @@ local CONTENT_OCTET_STREAM = "application/octet-stream" local HIDDEN_FOLDERS = { "@SYS", "@ROMFS", "@MISSION", "@PARAM" } -local CGI_BIN_PATH = "cgi-bin" - local MNT_PREFIX = "/mnt" local MNT_PREFIX2 = MNT_PREFIX .. "/" @@ -282,9 +284,7 @@ end return true if a string starts with the 2nd string --]] local function startswith(str, s) - local len1 = #str - local len2 = #s - return string.sub(str,1,len2) == s + return string.sub(str,1,#s) == s end local debug_count=0 @@ -338,7 +338,7 @@ function file_timestring(path) end local mtime = s:mtime() mtime = mtime + BRD_RTC_TZ_MIN:get()*60 - local year, month, day, hour, min, sec, wday = rtc:clock_s_to_date_fields(mtime) + local year, month, day, hour, min, sec, _ = rtc:clock_s_to_date_fields(mtime) if not year then return "" end @@ -520,7 +520,7 @@ local function Client(_sock, _idx) if endswith(path,"/") then path = string.sub(path, 1, #path-1) end - local dir, file = string.match(path, '(.*/)(.*)') + local dir, _ = string.match(path, '(.*/)(.*)') if not dir then return path end @@ -646,12 +646,12 @@ local function Client(_sock, _idx) local eval_code = "function eval_func()\n" .. code .. "\nend\n" local f, errloc, err = load(eval_code, "eval_func", "t", _ENV) if not f then - DEBUG(string.format("load failed: err=%s", err)) + DEBUG(string.format("load failed: err=%s errloc=%s", err, errloc)) return nil end - local success, err = pcall(f) + local success, err2 = pcall(f) if not success then - DEBUG(string.format("pcall failed: err=%s", err)) + DEBUG(string.format("pcall failed: err=%s", err2)) return nil end local ok, s2 = pcall(eval_func) @@ -719,7 +719,7 @@ local function Client(_sock, _idx) if path == "/" then return MIME_TYPES["html"] end - local file, ext = string.match(path, '(.*[.])(.*)') + local _, ext = string.match(path, '(.*[.])(.*)') ext = string.lower(ext) local ret = MIME_TYPES[ext] if not ret then From 867e9c6799ec29163d2a299f975d191cc3f3f2d9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 10 Dec 2023 11:30:11 +1100 Subject: [PATCH 0036/1335] AP_RTC: fixed build on arm --- libraries/AP_Filesystem/posix_compat.h | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_Filesystem/posix_compat.h b/libraries/AP_Filesystem/posix_compat.h index c899d81332ee98..4ccf56b5c5f43e 100644 --- a/libraries/AP_Filesystem/posix_compat.h +++ b/libraries/AP_Filesystem/posix_compat.h @@ -21,6 +21,7 @@ #include #include #include +#include #ifdef __cplusplus extern "C" { From ffb7328ede61f79a397b3da381270fa5d9bc482c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 10 Dec 2023 11:40:18 +1100 Subject: [PATCH 0037/1335] AP_Scripting: review fixes thanks Pete! --- libraries/AP_Scripting/applets/net_webserver.lua | 2 +- libraries/AP_Scripting/docs/docs.lua | 2 +- libraries/AP_Scripting/examples/net_test.lua | 8 ++++---- .../AP_Scripting/generator/description/bindings.desc | 2 +- libraries/AP_Scripting/lua_bindings.cpp | 4 +--- 5 files changed, 8 insertions(+), 10 deletions(-) diff --git a/libraries/AP_Scripting/applets/net_webserver.lua b/libraries/AP_Scripting/applets/net_webserver.lua index ac9df70379b864..4355fa6006e878 100644 --- a/libraries/AP_Scripting/applets/net_webserver.lua +++ b/libraries/AP_Scripting/applets/net_webserver.lua @@ -71,7 +71,7 @@ local BRD_RTC_TZ_MIN = Parameter("BRD_RTC_TZ_MIN") gcs:send_text(MAV_SEVERITY.INFO, string.format("WebServer: starting on port %u", WEB_BIND_PORT:get())) -local sock_listen = SocketAPM(0) +local sock_listen = Socket(0) local clients = {} local DOCTYPE = "" diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index 777eb8c8089d95..856105481eaba2 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -457,7 +457,7 @@ function motor_factor_table_ud:roll(index, value) end local SocketAPM_ud = {} -- desc -function SocketAPM(param1) end +function Socket(param1) end -- return true if a socket is connected ---@return boolean diff --git a/libraries/AP_Scripting/examples/net_test.lua b/libraries/AP_Scripting/examples/net_test.lua index 1db3e45f638067..b83fa2f8f4ba97 100644 --- a/libraries/AP_Scripting/examples/net_test.lua +++ b/libraries/AP_Scripting/examples/net_test.lua @@ -44,11 +44,11 @@ local function test_ip() end local counter = 0 -local sock_tcp_echo = SocketAPM(0) -local sock_udp_echo = SocketAPM(1) -local sock_tcp_in = SocketAPM(0) +local sock_tcp_echo = Socket(0) +local sock_udp_echo = Socket(1) +local sock_tcp_in = Socket(0) local sock_tcp_in2 = nil -local sock_udp_in = SocketAPM(1) +local sock_udp_in = Socket(1) assert(sock_tcp_echo, "net_test: failed to create tcp echo socket") assert(sock_udp_echo, "net_test: failed to create udp echo socket") diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index 6f77cc8124a980..3c0c37a7a936ae 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -537,7 +537,7 @@ ap_object AP_HAL::I2CDevice manual read_registers AP_HAL__I2CDevice_read_registe ap_object AP_HAL::I2CDevice method set_address void uint8_t'skip_check include AP_HAL/utility/Socket.h depends (AP_NETWORKING_ENABLED==1) -global manual SocketAPM lua_get_SocketAPM 1 depends (AP_NETWORKING_ENABLED==1) +global manual Socket lua_get_SocketAPM 1 depends (AP_NETWORKING_ENABLED==1) ap_object SocketAPM depends (AP_NETWORKING_ENABLED==1) ap_object SocketAPM method connect boolean string uint16_t'skip_check diff --git a/libraries/AP_Scripting/lua_bindings.cpp b/libraries/AP_Scripting/lua_bindings.cpp index 8020da37e92c0e..0059fb11509949 100644 --- a/libraries/AP_Scripting/lua_bindings.cpp +++ b/libraries/AP_Scripting/lua_bindings.cpp @@ -770,8 +770,6 @@ int lua_get_SocketAPM(lua_State *L) { const uint8_t datagram = get_uint8_t(L, 1); auto *scripting = AP::scripting(); - lua_gc(L, LUA_GCCOLLECT, 0); - if (scripting->num_net_sockets >= SCRIPTING_MAX_NUM_NET_SOCKET) { return luaL_argerror(L, 1, "no sockets available"); } @@ -829,7 +827,7 @@ int SocketAPM_sendfile(lua_State *L) { auto *scripting = AP::scripting(); if (scripting->num_net_sockets == 0) { - return luaL_argerror(L, 1, "socket close error"); + return luaL_argerror(L, 1, "sendfile error"); } auto *p = (luaL_Stream *)luaL_checkudata(L, 2, LUA_FILEHANDLE); From 75fca4c1715afb7f9545065adeb5f0de30c78646 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 10 Dec 2023 13:58:03 +1100 Subject: [PATCH 0038/1335] Tools: fixed AerobaticsScripting test we no longer allow open() on directories so that we match ChibiOS FATFS --- Tools/autotest/arduplane.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index fb78e2c186b536..5c76db5d35d888 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -4515,7 +4515,7 @@ def AerobaticsScripting(self): self.customise_SITL_commandline( [], model=model, - defaults_filepath="", + defaults_filepath="Tools/autotest/models/plane-3d.parm", wipe=True) self.context_push() From 375a940b51f4f6f310c4d7e5cb06c719981ffe79 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sat, 9 Dec 2023 13:54:26 +0000 Subject: [PATCH 0039/1335] AP_IOMCU: make adc interrupt driven --- libraries/AP_IOMCU/iofirmware/analog.cpp | 127 +++++++++++++++---- libraries/AP_IOMCU/iofirmware/analog.h | 13 +- libraries/AP_IOMCU/iofirmware/iofirmware.cpp | 8 +- 3 files changed, 116 insertions(+), 32 deletions(-) diff --git a/libraries/AP_IOMCU/iofirmware/analog.cpp b/libraries/AP_IOMCU/iofirmware/analog.cpp index e2c6f820810274..1da6d7f4e461fb 100644 --- a/libraries/AP_IOMCU/iofirmware/analog.cpp +++ b/libraries/AP_IOMCU/iofirmware/analog.cpp @@ -13,9 +13,9 @@ along with this program. If not, see . */ /* - analog capture for IOMCU. This uses direct register access to avoid - using up a DMA channel and to minimise latency. We capture a single - sample at a time + analog capture for IOMCU. This uses direct register access to avoid + using up a DMA channel and to minimise latency. We capture a single + sample at a time */ #include "ch.h" @@ -25,64 +25,135 @@ #if HAL_USE_ADC != TRUE #error "HAL_USE_ADC must be set" #endif +// we build this file with optimisation to lower the interrupt +// latency. +#pragma GCC optimize("O2") + +extern "C" { + extern void Vector88(); +} + +#define STM32_ADC1_NUMBER 18 +#define STM32_ADC1_HANDLER Vector88 + +const uint32_t VSERVO_CHANNEL = ADC_SQR3_SQ1_N(ADC_CHANNEL_IN4); +const uint32_t VRSSI_CHANNEL = ADC_SQR3_SQ1_N(ADC_CHANNEL_IN5); + +static uint16_t vrssi_val = 0xFFFF; +static uint16_t vservo_val = 0xFFFF; +static bool sample_vrssi_enable = true; +static bool sampling_vservo = true; /* initialise ADC capture */ void adc_init(void) { - adc_lld_init(); rccEnableADC1(true); + ADC1->CR1 = 0; + ADC1->CR2 = ADC_CR2_ADON; + + /* Reset calibration just to be safe.*/ + ADC1->CR2 = ADC_CR2_ADON | ADC_CR2_RSTCAL; + while ((ADC1->CR2 & ADC_CR2_RSTCAL) != 0) + ; + + /* Calibration.*/ + ADC1->CR2 = ADC_CR2_ADON | ADC_CR2_CAL; + while ((ADC1->CR2 & ADC_CR2_CAL) != 0) + ; /* set channels 4 and 5 for 28.5us sample time */ ADC1->SMPR2 = ADC_SMPR2_SMP_AN4(ADC_SAMPLE_28P5) | ADC_SMPR2_SMP_AN5(ADC_SAMPLE_28P5); - /* capture a single sample at a time */ + /* capture one sample at a time */ ADC1->SQR1 = 0; ADC1->SQR2 = 0; + + ADC1->CR1 |= ADC_CR1_EOCIE; + + nvicEnableVector(STM32_ADC1_NUMBER, STM32_ADC_ADC1_IRQ_PRIORITY); } /* - capture one sample on a channel + capture VSERVO in mV */ -static uint16_t adc_sample_channel(uint32_t channel) +void adc_enable_vrssi(void) { - // clear EOC - ADC1->SR = 0; + sample_vrssi_enable = true; +} - /* capture one sample */ - ADC1->SQR3 = channel; - ADC1->CR2 |= ADC_CR2_ADON; +/* + don't capture VRSSI + */ +void adc_disable_vrssi(void) +{ + sample_vrssi_enable = false; +} - /* wait for the conversion to complete */ - uint32_t counter = 16; +/* + capture one sample on a channel + */ +void adc_sample_channels() +{ + chSysLock(); - while (!(ADC1->SR & ADC_SR_EOC)) { - if (--counter == 0) { - // ensure EOC is clear - ADC1->SR = 0; - return 0xffff; - } + if (ADC1->SR & ADC_SR_STRT) { + return; // still waiting for sample } - // return sample (this also clears EOC flag) - return ADC1->DR; + /* capture another sample */ + ADC1->CR2 |= ADC_CR2_ADON; + + chSysUnlock(); } /* capture VSERVO in mV */ -uint16_t adc_sample_vservo(void) +uint16_t adc_vservo(void) { - const uint32_t channel = ADC_SQR3_SQ1_N(ADC_CHANNEL_IN4); - return adc_sample_channel(channel); + return vservo_val; } /* capture VRSSI in mV */ -uint16_t adc_sample_vrssi(void) +uint16_t adc_vrssi(void) { - const uint32_t channel = ADC_SQR3_SQ1_N(ADC_CHANNEL_IN5); - return adc_sample_channel(channel); + return vrssi_val; +} + +static void adc_read_sample() +{ + if (ADC1->SR & ADC_SR_EOC) { + + ADC1->SR &= ~(ADC_SR_EOC | ADC_SR_STRT); + + if (sampling_vservo) { + vservo_val = ADC1->DR; + if (sample_vrssi_enable) { + /* capture another sample */ + ADC1->SQR3 = VRSSI_CHANNEL; + ADC1->CR2 |= ADC_CR2_ADON; + sampling_vservo = false; + } + } else { + vrssi_val = ADC1->DR; + ADC1->SQR3 = VSERVO_CHANNEL; + sampling_vservo = true; + } + } +} + +OSAL_IRQ_HANDLER(STM32_ADC1_HANDLER) { + OSAL_IRQ_PROLOGUE(); + + chSysLockFromISR(); + + adc_read_sample(); + + chSysUnlockFromISR(); + + OSAL_IRQ_EPILOGUE(); } diff --git a/libraries/AP_IOMCU/iofirmware/analog.h b/libraries/AP_IOMCU/iofirmware/analog.h index 4871cdb32f7fc5..0e0622b3860cd7 100644 --- a/libraries/AP_IOMCU/iofirmware/analog.h +++ b/libraries/AP_IOMCU/iofirmware/analog.h @@ -9,9 +9,18 @@ void adc_init(void); /* capture VSERVO */ -uint16_t adc_sample_vservo(void); +uint16_t adc_vservo(void); /* capture VRSSI */ -uint16_t adc_sample_vrssi(void); +uint16_t adc_vrssi(void); + +/* start another update */ +void adc_sample_channels(void); + +/* capture VRSSI */ +void adc_enable_vrssi(void); + +/* don't capture VRSSI */ +void adc_disable_vrssi(void); diff --git a/libraries/AP_IOMCU/iofirmware/iofirmware.cpp b/libraries/AP_IOMCU/iofirmware/iofirmware.cpp index 3050a5b8e07cb4..3d1cce6f62d1e9 100644 --- a/libraries/AP_IOMCU/iofirmware/iofirmware.cpp +++ b/libraries/AP_IOMCU/iofirmware/iofirmware.cpp @@ -671,13 +671,15 @@ void AP_IOMCU_FW::process_io_packet() */ void AP_IOMCU_FW::page_status_update(void) { + adc_sample_channels(); + if ((reg_setup.features & P_SETUP_FEATURES_SBUS1_OUT) == 0) { // we can only get VRSSI when sbus is disabled - reg_status.vrssi = adc_sample_vrssi(); + reg_status.vrssi = adc_vrssi(); } else { reg_status.vrssi = 0; } - reg_status.vservo = adc_sample_vservo(); + reg_status.vservo = adc_vservo(); } bool AP_IOMCU_FW::handle_code_read() @@ -798,8 +800,10 @@ bool AP_IOMCU_FW::handle_code_write() // or disable SBUS out AFIO->MAPR = AFIO_MAPR_SWJ_CFG_NOJNTRST; + adc_disable_vrssi(); palClearLine(HAL_GPIO_PIN_SBUS_OUT_EN); } else { + adc_enable_vrssi(); palSetLine(HAL_GPIO_PIN_SBUS_OUT_EN); } if (reg_setup.features & P_SETUP_FEATURES_HEATER) { From 4a48dc2dde55302a736bb3177e61bd2d67c3e87f Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sat, 9 Dec 2023 14:01:51 +0000 Subject: [PATCH 0040/1335] IO_Firmware: fix adc reading --- .../IO_Firmware/iofirmware_dshot_highpolh.bin | Bin 46796 -> 46996 bytes .../IO_Firmware/iofirmware_dshot_lowpolh.bin | Bin 46796 -> 46996 bytes .../iofirmware_f103_8MHz_highpolh.bin | Bin 41028 -> 40544 bytes .../iofirmware_f103_8MHz_lowpolh.bin | Bin 41028 -> 40544 bytes .../iofirmware_f103_dshot_highpolh.bin | Bin 46788 -> 46988 bytes .../iofirmware_f103_dshot_lowpolh.bin | Bin 46788 -> 46988 bytes .../IO_Firmware/iofirmware_f103_highpolh.bin | Bin 41028 -> 40544 bytes Tools/IO_Firmware/iofirmware_f103_lowpolh.bin | Bin 41028 -> 40544 bytes Tools/IO_Firmware/iofirmware_highpolh.bin | Bin 41028 -> 40544 bytes Tools/IO_Firmware/iofirmware_lowpolh.bin | Bin 41028 -> 40544 bytes 10 files changed, 0 insertions(+), 0 deletions(-) diff --git a/Tools/IO_Firmware/iofirmware_dshot_highpolh.bin b/Tools/IO_Firmware/iofirmware_dshot_highpolh.bin index 83a7e2b6299695df11f9bb41ab3e2a6a4570dcdc..362fdf5ffa84648396d91b15c7e082d563589c74 100755 GIT binary patch delta 11272 zcmaKS3tUvy_W#~z9t;XPh{Q|e3?l*(I)Er@Di1xpM0}=M7D&{PXqZ}*5AYeJmbQIA z3R6mNSs>C4bpk8PZr5K>*44WH(pyQS-VQ0AGtBG%-GJ5oe{R3|e7jBCWf#q z)KI^Oe&?gxW%riL+4O!H!OM|)uq$9nK<-;uE`o^j3in#mWGd{OYs3F`aRaZeJs5Dq{sk zlfRd&Q;GRX0k7O>`{zI+o@G0Xsah{NTxH)FC7RAme&KzWtI^U&>b)}r`D2#jml(KT z^(e>PqD197yFMcCHklqRdCA+@4!=hRivbuAR&}wssY zq4}U2BL5Sk!RNftUh4QSGFQR-9B2Y`z?@#$K%{xuqoAbomC_l+6h^M66K{Dedoo}H zJy~-r?MF=_mU5PR=QT~4MxLk0@E8XlM~f#~>YwE$k99;y(UQgFC8x7BA!c7b3cgXe zg}PW@7ve>!vA!{sQGKt5&j`C6c;Y0%N?8&T>Mo#J!DRcX6x;A9n?LvwXuoanI6p3| zHb4`WXr+GWZawo3PoiJ2iQ%8o544UDy4P^}5K zLh3u8EC2RO5gXIGz@vP@9AY~4VG~UwGDZ7GYUPZhm@eMQyB$7)G@m}2=}{Wq@5x&) z^^vq$#s-5`n?tQW)&i+I10`&{jMkgIYnnRXZWRx}=m*3SgVwwLo`@F&ZW!4}+IX#l8ri!;?+yN!D^DgfYdT5MS=E@#4OK-!w4_5bj-gvjFF_T4 z;VQ)qlmYW%s!U66GQf~!o-)*VVa|_6g$q*}+25iP1Y;v}N6pY{wU|RKyFYrcFsqS0 z9etzx2lu#~*!-IO^`b`^=+Q~WI+G;G>GmJw78^0hJPn*<#lxPbeOU+chrLh4(hN;m-&k#nkT^{> z!ype~;jz!q*V(Sv9D0I%A6w_o)hVuBP1lrYB@&z0Lgc~hje8?e$N76-6=t1ei{mo; zKjfsD2HPZvW&)Sk*|-tI_Bln#@Z0>PV1A}LiCL7^tCiE%t5vXfFI)IlUUrfV9v(67 zl(TxZOF8WD&2lN7j>lH}WND?3Z#C;(%4Qd7^q!I@dlGSKF_-d%tNA$DnkX4f(UR~N zDp#--!_UyavhgEE(|v6DhSHG{% z)|Mb@aVbIeKKrN?1b%pzOVO~RL^J(`RV9Y|?nmi!CvlRIb7`N~Hzf9@x}FNpjvPm; z8BOx^+v1Fdb^ISyl#*@xn^?b53A(pVaiy3%DoO}C#TJiRUEX02&JiVZz7b1P>r2FD zpam#_;1y6As0K(sSPVb}EWl5|4Nm(L@dwc6zUU56?SnFSPXT|2ifcM zcwsvBTK6n`A&s(yqrJ6yS+BCP(SytHwR@BVmtIbGM&uCFAS*ZSMwM?2BA@80UZ}B# zT6brNi+X4uY>iJmdigQ0YK4{%tp20<;-3m<2NQ{H~M;1`NCnjM$d|X=03;Z}M z_wRTf$t=xC22E}ln@Qxko-ugN?taejBqN>I{hZ<%jdWJ`Q}T>LI=%au;z>e!yeBCq zDSK3ASV;b;oKe}Mr-bAa`MR5n4T6AH&a;csNcL%RSo!em;aPh5yxU@qn=()|FNw=B z=i}gA`u*d?{E@of!o7}ai(8r2ZQn{vM0Rw6KaE6&XPdK-H!U3Vbj)qa)X15xkZdt) zFy3q2;W^>i>mV1BKRDC&Q*w$&slmC!7yge*aitIpt`YxD8_F;(JTABI6gM4u ztBnlpXfv`U;~vM+ereojJpJyo2`y@U%Y8xAd&GP2c|^S€>6lR@f4^Mbm>r~$N zu-g+vx`PEw45wA~NfW12`Zjw$6Uz|w6;YxMnG<#7>rpwqTlF4@y z?@@2YPpngl3iN?>=at?+7qc%jZB(w`mK7_&v$y4B(F@FLN?4!CE>YrUAo~6K;Zyoh`V||KJDv_= z&*Z+uC8nBF(_rIEZDlxE;@WSe4wf`!I;nrGj}$1`RIy?LZd2z9Q+{2TKrQFnNkSh9 zKGV`ix+*(7$~(^YI{f-av7)JyL-j3|QYs4EJy>Hjx3!VjJFSVOciNx=?8B)U@T~gg zh0!%ECNG?ZvaGxUx}Uw77fNOJ3DTEX%(Pu}3p+DyK2{-o`Z`mIY^>}N(GuAET54-m*IVk;mHD(| zz0SWbTGGl-+Raitb{fsr$_4fx+vpR-z>*(G@LFK!MiX1>fv9pjEQg`Nr9^o&Ip11? zLTbAz

j%jqhUaKvqgoQ`SgPSt-(nT5ab&&$*Q&>UQ-ZI5La7KrOm)-ySE?2`&2A z7n^9*;OrTyxikz%hQ{Hgm`iBH7-?>?AV1t?E`hZ1;o`s?os=nUS0~jTa_C11b7Y6z zTq5jxq?jhHm;UPLRNnPDH!@M0C#6VG%TIi>+)AlBYx3DvUAKp-kKNUz%Qi&uW<2D7 z_%Lv08DXK80i|%o*Zps3`k*GZdfp3|G4BTx`;>smGpu^{%7Z%tG;%+cnxjkFtsB&* zEw-QFJ;8=#J!IBuWUb0dA9{rtxQ*}g05lTw&`Te1`xaS>Y1}$L z8=LLh`7v}f(>9Uda48?K&mUPtcd_yLp}s=@TbKAj`>E>} z*v6v#JSay)_fuCenciSI1*UR7BV2c!%F0t%!qfn%pA?RI+MQpwN2J$Y*BT10Yx*5Y zTXNk?STBuiiVh*-*X=_iw@zMtU8gsEaX2Xbx=wTAx{pwJonlLFa`iFk_j;6nc=GPJ zmsT9#ofh2`#7DP=G;tMaRZA*1)%w7Z8Y~@9r?FiH0r2&X6~xgA?AwAc8q4ejqv^9O zenBDqj_p`rGCQ3#>E>~5+|AZ2i>b+_XjLlq?Oxyc1^;LhO9c6Ic4Tw!?kMXzQmF&qPmo+XAeY<^+VxDQ;_bzCh&@qBt3iJQ@)tCej_ z!@oVQkBz=$;gJ;=iN4wDJwX`$bN5W%bX;pQpvBqjeBtwg$H8_k5Q7H&)*A$r zy=n?qJ&$y>=(UmsuFHL@p%M8nxs=N+t0+de;9|>)vXiFRgRl|TrRiF)ScB>i11b=L9C>NSf+N=V!nl-fb)N9_sms31>}Z?IcMrtTTxYtI$60ef9!k&k^!2eMxt z3-%UcgYjqLK{?+9KPq&2AT*Y?idUL(M0 z9UmUzeB-g_5zV^ZJrg#2^(BZV9Et`yVx9ZLEUVD8nbaFNx@6)eWTyJvRX^%80cWvzfH9B9{d2SiERNiBRn9WVZL``*R zL9O2}uCLp-@=)EiM#qyTiLf*&2kweTxn-wPPwlH6m37o~W${Pq>1wB9>v}8gaK||f zZ5b3M{iCh>_;_Y@wH;ji!J4R0Rk}kt?Eyf^iu&jp=Gi4=ORiQ z{HIV@*P0-`Bses)*VfW2Z>4#+pm(?o?o-c=B+++TcA`w*I-$1I)__at)+Js!WT#iA z05zxPjmYCU+=6X|(((pt%85aRr&iHm$F)W~yjPmPvB5Vr6r7o5|jH4-t?2!3@s&z^ZQDdJ-% z9i_n!ow_M(sJ0+h@Z-SIV!{|Ik{q74^bimZt2p24$#dmACmh-U#H1*Dn3qXPG5=&n^raxgCKu%(tyRidXkW=I+*v; zN*H%=qLZ5hQIPjBx-{HB>Lemps6i_|SXWV;Qs-2DV2MkkXeN7bX@QQncbc79I)eU_ zbu2Z-_;fWNH`-{TZ|uKY$BK6BLklhoa>IsNFG)CN5C`{m|6?|8SzMHtOD9D)is*xk zJ72f86&)yZc|*_fC&)j!oXRNn(y|!yF2|xq^Am}U#C)iL9&svfI{3|>jx#UdUg@ni zr($H^E}NgV<#dnBZD`P11UUtVi^0ZI@o>=jk?K$^xT6_uJanSRVwf6vE>Y=_Ay>NZ zmKh{kZFMS5Y|ZjGdW5~RJRpRRl9$!wq^R0)RNmz2@xN!CVgI{4B8g}7GZ$M8D>L-8 zLGrE>6xPH>pBXm`#xS=Y3I<$P9-O`vRPn$ke zCMkAhr9HYXSu&Nu!lzI<;8ealWDifqD3w!GN?xboPFosO?%%;@E4vKJg ze12H>X-pJPcnKD-3_u7CqjD$*po`qAsI2vsv`2JD1^F=t8KRd4W<^7rFS5^{35Rd{ z%QNQOckSP`8F)QwYEk|aV37JW3i8h<=`h+V$XzFKv5>vH_Ye0ThBb0k)H#O3-jv$V zI~3hT#J}Al^dKtv<;O01vOe* z?1QUYci4Drwo#@fts3+!xnn9 zQgWR^>{1rGgX#*cLUwaIG4qSs)(_yHLV=u$pt9S~MF?Y^ENDe$zYU%{ZFg^tM?PSS zSBwg{h0r)Rx>O#kW=g}PF%pp*SmTONVf_c}>lM>tRo9y1x(*|bf&QNJDyh&)iBbY| zq1ftCc6v6#PM_#n4>$f|o1INxIa=890()WQM&aP5`T?sJP*dNSy-h;SOw~jLe%Ec9 z_8~FcK=-h$=^JVXN`2Xm)j7D}TwNU+@K=xAb~m3Z`EAI#m|uBl%ov9rldCF84vN02 z%6O-Dma44onheFSapcLXp?u4`RHc~BE?>y@SFhG!*RZgI;jFpbB2;|Hel4GdyHt8b z5`THF;$AwJy-~5e+@lO{sz8qn4H`t$FL?N;Hjgr-Y3pyizxDD$nyP=}HTUw2O|`%A z-tFb-o0@;)z17QezTfg2@3mguukT;^kg$Dge#Gr{&D!&k(M}SHFGuM^mwjIl`Ly>G z9Cz|yry-~3-K+ckp8BQhRteIVPTySL93Rt1?U6}7QzAtoZ|{P*sZTbM&pP|`=I~%m z6!JEn!8Wx^d7oArD`zs(L3J@p%dNemR}uePiEjiMBsLS*7hvK~ABYFlakyKUXxIl?x43ZLs8 z-u_d()gE4HFYo13Y;L7W*RknU1-Kj6SMAZ~?!|R>FPrhg7Y2_q>?Hpt!zwq;4b|pA z=}Ee3F>0PqDWu6IJmN>{CxNmPEw^}Ti6r0Z=#(06QA7Q7`2US#T) zu)qXYnsmk55lrPc$fQsDxs6Li)i2+&LlB0ZVm@2%8xVv~+(rZ}wG#L4JctOed0Rv1 zQnq~SY*?euwuXjQI0Z8i&7~C(;K$kT!ap*)&8#QzRmL2zAGS@Pl(4v$|AD8DMFnsl zMw9c6)qkP+XF~l7gHlQ}M3%}vry}#)o`L5B+tcwpu>BC8sXKVuwkweB-(f{cxAUmx z?Lc`>eYW1cR%D0|ZsBI+Ur!Gs6SYr!@V=m<`nHSE$=6ewI#2oNi4GmAdtIgT{IFSc9pfe6l zgn%#N?lzv+%!+oeqbpeZZeFKpPoei*lnMyvmxV2RCW3c<&p152_a@>wzWcdkFQd&& zw=W~|Y8R0|?b3!GK3Jjf323y6BF zYp66{`lVL}M;T5a$1d;7&~c81#q6Kyn|{*2idOZVVUm&qxdH4{^X8foEw4cN;bdCjbKDOcTW<7;Dui4OL`YY|yl4lY^Z(Bs;`m1-G=T>>0C z4i6xE=0Z*S%tF5L`En5Xx%Uj1hJ*MJaH`9reDC%sH{CtvdIO6)G?5mwMTcU;{`$KY z+eA_*0;?XSt=s;%ltrxJP^z%l&D2AiH3$T-?+ypB{f7slWB<0XD~AWNbKNf&`Aamo zAM|j=nt>31i;b=+1bvnrs99R>QYP4lmZor{q&Fdai&^k>=uKV-<9dVgaIOy28?c1_?rGWBRoonhmG1K`2=B&?*2`MRlaWV`p`{Gca-(4 z>Ge>rI{AFHw>ttfsfj>rZe1-HS;4*Oa4}6|y$GZ!Fhh_)^Vt_ax9=O{y zm%Ez|$bcL$8~G0a^Zy`MfOHX1ERk{pEN|e^{N-0<)Faho0-vm1TkY5D;B49f3 z0I&*J1KcgY2kES>XdLtaum#u#>;Ue{-0k?7T*v|C8}MiVih$|BS-=;){uG7I^y0@U z=m^jW*Z~(nA*Tbpxjf(p1Op}@5{LoffOsGYXhdD-fmXoQi?egc%D*uxrRCPAlU*2Wkf*As3AI z1Dppm@cMvf!C$lmbpYEoqoc^Pfqw>=y?Ei`C!b-Xjz2uy=R=GW2mnF=5f}>G3nT!^ zz(inDH)Zc1e`U8fd=3pum!jb6j}&L;RkE)uNuxqGuu)BQnvMePdV-7 xdOVbRJUuTi5&e((y+qiso^<~A_u${KJwNv_O1{t%GUPP=CUvU*u@jF8{}1Njf#(1K delta 10988 zcmaKy3tUyj+W%+PzOYeH5RjY5-fWSZmko%brgD+RO++-)N)se&lb7(8S}LGYPHI(c^YZz8XJ*YjGizqn zGtbOCo9(}HU)|+Kl~baP97;4DIYcuO?CFgcA&x@+AKBATGb(n}qGLo;15BV31T+(k zZw=8zg7F{^6oJ*Cx~68-U{xw44%O^S^iHZJn&90;la2UL&Gj_05MTC~!)ewC-gfe%(@cnh_mgNGiM6!{h0x^E zOcK#AH>7ZG@h)SUK)GFoJ`usjY7f;VI>FkW|Ik$$QdpXKWl8x_NVbw;G)2?wA^hO* z$lXOC1PgunM+IA z8J{_->K4*k%EEkgerln`MfBH-HsABD@-h9xpJ+WJ-ty(?M0V9Ty#G=u znm;Rzn8^vJna7~Sz!{QDeCX8jR5)Z&N95lp1<|~RkiiNDEf|^=fXTtc?9}300pdeb zh!;BVNwi18+1G=1Q4K5cE2gip3w{%$8l*ylPxB8RO5Wo#(bq{w4K6Xv`JU83d`vEJ z2vSFhOY~=n{_FgxmFN!**&@XovWc?WK&UW+wffh4)?1EA5rg6zPqU=~dip7=2?#G+ zJ)CGJfxF-gXpSP9tB5}v_MfaozMMCwHy+m;|4}XsdHsP6^)mqLm6_Aq-VMa$!Mmk1 zi7t$Er4vsfg^eCuNlmPIu#P^>{yumLeUt?TMwRU?&%giTiU#TBHoY)FQHQY~wb}0} z;_`*^7xD!klH97$r{$$(pOummmKA0d9fQP^>aqvwkEwo(l%GJ&o2!E2%C0m>uWM;6 z5vs~*#Cy^+hAmQF#J!v8#y08c_+M{suBwyXG<4mh`b|hZt=%F`Px$%frmBlWrL_rl z(yQ7wX==hhZbs#7t{P;lld25gF8M^dZ}=PgF)+C7^P3sJ^)KF3wJWXc{_c;0b3=_+ zmMDxrEUC>T=)zgUU;a@3+DE><<)KS!GpYU;^ET-$A<<>`H-411U8$Qmze{O{zzrTEqIXJ>5Dc~mKAJb^JcRKqFI4X>_gG#o@>0Lpv?0`kQcY9k5JuI#dOmdM{lE`S$WvxW zNNBu-*K#`3tqPFUC@i~9R*xjZ^gYoLB(vn*>FiDe7Y8pL+ zDQtCgI9Gd|y%n9n%{$KiCwk^^J8ZQC6g-_O4^5f#TAK1A>~n5miqAaB>;u)PJI>N# z?$Fz8bZkIgw&g})Ic#Zvmx|Xm(g+=&n9B*1t&v5CkxP&}w^0X+_@y(NADK&F6|cvq zNZTfI!i&!OqJxn6#i`>Rn5t7~BsMr92&+G&=?^aw;#fH$id zH9B^mUCV2JpOO?z$qYNuYxylw)r>7tHLTa026-vAwXoZxA|{@(*KKr&{p{Y^4)IC* zGaJ3KmHg-T+SCs5HwS6)oR%-R60!F%hnVbaJ4&`C@;2v)i_ZvEw^k*#C!1>7 zjf8@jC6<831I9gRv>gk_M74HvE#_iiOmef558wx0f!cSa`ly91Y(ZkMN-o>ZHY8@y z$?Vg_Tz!?LfOm*jE&X??clX_cs2{rtg@3<)L=@V?i zxQ%6^B{)~h>kDPI&+;bPxxfgHLvStPDv%6n!9j2woCD}PXtu3rARta{TNMuv2F&WTE zdGqk;!}Ajht;XTG$Fw1ZY9Yen5)&M1VU#^0m*|EVWi#y~$;*uhCsa9M#prO{6p z2tzf`J}n|3yDA7vNuqkcJcIGWl?r31u{KjJ^ux3$gbb&4DRLIqX4;HiImfi$7pVoa zWH2g>PeMwT7~>RSTgIR-^3g`_liR*xVDbQGV1j6FkWoIP$z?vxs2!CP;u?eWBzHK$m5B5> zS7L5r&X}x_!ZEpHa+0Qn6cXWvQPJ=#fn!i@R zJT6yXh<$VAPtOwlS?L{ve4eN?IK`H^qLoTFHUa_)DWP!QB2-bosP&)^~L2w+L1G1i+#Z<|9BJ0as z=z**!eL8cig=hqnUC$sIS$D3%N_8SFPw@@JSI|cC863UVPk3U`*psDr_kD=VUqb#W zOgk}}`An>h|Jdm?s|D_aTJQq5TBK%g-h=nW-aQz5%)3q{|8m;)R*p{_62m7WXEE!T znAd-%lMcUUCd0eU8W#V^v)G(>J~9qr`y(dKU}@SmDTsQ8AIAwrs}=%TI=#s+?L4Kd>1uk6BFiq$m-2<@3hd(J z63*$QE``G6LTd=glEXTj?loGcxLpcr1~{k9rHnu;$FDz`3W0MsBPRY-_wzOlJ2ob=>_^Y;cw#c+BxqOv#{;2U`b4 zD*2(98h^ucL@h)&Eyzlw)W}%2i9XU)kQ2wzH`s=0+4O7n#k8<~sSYhK8;4bw^?<;d~9&$g3a_fws>YZeUZI3b0s~>dW{Nbo44!DFVyHgY{@gN)hXvVlXmTcZ89<-z)+#}hBEVo0-A?o|3&lu8e;#9ZP4!6{+kXp|^d{j@{*f)N!l*W!>OmvN}?xTl+)?qKO9xX{i&5kM&!(t z^fPqWM-(>I1O1Y7W1cGEgx9PwJjWY&PI%q=s8sbxNY0Zb{?d{m`)!Icy_!$q{iQ93 z^KUa8--gQqL%1DzC0qDr+rtM>@-tx;prxM;$aacvOVcvi+Ewmj>Azq6cB?W+6Dhy= zF8R!?!NxWZ#;Oe%ao*ni&(L%u(oe^d=5Za3P2stU2ZJ{bS zE_@ooa)m;$O}b@xsim|Trg+*WdE77bjJd;dZj83&{WP(iYbb>p?|>YMliHhcy4<#0 zolAD8VV=KpQhg;#WEspZI@Gd}XrzH``n3-py(x?#!Bf0gXtEIZ^A%knWtBB z!W|dW&OeN$d}019?c=U3(()Ofo8>R+jW%NDz43``Ue7=8wkfUbk*9KK5PRjR7&?+Q zK9x^H8C{S_yI9hK(Gi_4s`VOY!kQD_kSj$RiAHYZIA-E7s6EYIUND{8X=L9mNEq_G zQ_m;h$fn3q2u03+U&R7Sh~~{FwBx!gJ$a?3c4>>DQCeR}ySJ$P8s*(M9d+Yj&ME39 zId7QPp?f`RdmD=@TuK+SorR&^bl|-X`CPEq@heRFnZkVNr*DxQ78PaC57?iJbV2e& zc_!27*IS8Jw#D)h*e*^!$;K>ckEtN7c8S#r~lbb zlkOf>j=bA`Z5h?sMNF}_zgtb_7yaF=UBU@}W!1&uG@l(R*87&Z&Pq$lQ_ZSvJ<^}D ztHt5&tKW@0I4D5#TKKb=_tQxe+Z=U``1XcSgfGk>BWGSz!62@5YkYKv0r!iK9VGg0 zyXRy&>b84`cWpP#8oY55+wk-&oY}_sVr`J}_YTU{ss5t7Q+I7_@}l9MvZ}V-*1^^< zT@>!Gy(qUD-e-e7X{@qC!KgslnP=y~ zbrftY_NB3JU173ifx<1tENa+R zQE#bRMupS8dDo#Mrjjz1yd(=*>T{tqhRuI&G+wjyxjXE+3ElH`|KvCDynkJanCfME`QpE*7~i!Px?Xrfmzk zB)x7Z?n-A}OOk>YTlz9b}BmA^1w6S(QPRvqO%i*;5y3Z;4 zT^!<;c8MX@hO}QU_T=7gSGX0}F19-_bw>Qe@eN%A$R@t1tV=;oq|t55yEJ43mdf!E zvh7mm@V0+tT$Pk{FLsfB{l6XB$ZYOQe@s*z@|RdoTkN_*A!*zu~OJhs6dQLG&*1eWx7bX@^Uk%$|K-H*BwU zyHo+Y`D6PR=04*j?>DmP&@{V5=E5E}VwpiB7tY34WQU(0_N3W?Y0#I4;3Fw6bq-sY zFgC55a4)B==u#+de|rfZA{1_&HiI(mCs+ZyXtH)0r{U&~kr=ekD}*^Xutf7A@NKxn z%k~1kf+u4fs>J^yyB(11l_TV1b)YE{>GwKgoQTR)%-xTcf?*E3O!L2b$L+PFKH2vvjrN z**RA{%EBaB;%i9E!@XsFfkpI(q|>5X%kkG1_q28Xgk&1xi{U`YIU(W{CnTJLRbqc# z^IDP7M&WmkFAQ^A6(YLA8}Knt0Zv$mQQ5>A+=3vTTGimqD-Ws;!7F4V!_>Tgb~JSJ zTT2xGqcpAj+R>NOhICx$RIl-ARMwKNsXiVbs1H$LAv>^EU)Esx(X5f*P;nnEyMTu8 z*Mbe@1dXNb*mzD*EhpSNfzR6P1>Z|-i>#u*T1UZfl$y|Q>|mu>9d#!-;a#hmC(*xM z#IHUhbo>V}Qn8RV;q!39ch;NczBb74kJ6OiTE(wibzZZ$v68vVLwVUMe#Q#cg~3zy z{JH?ulv5P@arL^;{(J2|oBjEJLBrNJeZ1~j%Kg*Ef?k@;oj%FtzBDx9qmvrmrd}T>@Ifjr3mh}jeYe})_~_-56yiS zz&mGH#QL!T2jHicts=$toW;lT<9Q-1VoTSDa_7#lSJ%(*y5p!gs_OQEgU{k*H`fn^ zOIfvH9Cy8%P2TV_clXt%&o?Zjx_&XcTDja=l8$il?X-3KCq!ca_+IIi4gP#TmR*)x z*6LFBocT86#60#wCs!T8$MEXhl%+PY5vIGZmfMPVK^krtNSY1YiJFRVatEO22XUrv+>6Qj-;9sp5f6x1$-n=WV*M84y z>&^SRRro#cFTHtZTgj(=?H%sTJJIU%d*1%uyoOfor-c2w=>|2h%bPDmF0_+K{K}I) zeAQ1ykuP{o!v-bHwQF*Fo;}>pGn&5GvVr5h9o~7~xn8=nosmgi(;~G*_{0ivUB4V6 zxa|FUOXTZq6v~dBkiF%f?SKn#>@rG{X^QNtzr2IJ`pSN8>Zfc})mqNrWCyDf27GQK z(bK=z=(J%(@Nu$RRb%OW7G9m<*X}r?UTIWa-Y&i4qveBBh%kYzsSXRG!V{go7e;M&<_Hz$vj>K-i&wCMU zxP8A(vhvsGCc4D;TB%-9O7v}=G_kEyk(gd28#!ezfg>ngGWaOE+7wR|%IbG)5P@I2 zmfd?j3K#a!t-*99OWK-B%h{T(I=Y(e+!~iu={QglH}yc#0b?}(WaxoH$>h}$#3x`S ztaW@GI)T4#G)$$!3dc{ziBr4GL0B6U-XF`>C_0Df{uCCNx0Ow(38CZJ?3&r|-hNmU8p_)_J<;k* z%ON0de*YH!kX^6QtA}A8ER9Y5-sC79#=P0z5#C@?0rG)Fk^8;TZ?XP1p}xgIDW#cN zOt<|Tn#H=eXCfTGBOT#}9S0EV-jdUMY6IE&w~R>Lc1HV{oLsvYNUa#8wMc9*!yuF6)! zuc&o!dVQ&UzVg71d22AdcbEgYRZa7XzbJESpC!T|8xg*ErmJLGIb!(F6PgiFODG0@^_K{@z#)(YJefbvH~Rl0)kvXf#W$3q<&MT~ojq2r6IcJp4fZIC#YvrrQ?^i!^DU9%0eGP`0XkBYajK>_K@rTfZ+lc-F~T_^$^XO+xRO zzxteLQqYPUX4;oalbPrKID|?2^?u1H5t;+}R~j@C-tZ(k#W&gF{lTHxww{SG;xLHJms*x`}Inf7~o=`@1MZ^YGvGkh-`~hmKg_H6IZx$ggn zNTKkp;$ZDIUoLSUdvG9?``N*g-+LXMNj}ZA_5SQ1@A=~)qUS+VFF$z657C&Nhb+84 zfECvJBYlmnsV_!+gk7y)S>_T~n23_5$OcNSg9jJ0&}dcbJmASaf>`$G9zyJixE^so z#QP8jBHm+_`>obRBmFi`C~_Y^bZWBTf^#^<6IQ2q5&VzcDMmY7;uF22+-SOnx#3@z%4|5USL-C)Mx<)cW`8||Jk#1Ez7&UeHZ4V-uyt5yOUT%pCmLN#<`vJ?r zgq_y(*KSw7^>37aAlli-e||ja8z`3nO7$f&2>;Y1^=`IE+E|w zE`tt0djBq@;NO41$W+K7z79%|-iP=QXar$+ZcbsJfAB<^Dg#a6zl3Bwk@g0@Am9)A za@j~c$AfH80Oo@tun6?MT9)feXY-H))hOQzYW^U%1L>V$PX;N|?E6E(eLaGmw@G1m+`M0*XKk z7zyG*UwJ*!M?ekO2~6M&=qv9)ddC}hIpV9}0%!-9L7z-t$Jb4R94Pw?!2?haYJdto z&I6uv@FQF=k;sn+Nnkvf1X4i;$Od_!06Y$gz#>ormV)JAHL#!)-e}JkIFOc6%^|bg zFX`)@4uvB@B!~h3O~=pAMHy&(5+en&oC(jLfsRS+mm?F(9LT2g(A<3V5B#^LmZEGq z*Z}^oS2|EmpTd|HKySf+YtMwTGYiPGnn?>W8Q{MOR-mjBRO6?FL*T#3HKVKrEP4jA z;6LTqfRD?1b(rj2LNwiQz?77t2Jl=C#ax3KDMKybcos^FH~^mHFwhOM*FtF#uZDAQ zC*rHi@QILiAnl2`5p|k@MV4KRSw{K{_zawv)2oPP`XLn7EXDjG9*;^l5MMx{3US4A z=mgT;z!wcXKzyVeii!9#=m1wiGwNMOeB)WRu;Imm)C!Ci+}#9IgV?hYTCo{Tf)eO> zJn|^Yvhh3#>GMd-9`bdF$KzRcc3wyN23QXH7&fvoYH$%+$pi8VN<};g%&uh5HNIMA zslsP?1v(7fpAU+_B2WUZLu~%b=sR$L<;bIuorLsiq;H^nDbgE|t^k!F67BgSFAN+) zdJ^zPx*BC$!4cGN1~o|U$b%j1Mk5svQbEWQa8%K^EJ)+4s8o$b3eJPRf>fkOqRfGM z8AvZjdJ*DI-~be;z-P#Bc^z$ltFNIG$nyl=VD_@b%bs7uemnY9?2J$F2p$Jdfv3T9 zpcK3S)`QKU>JzrH>D}??_hJa38(amQ;4(M^jsOQJHsJp|vAg#5_#93gx7h4sZ$w1T kah1`&Y{aQrOl0)GB@1HMfaVZ&DSocKcA{xi^E2H40*C4bpk8PZr5K>*44WH(pyQS-VQ0AGtBG%-GJ5oe{R3|e7jBCWf#q z)KI^Oe&?gxW%riL+4O!H!OM|)uq$9nK<-;uE`o^j3in#mWGd{OYs3F`aRaZeJs5Dq{sk zlfRd&Q;GRX0k7O>`{zI+o@G0Xsah{NTxH)FC7RAme&KzWtI^U&>b)}r`D2#jml(KT z^(e>PqD197yFMcCHklqRdCA+@4!=hRivbuAR&}wssY zq4}U2BL5Sk!RNftUh4QSGFQR-9B2Y`z?@#$K%{xuqoAbomC_l+6h^M66K{Dedoo}H zJy~-r?MF=_mU5PR=QT~4MxLk0@E8XlM~f#~>YwE$k99;y(UQgFC8x7BA!c7b3cgXe zg}PW@7ve>!vA!{sQGKt5&j`C6c;Y0%N?8&T>Mo#J!DRcX6x;A9n?LvwXuoanI6p3| zHb4`WXr+GWZawo3PoiJ2iQ%8o544UDy4P^}5K zLh3u8EC2RO5gXIGz@vP@9AY~4VG~UwGDZ7GYUPZhm@eMQyB$7)G@m}2=}{Wq@5x&) z^^vq$#s-5`n?tQW)&i+I10`&{jMkgIYnnRXZWRx}=m*3SgVwwLo`@F&ZW!4}+IX#l8ri!;?+yN!D^DgfYdT5MS=E@#4OK-!w4_5bj-gvjFF_T4 z;VQ)qlmYW%s!U66GQf~!o-)*VVa|_6g$q*}+25iP1Y;v}N6pY{wU|RKyFYrcFsqS0 z9etzx2lu#~*!-IO^`b`^=+Q~WI+G;G>GmJw78^0hJPn*<#lxPbeOU+chrLh4(hN;m-&k#nkT^{> z!ype~;jz!q*V(Sv9D0I%A6w_o)hVuBP1lrYB@&z0Lgc~hje8?e$N76-6=t1ei{mo; zKjfsD2HPZvW&)Sk*|-tI_Bln#@Z0>PV1A}LiCL7^tCiE%t5vXfFI)IlUUrfV9v(67 zl(TxZOF8WD&2lN7j>lH}WND?3Z#C;(%4Qd7^q!I@dlGSKF_-d%tNA$DnkX4f(UR~N zDp#--!_UyavhgEE(|v6DhSHG{% z)|Mb@aVbIeKKrN?1b%pzOVO~RL^J(`RV9Y|?nmi!CvlRIb7`N~Hzf9@x}FNpjvPm; z8BOx^+v1Fdb^ISyl#*@xn^?b53A(pVaiy3%DoO}C#TJiRUEX02&JiVZz7b1P>r2FD zpam#_;1y6As0K(sSPVb}EWl5|4Nm(L@dwc6zUU56?SnFSPXT|2ifcM zcwsvBTK6n`A&s(yqrJ6yS+BCP(SytHwR@BVmtIbGM&uCFAS*ZSMwM?2BA@80UZ}B# zT6brNi+X4uY>iJmdigQ0YK4{%tp20<;-3m<2NQ{H~M;1`NCnjM$d|X=03;Z}M z_wRTf$t=xC22E}ln@Qxko-ugN?taejBqN>I{hZ<%jdWJ`Q}T>LI=%au;z>e!yeBCq zDSK3ASV;b;oKe}Mr-bAa`MR5n4T6AH&a;csNcL%RSo!em;aPh5yxU@qn=()|FNw=B z=i}gA`u*d?{E@of!o7}ai(8r2ZQn{vM0Rw6KaE6&XPdK-H!U3Vbj)qa)X15xkZdt) zFy3q2;W^>i>mV1BKRDC&Q*w$&slmC!7yge*aitIpt`YxD8_F;(JTABI6gM4u ztBnlpXfv`U;~vM+ereojJpJyo2`y@U%Y8xAd&GP2c|^S€>6lR@f4^Mbm>r~$N zu-g+vx`PEw45wA~NfW12`Zjw$6Uz|w6;YxMnG<#7>rpwqTlF4@y z?@@2YPpngl3iN?>=at?+7qc%jZB(w`mK7_&v$y4B(F@FLN?4!CE>YrUAo~6K;Zyoh`V||KJDv_= z&*Z+uC8nBF(_rIEZDlxE;@WSe4wf`!I;nrGj}$1`RIy?LZd2z9Q+{2TKrQFnNkSh9 zKGV`ix+*(7$~(^YI{f-av7)JyL-j3|QYs4EJy>Hjx3!VjJFSVOciNx=?8B)U@T~gg zh0!%ECNG?ZvaGxUx}Uw77fNOJ3DTEX%(Pu}3p+DyK2{-o`Z`mIY^>}N(GuAET54-m*IVk;mHD(| zz0SWbTGGl-+Raitb{fsr$_4fx+vpR-z>*(G@LFK!MiX1>fv9pjEQg`Nr9^o&Ip11? zLTbAz

j%jqhUaKvqgoQ`SgPSt-(nT5ab&&$*Q&>UQ-ZI5La7KrOm)-ySE?2`&2A z7n^9*;OrTyxikz%hQ{Hgm`iBH7-?>?AV1t?E`hZ1;o`s?os=nUS0~jTa_C11b7Y6z zTq5jxq?jhHm;UPLRNnPDH!@M0C#6VG%TIi>+)AlBYx3DvUAKp-kKNUz%Qi&uW<2D7 z_%Lv08DXK80i|%o*Zps3`k*GZdfp3|G4BTx`;>smGpu^{%7Z%tG;%+cnxjkFtsB&* zEw-QFJ;8=#J!IBuWUb0dA9{rtxQ*}g05lTw&`Te1`xaS>Y1}$L z8=LLh`7v}f(>9Uda48?K&mUPtcd_yLp}s=@TbKAj`>E>} z*v6v#JSay)_fuCenciSI1*UR7BV2c!%F0t%!qfn%pA?RI+MQpwN2J$Y*BT10Yx*5Y zTXNk?STBuiiVh*-*X=_iw@zMtU8gsEaX2Xbx=wTAx{pwJonlLFa`iFk_j;6nc=GPJ zmsT9#ofh2`#7DP=G;tMaRZA*1)%w7Z8Y~@9r?FiH0r2&X6~xgA?AwAc8q4ejqv^9O zenBDqj_p`rGCQ3#>E>~5+|AZ2i>b+_XjLlq?Oxyc1^;LhO9c6Ic4Tw!?kMXzQmF&qPmo+XAeY<^+VxDQ;_bzCh&@qBt3iJQ@)tCej_ z!@oVQkBz=$;gJ;=iN4wDJwX`$bN5W%bX;pQpvBqjeBtwg$H8_k5Q7H&)*A$r zy=n?qJ&$y>=(UmsuFHL@p%M8nxs=N+t0+de;9|>)vXiFRgRl|TrRiF)ScB>i11b=L9C>NSf+N=V!nl-fb)N9_sms31>}Z?IcMrtTTxYtI$60ef9!k&k^!2eMxt z3-%UcgYjqLK{?+9KPq&2AT*Y?idUL(M0 z9UmUzeB-g_5zV^ZJrg#2^(BZV9Et`yVx9ZLEUVD8nbaFNx@6)eWTyJvRX^%80cWvzfH9B9{d2SiERNiBRn9WVZL``*R zL9O2}uCLp-@=)EiM#qyTiLf*&2kweTxn-wPPwlH6m37o~W${Pq>1wB9>v}8gaK||f zZ5b3M{iCh>_;_Y@wH;ji!J4R0Rk}kt?Eyf^iu&jp=Gi4=ORiQ z{HIV@*P0-`Bses)*VfW2Z>4#+pm(?o?o-c=B+++TcA`w*I-$1I)__at)+Js!WT#iA z05zxPjmYCU+=6X|(((pt%85aRr&iHm$F)W~yjPmPvB5Vr6r7o5|jH4-t?2!3@s&z^ZQDdJ-% z9i_n!ow_M(sJ0+h@Z-SIV!{|Ik{q74^bimZt2p24$#dmACmh-U#H1*Dn3qXPG5=&n^raxgCKu%(tyRidXkW=I+*v; zN*H%=qLZ5hQIPjBx-{HB>Lemps6i_|SXWV;Qs-2DV2MkkXeN7bX@QQncbc79I)eU_ zbu2Z-_;fWNH`-{TZ|uKY$BK6BLklhoa>IsNFG)CN5C`{m|6?|8SzMHtOD9D)is*xk zJ72f86&)yZc|*_fC&)j!oXRNn(y|!yF2|xq^Am}U#C)iL9&svfI{3|>jx#UdUg@ni zr($H^E}NgV<#dnBZD`P11UUtVi^0ZI@o>=jk?K$^xT6_uJanSRVwf6vE>Y=_Ay>NZ zmKh{kZFMS5Y|ZjGdW5~RJRpRRl9$!wq^R0)RNmz2@xN!CVgI{4B8g}7GZ$M8D>L-8 zLGrE>6xPH>pBXm`#xS=Y3I<$P9-O`vRPn$ke zCMkAhr9HYXSu&Nu!lzI<;8ealWDifqD3w!GN?xboPFosO?%%;@E4vKJg ze12H>X-pJPcnKD-3_u7CqjD$*po`qAsI2vsv`2JD1^F=t8KRd4W<^7rFS5^{35Rd{ z%QNQOckSP`8F)QwYEk|aV37JW3i8h<=`h+V$XzFKv5>vH_Ye0ThBb0k)H#O3-jv$V zI~3hT#J}Al^dKtv<;O01vOe* z?1QUYci4Drwo#@fts3+!xnn9 zQgWR^>{1rGgX#*cLUwaIG4qSs)(_yHLV=u$pt9S~MF?Y^ENDe$zYU%{ZFg^tM?PSS zSBwg{h0r)Rx>O#kW=g}PF%pp*SmTONVf_c}>lM>tRo9y1x(*|bf&QNJDyh&)iBbY| zq1ftCc6v6#PM_#n4>$f|o1INxIa=890()WQM&aP5`T?sJP*dNSy-h;SOw~jLe%Ec9 z_8~FcK=-h$=^JVXN`2Xm)j7D}TwNU+@K=xAb~m3Z`EAI#m|uBl%ov9rldCF84vN02 z%6O-Dma44onheFSapcLXp?u4`RHc~BE?>y@SFhG!*RZgI;jFpbB2;|Hel4GdyHt8b z5`THF;$AwJy-~5e+@lO{sz8qn4H`t$FL?N;Hjgr-Y3pyizxDD$nyP=}HTUw2O|`%A z-tFb-o0@;)z17QezTfg2@3mguukT;^kg$Dge#Gr{&D!&k(M}SHFGuM^mwjIl`Ly>G z9Cz|yry-~3-K+ckp8BQhRteIVPTySL93Rt1?U6}7QzAtoZ|{P*sZTbM&pP|`=I~%m z6!JEn!8Wx^d7oArD`zs(L3J@p%dNemR}uePiEjiMBsLS*7hvK~ABYFlakyKUXxIl?x43ZLs8 z-u_d()gE4HFYo13Y;L7W*RknU1-Kj6SMAZ~?!|R>FPrhg7Y2_q>?Hpt!zwq;4b|pA z=}Ee3F>0PqDWu6IJmN>{CxNmPEw^}Ti6r0Z=#(06QA7Q7`2US#T) zu)qXYnsmk55lrPc$fQsDxs6Li)i2+&LlB0ZVm@2%8xVv~+(rZ}wG#L4JctOed0Rv1 zQnq~SY*?euwuXjQI0Z8i&7~C(;K$kT!ap*)&8#QzRmL2zAGS@Pl(4v$|AD8DMFnsl zMw9c6)qkP+XF~l7gHlQ}M3%}vry}#)o`L5B+tcwpu>BC8sXKVuwkweB-(f{cxAUmx z?Lc`>eYW1cR%D0|ZsBI+Ur!Gs6SYr!@V=m<`nHSE$=6ewI#2oNi4GmAdtIgT{IFSc9pfe6l zgn%#N?lzv+%!+oeqbpeZZeFKpPoei*lnMyvmxV2RCW3c<&p152_a@>wzWcdkFQd&& zw=W~|Y8R0|?b3!GK3Jjf323y6BF zYp66{`lVL}M;T5a$1d;7&~c81#q6Kyn|{*2idOZVVUm&qxdH4{^X8foEw4cN;bdCjbKDOcTW<7;Dui4OL`YY|yl4lY^Z(Bs;`m1-G=T>>0C z4i6xE=0Z*S%tF5L`En5Xx%Uj1hJ*MJaH`9reDC%sH{CtvdIO6)G?5mwMTcU;{`$KY z+eA_*0;?XSt=s;%ltrxJP^z%l&D2AiH3$T-?+ypB{f7slWB<0XD~AWNbKNf&`Aamo zAM|j=nt>31i;b=+1bvnrs99R>QYP4lmZor{q&Fdai&^k>=uKV-<9dVgaIOy28?c1_?rGWBRoonhmG1K`2=B&?*2`MRlaWV`p`{Gca-(4 z>Ge>rI{AFHw>ttfsfj>rZe1-HS;4*Oa4}6|y$GZ!Fhh_)^Vt_ax9=O{y zm%Ez|$bcL$8~G0a^Zy`MfOHX1ERk{pEN|e^{N-0<)Faho0-vm1TkY5D;B49f3 z0I&*J1KcgY2kES>XdLtaum#u#>;Ue{-0k?7T*v|C8}MiVih$|BS-=;){uG7I^y0@U z=m^jW*Z~(nA*Tbpxjf(p1Op}@5{LoffOsGYXhdD-fmXoQi?egc%D*uxrRCPAlU*2Wkf*As3AI z1Dppm@cMvf!C$lmbpYEoqoc^Pfqw>=y?Ei`C!b-Xjz2uy=R=GW2mnF=5f}>G3nT!^ zz(inDH)Zc1e`U8fd=3pum!jb6j}&L;RkE)uNuxqGuu)BQnvMePdV-7 xdOVbRJUuTi5&e((y+qiso^<~A_u${KJwNv_O1{t%GUPP=CUvU*u@jF8{}1Njf#(1K delta 10988 zcmaKy3tUyj+W%+PzOYeH5RjY5-fWSZmko%brgD+RO++-)N)se&lb7(8S}LGYPHI(c^YZz8XJ*YjGizqn zGtbOCo9(}HU)|+Kl~baP97;4DIYcuO?CFgcA&x@+AKBATGb(n}qGLo;15BV31T+(k zZw=8zg7F{^6oJ*Cx~68-U{xw44%O^S^iHZJn&90;la2UL&Gj_05MTC~!)ewC-gfe%(@cnh_mgNGiM6!{h0x^E zOcK#AH>7ZG@h)SUK)GFoJ`usjY7f;VI>FkW|Ik$$QdpXKWl8x_NVbw;G)2?wA^hO* z$lXOC1PgunM+IA z8J{_->K4*k%EEkgerln`MfBH-HsABD@-h9xpJ+WJ-ty(?M0V9Ty#G=u znm;Rzn8^vJna7~Sz!{QDeCX8jR5)Z&N95lp1<|~RkiiNDEf|^=fXTtc?9}300pdeb zh!;BVNwi18+1G=1Q4K5cE2gip3w{%$8l*ylPxB8RO5Wo#(bq{w4K6Xv`JU83d`vEJ z2vSFhOY~=n{_FgxmFN!**&@XovWc?WK&UW+wffh4)?1EA5rg6zPqU=~dip7=2?#G+ zJ)CGJfxF-gXpSP9tB5}v_MfaozMMCwHy+m;|4}XsdHsP6^)mqLm6_Aq-VMa$!Mmk1 zi7t$Er4vsfg^eCuNlmPIu#P^>{yumLeUt?TMwRU?&%giTiU#TBHoY)FQHQY~wb}0} z;_`*^7xD!klH97$r{$$(pOummmKA0d9fQP^>aqvwkEwo(l%GJ&o2!E2%C0m>uWM;6 z5vs~*#Cy^+hAmQF#J!v8#y08c_+M{suBwyXG<4mh`b|hZt=%F`Px$%frmBlWrL_rl z(yQ7wX==hhZbs#7t{P;lld25gF8M^dZ}=PgF)+C7^P3sJ^)KF3wJWXc{_c;0b3=_+ zmMDxrEUC>T=)zgUU;a@3+DE><<)KS!GpYU;^ET-$A<<>`H-411U8$Qmze{O{zzrTEqIXJ>5Dc~mKAJb^JcRKqFI4X>_gG#o@>0Lpv?0`kQcY9k5JuI#dOmdM{lE`S$WvxW zNNBu-*K#`3tqPFUC@i~9R*xjZ^gYoLB(vn*>FiDe7Y8pL+ zDQtCgI9Gd|y%n9n%{$KiCwk^^J8ZQC6g-_O4^5f#TAK1A>~n5miqAaB>;u)PJI>N# z?$Fz8bZkIgw&g})Ic#Zvmx|Xm(g+=&n9B*1t&v5CkxP&}w^0X+_@y(NADK&F6|cvq zNZTfI!i&!OqJxn6#i`>Rn5t7~BsMr92&+G&=?^aw;#fH$id zH9B^mUCV2JpOO?z$qYNuYxylw)r>7tHLTa026-vAwXoZxA|{@(*KKr&{p{Y^4)IC* zGaJ3KmHg-T+SCs5HwS6)oR%-R60!F%hnVbaJ4&`C@;2v)i_ZvEw^k*#C!1>7 zjf8@jC6<831I9gRv>gk_M74HvE#_iiOmef558wx0f!cSa`ly91Y(ZkMN-o>ZHY8@y z$?Vg_Tz!?LfOm*jE&X??clX_cs2{rtg@3<)L=@V?i zxQ%6^B{)~h>kDPI&+;bPxxfgHLvStPDv%6n!9j2woCD}PXtu3rARta{TNMuv2F&WTE zdGqk;!}Ajht;XTG$Fw1ZY9Yen5)&M1VU#^0m*|EVWi#y~$;*uhCsa9M#prO{6p z2tzf`J}n|3yDA7vNuqkcJcIGWl?r31u{KjJ^ux3$gbb&4DRLIqX4;HiImfi$7pVoa zWH2g>PeMwT7~>RSTgIR-^3g`_liR*xVDbQGV1j6FkWoIP$z?vxs2!CP;u?eWBzHK$m5B5> zS7L5r&X}x_!ZEpHa+0Qn6cXWvQPJ=#fn!i@R zJT6yXh<$VAPtOwlS?L{ve4eN?IK`H^qLoTFHUa_)DWP!QB2-bosP&)^~L2w+L1G1i+#Z<|9BJ0as z=z**!eL8cig=hqnUC$sIS$D3%N_8SFPw@@JSI|cC863UVPk3U`*psDr_kD=VUqb#W zOgk}}`An>h|Jdm?s|D_aTJQq5TBK%g-h=nW-aQz5%)3q{|8m;)R*p{_62m7WXEE!T znAd-%lMcUUCd0eU8W#V^v)G(>J~9qr`y(dKU}@SmDTsQ8AIAwrs}=%TI=#s+?L4Kd>1uk6BFiq$m-2<@3hd(J z63*$QE``G6LTd=glEXTj?loGcxLpcr1~{k9rHnu;$FDz`3W0MsBPRY-_wzOlJ2ob=>_^Y;cw#c+BxqOv#{;2U`b4 zD*2(98h^ucL@h)&Eyzlw)W}%2i9XU)kQ2wzH`s=0+4O7n#k8<~sSYhK8;4bw^?<;d~9&$g3a_fws>YZeUZI3b0s~>dW{Nbo44!DFVyHgY{@gN)hXvVlXmTcZ89<-z)+#}hBEVo0-A?o|3&lu8e;#9ZP4!6{+kXp|^d{j@{*f)N!l*W!>OmvN}?xTl+)?qKO9xX{i&5kM&!(t z^fPqWM-(>I1O1Y7W1cGEgx9PwJjWY&PI%q=s8sbxNY0Zb{?d{m`)!Icy_!$q{iQ93 z^KUa8--gQqL%1DzC0qDr+rtM>@-tx;prxM;$aacvOVcvi+Ewmj>Azq6cB?W+6Dhy= zF8R!?!NxWZ#;Oe%ao*ni&(L%u(oe^d=5Za3P2stU2ZJ{bS zE_@ooa)m;$O}b@xsim|Trg+*WdE77bjJd;dZj83&{WP(iYbb>p?|>YMliHhcy4<#0 zolAD8VV=KpQhg;#WEspZI@Gd}XrzH``n3-py(x?#!Bf0gXtEIZ^A%knWtBB z!W|dW&OeN$d}019?c=U3(()Ofo8>R+jW%NDz43``Ue7=8wkfUbk*9KK5PRjR7&?+Q zK9x^H8C{S_yI9hK(Gi_4s`VOY!kQD_kSj$RiAHYZIA-E7s6EYIUND{8X=L9mNEq_G zQ_m;h$fn3q2u03+U&R7Sh~~{FwBx!gJ$a?3c4>>DQCeR}ySJ$P8s*(M9d+Yj&ME39 zId7QPp?f`RdmD=@TuK+SorR&^bl|-X`CPEq@heRFnZkVNr*DxQ78PaC57?iJbV2e& zc_!27*IS8Jw#D)h*e*^!$;K>ckEtN7c8S#r~lbb zlkOf>j=bA`Z5h?sMNF}_zgtb_7yaF=UBU@}W!1&uG@l(R*87&Z&Pq$lQ_ZSvJ<^}D ztHt5&tKW@0I4D5#TKKb=_tQxe+Z=U``1XcSgfGk>BWGSz!62@5YkYKv0r!iK9VGg0 zyXRy&>b84`cWpP#8oY55+wk-&oY}_sVr`J}_YTU{ss5t7Q+I7_@}l9MvZ}V-*1^^< zT@>!Gy(qUD-e-e7X{@qC!KgslnP=y~ zbrftY_NB3JU173ifx<1tENa+R zQE#bRMupS8dDo#Mrjjz1yd(=*>T{tqhRuI&G+wjyxjXE+3ElH`|KvCDynkJanCfME`QpE*7~i!Px?Xrfmzk zB)x7Z?n-A}OOk>YTlz9b}BmA^1w6S(QPRvqO%i*;5y3Z;4 zT^!<;c8MX@hO}QU_T=7gSGX0}F19-_bw>Qe@eN%A$R@t1tV=;oq|t55yEJ43mdf!E zvh7mm@V0+tT$Pk{FLsfB{l6XB$ZYOQe@s*z@|RdoTkN_*A!*zu~OJhs6dQLG&*1eWx7bX@^Uk%$|K-H*BwU zyHo+Y`D6PR=04*j?>DmP&@{V5=E5E}VwpiB7tY34WQU(0_N3W?Y0#I4;3Fw6bq-sY zFgC55a4)B==u#+de|rfZA{1_&HiI(mCs+ZyXtH)0r{U&~kr=ekD}*^Xutf7A@NKxn z%k~1kf+u4fs>J^yyB(11l_TV1b)YE{>GwKgoQTR)%-xTcf?*E3O!L2b$L+PFKH2vvjrN z**RA{%EBaB;%i9E!@XsFfkpI(q|>5X%kkG1_q28Xgk&1xi{U`YIU(W{CnTJLRbqc# z^IDP7M&WmkFAQ^A6(YLA8}Knt0Zv$mQQ5>A+=3vTTGimqD-Ws;!7F4V!_>Tgb~JSJ zTT2xGqcpAj+R>NOhICx$RIl-ARMwKNsXiVbs1H$LAv>^EU)Esx(X5f*P;nnEyMTu8 z*Mbe@1dXNb*mzD*EhpSNfzR6P1>Z|-i>#u*T1UZfl$y|Q>|mu>9d#!-;a#hmC(*xM z#IHUhbo>V}Qn8RV;q!39ch;NczBb74kJ6OiTE(wibzZZ$v68vVLwVUMe#Q#cg~3zy z{JH?ulv5P@arL^;{(J2|oBjEJLBrNJeZ1~j%Kg*Ef?k@;oj%FtzBDx9qmvrmrd}T>@Ifjr3mh}jeYe})_~_-56yiS zz&mGH#QL!T2jHicts=$toW;lT<9Q-1VoTSDa_7#lSJ%(*y5p!gs_OQEgU{k*H`fn^ zOIfvH9Cy8%P2TV_clXt%&o?Zjx_&XcTDja=l8$il?X-3KCq!ca_+IIi4gP#TmR*)x z*6LFBocT86#60#wCs!T8$MEXhl%+PY5vIGZmfMPVK^krtNSY1YiJFRVatEO22XUrv+>6Qj-;9sp5f6x1$-n=WV*M84y z>&^SRRro#cFTHtZTgj(=?H%sTJJIU%d*1%uyoOfor-c2w=>|2h%bPDmF0_+K{K}I) zeAQ1ykuP{o!v-bHwQF*Fo;}>pGn&5GvVr5h9o~7~xn8=nosmgi(;~G*_{0ivUB4V6 zxa|FUOXTZq6v~dBkiF%f?SKn#>@rG{X^QNtzr2IJ`pSN8>Zfc})mqNrWCyDf27GQK z(bK=z=(J%(@Nu$RRb%OW7G9m<*X}r?UTIWa-Y&i4qveBBh%kYzsSXRG!V{go7e;M&<_Hz$vj>K-i&wCMU zxP8A(vhvsGCc4D;TB%-9O7v}=G_kEyk(gd28#!ezfg>ngGWaOE+7wR|%IbG)5P@I2 zmfd?j3K#a!t-*99OWK-B%h{T(I=Y(e+!~iu={QglH}yc#0b?}(WaxoH$>h}$#3x`S ztaW@GI)T4#G)$$!3dc{ziBr4GL0B6U-XF`>C_0Df{uCCNx0Ow(38CZJ?3&r|-hNmU8p_)_J<;k* z%ON0de*YH!kX^6QtA}A8ER9Y5-sC79#=P0z5#C@?0rG)Fk^8;TZ?XP1p}xgIDW#cN zOt<|Tn#H=eXCfTGBOT#}9S0EV-jdUMY6IE&w~R>Lc1HV{oLsvYNUa#8wMc9*!yuF6)! zuc&o!dVQ&UzVg71d22AdcbEgYRZa7XzbJESpC!T|8xg*ErmJLGIb!(F6PgiFODG0@^_K{@z#)(YJefbvH~Rl0)kvXf#W$3q<&MT~ojq2r6IcJp4fZIC#YvrrQ?^i!^DU9%0eGP`0XkBYajK>_K@rTfZ+lc-F~T_^$^XO+xRO zzxteLQqYPUX4;oalbPrKID|?2^?u1H5t;+}R~j@C-tZ(k#W&gF{lTHxww{SG;xLHJms*x`}Inf7~o=`@1MZ^YGvGkh-`~hmKg_H6IZx$ggn zNTKkp;$ZDIUoLSUdvG9?``N*g-+LXMNj}ZA_5SQ1@A=~)qUS+VFF$z657C&Nhb+84 zfECvJBYlmnsV_!+gk7y)S>_T~n23_5$OcNSg9jJ0&}dcbJmASaf>`$G9zyJixE^so z#QP8jBHm+_`>obRBmFi`C~_Y^bZWBTf^#^<6IQ2q5&VzcDMmY7;uF22+-SOnx#3@z%4|5USL-C)Mx<)cW`8||Jk#1Ez7&UeHZ4V-uyt5yOUT%pCmLN#<`vJ?r zgq_y(*KSw7^>37aAlli-e||ja8z`3nO7$f&2>;Y1^=`IE+E|w zE`tt0djBq@;NO41$W+K7z79%|-iP=QXar$+ZcbsJfAB<^Dg#a6zl3Bwk@g0@Am9)A za@j~c$AfH80Oo@tun6?MT9)feXY-H))hOQzYW^U%1L>V$PX;N|?E6E(eLaGmw@G1m+`M0*XKk z7zyG*UwJ*!M?ekO2~6M&=qv9)ddC}hIpV9}0%!-9L7z-t$Jb4R94Pw?!2?haYJdto z&I6uv@FQF=k;sn+Nnkvf1X4i;$Od_!06Y$gz#>ormV)JAHL#!)-e}JkIFOc6%^|bg zFX`)@4uvB@B!~h3O~=pAMHy&(5+en&oC(jLfsRS+mm?F(9LT2g(A<3V5B#^LmZEGq z*Z}^oS2|EmpTd|HKySf+YtMwTGYiPGnn?>W8Q{MOR-mjBRO6?FL*T#3HKVKrEP4jA z;6LTqfRD?1b(rj2LNwiQz?77t2Jl=C#ax3KDMKybcos^FH~^mHFwhOM*FtF#uZDAQ zC*rHi@QILiAnl2`5p|k@MV4KRSw{K{_zawv)2oPP`XLn7EXDjG9*;^l5MMx{3US4A z=mgT;z!wcXKzyVeii!9#=m1wiGwNMOeB)WRu;Imm)C!Ci+}#9IgV?hYTCo{Tf)eO> zJn|^Yvhh3#>GMd-9`bdF$KzRcc3wyN23QXH7&fvoYH$%+$pi8VN<};g%&uh5HNIMA zslsP?1v(7fpAU+_B2WUZLu~%b=sR$L<;bIuorLsiq;H^nDbgE|t^k!F67BgSFAN+) zdJ^zPx*BC$!4cGN1~o|U$b%j1Mk5svQbEWQa8%K^EJ)+4s8o$b3eJPRf>fkOqRfGM z8AvZjdJ*DI-~be;z-P#Bc^z$ltFNIG$nyl=VD_@b%bs7uemnY9?2J$F2p$Jdfv3T9 zpcK3S)`QKU>JzrH>D}??_hJa38(amQ;4(M^jsOQJHsJp|vAg#5_#93gx7h4sZ$w1T kah1`&Y{aQrOl0)GB@1HMfaVZ&DSocKcA{xi^E2H40*fD2^ojqaxwAjU+tnkmnIDf&M`pt9~D!{>Ja)585`pM)*#eOsdn--|2j%Qw?m4e`N62 zM+tvPLxe(~cKWiF{wcO_cUz;cKuNLuEYYu53y=ca#sKe*rGjPdLXwca@GV z+FVpw^t>g?*Y&y1*d_n@B4!DZv>NB-g8N_e4=w&|W=P3n79WG@bhadDx(SaJ`ADsH zqUSQyLTD^CN1{lz5b{9SWL*DqaHUUv2z==^y34uSESVCe+lo|mXAP-2+#6O~t23Y)^WrTL+)l1Uum3&3BeVdvyHtOJl9rel!7$-@#4pw zEkA3L(i=3!0;$|OJnyX1KQ*_=Bmdo{kA2iUrC4p8sXn%rsCTHbLNTX4)VRJfJc;~N zQC_WV7HA@owv^M@{mL9ug_0NR+n8-Rqs&Utz^Y1l$>h0Bjq4Dag;vQ=Rc^1Vyre8m ztx{~y31^gyROz-Me|=>)OO;Y-`gGo3l-uCZEkDC8V4mJMRxK%kzNWAU- zGjC`AB8KdJ$m_=b_AG;dF7Q~}TesEDahMrGq6TFIcNeE~N79-$rrQ5gKen)zd_z^+%a0j`y2&-PJ zHd3N`Q@vJKu}=+s>7SU#(49WVy2oyz+3Y~9k^8!eU5HKP_E)jC*l|8uEk?JNO*Ho4 z?o_d-jNjOq@(CVS(BwyuLQ8_f{ymmC!Af}l)$)&^< zzXk0{XeW7dZ*s?r$!3Dtou4drUw}Jq=6>W` z@oND&uf3$IaMfk;KIaV6>Yr3XR@uQucT{e%yFlkjH`-~%0C zPsVMeb*woqBJ9W0M6l*)R`@4rFL7ywijh$14(r)_Io-=%?me0=XSaG^p?Y?zkD1

(6I=-0~easrMUIAbHX-#WT0ex1Bjowx)@CL%hfxq0({oM&bvwi4`Xeq8HiD zq!fCA{VmBz@3Vg=8M*Hq`$GFt8p^_w2L+b7w0B2p>7o6VL|V%xC-=ijuqio)PGJX= z`vfPtOyW$E5aT2Ltk6S58pgg#PNx54fe#z0nWa1&ru)%Jq`xxr!vp9&w)Wu=TEccb zToQ88)id7bYJylaUx>BeNzWkC5a!=+IQ3!Xev@e*cA%fZ_XU?QUn?2d#eUs`>2Shl zWOXI#`a__Ns%_~PLL+u#iXc)2nl0UK+Dmvf*(4BY88f8x@zL(Xr`*TJqzK(7!9;Jj zc9?i%39|~3^4Nxyg-^23!JXVf{6v1gZcDz<37&Fo8SZ2UP|V z;X6nxzU&H6-356N&j0}!Z9Mn^HdXuBj8wsvk0nuE$$5JQ49n}{#>5q*6}4L8%M4HxGRi?2-SzgHz=C{i(f=52@(MdLEMooyJJ0_v$ zoTFmH@+!l1()>1R3>j^*99`0GtCP~vR-9C9b9=Lwy^`a!1mwRfTr1W|eh!mGW0?xq zs!5?+ZX^vOP&sucpjJ|y=ttmf)VG?3R>6kDqHaXgG?Hu0$%Ra>OV1@zWZNJ-yL+FZ zZ37Vw_CAB!1|aN@=V&7FZT%6^d7oTc8p0lTnmH}Me{N(^e{=u*0iz;|h;+=YT7BtG z%hgCs5yVt;FYj!i9jcQ8+qBL7F|K#Bn`zx`VGeav7u;W4Or(g`v&xA=5@*comER+` zLOETilMcE~u?BN&Zsela{Kz78^|>~ela{)o@_Xh*qt#w^_b~U!U$4AY7+DmPt9D0^ zeDrYc|=j{oX&@O6EP!eAbTfI^jDEf-QV!Zee zRtUXYD{jo%-oS}j(FtNYG&fv=sMraihRUq;1|FKfp5SYA(nlv);y{J_(ZPBR`h_lL zQRzLkTB+W{hNVX%aLiLXBfXGvLC)Ih!S^ZmXlw18LlZTAeOe2oC&#*EBfB~*soPt4 zyQf267*5TaBDEKMvX4D9d`i&J6DY4k6|kSJ8Qz;S?PqTeAIN>OpM5#}Vfg>Df$1|s z5%|L4WzqYl)*H=+xrSJ($5n=`ZUE>`<%n3j{9 ze$MP6YF6mPu1Nu6chRm0<-@Sm{=i>qK*K*FNl? zI5NuTlF3R1PF+dY>Wz(!Boq>LSKtN|0%b5@^yJF{`k^<{&Px zIZ&fL?2*^9nw*|Aie1hrj`_STQKX_Ew)c|_4e53?f_GwSlW((v++uE%lO50f6Zfc- z<>yVK-?M{x>**nul;0D39drH?x}P=V4~kjre$Y?a@BCD-5c7u-oO`=6+{B5RwCl(H zu=OEK+nk~C$otv9%_9fJIP*lOyug`>XGyD5?&l^yHJZ}P2XZ@(gll)HGX zrh2UkVHM5FMj7d8_Ts3x^c$_JhljmsMx_1Q^?!M|;I)eKTIpf+FBkh^)D-$8%Nd=* zQ72n9IyUU9>4Z<1fnzRM1`dLESk34N`UU&jXajb4_eRIjcUj1oL24U}*+sXqMucau zo&|TQ#QY0avJ(RX*w(@#8pfInmt#FG9XmDfX(xSD+k8fQ_p)Nwv&&=SxZCeDWo#;q zW=Z3cxewdelyT#@>rVFexc=Oat?avTiM_sP-Hho=9XtIo#Ppbab0NnAUZi>0W1O7! zChPs!Vid9Su|?Fx{KrSZU!UOr+ zoV3>=%+ogWl#`x!u!$2Ez|FY{L-C{&=hH{n!ig!ItgyWkdvW&__VL6K+&c;jdR*W> zQJCrR@eyhfN*!rFwN<~i<@*_OQpLW z_S2-k@f2t3dwgS~Hu2UMdo9AecokNB+Kng-)Gl%W!F%f50?hzoXCKq`{{NvDRg;){23mxgHA# zP73ig?+I@Cug;90Xvn^GMoWUX>svE+S;BMpI=7tQ(wMJXq9P|{P0Hj^ZFS91unY%^ zZn@0uBX)(H>n@Kfkcg)Et}n&#T-+*u={}UTsF|>)sl#=?E>8N4B~OdtesHo;(~9EK z58_+ZWj`HKqshfy#zl?UOH|i|&~p-Znn%0&vCGq<{3g5AQOHRzvX*ImLg*>IU5|WP zacWI@X-17(evkE=-Uo+($EVNcwjN~fPmc~QawLkxplvQE8fl6{-8fVqWIs+96256Y zb6jtyX@N;UULGPi(1)~`mZiE4)xIKkj2C){8}9gE&H0=SnvonI=GKYv^#W?r=86|} z)smeGPUN|B)Idi5|Ht;_5h2>V#2&Vq@7u zBI!5yk^xsk1ybSIR=JPURIi45L(?h?&iI;i(XhgPN6Da4>FFX1bdChERZeK-q?bLd z@*pS0(nY1=E;X&2BL!)5Rf|+P93~q*1=2HcJHyc`$2tuwIPvSUc4uiAEiUwFJx)uU zH0CrX&0s@|CuliovxjXj9+-T@<-K4iifKPa;TfL(iHz1kh+)`u~it#(wR z-hRi5E_vuAC%xI~Ba--^F5&L0uR%PL72l8u+q>BFbJCZsw;MZsklt@+X+L$zFDX@z zaRZgcyS~~hE>3=)U7i_3e=9 zCA_A@!sVZ7B1W~dSPm23ib3p_Pq03-jr2Wco}CvoS^1^0bA>NI%=XS67`D(AD`w)& zsq~T~S4X; zy=ykEGSW>M9Vz3ui*6smi?IY=FE;_#ekO7F0-l6|u)lnF?m<(i8Wt4R|9 zvDlQ-VX&E$%&kxs!C<_L-JdJqART5g&{Q@EPXn8br=C4+i9q}Auq@&(I2m6$g#Mjn zmk#zrf6Cra9V+^>-KG7w*-rNN(nxxcHI+v7+Nns5!Vw%X(KPDN`2_L`(4}kQH#guO z59dr~eewhjW(j2j=r#64SqwMn2wPJY%cSSl#8RozsjtzR_Z92yTC=lJJw;%ix<|e) zi6ZNgo-2V(=zPjm~mc8r((*yVKz05uhZmu{;Tdnhi*i}{$F)xI&?!C-u+egUWd-qaQ0W-TOGRI4WGB`x}xB{9m?p2?~btE z^HPBTh9o_*xv%-`Zz7Rqie80xpd@8$C8 zh+EO$`@+X4K(r)dUTvLq7Y$Zb-kaLJ`C2t;9xGm45ZI}0*Vq?N9eL9gI6BZAU^v?p zHy~hC94fd5XH8=0l24@1TwOX+)Mcs<(yS*p!`H2KxM{>@hNROB^%|#zO<(e2Adky$ zHB~Lu#2ib8`~4QnTpGuZ$!3TRWOxIcZ|^m&p;koIYls{IgA*kvE=g(xwqS zebV&y&)Mpy@@O^t=&99y>Rp>|BYyH=qnCfid*s*ZRSm0HF^ubfiv4RvB$w)Beb+>= z;FVEyJxg9`^i{v3M?T9QU)cwHK-D>^`-&8Mz}0Xu6_ZK2^PQ+6;!TTb1eH>q-&%%_xZ44i#3Z2GD`1G_s*khA31 zoa(MV;OY?Zz+GRSO1v{m{MynSK_w0HW{>#3QO)UYtv$JFJI95eVuh<8=@yOF*5k5V zE2_iDBgZ(|>#HN_R93%w0xe=)*F;eZOIi~_KVT!*7=0A=Grd~7U=2q(C73O?{X-S` z<-KV*TU7oLo`cu!!}G@4Y&;F?Y>$@ZU z>iRx0H%_&0nY8#7Nga?ncv2tc#hnd zhUZG}^Vmj4Pq55qRn0Q*^YF8(rQ=yM9mz&k_Q6a&ztTVj_F`oMoz3biW5Q=RxN5zf z!*P!@Q^6nSz_X~rw4?0D$}wHkcl{30J0VQml=@(F-6k?`8tn0 z+oQ?<6oeZ@W?d{gmi|FAygiZnhMk~Bjg=VBG|{v(O`5dqVs-Dz z`fiQvUvYYP1clGe-@abKwQ2hun_AA#-WGDpEw~ZU*M(sI_sIXx!%|m>;XFQV=kIa; zIM#<_`G~_s23xvqm{yi+753h?3qHwdgilGU-S|>09lLS};a3C0BZQv}N)et97J+2| zzmIzViXSEXU~mtN1$#ikF#JpnITDNpH^4ULU_EV{GGHyXvjyR8U`KqiC#tkeML z27_kU{I^P_z~&xoS{|t2Hs~CPy8%U*5Lvf#)1i8GMEmEL1(RX*}sKT3h-UP zXfU9I1jtU?u?SBG6F>|wfH=^Zz7yd+V1o^hEuaR}flh;q2)C?6Q$t<`AAobLAa-?mTEg z{6I9m1j1LqRd550v(JT7Brbw+7-TTyO~{)_yaf)Ip#P|P(1iFsRR>4SkS)Lg++a8C zC~S1aEOO_naS>(c!(huibS+3bZZWPRTo2Bp|6fGCo1u3jenWi+$g7Yy!4*)9w6)M} z0GDBZV?MjRvv*k7LX-kFsJ#*{n*sjE;MEsxw-%!gi!jF_btl*j_J9N6G8k(`{XsK0 zjCc!V3OI)F6;Ot7Z;*0-9lhKj2w_| zz)?--m?68DqBWM_>wr4YnUIWd1k#$2F9qT02#5yTN#gL@{zqatRAqn9!ctG1T`>XM2z+s8Ay|#Anw#~>7>cIg}19pQ=U>P_EN=$@| zIQm;Nyn;>12{w4QEv~xEV^ckQJd}Do?M3*-;B9*SW?j#2?2htzW*>fv+soQ^XVJba T^YsQgkI^?8=qUEV8@B%e?-JY1;G0c;Ws(#virSy+-&%FavA? zHQ?3f310=ygDc>t=ZT%Cs|g43;Yp=!vZ!5lr2m<;lp)V@6b@;5{Xgg3 z_OAWECI0_OyWF4fi!%sc_zd9*{z@fc=B|^vH4;fnuU<{}>T>h$n7NZpt$AI)$dg{v zRNw73%l}H=9b(LoNJfA}@{BE<6k2CaFV4!72r16$)>PP)Hl%a92Bez#x~K5$NUIL@ zS)$>2X@L-F;j?)M>;gEmYO57I^8fB!M~DuAPa)Ys zzfyXa#rRL^k*|2<5|1EKX=$@QI`2Li7c1(eO!kuh?7-}9YTKxp_)+usJP}fvu8W6S zn6B%HzLiRWDWK-6k5=@#OpN=LlO~V+dh0=@k_0$B@@oj4Bp&${wy^7}ph3;VcsO#s zl4!CJZIg*m=?;^-R%m(YONH$Zc$_X^azK>bX(0SLup*l9Ss=qm__>hJ2!F)cuKTuK z*8K;Y3g{SE2R=of3CK&$=NiJQTns&V@LKVBVu&JlG4G`5RAD;;*K^A~EWF!%`*ow# zMYA7`Jn3w`r-{##N}tY?0!VV5#yD#1Xv>Gn;G`u5*@f@IVw&FmAo2t?u2-x{JsQ`Q zhsKj%*OgW(TLjvVNLxy2^g(5wX}w~J<{L9?^~#(?Ev)t{FPlgsHLgWyj<8c$+4Hs{}|N8Mv8=9Byn=pIJuoDN(l}PseSTP?GZxjkh^gss(Mw-D`-vu0P%nMQZg)58 z{uPL&R~^{nb&jU8s;~#4W6r4U?4OiWbxE;toWXIc*sPaQ&an5w4{=&2vqkizi`d49 zc;5ldmz0w6RLW;(A{Np});Drmk6F;oNxBza{oq;qxi19qLuJk^kL=5KM;1kNZ~0JJ zKmK^*uB_{gq)uJW9qVBTi;7yOI}Fd2Qe6?Xjq?q0mZi5`q*5SD6$bWBMjZocy5x4T zbj{XDAGLO|2%=8gY`YNIOEt_tK=>U2M3@8lBYHpKwv@NAl5VHc zC+t(fL$|X}4QZn~w;ERZ<@j6qY!c^J7bu1y!+UO@O2;i}8}TKAn!_!;twmVPb^iuR z)ZElu^AE6`=>B0}y5SusR6HPa&np4R>XI)lj1{#gW?S@Dx{gH|ja=ygmTpYq#vEWz z8^`NiaAk^y{lnOkD?h+~HvZfGt)df!Dg&IxarX#od_hIQdVxxppbdbQll+yN1*On@ z>b0ZM262#;lep%X!lTgELp#~~_BMB{m|!KS!;M6JK>~$?wf_DV7Lc{hrEVG$Sl$t8%+#m#Wq4OJ=fZn@%h`mqbrnM zcyS-z>*9`?brA2p@LK_6Q9#!}6i^Pk7T3*LJ7Bi}cA-^j6NpsM5;Hs55&U*A;nj}a z@fP9VeVg!ez?Qe!zhgEGJacMSmLO3osUCi1=XmW!Zcx5rBviV8mI%dJf7JcV{@Ujm zdWd!HJC?3yGx}bp-Pxd6EB%q#W6#kSSw>t8eU25yz0Q@t$vXARw&gf!Htz_<;6?)f z!Gu@*)oj(>t__Nq8V;z@qQZWyf*9aPMmPjx^+k&y^1t=A8NI!>g%|~Ky;7dPUfBc> z^|C1$+s2_c+39}KBkr~Af59z}bopD{@>bWp7yK+*@uPe7dbixWmDKv?=1HDG*f*G4 zUeH>9l58I&1{h*R?g*7mu^#d7(_h$?_+j)57T7jAz>h$!03P|TEKb@=o@HqnZ#Kn4lBjeOb-!h40~cg0=>q{ z1{fp8xqoO>J;X70K=rw3ZPQ??THJRM=`(h2z>tu8PEDocAVh6_j3^k0O($Jr{sU(R zec|dAtG^N_7AzK`9k-IrL^88=14mPlof|lXzQLkQhJn0WSge)yx~TA0<9fwp!YY~l z=A3Wf094nwX%ykj>0R4;8Fo9X7n_1;*qd-!MB0pQPIg>;lkn;wm;@p{$95<7)gL^F zX;Q&HN)&oL36lUv02Hc;N0#8_h?K|NiBH*oX%4drqOl+VBaz>k2nC=R%zgT|U{?=08YB5b>|bka$54kx{jeuZY?t}Lg`FXvt1>q4Eh zuGwVM*rvfswWxH<=;d70T0MSbL#jRgJ!-GE!i8?7)=-;z3{ukqYIOEoqYdYfOWJIY z9ExI%1vERrQH-WCUahGr8fxOE7gf!=4A*1-sO_CER6K?v)-Pp&lyVUJsVy4;C) zHoFt8i8)Ex;RQ+7q?|#y;RQr`+nfFs(lt_}B8VnyP;alx(T>nb{vOOjIFBZlHn@kq zYqRP)^6sxGBvKGIkyH63#$bugiOgQFoXyus@vWxlUREJHe5sHVUZ8H2U(e^Hk6mFo zQI>G@W<+bGH8N+NvM)cpKwXz+^g%u-0L7pbYzO;6C8!4%fjSe450X?~oeJud&|;|7 zsn9Vk)VbMYZgUkQ&Ok}!j;2;kfjT7?Rj{?Ar*=uJMS1P2qZRDV=sw)V3f9d$ zlw0%`%P|j#)Jfl;Dn`Y-B^;{j7NZq=q5;9C1ws*cX=L}>#{5SvDfatUIwVt3tkj8J;VboWx{X{AXqUy9fa#>xnqr=s=%6Hhg>_U#YSRczPT$YQyXPHiK zv51^?^ey&!PA~c_tIJuAy=IVg7=4;8v_{Z!w$XYnOz+;Ij5cwiX3*7>zBphJrfo87 zJn|tnJ2!LK6Hbfhln*)6@O-t!DQ|O=UmH!yr9-)$N)FNAFP>-0aLQx6Ry(~`n_=}l z`!?4|>zQV3OmYuzn$4Rw18I5xF$b;JYLeF~2Ua89tYGX^x`dq>o5*=u*w1652QHj} z`!Toz=#zvW1V#XzWY^Gmv$V6cR59nriIvI*;+DT;qaQQS^Q`c(7=J*&+ zs$+}BC($G9_3;VZ=N|Tt@#DE77mJ=Sn49cmlPB~GO?Pf--ySYuM(}X6w;=Do&EA@@ z4B3WFTuP6#zf6pvd)V6(GyPSAca9u6qOL3pYo1uwGv)NzCZX%yh7XkB(#FP4Rh%TW z2#d5$Jmnduo(jbsZl0PMt2f{-iE;PaS8Spa?`gq>#G7@Hpxzw~JUR_O_VBjg{B} zJ(|AJx!)>VD#7+0%5*}c3m!;edvyRdo~xd#3dzsRFfIxZzfgkr6X~=kPUOUVY@cUf zH%2fn(!D&bC^%=Wh&$4_dw4a#ENU5%9`{_ktxYm4;&xh!>IYXjTbi&msRbQ_?ZHDw zf85Y^j8=;|XWbI#gC|Ap30U<6Wn^v`s(4p*d~^m^orwmH|UMiICJ1VtvIc!w8&iLmZ!7E>3wM_>pEj@ zQVHHx&r0SPU#nT^J%UIrNqCi`H1ei#1Y(qSg+bBzt;s-b=bie&;NkTF}$3 zahhuLr2KJx@R_PbcD2M-C5wiYj$4YEO6$%R*q~G5#1>iCqLDI`7CFU9vB6Slic3xV zSxH1%Mzd;hzgZ(CDS6WK<67k5%`I|or(q>0USHUj*Vwa)L)!&MC)^%6$##~LR-VN= zWOBhctwu^#SZ?9ags*Y(#Rr>$sJ5#mYTFx!g28~3mZ;`w<(2-T_K@x{CoN+q3ghV= zcC|3Uz6ci20AB1=%SjJU(|)u86ZZ@iI4R@|#;L{+caeUz>KqMp4#4UwcAz4)>UEuy zJ~+)u^(}gl#Qu5_pWpf$#3Sjkb^T!bSDcVJNoo0^u_F)C=XkpIe_V2svVQ_MRB62H zqrL3ntO7Y#ST6?5i-h~J(d3MpwfBv{;ZI|>7H2hT;JC38-vAvHxlVr z);KGTj$v`L@8TIUCxvcid2>eN!_>Apz35bSVopdznG#wx+s5V8-zG+NYUI8{_+sz$ zdXjxR$4Fmcnz@!P%awEj@35(JhYrbeMT==@DV2^kXN&#B6nLCK^e={EUH{q` z@kS%*&)1Qdo7npAV=4PvDd)6OQP&iJYvco#Fs~O~#m3GX&4rY( z7w2slZdjq#BeD;TvF0XW!KxjV=C)YX@cyvb1#^ozDa9>%w3kV zk846=v11GyYg@`a?PB$|;k1=GZ7GIMac!>NK)7tx)oYIu{t#M)d6Q9A87y{UsYL@h zor^6g3a6j4O+^uQhaxq0n5kQ0CCqDqE?E=1rH%;dp0OsqZTf_N)hthN=`pg+a-NH# zYn$aK+`g7(d6zR2%QM88C%rJPS>EPsme;iwJ2)xVNt5yQNl+R){nI#dO~Kkybpfxn zsSa;ymFBr1cD1O2&SYyA459h#ZwsQh$8n3tQq8ZMgVwg`F172#x{}{?pS0^n)~)|dSKqEns@w6K?tiuG zV(Sk6raRiM>sj}1o31MgKG3cVuKVyP>$&(@x{vK%ypX$el zd;rbpQ}SJ5%+tQ!yym%hYg^pM8-LQJZ;uzNTM_b@2yodnmsB4s-b({jmG^`6fgG)x zRKlh#%k%HhwrOgXP0NgM`;Yav`WZgF9W%r)HwG0viv5NdI^___-`%M_Mcvo>BJH)) zJCN5;Yw@XaTntB&sagH(po()_P6-K2NZ>eo#T-@IM z(&=P2cZEzZvl&nKp#Nekp0;2C)jhr1SN&G$zX1nVmif#V-KeyqR@DU51bI8oqOhm8 ziGIZUt-bAgJrh=r3O`v#jhbR&tiMeM)!)_($|zK)tVeD+%?ehAb4m-VTpb!U)~PWX zVWr;U;gqo7nT%Rdjd^4Xt6FLFQ73>$-psD9>>Kf#lY?~`Qe&}0J!(6bMXgGs%h=3S z20EXuSrt$J$&RfGi}=KOB4W6B!)6*or4OCo*+z`H+ZYNTMkNQkv8pdU%zU4X3f<#O z7q8oz&@($>lQHH_qiV6uSv~669US+~X?E%PkqIsg$D>7l*TNZzU|d%EAF6I(sjDYN z^*M_!C`IFnGjO~6{oS+zk34{#SRF<;vJ0z?`rhcfz!k4P}hrJKY zW)JLt$J0^zCZ2_BGVrWeW5+XQ?O}~@Hk&o99i~%HX*Zewx*-uioKeI06~%Vdw%xYZ zwhLF;Hs6!YW~}QQb^c7-nXb*^WmxPwVaWN)y1B+JPLKSFOJ~vJ zE5h~PI^74yms>$Zh{f+isLlEaZ^^gVn)U0rl=qmvEJ^ojgqoCEmWPbCmW{ykLfIfZ z-QH*728K)B`3Me$VuRVx&C#lux;dOF3tou!$Z@WKDy{X+ z!T^WX>TFaeDb9=d-RuM!eG;&e&9MnlXC~l>H#7LLaZDx7q$r~Uv;tpBG&xgIj!D(C z3!D4GDK~94dgD?}4_qVoXn$PjJ#uWbR=il{w>K?J%l!A^v|p@apWo)Xd*n^7w(njx zSZ&4mnHWly7?b)XZZn(q7bC8}gV>tCjGzOV<1fb46qjl@-KDQA_70!gCHd+Qg0g+^ zJW}#0zJ^E(n>}(B2L5lY9{K%NbvN+H3t7~bOd7yuZ>jM0$S=P~wA8$h1#UGW_I!IR z)f=1F9xL+3^4nuOy|Ll#vG=#m=mpEqc!3ZyiU_2KLwZ78Q(NQvCF)HUsRQv`g?z$WKZp$fCIHevU>lEBYKug7C2pZscBiXU|AOlk$DA8oR8J^QVzH2!Ns zWY4SJ`{muaSkn1g{k`tQe4mh`O|STo7C%W_Wlq;*VNG|nQgMRPJ3kg#_fqKgIFas> z;4+wt zco>`VaxZ(J8QRP?LJ-FG#zz6eBYHJG1@Tlc3CsXRU@=$O`92tNhvMEY*< z>LYeXd+WC9E5NH0YA)o0PCkaNMLJoL*H1ZIE^qoypv`)6aIL}Z3=7_fk5#BYKr2)_Yd z!aJMVSp|I=*aWtMm%vW28@vkM02SaEr~$RW0p1t!pC0ECxB%85vz=f!C~Idcq*_Qv z>uSD1Q`gIA2T zJu8gO8{gn#{edQ-9;FX0xWNk1~P#Kj0N^pg{U?R9w2fVVSf+>c7rnT5*UZHNdP}^ z@IxXoZ4oX6b3qYEosUeB<_2#d{wm~R6@-_9I8uWK-3WKFsPa)8yAT1N|7=)`3HbBOKC~z2D zfbMg!3idHe7`LlW$P8p-0qSy1g-ikCSn95A_JrkFYfIrGpt%8Vg4^IH5LS#%0f|UY z0Zq`QLau`D0m4y`hk+Ym3aJBAmZ6tb39cc$6j%`U1^yro+(sUOkRipGkO>IXz$gte z6L3`X+tA)DL2safSAZLIB&r$9lq-VI{5|&gdfvA zhyH-S@`Vfp7ZCP;j;-DET8jTx)Mg8625A5ZAPne06ZC12vrUBbKK6SNALB4~i%r>U zk3peU@M-V@kDa#HU^iydir&9lr!n{52z_J)eu+KEdhSc7gIVFeI$FXEuh!9t?8d8h Ity=m21I^KESpWb4 diff --git a/Tools/IO_Firmware/iofirmware_f103_8MHz_lowpolh.bin b/Tools/IO_Firmware/iofirmware_f103_8MHz_lowpolh.bin index cdb40f2fab870f0225c3f9ea488aaa2ba73fad86..19002c9bbf3669ce640fa90cb6fcf69f030a996d 100755 GIT binary patch delta 9672 zcmb`Nd3+Q_`v0qXW|9s$n2fD2^ojqaxwAjU+tnkmnIDf&M`pt9~D!{>Ja)585`pM)*#eOsdn--|2j%Qw?m4e`N62 zM+tvPLxe(~cKWiF{wcO_cUz;cKuNLuEYYu53y=ca#sKe*rGjPdLXwca@GV z+FVpw^t>g?*Y&y1*d_n@B4!DZv>NB-g8N_e4=w&|W=P3n79WG@bhadDx(SaJ`ADsH zqUSQyLTD^CN1{lz5b{9SWL*DqaHUUv2z==^y34uSESVCe+lo|mXAP-2+#6O~t23Y)^WrTL+)l1Uum3&3BeVdvyHtOJl9rel!7$-@#4pw zEkA3L(i=3!0;$|OJnyX1KQ*_=Bmdo{kA2iUrC4p8sXn%rsCTHbLNTX4)VRJfJc;~N zQC_WV7HA@owv^M@{mL9ug_0NR+n8-Rqs&Utz^Y1l$>h0Bjq4Dag;vQ=Rc^1Vyre8m ztx{~y31^gyROz-Me|=>)OO;Y-`gGo3l-uCZEkDC8V4mJMRxK%kzNWAU- zGjC`AB8KdJ$m_=b_AG;dF7Q~}TesEDahMrGq6TFIcNeE~N79-$rrQ5gKen)zd_z^+%a0j`y2&-PJ zHd3N`Q@vJKu}=+s>7SU#(49WVy2oyz+3Y~9k^8!eU5HKP_E)jC*l|8uEk?JNO*Ho4 z?o_d-jNjOq@(CVS(BwyuLQ8_f{ymmC!Af}l)$)&^< zzXk0{XeW7dZ*s?r$!3Dtou4drUw}Jq=6>W` z@oND&uf3$IaMfk;KIaV6>Yr3XR@uQucT{e%yFlkjH`-~%0C zPsVMeb*woqBJ9W0M6l*)R`@4rFL7ywijh$14(r)_Io-=%?me0=XSaG^p?Y?zkD1

(6I=-0~easrMUIAbHX-#WT0ex1Bjowx)@CL%hfxq0({oM&bvwi4`Xeq8HiD zq!fCA{VmBz@3Vg=8M*Hq`$GFt8p^_w2L+b7w0B2p>7o6VL|V%xC-=ijuqio)PGJX= z`vfPtOyW$E5aT2Ltk6S58pgg#PNx54fe#z0nWa1&ru)%Jq`xxr!vp9&w)Wu=TEccb zToQ88)id7bYJylaUx>BeNzWkC5a!=+IQ3!Xev@e*cA%fZ_XU?QUn?2d#eUs`>2Shl zWOXI#`a__Ns%_~PLL+u#iXc)2nl0UK+Dmvf*(4BY88f8x@zL(Xr`*TJqzK(7!9;Jj zc9?i%39|~3^4Nxyg-^23!JXVf{6v1gZcDz<37&Fo8SZ2UP|V z;X6nxzU&H6-356N&j0}!Z9Mn^HdXuBj8wsvk0nuE$$5JQ49n}{#>5q*6}4L8%M4HxGRi?2-SzgHz=C{i(f=52@(MdLEMooyJJ0_v$ zoTFmH@+!l1()>1R3>j^*99`0GtCP~vR-9C9b9=Lwy^`a!1mwRfTr1W|eh!mGW0?xq zs!5?+ZX^vOP&sucpjJ|y=ttmf)VG?3R>6kDqHaXgG?Hu0$%Ra>OV1@zWZNJ-yL+FZ zZ37Vw_CAB!1|aN@=V&7FZT%6^d7oTc8p0lTnmH}Me{N(^e{=u*0iz;|h;+=YT7BtG z%hgCs5yVt;FYj!i9jcQ8+qBL7F|K#Bn`zx`VGeav7u;W4Or(g`v&xA=5@*comER+` zLOETilMcE~u?BN&Zsela{Kz78^|>~ela{)o@_Xh*qt#w^_b~U!U$4AY7+DmPt9D0^ zeDrYc|=j{oX&@O6EP!eAbTfI^jDEf-QV!Zee zRtUXYD{jo%-oS}j(FtNYG&fv=sMraihRUq;1|FKfp5SYA(nlv);y{J_(ZPBR`h_lL zQRzLkTB+W{hNVX%aLiLXBfXGvLC)Ih!S^ZmXlw18LlZTAeOe2oC&#*EBfB~*soPt4 zyQf267*5TaBDEKMvX4D9d`i&J6DY4k6|kSJ8Qz;S?PqTeAIN>OpM5#}Vfg>Df$1|s z5%|L4WzqYl)*H=+xrSJ($5n=`ZUE>`<%n3j{9 ze$MP6YF6mPu1Nu6chRm0<-@Sm{=i>qK*K*FNl? zI5NuTlF3R1PF+dY>Wz(!Boq>LSKtN|0%b5@^yJF{`k^<{&Px zIZ&fL?2*^9nw*|Aie1hrj`_STQKX_Ew)c|_4e53?f_GwSlW((v++uE%lO50f6Zfc- z<>yVK-?M{x>**nul;0D39drH?x}P=V4~kjre$Y?a@BCD-5c7u-oO`=6+{B5RwCl(H zu=OEK+nk~C$otv9%_9fJIP*lOyug`>XGyD5?&l^yHJZ}P2XZ@(gll)HGX zrh2UkVHM5FMj7d8_Ts3x^c$_JhljmsMx_1Q^?!M|;I)eKTIpf+FBkh^)D-$8%Nd=* zQ72n9IyUU9>4Z<1fnzRM1`dLESk34N`UU&jXajb4_eRIjcUj1oL24U}*+sXqMucau zo&|TQ#QY0avJ(RX*w(@#8pfInmt#FG9XmDfX(xSD+k8fQ_p)Nwv&&=SxZCeDWo#;q zW=Z3cxewdelyT#@>rVFexc=Oat?avTiM_sP-Hho=9XtIo#Ppbab0NnAUZi>0W1O7! zChPs!Vid9Su|?Fx{KrSZU!UOr+ zoV3>=%+ogWl#`x!u!$2Ez|FY{L-C{&=hH{n!ig!ItgyWkdvW&__VL6K+&c;jdR*W> zQJCrR@eyhfN*!rFwN<~i<@*_OQpLW z_S2-k@f2t3dwgS~Hu2UMdo9AecokNB+Kng-)Gl%W!F%f50?hzoXCKq`{{NvDRg;){23mxgHA# zP73ig?+I@Cug;90Xvn^GMoWUX>svE+S;BMpI=7tQ(wMJXq9P|{P0Hj^ZFS91unY%^ zZn@0uBX)(H>n@Kfkcg)Et}n&#T-+*u={}UTsF|>)sl#=?E>8N4B~OdtesHo;(~9EK z58_+ZWj`HKqshfy#zl?UOH|i|&~p-Znn%0&vCGq<{3g5AQOHRzvX*ImLg*>IU5|WP zacWI@X-17(evkE=-Uo+($EVNcwjN~fPmc~QawLkxplvQE8fl6{-8fVqWIs+96256Y zb6jtyX@N;UULGPi(1)~`mZiE4)xIKkj2C){8}9gE&H0=SnvonI=GKYv^#W?r=86|} z)smeGPUN|B)Idi5|Ht;_5h2>V#2&Vq@7u zBI!5yk^xsk1ybSIR=JPURIi45L(?h?&iI;i(XhgPN6Da4>FFX1bdChERZeK-q?bLd z@*pS0(nY1=E;X&2BL!)5Rf|+P93~q*1=2HcJHyc`$2tuwIPvSUc4uiAEiUwFJx)uU zH0CrX&0s@|CuliovxjXj9+-T@<-K4iifKPa;TfL(iHz1kh+)`u~it#(wR z-hRi5E_vuAC%xI~Ba--^F5&L0uR%PL72l8u+q>BFbJCZsw;MZsklt@+X+L$zFDX@z zaRZgcyS~~hE>3=)U7i_3e=9 zCA_A@!sVZ7B1W~dSPm23ib3p_Pq03-jr2Wco}CvoS^1^0bA>NI%=XS67`D(AD`w)& zsq~T~S4X; zy=ykEGSW>M9Vz3ui*6smi?IY=FE;_#ekO7F0-l6|u)lnF?m<(i8Wt4R|9 zvDlQ-VX&E$%&kxs!C<_L-JdJqART5g&{Q@EPXn8br=C4+i9q}Auq@&(I2m6$g#Mjn zmk#zrf6Cra9V+^>-KG7w*-rNN(nxxcHI+v7+Nns5!Vw%X(KPDN`2_L`(4}kQH#guO z59dr~eewhjW(j2j=r#64SqwMn2wPJY%cSSl#8RozsjtzR_Z92yTC=lJJw;%ix<|e) zi6ZNgo-2V(=zPjm~mc8r((*yVKz05uhZmu{;Tdnhi*i}{$F)xI&?!C-u+egUWd-qaQ0W-TOGRI4WGB`x}xB{9m?p2?~btE z^HPBTh9o_*xv%-`Zz7Rqie80xpd@8$C8 zh+EO$`@+X4K(r)dUTvLq7Y$Zb-kaLJ`C2t;9xGm45ZI}0*Vq?N9eL9gI6BZAU^v?p zHy~hC94fd5XH8=0l24@1TwOX+)Mcs<(yS*p!`H2KxM{>@hNROB^%|#zO<(e2Adky$ zHB~Lu#2ib8`~4QnTpGuZ$!3TRWOxIcZ|^m&p;koIYls{IgA*kvE=g(xwqS zebV&y&)Mpy@@O^t=&99y>Rp>|BYyH=qnCfid*s*ZRSm0HF^ubfiv4RvB$w)Beb+>= z;FVEyJxg9`^i{v3M?T9QU)cwHK-D>^`-&8Mz}0Xu6_ZK2^PQ+6;!TTb1eH>q-&%%_xZ44i#3Z2GD`1G_s*khA31 zoa(MV;OY?Zz+GRSO1v{m{MynSK_w0HW{>#3QO)UYtv$JFJI95eVuh<8=@yOF*5k5V zE2_iDBgZ(|>#HN_R93%w0xe=)*F;eZOIi~_KVT!*7=0A=Grd~7U=2q(C73O?{X-S` z<-KV*TU7oLo`cu!!}G@4Y&;F?Y>$@ZU z>iRx0H%_&0nY8#7Nga?ncv2tc#hnd zhUZG}^Vmj4Pq55qRn0Q*^YF8(rQ=yM9mz&k_Q6a&ztTVj_F`oMoz3biW5Q=RxN5zf z!*P!@Q^6nSz_X~rw4?0D$}wHkcl{30J0VQml=@(F-6k?`8tn0 z+oQ?<6oeZ@W?d{gmi|FAygiZnhMk~Bjg=VBG|{v(O`5dqVs-Dz z`fiQvUvYYP1clGe-@abKwQ2hun_AA#-WGDpEw~ZU*M(sI_sIXx!%|m>;XFQV=kIa; zIM#<_`G~_s23xvqm{yi+753h?3qHwdgilGU-S|>09lLS};a3C0BZQv}N)et97J+2| zzmIzViXSEXU~mtN1$#ikF#JpnITDNpH^4ULU_EV{GGHyXvjyR8U`KqiC#tkeML z27_kU{I^P_z~&xoS{|t2Hs~CPy8%U*5Lvf#)1i8GMEmEL1(RX*}sKT3h-UP zXfU9I1jtU?u?SBG6F>|wfH=^Zz7yd+V1o^hEuaR}flh;q2)C?6Q$t<`AAobLAa-?mTEg z{6I9m1j1LqRd550v(JT7Brbw+7-TTyO~{)_yaf)Ip#P|P(1iFsRR>4SkS)Lg++a8C zC~S1aEOO_naS>(c!(huibS+3bZZWPRTo2Bp|6fGCo1u3jenWi+$g7Yy!4*)9w6)M} z0GDBZV?MjRvv*k7LX-kFsJ#*{n*sjE;MEsxw-%!gi!jF_btl*j_J9N6G8k(`{XsK0 zjCc!V3OI)F6;Ot7Z;*0-9lhKj2w_| zz)?--m?68DqBWM_>wr4YnUIWd1k#$2F9qT02#5yTN#gL@{zqatRAqn9!ctG1T`>XM2z+s8Ay|#Anw#~>7>cIg}19pQ=U>P_EN=$@| zIQm;Nyn;>12{w4QEv~xEV^ckQJd}Do?M3*-;B9*SW?j#2?2htzW*>fv+soQ^XVJba T^YsQgkI^?8=qUEV8@B%e?-JY1;G0c;Ws(#virSy+-&%FavA? zHQ?3f310=ygDc>t=ZT%Cs|g43;Yp=!vZ!5lr2m<;lp)V@6b@;5{Xgg3 z_OAWECI0_OyWF4fi!%sc_zd9*{z@fc=B|^vH4;fnuU<{}>T>h$n7NZpt$AI)$dg{v zRNw73%l}H=9b(LoNJfA}@{BE<6k2CaFV4!72r16$)>PP)Hl%a92Bez#x~K5$NUIL@ zS)$>2X@L-F;j?)M>;gEmYO57I^8fB!M~DuAPa)Ys zzfyXa#rRL^k*|2<5|1EKX=$@QI`2Li7c1(eO!kuh?7-}9YTKxp_)+usJP}fvu8W6S zn6B%HzLiRWDWK-6k5=@#OpN=LlO~V+dh0=@k_0$B@@oj4Bp&${wy^7}ph3;VcsO#s zl4!CJZIg*m=?;^-R%m(YONH$Zc$_X^azK>bX(0SLup*l9Ss=qm__>hJ2!F)cuKTuK z*8K;Y3g{SE2R=of3CK&$=NiJQTns&V@LKVBVu&JlG4G`5RAD;;*K^A~EWF!%`*ow# zMYA7`Jn3w`r-{##N}tY?0!VV5#yD#1Xv>Gn;G`u5*@f@IVw&FmAo2t?u2-x{JsQ`Q zhsKj%*OgW(TLjvVNLxy2^g(5wX}w~J<{L9?^~#(?Ev)t{FPlgsHLgWyj<8c$+4Hs{}|N8Mv8=9Byn=pIJuoDN(l}PseSTP?GZxjkh^gss(Mw-D`-vu0P%nMQZg)58 z{uPL&R~^{nb&jU8s;~#4W6r4U?4OiWbxE;toWXIc*sPaQ&an5w4{=&2vqkizi`d49 zc;5ldmz0w6RLW;(A{Np});Drmk6F;oNxBza{oq;qxi19qLuJk^kL=5KM;1kNZ~0JJ zKmK^*uB_{gq)uJW9qVBTi;7yOI}Fd2Qe6?Xjq?q0mZi5`q*5SD6$bWBMjZocy5x4T zbj{XDAGLO|2%=8gY`YNIOEt_tK=>U2M3@8lBYHpKwv@NAl5VHc zC+t(fL$|X}4QZn~w;ERZ<@j6qY!c^J7bu1y!+UO@O2;i}8}TKAn!_!;twmVPb^iuR z)ZElu^AE6`=>B0}y5SusR6HPa&np4R>XI)lj1{#gW?S@Dx{gH|ja=ygmTpYq#vEWz z8^`NiaAk^y{lnOkD?h+~HvZfGt)df!Dg&IxarX#od_hIQdVxxppbdbQll+yN1*On@ z>b0ZM262#;lep%X!lTgELp#~~_BMB{m|!KS!;M6JK>~$?wf_DV7Lc{hrEVG$Sl$t8%+#m#Wq4OJ=fZn@%h`mqbrnM zcyS-z>*9`?brA2p@LK_6Q9#!}6i^Pk7T3*LJ7Bi}cA-^j6NpsM5;Hs55&U*A;nj}a z@fP9VeVg!ez?Qe!zhgEGJacMSmLO3osUCi1=XmW!Zcx5rBviV8mI%dJf7JcV{@Ujm zdWd!HJC?3yGx}bp-Pxd6EB%q#W6#kSSw>t8eU25yz0Q@t$vXARw&gf!Htz_<;6?)f z!Gu@*)oj(>t__Nq8V;z@qQZWyf*9aPMmPjx^+k&y^1t=A8NI!>g%|~Ky;7dPUfBc> z^|C1$+s2_c+39}KBkr~Af59z}bopD{@>bWp7yK+*@uPe7dbixWmDKv?=1HDG*f*G4 zUeH>9l58I&1{h*R?g*7mu^#d7(_h$?_+j)57T7jAz>h$!03P|TEKb@=o@HqnZ#Kn4lBjeOb-!h40~cg0=>q{ z1{fp8xqoO>J;X70K=rw3ZPQ??THJRM=`(h2z>tu8PEDocAVh6_j3^k0O($Jr{sU(R zec|dAtG^N_7AzK`9k-IrL^88=14mPlof|lXzQLkQhJn0WSge)yx~TA0<9fwp!YY~l z=A3Wf094nwX%ykj>0R4;8Fo9X7n_1;*qd-!MB0pQPIg>;lkn;wm;@p{$95<7)gL^F zX;Q&HN)&oL36lUv02Hc;N0#8_h?K|NiBH*oX%4drqOl+VBaz>k2nC=R%zgT|U{?=08YB5b>|bka$54kx{jeuZY?t}Lg`FXvt1>q4Eh zuGwVM*rvfswWxH<=;d70T0MSbL#jRgJ!-GE!i8?7)=-;z3{ukqYIOEoqYdYfOWJIY z9ExI%1vERrQH-WCUahGr8fxOE7gf!=4A*1-sO_CER6K?v)-Pp&lyVUJsVy4;C) zHoFt8i8)Ex;RQ+7q?|#y;RQr`+nfFs(lt_}B8VnyP;alx(T>nb{vOOjIFBZlHn@kq zYqRP)^6sxGBvKGIkyH63#$bugiOgQFoXyus@vWxlUREJHe5sHVUZ8H2U(e^Hk6mFo zQI>G@W<+bGH8N+NvM)cpKwXz+^g%u-0L7pbYzO;6C8!4%fjSe450X?~oeJud&|;|7 zsn9Vk)VbMYZgUkQ&Ok}!j;2;kfjT7?Rj{?Ar*=uJMS1P2qZRDV=sw)V3f9d$ zlw0%`%P|j#)Jfl;Dn`Y-B^;{j7NZq=q5;9C1ws*cX=L}>#{5SvDfatUIwVt3tkj8J;VboWx{X{AXqUy9fa#>xnqr=s=%6Hhg>_U#YSRczPT$YQyXPHiK zv51^?^ey&!PA~c_tIJuAy=IVg7=4;8v_{Z!w$XYnOz+;Ij5cwiX3*7>zBphJrfo87 zJn|tnJ2!LK6Hbfhln*)6@O-t!DQ|O=UmH!yr9-)$N)FNAFP>-0aLQx6Ry(~`n_=}l z`!?4|>zQV3OmYuzn$4Rw18I5xF$b;JYLeF~2Ua89tYGX^x`dq>o5*=u*w1652QHj} z`!Toz=#zvW1V#XzWY^Gmv$V6cR59nriIvI*;+DT;qaQQS^Q`c(7=J*&+ zs$+}BC($G9_3;VZ=N|Tt@#DE77mJ=Sn49cmlPB~GO?Pf--ySYuM(}X6w;=Do&EA@@ z4B3WFTuP6#zf6pvd)V6(GyPSAca9u6qOL3pYo1uwGv)NzCZX%yh7XkB(#FP4Rh%TW z2#d5$Jmnduo(jbsZl0PMt2f{-iE;PaS8Spa?`gq>#G7@Hpxzw~JUR_O_VBjg{B} zJ(|AJx!)>VD#7+0%5*}c3m!;edvyRdo~xd#3dzsRFfIxZzfgkr6X~=kPUOUVY@cUf zH%2fn(!D&bC^%=Wh&$4_dw4a#ENU5%9`{_ktxYm4;&xh!>IYXjTbi&msRbQ_?ZHDw zf85Y^j8=;|XWbI#gC|Ap30U<6Wn^v`s(4p*d~^m^orwmH|UMiICJ1VtvIc!w8&iLmZ!7E>3wM_>pEj@ zQVHHx&r0SPU#nT^J%UIrNqCi`H1ei#1Y(qSg+bBzt;s-b=bie&;NkTF}$3 zahhuLr2KJx@R_PbcD2M-C5wiYj$4YEO6$%R*q~G5#1>iCqLDI`7CFU9vB6Slic3xV zSxH1%Mzd;hzgZ(CDS6WK<67k5%`I|or(q>0USHUj*Vwa)L)!&MC)^%6$##~LR-VN= zWOBhctwu^#SZ?9ags*Y(#Rr>$sJ5#mYTFx!g28~3mZ;`w<(2-T_K@x{CoN+q3ghV= zcC|3Uz6ci20AB1=%SjJU(|)u86ZZ@iI4R@|#;L{+caeUz>KqMp4#4UwcAz4)>UEuy zJ~+)u^(}gl#Qu5_pWpf$#3Sjkb^T!bSDcVJNoo0^u_F)C=XkpIe_V2svVQ_MRB62H zqrL3ntO7Y#ST6?5i-h~J(d3MpwfBv{;ZI|>7H2hT;JC38-vAvHxlVr z);KGTj$v`L@8TIUCxvcid2>eN!_>Apz35bSVopdznG#wx+s5V8-zG+NYUI8{_+sz$ zdXjxR$4Fmcnz@!P%awEj@35(JhYrbeMT==@DV2^kXN&#B6nLCK^e={EUH{q` z@kS%*&)1Qdo7npAV=4PvDd)6OQP&iJYvco#Fs~O~#m3GX&4rY( z7w2slZdjq#BeD;TvF0XW!KxjV=C)YX@cyvb1#^ozDa9>%w3kV zk846=v11GyYg@`a?PB$|;k1=GZ7GIMac!>NK)7tx)oYIu{t#M)d6Q9A87y{UsYL@h zor^6g3a6j4O+^uQhaxq0n5kQ0CCqDqE?E=1rH%;dp0OsqZTf_N)hthN=`pg+a-NH# zYn$aK+`g7(d6zR2%QM88C%rJPS>EPsme;iwJ2)xVNt5yQNl+R){nI#dO~Kkybpfxn zsSa;ymFBr1cD1O2&SYyA459h#ZwsQh$8n3tQq8ZMgVwg`F172#x{}{?pS0^n)~)|dSKqEns@w6K?tiuG zV(Sk6raRiM>sj}1o31MgKG3cVuKVyP>$&(@x{vK%ypX$el zd;rbpQ}SJ5%+tQ!yym%hYg^pM8-LQJZ;uzNTM_b@2yodnmsB4s-b({jmG^`6fgG)x zRKlh#%k%HhwrOgXP0NgM`;Yav`WZgF9W%r)HwG0viv5NdI^___-`%M_Mcvo>BJH)) zJCN5;Yw@XaTntB&sagH(po()_P6-K2NZ>eo#T-@IM z(&=P2cZEzZvl&nKp#Nekp0;2C)jhr1SN&G$zX1nVmif#V-KeyqR@DU51bI8oqOhm8 ziGIZUt-bAgJrh=r3O`v#jhbR&tiMeM)!)_($|zK)tVeD+%?ehAb4m-VTpb!U)~PWX zVWr;U;gqo7nT%Rdjd^4Xt6FLFQ73>$-psD9>>Kf#lY?~`Qe&}0J!(6bMXgGs%h=3S z20EXuSrt$J$&RfGi}=KOB4W6B!)6*or4OCo*+z`H+ZYNTMkNQkv8pdU%zU4X3f<#O z7q8oz&@($>lQHH_qiV6uSv~669US+~X?E%PkqIsg$D>7l*TNZzU|d%EAF6I(sjDYN z^*M_!C`IFnGjO~6{oS+zk34{#SRF<;vJ0z?`rhcfz!k4P}hrJKY zW)JLt$J0^zCZ2_BGVrWeW5+XQ?O}~@Hk&o99i~%HX*Zewx*-uioKeI06~%Vdw%xYZ zwhLF;Hs6!YW~}QQb^c7-nXb*^WmxPwVaWN)y1B+JPLKSFOJ~vJ zE5h~PI^74yms>$Zh{f+isLlEaZ^^gVn)U0rl=qmvEJ^ojgqoCEmWPbCmW{ykLfIfZ z-QH*728K)B`3Me$VuRVx&C#lux;dOF3tou!$Z@WKDy{X+ z!T^WX>TFaeDb9=d-RuM!eG;&e&9MnlXC~l>H#7LLaZDx7q$r~Uv;tpBG&xgIj!D(C z3!D4GDK~94dgD?}4_qVoXn$PjJ#uWbR=il{w>K?J%l!A^v|p@apWo)Xd*n^7w(njx zSZ&4mnHWly7?b)XZZn(q7bC8}gV>tCjGzOV<1fb46qjl@-KDQA_70!gCHd+Qg0g+^ zJW}#0zJ^E(n>}(B2L5lY9{K%NbvN+H3t7~bOd7yuZ>jM0$S=P~wA8$h1#UGW_I!IR z)f=1F9xL+3^4nuOy|Ll#vG=#m=mpEqc!3ZyiU_2KLwZ78Q(NQvCF)HUsRQv`g?z$WKZp$fCIHevU>lEBYKug7C2pZscBiXU|AOlk$DA8oR8J^QVzH2!Ns zWY4SJ`{muaSkn1g{k`tQe4mh`O|STo7C%W_Wlq;*VNG|nQgMRPJ3kg#_fqKgIFas> z;4+wt zco>`VaxZ(J8QRP?LJ-FG#zz6eBYHJG1@Tlc3CsXRU@=$O`92tNhvMEY*< z>LYeXd+WC9E5NH0YA)o0PCkaNMLJoL*H1ZIE^qoypv`)6aIL}Z3=7_fk5#BYKr2)_Yd z!aJMVSp|I=*aWtMm%vW28@vkM02SaEr~$RW0p1t!pC0ECxB%85vz=f!C~Idcq*_Qv z>uSD1Q`gIA2T zJu8gO8{gn#{edQ-9;FX0xWNk1~P#Kj0N^pg{U?R9w2fVVSf+>c7rnT5*UZHNdP}^ z@IxXoZ4oX6b3qYEosUeB<_2#d{wm~R6@-_9I8uWK-3WKFsPa)8yAT1N|7=)`3HbBOKC~z2D zfbMg!3idHe7`LlW$P8p-0qSy1g-ikCSn95A_JrkFYfIrGpt%8Vg4^IH5LS#%0f|UY z0Zq`QLau`D0m4y`hk+Ym3aJBAmZ6tb39cc$6j%`U1^yro+(sUOkRipGkO>IXz$gte z6L3`X+tA)DL2safSAZLIB&r$9lq-VI{5|&gdfvA zhyH-S@`Vfp7ZCP;j;-DET8jTx)Mg8625A5ZAPne06ZC12vrUBbKK6SNALB4~i%r>U zk3peU@M-V@kDa#HU^iydir&9lr!n{52z_J)eu+KEdhSc7gIVFeI$FXEuh!9t?8d8h Ity=m21I^KESpWb4 diff --git a/Tools/IO_Firmware/iofirmware_f103_dshot_highpolh.bin b/Tools/IO_Firmware/iofirmware_f103_dshot_highpolh.bin index 3d993264ce8699942bf654a8877104efe329e02f..dcdc39f66d8b805e0bb85effbaf9bd894a20623d 100755 GIT binary patch delta 11147 zcmaKS3tUvy_W#~z9t;XPh$s({d58=mIG`wIDi1llR7A7V(m=AtM8mYgGzT9jrWUrf zd{LNM+RX%!3UvfaZ+g3S!Stqe`<2}kiM*Xj@tk2^|L+;F?Em@QAD_>6uYJ~D`?dDk zYp=bBGqfn)y969yA90`|)zs)`VdX?>t5{X8}79*+4Wo zz@pcQW;L)KI0V>$R^U1?Mfc}crpTfa47XyD5`(b^uO*$VpI)@#0zfEMf(Hvcigy%jpW495UsDbj3FhNy>=IEJqs^zGHQLg5&cV z36ba4q98h=B^u2w@&h46C-ZKeAsU&#OigrUz=O=*C((M$?P=2p3ti-UPa7c$K3Jl0 zWSFxxG@PcCW(DVkTVD6mUJkeP%P|Q3IPrCFqj456tPF@{UPS3rvuiTRkn zjzrTT+Pt8gT?^9hkmq(4?OrgYaC2d0;U-IjpX-v!*eiEaA+rPvN`B{@o(lC2wITlwDKPPV0%JRao(|WA5Zz2Y(HsDXmZp*bnyU3Dx&=BG z-ftJxvW9-el(Dejal^F@O5Q8F+{dIs^S6F}mx*z|bkyt>Ri6D)Ez#P%q8hoQM3!MI zgUf>L4q`ksXq}X3&LK*>nNT5#`Sm~Gzuj?6GW1KVYhn%kjr2Ub+CR!VK89#iKqIgT zSZ%@{0NoP(XG{cN<{5jaqKDou*N%E$1D^wdz!N<(QOL`3b)cm4t)!JGJ1;#~E3Kbq6#6LkW8z1howpTnDNPDvzEEB| zDd&uol9XNO6?0r#Lt5VKB3U_)sjZ!=BhG{s=Qkzr|;o=m)TV{K)P^t!qI1~slh?n&J`X=>7s)*EXoTcon28tD~XvotB` zn;S8?Yb*O%YNSf@#gb2@JLc9K7~s-1mG#cwdWKaat%qz%(wQ5Xzx6I&Q@JbMdS~Z{ zVR;djDeC)pRjUNW}lt(PukwuOFX{(aX5MoNS-dXu!#$7)69bYr= zefXqa2NQV6^TrKDnL?PT;Nq-zwtkptp#pKL=5M;8Wpx8X61-xAQ)}?g3oj~dtM5E# zwcfQJ>7Kpy&Pzw~@0@!sn182ySzDN)s|}X^%fMZ*^bMhjFonj@5y-cPX2gzjDs_Is zU6-zIyYzQ69a(`?slP0haDGB>clUNlvB^7QW>|gTg|2RnqSkCHVg(W-Xp|*HU zeBT^DVTjYfn|QO{Pl#t5!;OKmiOc&(c3fBL8^ir5)z+VmU{u{>{IetP(6?Cr;1C%9 z{J~FPBb*&PE=Vqv8ldteO1=+e3+Y&P zS{FAk&T&byB;5|L?|jMn?N>VNP0Kv5c#$de8T2m8(vOJgc z`;lftqo?GlR_h~t162C6Q~Ig>?g1w4Cx=^yYromixBU@$qW#CVqad~lt2MX8eykdW^ir3cZc}~b+t7Ai~DP7S; zAAnE5e-wNwob{M^oW|(&T4JhHHI5U?JO_#nLgqgn6>ss$)O&~_I!~5}E3A+v=v4O2 zgcF|hTrc_ra^FDipik~?v^6NtWFY!f$uiDQu%n(_>umcF!vSfBPW8Bb4=QGRqUY^L z#Z$j`uoi-S|I|SxbhoDEGdj630~S>+aMoPjxR(e8X|RX~oC|Lg5$wOg!olSco^`GR*O z4kG3jzjQYrB~>GNt=`0Q?^B_itxY%$7o0g_4BgFM9+60Qup=Xk^cD8i2qPys>!lI> zY2bXfvLjPT5ALrd!U`6aID%%eoWw}_5PLc?CTNJ;%+DjSk$ys$lO7~O3VS;-R^{g= z!WMQRF*!=@mizLRAOt2t%m873StW#A$9vK)#=yewdhMosDEJXwF45~{i$@yhuWakcsK7m_e)2d@BXTbNvwGXe-n6I13!}!- z8s?wu?X$&Yf*<=*((x&_swOsIbdsv(glq;=M#pdgC)f+4S3P5QgyrdYW1$xQur`qB znt>Le5Q0B|3P24&`oIeSI=~Fv1b&feU!wa7w7ECYodaqDPzT?sKmazL2KWUs51wRm z$LOfQtYe}g2ROW9l3OhpT!uWNA7qi;tyYrv0TGU|6Jx^SGhL~5!TN!4IMZB{4Iw#| zp=!bIrN-bXX3JleDl8F}9a(C@<23OKVJxF5!PajjvqfQf41Aeq@`&(=qc9jbN-=}V zW;+Rkk_RV2Z-}NWa+D>Pk?hi}6ws802eOIqsCO*VnZ9(oHwF28Upm=42KgLc%6ms6 zpW#bWy~){Rs4(7}oR^$CIy<~@bl&LPF_Xg!iO}JZ#Rfq@DdanJ{3zC%5*d_`n~vLYc^%2PlSCsg;JwAH zf{p|fHt<9vFKSg2ZWYMO`fCK07xp=))IaPKLa0tH1Tn|>g^aHa;8W-__77ekxLWSIr{G`A&BqKRaIz31_aKM6 z9&rL2m!;?S*x1}GGabTS%Nj^S>)*>7N$FztZMKd6RKGJPjzf@eHZO->Vtpq^_R4hY zczGudI#oYI1S`ld zirnKK##3I$cUxdZQ;JPif~)|yD6oIz7tw#P#A$ERwe0+~IrKvoQ?M4{&R+_m=nL$N zf~8oTiPOhKKH$2)m63mH+lGUM{6hi{)`MAZ~FF%bTgEo7ke6(Fk7I%rUZBX6~j{?CFQc(4p+@ zhdXfWZhB;av{}UW0M`J9Me_uF_TyGF*&JxMXj=Pz)K$SptMbT9MQ<)E>N>-+_y)GDXB#r z_i7W38Js&^GL}Z-j-YV*iN+FY7|TDpfD`6+8A~9oox5OQo{G=rw@H&~_c_(0xkm)2 z!&t(-`NRU6ypI3a*(rV$aBkE{em0-V!=yhC%<+h&(nFbNTUEXgQXThZlPXseBX{E^ zU&_}t|iKSy$;M{x~#pcW%Njurrxg!j>yi^x3#)b_dye3!Zv=EKlKp{r=5Rlr$ew;g% zTd;s7J&|Nw>M`<32x}C%3SqwIkE_b{1qgks>qxdHm$>o-7Bww| z@54u7%eK4z*>1?F?NDlpIuv~lrZ4I6ff9V*4K zjsUK>gJK(Qa`)1!cX`FHz4>=NOUsY$NH;Zw%5z>#nq;GCl}gGt)dnC88q8Nq)7aZZ zAqdqPisE%9%yPf9%zQ<9h&+~ylYJ3OPZi!PAInpnLJ09NZr*6RoQ<7Vj5}WSJiYOT zizeSXs*JzY`om(XcZ*7i>U#T3VNTK4ZMqUpXk^#sMbSBo78`@Mc+a5gv^G_hEbS6o zS#oid?=p6HD$z6mig5*{9B1&KqqS zv_6qtF5bYkJK0$G8W;}m}Cys^Jav74Bl zYT1rmdReNfSu>ap(_F2w`*YkdAjoY3s(?3uhP__dybmLRM7VD zuE8Kf7FbpC4z#eH3nFM7YgjNMj7ewO4YbrID`Fr&h*$IH76qCIT_2?Hx1UqcmO+vH z*KNK-dPDke+ND3V>3tP9d2hDKi_Fd~He2OYip1=zq?_i96CrsKWpVZA45bahlPUc0 zflxKiITbV4)Y2b5NcV4%{WKMJOXo%r)7_RgP^WhtS6gapz$LV5iC-Rh!!Mf?cDt!@ zJ<8+~+25^$UCSLFwi1nm_^!OcoTua?EhDCyn7AmAQl?rwk~Xrji;Xc~!+|}(r@@dp z;k>5;`odXlAV#lPi5o02;%mEC)UmaT^+VR;yjX1}ao@Lo-geJ5%BPHcENL3NBJ+}_ z*Pk6S%kI9^ZZMXIW6kKL_94YdqciM8u|9oMTF1ppSe1x6IaS8}1dren|JK!EnT!iI zv}x8os}QClmND_+d>C|o$yLCw=82ISo<@K+ZdtxEW*wR5EtlSK z9catrf59!8U3&Idq&z_RB1bH;VZP+;ZSsfN#PT|eOKfKcO6T;Q1fKFrfc_Fp$t6C* zf|eNLr7<*#6)!FFHCx-v{8Awz!Xz8?~k)anwO*v9AM%?G=hBZ@jS6ek@_ zsvR$EvS*f8O>Rq(mntd8QQ>)ScUYc%n%#KbknCGj9G>!ma)S1xhWD@I1Py+AAS9)M z+I1ulQ$Frg^18ZVJhAKW*s_9+e_@1b;|bZbEO{ZqYIT?!^Mz>zLj{uR5X&5Vv3X4`}#ajht}lI2}e?IpL?{xNiuzk7Mx~}i7x{V-j5u}i$-t(i1~8!feU_$e=U ziLKt@lMoaHP#xS?gYvBqK7fy{8{PO@ofZl_?iz*bN~uj_NCb`abxVbbC#f)=eODII z`)$`xZTY|2@S7pp!(*c@M2yipHipMb%_f- zp>@R;F1NXz80Gt0<);WeVL&dClbGuz1NVT7=~iU-dDeTk?cUX~=2P~|5-7ux8z=ZRAtw~Z#&r7l~Eks%x13~%~ij`USGMM zJG7}j{N;I6-#d0!6PGtb(i0Ak8Kf!uGrap@6j;5CirW5sZ&tl34_B1-RS_W{dxf@p z<+3gR0=Z5WW{rqVcB-KiNlbK73`r8ly8Lq_@ujXz*!ON{zOV{5wxmlE=d(H1g{-V* zl>(cCIclQVIjfl~`;2v2r_s4AuRK})SW`Znrn4jE&s)7>LQ@$=q-jv#LHd$c{;|p{ z4r!|Vo%gpMUU<`v-+9eFJZ;m#-+3SP@YGG8{LcHJhvzzV?swihJ-pveUHOc#eXFn2 zn{4Bn3(@^tBpN@zWDH&Q@1p1z{3qi)5;QJNUiY`3@0--GSo<=^+gyQD0`mg&XWFBa z113l7h_I>);`&~>L^$H=)l(v0d}B~ndR%_U*1w4txq@hpq|j9P;XLt8Hevm%)Wt5W zU(WsPX4xB(`jk6~Y3er`y)Kdne{-|S4Wn@{ZrYI9f0O&LdZ|Tqd7HFHtK-8`iEzis zLMsP_dc}87$gOv)ue4`sdrq*)l@fiCWo|5@wd}o(tJP_{@Uzt}mhj3&jaN)PF8@ry zp4{|kgffrdEhj@VYZV>MirIy-g&gZg@N#^U{kkb8!sXq)X^3S^QA%&>)aee zr?AK^kpm~V)A=7P_An}pg-phzpW9@Kk@W>zwsZ7B*7n-?crAVlzQ4mX429^7&y}Nl zY$f>gKL%rE1ywW0tUF1KigJXZr5TvWALVI|(T;UE7tVzSc#A^Ia@q_h6XUl-+S@hrrm|l@YP~=)QD6Uh~zmLHm!I z!pe^l;e)QB{CNJ?HZDPV)pz7zFXWz(-~{Dq$q#;T=E7RmxVu}6W~SORBQWE5@J70^ z_oU#}1V5|I-xC!kOUq&P_tLp?ja}=PIQ5F8oksA$SG^~ZYS=&aL=61d@%}3{9ZLVG zu8oe|%r$)AMGn1HGg|$KZ_;Kqr#cU}-9yze2ufS4^_<{hcdAWvJBxfPGVWCeSF5#k zzw+VE2;=!X^!6z9l7FWr4Ph3#JM{_P_~jwJHKNZiD7^y+fHZ);^VTp9we{7${p&L|H^#?%nqdTwXZ32w;&l5g7m28Y9vM?FaLMsV^RJQi#t#ZiY5*$wYtS@8&T3!*@vn1 zng$KjLY->8pUxw?yTAc;fck@Wg7yNngAN3})g=#Ftv4axhIm9C;M*Qewp&c_5TTFc z5&JtmVjs6hEOC3qsXbGC&b9-JAwsWD;C$F;n}T|2amSLMS?pfcZxbI7igmj8FCT2> zyXHyfJw$(3e8o{yM}{lE!F^qk(WUB4m^AcfKO)%zb2`OOd=kqYp^)hHEo{t&v)A^q z-J9R_73Dj{gB~Wl`)KkC53P#j>5fiuna3=U3^jgUl4Ik$;)4#EHs2ngXukdV^o%=% zd}@C~aV7QJwoB~g_cG{2cKW?9)EiUqzY8h#uOBqf>2(t@Utm@${>um0i~IrL5O5eE zJ%4-C5C{S^9de)zz0>z z{QrZh0B<9Z2K--xT8;AYKqhc+P}h;q0j2;2KEAcPXeU0ZfxW;1;1F;ar~~d*o|XMa zerrC;fg;@BmjiXkSA*t&?gc#rEI|GM=)L-?N1#DK5BT@MZGHF;foL!jfmpx}ekb6# zuY3{s&jYi7BA^1;2;A#nFY*Od=p6I_upQV5R0H>9?hQO`3giIm79=)c5ikq50EA%F zt*CUq2e&3;Ab=a7C|3dgKp+qVgaBcH9*70vfkYq~7z>OCPNS{Mz*XRE4=y}HX81a} zH@bEdbON^kJMiCZeCsUC4p{y;W(vr175Lr)9G<`u4nJT$3-)=Sa}LHg_rEuljIyyn zCh&iCc^2j8f$@dV74YANwgqKd3(3=(z+xx?_-}#*D4Pk)nvZz^|4ps}WgCIyry&dc zS&mKp&}vN%Ac}h`1T9#EmhrfK0f=0J;R1Whps{ka1YE#7_FmBIptpe2c%i1tVLPDP z@qn`cbnCNl1)vvztH5f=RRHIaU$hFEMt&=>9e8*rlI70>D9l_8Tfz4%G}M6aYUD2i zTNmQryg*L_`V!ax=z`T4262wDm!Y|85RorotZ{M&Wn}o(4S&aP*J0U9<@ezk=NlQ~>uD-3|G6 zd^dtp(0It{K@Z40z$Ui`tOo!2EocMSxfugR*;(+<12Y#dT>R{dEaB+f1m$N?4-g3S z144npzz|>BC+t?csX8lzP40A8s9L#{N+wdKjB(o_Ul+(k4^GZVziHq`J|ni+VZz%;ed z0?oqGlbzB)>&J5Fab;hi@-XtW5*1%wq+8GD6Z2im?Ud2IYN}s`}<}SshxLVQr)0^Q^v4z|goRLX?(V zP!S#RBRqeXd`}3`DRIU#gjeDhYl*HDq_ECD@nsX8t~Oq@+sSvXHbPWFfK1~^ti3gO z08K8}3A@@!c^F@2R?4j5yslM79Ljn}-?g4bnYsFjbH+){{Zzg$QB zEN&?np(DgC`MKC*fvW=~D=~Z!wn>gRWf66!iBNF}`z-K)_a5s}Ir5SC`crIGkb!>6 zYJwul)(s|nI(Ps+2bO5U--J9r=)YNucqML5w;bOsf3FvXxB#F6c_?E~x6YjI^6o;C z2XB{7A^LFAkw(15k!)1I3i>{?^wZOM?7M#B>EkS-e{|V9<@xttSY9W;++q;>sA|#p zBX-9&tTS?Q!qURbqNC85r7e4){g@gy$@vMiZDVC{T-lX6 zd5ez560x$JM(&pvm^R6Ik@s$;nOo#}@ju_%SXnE-ZtA#24I2=er`se?O8C#M4V4$> z$*U7;<;}Vld1Au9ZbfHrtbD{=D_5E>F8)NmZ~FQcDz{=oWrO_}R7t5yt^6`{lN0`S zEB%+=#TzPjrGoS9YHrPB&B0VbjdtdP^}5Lb?oPLnXy?&AQ!fevv%vdPQ5q zgL7r;uXZ)L?Ebos^Y5Qq9w5A1{(M_Vq^(UcE)pp>K9;8zF3ZPEH1Vu_jGYgzpf9nh zA@TGpRuM8BR^J$s=9Okw>%7DtnL8xNmpX|-vH4_-m{O)6(BOO7))k|wGg(U6jRCVl z#@dy7UvL|RzFA)40DGih6ij+A(ZHsK8hn*nE8|5O>lYd-LcJ*E8@7fqs_i!R!2|F2 z-+5f=B2z*_{Uv!Z$LTG%OH;hWDi$9x2LoY8#29}?S#CtvFH;MBP(8-3M^oh5 z7OOi-mm~D3cbj}kUOk11`An}bp~Kl$eO&)U>m}KoaBo1vgBQxKeXYazG|zQQ->|Rr zY4k@H5IH=WSkK6nQ$A=z6H&>Y3fCg6bQ{fdOO2B6<5$i9lwhdyMf2EFYr{cd@@4;^R0_z<;VcZReezi}wZw{YH zVtktYg%FhWxx=f@a$DRs2)UFJl&2cIpIrMgB}!>ZsZSkao1=$>yzR^v$x>cHmSgN~V*)q%7`tekqIJN1%PJNd zGmzVPjAh6CSa!!XCMT}&K;b6%&_K6F@T=DgoS0?3Sy+yk-iXoF(@4FLn8S(VY*9rY zA(kL^2K1=-h07=m%^|48jrbIK`xs7q!F8bMAas6mX#}%Jr^!VkqjD6DxWWo~oKDlZ zg>d2m*Uh41I(L}#4HOT06c3=VupDC~(Wl7fFc9+u6iY zhh_GC+CejU%VSVY0YR*0*znkW4xPaN+D9qqqsb0p&daIi)8Y3tsZcQVV~(*P?YwKRHR0cW%DuPQ*8O9Svtpfz-FesqRQu(}VjfiMXEK zj2|A6=e*S3tAH3Hm(YVXseJRU)HCh941vuwibN6dNtT!p?H}tj33EwIxR)4Zrw55R zj+G?DXndUn!?`9QDZJ{yj25^CNQbEM!zPH{&=<9raR~ zWDUvD35G&HyrfKDqMHHC;3FumhO7k1pc)(m$G|yI-iPQmf%3jY_afxU-iQauKFEXn zE6`D^;i|wU=v1D-gBwjAukD5Y*ln&U*_=w*_~hR77RyPFDD$zpr39x|40c535Pg_g z@!o#2GPHq@0`g4e z4_9>QYQ_6@qo5MgU7p+})fslPPxevWH$_^pRW_Mb=2_mU=P z$M2#sN~0#CQ)o`GSy|92X?~5GT!R@4pi63a<9>Lop^#?!S&pG2D$(fV#^g*QPH~UI zHQ#g1b&o_i%X1anNeHKTt|{)a5x5!aR<5JniMWn(C*~w(kH{QQI3j06c2e$uLL%OD zDe3)?t`_sHIw2uvkjJB_$7sbJZguAfq7qlRx<=6t^M+&($i@tS90F8xkgysPJrk*1$|8Pu7a>xgs)EVx}`V zdtg==I(m;QJSRMRBlHHqj7hU%9+_YUFoV^g5>$hO;21au6q7lI9#l+5F`ZnPgkmyX z<`awgxQXy065G=Wuh`Kg__$7lm9D=Fc?E@-P7|JO8vSHn-HB2>`##i_Hh z#^q|$ia$1K#fRWxlicVlcnSWP`1@fp+UZgYFQ@Ko=7iL+7$F%kMeN3yyxy5EI{022 z8Qj^%vqv9Wh?#xgW211r`j~|qVr{4%8%({uk70?U(~6WejVs}Ho?wH=zpi#l17vn` zypBH0u8)tP#SPB!1(g1o&|B+IWf>#kOvrVAC^_=~A{WL+|^F^62gaBeP^g_s=~^c&L#c z{2JAQOG;+;3_W-IBpaA%qOmMLvp*f!urM=`QZw6=Wuc~qnb~n1-Nq_%v*?%XtK9Hj z6P!9h8Te*P!^7NOl(sTDX)Nu>#!uR&XiPGU83+GfYB`39Mrs@=s8(x)zHvT6e_?DZ z45>Kfmy!f(I^Rwbl*MN+IBU1m;IPO#lYiV`mYAO&qPbuyr8-reXz?@LZX{@;}tzg#t2pYjcCKu6KwsvwT{fWJa@Kt7={3hMXb`;FUWc72wM*TDP z{qh@Rr(A^oVIu^c>dtX0xAX#IQ&!M}%xmf>IMwk}L+KVaYwD+HOT^>- z5kKnj^ifl-S%O{KZ=HZ^jck`*wUb}kOv&XVxm|KL(cUjzU`n$~DITpI9<7(5wVE|N zZlEpfpN~f+2YAxvdD3PgE$9DR0`X`Sc(ep)CEMAEX-{H7xNTZIwmGM#8HRVv!)|&$ z;b(&NpaGl!8nH}8<5I+3<>hk9VsI2$;3URsRLR?m|P*JCT&~J@Px+L$EpTgRt z)<%qDE-2x&h-*hQaj#)+jm(}R8z$@F=T&yi1HW2)4_&O>3J<8{r3YHz@6UuB&ZVt>;GQn*Nk3wQ_Z(mePz}&?9kjYaRUP;}W(DKoc5{XNoXK)qPUA#tGvj6tg7HVs zK15Hj%d@BI(%hTmWt0Ebro1&@f7IJ37D}{W7me+zUX!V>)+&(k=c1}XrOqW4Oz@kc( ztrBxwzip$!7s0XePwGZp#ztM)Ta{W`t@?} z)KBp~PH8(!EL=iM*uKJ0U)uNHRb}>m$N4i{>gR>|Fv5@`<+`XS9rpThkv>@ICGTWv z+|o>R6f0C^mFkejonVj6HDb)qpF33NhuZCzSDLQKkCR#1n97&1)D-dk@<#=D6w&Eq zN9K;C&$ITq#k8K~73&ROI%v|}BkG}dTfbjQ^$zJFI;OYBNM;xPvrV^{6Zf$l#St{0 z)fXH5%iL$=#pM&)G~2thKV>(IBRm_ryLmWz0G8D_vtmK>k}&Xd=7s1ramK4AYz#hj z664)g?{Re49Zx&&+HbY-C_S20%zK4vwX;dZI_@VsGtCdA|77X&qrDX)Y`LR{Ctfu_ zB2afhDJ9scYijDGed*PBLGwM^KYv)9&V6n~ZTdf2VJ92A3<-$#BgdC8?qofWSlh^V|HVzruBPsa6OK5ia7C0ms5I;ZCemZPq7ad=soRH z`dqQB19;V$?D~Sw4Uaffdx&wtg>F2@;xS;EtI$6@+hzVZs?oj^rd_)rw5iK(ZlR~uojm2lgVqO%HlCWq7A+bZ zanAn!f>&T!9iDfw&04#Zil@5cZopE`E-KR~qq2}?Jrha;*!*XPhrBAEX^*6(7NsNl z3t@s*IJeYSa7c^Tp=XBEc6R-lcv{H%mL$Qark6A*lSYXFhd1GiGdz2IrJh}7E?aD% zd)O{q*RrO?5ut0W#Q4(%hg9Uggi{oFGhNGoOY#;|aYq`vw>T-J#M;~V;Z>i=%ko=9 z)488IrKPs_JpOXRk|)aEM6P4-e!g~PE!AS`IgLUAN^qwSUk*y>V$y3iGSzg6Y2Ux(D{ zy3`)|11HpV^dTFBqOuMZIi5fkt1UED!cE@`EkZ2w!+Rry6-FFmPtOFvqvkpIxNqUuOZsBrXv$Fw;pX9!j7v7uVI5u4km}p& zk^)%g(nQ+KqMkKGUx&{aEllwE{jXdVc>g+qL=uBr`V;oL%4U)5a!cdbv(M@WRoQmR z>)~O)YyGUP$CW8Fkm6_fMz_S=nAJusHStQ~Y`j`_^w~kP+OWrqG?Wj(n^RqCA2c^% zWNIhjUQS)!p;FzscnNPO6bCphCUx8o@C**gV(T#HV%?19nRL&p#5`=im8m`nR8Lp6+ z74ux_?rrpj@x%x^vqSoU&0IFS?>NM%ulVRM!Jr&c0Xw_QfT^f`S$GU@S9ktMD9)Gs zQaF*Gz|yWUZJk>16>^&3_i$8atpAJ7A^pOJFAoo`cW8yac*Y?|c_<7@Rn*}{m6J)U zbd)Vzp02rO;rL+>3f*50RGpFOkXPIS1L_p|qKZ{>u z+FG?RtG;|uO1(q+mi@dUnuf9dD~mj*Q}>(MODl)bKz3-QK8Dy@j`&$r*8YtZbzTB@h}R7iDsF2rx^^>Z<=v(D#+mkmAH<%H!%U9PXtR?<%( z!ymn%7fDLKIJv-zLj+Tk5*myct8~$7tWOs7t5KyCDz+alG|SROcZ^__uE{E~Shh-i zZ4|33DmL4cv@`B_q=m?e#{WQL3brmUqEtU<+N}E3T$u2ENmpSF$7M^HKU#^g!-+m8 zIWdf#cz)Xivz_ALI=(R6+n)vwn=B%%r)Vm`yC?$W&6WN#zTgC%AsP+Ns5_%$C}XIRgV9(1q%O$O}*Ig*EI_% z_pP1j){f&&onVD)2hzi=Y;92399M9Cv6;(mX(t9{ul09qU`ss)=5VvRwUOK%JG--02tsSlD_KckB~3Y5inu%-&g_q}=>t z{SX}Rt2V4EqvAiBkD+9~QH9f#OK!_;9`^e8=5xQs{ZDt?C(T!Wjce(SJJx*r*SNoQ z#~p5#e~tU7J8pk7|7p)N-tCUt-5mTWVbX@1)X1)HJRgp*~PS?Gc=YDjbc^Ud+mpJ|Uu^2v?T5%D7%)b+ixiP-Mw)tzFwotzSl zw6~8dr{L#z;n=PqiX+K1MLC1NzKgy7%4_s7rmtMX4RW!!Diit~w-e)}Z+N{foQPQF z{i|{$z0Cru(gV*r4{2AJHJ5kFZ~5tjkQ5>gbFjr#VZl_KbW$n3tNTj3n>O(ztF4l; zK(5(bM89SB&Fi&ys|nv!%{IJx@ewNCKCXNP@oNn5H0lYNefuZDhhWO>`4GvT+A>4! zmi9NZmOllCs&fcVXwqbppQ@up^<<%9IY%EMIE*{YzSb$6Sq*tgfvSvcDM}{@n>2;Qp%dIy82t(yMOi295$yboD6D1NyV=)sqZ=cetgM z4o#L8hlx68&l~f?M0vX(&g0OLnT*zidMbOH>1#I9z3f1ZQo{9`V(;xp4~kH9vUZP0 zT-EL|xSrjeh^y6e9lD3XT2JrE(8k+|7-DCA-Wo_hV?*DHn_#sOvD20oy64Dysa^vA z^~$jQM~ormM+m+q4i?4=Keuti)K@*T3&zXt6Ea+;(k$gDPm5vrHLH26s~2amn{Q3^ zWyb@mXjSit0qcplj-~I72vM}*#4^5<&z19?eqQmDuE>6q2@d<#?Tx21*vETA`;WH$ zd2?-t+B?ElWzA0CAoyP7@U*+^#@;79jh?~AzMVtkSk>Fnv_GqVThD2o?9$stdXqWd z4v+iR%GLQ$4yJIg-P_3`#RbFlTKjHL;L= z23*JP3uP~szl1|CFXk+dU^Dg^L*|^Aihn#{tr7ZT+nK)+J_V(CU^V-4XfnIGFAi7# zcMTcIND&+R3$N7ik-ow}oF2aJRtp#EefCTUQ8V8?IA|%=u=DL)Kev=+?>e<3v#F#Bgu zEm5USEmquy@}7wJ!Z9A*bO>kvB{r<@U2bWwOL6>eDT!shHy&pORqw@xFYNxh>-mSo z5Q=|NVD;_saBgWIYkhA5XLGW^{rgdwA*Wc%fk1X)e;{u9b=^2TH>B&vcpwnHc885W z5CeIMl^iIBL@5VWl)0q^7NVvpic8b#`9>Z+bHJw6d+A)#K1d#NFQhkQ4P-CKU6B1D zci5DAYxPEiU&U%fspC5?KGP}fcebF=;L&q%uLqT6ExTKz!!(q$4!niij?l*RBv=?$wQTkiE!wcPt`O4@xw zKIwczbtUCmTOf-+m_}>Zs)Ju>Eu#p3dQ^k(K_s1Wb1eQ50=AAP{8?}r;j7>}xB*D_ z?{W(M90ZakKo7DVEJOGM$a>HOqHu3XVaNacWSMU|iokz}6#Nkm0wEy$ckxPE67C-b z1z;wa4;FzXpy$zwUQf6{fF9U^^j)ClcY1pf-Ukk(lQRB;-z5|w!y2Ge>JX?0|GQF6 zh_irI;Qy*rBhr_FHK3yh1@&;r(_yFOXkUja+r{ga*pa^7jGqwzY9)}5U2sZsPQ!5{{-Q^ zyBUi3N5NPy0i=U0kOvCDG%ynsfkj{mSO!*sHDDc}C@Tnr08KZ(PmrmehxF7g1_?=E zD2NAtWaF(fkOrD&p`}34JB$1C;Ko????a=@G*6-aAZa%02mYw2RY+R{D!~8sNX^qI z53HI4y9Iw#-dUu5J_mN4J{O$<{z$P3X7qkn3RtK+WePMcc6jJ8pL@+rsIAc!grCr3gHTbtH4$; zv=Z$_TokBBI2{BbyaQ>wKqK;7Kn=os^I%6-6jB8xUnuzlj;eZw3u)SnOsL=?&<#G)&Lez!3(5dDUqvMl=MRFww526WpM9R)Ir4OD<|ily z6oBdADKHn9!BVgitOeztu;&`ye)PaQC<&YgP2eo32YW#kxC)9*gsjH2+f(CnSc=?c zc}KUUnx1f%(Vl3?2|9G7@i)zxF6uYJ~D`?dDk zYp=bBGqfn)y969yA90`|)zs)`VdX?>t5{X8}79*+4Wo zz@pcQW;L)KI0V>$R^U1?Mfc}crpTfa47XyD5`(b^uO*$VpI)@#0zfEMf(Hvcigy%jpW495UsDbj3FhNy>=IEJqs^zGHQLg5&cV z36ba4q98h=B^u2w@&h46C-ZKeAsU&#OigrUz=O=*C((M$?P=2p3ti-UPa7c$K3Jl0 zWSFxxG@PcCW(DVkTVD6mUJkeP%P|Q3IPrCFqj456tPF@{UPS3rvuiTRkn zjzrTT+Pt8gT?^9hkmq(4?OrgYaC2d0;U-IjpX-v!*eiEaA+rPvN`B{@o(lC2wITlwDKPPV0%JRao(|WA5Zz2Y(HsDXmZp*bnyU3Dx&=BG z-ftJxvW9-el(Dejal^F@O5Q8F+{dIs^S6F}mx*z|bkyt>Ri6D)Ez#P%q8hoQM3!MI zgUf>L4q`ksXq}X3&LK*>nNT5#`Sm~Gzuj?6GW1KVYhn%kjr2Ub+CR!VK89#iKqIgT zSZ%@{0NoP(XG{cN<{5jaqKDou*N%E$1D^wdz!N<(QOL`3b)cm4t)!JGJ1;#~E3Kbq6#6LkW8z1howpTnDNPDvzEEB| zDd&uol9XNO6?0r#Lt5VKB3U_)sjZ!=BhG{s=Qkzr|;o=m)TV{K)P^t!qI1~slh?n&J`X=>7s)*EXoTcon28tD~XvotB` zn;S8?Yb*O%YNSf@#gb2@JLc9K7~s-1mG#cwdWKaat%qz%(wQ5Xzx6I&Q@JbMdS~Z{ zVR;djDeC)pRjUNW}lt(PukwuOFX{(aX5MoNS-dXu!#$7)69bYr= zefXqa2NQV6^TrKDnL?PT;Nq-zwtkptp#pKL=5M;8Wpx8X61-xAQ)}?g3oj~dtM5E# zwcfQJ>7Kpy&Pzw~@0@!sn182ySzDN)s|}X^%fMZ*^bMhjFonj@5y-cPX2gzjDs_Is zU6-zIyYzQ69a(`?slP0haDGB>clUNlvB^7QW>|gTg|2RnqSkCHVg(W-Xp|*HU zeBT^DVTjYfn|QO{Pl#t5!;OKmiOc&(c3fBL8^ir5)z+VmU{u{>{IetP(6?Cr;1C%9 z{J~FPBb*&PE=Vqv8ldteO1=+e3+Y&P zS{FAk&T&byB;5|L?|jMn?N>VNP0Kv5c#$de8T2m8(vOJgc z`;lftqo?GlR_h~t162C6Q~Ig>?g1w4Cx=^yYromixBU@$qW#CVqad~lt2MX8eykdW^ir3cZc}~b+t7Ai~DP7S; zAAnE5e-wNwob{M^oW|(&T4JhHHI5U?JO_#nLgqgn6>ss$)O&~_I!~5}E3A+v=v4O2 zgcF|hTrc_ra^FDipik~?v^6NtWFY!f$uiDQu%n(_>umcF!vSfBPW8Bb4=QGRqUY^L z#Z$j`uoi-S|I|SxbhoDEGdj630~S>+aMoPjxR(e8X|RX~oC|Lg5$wOg!olSco^`GR*O z4kG3jzjQYrB~>GNt=`0Q?^B_itxY%$7o0g_4BgFM9+60Qup=Xk^cD8i2qPys>!lI> zY2bXfvLjPT5ALrd!U`6aID%%eoWw}_5PLc?CTNJ;%+DjSk$ys$lO7~O3VS;-R^{g= z!WMQRF*!=@mizLRAOt2t%m873StW#A$9vK)#=yewdhMosDEJXwF45~{i$@yhuWakcsK7m_e)2d@BXTbNvwGXe-n6I13!}!- z8s?wu?X$&Yf*<=*((x&_swOsIbdsv(glq;=M#pdgC)f+4S3P5QgyrdYW1$xQur`qB znt>Le5Q0B|3P24&`oIeSI=~Fv1b&feU!wa7w7ECYodaqDPzT?sKmazL2KWUs51wRm z$LOfQtYe}g2ROW9l3OhpT!uWNA7qi;tyYrv0TGU|6Jx^SGhL~5!TN!4IMZB{4Iw#| zp=!bIrN-bXX3JleDl8F}9a(C@<23OKVJxF5!PajjvqfQf41Aeq@`&(=qc9jbN-=}V zW;+Rkk_RV2Z-}NWa+D>Pk?hi}6ws802eOIqsCO*VnZ9(oHwF28Upm=42KgLc%6ms6 zpW#bWy~){Rs4(7}oR^$CIy<~@bl&LPF_Xg!iO}JZ#Rfq@DdanJ{3zC%5*d_`n~vLYc^%2PlSCsg;JwAH zf{p|fHt<9vFKSg2ZWYMO`fCK07xp=))IaPKLa0tH1Tn|>g^aHa;8W-__77ekxLWSIr{G`A&BqKRaIz31_aKM6 z9&rL2m!;?S*x1}GGabTS%Nj^S>)*>7N$FztZMKd6RKGJPjzf@eHZO->Vtpq^_R4hY zczGudI#oYI1S`ld zirnKK##3I$cUxdZQ;JPif~)|yD6oIz7tw#P#A$ERwe0+~IrKvoQ?M4{&R+_m=nL$N zf~8oTiPOhKKH$2)m63mH+lGUM{6hi{)`MAZ~FF%bTgEo7ke6(Fk7I%rUZBX6~j{?CFQc(4p+@ zhdXfWZhB;av{}UW0M`J9Me_uF_TyGF*&JxMXj=Pz)K$SptMbT9MQ<)E>N>-+_y)GDXB#r z_i7W38Js&^GL}Z-j-YV*iN+FY7|TDpfD`6+8A~9oox5OQo{G=rw@H&~_c_(0xkm)2 z!&t(-`NRU6ypI3a*(rV$aBkE{em0-V!=yhC%<+h&(nFbNTUEXgQXThZlPXseBX{E^ zU&_}t|iKSy$;M{x~#pcW%Njurrxg!j>yi^x3#)b_dye3!Zv=EKlKp{r=5Rlr$ew;g% zTd;s7J&|Nw>M`<32x}C%3SqwIkE_b{1qgks>qxdHm$>o-7Bww| z@54u7%eK4z*>1?F?NDlpIuv~lrZ4I6ff9V*4K zjsUK>gJK(Qa`)1!cX`FHz4>=NOUsY$NH;Zw%5z>#nq;GCl}gGt)dnC88q8Nq)7aZZ zAqdqPisE%9%yPf9%zQ<9h&+~ylYJ3OPZi!PAInpnLJ09NZr*6RoQ<7Vj5}WSJiYOT zizeSXs*JzY`om(XcZ*7i>U#T3VNTK4ZMqUpXk^#sMbSBo78`@Mc+a5gv^G_hEbS6o zS#oid?=p6HD$z6mig5*{9B1&KqqS zv_6qtF5bYkJK0$G8W;}m}Cys^Jav74Bl zYT1rmdReNfSu>ap(_F2w`*YkdAjoY3s(?3uhP__dybmLRM7VD zuE8Kf7FbpC4z#eH3nFM7YgjNMj7ewO4YbrID`Fr&h*$IH76qCIT_2?Hx1UqcmO+vH z*KNK-dPDke+ND3V>3tP9d2hDKi_Fd~He2OYip1=zq?_i96CrsKWpVZA45bahlPUc0 zflxKiITbV4)Y2b5NcV4%{WKMJOXo%r)7_RgP^WhtS6gapz$LV5iC-Rh!!Mf?cDt!@ zJ<8+~+25^$UCSLFwi1nm_^!OcoTua?EhDCyn7AmAQl?rwk~Xrji;Xc~!+|}(r@@dp z;k>5;`odXlAV#lPi5o02;%mEC)UmaT^+VR;yjX1}ao@Lo-geJ5%BPHcENL3NBJ+}_ z*Pk6S%kI9^ZZMXIW6kKL_94YdqciM8u|9oMTF1ppSe1x6IaS8}1dren|JK!EnT!iI zv}x8os}QClmND_+d>C|o$yLCw=82ISo<@K+ZdtxEW*wR5EtlSK z9catrf59!8U3&Idq&z_RB1bH;VZP+;ZSsfN#PT|eOKfKcO6T;Q1fKFrfc_Fp$t6C* zf|eNLr7<*#6)!FFHCx-v{8Awz!Xz8?~k)anwO*v9AM%?G=hBZ@jS6ek@_ zsvR$EvS*f8O>Rq(mntd8QQ>)ScUYc%n%#KbknCGj9G>!ma)S1xhWD@I1Py+AAS9)M z+I1ulQ$Frg^18ZVJhAKW*s_9+e_@1b;|bZbEO{ZqYIT?!^Mz>zLj{uR5X&5Vv3X4`}#ajht}lI2}e?IpL?{xNiuzk7Mx~}i7x{V-j5u}i$-t(i1~8!feU_$e=U ziLKt@lMoaHP#xS?gYvBqK7fy{8{PO@ofZl_?iz*bN~uj_NCb`abxVbbC#f)=eODII z`)$`xZTY|2@S7pp!(*c@M2yipHipMb%_f- zp>@R;F1NXz80Gt0<);WeVL&dClbGuz1NVT7=~iU-dDeTk?cUX~=2P~|5-7ux8z=ZRAtw~Z#&r7l~Eks%x13~%~ij`USGMM zJG7}j{N;I6-#d0!6PGtb(i0Ak8Kf!uGrap@6j;5CirW5sZ&tl34_B1-RS_W{dxf@p z<+3gR0=Z5WW{rqVcB-KiNlbK73`r8ly8Lq_@ujXz*!ON{zOV{5wxmlE=d(H1g{-V* zl>(cCIclQVIjfl~`;2v2r_s4AuRK})SW`Znrn4jE&s)7>LQ@$=q-jv#LHd$c{;|p{ z4r!|Vo%gpMUU<`v-+9eFJZ;m#-+3SP@YGG8{LcHJhvzzV?swihJ-pveUHOc#eXFn2 zn{4Bn3(@^tBpN@zWDH&Q@1p1z{3qi)5;QJNUiY`3@0--GSo<=^+gyQD0`mg&XWFBa z113l7h_I>);`&~>L^$H=)l(v0d}B~ndR%_U*1w4txq@hpq|j9P;XLt8Hevm%)Wt5W zU(WsPX4xB(`jk6~Y3er`y)Kdne{-|S4Wn@{ZrYI9f0O&LdZ|Tqd7HFHtK-8`iEzis zLMsP_dc}87$gOv)ue4`sdrq*)l@fiCWo|5@wd}o(tJP_{@Uzt}mhj3&jaN)PF8@ry zp4{|kgffrdEhj@VYZV>MirIy-g&gZg@N#^U{kkb8!sXq)X^3S^QA%&>)aee zr?AK^kpm~V)A=7P_An}pg-phzpW9@Kk@W>zwsZ7B*7n-?crAVlzQ4mX429^7&y}Nl zY$f>gKL%rE1ywW0tUF1KigJXZr5TvWALVI|(T;UE7tVzSc#A^Ia@q_h6XUl-+S@hrrm|l@YP~=)QD6Uh~zmLHm!I z!pe^l;e)QB{CNJ?HZDPV)pz7zFXWz(-~{Dq$q#;T=E7RmxVu}6W~SORBQWE5@J70^ z_oU#}1V5|I-xC!kOUq&P_tLp?ja}=PIQ5F8oksA$SG^~ZYS=&aL=61d@%}3{9ZLVG zu8oe|%r$)AMGn1HGg|$KZ_;Kqr#cU}-9yze2ufS4^_<{hcdAWvJBxfPGVWCeSF5#k zzw+VE2;=!X^!6z9l7FWr4Ph3#JM{_P_~jwJHKNZiD7^y+fHZ);^VTp9we{7${p&L|H^#?%nqdTwXZ32w;&l5g7m28Y9vM?FaLMsV^RJQi#t#ZiY5*$wYtS@8&T3!*@vn1 zng$KjLY->8pUxw?yTAc;fck@Wg7yNngAN3})g=#Ftv4axhIm9C;M*Qewp&c_5TTFc z5&JtmVjs6hEOC3qsXbGC&b9-JAwsWD;C$F;n}T|2amSLMS?pfcZxbI7igmj8FCT2> zyXHyfJw$(3e8o{yM}{lE!F^qk(WUB4m^AcfKO)%zb2`OOd=kqYp^)hHEo{t&v)A^q z-J9R_73Dj{gB~Wl`)KkC53P#j>5fiuna3=U3^jgUl4Ik$;)4#EHs2ngXukdV^o%=% zd}@C~aV7QJwoB~g_cG{2cKW?9)EiUqzY8h#uOBqf>2(t@Utm@${>um0i~IrL5O5eE zJ%4-C5C{S^9de)zz0>z z{QrZh0B<9Z2K--xT8;AYKqhc+P}h;q0j2;2KEAcPXeU0ZfxW;1;1F;ar~~d*o|XMa zerrC;fg;@BmjiXkSA*t&?gc#rEI|GM=)L-?N1#DK5BT@MZGHF;foL!jfmpx}ekb6# zuY3{s&jYi7BA^1;2;A#nFY*Od=p6I_upQV5R0H>9?hQO`3giIm79=)c5ikq50EA%F zt*CUq2e&3;Ab=a7C|3dgKp+qVgaBcH9*70vfkYq~7z>OCPNS{Mz*XRE4=y}HX81a} zH@bEdbON^kJMiCZeCsUC4p{y;W(vr175Lr)9G<`u4nJT$3-)=Sa}LHg_rEuljIyyn zCh&iCc^2j8f$@dV74YANwgqKd3(3=(z+xx?_-}#*D4Pk)nvZz^|4ps}WgCIyry&dc zS&mKp&}vN%Ac}h`1T9#EmhrfK0f=0J;R1Whps{ka1YE#7_FmBIptpe2c%i1tVLPDP z@qn`cbnCNl1)vvztH5f=RRHIaU$hFEMt&=>9e8*rlI70>D9l_8Tfz4%G}M6aYUD2i zTNmQryg*L_`V!ax=z`T4262wDm!Y|85RorotZ{M&Wn}o(4S&aP*J0U9<@ezk=NlQ~>uD-3|G6 zd^dtp(0It{K@Z40z$Ui`tOo!2EocMSxfugR*;(+<12Y#dT>R{dEaB+f1m$N?4-g3S z144npzz|>BC+t?csX8lzP40A8s9L#{N+wdKjB(o_Ul+(k4^GZVziHq`J|ni+VZz%;ed z0?oqGlbzB)>&J5Fab;hi@-XtW5*1%wq+8GD6Z2im?Ud2IYN}s`}<}SshxLVQr)0^Q^v4z|goRLX?(V zP!S#RBRqeXd`}3`DRIU#gjeDhYl*HDq_ECD@nsX8t~Oq@+sSvXHbPWFfK1~^ti3gO z08K8}3A@@!c^F@2R?4j5yslM79Ljn}-?g4bnYsFjbH+){{Zzg$QB zEN&?np(DgC`MKC*fvW=~D=~Z!wn>gRWf66!iBNF}`z-K)_a5s}Ir5SC`crIGkb!>6 zYJwul)(s|nI(Ps+2bO5U--J9r=)YNucqML5w;bOsf3FvXxB#F6c_?E~x6YjI^6o;C z2XB{7A^LFAkw(15k!)1I3i>{?^wZOM?7M#B>EkS-e{|V9<@xttSY9W;++q;>sA|#p zBX-9&tTS?Q!qURbqNC85r7e4){g@gy$@vMiZDVC{T-lX6 zd5ez560x$JM(&pvm^R6Ik@s$;nOo#}@ju_%SXnE-ZtA#24I2=er`se?O8C#M4V4$> z$*U7;<;}Vld1Au9ZbfHrtbD{=D_5E>F8)NmZ~FQcDz{=oWrO_}R7t5yt^6`{lN0`S zEB%+=#TzPjrGoS9YHrPB&B0VbjdtdP^}5Lb?oPLnXy?&AQ!fevv%vdPQ5q zgL7r;uXZ)L?Ebos^Y5Qq9w5A1{(M_Vq^(UcE)pp>K9;8zF3ZPEH1Vu_jGYgzpf9nh zA@TGpRuM8BR^J$s=9Okw>%7DtnL8xNmpX|-vH4_-m{O)6(BOO7))k|wGg(U6jRCVl z#@dy7UvL|RzFA)40DGih6ij+A(ZHsK8hn*nE8|5O>lYd-LcJ*E8@7fqs_i!R!2|F2 z-+5f=B2z*_{Uv!Z$LTG%OH;hWDi$9x2LoY8#29}?S#CtvFH;MBP(8-3M^oh5 z7OOi-mm~D3cbj}kUOk11`An}bp~Kl$eO&)U>m}KoaBo1vgBQxKeXYazG|zQQ->|Rr zY4k@H5IH=WSkK6nQ$A=z6H&>Y3fCg6bQ{fdOO2B6<5$i9lwhdyMf2EFYr{cd@@4;^R0_z<;VcZReezi}wZw{YH zVtktYg%FhWxx=f@a$DRs2)UFJl&2cIpIrMgB}!>ZsZSkao1=$>yzR^v$x>cHmSgN~V*)q%7`tekqIJN1%PJNd zGmzVPjAh6CSa!!XCMT}&K;b6%&_K6F@T=DgoS0?3Sy+yk-iXoF(@4FLn8S(VY*9rY zA(kL^2K1=-h07=m%^|48jrbIK`xs7q!F8bMAas6mX#}%Jr^!VkqjD6DxWWo~oKDlZ zg>d2m*Uh41I(L}#4HOT06c3=VupDC~(Wl7fFc9+u6iY zhh_GC+CejU%VSVY0YR*0*znkW4xPaN+D9qqqsb0p&daIi)8Y3tsZcQVV~(*P?YwKRHR0cW%DuPQ*8O9Svtpfz-FesqRQu(}VjfiMXEK zj2|A6=e*S3tAH3Hm(YVXseJRU)HCh941vuwibN6dNtT!p?H}tj33EwIxR)4Zrw55R zj+G?DXndUn!?`9QDZJ{yj25^CNQbEM!zPH{&=<9raR~ zWDUvD35G&HyrfKDqMHHC;3FumhO7k1pc)(m$G|yI-iPQmf%3jY_afxU-iQauKFEXn zE6`D^;i|wU=v1D-gBwjAukD5Y*ln&U*_=w*_~hR77RyPFDD$zpr39x|40c535Pg_g z@!o#2GPHq@0`g4e z4_9>QYQ_6@qo5MgU7p+})fslPPxevWH$_^pRW_Mb=2_mU=P z$M2#sN~0#CQ)o`GSy|92X?~5GT!R@4pi63a<9>Lop^#?!S&pG2D$(fV#^g*QPH~UI zHQ#g1b&o_i%X1anNeHKTt|{)a5x5!aR<5JniMWn(C*~w(kH{QQI3j06c2e$uLL%OD zDe3)?t`_sHIw2uvkjJB_$7sbJZguAfq7qlRx<=6t^M+&($i@tS90F8xkgysPJrk*1$|8Pu7a>xgs)EVx}`V zdtg==I(m;QJSRMRBlHHqj7hU%9+_YUFoV^g5>$hO;21au6q7lI9#l+5F`ZnPgkmyX z<`awgxQXy065G=Wuh`Kg__$7lm9D=Fc?E@-P7|JO8vSHn-HB2>`##i_Hh z#^q|$ia$1K#fRWxlicVlcnSWP`1@fp+UZgYFQ@Ko=7iL+7$F%kMeN3yyxy5EI{022 z8Qj^%vqv9Wh?#xgW211r`j~|qVr{4%8%({uk70?U(~6WejVs}Ho?wH=zpi#l17vn` zypBH0u8)tP#SPB!1(g1o&|B+IWf>#kOvrVAC^_=~A{WL+|^F^62gaBeP^g_s=~^c&L#c z{2JAQOG;+;3_W-IBpaA%qOmMLvp*f!urM=`QZw6=Wuc~qnb~n1-Nq_%v*?%XtK9Hj z6P!9h8Te*P!^7NOl(sTDX)Nu>#!uR&XiPGU83+GfYB`39Mrs@=s8(x)zHvT6e_?DZ z45>Kfmy!f(I^Rwbl*MN+IBU1m;IPO#lYiV`mYAO&qPbuyr8-reXz?@LZX{@;}tzg#t2pYjcCKu6KwsvwT{fWJa@Kt7={3hMXb`;FUWc72wM*TDP z{qh@Rr(A^oVIu^c>dtX0xAX#IQ&!M}%xmf>IMwk}L+KVaYwD+HOT^>- z5kKnj^ifl-S%O{KZ=HZ^jck`*wUb}kOv&XVxm|KL(cUjzU`n$~DITpI9<7(5wVE|N zZlEpfpN~f+2YAxvdD3PgE$9DR0`X`Sc(ep)CEMAEX-{H7xNTZIwmGM#8HRVv!)|&$ z;b(&NpaGl!8nH}8<5I+3<>hk9VsI2$;3URsRLR?m|P*JCT&~J@Px+L$EpTgRt z)<%qDE-2x&h-*hQaj#)+jm(}R8z$@F=T&yi1HW2)4_&O>3J<8{r3YHz@6UuB&ZVt>;GQn*Nk3wQ_Z(mePz}&?9kjYaRUP;}W(DKoc5{XNoXK)qPUA#tGvj6tg7HVs zK15Hj%d@BI(%hTmWt0Ebro1&@f7IJ37D}{W7me+zUX!V>)+&(k=c1}XrOqW4Oz@kc( ztrBxwzip$!7s0XePwGZp#ztM)Ta{W`t@?} z)KBp~PH8(!EL=iM*uKJ0U)uNHRb}>m$N4i{>gR>|Fv5@`<+`XS9rpThkv>@ICGTWv z+|o>R6f0C^mFkejonVj6HDb)qpF33NhuZCzSDLQKkCR#1n97&1)D-dk@<#=D6w&Eq zN9K;C&$ITq#k8K~73&ROI%v|}BkG}dTfbjQ^$zJFI;OYBNM;xPvrV^{6Zf$l#St{0 z)fXH5%iL$=#pM&)G~2thKV>(IBRm_ryLmWz0G8D_vtmK>k}&Xd=7s1ramK4AYz#hj z664)g?{Re49Zx&&+HbY-C_S20%zK4vwX;dZI_@VsGtCdA|77X&qrDX)Y`LR{Ctfu_ zB2afhDJ9scYijDGed*PBLGwM^KYv)9&V6n~ZTdf2VJ92A3<-$#BgdC8?qofWSlh^V|HVzruBPsa6OK5ia7C0ms5I;ZCemZPq7ad=soRH z`dqQB19;V$?D~Sw4Uaffdx&wtg>F2@;xS;EtI$6@+hzVZs?oj^rd_)rw5iK(ZlR~uojm2lgVqO%HlCWq7A+bZ zanAn!f>&T!9iDfw&04#Zil@5cZopE`E-KR~qq2}?Jrha;*!*XPhrBAEX^*6(7NsNl z3t@s*IJeYSa7c^Tp=XBEc6R-lcv{H%mL$Qark6A*lSYXFhd1GiGdz2IrJh}7E?aD% zd)O{q*RrO?5ut0W#Q4(%hg9Uggi{oFGhNGoOY#;|aYq`vw>T-J#M;~V;Z>i=%ko=9 z)488IrKPs_JpOXRk|)aEM6P4-e!g~PE!AS`IgLUAN^qwSUk*y>V$y3iGSzg6Y2Ux(D{ zy3`)|11HpV^dTFBqOuMZIi5fkt1UED!cE@`EkZ2w!+Rry6-FFmPtOFvqvkpIxNqUuOZsBrXv$Fw;pX9!j7v7uVI5u4km}p& zk^)%g(nQ+KqMkKGUx&{aEllwE{jXdVc>g+qL=uBr`V;oL%4U)5a!cdbv(M@WRoQmR z>)~O)YyGUP$CW8Fkm6_fMz_S=nAJusHStQ~Y`j`_^w~kP+OWrqG?Wj(n^RqCA2c^% zWNIhjUQS)!p;FzscnNPO6bCphCUx8o@C**gV(T#HV%?19nRL&p#5`=im8m`nR8Lp6+ z74ux_?rrpj@x%x^vqSoU&0IFS?>NM%ulVRM!Jr&c0Xw_QfT^f`S$GU@S9ktMD9)Gs zQaF*Gz|yWUZJk>16>^&3_i$8atpAJ7A^pOJFAoo`cW8yac*Y?|c_<7@Rn*}{m6J)U zbd)Vzp02rO;rL+>3f*50RGpFOkXPIS1L_p|qKZ{>u z+FG?RtG;|uO1(q+mi@dUnuf9dD~mj*Q}>(MODl)bKz3-QK8Dy@j`&$r*8YtZbzTB@h}R7iDsF2rx^^>Z<=v(D#+mkmAH<%H!%U9PXtR?<%( z!ymn%7fDLKIJv-zLj+Tk5*myct8~$7tWOs7t5KyCDz+alG|SROcZ^__uE{E~Shh-i zZ4|33DmL4cv@`B_q=m?e#{WQL3brmUqEtU<+N}E3T$u2ENmpSF$7M^HKU#^g!-+m8 zIWdf#cz)Xivz_ALI=(R6+n)vwn=B%%r)Vm`yC?$W&6WN#zTgC%AsP+Ns5_%$C}XIRgV9(1q%O$O}*Ig*EI_% z_pP1j){f&&onVD)2hzi=Y;92399M9Cv6;(mX(t9{ul09qU`ss)=5VvRwUOK%JG--02tsSlD_KckB~3Y5inu%-&g_q}=>t z{SX}Rt2V4EqvAiBkD+9~QH9f#OK!_;9`^e8=5xQs{ZDt?C(T!Wjce(SJJx*r*SNoQ z#~p5#e~tU7J8pk7|7p)N-tCUt-5mTWVbX@1)X1)HJRgp*~PS?Gc=YDjbc^Ud+mpJ|Uu^2v?T5%D7%)b+ixiP-Mw)tzFwotzSl zw6~8dr{L#z;n=PqiX+K1MLC1NzKgy7%4_s7rmtMX4RW!!Diit~w-e)}Z+N{foQPQF z{i|{$z0Cru(gV*r4{2AJHJ5kFZ~5tjkQ5>gbFjr#VZl_KbW$n3tNTj3n>O(ztF4l; zK(5(bM89SB&Fi&ys|nv!%{IJx@ewNCKCXNP@oNn5H0lYNefuZDhhWO>`4GvT+A>4! zmi9NZmOllCs&fcVXwqbppQ@up^<<%9IY%EMIE*{YzSb$6Sq*tgfvSvcDM}{@n>2;Qp%dIy82t(yMOi295$yboD6D1NyV=)sqZ=cetgM z4o#L8hlx68&l~f?M0vX(&g0OLnT*zidMbOH>1#I9z3f1ZQo{9`V(;xp4~kH9vUZP0 zT-EL|xSrjeh^y6e9lD3XT2JrE(8k+|7-DCA-Wo_hV?*DHn_#sOvD20oy64Dysa^vA z^~$jQM~ormM+m+q4i?4=Keuti)K@*T3&zXt6Ea+;(k$gDPm5vrHLH26s~2amn{Q3^ zWyb@mXjSit0qcplj-~I72vM}*#4^5<&z19?eqQmDuE>6q2@d<#?Tx21*vETA`;WH$ zd2?-t+B?ElWzA0CAoyP7@U*+^#@;79jh?~AzMVtkSk>Fnv_GqVThD2o?9$stdXqWd z4v+iR%GLQ$4yJIg-P_3`#RbFlTKjHL;L= z23*JP3uP~szl1|CFXk+dU^Dg^L*|^Aihn#{tr7ZT+nK)+J_V(CU^V-4XfnIGFAi7# zcMTcIND&+R3$N7ik-ow}oF2aJRtp#EefCTUQ8V8?IA|%=u=DL)Kev=+?>e<3v#F#Bgu zEm5USEmquy@}7wJ!Z9A*bO>kvB{r<@U2bWwOL6>eDT!shHy&pORqw@xFYNxh>-mSo z5Q=|NVD;_saBgWIYkhA5XLGW^{rgdwA*Wc%fk1X)e;{u9b=^2TH>B&vcpwnHc885W z5CeIMl^iIBL@5VWl)0q^7NVvpic8b#`9>Z+bHJw6d+A)#K1d#NFQhkQ4P-CKU6B1D zci5DAYxPEiU&U%fspC5?KGP}fcebF=;L&q%uLqT6ExTKz!!(q$4!niij?l*RBv=?$wQTkiE!wcPt`O4@xw zKIwczbtUCmTOf-+m_}>Zs)Ju>Eu#p3dQ^k(K_s1Wb1eQ50=AAP{8?}r;j7>}xB*D_ z?{W(M90ZakKo7DVEJOGM$a>HOqHu3XVaNacWSMU|iokz}6#Nkm0wEy$ckxPE67C-b z1z;wa4;FzXpy$zwUQf6{fF9U^^j)ClcY1pf-Ukk(lQRB;-z5|w!y2Ge>JX?0|GQF6 zh_irI;Qy*rBhr_FHK3yh1@&;r(_yFOXkUja+r{ga*pa^7jGqwzY9)}5U2sZsPQ!5{{-Q^ zyBUi3N5NPy0i=U0kOvCDG%ynsfkj{mSO!*sHDDc}C@Tnr08KZ(PmrmehxF7g1_?=E zD2NAtWaF(fkOrD&p`}34JB$1C;Ko????a=@G*6-aAZa%02mYw2RY+R{D!~8sNX^qI z53HI4y9Iw#-dUu5J_mN4J{O$<{z$P3X7qkn3RtK+WePMcc6jJ8pL@+rsIAc!grCr3gHTbtH4$; zv=Z$_TokBBI2{BbyaQ>wKqK;7Kn=os^I%6-6jB8xUnuzlj;eZw3u)SnOsL=?&<#G)&Lez!3(5dDUqvMl=MRFww526WpM9R)Ir4OD<|ily z6oBdADKHn9!BVgitOeztu;&`ye)PaQC<&YgP2eo32YW#kxC)9*gsjH2+f(CnSc=?c zc}KUUnx1f%(Vl3?2|9G7@i)zxFRUGW(FP;CoQ^?IN0Ip6a= z>vQ(u%xUiWDb89(iLNM&@DB@w-_wRJx;>kufzGqm#^&^D8 zs3N)ouTBQC)jgA}A+C;QZ_(u-Uv)GSq7njSnn2VsKE=XR`x~A2ECBji)k2ovOF)kwP!A-A1%r zno&BwEu$+~z3=2cL9$yix^)5-SJ=Ix^6!xev4WTA!}NZ| z0U^CnA1zHIzBKJyp6HIU9e!>)j_vRtnV_v#3vOvc$GdW&@v67?C1ThwA2Yh8=Q{Sw zHAHK3OIzSOMqtAv|J8wUGBF&AD3_CrxkTM+BvkyKZR}O8_7*>Jvw_+v)&+KzKy``% zS7WgyCx}fSt_n}M`vu)QQ8tK+qX<6?+yOT5X9MA{Dq-F4SpvPHo7^Rbbjkbe!lCm4 zcBCH-_9!;}kZ3|zhTlMvw%08ai9V9t$t2$5L^sm~lyi;__GZ9*Yk@)ZSM5i`k2%_Y zRwbl1stoyJnPqhD8F_GWPN7@+yHgwWuxWac(m6A{tZm`%P(!(FN`9buV`WGJ`Ki3D zM&6>M@kD&Sj7II3=NZf8+$itnO!H}ZPLc{%Rq{(l_bqDJ0N)(+N?x*jYeVHld3kb` zY<*UDT24zAZ|UuUrQY!kw#}rny zsJX7~W2^O-weNJc-Fk1;JNfrMUK%LuEnCVK2fjg{WW9ot=tnF)Xa)UC-JgSoQyR@$ zgXf1PI$}}KMT}CvTraWE5ib}~w3k@ImONn4d>%k_U)1e<;0=x*Wy3?;xbr8NF)WB{ zJi&ypgWR+2ObqKw=doVl2|n@m&*kM4shGzy!%OJ{?49r#eP%&7C;8{Fy0$ge4?oih zXXH7v-I9jsBTBf}>}*R!2(4z-5gRpntbVn1iIFdIKD`_j8SNLT*pr>@H>kf6HPF`k zkM+;(m7@{IcKGM&1dW)}p)+t%zPY+cjacPoA-afuieXI^;kRgs?hNGj=(ofcG5?tw zx|ND&*dsbOD)opyebhFWewA;YpNY>QalVZKLMSp^?eea%-4#?IzdLhNciB37X z=q+eZKs(iwdb2B5NHh_wCO4AO$+KV9ERIrc+g{5jLafTu~9^yCYwikiHng?Np`lSe^j;n3KG7CbiS_W+53@h z)vpC)!>-rw3aEsg?7TU9JM8AbE~Hjz0uc+_ql;5*%d3M3uXN+R{e%yClkjJ%@qwz@ z6VaP!J!_2)4gTR2(OI%pt9mA=FLEgbvVl^TUv#HniDxc}?>K#oY)uig`dEQGOvPjDjrb2}3oA+(MlZ0P z2}$%k`&)v6-eW%|7`Sik`+^2i8pMJVhxwH{)pxSg^x*zVBCcoC5(i-?*qj(ir?Ufz zF#+*TqcEGqMS6)p%k&@-N3pLG6X`#h--8BfVo47MYkqJL@vqGE;1GJ3t$#3(7PB1> z76)E%_KWqp948bm)J55Dr=}5c1nW6yH1%SpLDOgqs~)8He!;0*s226?!k|6@bTr}9 zGI|kZ{~^$Z*R>4_q@la9L=dqY-Ii)I?j^huZPXEQ1=Abvof%SDr5mW)+Vrk2 ztWYCn*frvGN0f=^Bh1Q5>n|(go`{dNSCy*F;pSJebqhOX51m^&=hlc;M_O&5z7H0m zXB}gsf^#cFG~&VzY6u)>G#^>kX{!-a(N~;UWOaFxm%ftiF#G1ctGiO95q<1Nv&uXJ zSt}+5E~%L`jzQ&=lYml5WuYH~)+nud484K_hgms@C~+jmlAQyYTA!Lj#ITNGaQk@N zppK#N2Y6injv?^(ggcIie8*q}G#;1hNP*w&N-?G64bBNG9Bdk#H)L#BArX(d6ss>? zDLE>U$vPp~)Zeojs7Go_$o-Yp`9J)%o|<7ZEYE{fvCPfJ7T|`{(t| zDVI+bXv709W0c+$l@qokDle>1*?q3e=fvgC@VtJx5$Ls-U42b`^ES$_6@(Q=<|xC_ zEggBEG%6qc{sGZF82)V_OnDdD59vv2}HFKd; zM#;wq39s}adw1~kUX~LU48(iNphCBYu*e}F=Jj-UG;73%8Z_cm(7Qpd_Y=H@03lX* z06T=%r4}}2Y;WX*jEFcP6`E^Kogmu?q58^<)J7hfzaHmnHR4CdS^Q9$`@zoo5Br5K zW#Os))M~N8%|@k0z;o1HH!HP(a{i9Gn&I~-_i%gNnqZaYjQiP}qla>z>}Ow&eh~S8*~qkM zLGXO)u8U2>nLDVuE-WLSql{&ZncpMJrA$)NIJUa(y)iu~y~IAqYE92TTP(KMuq-FG z{G8rbP_5Dky%KzdK7viwm5stt`{UxYpGuRd@j?qp?jb0Lp~u@RTiwz-&f~2Cy<*s1 zAuHVLqR~QioU)Uy*BY9eNy0BpDVATFiS8aVWoP&M)JY6SWq;%IvY%0Fz^cOhTKze{ zRzH>ckXu^MYP0*%aMqMv6#02ayg&t=&^b;j8dGiP1kb|MA>Cs6IYr!N2RoMYC+=Yf z%gcR?e#Z{vZlniULS8?dbxe87=zi9iH!O0g>;8OFewR-<3p9Ng%DJ}7qm7)PO1XN> z2S*>m)U9bMx3r)AXv!KE>Btov(jrGX+~RhJG{{AMYBr{p4dr&odBp3UWu7t9A@%TB z&G1+iz$${3jy2Fz?8ULssn^<-93J$<84&lQ^Z&}>yvHisW2J@Fzntv*vD4`jEPGrM zM;&aekchJ591p%bF%cbGP1S@`Pj> z!4f7WavyfE=@Tb%R~_u_iG#Tx+S#`gp3YL`Nd4i@>7hD96o$lNqmm2p48a)WW%XeU9US$f02XAnwxvn za^haQZh^X$r=0klolTj%2-%#SJQ6OQvXDN+7EejyB$@4<(x1C0vyZ2Y;ogy%|D!tY z6PXzwofN7RA=i`E(_YxAu-Kk+lGwD1E-8}jezch0VRUL}&#k90cRel8vgoPj)Kt9V zWjZwBt zr9lO3$FyzqA1r2iB(JP2Zt1&57BpjuHO;AR{T|DN?Y1_J6NjH7#8RKRRxS7mrUq;r zxGBWezNd3Ze|4n&L<9G2Fqq>!L*J6N%N&x;*Sn-Rr^uFQFIYd{cf2X4=hAlROV`1SC9QopEb*~O?t2Ft`&eOg z>H&PK`pl;SYgIWo%Q&eabD5HL0rZ^6o#N4NKCJ1naGz-|WfpSci>&Rjm_T|`Yttf~ zT9{E=R+3ihlHOy3X2#$W@aW9B+|~o^{h1L#h4y%X=+&)dL?uqQD+h;~1MG*Hy11{~ zPao6TXo_FL4^1O^YyaVY3orgIyXSwn2xQbU0%L zO^s-yItS8RThw_9;lyuUICnYOmRYfeKF);=h9^=Qh+$t5J?N4WoT?h5jgB(%Nvz!DlD4t6k0;VK?8xKMJ&s`OR2J3PgY3%Vd7SLW1{C&>2|_3OU^M&US%i?( zdfKWZerU}54mIuq=%H2}rQ%Jtq%hRViFUVA6ViBFa`)prw?wzp3t?rR$o0ChenNBU z0|FT|{GuLDL-}ICgmx*$VQf%*1E6V_bdK2CR6)PWc3V!PV#%pOGj#Sip=4Q^A(F^DFh~)-1*|u$aa>!U5aw(S8>Ai($36MFk74$(^}k? zIC1HjY1pJ@L^4W6DOU*MJ&Ct#!pZm)Ewf( zsZ1(Lpck28cA~W$7B2!`=+VH5|2jeAX%i=Ye*)Wx=s2Ow6knX$;~SLWD78O`>1?r~ z5)HQ777WRQCphuVb}xa%{&W#-nV%ECY`@jqod+54c82;>r}UCs z^$0gqZocEKzU1Vj=UCJ1NE*w2oE@BS)JDZ4*yl;CcyThaixZ9^yJTck(-Dhq^XvGw zIY{`rnTUU3gNoC!5-lmd19#?};q)+jdCq8D3I92#U(yN%2>O78lO7aN_e$!4p=urV_*K=#_I< za^gnkTs&o@8q>OBCXsK7%jMy?E{!Nq&Uo_>JITnwonlPwvayhTbIaw)h@az}j~I(l z6$-J`nABykg%r;(mzTg`l9Sz=ufs(;*sQ0?Y#3ZUn+8|Qo-&7`e|MOdaOWM2FBw7q z&N54e`(Qj}R@4LuJ=yM(LEKyi`+G?kJ-}K@!u#)(#pZ~^gg=e0QKrtvkWE07s*2sx zh<7~PGnwUyq_wF{j%MW+fpzLG zxn3Mj_<4X;l@9cp)C<>&!|c;ioaC5cK~lG3`hrnbC62FG<+!CU-O9tDTbkNfhAMUH zKJU_vZ`}H;?tGVSOk>rry3<{{5sfv!>fYXks(Y(TH=yxir>++Y-rJ>&XuN)y z4OqB_ZfAQImU7}@=D+Cu;O(fOwq7+>xt@LG^pifGyaqaXQ)k%Q6YlTy z>Iz#h-UlL&v4E&a+Jd@z%PtzAs5~#Vd-K#v)B;wtG~cgV+o`cFoso6J={L^L53a{5i67hCEH6|{U^Cam4DI76M#|z} zQ!1x=-^(L}>O0;%6?sR7aNXP*N<|gYW{&x;SxMK%gK*5a{T zEhy8-Ek!!m>uba44A!uAGA(4i)`e3uOIR05KVVtw3|_MGnO?11w2q^k9Ke=Z|DlMy zvH>)NEh+m5?(p^d;9gsw30J?t3U|+jL#otMA#B{nVH)LFRKhlI9HQzt8Nxo;*az{K zH^xL>JK1?;QsY;QtLB%?yUed<(93S=Mx!Mgcfaysp4|Gd1?A%n4>{b@d8a1V3-{u! z4$fe(RG{kKI7%E3#04D46A&zNWy%c_jQO1-dBPj&3Y$~ZcgHB?51%(8PeS{sM! z9%rJup122|K^3MRVLw!k@1eByTLfJXH#-%(x13)1 zEkyaINj{0*6}tAq%$_c3Ctg81ZL?l1wYsEPow1nP zUV6Ts7doVqPA|Q;u0#4WBoA2!=>z!=WDm$AkbNKzIF;?jOCJmW9vpL(&;3S+56<^t zZX#;s4(VNIha`gUIy$5rwCjZqB?S@vkH3P}6LDbhacWRmh~ab#O*!47O35rz&aQ0W z*090lr$&cT3`fTd6f{tAc)zSvSQcmKbMYG8~A|$5DdEGLg9}D`gHt=9erQKW%yfxQmHt|MDXvG8Uo#L z&i zA>b}DqXkFe=u765!(c`4pdJgt)n23HUE%l2*jGfs&~h=ira>Ye1ZBD#qyW8Tg#wj||r$Zat`& ziFSZLva3a0Jt%q{w&36GCT8ZZSUy6RyQpM&NzsCmWhIN|lZlz^yO+be#;K=w^>Z-o z<|2oA_@5AP34}gD_@jmBIZzK8fDL>A?iOL8Kzs>g?rhW)avSi2-wvsPJPW&Xpbg>b z2z&|nFM-S88klICk4zD{1jfOT0gyK!Zy@p}I8==Bqv$~k!gm!NGHQiv19sp7yJ1IR zqbXuxJJ(DMEyWlH&o98xg0$fk<1+jW;2g&P1=PD0dKbdilr}(KhP(kTfg;4MhpqxN z!T#Dpc5CN=;NZn51ym@b5?Qta{Exw_&slFSMIDx4jYI5Cup8_F)u0JXu%P~+6&ymi z4KfKFh5r&Lg1;WJ0oXtQ^3y;U0CvD12Ppg>Anq)<0rsH0bC4GnV=Uc-XCaL2kS@Sc zRrj1ByO*Okmf`Dwde9w_2!ANzT97UY{+aMkfV>1+z+LEDK`r#QCy^eUTY>q5xHhFM zFnLkwqQxuO;ayW^=f8>Hmz1j@XaPThHsApCFyXy{KM3rS-PPz`aP(`i=zz6YTxLQB zLl!}n0Q}m*&t1c2z4rR>ZChXh8bCFu1-rp!umYR~#YRHXj{MfrS8(n)&W7x^#=TqW zw$iSW-EKeNjPhxO6NgB6qm>K4Ndw|5;dvgA|JkO`!s<+;* zz22(o;rbcw<9g0sLWyuRobVSj2_FM?w#jLb$Dx0m#yx+G7nc7q{dK9a8aX1t<}D9dVUpprxBlH27EI$koKL>)0J zE@+5A0tnClOs=Eaf~x!UDB)FouAT__Aekj}OthQaEe$?Wh>LvR(m;qt3{q%3>EpZ@ z8cvgovq*FYYk0xLnR{&M66N+31Vo3~Hu>l-(V@*3^B#GM!wZVDt}G}y0n0kllbZP& zy%f^oW8G7f{(vmmQ<(SQO48mUtu?%mM1M0Qd?xRJT>xiRZMA|&{@)$z2+<+%IV3ya zS3>Wy82<^~@)eJ~%p-_YTHK_M&U-+{#EN<;lfB|UGcdc0+BRw?e$@OUPlQya>*S#p zrt3VcccoHb3aGi}qZNHF6Jxn@!sLQowKg2i>+KKGyTtkkCY!xw|>fd@Z8e1W!27msFYfna%F>1 zkIG#8Df3>(nQP1Tq}w0tITmb@%9IA9?P^*Db1;yy&Kh~DBmXh zr6C~N7c=jfhU$l(+U<{CJl@)P`-4@-^B#P@} zTj@%+F*uQ)XSKo0=_l3wLsBS>V?|x(h9x>YAmM^5QB1G-sB_rt3nK4(Asl^}ks%$nhmecA5FqKK}|A1mv} z9&6Z@b-jVqsq49YJq%(|QR{Sv;JH$&E26e>z9G)i^yUjx3S_B5|DMUHV?a%(+)kFx z**fWymQEHy)JY$;2u3d2&mu(WrErC97b1J8hWYymzaxMMvmpPC-cPtKewGv6H|%RSyyLivhh+9SB_LT{@+F0_q87z$i{47tu_&XFE7{M|jY-_7{cMGC ztlkAzrfAsTjorDj{p=UxzwF;DI#H-Hz-b(F53|M>R1~ZisB{V10BAYMU%6RO0?p@M zI~r{e2Ut0YYlD0 zszrQ3sWL*)HEyvJPU_>nS$GnLdti9bYgmNLBCWB}#9&rz!}QYgEv*@!yWKOoLfM5E z_u;)x?wA<|@ZO8R6)+kFbpAsDWw2{@-JG!lcJp8tTBSCDNCnL?Gm{;`?*1sBu_hs6Z4T!bUe=~dRS^6@|h>M}mv!b{+xw5xehd$Z194F1@9ibT9NZ>z^ z@QS~ht-9N_LJ?EL0X14w*snzp102Z+hhVI}Y8FKPx863Rx7RikqadzV%JSDMo8X~d zH6>%)IQTX@)hBw`{pRu)-STjkzr`(Yb@^rzz(?H5H0SdV_a15GZIID^DtrFfd?K_ZP}PxVWn-?Gwv z#)vWQpBhvTanv19eKuO#IFPCq51d5$f}QO*DCE9VQz$55lRiYhLNk9?meb~!^SH=@3T|OK!iJbpM1*zgmvC0*OG*=$E`kH?nFGB z+=}K!W zq`Hp02Wtw66ogIWWIl;8SfX47EBH z+NXs&Hyh2Z&ZB*Lj6aB*26Wev!I8r_JPCs)cmDBIG0Jrz8+8n_*``5fbL^g$2Axz{ ztCPL}8)}srf6+$_6l2A%*o?ZiXvGcbJL)(wJu*&AhUN#iASzgg)KHe5T*pH*w3e^Z zNyBQ{Yl9UorZ;VTx#4<<5cgaP|o)3O`B(-V^)G4u`f~_4nxl>v#%4<^{sbF_T_Tny7urB7o z+=6#lj=5i?PWtg=F)H3A;b2{t7_HbH4G1>PBRc7dQoX~B6Zre@RBuS{!_jT5YSi2g zX=sGHApiYNb#!J2N-wemv2oZ4mmn59hQs~KHQhzcN}bp_-cRf%re4Hg&NSbfpF~Yx z-X=-vnXLo7qerfGITXPZ7~hLc&&mwbT`(0>L3L9B##;>}UcNY>7?WRk$m+7P=-13A zJBpUFnCu?32g}SZjJnd&N2H=4s!q!zm)0da+FgB%e21OQF65Yt^|HLiWx3b~mZ|g> zi^y3=-(hd&^q|kNx}2rhYX(?{&=qXHHG-D0jn=badiM@xq=^$X1FoI$#Q}>jZKGM^ zkq@$&xtT+ra#}>Ee9)PO=j+W*d7GQuYcM634CZz!IYj@Uc#bK4*7-KD=Ud;ThRa(V#c$4sUEZ1$LEDbKzgGsXYDlcs7L>$P_;Dh{4yj*a1@ zI<{bJ5>0y5#JC-YQvFLFFxrt6Taa^C!bmx|~?cow;1P?cR3-ZCc?45B- zkZsub#q=0^X?z6T!`>aA>8~2RclhvOb!Ayt)A+jXDW}df3Z3s>{74BdX=vzB#YsZ5 zut3|$Q%>@2W?xTOglsaO9ERtbCl}IF?AIp~x#dkP`l+7Wk|vh@)F>_iSJ|foE~klA zJ~ci}EkdawjrDr$LvXEGZW3$0;Ff!{sEIS_L$+pOSjSEdEKcvH#eE zXnIHIey?n)1lxBgQwfpIdmx4F)dAReu6eF0BtJ95xFA6MN(n9}(kV}z$cg#bK2O7L zlwe$-dv!`taL!s0ccd}*@oIos)G{JH>G}4yHp#Gn+i5APA6VsVZp6~07IX}@2M-BZJ#v|7wT&pGmCgR5;AvvK6tp|WZN*%y^#|}ZTvSJn&Vc0nUlt`#3^BP4zo@P z8*<*Mv0k%9gilPLn5N#q)h$fH7Vj^*TI>0~v zmy1J%Cai#4$VjRwt@IJOqrA|)t?s|DU#BI+_IK;V*jfP<48>_(2hT?ZC*Fy9ru8Vq zNiA--e9Xy4JsoRwI2YC$=MAVO#2MBPyXx@$4zpLM=WwJG`)+#AiT%*GzF3#N&Zv$zxrR0h#2<~h;?&|k zgdS=XaQ64$)Q$Zb-YQ7!vXU45`W&qDi`H1ei#1Y(qSg+bBzt;r-b=bie(wyMT+rRF zahhuLr2H|x@R_Pvb~VRVC5wiYj$4YEO6$%P*q~G5#AaF7tdTO5W;w-4vB6Sll1okd zMM*?jMw4psph+VoDS6ThW18imP0eyor(q>0UZ3BZ*XT2fL)!^QC)^%6$##a5R-VB+ zWOBh6twu^#SZ?9qgl};2#Rr>$sMf0`YTFZsg8qP$7OCcGWtIM-_Mq+%CoN&e3*+e> zcC9eMZiB^Az>6JfIqA_U+J|1m#63*~P6|1VajNmdU8GN~I!6PY{jmCq9jHjHdR^zF zk4|w?eY0L9vG*?E^IKnocsM<_t`BVgf)g?)Da}7MwC6#39ZT2#k4sKc%Exhom4>@M z+RH9Zj%S-@L`9^x48%TJ?BJslA)~z6Q|WIGDxG5=&Ik#d>WM|q^=|pGAz1uZ1Cj2r zh8bye6pNdA7tfGcDReW-n>7+2rnb%MK_|20vqBE%p&p;Bf-czZi~neQRUH z8x5o{Uq@nYV(Wi^#V{Nh?_=j?PY5bkx}yP3Ij4n+y2b!pBOkJaIX&nqHhRuTE@T;d zdCrERhUIEKB74yoYi<%2tlCj&Zi`h7mxs+Pm|e_CDQ?jl*ES{-#7w}q} z>hLC4X`T;a*NQ6Wbhc*RAeztqIxmVFc!YgDFPiO|-&a4iGtS&c*k|+esfk4_NNiV( zT`_Y_uYBag(1(Uit z>kqhCMzX7mhWS>zd<+o+k&d&dXP(D(eD^bT6R5Pz5s7a|9{E9CF+N>sd#UdgyGRT^ zfM)bs_CsOJ3SVztb6mW&HSXh$Kkd@D#f#Og2ziVLxNMr2RUa+hO9NGv_k;BQ9IcwP zj7?gS=ijbv)zmDRk{RLlAMJ1TGkknIW{_WQ3@Ug8`wcO4$RU!yyF*)wy07&{+8d{K zAg`a-;#1|A7>*=Uv-;V~%_c0}=Kmx5NKI8sO=gWtNBaIAOIa4f4Qycr%aS^M=OnRD ze8U@rDD|Gm%9jnsm*9Ua%M7~gKB`}8(_P-7>W`cJleg#`j=CfaQq0)|8RTEGX9bFX`@tN~@#8B~u%`}QiA3J}r4I6d0ArwB0N)C2oRd0HT`92pFy2qI= zUbi)(XLiCSW7M4n)nc2odc<=(IPSYs?9vOv6BG=`<3;|^%o&MbTvGBMs%~JZt0zSD zI)g4KLF0-uaJ&2c-LwLa+>ae!9Y!~@^Q(>ep6I*4ebx6?bCm1Zg*|%lYgPQ+-iv0l zhxWhW=_q*{&%!kscvh^j;~BH|kVZI@%`UDTqEk<4H<|ysK@mTlR>Sxe#dgiM-L}`Z z3s>1z-;>Rzt?M0i?sV&!uGQjISnNrsS3UBLy5g*C_SU)~$ocBJ*~TqSkNlZSXVK#; z!u8)e-3P~)TR}wViQk7%oAnXil5ep!>(_B9A25AslJ4~gH7T_;4;gJO9fs%m(gAq7 zz0brA441ld8&pk`_nEL!wOqZ?it#$Xu{S--8aEnn;Rz~>qctqGEGqO^6IU7F;BXt} ztW@ZTj(mVBBp+o<%AV+;wl+AJ2%*93v$CYeqxwx^r=Q_FAG4UeX)GrMvtygOs^XJP zBf9p*s~T&>%806*M~9<1{D4)Q)i;=hZw}{TgW2HC(W;odIh-l;UX1q0ajt+Wt@Z7~ z0EgD^K^I053jY~D%aE;)j{c)l9$gxdY@j{i~-n1|+^WTfpezA^yd7JC%kvF+ozkAtW zwH4=QVkl8!OzM}o&1}j`MqGafur)6Yqy3rVC1YxeOSPNo(pMIHhfnR2TnynTP`VGE zM@l})*AQublSi(?!2h+yBY)VU?gk!tK8xCtNdwr-Efu~V`PC1ImYVmmz^z8aUTBM@ zdSi3iVnyCqep_s(H#W2__TkoP9X+zo2iQ@)`NX|E-|msWaCl=_=XwKQ!;3BQbeG=X zBecjJ707XW|si*Qh_@`Qlcwy`@E->}ru`fpV}1 zaRu#q+1oB6aVJ-z^+Y1}lX=p0qc(>(OvW#ddkTG`I||{2E%LxKBf}^%Z0%_Lu7pp` z>WK3WwUGN>r|FTOfy?TMZyKT4W!}Oss!C1${l87Hr*=)ifm$M2J^x7(^kVR}u6g~_ zlG7tDgji&Gp+XF@+|OBFMfz&LvEwI8O-8fsVZTwm?)VVJ;SZCkUXv(iC`>wB!?y2G zzd`-A(UaHw6%}PUSHY#X|APyfZ1wW%@z}{{_biL?gKnKkt-#bHjdrekpLLbSe~ydn zeywYtygL_`b^Nyeeph0CK**8C*ZfGcpQNoar)#pXraN1yI8N!AAB(JeD0F+ANO#F{ zsA9qo)B1~8BCwI=>&>b}CK?nmHUk-b)cBg_iuqc@`{+t`Y1;_xBl!mp>$?3jeN7VK zYm=&f+8#~E(4ja5fkVRxe*-k85dI-(0&YOs{%#K^{D)w9Dz+NPILIn+4&g7sWiT7@ zFgEGc9`-;pw3)4hAdKyej{=6r^lEwv;;CQ)mG4L23Nti?C7iA>|4`+f9>28=sj=)oNvPc*`Do9gd4$aPz7p0Eoe_q$Rqq9 z5C#k&6IeiddLhEEKZibroDC-ApO5KbxCl#-Mc|WjtC6RJ%;XM+0>Z_dtdtft^L|>~AlH#U@ZQ0iy%{EZ2uf zYXZ6_|9k1BNZ$k=K863@nfT}VWg^Wo5o2&}G6og=S;4+jFeV^y8vcC;{Fz-U($c`s z_)Hl%{r|Nan~}GC*-*ijkLqskk><^;AZcqwd0b`Ih0pJG? zeo!Q)Ey9IhHYftAbCD_1+~6(5Ux!?%g79Jxhf3{K^tLuN1Jse|c_f;e1S0aCrf2A$8ASeJ#XSVXzqMDFnI{q-7!=gK!nX2FN%N1rCAp z(0vJ3!9HdY<9785nTBjEKwYk>kSSmcOWpO7Jz*)<+G4l}Xl{U;;5PUfgcYMxKqAsp zKqGXikgK43h;S6-A>c-sLh8VzCFo^Uf^QLC3@ixy0)G$(ZX=IC$dF=8$OHsxV3Y=# z2{@|xZD?;ULvNshSAiR}CoD&}5NU~!t3U<9yCI`g9Tv68_`&2>&Vg5_|=&g73jia2MPIGH92x3~+*e1JF~jS1bUeH9 Kx?QU_;Qs(ZM{1-1 diff --git a/Tools/IO_Firmware/iofirmware_f103_lowpolh.bin b/Tools/IO_Firmware/iofirmware_f103_lowpolh.bin index 2179b5cbc5efb9479ae4c1206187a436fdc5234d..df3d1554a3a13e0b6122f807557df5cbf47d7efb 100755 GIT binary patch delta 9647 zcmb`Nd0dp${>RUGW(FP;CoQ^?IN0Ip6a= z>vQ(u%xUiWDb89(iLNM&@DB@w-_wRJx;>kufzGqm#^&^D8 zs3N)ouTBQC)jgA}A+C;QZ_(u-Uv)GSq7njSnn2VsKE=XR`x~A2ECBji)k2ovOF)kwP!A-A1%r zno&BwEu$+~z3=2cL9$yix^)5-SJ=Ix^6!xev4WTA!}NZ| z0U^CnA1zHIzBKJyp6HIU9e!>)j_vRtnV_v#3vOvc$GdW&@v67?C1ThwA2Yh8=Q{Sw zHAHK3OIzSOMqtAv|J8wUGBF&AD3_CrxkTM+BvkyKZR}O8_7*>Jvw_+v)&+KzKy``% zS7WgyCx}fSt_n}M`vu)QQ8tK+qX<6?+yOT5X9MA{Dq-F4SpvPHo7^Rbbjkbe!lCm4 zcBCH-_9!;}kZ3|zhTlMvw%08ai9V9t$t2$5L^sm~lyi;__GZ9*Yk@)ZSM5i`k2%_Y zRwbl1stoyJnPqhD8F_GWPN7@+yHgwWuxWac(m6A{tZm`%P(!(FN`9buV`WGJ`Ki3D zM&6>M@kD&Sj7II3=NZf8+$itnO!H}ZPLc{%Rq{(l_bqDJ0N)(+N?x*jYeVHld3kb` zY<*UDT24zAZ|UuUrQY!kw#}rny zsJX7~W2^O-weNJc-Fk1;JNfrMUK%LuEnCVK2fjg{WW9ot=tnF)Xa)UC-JgSoQyR@$ zgXf1PI$}}KMT}CvTraWE5ib}~w3k@ImONn4d>%k_U)1e<;0=x*Wy3?;xbr8NF)WB{ zJi&ypgWR+2ObqKw=doVl2|n@m&*kM4shGzy!%OJ{?49r#eP%&7C;8{Fy0$ge4?oih zXXH7v-I9jsBTBf}>}*R!2(4z-5gRpntbVn1iIFdIKD`_j8SNLT*pr>@H>kf6HPF`k zkM+;(m7@{IcKGM&1dW)}p)+t%zPY+cjacPoA-afuieXI^;kRgs?hNGj=(ofcG5?tw zx|ND&*dsbOD)opyebhFWewA;YpNY>QalVZKLMSp^?eea%-4#?IzdLhNciB37X z=q+eZKs(iwdb2B5NHh_wCO4AO$+KV9ERIrc+g{5jLafTu~9^yCYwikiHng?Np`lSe^j;n3KG7CbiS_W+53@h z)vpC)!>-rw3aEsg?7TU9JM8AbE~Hjz0uc+_ql;5*%d3M3uXN+R{e%yClkjJ%@qwz@ z6VaP!J!_2)4gTR2(OI%pt9mA=FLEgbvVl^TUv#HniDxc}?>K#oY)uig`dEQGOvPjDjrb2}3oA+(MlZ0P z2}$%k`&)v6-eW%|7`Sik`+^2i8pMJVhxwH{)pxSg^x*zVBCcoC5(i-?*qj(ir?Ufz zF#+*TqcEGqMS6)p%k&@-N3pLG6X`#h--8BfVo47MYkqJL@vqGE;1GJ3t$#3(7PB1> z76)E%_KWqp948bm)J55Dr=}5c1nW6yH1%SpLDOgqs~)8He!;0*s226?!k|6@bTr}9 zGI|kZ{~^$Z*R>4_q@la9L=dqY-Ii)I?j^huZPXEQ1=Abvof%SDr5mW)+Vrk2 ztWYCn*frvGN0f=^Bh1Q5>n|(go`{dNSCy*F;pSJebqhOX51m^&=hlc;M_O&5z7H0m zXB}gsf^#cFG~&VzY6u)>G#^>kX{!-a(N~;UWOaFxm%ftiF#G1ctGiO95q<1Nv&uXJ zSt}+5E~%L`jzQ&=lYml5WuYH~)+nud484K_hgms@C~+jmlAQyYTA!Lj#ITNGaQk@N zppK#N2Y6injv?^(ggcIie8*q}G#;1hNP*w&N-?G64bBNG9Bdk#H)L#BArX(d6ss>? zDLE>U$vPp~)Zeojs7Go_$o-Yp`9J)%o|<7ZEYE{fvCPfJ7T|`{(t| zDVI+bXv709W0c+$l@qokDle>1*?q3e=fvgC@VtJx5$Ls-U42b`^ES$_6@(Q=<|xC_ zEggBEG%6qc{sGZF82)V_OnDdD59vv2}HFKd; zM#;wq39s}adw1~kUX~LU48(iNphCBYu*e}F=Jj-UG;73%8Z_cm(7Qpd_Y=H@03lX* z06T=%r4}}2Y;WX*jEFcP6`E^Kogmu?q58^<)J7hfzaHmnHR4CdS^Q9$`@zoo5Br5K zW#Os))M~N8%|@k0z;o1HH!HP(a{i9Gn&I~-_i%gNnqZaYjQiP}qla>z>}Ow&eh~S8*~qkM zLGXO)u8U2>nLDVuE-WLSql{&ZncpMJrA$)NIJUa(y)iu~y~IAqYE92TTP(KMuq-FG z{G8rbP_5Dky%KzdK7viwm5stt`{UxYpGuRd@j?qp?jb0Lp~u@RTiwz-&f~2Cy<*s1 zAuHVLqR~QioU)Uy*BY9eNy0BpDVATFiS8aVWoP&M)JY6SWq;%IvY%0Fz^cOhTKze{ zRzH>ckXu^MYP0*%aMqMv6#02ayg&t=&^b;j8dGiP1kb|MA>Cs6IYr!N2RoMYC+=Yf z%gcR?e#Z{vZlniULS8?dbxe87=zi9iH!O0g>;8OFewR-<3p9Ng%DJ}7qm7)PO1XN> z2S*>m)U9bMx3r)AXv!KE>Btov(jrGX+~RhJG{{AMYBr{p4dr&odBp3UWu7t9A@%TB z&G1+iz$${3jy2Fz?8ULssn^<-93J$<84&lQ^Z&}>yvHisW2J@Fzntv*vD4`jEPGrM zM;&aekchJ591p%bF%cbGP1S@`Pj> z!4f7WavyfE=@Tb%R~_u_iG#Tx+S#`gp3YL`Nd4i@>7hD96o$lNqmm2p48a)WW%XeU9US$f02XAnwxvn za^haQZh^X$r=0klolTj%2-%#SJQ6OQvXDN+7EejyB$@4<(x1C0vyZ2Y;ogy%|D!tY z6PXzwofN7RA=i`E(_YxAu-Kk+lGwD1E-8}jezch0VRUL}&#k90cRel8vgoPj)Kt9V zWjZwBt zr9lO3$FyzqA1r2iB(JP2Zt1&57BpjuHO;AR{T|DN?Y1_J6NjH7#8RKRRxS7mrUq;r zxGBWezNd3Ze|4n&L<9G2Fqq>!L*J6N%N&x;*Sn-Rr^uFQFIYd{cf2X4=hAlROV`1SC9QopEb*~O?t2Ft`&eOg z>H&PK`pl;SYgIWo%Q&eabD5HL0rZ^6o#N4NKCJ1naGz-|WfpSci>&Rjm_T|`Yttf~ zT9{E=R+3ihlHOy3X2#$W@aW9B+|~o^{h1L#h4y%X=+&)dL?uqQD+h;~1MG*Hy11{~ zPao6TXo_FL4^1O^YyaVY3orgIyXSwn2xQbU0%L zO^s-yItS8RThw_9;lyuUICnYOmRYfeKF);=h9^=Qh+$t5J?N4WoT?h5jgB(%Nvz!DlD4t6k0;VK?8xKMJ&s`OR2J3PgY3%Vd7SLW1{C&>2|_3OU^M&US%i?( zdfKWZerU}54mIuq=%H2}rQ%Jtq%hRViFUVA6ViBFa`)prw?wzp3t?rR$o0ChenNBU z0|FT|{GuLDL-}ICgmx*$VQf%*1E6V_bdK2CR6)PWc3V!PV#%pOGj#Sip=4Q^A(F^DFh~)-1*|u$aa>!U5aw(S8>Ai($36MFk74$(^}k? zIC1HjY1pJ@L^4W6DOU*MJ&Ct#!pZm)Ewf( zsZ1(Lpck28cA~W$7B2!`=+VH5|2jeAX%i=Ye*)Wx=s2Ow6knX$;~SLWD78O`>1?r~ z5)HQ777WRQCphuVb}xa%{&W#-nV%ECY`@jqod+54c82;>r}UCs z^$0gqZocEKzU1Vj=UCJ1NE*w2oE@BS)JDZ4*yl;CcyThaixZ9^yJTck(-Dhq^XvGw zIY{`rnTUU3gNoC!5-lmd19#?};q)+jdCq8D3I92#U(yN%2>O78lO7aN_e$!4p=urV_*K=#_I< za^gnkTs&o@8q>OBCXsK7%jMy?E{!Nq&Uo_>JITnwonlPwvayhTbIaw)h@az}j~I(l z6$-J`nABykg%r;(mzTg`l9Sz=ufs(;*sQ0?Y#3ZUn+8|Qo-&7`e|MOdaOWM2FBw7q z&N54e`(Qj}R@4LuJ=yM(LEKyi`+G?kJ-}K@!u#)(#pZ~^gg=e0QKrtvkWE07s*2sx zh<7~PGnwUyq_wF{j%MW+fpzLG zxn3Mj_<4X;l@9cp)C<>&!|c;ioaC5cK~lG3`hrnbC62FG<+!CU-O9tDTbkNfhAMUH zKJU_vZ`}H;?tGVSOk>rry3<{{5sfv!>fYXks(Y(TH=yxir>++Y-rJ>&XuN)y z4OqB_ZfAQImU7}@=D+Cu;O(fOwq7+>xt@LG^pifGyaqaXQ)k%Q6YlTy z>Iz#h-UlL&v4E&a+Jd@z%PtzAs5~#Vd-K#v)B;wtG~cgV+o`cFoso6J={L^L53a{5i67hCEH6|{U^Cam4DI76M#|z} zQ!1x=-^(L}>O0;%6?sR7aNXP*N<|gYW{&x;SxMK%gK*5a{T zEhy8-Ek!!m>uba44A!uAGA(4i)`e3uOIR05KVVtw3|_MGnO?11w2q^k9Ke=Z|DlMy zvH>)NEh+m5?(p^d;9gsw30J?t3U|+jL#otMA#B{nVH)LFRKhlI9HQzt8Nxo;*az{K zH^xL>JK1?;QsY;QtLB%?yUed<(93S=Mx!Mgcfaysp4|Gd1?A%n4>{b@d8a1V3-{u! z4$fe(RG{kKI7%E3#04D46A&zNWy%c_jQO1-dBPj&3Y$~ZcgHB?51%(8PeS{sM! z9%rJup122|K^3MRVLw!k@1eByTLfJXH#-%(x13)1 zEkyaINj{0*6}tAq%$_c3Ctg81ZL?l1wYsEPow1nP zUV6Ts7doVqPA|Q;u0#4WBoA2!=>z!=WDm$AkbNKzIF;?jOCJmW9vpL(&;3S+56<^t zZX#;s4(VNIha`gUIy$5rwCjZqB?S@vkH3P}6LDbhacWRmh~ab#O*!47O35rz&aQ0W z*090lr$&cT3`fTd6f{tAc)zSvSQcmKbMYG8~A|$5DdEGLg9}D`gHt=9erQKW%yfxQmHt|MDXvG8Uo#L z&i zA>b}DqXkFe=u765!(c`4pdJgt)n23HUE%l2*jGfs&~h=ira>Ye1ZBD#qyW8Tg#wj||r$Zat`& ziFSZLva3a0Jt%q{w&36GCT8ZZSUy6RyQpM&NzsCmWhIN|lZlz^yO+be#;K=w^>Z-o z<|2oA_@5AP34}gD_@jmBIZzK8fDL>A?iOL8Kzs>g?rhW)avSi2-wvsPJPW&Xpbg>b z2z&|nFM-S88klICk4zD{1jfOT0gyK!Zy@p}I8==Bqv$~k!gm!NGHQiv19sp7yJ1IR zqbXuxJJ(DMEyWlH&o98xg0$fk<1+jW;2g&P1=PD0dKbdilr}(KhP(kTfg;4MhpqxN z!T#Dpc5CN=;NZn51ym@b5?Qta{Exw_&slFSMIDx4jYI5Cup8_F)u0JXu%P~+6&ymi z4KfKFh5r&Lg1;WJ0oXtQ^3y;U0CvD12Ppg>Anq)<0rsH0bC4GnV=Uc-XCaL2kS@Sc zRrj1ByO*Okmf`Dwde9w_2!ANzT97UY{+aMkfV>1+z+LEDK`r#QCy^eUTY>q5xHhFM zFnLkwqQxuO;ayW^=f8>Hmz1j@XaPThHsApCFyXy{KM3rS-PPz`aP(`i=zz6YTxLQB zLl!}n0Q}m*&t1c2z4rR>ZChXh8bCFu1-rp!umYR~#YRHXj{MfrS8(n)&W7x^#=TqW zw$iSW-EKeNjPhxO6NgB6qm>K4Ndw|5;dvgA|JkO`!s<+;* zz22(o;rbcw<9g0sLWyuRobVSj2_FM?w#jLb$Dx0m#yx+G7nc7q{dK9a8aX1t<}D9dVUpprxBlH27EI$koKL>)0J zE@+5A0tnClOs=Eaf~x!UDB)FouAT__Aekj}OthQaEe$?Wh>LvR(m;qt3{q%3>EpZ@ z8cvgovq*FYYk0xLnR{&M66N+31Vo3~Hu>l-(V@*3^B#GM!wZVDt}G}y0n0kllbZP& zy%f^oW8G7f{(vmmQ<(SQO48mUtu?%mM1M0Qd?xRJT>xiRZMA|&{@)$z2+<+%IV3ya zS3>Wy82<^~@)eJ~%p-_YTHK_M&U-+{#EN<;lfB|UGcdc0+BRw?e$@OUPlQya>*S#p zrt3VcccoHb3aGi}qZNHF6Jxn@!sLQowKg2i>+KKGyTtkkCY!xw|>fd@Z8e1W!27msFYfna%F>1 zkIG#8Df3>(nQP1Tq}w0tITmb@%9IA9?P^*Db1;yy&Kh~DBmXh zr6C~N7c=jfhU$l(+U<{CJl@)P`-4@-^B#P@} zTj@%+F*uQ)XSKo0=_l3wLsBS>V?|x(h9x>YAmM^5QB1G-sB_rt3nK4(Asl^}ks%$nhmecA5FqKK}|A1mv} z9&6Z@b-jVqsq49YJq%(|QR{Sv;JH$&E26e>z9G)i^yUjx3S_B5|DMUHV?a%(+)kFx z**fWymQEHy)JY$;2u3d2&mu(WrErC97b1J8hWYymzaxMMvmpPC-cPtKewGv6H|%RSyyLivhh+9SB_LT{@+F0_q87z$i{47tu_&XFE7{M|jY-_7{cMGC ztlkAzrfAsTjorDj{p=UxzwF;DI#H-Hz-b(F53|M>R1~ZisB{V10BAYMU%6RO0?p@M zI~r{e2Ut0YYlD0 zszrQ3sWL*)HEyvJPU_>nS$GnLdti9bYgmNLBCWB}#9&rz!}QYgEv*@!yWKOoLfM5E z_u;)x?wA<|@ZO8R6)+kFbpAsDWw2{@-JG!lcJp8tTBSCDNCnL?Gm{;`?*1sBu_hs6Z4T!bUe=~dRS^6@|h>M}mv!b{+xw5xehd$Z194F1@9ibT9NZ>z^ z@QS~ht-9N_LJ?EL0X14w*snzp102Z+hhVI}Y8FKPx863Rx7RikqadzV%JSDMo8X~d zH6>%)IQTX@)hBw`{pRu)-STjkzr`(Yb@^rzz(?H5H0SdV_a15GZIID^DtrFfd?K_ZP}PxVWn-?Gwv z#)vWQpBhvTanv19eKuO#IFPCq51d5$f}QO*DCE9VQz$55lRiYhLNk9?meb~!^SH=@3T|OK!iJbpM1*zgmvC0*OG*=$E`kH?nFGB z+=}K!W zq`Hp02Wtw66ogIWWIl;8SfX47EBH z+NXs&Hyh2Z&ZB*Lj6aB*26Wev!I8r_JPCs)cmDBIG0Jrz8+8n_*``5fbL^g$2Axz{ ztCPL}8)}srf6+$_6l2A%*o?ZiXvGcbJL)(wJu*&AhUN#iASzgg)KHe5T*pH*w3e^Z zNyBQ{Yl9UorZ;VTx#4<<5cgaP|o)3O`B(-V^)G4u`f~_4nxl>v#%4<^{sbF_T_Tny7urB7o z+=6#lj=5i?PWtg=F)H3A;b2{t7_HbH4G1>PBRc7dQoX~B6Zre@RBuS{!_jT5YSi2g zX=sGHApiYNb#!J2N-wemv2oZ4mmn59hQs~KHQhzcN}bp_-cRf%re4Hg&NSbfpF~Yx z-X=-vnXLo7qerfGITXPZ7~hLc&&mwbT`(0>L3L9B##;>}UcNY>7?WRk$m+7P=-13A zJBpUFnCu?32g}SZjJnd&N2H=4s!q!zm)0da+FgB%e21OQF65Yt^|HLiWx3b~mZ|g> zi^y3=-(hd&^q|kNx}2rhYX(?{&=qXHHG-D0jn=badiM@xq=^$X1FoI$#Q}>jZKGM^ zkq@$&xtT+ra#}>Ee9)PO=j+W*d7GQuYcM634CZz!IYj@Uc#bK4*7-KD=Ud;ThRa(V#c$4sUEZ1$LEDbKzgGsXYDlcs7L>$P_;Dh{4yj*a1@ zI<{bJ5>0y5#JC-YQvFLFFxrt6Taa^C!bmx|~?cow;1P?cR3-ZCc?45B- zkZsub#q=0^X?z6T!`>aA>8~2RclhvOb!Ayt)A+jXDW}df3Z3s>{74BdX=vzB#YsZ5 zut3|$Q%>@2W?xTOglsaO9ERtbCl}IF?AIp~x#dkP`l+7Wk|vh@)F>_iSJ|foE~klA zJ~ci}EkdawjrDr$LvXEGZW3$0;Ff!{sEIS_L$+pOSjSEdEKcvH#eE zXnIHIey?n)1lxBgQwfpIdmx4F)dAReu6eF0BtJ95xFA6MN(n9}(kV}z$cg#bK2O7L zlwe$-dv!`taL!s0ccd}*@oIos)G{JH>G}4yHp#Gn+i5APA6VsVZp6~07IX}@2M-BZJ#v|7wT&pGmCgR5;AvvK6tp|WZN*%y^#|}ZTvSJn&Vc0nUlt`#3^BP4zo@P z8*<*Mv0k%9gilPLn5N#q)h$fH7Vj^*TI>0~v zmy1J%Cai#4$VjRwt@IJOqrA|)t?s|DU#BI+_IK;V*jfP<48>_(2hT?ZC*Fy9ru8Vq zNiA--e9Xy4JsoRwI2YC$=MAVO#2MBPyXx@$4zpLM=WwJG`)+#AiT%*GzF3#N&Zv$zxrR0h#2<~h;?&|k zgdS=XaQ64$)Q$Zb-YQ7!vXU45`W&qDi`H1ei#1Y(qSg+bBzt;r-b=bie(wyMT+rRF zahhuLr2H|x@R_Pvb~VRVC5wiYj$4YEO6$%P*q~G5#AaF7tdTO5W;w-4vB6Sll1okd zMM*?jMw4psph+VoDS6ThW18imP0eyor(q>0UZ3BZ*XT2fL)!^QC)^%6$##a5R-VB+ zWOBh6twu^#SZ?9qgl};2#Rr>$sMf0`YTFZsg8qP$7OCcGWtIM-_Mq+%CoN&e3*+e> zcC9eMZiB^Az>6JfIqA_U+J|1m#63*~P6|1VajNmdU8GN~I!6PY{jmCq9jHjHdR^zF zk4|w?eY0L9vG*?E^IKnocsM<_t`BVgf)g?)Da}7MwC6#39ZT2#k4sKc%Exhom4>@M z+RH9Zj%S-@L`9^x48%TJ?BJslA)~z6Q|WIGDxG5=&Ik#d>WM|q^=|pGAz1uZ1Cj2r zh8bye6pNdA7tfGcDReW-n>7+2rnb%MK_|20vqBE%p&p;Bf-czZi~neQRUH z8x5o{Uq@nYV(Wi^#V{Nh?_=j?PY5bkx}yP3Ij4n+y2b!pBOkJaIX&nqHhRuTE@T;d zdCrERhUIEKB74yoYi<%2tlCj&Zi`h7mxs+Pm|e_CDQ?jl*ES{-#7w}q} z>hLC4X`T;a*NQ6Wbhc*RAeztqIxmVFc!YgDFPiO|-&a4iGtS&c*k|+esfk4_NNiV( zT`_Y_uYBag(1(Uit z>kqhCMzX7mhWS>zd<+o+k&d&dXP(D(eD^bT6R5Pz5s7a|9{E9CF+N>sd#UdgyGRT^ zfM)bs_CsOJ3SVztb6mW&HSXh$Kkd@D#f#Og2ziVLxNMr2RUa+hO9NGv_k;BQ9IcwP zj7?gS=ijbv)zmDRk{RLlAMJ1TGkknIW{_WQ3@Ug8`wcO4$RU!yyF*)wy07&{+8d{K zAg`a-;#1|A7>*=Uv-;V~%_c0}=Kmx5NKI8sO=gWtNBaIAOIa4f4Qycr%aS^M=OnRD ze8U@rDD|Gm%9jnsm*9Ua%M7~gKB`}8(_P-7>W`cJleg#`j=CfaQq0)|8RTEGX9bFX`@tN~@#8B~u%`}QiA3J}r4I6d0ArwB0N)C2oRd0HT`92pFy2qI= zUbi)(XLiCSW7M4n)nc2odc<=(IPSYs?9vOv6BG=`<3;|^%o&MbTvGBMs%~JZt0zSD zI)g4KLF0-uaJ&2c-LwLa+>ae!9Y!~@^Q(>ep6I*4ebx6?bCm1Zg*|%lYgPQ+-iv0l zhxWhW=_q*{&%!kscvh^j;~BH|kVZI@%`UDTqEk<4H<|ysK@mTlR>Sxe#dgiM-L}`Z z3s>1z-;>Rzt?M0i?sV&!uGQjISnNrsS3UBLy5g*C_SU)~$ocBJ*~TqSkNlZSXVK#; z!u8)e-3P~)TR}wViQk7%oAnXil5ep!>(_B9A25AslJ4~gH7T_;4;gJO9fs%m(gAq7 zz0brA441ld8&pk`_nEL!wOqZ?it#$Xu{S--8aEnn;Rz~>qctqGEGqO^6IU7F;BXt} ztW@ZTj(mVBBp+o<%AV+;wl+AJ2%*93v$CYeqxwx^r=Q_FAG4UeX)GrMvtygOs^XJP zBf9p*s~T&>%806*M~9<1{D4)Q)i;=hZw}{TgW2HC(W;odIh-l;UX1q0ajt+Wt@Z7~ z0EgD^K^I053jY~D%aE;)j{c)l9$gxdY@j{i~-n1|+^WTfpezA^yd7JC%kvF+ozkAtW zwH4=QVkl8!OzM}o&1}j`MqGafur)6Yqy3rVC1YxeOSPNo(pMIHhfnR2TnynTP`VGE zM@l})*AQublSi(?!2h+yBY)VU?gk!tK8xCtNdwr-Efu~V`PC1ImYVmmz^z8aUTBM@ zdSi3iVnyCqep_s(H#W2__TkoP9X+zo2iQ@)`NX|E-|msWaCl=_=XwKQ!;3BQbeG=X zBecjJ707XW|si*Qh_@`Qlcwy`@E->}ru`fpV}1 zaRu#q+1oB6aVJ-z^+Y1}lX=p0qc(>(OvW#ddkTG`I||{2E%LxKBf}^%Z0%_Lu7pp` z>WK3WwUGN>r|FTOfy?TMZyKT4W!}Oss!C1${l87Hr*=)ifm$M2J^x7(^kVR}u6g~_ zlG7tDgji&Gp+XF@+|OBFMfz&LvEwI8O-8fsVZTwm?)VVJ;SZCkUXv(iC`>wB!?y2G zzd`-A(UaHw6%}PUSHY#X|APyfZ1wW%@z}{{_biL?gKnKkt-#bHjdrekpLLbSe~ydn zeywYtygL_`b^Nyeeph0CK**8C*ZfGcpQNoar)#pXraN1yI8N!AAB(JeD0F+ANO#F{ zsA9qo)B1~8BCwI=>&>b}CK?nmHUk-b)cBg_iuqc@`{+t`Y1;_xBl!mp>$?3jeN7VK zYm=&f+8#~E(4ja5fkVRxe*-k85dI-(0&YOs{%#K^{D)w9Dz+NPILIn+4&g7sWiT7@ zFgEGc9`-;pw3)4hAdKyej{=6r^lEwv;;CQ)mG4L23Nti?C7iA>|4`+f9>28=sj=)oNvPc*`Do9gd4$aPz7p0Eoe_q$Rqq9 z5C#k&6IeiddLhEEKZibroDC-ApO5KbxCl#-Mc|WjtC6RJ%;XM+0>Z_dtdtft^L|>~AlH#U@ZQ0iy%{EZ2uf zYXZ6_|9k1BNZ$k=K863@nfT}VWg^Wo5o2&}G6og=S;4+jFeV^y8vcC;{Fz-U($c`s z_)Hl%{r|Nan~}GC*-*ijkLqskk><^;AZcqwd0b`Ih0pJG? zeo!Q)Ey9IhHYftAbCD_1+~6(5Ux!?%g79Jxhf3{K^tLuN1Jse|c_f;e1S0aCrf2A$8ASeJ#XSVXzqMDFnI{q-7!=gK!nX2FN%N1rCAp z(0vJ3!9HdY<9785nTBjEKwYk>kSSmcOWpO7Jz*)<+G4l}Xl{U;;5PUfgcYMxKqAsp zKqGXikgK43h;S6-A>c-sLh8VzCFo^Uf^QLC3@ixy0)G$(ZX=IC$dF=8$OHsxV3Y=# z2{@|xZD?;ULvNshSAiR}CoD&}5NU~!t3U<9yCI`g9Tv68_`&2>&Vg5_|=&g73jia2MPIGH92x3~+*e1JF~jS1bUeH9 Kx?QU_;Qs(ZM{1-1 diff --git a/Tools/IO_Firmware/iofirmware_highpolh.bin b/Tools/IO_Firmware/iofirmware_highpolh.bin index 4e2b62dec6a670717a5576388d7117c53931ccdd..2d30bc034288e00249096e372f3efd34b99be500 100755 GIT binary patch delta 9768 zcmb`Ndt6jy{>Pu^%!Px14uZ;6&&)WAAUS{+yrf*@a2XXabv3m>yo}ezOWw)`6Aeu_ z_0iT#rlpoz8btIHV?tAR*LK~cw9U#^D;-(2JtQ^b0#-2K0fKWzKp6~gQH z5q>OK1rCEP&l3JMPz^4CYtIrp--v)_4JwWK_rmItNhvg|v`tQFmk(F;pTc9;6F#Y& z@WqfrU;X!Tf5~J2Z;AguX<3PcKc7kX&=rIy_$!r28h4%4t(8c6M%5a+S5q}Jz^2j$ z$h`CynSI%5v^hY!>Eoq0q_2mRv9bKN??4(k3bJsClf29kMF4nPeK~bUC z-y-}a6%h)wZS-fWf|3H_y{*mwsSB$N>R}JFL|L~7=&nRryXG3CuAKS3sG?3Q^J>%r zHC$WJd5o!aa!Dtfxz?6#%MQx>dO=W5*Ols0693?mxmIH!!s8`-tQivJ_7w3pTQ;d9 zy=mH~sPQuR3@Ejm-wPCoiT2i6LUZ@b&1fP^_7v}(JGN+ZQMtY7MQe0`=d#AwDeuK1 zW(||nDtCQ;(-#B7i$9wYR`Qrtt2ftXN`k7Z@K}*n3jUDjxHP2_YM_=VRH;-#9txX{ z>+Xk^YxBZTmQJOq-)2phDBV`1XgeB6EfN0kB~?5TIwDGo`RcapKG!lI@fYN{&8KOk ziFKro4Gb=&FR<$1!X8~^pDWoXh*VnItTp5}k-|7pD+RFFkg44wx}rVz$aSKlX(X7Y zea{o&INK89qhr~Y&chRQ)oRh_+R*x*Tx9+#Am9oy9+KZR`&=)z9+E4F&f#-yMd)1u z8}_fxtHM%bVmumCCMTJ5iMr8DsC1V-)8()_K>FOrdg~_91?(AJtbLAw@B_eipc=em zB>ZPeT=+F}p;vTc+htJa+(uKU4#RYGc=%9t;e+D7G`lLsc}6!~1AdUS?IEsqx~V=z@~ ze-Ql+HI~Vi`&1G_~A;6hwJuS~nQo-tgyxr`( zMUBrRG*c*(^OEIT&zE14mn9#NBR2`B<+Nn!mOgJ?c~|QJx!nBef{*0y%}%zrYh=ln zx3Yc=DtW$qPlml|_lYn|wDpSxD(hDZc4ZSZ;+*;8htfBm2x?D{Ubrip8h>zZmCq3p zXK#A;MCMOo*z5jM94BV#1-#V9THn5HyTBa2V|?T%jt8CK(_-e zQN@d#RS*7bxBs-}owjb;n^wM)-}L7tVdCqhOW2&S{d74C2v4GaVnf59rhlw@CwwTS z{a8b{Igv^3I8<~Ab1x)UD=l}&i)K`+SYwPM~}0l$OjSEPbq!s zpPXEIS+;VV-f`QOrj@RoVk4uDa0go0?Wmq~HVcSO2#jyOEH4{Rr93t~dOq#W-i)5w z;|b_yCf|>$da&Al_A@~|C(oSWb7@#)%-raAo6pH*<4-tuWnXuaI>oFDpTxBTwoXX`iz!KR0?8_UITiY(MDZ$=P{jgyX0u38Lgdj1yLhC(JB}@LvXGT ztC8OKF`W?8OEIiHK={o%coE3E7}>-IDgT8Ex|K@jm__i>{>-9JANi(NzcM&4#KPy0 ze!+F2Vk8QD$s17NxGlXz0*RoMa2vVR2rH!?*g%O=no?@*0rs)Jf8@*Fe2F}E_yL)9 zUe={5-*jnloT!#Iu`Y%!G?VQ!7`eL#*hhwBuHpdu$uM54R-?;mHqO|SYdXLd8Nan( zl{KPJsfSlM;vH^DC^}qJCQ#{b(CVP&qyYJ5Q7JU%{dUx#7gH>pu{~K3K^Ab=Noz(4$Hfc@fG9?_L^oKLcWzhSC9?6F2Aav z9Cotj=8PS%n+dy!N~H@#Drzy6q&i9uhZ9~ISaO)~!W&q2AmzhshH1lq>XW;&1vp{J zNr-A?P=fjrmr@`b36*}RC4w#c*Sg!RN1qk+b@o!9v2+Ey*5?YugxOVfek41J8L~YEMY6*EP{I z`?=s;wfM*Tr?p_{yy4`cDDkKLXO7BggpeI(1w2Ezcq$KR3r&pZzYCo}Pp;-fk;oY$fUkn-9b!~gG@{kdQ66i&hc!!iO(g$%MmG;tx0;y z-q0Lr5kzB=4sW6&hzO^_B?VYthm^npK!V|2fB?+kHn^)u%!uzHZI~e|K}9FzK|Bov z<4fkjUD&*h=5%ZV0^s`hSa;9gltJ120$=e;Lr_}N76o1xMtL+^t?Vz-Ae9jxjn*r@uwoRj zjj<~G8zqh8*zDOk2&7i0<`5~WbqJn4{Lk>#!3c-?pPgF=Aspm?@~s0A*7%=XYYM_X zZ;B-)Z(vST(Ll?2kQ24o zkQY^?EQnvu;iP4r=)7LJF&M|!yge;F^VZ3)6hsxp<|uR2=X&cyQm4H4hv$TUK1}_M z$?!FXN|_AGq_E*-E0dvPVkon-IK9n%bWD(E;mW2%r%aT;9wEFks_gB7k9Xa0%7(ev zq|7V43FWP@fMX zZL21I)Z*y|ZZ;J{uvmTKtH|K%28lw^tRg||vkVQy$EbQ%Er!()t6DnitD2NrK)DEa z)sdl1l*?|ZdUbfbDlnlXUz%6warI^OBNMuw#Hc(I{`*nXqAF4*)E5U?=TVP$&N_(( zwyPozvE`%sa3c<}S4R!zzBt4_AN5F#TDo0lLr=RV9;xeUQj0y&<8bplqL#k)RS9W0 zBM679x@N?4l(9!g&*_xqRX%r8H~DbYiP4=Xy~1j;8q+f{7BNLv+YO=|~(6{#=sw=vkTe9^fF7xiN+d}om0#) zH#?T|GMDXU8M)KwKiU4=b^0ToL-NaHhg>Y|keQifoT`r(wR*w?QQbIF<#R1(nR!d; zA@)CcL+BFrue@kl#)2$oDaSss^nl)J$r_?}=ZbFE5_dYDb6VW46fgPFX-+L2%9?8yD}j}aG16N0!WdKPjTWVZWPe&;q}})YrxO0=x9a7$3WwEo z5Bq-1<8&SyH8zQ(Znk8sVZh&~<1GFJj?rKt*bm+W8p*Dr32D;K(o#9Cpr2SFZy;XR z7wqg`*hu?WJ4UKM;O`^~k?NC8jD^#cXCZ(-o;%?O>j5E|^BU zv4(;bSiy@6r-p2E(?`{fr`31rWrvPkC^T`>hfFF=rZLPoK9RfF%Epf$&wb@)Z;T(v z{m{a`9v|QPi=7p1jr)5i!>KIom18~SkK3npo(peEshmi%H$F6=XQxU| zI@v5NP&e|FlU{3P<0dXb;f{&J@ob*Bkd9|_CMD4jwtJF^c4Bptvbggy)BaB2zLicK)u!bO#5&&&|mx(Ggj9sKzXwYj|Xk{3=cqyOjpLHyF>ZC4{JnF`~@HLLxI@Fra z7Eg_&e`GICjU3X?qq2NujgFd}F*%(_TNI}zW3>(uy{`FQt=I)}j<+-#TV+-8odAk& zZ%K>mTlUq|EMu&PlN#I|3nU>fCH<}+cHsvNKD zwuc%smnwBlgPxNjYI%%UFLq&Cbl`Na;^H~!FuOOcZy5bR=g=XaTAW&0IybG->w2H{ zo!*x|%krnsN`3{ol`T!0DbSK8_a0897CBxddUfLnqLSt{w}nd)p4qJILu%h-x26m6 z-?p57SLdK9AqhX!4-=X((R6U}QuX?Z0FgV+3q9ML{!b4xKhZxf!K)GDY6P?}9J^`_ zHd0h@Bh!^dZMzyyYVmqqyoZ%N5ohe-Sy*G7mr_HF2aD+uuPec$sxUj~aN`Wc8Qph! zF>s$eF+I1kwr!uvSF6pOw7i)Lyh91iscGAw88*rtg z>;q||Ktj-^%WgGJFBqss0XubfE1Opo)m6Nl2UT zw}^qoR$spKY+;LQMstg+k6XWz6R*#2D=QbDg$MIjhhrTl&8)?apccnKHl(;v%}Fo& z*yiHFiN~-d#T7|WY}=U+tsR4|j|ZGIPccs~ufPg$$Z zPMkTE9%C=f97Q*=PiFSQB>30NZqfgcBPvU*T;AyhVpJxB^(f(O_(r_0ldRV)BYmG` z&dTlll>C#kV_7df%J$3}Jm@KpK}<(aao%js5#z<7*o7xyfbl-o^{+9BH=LwDUq?(g zmE{!Ee;Nwj!8EfchQBWNL2vwPz5V$1AN-1(*KZ?iWHt6!!x zB&H8FS;i#eBUMIfzbDtCgbzfP6wR`6(jPpcKdx>}CB_-16|+`w(iRW<{hS!?IS+e# zPET%;hy4}e2@ktFN5J_g#HzLoPkPSx2{rcIasW7s4Z@%a;kv$!L4CQG~s6hwrhTW?Sw8wC_BbJo?k#C zSoDIV4#oHdBkf8WU#-gVxxVo!ca%QYw=13Z&$|DeSeJgT)3L`sed-yUcy~WlH__*M))9_t8lS5Po5;>% z)P0nEV?4x!o5RdL%f2f%Ef4gUmEqwnZSeqqe3(bu9=BnV_eU9H08x{)1y#pwdugbm z@?RPcUPP6o1#HTa{E!Z9o2Gin)GU`LWNe5fSbwg;G$?qC2@TwV11ZsW$|F*Pr&D{1 zvL^LK+J;k`QP#ERaTAJiNh(cKZkFz`iAxWL@VIqXQk7cGOtWlM;4iVU%S<>@FI|?> zxx!82#(l}_g;*lp^0N1q4dy=fvb)Ph=f3GZu3c)?T-hPNq7%f(G$Qr(46+`7cfZqC z^uANs(-K_rD(`-E`zw(Bt!dNQ+I2siGP6}ryXc#2@$w$n-)>xjZmdRp023+#IaeBQ*{y?8CMjnPXKteVO@I>FJA1zdC^qWn))IM)!BW z6Fp44VKtAYQXlts*5RY?I3wV2D0TpASNEks?C9#)2v19fc-`6jC)N#&zWad^QR5evudG|Gd#$^03T$&05zM=;Z|q+_ zXxnqOS!{>Jo(y``=ekj6%Z^~_WkXQ(si&|Ll!L?$8%B`8@H*uB4%$I+1-PzDogar=*qmG zju|*h6iWAmu~VC(I5~`czR947mQ7LYy%*yWKRNXneh^Cocb!Ei2;V=P2pyn#xKL2# zJ&pnh^kx>gxi2LwX|vHEm#TY+FI4b`5S&?ku9eMd@ls{*-tc59>wl$kG8_*e=ka3 zZFo0Uuw^g&hLn1euO`xy%{~|P_*?-#pDVQe+x>t|-;%|Z`PiW?n*+VBs5+viX*<}^ z-y0EAx5sArV?TV@mbT3w`=UMO@W(!Ck2U;$dXU%k67EXcYztqSZ}++;w58$`*6R6c zUTk&!$)nW=2(7NOkUV4^WFX`Rkewj^2eJobl}A}}wE8%Nk7NJJSK}t8H4qzmosUR5 zxz%;r)9UhopITd86VS0etx66ebw2qDx=*D3-A>~3gKs(AKvPaPs8TYEmF*}?-5Qhp zlE1``AL0(-Hn#27O{wL+e}KHMJAQW*h84i)`oza3trR18yxEQ)2ZKZ^MqmLk;nISY zZX2m~xsJ>1qir8+O(}%$mr}KTyMY!i9!B`5LF5R+7lLAhXMwq3A;1r_{=X@Y;-_P9 z6Xb&3KtB?{k3&8RvcMIvk!g1Hvad~pwb;gbgg1gMVB14_CH*Mk$H94U5nKh=zzxt* zvtri~K7(7R3qS(`K?vwb3q`mah)lfQjbd88V0L^~Ay{%2@NXP=YU@RyE6TuYF(Q0qTFX4XqcrPFeB(|f6?6A#6 zcp?}Jx`9X#3p&!bA-o%`vE#8G90kWghrxM-@2$d6LtX$izyZ#H4x5QNgkKDjvQZdV z1CE2~AQw1*2I&uw=UzM4@QND1Jd4T<~A&Bn?Qv2Z|?So`c^iuM%n1lgS)DX)0bP_$|Yyk+uq~nT~#d-?BT3 zwBumPlduK9wqxJ?A*Fpj`bRNxCO)rOu$+y5Isq3!=sf%*N)bi~90!%48q|QB#c&8n zFNRE?ffhk-1R8`JA-%u>yEEV(!iVwyDi;vG2B{~QJz_&ZOAkRMqw{{JISukpZd;mDA>i9Is&Se;lrFc2uIOs?)AsmXd8_3rW;fV<6 zLS6(nz)k2Iz)|R{mm@zo^E5saq}@~M0uvX_U-Z-pc4F@&`_wmZ-orWXHn<1wgJ$3Z znq!0y0$o9mcG=O44!;t)8omWQ4IeTQG6Zr8WHCrYcse8@TpAB(Tjn4o9s@Y6WcF9q z4z1pd@dekw1#ktN0ms2^&;Uxzgp7Xcmtok2t;b0=bf4W+G2drbO7{6E_4(SW2#m!* p^!~-Vl3m*utu4pT0P^dsbzcU4Wlw*#4*zFD_t()e?96`q{{mF)rj7sr delta 10163 zcmb`Nd0bT0|NqaqGXoa{9R!qB?=YeWVgra`h7KT?Wl+E^*8~+EcU&sXbZ|%0(vI~} z)6&e+(gKN+bOOuzwtW2jq}4P(X&Wvd`&?YQms!8BJ3!0#@#*u|kH_PA&pGe&zVCC+ z`<{Kca+*8a#M!DS5spU@{^MN2$Aax0;dq2^K>kO57VPn7I?Jp5ktw7fa7; z>TY(Q5&TW@4PwlZNRD12#YP7wMKqeTEAxsaLMrpRx0ZLK&Dor;8M$V@aWS5qd36!~ zl^Var3NNL#u_psZPT{3dNOWrpFA5)ZEL(GNoT81c&TDI-QiIaHsQaH}yp(gVyd?46r^mn_{|UVQgL>T`3omZ)+PcX3A4Ox_MXJ!e*RwSrgve_a|0(IN6FLiSQn z6?L=t;L@I>6|ek=R}iVRxXmxF_%10;5dEYawmo=Ccz$=ZO>LK+nn@5f|Hu;|levSv zw1Bz04(nH=l$rGPm;AM&|ChvgKsjOZ%7;8JDK$iI_sTCKc7k~2y=-Q;m7$q!#CSAj zgOXw@Alg! zzU~O${tr6)A$tO>0`J3SJZ!0UzC>INDSH>h!gVoB}U zvc5VZiQHaaRikVZXd;oeRnfSYl-Z^YN@53@vDFD%elFD=-eM^K5grceKnzxDN?j{N9_yYr~=mzEvMSwa$QcUQlj^Q##8 zqR+~^ug@|FqE{a0IsP+gR6q4lwmmdDEz7B^*n?_Od|<2aw-$X|06N*?mb!Z%*=)bA zd856Nw!16eD8BpA(opfms%7lE&==?mW(!N9AG6x9hv_GE{lbS*n#{_3%!y2QCZL$} z=ySmZev;%&6iq1DPikXVdl+@!hG0z91@wG@qnYez^*IpT@A>F;jZZfNWOkov6BdkJ;Y;ToBJHvu1eZ0Jbw` zE;qozTrm+eorTA)*B!)klTx=o_9-qP+_^E^ah^&cEM2&-PX=nBukTvawV+$RPWsl< zwLlPc(glxT zy>G}GZtxgZ1QiBb_O zJ8l5|iY<=oNk3tmPqWFS13(F@7%0H;RURXza!9dXfEX{NDDR zq7#K$14j1i?qQasvcqK?1S)+2sUA{J3RZq9tAgZHpB{}fh-ns1;@aZNk3rf5=|tb# zPq`DsWDCLEa5crO>=?#L!`+9=k3i>j=vaL^tKB3n-lA$Gm2Fgp3%b^AHo{4X?w`s} zLUAt?kN6bl!dQ$YA&wZ#iglQuw9(UU_=D?x;tngj@!~$b*VP?A<0ZVe=C=Yyp@43G zDxeyA4%bgJc0q3*^df52CJ?F25kE7-F1!*(c-4&uUM76gD}=8EyI)}!<2TV$th{ez z_}$a+Z=PmFmn7|ZF0Di{5-R<|p6dH3J;MC^jiRgB_j_b{};GjhZvWbA3DxS^Lcv&K3fdX4I;e4rX|K^1bGBeZ_lXLisA78=MF*SfAgRj z9$e=jMnT-5RF`Z}wqRa(+LVF$`prY^L}J{qJB|Zu+_KpfT;P^>x@NBlD$t4_-f8l4 z%LyLR5KvSsdDAdqGq=3R({zIDNE7vj1d)4{N+(&jq%-v2tT|~2{hS31NTGjc!v+|s zgH0b`Z0$V=5k+RQ#qzK@P&ZOO5;jP)GYFT~_Bi8Dxl z^z{G-Jwl|BtaxBDz06h*G}2ObaA3IZu9HZAXQu|H(>ttnU?`rt`(}oI?&_W3_f3DX zY@rZmzm{Ppl9{c#Zv++Dsrx3;w^_K!;NQzFEYwQ1EYs98WbJUmo3pzSJv>DqeXXv- z6iOoxVTvHqR=6$0{_P>ctJx-jNUPY+lzx6SFX2-jX78p5Js*OK-W~&is^XO;%qm1G zX7^GS&--^kK@!UlxP@nx$( zNg&=q`U-TkTC9v<8+3{evwx%twu=feuD=sf&D-;#SXCcCI=(oq%wdhUyeUML>7>uv zbkYrHoP`)-tm-`5RZ)ivk!Cm!%-2|>t-JGth3#P=R_TwuI;oq>TpMcWiAgBRRTLLq zP#vL@)_bWjbd<^Z+Ol?Co%9iW#Ytyu@G3;}cjq~+L4|J$7t3|ho;H(JW1Rxis!EMp zZXu0DsGPd4tCdtI`5)05wN*U4LM;(ib$_Ae>FaexMl06#FSPkyIReER%V@sdUI|a^ zK&vzA2j>$h%#)612%a_~b@dEFqKogzd(sfs`JS976>+ayeY)H!c(%DyEGdPl`B7!5 zmej(uqNp+=z2eKifP9VAq6nhN(#JPTXou;fo?dP1AdL4`x7zoAm_>|duP3KbV;C0A z(VrjpF+@xddtd<(JX_O3=w%#P_VWNz zDQVzqby8^qdvdVCjdrl=A-~ekm@T7sADxt=)MWFG>7r0pQ6`9em!o`)L(St_F|>hL zb%Jp*9h24Lba-*Defe$2V0?Hl5(!5faJdI_JNa{Wj4PF)Y!NZ4DQ#x)V(YNsEwAfs6*{q7QjpkF%xuOto@u^4Kb4x!T_>rAyBiZ%FYb_*6ZceMjC=u?lxAXF_=6dsD=|&ct-<$Sknfc}P0(&7pn%-ci^2@pX zF4n8yS+3N@-YS?%ud&d=^;quzR@j?9#@;SmhGitlG9>m9ccMr|K~!f$ubkGHVTYG| z^PNYoW;V{#;4XN49CXSj+7qPlg zDV*2AejXJUK64u3kAr5=29h2kd>V@#9SKhi8Ev2+ut}ri=?P{VJw$Ee=;!DzHnw;O zoxz?czDa*!kCv?D)z+ynrDPTjX46U^r9AtxbV_i5i)LzDo3uBZ6+6!|$Ha4vMmB3q zDt(pxZA>!vwU>Q3W(+si#iGUz;wCy-$=Jk*Z09yiS?Ykef=|q2!o7=-9AVFoT?(@y z$t{V#qXSM z6}sJQeoqOjYH10q<)pz5VS%=lr<~N=!TvFR5sYU}7>4J{2@C0Y)-oZ5KEWa%jHlIX z#Dlq9P8-|wpum;2u_F(Ti&P6x>Pc&pA66+$wA0)q!F=8=_haD`XU5<2ys3O;N==K7 z$h}E*Ch_d`f$8>ZikXx8*fCgrt>fALiJwv%n>#5vfs^JaxA>M8ZQ@TCUbG4ePB(ai6vNVPeE^_U|gVkddl3e!gXSu^LFVSys9^g zT1KP^-pkjusfGpIGX-;-2Gu$ptr(EB0G`6~;iV%!YHr^LtHm7gen8H(@Tj2b(|jDA zLl9RR$j(llV5@X#TmOaG&3;V}_surf;S}O*NmIkbSIQ%5kz9qQj*-rCq8hU7* z(c0fP@+!^GStIiJdbj+sQ)9VgjgFd_Juyo?A*(B)f}KOK=$1p=equL-!S1SPTpwu4 zZ~9Zr8%rJXkM1McOIiurGi8L|5EmzDTLkEPjqLE$exV27(cATSPb*HTt(t4Db<0!PcT@Y( zXPN)B3a;uXTQn^utcN2}BnEA3712m~-*)K0QTF^aA#t6f>4e@+(}I(JX}(`*!zj6n z@}&BWHU1)ZoELhD8?X6c2x#5x+Oz=)xo(}9&>)~H1F-?uVZNh+6EDRsZr?d^SjpY; z>rVE-LkUK^b76yVURnb&9xA6t+;X#1Q)9BzVa6FG>DT5vEpAL)n;)81@TvL%Fx2^a zt%;L%v{8Y#tFg71`_=83`XSUwJNdej;|CWT8r0m9Hrl7pmG*53Nl=>I@(`9hJ(&t@ z%JlfaOIZ2UX+Gjrwsm?TN4m1FruVUpgck!aOdmL{mX}daTLlt~#{A;c;)nwmwF;C< z;n@6P@kV_@#qKM3F(~m!V^Ex?AgWR$y`iYJBaPQ&Z*R_b8urSsoo*j}O1)4NEVj(= zA(H!so;To*s8}i~b;$lsQ-d1oYlFxk6K6tghG!JvFS;nUJt<|e?Z-zn$b?PAV8BTm)c3Ng zYl21X5#3Qvs%Ed0Cvn8fz9=7HTL6_u0WStNa8l4Inn;^DDdrRvI4S9rI+%iRTuE$D zdu%`FK#b5zJF3)RzgCG}d*K~U`pV%al7!pmaWyu;AikQN(3l9_gYY}fY|fusI&F}? zuV-sNbIGa7fwA0RrRAo-_DdHhC$Y6NV(CQo!i?~w%XTVVa%0z@Ae|o%bN$5=FqaBL zv%LxMVW#KDmN4=A79!nd-_6LPBbj05O+15V4W(OI-mDS0Fxot;cgkdR4ShW|G@bCu zf>$eM)bf}CHYyRdGp$@<({*B0yHn9?I05>)0YpoJ#Mt<%@~pP|Q*xY=1?x&I}X#n7v|r*h@;UxD+hMg&r#ETJ;!ZT@==L zb}zbw<<1_#1utitW^b}ZKCBiQ)0f6uic&F%RUcX01r{}aAaZ6|MI|TYxJ6%D+nPa) zGvXhucocJmy8<^j876Z_&N%YJ%niy=92D;_QBTyfkvq=B;W@#S(V7W!oDIqnCIM=#_ zt8%fE*88c4-LVce1om%VKMaJ+SJw~iF~T2#Gtkp=Hr9lRfh>LQeX-qK`ofQLHKN`c z)O_wbwGtL5_7{UJ=7mK1l&zf`y}+(WEuHVGYjF*1Gyq+OCShA65hzxtwb|{RFzP~^ z{GiJZvv-?3)_Sao2CMw>o6Q8(;cO zcC14-sPWBqSvM5?VuvuX@$50yW8q_TAKSTbKKI2j=2`e|_&!t+oAe^}nA_9MS$@Fr zHik7X8W!-e%ij=OA4a*=pkX6E!= z{zG~EBLO~JkGptFd)nWZUheYiNLOO`41$eu07qW)^18#7&(RQ7#%!l)Urdt*We>HS1mPzxtEOy_&t@oJf51_{N-s~Z#YT9=!?8Th$T27 zv17{zb6OAkarwy5tM21|%dEODcPabyf*5Hg(nD<6!?BT6@;jwkYX8QS9qxC%lfjle zEJt2-`dR!6&tB(@JPw`OH1+7|m!`LW%ho` zO7!)iK35hfY~5305K%AFJ1*qe$Q8r66OBxGDh%J|$9JevgDq@MnYy~^>rFkz~qF;2ilQSACH$pi9OW*IWdgWr4wK9uN zW$RZOaAR|LWfJ|AHLr|}e%JX%^!?&ht7#;zi=01LhmE}15`l@1;zmaISUtO%vy ztbFzOUQwsfwkq6=RI07}U0ZEioXgj?&Ft1{qhBAmCw*UCk2M_S`gCVewy)ISwyiJC zXOUI^gXh(%LwIgnn}er&eNT2}trf9?bw@Q_Pv^6H>xTHLySV_yQr8cP{^FFHz|SGp zOV%CM=d8PNP;Q@MaI{|EPgi#en?H7ZeNUM9VEquE$%>q9POtolOIP5BJBlm6xz-=M zpKGB+NH|V-)hb`V^ewGr_Z%W|4s=;A;&8p_X%@%yCTbui-_hr=voGFJ?_owx& zygD}G^){|XZ|88Z<}6g`0+-%J#U41$o~<4osFoiVMudnk_Dgl@ACrk&#IBbxP5wb+ z&6Y7S0+jiBuUz5P6n=(Na#KY1O-gyYDreG`u&1{s^caA+#uB|Ey0-AwSJj51%mHC+ z_|_;cA&gDl8m9(pwni~&-kLbC+~1|I)mjdf>+M>LvqkO2*qh=fq&MJ-6M*gBnvfiF zYAk+RGlPG%jI1Gi2FmCJZNm+Xrf@RKF{yHPYimDhV&P91L)ElY-xDVmJ}wwH23|RV zS)PcD-r_R(uHLMWY{v$i7^;+blX@SxmD!#!;w+uU4nHxB-p8&!Vay!rQuU^~{AwzF zpH+2AiTY{5(S4YCq>Ph%J&~rjdF5Jkh_^jn`HV+h4ZQMvmbERHb9h+wwrv4k`T2K= zmYVmm*zHE7syk8zzSPo=)Wg2i)Q;3aUrOvqo!dUGi&qYP7eCec?4&lR2zi7v5e6WfjxZ466ofqyKIl@b>1RklycD~0_2a(g3Bb8z zlgA^^c6sDVa16YRwAPCs=X?!APd@oLnolHRJ6SAUG3Nf-IA$__N!(lRAIBTI2vOx8 zd4$hkyQjT!8E&xKuRGO3?)YX+ue=J|?=HCSh`=&)5WkQr^-XvFXS^-5M>00*63OfH zElKth!!GqGzAq~yJNkThfh^Bah(X4V_&_ZgpuK3rPmr1%hwk3Mk$rFY6U813l?gtT zp3VrU1YW`-Z&xq6-fs04J3gnPEQ<2;|`V)2dh%e!1|y3>Q0?-FvX_1Pfe2$Hn5=4?$K275OP6~`)lN)li? zQlUHgi*&avcUMgKnc1%y;{iIde9@tXFrq;bV{%~Vz1C+n7tEJhPQsP!%2UI&zsi@r zEN;gqe#cV@Uz=KYdq*5CZ5v8>H#j(q@ZW&zh~EOO;2yxQ$iBa;4`6=;7G~l`2B87r zQD8^>18@#ZLpp?2Jl)$CV1_ieonXX6KsdlU_nTbJPeD2zi~{39Ij8`0L1)RTUT3@@ zi}0mjJMwpeXa1nK2l4&jpc((4aQF`ylkmb4pjPTAI1c`ArRpJT087Ast5hxW7lMaD zXQe`5dnMAV!CIf()}Hk-66ZiO_!4{rE`zI}^W}}%zsK#P;ZN`lIMYEr!cN`Gh+hX+ z!BKD=)Pm0Z_+spXL5K~HNRSD#K&Qea#GiQ#Zbmo_i~^-#Jm}Q9o`+3vK0cEOV~B@< zEYOPdWl)Ov9apR^rrE|7jEYZAeOSmTvSh{&dU%xeF=15k$lT2M^ksrLCbu** zKI36wT;4b}3?xJ<;K&uGB~ASTNL6unLehgs*$+KBzXI7a6Md)xE&+zw@HE&t7v3(z za0Wv`CddN0z_z3u)q}z%e$WH;+AxlTN1hQL*ha)@)?jha= z+@N$RoD5kh_!9BCAPaE{bie?v!bSkX;7ZJm@rWFU(olq%fTNn zjD?6#LSBD_OTd1_cOnc|Wgr>x6wr#e`w_ek0zf@v>0l@rzi9rV#gDR2_Dp!l`3m7b zdX4aZ2hHGXa2fmnu7iJrUx5>JR-toZIs+$v0|GEfxe*@3WJFgX4bC90TgBGxeST=l zc6Pu^%!Px14uZ;6&&)WAAUS{+yrf*@a2XXabv3m>yo}ezOWw)`6Aeu_ z_0iT#rlpoz8btIHV?tAR*LK~cw9U#^D;-(2JtQ^b0#-2K0fKWzKp6~gQH z5q>OK1rCEP&l3JMPz^4CYtIrp--v)_4JwWK_rmItNhvg|v`tQFmk(F;pTc9;6F#Y& z@WqfrU;X!Tf5~J2Z;AguX<3PcKc7kX&=rIy_$!r28h4%4t(8c6M%5a+S5q}Jz^2j$ z$h`CynSI%5v^hY!>Eoq0q_2mRv9bKN??4(k3bJsClf29kMF4nPeK~bUC z-y-}a6%h)wZS-fWf|3H_y{*mwsSB$N>R}JFL|L~7=&nRryXG3CuAKS3sG?3Q^J>%r zHC$WJd5o!aa!Dtfxz?6#%MQx>dO=W5*Ols0693?mxmIH!!s8`-tQivJ_7w3pTQ;d9 zy=mH~sPQuR3@Ejm-wPCoiT2i6LUZ@b&1fP^_7v}(JGN+ZQMtY7MQe0`=d#AwDeuK1 zW(||nDtCQ;(-#B7i$9wYR`Qrtt2ftXN`k7Z@K}*n3jUDjxHP2_YM_=VRH;-#9txX{ z>+Xk^YxBZTmQJOq-)2phDBV`1XgeB6EfN0kB~?5TIwDGo`RcapKG!lI@fYN{&8KOk ziFKro4Gb=&FR<$1!X8~^pDWoXh*VnItTp5}k-|7pD+RFFkg44wx}rVz$aSKlX(X7Y zea{o&INK89qhr~Y&chRQ)oRh_+R*x*Tx9+#Am9oy9+KZR`&=)z9+E4F&f#-yMd)1u z8}_fxtHM%bVmumCCMTJ5iMr8DsC1V-)8()_K>FOrdg~_91?(AJtbLAw@B_eipc=em zB>ZPeT=+F}p;vTc+htJa+(uKU4#RYGc=%9t;e+D7G`lLsc}6!~1AdUS?IEsqx~V=z@~ ze-Ql+HI~Vi`&1G_~A;6hwJuS~nQo-tgyxr`( zMUBrRG*c*(^OEIT&zE14mn9#NBR2`B<+Nn!mOgJ?c~|QJx!nBef{*0y%}%zrYh=ln zx3Yc=DtW$qPlml|_lYn|wDpSxD(hDZc4ZSZ;+*;8htfBm2x?D{Ubrip8h>zZmCq3p zXK#A;MCMOo*z5jM94BV#1-#V9THn5HyTBa2V|?T%jt8CK(_-e zQN@d#RS*7bxBs-}owjb;n^wM)-}L7tVdCqhOW2&S{d74C2v4GaVnf59rhlw@CwwTS z{a8b{Igv^3I8<~Ab1x)UD=l}&i)K`+SYwPM~}0l$OjSEPbq!s zpPXEIS+;VV-f`QOrj@RoVk4uDa0go0?Wmq~HVcSO2#jyOEH4{Rr93t~dOq#W-i)5w z;|b_yCf|>$da&Al_A@~|C(oSWb7@#)%-raAo6pH*<4-tuWnXuaI>oFDpTxBTwoXX`iz!KR0?8_UITiY(MDZ$=P{jgyX0u38Lgdj1yLhC(JB}@LvXGT ztC8OKF`W?8OEIiHK={o%coE3E7}>-IDgT8Ex|K@jm__i>{>-9JANi(NzcM&4#KPy0 ze!+F2Vk8QD$s17NxGlXz0*RoMa2vVR2rH!?*g%O=no?@*0rs)Jf8@*Fe2F}E_yL)9 zUe={5-*jnloT!#Iu`Y%!G?VQ!7`eL#*hhwBuHpdu$uM54R-?;mHqO|SYdXLd8Nan( zl{KPJsfSlM;vH^DC^}qJCQ#{b(CVP&qyYJ5Q7JU%{dUx#7gH>pu{~K3K^Ab=Noz(4$Hfc@fG9?_L^oKLcWzhSC9?6F2Aav z9Cotj=8PS%n+dy!N~H@#Drzy6q&i9uhZ9~ISaO)~!W&q2AmzhshH1lq>XW;&1vp{J zNr-A?P=fjrmr@`b36*}RC4w#c*Sg!RN1qk+b@o!9v2+Ey*5?YugxOVfek41J8L~YEMY6*EP{I z`?=s;wfM*Tr?p_{yy4`cDDkKLXO7BggpeI(1w2Ezcq$KR3r&pZzYCo}Pp;-fk;oY$fUkn-9b!~gG@{kdQ66i&hc!!iO(g$%MmG;tx0;y z-q0Lr5kzB=4sW6&hzO^_B?VYthm^npK!V|2fB?+kHn^)u%!uzHZI~e|K}9FzK|Bov z<4fkjUD&*h=5%ZV0^s`hSa;9gltJ120$=e;Lr_}N76o1xMtL+^t?Vz-Ae9jxjn*r@uwoRj zjj<~G8zqh8*zDOk2&7i0<`5~WbqJn4{Lk>#!3c-?pPgF=Aspm?@~s0A*7%=XYYM_X zZ;B-)Z(vST(Ll?2kQ24o zkQY^?EQnvu;iP4r=)7LJF&M|!yge;F^VZ3)6hsxp<|uR2=X&cyQm4H4hv$TUK1}_M z$?!FXN|_AGq_E*-E0dvPVkon-IK9n%bWD(E;mW2%r%aT;9wEFks_gB7k9Xa0%7(ev zq|7V43FWP@fMX zZL21I)Z*y|ZZ;J{uvmTKtH|K%28lw^tRg||vkVQy$EbQ%Er!()t6DnitD2NrK)DEa z)sdl1l*?|ZdUbfbDlnlXUz%6warI^OBNMuw#Hc(I{`*nXqAF4*)E5U?=TVP$&N_(( zwyPozvE`%sa3c<}S4R!zzBt4_AN5F#TDo0lLr=RV9;xeUQj0y&<8bplqL#k)RS9W0 zBM679x@N?4l(9!g&*_xqRX%r8H~DbYiP4=Xy~1j;8q+f{7BNLv+YO=|~(6{#=sw=vkTe9^fF7xiN+d}om0#) zH#?T|GMDXU8M)KwKiU4=b^0ToL-NaHhg>Y|keQifoT`r(wR*w?QQbIF<#R1(nR!d; zA@)CcL+BFrue@kl#)2$oDaSss^nl)J$r_?}=ZbFE5_dYDb6VW46fgPFX-+L2%9?8yD}j}aG16N0!WdKPjTWVZWPe&;q}})YrxO0=x9a7$3WwEo z5Bq-1<8&SyH8zQ(Znk8sVZh&~<1GFJj?rKt*bm+W8p*Dr32D;K(o#9Cpr2SFZy;XR z7wqg`*hu?WJ4UKM;O`^~k?NC8jD^#cXCZ(-o;%?O>j5E|^BU zv4(;bSiy@6r-p2E(?`{fr`31rWrvPkC^T`>hfFF=rZLPoK9RfF%Epf$&wb@)Z;T(v z{m{a`9v|QPi=7p1jr)5i!>KIom18~SkK3npo(peEshmi%H$F6=XQxU| zI@v5NP&e|FlU{3P<0dXb;f{&J@ob*Bkd9|_CMD4jwtJF^c4Bptvbggy)BaB2zLicK)u!bO#5&&&|mx(Ggj9sKzXwYj|Xk{3=cqyOjpLHyF>ZC4{JnF`~@HLLxI@Fra z7Eg_&e`GICjU3X?qq2NujgFd}F*%(_TNI}zW3>(uy{`FQt=I)}j<+-#TV+-8odAk& zZ%K>mTlUq|EMu&PlN#I|3nU>fCH<}+cHsvNKD zwuc%smnwBlgPxNjYI%%UFLq&Cbl`Na;^H~!FuOOcZy5bR=g=XaTAW&0IybG->w2H{ zo!*x|%krnsN`3{ol`T!0DbSK8_a0897CBxddUfLnqLSt{w}nd)p4qJILu%h-x26m6 z-?p57SLdK9AqhX!4-=X((R6U}QuX?Z0FgV+3q9ML{!b4xKhZxf!K)GDY6P?}9J^`_ zHd0h@Bh!^dZMzyyYVmqqyoZ%N5ohe-Sy*G7mr_HF2aD+uuPec$sxUj~aN`Wc8Qph! zF>s$eF+I1kwr!uvSF6pOw7i)Lyh91iscGAw88*rtg z>;q||Ktj-^%WgGJFBqss0XubfE1Opo)m6Nl2UT zw}^qoR$spKY+;LQMstg+k6XWz6R*#2D=QbDg$MIjhhrTl&8)?apccnKHl(;v%}Fo& z*yiHFiN~-d#T7|WY}=U+tsR4|j|ZGIPccs~ufPg$$Z zPMkTE9%C=f97Q*=PiFSQB>30NZqfgcBPvU*T;AyhVpJxB^(f(O_(r_0ldRV)BYmG` z&dTlll>C#kV_7df%J$3}Jm@KpK}<(aao%js5#z<7*o7xyfbl-o^{+9BH=LwDUq?(g zmE{!Ee;Nwj!8EfchQBWNL2vwPz5V$1AN-1(*KZ?iWHt6!!x zB&H8FS;i#eBUMIfzbDtCgbzfP6wR`6(jPpcKdx>}CB_-16|+`w(iRW<{hS!?IS+e# zPET%;hy4}e2@ktFN5J_g#HzLoPkPSx2{rcIasW7s4Z@%a;kv$!L4CQG~s6hwrhTW?Sw8wC_BbJo?k#C zSoDIV4#oHdBkf8WU#-gVxxVo!ca%QYw=13Z&$|DeSeJgT)3L`sed-yUcy~WlH__*M))9_t8lS5Po5;>% z)P0nEV?4x!o5RdL%f2f%Ef4gUmEqwnZSeqqe3(bu9=BnV_eU9H08x{)1y#pwdugbm z@?RPcUPP6o1#HTa{E!Z9o2Gin)GU`LWNe5fSbwg;G$?qC2@TwV11ZsW$|F*Pr&D{1 zvL^LK+J;k`QP#ERaTAJiNh(cKZkFz`iAxWL@VIqXQk7cGOtWlM;4iVU%S<>@FI|?> zxx!82#(l}_g;*lp^0N1q4dy=fvb)Ph=f3GZu3c)?T-hPNq7%f(G$Qr(46+`7cfZqC z^uANs(-K_rD(`-E`zw(Bt!dNQ+I2siGP6}ryXc#2@$w$n-)>xjZmdRp023+#IaeBQ*{y?8CMjnPXKteVO@I>FJA1zdC^qWn))IM)!BW z6Fp44VKtAYQXlts*5RY?I3wV2D0TpASNEks?C9#)2v19fc-`6jC)N#&zWad^QR5evudG|Gd#$^03T$&05zM=;Z|q+_ zXxnqOS!{>Jo(y``=ekj6%Z^~_WkXQ(si&|Ll!L?$8%B`8@H*uB4%$I+1-PzDogar=*qmG zju|*h6iWAmu~VC(I5~`czR947mQ7LYy%*yWKRNXneh^Cocb!Ei2;V=P2pyn#xKL2# zJ&pnh^kx>gxi2LwX|vHEm#TY+FI4b`5S&?ku9eMd@ls{*-tc59>wl$kG8_*e=ka3 zZFo0Uuw^g&hLn1euO`xy%{~|P_*?-#pDVQe+x>t|-;%|Z`PiW?n*+VBs5+viX*<}^ z-y0EAx5sArV?TV@mbT3w`=UMO@W(!Ck2U;$dXU%k67EXcYztqSZ}++;w58$`*6R6c zUTk&!$)nW=2(7NOkUV4^WFX`Rkewj^2eJobl}A}}wE8%Nk7NJJSK}t8H4qzmosUR5 zxz%;r)9UhopITd86VS0etx66ebw2qDx=*D3-A>~3gKs(AKvPaPs8TYEmF*}?-5Qhp zlE1``AL0(-Hn#27O{wL+e}KHMJAQW*h84i)`oza3trR18yxEQ)2ZKZ^MqmLk;nISY zZX2m~xsJ>1qir8+O(}%$mr}KTyMY!i9!B`5LF5R+7lLAhXMwq3A;1r_{=X@Y;-_P9 z6Xb&3KtB?{k3&8RvcMIvk!g1Hvad~pwb;gbgg1gMVB14_CH*Mk$H94U5nKh=zzxt* zvtri~K7(7R3qS(`K?vwb3q`mah)lfQjbd88V0L^~Ay{%2@NXP=YU@RyE6TuYF(Q0qTFX4XqcrPFeB(|f6?6A#6 zcp?}Jx`9X#3p&!bA-o%`vE#8G90kWghrxM-@2$d6LtX$izyZ#H4x5QNgkKDjvQZdV z1CE2~AQw1*2I&uw=UzM4@QND1Jd4T<~A&Bn?Qv2Z|?So`c^iuM%n1lgS)DX)0bP_$|Yyk+uq~nT~#d-?BT3 zwBumPlduK9wqxJ?A*Fpj`bRNxCO)rOu$+y5Isq3!=sf%*N)bi~90!%48q|QB#c&8n zFNRE?ffhk-1R8`JA-%u>yEEV(!iVwyDi;vG2B{~QJz_&ZOAkRMqw{{JISukpZd;mDA>i9Is&Se;lrFc2uIOs?)AsmXd8_3rW;fV<6 zLS6(nz)k2Iz)|R{mm@zo^E5saq}@~M0uvX_U-Z-pc4F@&`_wmZ-orWXHn<1wgJ$3Z znq!0y0$o9mcG=O44!;t)8omWQ4IeTQG6Zr8WHCrYcse8@TpAB(Tjn4o9s@Y6WcF9q z4z1pd@dekw1#ktN0ms2^&;Uxzgp7Xcmtok2t;b0=bf4W+G2drbO7{6E_4(SW2#m!* p^!~-Vl3m*utu4pT0P^dsbzcU4Wlw*#4*zFD_t()e?96`q{{mF)rj7sr delta 10163 zcmb`Nd0bT0|NqaqGXoa{9R!qB?=YeWVgra`h7KT?Wl+E^*8~+EcU&sXbZ|%0(vI~} z)6&e+(gKN+bOOuzwtW2jq}4P(X&Wvd`&?YQms!8BJ3!0#@#*u|kH_PA&pGe&zVCC+ z`<{Kca+*8a#M!DS5spU@{^MN2$Aax0;dq2^K>kO57VPn7I?Jp5ktw7fa7; z>TY(Q5&TW@4PwlZNRD12#YP7wMKqeTEAxsaLMrpRx0ZLK&Dor;8M$V@aWS5qd36!~ zl^Var3NNL#u_psZPT{3dNOWrpFA5)ZEL(GNoT81c&TDI-QiIaHsQaH}yp(gVyd?46r^mn_{|UVQgL>T`3omZ)+PcX3A4Ox_MXJ!e*RwSrgve_a|0(IN6FLiSQn z6?L=t;L@I>6|ek=R}iVRxXmxF_%10;5dEYawmo=Ccz$=ZO>LK+nn@5f|Hu;|levSv zw1Bz04(nH=l$rGPm;AM&|ChvgKsjOZ%7;8JDK$iI_sTCKc7k~2y=-Q;m7$q!#CSAj zgOXw@Alg! zzU~O${tr6)A$tO>0`J3SJZ!0UzC>INDSH>h!gVoB}U zvc5VZiQHaaRikVZXd;oeRnfSYl-Z^YN@53@vDFD%elFD=-eM^K5grceKnzxDN?j{N9_yYr~=mzEvMSwa$QcUQlj^Q##8 zqR+~^ug@|FqE{a0IsP+gR6q4lwmmdDEz7B^*n?_Od|<2aw-$X|06N*?mb!Z%*=)bA zd856Nw!16eD8BpA(opfms%7lE&==?mW(!N9AG6x9hv_GE{lbS*n#{_3%!y2QCZL$} z=ySmZev;%&6iq1DPikXVdl+@!hG0z91@wG@qnYez^*IpT@A>F;jZZfNWOkov6BdkJ;Y;ToBJHvu1eZ0Jbw` zE;qozTrm+eorTA)*B!)klTx=o_9-qP+_^E^ah^&cEM2&-PX=nBukTvawV+$RPWsl< zwLlPc(glxT zy>G}GZtxgZ1QiBb_O zJ8l5|iY<=oNk3tmPqWFS13(F@7%0H;RURXza!9dXfEX{NDDR zq7#K$14j1i?qQasvcqK?1S)+2sUA{J3RZq9tAgZHpB{}fh-ns1;@aZNk3rf5=|tb# zPq`DsWDCLEa5crO>=?#L!`+9=k3i>j=vaL^tKB3n-lA$Gm2Fgp3%b^AHo{4X?w`s} zLUAt?kN6bl!dQ$YA&wZ#iglQuw9(UU_=D?x;tngj@!~$b*VP?A<0ZVe=C=Yyp@43G zDxeyA4%bgJc0q3*^df52CJ?F25kE7-F1!*(c-4&uUM76gD}=8EyI)}!<2TV$th{ez z_}$a+Z=PmFmn7|ZF0Di{5-R<|p6dH3J;MC^jiRgB_j_b{};GjhZvWbA3DxS^Lcv&K3fdX4I;e4rX|K^1bGBeZ_lXLisA78=MF*SfAgRj z9$e=jMnT-5RF`Z}wqRa(+LVF$`prY^L}J{qJB|Zu+_KpfT;P^>x@NBlD$t4_-f8l4 z%LyLR5KvSsdDAdqGq=3R({zIDNE7vj1d)4{N+(&jq%-v2tT|~2{hS31NTGjc!v+|s zgH0b`Z0$V=5k+RQ#qzK@P&ZOO5;jP)GYFT~_Bi8Dxl z^z{G-Jwl|BtaxBDz06h*G}2ObaA3IZu9HZAXQu|H(>ttnU?`rt`(}oI?&_W3_f3DX zY@rZmzm{Ppl9{c#Zv++Dsrx3;w^_K!;NQzFEYwQ1EYs98WbJUmo3pzSJv>DqeXXv- z6iOoxVTvHqR=6$0{_P>ctJx-jNUPY+lzx6SFX2-jX78p5Js*OK-W~&is^XO;%qm1G zX7^GS&--^kK@!UlxP@nx$( zNg&=q`U-TkTC9v<8+3{evwx%twu=feuD=sf&D-;#SXCcCI=(oq%wdhUyeUML>7>uv zbkYrHoP`)-tm-`5RZ)ivk!Cm!%-2|>t-JGth3#P=R_TwuI;oq>TpMcWiAgBRRTLLq zP#vL@)_bWjbd<^Z+Ol?Co%9iW#Ytyu@G3;}cjq~+L4|J$7t3|ho;H(JW1Rxis!EMp zZXu0DsGPd4tCdtI`5)05wN*U4LM;(ib$_Ae>FaexMl06#FSPkyIReER%V@sdUI|a^ zK&vzA2j>$h%#)612%a_~b@dEFqKogzd(sfs`JS976>+ayeY)H!c(%DyEGdPl`B7!5 zmej(uqNp+=z2eKifP9VAq6nhN(#JPTXou;fo?dP1AdL4`x7zoAm_>|duP3KbV;C0A z(VrjpF+@xddtd<(JX_O3=w%#P_VWNz zDQVzqby8^qdvdVCjdrl=A-~ekm@T7sADxt=)MWFG>7r0pQ6`9em!o`)L(St_F|>hL zb%Jp*9h24Lba-*Defe$2V0?Hl5(!5faJdI_JNa{Wj4PF)Y!NZ4DQ#x)V(YNsEwAfs6*{q7QjpkF%xuOto@u^4Kb4x!T_>rAyBiZ%FYb_*6ZceMjC=u?lxAXF_=6dsD=|&ct-<$Sknfc}P0(&7pn%-ci^2@pX zF4n8yS+3N@-YS?%ud&d=^;quzR@j?9#@;SmhGitlG9>m9ccMr|K~!f$ubkGHVTYG| z^PNYoW;V{#;4XN49CXSj+7qPlg zDV*2AejXJUK64u3kAr5=29h2kd>V@#9SKhi8Ev2+ut}ri=?P{VJw$Ee=;!DzHnw;O zoxz?czDa*!kCv?D)z+ynrDPTjX46U^r9AtxbV_i5i)LzDo3uBZ6+6!|$Ha4vMmB3q zDt(pxZA>!vwU>Q3W(+si#iGUz;wCy-$=Jk*Z09yiS?Ykef=|q2!o7=-9AVFoT?(@y z$t{V#qXSM z6}sJQeoqOjYH10q<)pz5VS%=lr<~N=!TvFR5sYU}7>4J{2@C0Y)-oZ5KEWa%jHlIX z#Dlq9P8-|wpum;2u_F(Ti&P6x>Pc&pA66+$wA0)q!F=8=_haD`XU5<2ys3O;N==K7 z$h}E*Ch_d`f$8>ZikXx8*fCgrt>fALiJwv%n>#5vfs^JaxA>M8ZQ@TCUbG4ePB(ai6vNVPeE^_U|gVkddl3e!gXSu^LFVSys9^g zT1KP^-pkjusfGpIGX-;-2Gu$ptr(EB0G`6~;iV%!YHr^LtHm7gen8H(@Tj2b(|jDA zLl9RR$j(llV5@X#TmOaG&3;V}_surf;S}O*NmIkbSIQ%5kz9qQj*-rCq8hU7* z(c0fP@+!^GStIiJdbj+sQ)9VgjgFd_Juyo?A*(B)f}KOK=$1p=equL-!S1SPTpwu4 zZ~9Zr8%rJXkM1McOIiurGi8L|5EmzDTLkEPjqLE$exV27(cATSPb*HTt(t4Db<0!PcT@Y( zXPN)B3a;uXTQn^utcN2}BnEA3712m~-*)K0QTF^aA#t6f>4e@+(}I(JX}(`*!zj6n z@}&BWHU1)ZoELhD8?X6c2x#5x+Oz=)xo(}9&>)~H1F-?uVZNh+6EDRsZr?d^SjpY; z>rVE-LkUK^b76yVURnb&9xA6t+;X#1Q)9BzVa6FG>DT5vEpAL)n;)81@TvL%Fx2^a zt%;L%v{8Y#tFg71`_=83`XSUwJNdej;|CWT8r0m9Hrl7pmG*53Nl=>I@(`9hJ(&t@ z%JlfaOIZ2UX+Gjrwsm?TN4m1FruVUpgck!aOdmL{mX}daTLlt~#{A;c;)nwmwF;C< z;n@6P@kV_@#qKM3F(~m!V^Ex?AgWR$y`iYJBaPQ&Z*R_b8urSsoo*j}O1)4NEVj(= zA(H!so;To*s8}i~b;$lsQ-d1oYlFxk6K6tghG!JvFS;nUJt<|e?Z-zn$b?PAV8BTm)c3Ng zYl21X5#3Qvs%Ed0Cvn8fz9=7HTL6_u0WStNa8l4Inn;^DDdrRvI4S9rI+%iRTuE$D zdu%`FK#b5zJF3)RzgCG}d*K~U`pV%al7!pmaWyu;AikQN(3l9_gYY}fY|fusI&F}? zuV-sNbIGa7fwA0RrRAo-_DdHhC$Y6NV(CQo!i?~w%XTVVa%0z@Ae|o%bN$5=FqaBL zv%LxMVW#KDmN4=A79!nd-_6LPBbj05O+15V4W(OI-mDS0Fxot;cgkdR4ShW|G@bCu zf>$eM)bf}CHYyRdGp$@<({*B0yHn9?I05>)0YpoJ#Mt<%@~pP|Q*xY=1?x&I}X#n7v|r*h@;UxD+hMg&r#ETJ;!ZT@==L zb}zbw<<1_#1utitW^b}ZKCBiQ)0f6uic&F%RUcX01r{}aAaZ6|MI|TYxJ6%D+nPa) zGvXhucocJmy8<^j876Z_&N%YJ%niy=92D;_QBTyfkvq=B;W@#S(V7W!oDIqnCIM=#_ zt8%fE*88c4-LVce1om%VKMaJ+SJw~iF~T2#Gtkp=Hr9lRfh>LQeX-qK`ofQLHKN`c z)O_wbwGtL5_7{UJ=7mK1l&zf`y}+(WEuHVGYjF*1Gyq+OCShA65hzxtwb|{RFzP~^ z{GiJZvv-?3)_Sao2CMw>o6Q8(;cO zcC14-sPWBqSvM5?VuvuX@$50yW8q_TAKSTbKKI2j=2`e|_&!t+oAe^}nA_9MS$@Fr zHik7X8W!-e%ij=OA4a*=pkX6E!= z{zG~EBLO~JkGptFd)nWZUheYiNLOO`41$eu07qW)^18#7&(RQ7#%!l)Urdt*We>HS1mPzxtEOy_&t@oJf51_{N-s~Z#YT9=!?8Th$T27 zv17{zb6OAkarwy5tM21|%dEODcPabyf*5Hg(nD<6!?BT6@;jwkYX8QS9qxC%lfjle zEJt2-`dR!6&tB(@JPw`OH1+7|m!`LW%ho` zO7!)iK35hfY~5305K%AFJ1*qe$Q8r66OBxGDh%J|$9JevgDq@MnYy~^>rFkz~qF;2ilQSACH$pi9OW*IWdgWr4wK9uN zW$RZOaAR|LWfJ|AHLr|}e%JX%^!?&ht7#;zi=01LhmE}15`l@1;zmaISUtO%vy ztbFzOUQwsfwkq6=RI07}U0ZEioXgj?&Ft1{qhBAmCw*UCk2M_S`gCVewy)ISwyiJC zXOUI^gXh(%LwIgnn}er&eNT2}trf9?bw@Q_Pv^6H>xTHLySV_yQr8cP{^FFHz|SGp zOV%CM=d8PNP;Q@MaI{|EPgi#en?H7ZeNUM9VEquE$%>q9POtolOIP5BJBlm6xz-=M zpKGB+NH|V-)hb`V^ewGr_Z%W|4s=;A;&8p_X%@%yCTbui-_hr=voGFJ?_owx& zygD}G^){|XZ|88Z<}6g`0+-%J#U41$o~<4osFoiVMudnk_Dgl@ACrk&#IBbxP5wb+ z&6Y7S0+jiBuUz5P6n=(Na#KY1O-gyYDreG`u&1{s^caA+#uB|Ey0-AwSJj51%mHC+ z_|_;cA&gDl8m9(pwni~&-kLbC+~1|I)mjdf>+M>LvqkO2*qh=fq&MJ-6M*gBnvfiF zYAk+RGlPG%jI1Gi2FmCJZNm+Xrf@RKF{yHPYimDhV&P91L)ElY-xDVmJ}wwH23|RV zS)PcD-r_R(uHLMWY{v$i7^;+blX@SxmD!#!;w+uU4nHxB-p8&!Vay!rQuU^~{AwzF zpH+2AiTY{5(S4YCq>Ph%J&~rjdF5Jkh_^jn`HV+h4ZQMvmbERHb9h+wwrv4k`T2K= zmYVmm*zHE7syk8zzSPo=)Wg2i)Q;3aUrOvqo!dUGi&qYP7eCec?4&lR2zi7v5e6WfjxZ466ofqyKIl@b>1RklycD~0_2a(g3Bb8z zlgA^^c6sDVa16YRwAPCs=X?!APd@oLnolHRJ6SAUG3Nf-IA$__N!(lRAIBTI2vOx8 zd4$hkyQjT!8E&xKuRGO3?)YX+ue=J|?=HCSh`=&)5WkQr^-XvFXS^-5M>00*63OfH zElKth!!GqGzAq~yJNkThfh^Bah(X4V_&_ZgpuK3rPmr1%hwk3Mk$rFY6U813l?gtT zp3VrU1YW`-Z&xq6-fs04J3gnPEQ<2;|`V)2dh%e!1|y3>Q0?-FvX_1Pfe2$Hn5=4?$K275OP6~`)lN)li? zQlUHgi*&avcUMgKnc1%y;{iIde9@tXFrq;bV{%~Vz1C+n7tEJhPQsP!%2UI&zsi@r zEN;gqe#cV@Uz=KYdq*5CZ5v8>H#j(q@ZW&zh~EOO;2yxQ$iBa;4`6=;7G~l`2B87r zQD8^>18@#ZLpp?2Jl)$CV1_ieonXX6KsdlU_nTbJPeD2zi~{39Ij8`0L1)RTUT3@@ zi}0mjJMwpeXa1nK2l4&jpc((4aQF`ylkmb4pjPTAI1c`ArRpJT087Ast5hxW7lMaD zXQe`5dnMAV!CIf()}Hk-66ZiO_!4{rE`zI}^W}}%zsK#P;ZN`lIMYEr!cN`Gh+hX+ z!BKD=)Pm0Z_+spXL5K~HNRSD#K&Qea#GiQ#Zbmo_i~^-#Jm}Q9o`+3vK0cEOV~B@< zEYOPdWl)Ov9apR^rrE|7jEYZAeOSmTvSh{&dU%xeF=15k$lT2M^ksrLCbu** zKI36wT;4b}3?xJ<;K&uGB~ASTNL6unLehgs*$+KBzXI7a6Md)xE&+zw@HE&t7v3(z za0Wv`CddN0z_z3u)q}z%e$WH;+AxlTN1hQL*ha)@)?jha= z+@N$RoD5kh_!9BCAPaE{bie?v!bSkX;7ZJm@rWFU(olq%fTNn zjD?6#LSBD_OTd1_cOnc|Wgr>x6wr#e`w_ek0zf@v>0l@rzi9rV#gDR2_Dp!l`3m7b zdX4aZ2hHGXa2fmnu7iJrUx5>JR-toZIs+$v0|GEfxe*@3WJFgX4bC90TgBGxeST=l zc6 Date: Sun, 3 Dec 2023 11:32:28 +1100 Subject: [PATCH 0041/1335] AP_Scripting: added readstring for uarts this is much more efficient than reading a byte at a time --- libraries/AP_Scripting/docs/docs.lua | 8 +++++++ .../generator/description/bindings.desc | 1 + libraries/AP_Scripting/lua_bindings.cpp | 24 +++++++++++++++++++ libraries/AP_Scripting/lua_bindings.h | 1 + 4 files changed, 34 insertions(+) diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index 856105481eaba2..1d57957c7b0e30 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -1140,6 +1140,14 @@ function AP_HAL__UARTDriver_ud:read() end ---@param baud_rate uint32_t_ud function AP_HAL__UARTDriver_ud:begin(baud_rate) end +--[[ + read count bytes from a uart and return as a lua string. Note + that the returned string can be shorter than the requested length +--]] +---@param count integer +---@return string|nil +function AP_HAL__UARTDriver_ud:readstring(count) end + -- desc ---@class RC_Channel_ud diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index 3c0c37a7a936ae..74cc6c109de8e3 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -357,6 +357,7 @@ include AP_SerialManager/AP_SerialManager.h ap_object AP_HAL::UARTDriver depends HAL_GCS_ENABLED ap_object AP_HAL::UARTDriver method begin void uint32_t 1U UINT32_MAX ap_object AP_HAL::UARTDriver method read int16_t +ap_object AP_HAL::UARTDriver manual readstring AP_HAL__UARTDriver_readstring 1 ap_object AP_HAL::UARTDriver method write uint32_t uint8_t'skip_check ap_object AP_HAL::UARTDriver method available uint32_t ap_object AP_HAL::UARTDriver method set_flow_control void AP_HAL::UARTDriver::flow_control'enum AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE AP_HAL::UARTDriver::FLOW_CONTROL_AUTO diff --git a/libraries/AP_Scripting/lua_bindings.cpp b/libraries/AP_Scripting/lua_bindings.cpp index 0059fb11509949..a8637ed380547a 100644 --- a/libraries/AP_Scripting/lua_bindings.cpp +++ b/libraries/AP_Scripting/lua_bindings.cpp @@ -638,6 +638,30 @@ int AP_HAL__I2CDevice_read_registers(lua_State *L) { return success; } +int AP_HAL__UARTDriver_readstring(lua_State *L) { + binding_argcheck(L, 2); + + AP_HAL::UARTDriver * ud = *check_AP_HAL__UARTDriver(L, 1); + + const uint16_t count = get_uint16_t(L, 2); + uint8_t *data = (uint8_t*)malloc(count); + if (data == nullptr) { + return 0; + } + + const auto ret = ud->read(data, count); + if (ret < 0) { + free(data); + return 0; + } + + // push to lua string + lua_pushlstring(L, (const char *)data, ret); + free(data); + + return 1; +} + #if AP_SCRIPTING_CAN_SENSOR_ENABLED int lua_get_CAN_device(lua_State *L) { diff --git a/libraries/AP_Scripting/lua_bindings.h b/libraries/AP_Scripting/lua_bindings.h index 6bc459dc27bf2b..99e4f8a3747727 100644 --- a/libraries/AP_Scripting/lua_bindings.h +++ b/libraries/AP_Scripting/lua_bindings.h @@ -8,6 +8,7 @@ int lua_mission_receive(lua_State *L); int AP_Logger_Write(lua_State *L); int lua_get_i2c_device(lua_State *L); int AP_HAL__I2CDevice_read_registers(lua_State *L); +int AP_HAL__UARTDriver_readstring(lua_State *L); int lua_get_CAN_device(lua_State *L); int lua_get_CAN_device2(lua_State *L); int lua_dirlist(lua_State *L); From ff86e2dda88b9644e523b481019d3fe6f00aa701 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 8 Dec 2023 13:07:31 +1100 Subject: [PATCH 0042/1335] AP_WindVane: add and use AP_WINDVANE_*_ENABLED defines --- libraries/AP_WindVane/AP_WindVane.cpp | 26 ++++++++++-- libraries/AP_WindVane/AP_WindVane.h | 22 +++++++++- .../AP_WindVane/AP_WindVane_Airspeed.cpp | 8 +++- libraries/AP_WindVane/AP_WindVane_Airspeed.h | 6 +++ libraries/AP_WindVane/AP_WindVane_Analog.cpp | 6 +++ libraries/AP_WindVane/AP_WindVane_Analog.h | 6 +++ libraries/AP_WindVane/AP_WindVane_Backend.cpp | 6 +++ libraries/AP_WindVane/AP_WindVane_Backend.h | 6 +++ libraries/AP_WindVane/AP_WindVane_Home.cpp | 6 +++ libraries/AP_WindVane/AP_WindVane_Home.h | 6 +++ .../AP_WindVane/AP_WindVane_ModernDevice.cpp | 6 +++ .../AP_WindVane/AP_WindVane_ModernDevice.h | 6 +++ libraries/AP_WindVane/AP_WindVane_NMEA.cpp | 6 +++ libraries/AP_WindVane/AP_WindVane_NMEA.h | 6 +++ libraries/AP_WindVane/AP_WindVane_RPM.cpp | 8 +++- libraries/AP_WindVane/AP_WindVane_RPM.h | 6 +++ libraries/AP_WindVane/AP_WindVane_SITL.cpp | 8 ++-- libraries/AP_WindVane/AP_WindVane_SITL.h | 6 +++ libraries/AP_WindVane/AP_WindVane_config.h | 42 +++++++++++++++++++ 19 files changed, 180 insertions(+), 12 deletions(-) create mode 100644 libraries/AP_WindVane/AP_WindVane_config.h diff --git a/libraries/AP_WindVane/AP_WindVane.cpp b/libraries/AP_WindVane/AP_WindVane.cpp index cd541779016eec..3b3cb718352426 100644 --- a/libraries/AP_WindVane/AP_WindVane.cpp +++ b/libraries/AP_WindVane/AP_WindVane.cpp @@ -13,6 +13,10 @@ along with this program. If not, see . */ +#include "AP_WindVane_config.h" + +#if AP_WINDVANE_ENABLED + #include "AP_WindVane.h" #include "AP_WindVane_Home.h" @@ -202,36 +206,46 @@ void AP_WindVane::init(const AP_SerialManager& serial_manager) case WindVaneType::WINDVANE_NONE: // WindVane disabled return; +#if AP_WINDVANE_HOME_ENABLED case WindVaneType::WINDVANE_HOME_HEADING: case WindVaneType::WINDVANE_PWM_PIN: _direction_driver = new AP_WindVane_Home(*this); break; +#endif +#if AP_WINDVANE_ANALOG_ENABLED case WindVaneType::WINDVANE_ANALOG_PIN: _direction_driver = new AP_WindVane_Analog(*this); break; -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#endif +#if AP_WINDVANE_SIM_ENABLED case WindVaneType::WINDVANE_SITL_TRUE: case WindVaneType::WINDVANE_SITL_APPARENT: _direction_driver = new AP_WindVane_SITL(*this); break; #endif +#if AP_WINDVANE_NMEA_ENABLED case WindVaneType::WINDVANE_NMEA: _direction_driver = new AP_WindVane_NMEA(*this); _direction_driver->init(serial_manager); break; +#endif } // wind speed switch (_speed_sensor_type) { case Speed_type::WINDSPEED_NONE: break; +#if AP_WINDVANE_AIRSPEED_ENABLED case Speed_type::WINDSPEED_AIRSPEED: _speed_driver = new AP_WindVane_Airspeed(*this); break; +#endif +#if AP_WINDVANE_MODERNDEVICE_ENABLED case Speed_type::WINDVANE_WIND_SENSOR_REV_P: _speed_driver = new AP_WindVane_ModernDevice(*this); break; -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#endif +#if AP_WINDVANE_SIM_ENABLED case Speed_type::WINDSPEED_SITL_TRUE: case Speed_type::WINDSPEED_SITL_APPARENT: // single driver does both speed and direction @@ -241,7 +255,8 @@ void AP_WindVane::init(const AP_SerialManager& serial_manager) _speed_driver = _direction_driver; } break; -#endif +#endif // AP_WINDVANE_SIM_ENABLED +#if AP_WINDVANE_NMEA_ENABLED case Speed_type::WINDSPEED_NMEA: // single driver does both speed and direction if (_direction_type != WindVaneType::WINDVANE_NMEA) { @@ -251,9 +266,12 @@ void AP_WindVane::init(const AP_SerialManager& serial_manager) _speed_driver = _direction_driver; } break; +#endif // AP_WINDVANE_NMEA_ENABLED +#if AP_WINDVANE_RPM_ENABLED case Speed_type::WINDSPEED_RPM: _speed_driver = new AP_WindVane_RPM(*this); break; +#endif } } @@ -476,3 +494,5 @@ namespace AP { return AP_WindVane::get_singleton(); } }; + +#endif // AP_WINDVANE_ENABLED diff --git a/libraries/AP_WindVane/AP_WindVane.h b/libraries/AP_WindVane/AP_WindVane.h index e17edbaa49f7b0..148f072e867a53 100644 --- a/libraries/AP_WindVane/AP_WindVane.h +++ b/libraries/AP_WindVane/AP_WindVane.h @@ -14,6 +14,10 @@ */ #pragma once +#include "AP_WindVane_config.h" + +#if AP_WINDVANE_ENABLED + #include #include #include @@ -162,11 +166,17 @@ class AP_WindVane enum WindVaneType { WINDVANE_NONE = 0, +#if AP_WINDVANE_HOME_ENABLED WINDVANE_HOME_HEADING = 1, WINDVANE_PWM_PIN = 2, +#endif +#if AP_WINDVANE_ANALOG_ENABLED WINDVANE_ANALOG_PIN = 3, +#endif +#if AP_WINDVANE_NMEA_ENABLED WINDVANE_NMEA = 4, -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#endif +#if AP_WINDVANE_SIM_ENABLED WINDVANE_SITL_TRUE = 10, WINDVANE_SITL_APPARENT = 11, #endif @@ -174,11 +184,17 @@ class AP_WindVane enum Speed_type { WINDSPEED_NONE = 0, +#if AP_WINDVANE_AIRSPEED_ENABLED WINDSPEED_AIRSPEED = 1, +#endif WINDVANE_WIND_SENSOR_REV_P = 2, +#if AP_WINDVANE_RPM_ENABLED WINDSPEED_RPM = 3, +#endif +#if AP_WINDVANE_NMEA_ENABLED WINDSPEED_NMEA = 4, -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#endif +#if AP_WINDVANE_SIM_ENABLED WINDSPEED_SITL_TRUE = 10, WINDSPEED_SITL_APPARENT = 11, #endif @@ -190,3 +206,5 @@ class AP_WindVane namespace AP { AP_WindVane *windvane(); }; + +#endif // AP_WINDVANE_ENABLED diff --git a/libraries/AP_WindVane/AP_WindVane_Airspeed.cpp b/libraries/AP_WindVane/AP_WindVane_Airspeed.cpp index 094d27cc496925..54496e2f15857d 100644 --- a/libraries/AP_WindVane/AP_WindVane_Airspeed.cpp +++ b/libraries/AP_WindVane/AP_WindVane_Airspeed.cpp @@ -13,14 +13,18 @@ along with this program. If not, see . */ +#include "AP_WindVane_config.h" + +#if AP_WINDVANE_AIRSPEED_ENABLED + #include "AP_WindVane_Airspeed.h" void AP_WindVane_Airspeed::update_speed() { -#if AP_AIRSPEED_ENABLED const AP_Airspeed* airspeed = AP_Airspeed::get_singleton(); if (airspeed != nullptr) { _frontend._speed_apparent_raw = airspeed->get_raw_airspeed(); } -#endif } + +#endif // AP_WINDVANE_AIRSPEED_ENABLED diff --git a/libraries/AP_WindVane/AP_WindVane_Airspeed.h b/libraries/AP_WindVane/AP_WindVane_Airspeed.h index 8f69151bc442fd..d64c8badb7c0e4 100644 --- a/libraries/AP_WindVane/AP_WindVane_Airspeed.h +++ b/libraries/AP_WindVane/AP_WindVane_Airspeed.h @@ -14,6 +14,10 @@ */ #pragma once +#include "AP_WindVane_config.h" + +#if AP_WINDVANE_AIRSPEED_ENABLED + #include "AP_WindVane_Backend.h" #include @@ -27,3 +31,5 @@ class AP_WindVane_Airspeed : public AP_WindVane_Backend // update state void update_speed() override; }; + +#endif // AP_WINDVANE_AIRSPEED_ENABLED diff --git a/libraries/AP_WindVane/AP_WindVane_Analog.cpp b/libraries/AP_WindVane/AP_WindVane_Analog.cpp index cee49bdd1ef3c6..404fa4ea94d8f7 100644 --- a/libraries/AP_WindVane/AP_WindVane_Analog.cpp +++ b/libraries/AP_WindVane/AP_WindVane_Analog.cpp @@ -13,6 +13,10 @@ along with this program. If not, see . */ +#include "AP_WindVane_config.h" + +#if AP_WINDVANE_ANALOG_ENABLED + #include "AP_WindVane_Analog.h" #include @@ -82,3 +86,5 @@ void AP_WindVane_Analog::calibrate() _cal_start_ms = 0; } } + +#endif // AP_WINDVANE_ANALOG_ENABLED diff --git a/libraries/AP_WindVane/AP_WindVane_Analog.h b/libraries/AP_WindVane/AP_WindVane_Analog.h index 017266b0be9a66..658761c5381f76 100644 --- a/libraries/AP_WindVane/AP_WindVane_Analog.h +++ b/libraries/AP_WindVane/AP_WindVane_Analog.h @@ -14,6 +14,10 @@ */ #pragma once +#include "AP_WindVane_config.h" + +#if AP_WINDVANE_ANALOG_ENABLED + #include "AP_WindVane_Backend.h" class AP_WindVane_Analog : public AP_WindVane_Backend @@ -35,3 +39,5 @@ class AP_WindVane_Analog : public AP_WindVane_Backend float _cal_volt_min; float _cal_volt_max; }; + +#endif // AP_WINDVANE_ANALOG_ENABLED diff --git a/libraries/AP_WindVane/AP_WindVane_Backend.cpp b/libraries/AP_WindVane/AP_WindVane_Backend.cpp index 39f9ac9ed79174..7f9ea4026769e7 100644 --- a/libraries/AP_WindVane/AP_WindVane_Backend.cpp +++ b/libraries/AP_WindVane/AP_WindVane_Backend.cpp @@ -13,6 +13,10 @@ along with this program. If not, see . */ +#include "AP_WindVane_config.h" + +#if AP_WINDVANE_ENABLED + #include "AP_WindVane.h" #include "AP_WindVane_Backend.h" @@ -31,3 +35,5 @@ void AP_WindVane_Backend::calibrate() _frontend._calibration.set_and_save(0); return; } + +#endif // AP_WINDVANE_ENABLED diff --git a/libraries/AP_WindVane/AP_WindVane_Backend.h b/libraries/AP_WindVane/AP_WindVane_Backend.h index e347de49723509..54b9b227e26bd7 100644 --- a/libraries/AP_WindVane/AP_WindVane_Backend.h +++ b/libraries/AP_WindVane/AP_WindVane_Backend.h @@ -14,6 +14,10 @@ */ #pragma once +#include "AP_WindVane_config.h" + +#if AP_WINDVANE_ENABLED + #include "AP_WindVane.h" class AP_WindVane_Backend @@ -39,3 +43,5 @@ class AP_WindVane_Backend AP_WindVane &_frontend; }; + +#endif // AP_WINDVANE_ENABLED diff --git a/libraries/AP_WindVane/AP_WindVane_Home.cpp b/libraries/AP_WindVane/AP_WindVane_Home.cpp index 042d4ca0c1889f..c291fb75dc8455 100644 --- a/libraries/AP_WindVane/AP_WindVane_Home.cpp +++ b/libraries/AP_WindVane/AP_WindVane_Home.cpp @@ -13,6 +13,10 @@ along with this program. If not, see . */ +#include "AP_WindVane_config.h" + +#if AP_WINDVANE_HOME_ENABLED + #include "AP_WindVane_Home.h" #include @@ -30,3 +34,5 @@ void AP_WindVane_Home::update_direction() _frontend._direction_apparent_raw = wrap_PI(direction_apparent_ef - AP::ahrs().yaw); } + +#endif // AP_WINDVANE_HOME_ENABLED diff --git a/libraries/AP_WindVane/AP_WindVane_Home.h b/libraries/AP_WindVane/AP_WindVane_Home.h index 8a60d807a364e5..32dfe1a9920fb5 100644 --- a/libraries/AP_WindVane/AP_WindVane_Home.h +++ b/libraries/AP_WindVane/AP_WindVane_Home.h @@ -14,6 +14,10 @@ */ #pragma once +#include "AP_WindVane_config.h" + +#if AP_WINDVANE_HOME_ENABLED + #include "AP_WindVane_Backend.h" #include @@ -26,3 +30,5 @@ class AP_WindVane_Home : public AP_WindVane_Backend // update state void update_direction() override; }; + +#endif // AP_WINDVANE_HOME_ENABLED diff --git a/libraries/AP_WindVane/AP_WindVane_ModernDevice.cpp b/libraries/AP_WindVane/AP_WindVane_ModernDevice.cpp index 9daacb6c86bdf3..c88fb13cff82b1 100644 --- a/libraries/AP_WindVane/AP_WindVane_ModernDevice.cpp +++ b/libraries/AP_WindVane/AP_WindVane_ModernDevice.cpp @@ -13,6 +13,10 @@ along with this program. If not, see . */ +#include "AP_WindVane_config.h" + +#if AP_WINDVANE_MODERNDEVICE_ENABLED + #include "AP_WindVane_ModernDevice.h" // read wind speed from Modern Device rev p wind sensor // https://moderndevice.com/news/calibrating-rev-p-wind-sensor-new-regression/ @@ -70,3 +74,5 @@ void AP_WindVane_ModernDevice::calibrate() _frontend._speed_sensor_voltage_offset.set_and_save(_current_analog_voltage); _frontend._calibration.set_and_save(0); } + +#endif // AP_WINDVANE_MODERNDEVICE_ENABLED diff --git a/libraries/AP_WindVane/AP_WindVane_ModernDevice.h b/libraries/AP_WindVane/AP_WindVane_ModernDevice.h index 1d32708881666f..e94690fe3a5850 100644 --- a/libraries/AP_WindVane/AP_WindVane_ModernDevice.h +++ b/libraries/AP_WindVane/AP_WindVane_ModernDevice.h @@ -14,6 +14,10 @@ */ #pragma once +#include "AP_WindVane_config.h" + +#if AP_WINDVANE_MODERNDEVICE_ENABLED + #include "AP_WindVane_Backend.h" class AP_WindVane_ModernDevice : public AP_WindVane_Backend @@ -33,3 +37,5 @@ class AP_WindVane_ModernDevice : public AP_WindVane_Backend AP_HAL::AnalogSource *_speed_analog_source; AP_HAL::AnalogSource *_temp_analog_source; }; + +#endif // AP_WINDVANE_MODERNDEVICE_ENABLED diff --git a/libraries/AP_WindVane/AP_WindVane_NMEA.cpp b/libraries/AP_WindVane/AP_WindVane_NMEA.cpp index 7501571afb69a7..ef6f693740cde4 100644 --- a/libraries/AP_WindVane/AP_WindVane_NMEA.cpp +++ b/libraries/AP_WindVane/AP_WindVane_NMEA.cpp @@ -13,6 +13,10 @@ along with this program. If not, see . */ +#include "AP_WindVane_config.h" + +#if AP_WINDVANE_NMEA_ENABLED + #include #include "AP_WindVane_NMEA.h" #include @@ -197,3 +201,5 @@ bool AP_WindVane_NMEA::decode_latest_term() } return false; } + +#endif // AP_WINDVANE_NMEA_ENABLED diff --git a/libraries/AP_WindVane/AP_WindVane_NMEA.h b/libraries/AP_WindVane/AP_WindVane_NMEA.h index f23f35b8b3cf58..71c4e0a86e82c6 100644 --- a/libraries/AP_WindVane/AP_WindVane_NMEA.h +++ b/libraries/AP_WindVane/AP_WindVane_NMEA.h @@ -14,6 +14,10 @@ */ #pragma once +#include "AP_WindVane_config.h" + +#if AP_WINDVANE_NMEA_ENABLED + #include "AP_WindVane_Backend.h" class AP_WindVane_NMEA : public AP_WindVane_Backend @@ -54,3 +58,5 @@ class AP_WindVane_NMEA : public AP_WindVane_Backend bool _sentence_valid; // is current sentence valid so far bool _sentence_done; // true if this sentence has already been decoded }; + +#endif // AP_WINDVANE_NMEA_ENABLED diff --git a/libraries/AP_WindVane/AP_WindVane_RPM.cpp b/libraries/AP_WindVane/AP_WindVane_RPM.cpp index 069f30b657e973..b80b366c5fb94a 100644 --- a/libraries/AP_WindVane/AP_WindVane_RPM.cpp +++ b/libraries/AP_WindVane/AP_WindVane_RPM.cpp @@ -15,11 +15,14 @@ #include "AP_WindVane_RPM.h" +#include "AP_WindVane_config.h" + +#if AP_WINDVANE_RPM_ENABLED + #include void AP_WindVane_RPM::update_speed() { -#if AP_RPM_ENABLED const AP_RPM* rpm = AP_RPM::get_singleton(); if (rpm != nullptr) { float temp_speed; @@ -28,5 +31,6 @@ void AP_WindVane_RPM::update_speed() _frontend._speed_apparent_raw = temp_speed; } } -#endif // AP_RPM_ENABLED } + +#endif // AP_WINDVANE_RPM_ENABLED diff --git a/libraries/AP_WindVane/AP_WindVane_RPM.h b/libraries/AP_WindVane/AP_WindVane_RPM.h index 3d2c9e2dfe80c1..b68f7e8b3bf0bb 100644 --- a/libraries/AP_WindVane/AP_WindVane_RPM.h +++ b/libraries/AP_WindVane/AP_WindVane_RPM.h @@ -14,6 +14,10 @@ */ #pragma once +#include "AP_WindVane_config.h" + +#if AP_WINDVANE_RPM_ENABLED + #include "AP_WindVane_Backend.h" class AP_WindVane_RPM : public AP_WindVane_Backend @@ -25,3 +29,5 @@ class AP_WindVane_RPM : public AP_WindVane_Backend // update state void update_speed() override; }; + +#endif // AP_WINDVANE_RPM_ENABLED diff --git a/libraries/AP_WindVane/AP_WindVane_SITL.cpp b/libraries/AP_WindVane/AP_WindVane_SITL.cpp index 8460bbf5cddd59..061e42158eee41 100644 --- a/libraries/AP_WindVane/AP_WindVane_SITL.cpp +++ b/libraries/AP_WindVane/AP_WindVane_SITL.cpp @@ -13,9 +13,11 @@ along with this program. If not, see . */ -#include "AP_WindVane_SITL.h" +#include "AP_WindVane_config.h" + +#if AP_WINDVANE_SIM_ENABLED -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#include "AP_WindVane_SITL.h" #include #include @@ -71,4 +73,4 @@ void AP_WindVane_SITL::update_speed() _frontend._speed_apparent_raw = AP::sitl()->get_apparent_wind_spd(); } } -#endif +#endif // AP_WINDVANE_SIM_ENABLED diff --git a/libraries/AP_WindVane/AP_WindVane_SITL.h b/libraries/AP_WindVane/AP_WindVane_SITL.h index c9d3bd68ae4733..f84d0a815d4e9c 100644 --- a/libraries/AP_WindVane/AP_WindVane_SITL.h +++ b/libraries/AP_WindVane/AP_WindVane_SITL.h @@ -14,6 +14,10 @@ */ #pragma once +#include "AP_WindVane_config.h" + +#if AP_WINDVANE_SIM_ENABLED + #include "AP_WindVane_Backend.h" class AP_WindVane_SITL : public AP_WindVane_Backend @@ -29,3 +33,5 @@ class AP_WindVane_SITL : public AP_WindVane_Backend void update_speed() override; #endif }; + +#endif // AP_WINDVANE_SIM_ENABLED diff --git a/libraries/AP_WindVane/AP_WindVane_config.h b/libraries/AP_WindVane/AP_WindVane_config.h new file mode 100644 index 00000000000000..2c1e0f46c83826 --- /dev/null +++ b/libraries/AP_WindVane/AP_WindVane_config.h @@ -0,0 +1,42 @@ +#pragma once + +#include + +#include +#include + +#ifndef AP_WINDVANE_ENABLED +#define AP_WINDVANE_ENABLED 1 +#endif + +#ifndef AP_WINDVANE_BACKEND_DEFAULT_ENABLED +#define AP_WINDVANE_BACKEND_DEFAULT_ENABLED AP_WINDVANE_ENABLED +#endif + +#ifndef AP_WINDVANE_AIRSPEED_ENABLED +#define AP_WINDVANE_AIRSPEED_ENABLED AP_WINDVANE_BACKEND_DEFAULT_ENABLED && AP_AIRSPEED_ENABLED +#endif + +#ifndef AP_WINDVANE_ANALOG_ENABLED +#define AP_WINDVANE_ANALOG_ENABLED AP_WINDVANE_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_WINDVANE_HOME_ENABLED +#define AP_WINDVANE_HOME_ENABLED AP_WINDVANE_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_WINDVANE_MODERNDEVICE_ENABLED +#define AP_WINDVANE_MODERNDEVICE_ENABLED AP_WINDVANE_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_WINDVANE_NMEA_ENABLED +#define AP_WINDVANE_NMEA_ENABLED AP_WINDVANE_BACKEND_DEFAULT_ENABLED +#endif + +#ifndef AP_WINDVANE_RPM_ENABLED +#define AP_WINDVANE_RPM_ENABLED AP_WINDVANE_BACKEND_DEFAULT_ENABLED && AP_RPM_ENABLED +#endif + +#ifndef AP_WINDVANE_SIM_ENABLED +#define AP_WINDVANE_SIM_ENABLED AP_WINDVANE_BACKEND_DEFAULT_ENABLED && AP_SIM_ENABLED +#endif From f8d7be5e43686e5a20a1a59420c308ac1fab4c70 Mon Sep 17 00:00:00 2001 From: Bob Long Date: Wed, 12 Apr 2023 02:09:16 -0400 Subject: [PATCH 0043/1335] Plane: fix bug in RTL_AUTOLAND with rally points After loading the rally point, ModeRTL:navigate checks if rally altitude has been reached before altitude_error_cm gets updated --- ArduPlane/commands_logic.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduPlane/commands_logic.cpp b/ArduPlane/commands_logic.cpp index 823f1e4da93bb5..439c03d80a05e3 100644 --- a/ArduPlane/commands_logic.cpp +++ b/ArduPlane/commands_logic.cpp @@ -348,6 +348,7 @@ void Plane::do_RTL(int32_t rtl_altitude_AMSL_cm) next_WP_loc = calc_best_rally_or_home_location(current_loc, rtl_altitude_AMSL_cm); setup_terrain_target_alt(next_WP_loc); set_target_altitude_location(next_WP_loc); + plane.altitude_error_cm = calc_altitude_error_cm(); if (aparm.loiter_radius < 0) { loiter.direction = -1; From e6feebb2fb19f303a928e4a2f37493042838850c Mon Sep 17 00:00:00 2001 From: "tomas.vrsansky" Date: Fri, 8 Dec 2023 12:10:06 +0100 Subject: [PATCH 0044/1335] AP_HAL_ChibiOS: add hwdef files for Airvolute DCS2 onboard FMU added ethernet config to hwdef updated readme.md hwdef: MAC parameters redefined according to ChibiOS hwdef: add default params for Airvolute DCS2 on board FMU update according to new changes in ChibiOS MAC driver added defines to support ethernet communication bootloaders: Airvolute-DCS2 --- .../Airvolute-DCS2/DC2.Pilot peripherals.png | Bin 0 -> 243478 bytes .../Airvolute-DCS2/DCS2.Pilot_BottomSide.png | Bin 0 -> 572645 bytes .../Airvolute-DCS2/DCS2.Pilot_TopSide.png | Bin 0 -> 611365 bytes .../hwdef/Airvolute-DCS2/README.md | 256 ++++++++++++++++++ .../hwdef/Airvolute-DCS2/defaults.parm | 4 + .../hwdef/Airvolute-DCS2/hwdef-bl.dat | 58 ++++ .../hwdef/Airvolute-DCS2/hwdef.dat | 174 ++++++++++++ 7 files changed, 492 insertions(+) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/Airvolute-DCS2/DC2.Pilot peripherals.png create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/Airvolute-DCS2/DCS2.Pilot_BottomSide.png create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/Airvolute-DCS2/DCS2.Pilot_TopSide.png create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/Airvolute-DCS2/README.md create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/Airvolute-DCS2/defaults.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/Airvolute-DCS2/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/Airvolute-DCS2/hwdef.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Airvolute-DCS2/DC2.Pilot peripherals.png b/libraries/AP_HAL_ChibiOS/hwdef/Airvolute-DCS2/DC2.Pilot peripherals.png new file mode 100644 index 0000000000000000000000000000000000000000..e12b3c6c1edc7dbe878cf962724a9855d4560a61 GIT binary patch literal 243478 zcmeFZcT^MK_cn@XM1u$_h=>#m2%!lAQY3(=7?4gtI*OD8=}k(gA_`KZ388lgB}nfG z3MdeIKswSPKxm;Ply~^}`F?+Q-F4Uf|Gw{?wFsPHCNp!+*=O(lJkOqw>Z*!#;Ok&2 zDk?hIv&WiLR5Tt`RA=nYodxzBiO(4VzfL)6Dn6nr>bkK6G|pJctH@JPeGR8QcnJd9 z=k1^AIZ;tv2!|Fnc9g+>3LcL)pL7yI|1zo-1O!w6OD>HC6;>R1%^SYG?B z@ya+&9e(z(ZG*-kBz>Bi=Az*f4TABxVAjfMo#hH2rb`8bAZ_cybh!2S;K%7!4N%sH z7nf+5o(xn}UAlW~4VOZ6N(o9xNSK}NOh}}-PwE=qz55F%B`Nu9tApr1(wY4Ip9lH- z;b_Lbd(vdc*Z=2lDyoS4XFN{*x5;UFZkzhQEx9g+#gnf4yZI*G?4kWngNjO0 zA(i=mT8{7Kg#M>Bd%@56e_B6T{y%!bev6$OMI25Kj}Nxy*J_F4Gp(WbOD%9B*v6w8 z)_&8%@<9>4!m`Mv-i)9neEyf=w=<#RaqasnrQMxIZsX?3Z>P_1bx9NBc(tE&B+!2LHZ2g~(%5{VPT09&ldRvZ^A+&TVcSfueaN?t#XYT=L zBUuj$uHp;`V|iM4OMh`E#Dxgf{Cr4RDaHBMrN0c9*@=^!`E-A!Okb_ggsX0&mDSZ# z+Ii75O!nw4>k8iET|iwrsYjxaaEj)J=~W|V4N4)@MxRlbr zhWyS;&GAo(x$xSC>GroN- zdC7OFSYyh5)TXlBZ{`(3hEcTej7hK$;y&raISiLb47k!bl6pkx7>Q@s34s8=u&bVnJ>zM{^DS@Y zvHYQZg_U)hS%w>NBJVV&Je6peH)(Xp(e#f6%2{u8tqafZRE$=<*u^LGkE5yNO8APZ zn#*iPD_UywN-e6zPDQxbSakm(^F57EifLC@>B~_|i4?J7Du9SvmtR{QDZg*l`bn78 zuI?-AWfizg{_+g6*W)=_^jAT}2-5ah*-V&pm!T6*Y|Uu@Jw1nU%#=o9SiV`9B)5al zox--foMfb6-TI^5B3|=m$g}I_{VET{u5drMCzd>E!c86@?N(q2#hI&x4@T%c7*f?E zYQZ@JFECOD!;5p8VqN4<8nThz3j^NE7o}IGCd?K4q$;zWRE+PSjBhK3eLAeSwuu}W zP$3I)ADRgGSOR^zj2o>C7oVX&%5Wd6vuhBStxm&N`s@98^Ey_fR*lVKq;T*T9mx0X z7ZdO5r6Fv}FmbBEqG6xeULl_-i&YiBlEP+Z?P%z=(K4=1r58((!!oj_J}b2aN3c8h z$XleKb`Y9WIp0F-{Zt@4KeKsg@am#~izne@!`=2- zm8f5a`P6Sg$@oEAu9A>`D5L)YXHN+7c2B~^lcm-7&4%B^sd>GvwEaQ4!Uh3c$$X`S z4Y15=Zuw1ka!|hLIe*=;wIYrCEZEFr8V};-gd%Q>VQchG2{5U*xM=05mV->dQ;;6L z4<*Bl?_dgkBai$Zfu1sDYCpBCT32b(0mT5bz?L>CDtG;U-tub@BGSKZs)6DKH? z$WmbXsl=Y?8vlS!F2(|1GHrE?Xl(1XOuaBZwUA*BxyPvJm!o8HE=Qx&A*O6?qJ`Py z&9P9hKi!{wN|@Z^Lyf@|G69=Xy^Im6n)3g_i52O086#8;SocXPZ~ggQC`3k`OG)wi z(!wd^o1NZJ+i)5fSLDlsy$$gm=Pt>GI0br{GFZ;bArqf^_ob{aV*|O05TR+Or-Ms- zpQIF-GBg*YakrO`{g54oto7hm7zX`Qsvs$**Zhoe(tA?@MkXaus#3p5PqZR*JCvh7 zVp5-_apsHI&fF=_%S$yM;Wr0)l~2H;4_OyJE3!MFa7#`-mJ9{&hiT&BVlI6Po8L~; zS2esj$F2*WW%l^M$$Kt*u&EMO5OfprSHI`=*qkC=~^$rpNc8MHQyxyA@O1#fZCguA~4zvVW6 zig0%rZq>L;hxOcDD-vQe&*P4la7ZUuD^c$7`nt@;=+-pMJ2xvKSw#^hm7<`{6mK%3 z|ErnegFDxoCI(?CwO!IiHO{|Q916CK3`rXvRJYd>?a50yZP3&-CwX3*h~&oxQ^W-|?_m%8 z272JRoY;QQEh(2}Q8(G##;b%(^B`F#7Z0opW*|VyTaxS*(6Q0>rIpE}r{Km>;_R3F z!vt4KneoxvP%=tA=MTCuJAdBw&iNwC^%t8-lS3o6Y`QUI=oh6)heGAIDdd@(Yo{7x z(@DMV>M5mz!c|=j{oX?osEaXDK})55BHvT;Vlzm2bKZS5XJmy)Ifn&hvIml!%X`{6 z4pQ8hY9n%&HA~it8p={MG@I@SI}Z=p5~HH}NduC3e}N@3E>81jMmSWdxbh;;I=st) z>a~$Tm)jpxA-($Cnqj#8a$XK3{ra#?%~G~4X4+-tx3FXK@<_S$LUwTWhQ@JDky;AW z7SmS%tYsDb6^K!M=yfsVj#IbHLblbKTO-A2wq|b)lV9YhrPB?p$qdzRTt?oDrXLNt z#po=}D5Yo&)Oj&i(nk*7Ml^B>V1JWRq+BpEwozdO`y52M_kD{_d#8`gq+^7%zznbk zJ2*kY1_cla!H33H-Zmp;9}~aStT*sDKerkWlbnzH>Cli5ViVHn&~ZE3U#QJXr{jP= z+&mtLaq=!I%Ou9ydmpB^ zQUsUcKB6bw5PO7oxyM2SOr8&EmYh_ibV0RK-bzx*)0z7zk0_kB(xgK^(%uDI-N-7^ zkiF3AzWAEk-6g{-E6yBI&Xd$sax(7Lzh_E=;@L~T+^2nVB&d@=+Q)DGg)%p=JC1(c zA-RxvpAw;P5iv-2L&AQ?EL=vM(jnC7tksn)gXqf~{$k{+H@m&8R8OxU{+NxH+^OM7 zPF^~2AetSc4}ZV=B}ND%`k;;0I^*vHUzZTpy)NvzGi+J=6^Af<>*0czm;@a^KqUD( z&fUrwQf~h?5OvLAn8yQbJTr4*$VFIDWSh?TyYpAxNXIQlUt(45rPl|1rjbe6Ot|a> zwAuuBApwYfyLC1^fEhO;F7sgAS!?vydsbU3lg~2kbuWAlNj8IsJ_ojJgiy`mtH@)@1ZZMnijSxP}HmYCKLlJY3fW zg)^^iC*3pWu>oSD`4MZZi^BB2*|BaT8QweWdqmOcZ0Oz8F0U`ifqX{gJ}=K`eifx6{PrX8CgY!K2p=q=_cAbm(IteimB${zfox8+fHuLf`LEaN*! zPeSs8CGvt_^)gotf^9+;AE!OCVH(iRkdiRrs-W&4GIRz9;4JERV@MKSImvji0wmC&-&Yf9mGon{md>NJ*^Z?1b zv?ZiH=aFWUt5Y5olW8UwxCn_8e4j0py>2x5*|EV6l8Al$^0K6;z_?dj6VNN z*7=J$X{hY(YW)R&(WXk#ZG(z&*U^~6L&#%7g7}N8v)vEMv%6I&Sp!=-J$62n(E+$5 zp-O1Z3GY3E%rERL&?_B_Xzw9CN+XuA+g>=fV0RmHV3LG(93GS((XhWYg)JD2-;ds8 z)mz!WOhq*iPQ&5VLlWx?=mV?Y=`GhDIPA{HHXuj8^1lYcmHEvMp~{akLF^ujW2&nb zz%Y{X=F>3h0mu1Wx;Yp^!lm0!fA53Z2=)FlFpSvbJpsibyCzgBMV^k&)i@oMjbb)_ zfRjZeH?4+($@#y2OdU+Ok7Qm>$=`8V_rW9B%86ojtGDU;MYf?2)l_n9=!gcB2%~ME ztQE7_g!V7ZNQVaHfSIdvKjEpB>b|e~GGRs7JcpUq>V|nK*OeFAIwo0G24yRv+UglO z+qKS1uSWYd)67QvE0KNSPKmbTHPsC(kZr1OkoVNa@dlF5P@$y+dc^YmoZ>8!hMc$ zhcBZ@U0fGEQ*8)tj=nrg+O8K^_!FrqYo{T%?oTUdPn?EBsPf#cjI;XatkVu}*oGMR z#RD#Fq@FJ&7E1_IQoiEF_kK{TsTkSoo|;G!Sf~<+VZX2sboO}dCW$yXNowKSB|oO* z^-&-ytE?!>jthzog7QKpC`l6Qf#|^XFbdoqxmatkd^E7HN$*2VsVa#)->*)9aftHoLP?Y9k^n zF*31^92oONugzcc6P`qy*!rAZWRT95kn2PY8r#Zel|hA}e$s?mKir)heTn|E6BQf( z-akXXV#nz1xajfJ!+eb$t<`Q40oz!yia}0{D5je))+493%52D=$_oFW2q(jeALIDR zowa;Z?HUKEWEPv4Y zW9M@w$XziBV_TQs_-vApHrLBo3|8llndZ~a^h%iP%1jq9T8)@l)pXxSSA7__&6pJR zY7loomQnNAH_mLV&~Kxc>HW(xb7_+c&Yy)IE@WY3UB=Xsr10L%{`i7-yqupI?+xwW z0vRTcg0`55O^glJD%h9kgMm?QEj2L|CJgpsu~MsB znPz%JNid4;5JR9yGHLidRt?LLq91BetQM&#q3N4k z$+@0io^NTlnsRlVw%(|oaA;%u8Xx6x&!|jgq~cMEM#LmXOndudS3KG4i;iSl;Tp%O zUq-19V1{xJmhyIXR!3_aMzl!wu)r^fTy-@)O8_3qErh1($k%2r&oZ9jtz2$LYW^t{ zS&0ZNZwc=$AX@00u8TSMgFDHMTQzZ!T%wj@wzt&>iVc%T z-Hik{Q%HmbGFq#Lf9)WZI6C_)>h_ns=3R;Fx*s_$qcsD5X7yF@NH9L^CU|A6v}K}F zQJ8t^_OyL#$tKRvv4tdsjPR#xVpgKl!= zN$*7y~#^ICWDkrw0?jZNe0uhL%F1ZBQ@{^j9gmZHYMIUiNVD%Q|4H^gYLoD z6mU}!nuMzj=keb7uZGLSM`@izK5Si|cf}vV6@mLpUK%#!1OGO37^#Z0x{E?CJnus+ z6C#akiYwkYG>%qkizxcjoMMn>eip$&c(HSgwHZ8!ELv5BrFEN0XCCTl*Q#x&&o;)kNV8EPq|AG|w%bOjnUKPr@y4QKp+ zHpz_x?tSd_Bt`{pZnRwUyD|#nxNUE$cI>1JLhe1Pz;Al#esT;OttB>$)+<=+>iSJ+ zg1HA$U6nOkpL415Kt2u7M`GM`A`0|RfqD<3L}D=TDx-@=>sCqSYe~{>f^Q3M08mB| zc5bPeZ|#+8pl?ka_-g8Vgkdo_>K@Y@Zd9^>Jm|AS(+ghbjjYv=qn40?i_Fdouw?45 z_}NnA%wm-q#@KklH<$Hhl62HOW&JyS!bLWzDmRt9b(x~|v6PICGB`?z3*`O z6u{ShQ|Vod(KY_s)(j+$UrBu02*TX>c2xL!B|7f~RKQW*} zi()dGw9OI&$xD4ih$!oP)L4s8ciB9py~=?yaS6>M(b4dJZ^mDvc~aiXC1t{G?rqHm zP7)GT5kpYE$5$QIUd|+bl+8gVIXCor_wN>~tK1stCO16cU06b*d}fM>k+Dllo|h|+ zY2iXC<%CB-FeanX)KO$qThq`UT%$-&BdTrid_XK>u=F)QnYL$ecNeRb&~?)drK9rHe^Wgk>_aeJFsVGUf@2!D}w zbCghP>aSQRJ5&sWZzByz<3Iceb25Y=vd6i0)!@y`vvk)*E5XLAtTvOE6mR^=ma7N* z>}KjO)RsxuYVf)+E#hu7l|VAGBh|ul+kd(Y>g6ob#)vXH^J~|eYo-~O=gJu|vp9@% zC%k!;Up-iJ*L?AVYC8DZ;&F)_=o2LFQ>6B}YncG}BLu@EDx!g9w~r*2gA|FpV=lIF z`US_f9PAz|UobT*Y+*1r;S$Jfrt1A=8^IK7*sy!x z9gtzUoibfJQ@i2dM(Sj$gabY7PLfdH!>Z_k_jw{q(_NE+JZ5T*IZZQ$3!Ax44cWb4 zQ$Hct?zW32K~XiULXYWX@sBiZ&LI1Q+ZSJI->r!g`M3K$zv z)L3xzQN=g(yXjI?;ORM%t(acMPDD=9JUN|7-$EjeO?$EO0u@!+MGg6IWN*2d#BD9W zSihe+eI0C{?A!-C0SCVl1Gev(r-{g@`7yw;%U8TaeYjk#-u?!Rl|Tmbxi!#3_fiSg zj1x5IO8Uh!dE;H{mf1nQ-x+7|4^hRxv1SAHueIS7ExDwH<#s|BN*TlQEo%vMyR}SJJ;`EN#8ELBV>neo`!QrkNPwK0kG9C~d`>KN zh(p=h_xE&8#7$+jco6NNfu`om(j7NVb>8RlkyX^X=C<1RY3mpvFI3tiK1x?aiF^`m ze59xH6Us(GaPaif$tC6@qg%t+2xPQ!|4vmGn?qA;RYC8gvU&uyEB-3;jq_XbZ4z0p zv-nI+Y)x+o_UsL4sR7|--h{wzwa{)fBhq&_SY*;%) zCUFj$pgFHB10avYXK5~KNbjdZ(t%y^FnWMf@g2Mg`KB(QA@+XJ`_3BL zyjy1X&DDo+9RdK`j@Q1HUM-6vShrjH#9|Wnm&w967~$&TNRHearnRdTPQ>eh31>e- zhCbAWj{_LNoAnnR+rz$hli#MZ8ld%kilF_%!8>|!Bh)&SmYKG2H-#SklQsE5n1MFf zZ{mW6{E;-VPV1{LHu=30*pV?qJwmsrcCDs_cG^H+Q_M}^W?r!#T%1wMH?NzUxAyB; z&K~CGlE2n)oJPDOj3pkpg#>~^GLu%J64toh5U?W9mQdqC3Bg*>rqy6~Z5%MHEbSn@ zLe6Jj53Y0|wikQ9lf-nD)=Ld4ZHt8Tgb6$V2nY{N*|}k`G<9U`xjILND1gA=6-a81 zDF(wKJLP-&a`%^*Y?NLuMi1o0l&ICCtCtK;Eq^@qpa}B{M)nSBVUjCjWFtz^EHzR`8$9icXK6l_fGbe|uvME|sC*mR1x5x5op#)Tm)_QK+&cmN}BUAG+kF z8+ySE7zxd#*R%l|Tl zmF9_ge`^eGnXEDF+g?%lSlm?Es|dW^+Upurn)+mD!{gh2j{<#pxoaNAYW((Ty>AX7 zN(d6*0!wW$Pe5tlJq$*ooHzRs#?jjuZl#}F)A30Ao*~cA{43$$(5>h2u^9a5w99^{dm@BN_Q&lx;%+E~Y-{c8>yZXPL_m9fyLPtik8YGI4cVkr-SqqY z=i{`sGPIbNt6E^CHPdC*&?seLLxS6JggwxQ7K zx5;q;1~h=VL_y4Dv=W%d||#Mp!2pjF`a)!Eahu zeKTQ>cL*FJCw2&I#F%_6hMqiIwL)Ps<^o&aeC__Wez=P>?xKbpLO z)2CZ{ynBx{?8hu^b#LE`7wyi()O?3*FsQtcWGN(1@Koi~+}Tc*H}2AtZ-Jgr-ugLJ zlrVtU9U+w$UJNQ1CHb=XT_i2uK(ij?GkwG1$0cA!QizR{B(Wa1JF2{^^cEUu+R;amB4kL? z$B&zH8wcS4;N0TMp~t^t4FaJVyCME{cmgmae7bp4PKM&tn}UJ}js z(SuI@lUdSkb2HWbkf~4BM#Y1h+HvPJ%59Nbs>4^xdF-{*8cWnrJr4wDgckvB+!eLN z2;PJ!ldBh!JDx}AHW|RjHFLGpb(6q9%IVLizD@~isY?C!Puh0$!Cj0WRz~@=oQ8qtES#_mB#9 z6i0Rnw?}iWpUITvn5890UtYw!)S=a2%Jhbq3O2w@q!_8FIK$IRv_ovx=1wpeBi?cr zu8(MwG>qrgQ~4wVyLvH~-5}Y6rbEjzyT-#olDVz`R2QeV%8;+}3hq|h4W%#^=;+Je z$9yle1N!59n?U>Ld^x)`A$3DJw*WeEdsJ^b&YMNrwLpe?cwIf11koVF<)b-7^Alnx^JR+x?Rih}#);yf+j6pjt2#V%Z}C{#dg! zSpN>)E$=M(HmzHQ{z0-+m!vqYdWx206Gq9W2r$$!0Q9tpFl^fNJ57VOsTghzwNd&d zpKDSsF$o8^2?WRF%V8TNVACTiT7N7e?Mc`cb$OktP(@TV6A#=kp@xUd!BnzLqXQ~L z(mp>my4Z8HC&o{_+{-P%xz3Q$9gf@!U)$J$xC98T zC@a>Qa3->F0dt_Bx5?W-pdn@z=G(AMhD8;run>4>HUA4~xx6ImGw$#_DqZC=J^kP^ zu_uhn1Fe=~OKByU6`J_xe!%KdJlY3eKD*?VaX|@`j4EZ!di`|yW$mMdidT2c1FlkJ z-tLaO8JW1``EoCjRfd|uo0M<1TwNsCP*R|Gh(Bb1I0mxhiJ{>tn{-ZG_K;RlkpgHk z_pkf&2??O9FTT}VJI{nZsA+ip2mO-qo`#b^6IFUqPP&LVZOj&wG@w<4)kq7PEahJ| z-ix+N!O1S zKqA5@-jwA84v)o~lg7EtwSV>6|nZK;a<1+k|BWSSfNJ{7lO80xP zP5LdEW@=>|jf!*EGjOx6W*;eGCyn|LHe`3-vdbB@#AW1m^$G)aK;h2Zxd)(2&cyoN zs~6Vh=ez)26GOK3>O{R~ty`!uiUc>1L0krHGv2$PwJw}!a~(dKUZgS8Zl?I@S}(t} z_9+Aixd{-YH?#psNcU>RQ;m6>w3X4^f{7E#ry*NgI%BQee_Jm`%f>MlsvDD^U$71E zx|KM7K1t{z;!&pX6}{7_Y(n*}ymojD?3r^znLzikk$BPmAE z_V-qE7Pxd5N75K0F;P*;vFCd9BZ|;1BOh?Y{5YX~=sVhC?|_Y}5CV zM<-YriX*d|i;iQeug-s0Qjcs1&xSfLs@Eog$9O*!mAtX>yl1UQY3wFqtQcjVM9 zBkkJCn1}xz3!-i9>Pb?ELBsI_T;@pL4+W`jG=1+p3v46{(|K=vpT^j%0kSTFwQ3Ut z6(5pC($KL_%#_2*es0k?rCWuh9(XUJF%xFM<{2o`9-uAoa%>|hNc;`y@Kf!&GRE<% zI)2ri(Zy_vmyefMA}hpS0=9*_4o``1JxTe==uv>KGc?Jl+7bMrdnNfX#h9KcPs$rV zmWsZ-%^B)#w#gv+Jbf}p6h~_%9aS;|%re=bFLVZPz6Jt00Izaizg-2|xW}?+D;nxV zr(BAKq>X**1!QJb4a5p8bJ}SOUW*ydoARf=0hxIS1jRNvLHEAv z#V4=jWw4*qc30IF`Q-24v~MkwUW8?g%flbaiSgdM4j(V^e+aM_zG}a*-lTjBicZQf zpnqEdAdZEMZ^iRD`%gjcfFTIMfGXm9MRIAmSqQUP@ zF!~=kyCelSK&?>groy`(9c@%_SH6!i477A6`c9tdA%Iqe)4kyP`4*6{-6;~n5C9hS zMB~xMt#T?O8wP%H!+rKM5XJ@9@AbPCvX}Nm`A?7q+dvI2H?Qm(h1W`SL)a*R;02~n zFb^v3<(s~lJEbOAhzUDv=D z;NN_B_B;zrlPh#ns>3d!=4)bskrZ4#{W>dHn)z88#DNs;GG+-!NF9~SZlijjU~k!e zXq84jvXNB#Il3h;$DNkf`6#a}6Q#v-u3$@lWXeT7ZSqzUEtu_Ciaq-4cx3F0SLXpN zy~hrxXPGod23*jl@{miwS-Rj(XJuvi@XQr)5EDJXY3vHhfL?1SYtWaas6qERcSLRYsHQh)P(Ez*-u zeb@YZE)@(E5D0F6Psch>j?C*RQg=-OBg&sM?F7-*ZySFHv^t0W@G{<>%gm;IT32B< zFERGd{bm=EJ-g^&*@w}LKa?RabS+c>NZ2V0$XLXC4BjxeS*|~JImi{yp*b5ZaP>)B zu=j;Xf3@phqFpkGPteHo8J}1mbdm5+zqSQY|CTB$QCf&zcjNrc1#53^0MwJK)$Pox z1UN-7&tvBieaP$3Fccoc!2GV?p%Do1s@!l(H*S!ABy^3!8n2KWa6o)jZ>`j!O(mr| zvE#saXnaS8K|PnnH&}=u@Z9G9Czi;alQ<$g5uHqK2VM z>x*O`=oQW&!O~Z&Rx3uwYUd$IyhYuDVbHBiqI}wxn%EtgCyCn;N@>>b9<}cql2YaS zNY;gn5JqL>#FI98UU^3#TjtkXSJ-8!i51{x$m>)ee~@+FgNG+qpCzM2KZ7SOozPxI zb7AY5`K89=L!wOtH=X$=gojC2oCjIK4=H^R9GgGaW`1gUBE3h3CLaGvQHkKo3ZUGk6*4*^Tz7o)s{(f_f>4>piv{#F^B{L_V z!5fgcIug?n@!)8ltvgl59@syDgRoO)4o$gPL|%U&gk(26;}k*9z#c)R=e2V)sY_Io zq?q{cD7QcCJzqF7{FEo0S`F3~6~@HW2Z>sOGoR7vm^@JE@D)NY0-kY!r`sifu{s z7E2NX)f$r@Go8x2P!5qhg|XF}?R=x=ds`*3g)YzZEsS@8F`O@`-x*Osv#c*9WTslh z?#lNOGbbn39kQKl`*xNM;UP}yn!aj&NEwN%2L;YyJMra#or#kDq!=}da+}n0Q-Jmk?r3i27U-=s{n$?OFMPCz?{PT|mE z9RN(~^s;XO!b0UwtCm?OPukUdwYd2)AZc!v| zO!Y#0?N?1=&T|_%d3v1F+8St}wS*v#z}KwZ(b?*HHPmfr@rNA8!?}sP{Cp|-VNVJb z$2R!9jmmuB(8t9EB+SmfV4-H%sOSQy>{e<16ae4BXN#AO0O`fp<&YEY=dg8Qxz6mv zj#W_;oNOqY>+hS6>@h24P=}(LWz5gxJZ)x6K-3wUXq*(5BmrxSnb+fk5k8k4WjqZH zKHzXc44Slg4jjjh;P!>%4uM>uy1K1jRO6Uq2*GgxBxh@ld_t=Zo+t92hK7NX!`N;U@CZk@tyRarmsw>N|6Io9UK47tL2g_a)X&$YnFjgGaMD9)@S z@iSZ~+rW8^Up7PgE&vQ++lAvQv_ww^a0=W-LSq&qcl7#>u1h**CSdZAMs9c5`saEY z@Rls)ol4Fy0-IPpaoYJr3`KUVebkoet&o0%)ig>}O1xi(G``Y?>Ixie>?zmobH9Vz zxhv49Kgml)RWeohGQ6AJ!lTo;i=S~{`bD9wa%q9l+83=!H*0FDUqFH<;(1iH`_%{M z{ib;q?b5a@ixYI4?~J!q0c2V8ql=*#7_k67#uoMWvp|}YBz6Cufca^w1_!u!5O0)7 zQO!@K9xXPc+`}$_HYSoIXrv}+;WEjwVWFPH`XT5|?GM?!^AalU2YK%R6|NxuigL_| zuAVEvO~%$Ik&hpVF}w~HS?#-VTEjV6wV&OJYp3v}EAQxRp_%7a!XK^#D6+d}nuc;9 zmJmI!kgU8xu^ER3m`tK(T7^+a)|OjVHx84Rr61ovQc33T&{$ekN#9BDxa7uP2e9Zx zLTGP=_Teu5wG0U<@s9nYyQpw*c?=zZrnCmyhznPi4QE@7JJ<}mDxdY8zEMo5uoxo5hKXm=uY54ga zWCD;zUt#^JCFY1Pc*TrQn`sy`(*eaxi3jsuQ^O33@{g%1irpzc&ofe?57N`um!zj! zJZ8M}ixp0jX;$@{=*Pa+>nNodLJz*&8hR{fm`)`_&949X zZp}V0cqCvRPnL-jMQE7JL5ACG2La+lSU|$?fN{X!u;4g z2qh%VhE)uy{brPi5gFBmbL0$6-Z~85vAeoR!7j&zWZCrCX(j^baWm-@u)bSOx-j*V zc4^{mb2tq9ZO8lROFEK#K5lk!o+`Tt85#;GKTUHn7m;J(T{Z?{HtZ=p@7w7VU(Xby z9rGg3sMdA$jY|Ryelu1HE?_;O|8$@vN($a+XiKutZ0?$V*n5+_qgyi z^W8j5RVHRWGK>#bs&gXBJB-?K|4P6TpTWXs|?dCmsD3B2^76L_1FeFN@Y6356=L(-`-W zxeImC$Nj_*Z_D)T^R80tA^U>d0@AD1d^m@wR)EifJBw9G-OZ_g3e#6x4boiF=SC*~ z5j^lrbqPnS8jWoL^86O~_>Ebgw)CS$^&BD!olOIQ5faL9O@eP%?xGr_{wX3TVqj}T zVClD6_P7+!fnca?RSpT=jC2Juo&B4Zq){zXJG1!W6=&#Q4b@F{^|VskN*%YF;Dd zbC-~mvGZ7>Lo18zb8k?0(ujpkM$T4c7|i@4($nQ2*256ln0NNWN!Y|bgSNBRoBoos zfmZGRLK%&KlTp3IPhng(X6uzAZxff^b`sn)^wN(gjBYAZmGHK>u28AFmCh>EHL)8D zh(agzy&DV%GK<5dIRxu9K$vHbikb6ia~5DaU<;|;0k2u37HEwYw9$jQlh!^B=Tpo` z6UP%3+h4IWx+!0GbO9x+6MVf2U#(p+>Fr6mK36en>xBBXJ>WK0^1Ut9PF$|M^GEMP zB#e?i(CtnrtaL@Gph$S#d4LOXB%bJpsi+|Nq3QKS94u+nLQLmQ0D_9^hUKBz$Sr?u z`@wQ+-F`r*R|@#W1mk)Sd|l5KD$Eo7j}!GX5TJsyW4C&!rvbdlVt&{%#f6C0oKld# zPL+E{jH?7#4r_quzbF42-`^{x&lQDE49X3kX>V1x2m@C}3#Y#ID%Nt%ZsonAz;fw~ zJ1{%c)wbns|2=&A(m$n7>Wt>o7$qj{Rr4W76{7W2q95x4KGzEUw?-tD>Tdy6uq#kaP}^X2Qhy`~P&m(nF0#FOk0nNL zc($@w{!?P4GCVfb6kx>h@5TPsZ>g67zGd8ELPsAk`OcG~qlv#IU!4CG6Hrk-F>w6F zg#!*U>NUms*J0LJ{+=KBZzo&^d75~xia7y7PIMTXbWK{zsB^yxE>|Pt+~(hMF-E_C z>c4zT3;|(`1$lc({6&5$5s*!p22=tSBu-kQSq|uV09JVb5OIm|_g?y==>NHf@AgTx z8tHFm{e5Be5Z^;@tzeS2_wytWxA zD=hp$f4@<5*ZKGN1G}B@d6Yu&f9nT1`E*3K;^4Tt`P5;xs+%X%PX9c|BAYP9U`uE# zgZ01Fi@vdg9i5i0BD7bT7PCVC|7r5qOsW1)E!*^!D(g>{>D(R`5?$)+D;t_X`62pS z>CT<&E>#(LZ0_;4S;bZ~l^qPXB(bV`YQhk9RbRYBzy zQ@m2$kH0XlSPPfQj1(ck#5QC+ zzHF=CFM8n6_4E_JNch%PgCa|A=vIkm5R%n?pxUWRfdy${I^SmArM@G}>{%)zy zPnSQqJ~7k|pE z5WZz}mtv1lan$=w=56P(88x}6!ao|5msaW3Mhm~??;S2?joXnq1SZuo=2|vpo`zks zHpyVrFEY^qDpDJX2j1#FX*RokYu!K0?mX@X<$Uyfc6&KarF1eYZYz$O;PLYt(dT52 zfd8E%x528A4AE;5Dl_4_2VH0Di)yzoKFIv+e+}&Y6h4l5d7YW*)5ml<1keq_LiB2+ zV|~>`wM-F|W(nNfJy|sEL zROx=9iEEXBg@E)yJdo`QN6u$B$UBSz$eP)sEe(d%{TvfV1$5tc+V*+;M(R**5KCFg zSrZX}h+?=%6`W0r&G>;5Jn4k+_0yML!YBd_X*(d)cx`=IZChPEt=hoNjtLF!Eq}}NB{kNJ^~C^DByI{q|_Z<<1HJzuU6I5uuH_G~NDfdI2`gZ%nX_Y9~c-nL=)E>Kd@|fj>;%fA{0=0-W%0G6ElXtQg{$PXHT1khrMmS zcm;$NdoC|2gsaHZh+h@(dcKGG8Gv{4gjOvq%$Wql$3PeJ4;c~_2X?J8nB2-K-}(cn zpr=KVG8qlGrFJ44ZZ~y9_Uz>cEa$TJpC5SHHU2sEAT#e(Z2n7c>47Jxl;%X4?2(bX(nwsaM;EJlZ0uPORGacP|DF9wPwnmUyy5u;3>HcurN zXC5xZh?s1g+OAp-;6hxd)2gt&$6(S4g@_iWV5v>}eGue$WZYgi|H(sJd1ei)(k)jt zi+pBT9%1K5ykLtx6A;Q*G}g1T`OZOTL|1JxV||l}@nSb0%#dm6@-7=iCRD3;g9hF{h{>}~ zDUEa!O{X4j`w)-&%52m?ZOu|e z#bqcJFr#IBcOC87jk-q^Ay}Um0ag!6J#f3Fx}FwTW?MzPH8fP_F{#ftSE}jiq`h8# zt!WNozv4nH|4QIfEk=zht#+GH4!mt$aLFYOhx-h`9sGp+JJ*63Q`J)+*_gMM2cl!U zH9uj3f9v`Y@}ypHyxlM=4*tF9USMrf%E(_ddlWKrKWk=$DJByk`ux|Yme+>N-@6}N zdrs@tP%|Mq8u>JBH3n&e&6UwNw^Ovq=MW;+k4GS?^>*o2tRuo$yLC5KcGIxg4+QV) zPB&NrJ<2;@3VC0WKx7r~tG6!tJx5-7n{+>nt*2+uRz1x|$lND8YoBJwfWYe=uc1$V zd-8IMe}eXv*!5;i~g`DVT=)dkS3N8w#8BdlgG4O~Y1AaXXQE3~-J~vGLNK zw04v!Wwc!_W2r1{@7Jsm+GaxJe4Wnfj7wk_9sJ!D{*#6E#(zEV3oT!H#sl?KuHU?S zn&1>X#+~B6KgSrgu^e#Ao4tXpJ0!@^(j=c3>BA$(1%|@Vhs?HDL~&j-iSEsTJMezW zF-bnZ@o?XQa$PJmc0^FIdcvvYc0)KjE8D)uQjG5y$J%z z2CP?b^fxZ;r$ry?eHfez*p)3ITu#iHu%<*&k4J7FZqF#0k47e!*2lc9I>~BDAOF6I zWZ<(YYh28HDJmc~C8x?&oXJ$HJU`k08d_2LtcZVnZOoVtLd0JTIwqcL^*du%_9bN| zyLaJFPTtkV6?=O)T%RU?Ha62{gYt5nH}tq4(K2Ufq6HfzENBUWoXS;>wseX$;xoW2 zEo>qB74#y()bAA6WO{ZyHEbm9%BG8ou%CBQVwoY9MQL!V z$8tg}e_s)kir09WSK_4niwcCn=_aW}oTO~9za~fJtD|^I6x8Prr#Y>c8brU%(CnMh z<)Q!_;cNBpOJ(HpGv%)9)&IO+j_?}Ks;smcodf>;lV;>3!2>>k#y{In?*B^z_+sDx z4c{j7{{{#=PZ)NpIzqdzhPvSzj}C*~Ek}YZMilRN2BmmeK=)Ui?i2E{~Jc;&+=K$Ve@t>`% z%-8~28l~5BLzHs~p@Yxw`K1E&<{ zv{fxNdU`snsv@Xe-D;Iko2salP^-k&a#~e7>>90F38F%b2vx1NBzCNjpu~(7i4o&> z=X^fD@AvDEKH5Hnv<|?eo0jH9k=G2kM zD>si{ioBHHYJADH)l^mR;-y^8-7llWaU{c;o{P{`=l$PZ%zdv9Enxczk%YjfbqlGS zyG3rPmywHuqosJ5m^xo^xl-fSu=d7=hRW`D>$_>9S{am!TZGw)gJey?|M%m9HdU=8 zWZ56zU-Iv4M)#G_kBCa)VS_QU`3|LLfebyS4X*`Ts>20L&lmRKdC=jZxA znKIaf^f5OtFgNC2c z=Mhc*uK)k5K!_@*)y2U)$D|9EOTsCWjB0W#{6exML(IqBL?g_JN#&Q$q6s&SaO-^k z@2@j;;|-+Ry9!`aqE|9o)`z|e@mAg>YpjnVteI;~PRe2qk!k-o^}{o1VG~W= zjjV6mUhD0o55}@p0m3HGFxq?AH@n)Kz8M&-_n`1@I7R6HSQVbtqDlRwx1EHC=l0eW zu{-@)gDAgf?LlNw4vdQPA(>VFU-VV7>skI#rH0*$z3|u1h$f@z{)SNtc441`*yB%& z&NV)84D&(#zi-Cqb~H6om-%tC({3q)5WL_*&yCboKlYPf=Y1FW38Vt`(fPRlvrasl zJzSQQUiEK22hUx#6;c0{jPn^GbXjzUQ{HuLjV)Q`%%D55)+JIoJ9Ty}uD?ba7U8it zTM@tcIZ;`UG|SURJ)f}aow|D&;WIq{)O@YrYC`66dpryqk_x09=auGj*LU8Z@7!5^ zJ@hcgZB&crXSotg>EUrNW*L$nypK=J-wU~}}z0F`10viRMt*%dGh7Ud0hiHJ! z^)(cbztY8Fb~dH6*cz>+cq=jgZxMu1GZ`mpD5Ab@Ig>)%EIQ?}wa}0#VM~kHWh0qO z(bjZD$JoOsF4Kio9#IaAYQ39lb}Gzd!t}g?E@zXHadtz?9{r>zf%PHlzxLA44&3h# zpe|a&AK`>{r!O&oMxM_Ur6{>A>dYKgSJmSq+3el)uh@0hi9m;V&n5Wx`_F35Zz9!? zk-Iplr|G{j?iq&tOCBb}Ve0C~^a;rEO;h3x2_*(~ss;O75AxP&ix{vp)Lr`73cLn< z<_q3iV!0VQ@!9SjvmsHlg#L5z3tgc;VQ!HF*7v)ksn0Rn0}Hf0ZE#kf5W9?e|J4`KrJmdFh)W^#{1j9f59*W_GNYIll)mq4MrkU$5bcqJ%Cl!*mx9p>qegJnf3$rp09X(h3dFX?G zGf)O<2kX=f!6a0Gep?-qMGa#b`?tv!4f@;WlvcLM(HS)~2mmi&HfM`+i3Mqno?AeL z*}A{j+IlghAY?W=jmU>YIKRSA*T%J}U0&>FN~@jeIOURR<9d?05~&BdDXi7w{rFGb zfS*O6#UzprL;;uAX^~Afphf^#F52}wZ01dczL1l8JYb%i3 zeF${p|LL`b_L(V+a^|Eo=G~I@kBd4ity&y)QU;I@<@wUOOo{!INw3BO2W&~&tgjCx z)_DJ9e0pnAi2;2|l^7dU&ps)C_}>`iGdCAu)R5`Z>Z)2d?uvWGHsDLK1tB{k>zN7c zS@&|zz#sl!CB^DxE2kNM9raEQ{_X%#4R^%1c?T>u)5&NlHPc+*#H_!OmXAJyhHPWq zoi&U9DoUUsX>@_B%zNS8yCwe<&B_IpKE;2Y00;(S%Y8O@4zLEQ4IGW#S95dnEs1RH#3nUX8fKOA@V}!lzpMiuSgr^@5Pnk=uS)(9EC3 z)h{HLn7Y6Bi>sS>ArC73r(EF#mK8V+QNyy}c;~9q)Qp1fk0?~hus)rkSS*dwss-z}jfLE;)J}2>7<$)wHH`E+b7>RyT0Y5)0H8>0(Y{-F)jeUY+t_kNBIa zyFs!6Aueb~41nwKy9r8-wOs6z_l?T_NFcfMv%r;dL1J9|hfie=reXDkLnmM^{9I_- z+l99+qyydHCK(gq20Bl*u%JP3h~?;-s0NOiEx?xf7%=%Hyq#|(N%;)yaJ#DBGe@q{ zxgGH8Bfha&NAz{-80i$^H~hKG7KHYQy$VOXcc*rdPFvrlj69i1%n)Lm)CR_!jF|An zlFjWh4(x^Ik#u$Gi>|~gS{T>zp>=VU&DX!+cVsxa8)F9~Mxe&xTtXB9J_t14^ST$} z=R!eo)LTd+K@pd(Q-01g$6K1dP0vD%9Aix-s#7oNgsxSr3kZaw;yyYA4Sjb^8aOlB zzB6kYdATS%C{q*kNRYsufPq@}Vrzfy?YHML+ArdX1QoVR`f0~<_lNUGlV)uzl7}ynYxM@+BC>b{t4~Q zEJ(0%YtUZ#_Q4;XxulFPAO7Lpv_pWckN(I2{RwS+NWBf`_gR%wFC!Q>*lFki;*IP9 zh)C|Tn95!Qvrf5n+a>8YX^%DIdNE=f;!o8p4>q);R&~E6x*~HBsiO~ku)kZ}vv5rH zawg0$>5{`9xc?_Yf-}Z+24J}w;(8f>r}iUBgIe0{D&$YjvCbH{F7qpgU^d~Hwcd!>fu7$J7V-p)F_Z7Yw#07d%@MB^qgUD{q(#v9-QwbmiYVUu3S7^NUD%XPri= zMoD;yxb;2^(2Sd$4_w~enLT;pslX>p3$sH1@N%?IdsZJkX zd%l_aE)0ShetOL9^-K&z-i81!#Fv}2J-AA?){+ZulpWMtNYXA0=a8pIv|p((iP$J` z(`6IS=iUvl7@$5?Kc7XlUQ?gHNc;X$ck>Q*ER5vUTs!fFmXVJe?tQ;AMy9_wzZhU> z*TMhWQ8_;}*DKY&20P?7>8!F8!^A5m;upXe@f;XuDD%wf$H51QHRw13v0z`vT5wGhOOH$k4>^%A!Nj#$^ z1Yr!!JPb|J>?GoS!4yvZ0p> z0IL)RkSjr>K(PB*y)YVc90^2${s<~o-)34ww-_~Jjr(!!lqjmW>sB-MfUw4wkziUl z{BV?Z=v;jf@qoLIbG_r7 z3UFfP&w)Er}5K*V|q%NSLHVp!yPM@u6wCrg>o2J~@xp6^_bgcMB6x_;d8C*i=Vmw8$@=lg(V zvt?4)IYf`Q6vx;_|tF_7#Cm%G;88zDFIhsB4uix2Epud+9%J1<)l zZj%&hM*3m#k~h*r=pMzkS02q4sH=jlJq#kxB>H$fl31sKaR`i7GUenBvETeAzA#eI zny$sSRykeRY`!2$rH%ww47n0~h{`oP-6L1VrQvrO#3!3R%p^zmtm|4zuAxafG$Kv6 zu3xx}iK`L0l)XOKryWS75ha3kfiKnp{BAh*r0C2&7+pZVbgcDSZvYB@-{6)`$mkn` zTPyRJtTfg6rpY%(!z^n`ZMA)5Sy9YvgwF4nZb#6^vk;2fQLff3g@oJ1439xsmi7Dg zD70OA9ApZeWtHM7kcv}gSVmhZK6#L6pC_^uVMg>~EUaI>A=Q91=MYWcI zy-&kD$7C#hcsjM2FD2eOwH+o;O9+RC4xbk|IKMAGG#Q3;0u;Hs2n=oQYH*HBbGyk^D=uDyLjh27*z zLcmeEa&B_J^j5@fsw*o7MsM^O8BW{Z+Ur)p5({Bz4mUD!K3Ud^3ySy!SWqV5U$$zm znXPN8Q}+B_QPb5T^pQUMuu_}Hui3DXFY^mt;=@Jjr#S9d<`uj27KFI>jk_oZnQ*$- zQbs&7$K&{7?b9Kjkz8Vo(Z#vef3k{v?65mJMOmW3)UKDBGY^>Te-FX$vSg9wya$F6 za>*9X3PRFPEhVr5SIjRwa;g@yZFYA`phTWO+x6sav zN-qVk*cyR}!q3ilUQ*QO1H>cp7hNt6v5zpRMoV?d`t9af_$@`KkhG_vC1c}!Nm|}1 zlsu#5K#pgCd4<_PzQC!evIa7LHF@D}rZm^{o&u+VEq9=w--vlb9XG+(3n zDs#HK?)v)qdaGQG&r_MHsDtEWQL(i(OBHj%EiB<#Yt26?3OJ;uP%ZS~^ka9#~UcI@8+Mme9$H1WE9(jztOHMf3 z65DsL2{%;F?2vGhtQ`348jSt@N+fHkDc3_Ptb+4CYcUw0yOHy~>&ELJZUT#R|L04I zCuKIF-Gx6KPBU@Y11~jpA7B}o5?SFGO_KKIO%L_LP}mNlKBSnlMA}YJd>ACXejeM^ zGrPZ+stx=-t(O`t0dsZbAz?H@B7W})HL*lW=P!(cfb>7m4_B4L{=DZy%6Z%-OF|8y zAiO0hIw+QPb5c&2QrvJWpn$RSP}RHRECn`SKc+}P9aWd((zMIM_|QM2+^h^NPG7-z z=s>IOjjE$d7rfm(yqr87QXNA*)X!yS2MzzS5-K8o1fhdQr2{SW11&oX(U@^nppO?C z9!6>$NUshpb9*Hf5%9pkFS$@_t0Uj1BDgR2W=71;^~C9f=| z=KKAJzpfL%_#GfUXjgz;oDF%NE!}nRo$@CIeB>U7#tydhSt)$I4mLr%o_1cQYmc_} zSjiU6tGo^d5Bw4`9y=U*0!qP;$4S&H|9Yjn^@uspv`dC#7DZPl0AKg>`p0^HXk27w zyb4REXwhh`tCUS{R~l&aD7iNqiXZV>)ONsHKXAZS5m2GFG;`CbFz!xJ2Q{#{8yY|7 zRYF>hEih_)^duH^Hap&u7BnLt)m{*C*F-s-JXF(OQi`$#S(SO>#>)AOvuXANxF#)H z*evC_lgl$loFon8E(U?d4dM@Ply@rLpt?(EE*d5&GeP>9FT~pZv8H;V2D4KuH)P{! zQ@WznJdEAo85Oc!J?Hi-Vx|8ky?L=o-G}bu6@*+3!}|U>JDNUGl^v=3UrU6=uUY)X{%dnkLl<|b;y<{t>dkIQIw7j4o@A>{xxiIr)A4Q6O|EAT@ z5GwT!=MJaz7+{T{fe;_*&DxT4mWOee-}V;GZbdgRq0*R!Uv2a~scpU9pvC~3?VRBj zXhjVLK1z(8)_$}b;xW!|*T$N)%gy{S8lQPR_0b>wa*ym@Tu*cC+uggGp!9Hhy?amh zv1`=u=6JlcH$KDDe;qWG){rlYoxvDrT3RoU?}H9yvB&qBHg|Ff^}0Oi@nc1}0rzid zm4x%}ePc!)$-CS}()tfW1@TVn!(K{ux*y{W`-Bm;p1QZ7Jo7I1NA0G@Z5`YUZ3pfx z@wx$KAv@Z3)YUB;XRUVCr=pn;ersjzq|)baM=}N-_oBQ{h!FR)67`j$>XRWq=N;Z;L0vW5qK}SHyP$!V@PvvMc2?gH6?Y=*pcNmAmS+PL5x8tFwAPcE2{+wm@lf$D!?f1bNtTM=_rV3J&wRy2f4O0)CV>_u4WsnB9T z*#6zTVjUncu+3Eb7R@cEVfD6p;i@ijNk!sawmUV1_~ktR@Js6BnLRaWA3Pl`bJLofN44)6P&-2XH0dk5^(<`pi-H*q6nB0S9>g|Kjl&U@&D1k+-H&8`B-FV) z!Q5d`PCqX~C%oi*;B|EsRL%m3c&hi&I^sp(a z9QNdN)-5-BbUb79X{zUsPJ0iy!|%@OZayw7E8oOo+=pbA=GqIrTB?$tO*?@rf65a} zugoTyq~$(3*Jx39KB8&oVJc~IXLf$cJF9_Vy)@bS&b={6FoU|M-C5<7|90~x21`1B zw5VQr$^z=#cF(f;edTdL?`E{V`@w&D8dz`?-|6bZz%=yU9!g8eJ8W5iqesX2Hw9d(1uD5+?-0Q`Eln1*AKEf8vr*ki3jjt2iqxzlu9(Dw27vyAO) zOzTU)QB*U?w>1iI_;^mDj}F&dJ@U>l5IP5}#QNYB+_7zKfJhtZTKEHwkUhELGJL~r zeHX}ND=6=|lL9JoJqF4hd{})bQIsX>tZ}nrO4)_MEHb}}XmOuA`f=`Kin&$YJ*${p zzbd$ZCpT%0Nnj+l(^+4uH}(}vgIe^YZHa-SX){#{ypbQ^SWr9s}VQsIHyr zMx~?4*$%SI8mDg^HKQ+#GU97=+KEruecesb>P<{C(9UH_Jhh}$ zrF{C5UnyU`D{v27REzMtZZlfNp5LneW6}Pa$FTYuKp_7ERazu)c{>!vpxt3i({>hv zAr~kg4EgO27-R-jzBvf)2O(cI0iTrcG6iqmRH(((w2KZS>1}2~OrQ{UlkPFM``%k< z?C-iNUtSSY>Nxovv-KqU`tb?|1vj7Ec=E+R0_r%D%aW-^#kZ1jQtFEA(EUnMe?;*)sv^=Z|~m6FquwWc`q$ z^eWVj^+0}7${nWmzwyF^R}DQ#Xv*x=&GOz|NpkduS2X&$_HgF#h`UJ%Noq^PjW7Qt zvRtOCffs2DVg`uClZ@}FRqaSdY)|gSj!XXleO$^tU5U0ixF+SFGux%8neK$*O|$QV z2`JS*)WSDpUw%lau_! z-rkab3!TS|xhQXkdg{rm;4};QgK=2h8g4>3 zQ8u@-mG!hn7tIw9F0Ol;-S`G-L~y_Xvcm#kQ6{2Mc2_&?tX!$tzPl$t*M=bPCDEUK z!I59y9w1I+%OM%6OWVxMqkDcIL7q30-fD;_y;ZS}$24MxeyC70Tue^-zp(jW7ea3T zVZMCdVA9#_WN{pKItZ==9rb2-uZ+Ohtm=U( zRUb@dU?`}opy~-I0UbdKIx`|*@1uf!H321;CV#zp^THs9HQ+>XUOJy^S?*DCr)%1- zL7Qy>n%lTZ zg$;IWEd^lPe>THrh2*mgPT;zF7{J@6UO!%S@|#lw>$Sw&oXS5_5{rME4m~HApR+gh z}?$Y}2D9E7JO3sAT)}gKO zENO48uhNaXA2dBCZx=G-vPaYB%>J}#e#rYx)P6UpzXpET?4-ac2QZ-lB7>HDfIfZV zQ%|MY-n*TmLJQQ&a@5SY3~!#LLl>ay#wS}tFMYQNdDe*F znd7!))csZo!IyQFEy!S|V+jl~PtywZywqr_scyz2toL+=`@UX$O-`o6Xktl&kh=Dd zfO*K5u#IsGNCl|2>D4N)G;&rraS(r6I7vI~tJB?ewFpM5rS%WCQHI|EjM{(E0g}d9 zFjOzB$Zg~_YghIx<3-bO%~S{zSKUm-P>uH9RqnU=FNlMD ztUTfc70MC0in>z?!nDD=Iod;svakA^0Kkup&u3W&xhWPKJLqUG3^?uU`p4E(8n}K| zTIq|t0~S8}#cVq-K{=&amTt=?8JE9X6<7&13b|)<+I(7UZ2CdQ1*`avg<3GVEmIf| z@=e~+%$w5T4`T_azb_&LB-0+U{%${3(NH`69Y*JF)eTwuMgLtQon?e0e1jc3kTQmj zf#S+g_sfq0@}^xMv);mALw&W=7>-l-eQv2(HnWZ=TD{J+XZ4dQ3wO zU2US~3=sr}NQdgQ&25Rwr=D)DFVn!Sj_~3j*QH#q1kAuVXb&tYF0&?_j#d5b3BV?par-m`k3 zDEmi=w-N6*$nc{xlpr7FW2)q>PCz0!e$I0Tx@;}qb_8SvP#-7yX_)`=hF-VlORk;@ zr{11FSy<`?HPxYoF^5Xsd<@lO|J?=!iA*kUiZ5-ce*U8RIS@crma;O6#p`2*ul!6b z5fc3=8M(cJ+rf~n>_~ir%)jNb)KLUkU<0nVy?}mM&EE@qsN!Qyt-WG=?kTBhc^fiF z3CZuE&k-;X%*(q@{$D%wcD&1n=jBvbP8KBd8fmxw(SrKw)Td?jAfFNYWb555B!43w zBdGV3{~z;xHJL7EGUdlbs%F*OYI=v?a6`p1kV72C`FLTnKsl6B2faS<1_J;i7*x}+ zC1C*w-VxmNBW0wWOO0!_%-vtE`$u6^#&B;LL}z0Q7y`h34Q0)_fssn`>V*(X$E`nN^TR?Mf_ZRIF+ETH3gE+8;hAmF*u}jmgl#hx|D?4R#08QSHmi%}yqr zo!_B?FUO}ySlFSJ@Nb0J9b0VqtRc>?G?meGdc@|eJ998+I&1w$gEy{eIsn^qQKC+{ znjFD00s9Q!*?3tbXm98JfD-uTfCD`RMq*jv#a9oyoxvS+vqRZdf>wZT+y_*VWACzo zXVY%z*QT=@EbBm``Mk8fDQ~acV;v|f%gI#7@BKAi87^m3=sgGnm=KA&<9%_dsB|m7 z&!`TI8-BKJe^>=ozhZF9@}~m(%)wrF2$@QOaISLh(>^audsns{Flqy@@zndUEGB=y}cRNdmT#dnl0m+%Y&Rtl6ko9Hj#fXBC@Vn!gM*|#d zVKgtId{V=ME$YaCcU5G&z50dNji>RZmzH)p4*r`RX<5=uobJSZFYrLn0)Fxn%%W!BKS`dBC|+JZB`&DJ!J*yDgI7k>+cM95y3N*Y zV2cM~1V^aFQigHGxVYG8N6gJ6si5pNfxL*S42NqujprP~<6B7O6u3ud=WLWVhmDse z%1%3Yn&{E>{re)c@E?Ane3NV5WHgvt1~U1keVqH9Ty|c#3r|1KS?=R?t*$I++?Y^Q zdGM`}9xtt1V?cc+iRTu$kZdJ-?w)p6!zSGUGDFG#p=c}+`>Kwm?LXRdBmKLWr~34U ze4{`MFFlK9?>DwYoNHGtdjJ|uOx2~s&BN@p5uNF9>gIwWc5&5#Xf!?IGECeQM6UkZ zPK<h*YWoC|uKI z1BO>6NW?bWi?WV3)zR*{$G9ZVQ+#)Tn{UMxO6Y7`DS`oVIYNta#bxnlZDVjXAXR{? zOEu5GF|_Mx=5tTrBbqP*27L_4rP#%kbD+jG`$vYUo{-!rOtt8mWr(Sf*~z#2b3FxZ z41RdFwXx+YP@EJ`1fmO+bA7TzyAZBY7nYlv`6LEQ5#;23GCKPSkE;Jzqu(rxZOCzg zC#i)FIwQO+N%~9HP6T%_7e$cC8t5gOXvz9kp(T1ROGSq1f$3)J=}tRyPq1Vw>-rC^ z+bgdnh`%wq^HkAkd~U?0&PLXYx|L;v!lmQ*x(`Cl!_W@Ubql)aup)92k8*{E3L%}o3xz$NnlD#z0lvNdfL5W@x~TmErpd5 zr?RG;Wu>zl=OT8Xidm?0?00|F1JHxD_YS%`M?hSzxAHxx$GjA9YZ>}WR}gx#A0_;` zA1ckS0|+MmX#ZYAUeuh{i&w6q*F2hz`DIAn9^!3Rta*=gCxWO2A$UUclT!6q=<~Cw z6+aC6j?!$#58!vnf_$Mm(#ue1Lh6v3{yPcb#%Aqcjz8=JTQEbk->F$h(FC(gAZ{U5 zAvMe7BBzXfMk2mTck&fz5ob6V7wyzV*i^p>N!Wtul$b`&%JxZI+auFvxZ70u+I$Le ze?qFG7BLi$amVSoA=ia((Id}8?f$(?{)pNJAoW9Y24}c<&FZGv@AqJN5nimlwp*4_ z!keE8FM+N>cj+yQFE#JHDgd;uPd93|Bq*CZ0FYp0Dsp?Swx{JOn7~*iVrP|^`CVh` zoy9_+bxHN!1tYZ+#eIg!^)<4oi*^A@`ShD>Iz3_XvtW7?R-}Ip+vSc%y-O(2w*^U^ zQ9K`LY`J=yd$Z-0a``V>$h72o zxxthAWz|s3SdgMrKk+MD?%xt;e?{CtFJ$0KLfxr@q0v2m&0I%c&r_GSmHRorIki68 zfT{buln8$`Zw@x>QPWeNyX#E=(A5*L6hQ!_1)xypJ9ER^MR#}O07 z@prhs`o%5@sT^LXhLz}()T#Tu%vA1{lQ=-|Yr*RKh?mvTGfDfS!9Q;B3bs{RrnH9+ z_cL2s_AR7-ylSE|UM_bie?MWI$G0wkYF>yFxC1pq>sMa(OgZ~DwbCO+wtVx+Fs8o5 zdb!rpHWv_Ihaquj1D_9){zPR+dmWh52rvG8@*i&Hoz$~9_}Qa1T&LSz8p?A-bcQvt z%U>+Y`{aj%RtG^or}6>q$(E4+7blTRI;M}dvv**0^}@Y3JH`Xq_)I87mLT_wcUaLm z=tONS(puBvhVf@8G?z{Ez-2phis*%ZorR?sds*|IvsH3fl6?I0^rFM8W5lK#(&2YW zMct9==QGjDyzi2gKu?_E^-P+XkYVVPZs0&ry!%5m*Yv-Fq$v>$5txX3w*;I|2&e-$ zAg!;Et3JjrYp2K-hxa{xgoO5*$~F&P5cqq3-(iQ|G*>Pyf8VgosMn1BJz=Pw!(FWM z_j^_)mpx)YqwEqsfhnB9x_Ol89$gqdA~7QpY?}%44@b2$#uFRwJaz3;#mAv_sQqjA zWdB5hF_+)?LPeJ?j-DvE=YlNQZ&@tKd%XS7H60KGb4eOWLTlW+(^%@3LMnDutAT{O3_lK+W(}eP$5giN4A7JT@Wu-%$w_5)V_g{ zZ6XO~wqyWXhL;t2-hv7i6p6Qp71`uPE!uiX`ao#g57a*yj4Y?>=hZ;|SnI!0c7QN- zPv4p`gc`GAz(aJqIBUJ86i7wozxoIuK`(Zvb!_#&Z`k++YcgVE$?C}eSxzUgoW2>F zKHDBJGD#xV+5fF+At;>6;0^Z?Ul}3ku0+ALxrpn=q&~s_{vH=UoxK>{ ze;;({EfI_l^(QoZ}7a+!UNcx;pj#o{;+NkmX9b79_CRmK+~HD5J_FLkUZ{KkhF6JI?)f z&VZ!82i=3>>!r&{E2J&ej@$GuG+5$o4*^NYp9aR#B~}VNEFgJ_x;yN@qeB{ucFhWS z+mZ7S=A@zpE#g_3rd_L%N2Bs`HKv~bG&zZXR?o67HOYEu^9f}N5WfcN!aS?7&azS3 z9xA3Sb+c)?Synpp@$PC}^PMGr8Up~-(MJVE0B@&50M2m$jbBzDadaA4Ryci22!P-Ajn?w`_J7O904-v;ndpcP5`t*;SRQK* z+{EXuGoTO*P=4F;b1Sqxr3iPD&w%;`xCT#N;r|sioGV_QiQ`{S|>=Z=Bn) z4gg7kOLI=tnlyc-u6polv$S)@S;uU?KOXS~zvGvGUYd+r*VaZ9ycQQ-cam_j{Mi?Q z>{L2ml%@k%uf9{j2n2Eml>d93OyXIU>x8Q3<8(RektCh=MW02-P}3{*uu<@LH<&gj zQ_B|R4!^O~`GH^iL7aPB(sZ1(zF!OYIc7-kjQgJfosrCOup%MXZz%O_O~vODMWj1b zl_IxFLgso+XJ+U@O5s;rJ3g<}ZEkX;N4oFn>~cmG^3`EatTtE)Et>*B%~JtrgrHY% zsFmQ=mw!_PRK8@^%OfVkk=*4r0_d|?(|PxxLGRIX*>Nc?ozqk;xSwIA>HOS)R+}>a zl4Ko1cV{ENZm(#OB@4RVgvuM&zSjNLZt7GsRhskvBiQ|Y*!ysyU8hrelDzwPdMuhB z^l6@fYee-wb(Vd>0@#$gA7Q39)oUcYP|{;Up1nBZhjtBqEh=ZLLcx)E@41hsSP)D` zOZ3KCMRzvG^5cV9XO<{Nd18+o9v_{7>fdYrvSRwm&rsYWz4cjaYS|D*ol0zsTOUAU z8YZ{I?}miDnfF>=nm#``pokmlZ|slR8>#BxmHGq7O>Uh9>wokUpY8eV+=$J(%{p25 zlXDwS;2RC!!X?3;NdQl(>SEm=YjT3sH1qh{;1!cAtIk@AFE^nzEC(l78K|QWZ_s(u zOpWzId(I+5eb=2c;1FrZk&E36%LwuQ`p}v6JCQh(cru6oy%%_{p5PpH)ldH2h3sUgcM=TjL#oL>%a;Z{(u+I@&M7Sd z4;E`f)H#k0_JN(va<9qX-45}iHLS$cnwA^-u0us6Pferkt=2Q!8(Bld=2-z7*wB=H zuCjFG+J|{B;vkEokiNp1J)dZ>S{|+MXGtbG_DzrDg;D=-|{iiQ@>a?si<#bL6!4{+*Px`T;VVAV-C;Bh%p^Z5v6nx+1 z_WIM{y-c0HFCc?>b2$`i8|eQb>f*F5n5^9b9Kna&;U84Bd&p|mMwB%;uP?#D`xTa_ zeqWS{(^{O{$`pJhxSJI0-DEKh%iQv|${iIC7-H3svODmMIJAS4;WI_m@0eA(NngB zI^MkZo%MeZiXd z0lZ9JpoeI*V{V=8&mNourB$oPS*zyAKwQ~DN*Xk)R<{rZ>f zCl2EMYBs)-YD&^SSq5Y&%F;upaNl7;gq>RW#IQ(VIG`k%-3}36JHkDVS=|!ml&Jk* zY|5X>9GV7bw5VZV;;Sx#k<5H5_OZ|l@w`8(1MDzP#7y!(wex7iMa#2~Gsk?CV^02P zLDV&~)c8Q9UaVIa6EmZW)Etz3t0@GPFAM3?RRU}KN!xn#a9&_#23}8HV!WCXz8tOz;}~aFE>w;(jn#<#E#&%UavFG{%1da&alYGc;cFQG6 z2&3YDfKP>}3nTYsTix##+9&6_5Gg*~HS_sKk|ym(E8?NAM$d;i7*9ybbm^crMk}i4 zyW3)`+ZOEV?}8vz6KnAJczGA{hfASj{@@~9blCaHVIKjvV4D5G&~=@eqWn)*rk_|ZQ=LBD5!}u)v*HV@(?$F^p4IAM#$o555C7qWN!r(6C zp5KY#i9|2Fx>07fg@j4vZwj?!K18QZG^p@*2+1Ie z-gj@j>lo8>g49GUe>x+A>y@lRDsdc5PWaw<%Z7>a^s6?b-Y5K85V~mB-rZ0&QWb`5 zaID>NAgoi)fHyP?O)Ic(heYq=(VtJAMr9qkcc9F|K5qcFw)>vsZ^gBBeQyCCe;|kU zv3{KvNi%l4ySKZ;sB+1?(Ypxpb?{qfc9L3mrj#Q60K3LF5yPu^9yRA8lwix>1W&Vn z{9K~vJy9-fm!Q*XYgt(PahdSV7z`P>XE zW7Ys3!*xb0iZM`(dZu>w_X`g@NZaQf6CW!UHs;6p=BrTp6s&hMa5dGPHIj<{-QfZ-4g=$V2goDcUPg*xTRC^^VQ4|v1M4fTI)`x>(VJx>$F+una} zf$wTA>R(|A&&8u z?>sS z36UM~Y#kZr=@QtuYa#t<7@!6j^FR;a>ZHSaO?1Z2Jv%V-VAU~8Bp74wy$7b=xo~@$ zIE0noKL93D-0LXu2(Li(A`q3=3&F)CzVtO-;VSYfT!elp+Z1&g=Q>@&Z*0wD5XTz^ zHh@7I91C1l_oIccS5uH+o<`m2&5778zudG}h*9)GE#9v?yFF;>a+$`1v75tsHhutg zoROo0tPf7?(?v*?`xn=r1Rj&v3~$uc(9)q6Vj~O}F7!e|n5S6J&!D>&e2$)p%faLu z2rD%F;=dM(QC4@FE5Mr@CU_mD!$IB>@(As>8)~`Fg;&IlD*?+IotLe}frNH_@X*J+ zDjam59U(5Zk98yZ=dZW?f%D$*Q7OEfpeW(wEek*_?SytRH&FU)N31!&%gX4IC_ zDhy)z)U*njWBobE|>#HERCl+M|3ieaCOr-?OG(I{rRlo0*+95qCgea&_oM zv-dadq(QzH+E7ZV{tVDAN-zBv(1kf;Uso?)Nezci{yYa7xaY6tiShhdqJ~TSz++~abxHg< zR4qwbYT+xuK${r%J^n`{JQMP7z|oWM5tbBveXmbTvD{cetZk$K7~P+c>hoxS`wEM^ z%V9nx#1ZGfMo%=i0f@&E_DSTAxxLtvc+g~)D{-wCO?7{bDIDTg<*d!R*2tG{(Tl@@ zTsCWHE&^-mhENW0!gQK~V6pMeMCeCX=nw30?s3Vt9+X5Xa16XtCW}FQ``^3OPw4#~ zZrRn&-yO4E;Vi~#@`&}SzYq28Oj0^`tI)$}v#H@xVl?%^g+I^|$49$3Ch7s=$A!Bb zflSu8kb6e6FNPf`{e8>Si!&Q=#{R+}9-MmBjHcnH(}RNF__==He=*?f#Qu8A(Zf7L ze>K)H9nuj+*6U%qx9A5xw*70#SB&x&<~O=-@PIc?&51A2pCr2%jp1<3k<^dKwa|Qi;kBVH#!JCD^n1f~g=Q0*FU^od<^ynGz%*lQ zB66S@R5EZ^=1Tv&{JBo)4drOHL$s*tyaNIIz$lHby53JhZ)X37_HOMV!N{7&A>%K4 zW@n+2t_Jm=$rV>kaa-(!)+FhrI91)#Xg0jzDzhh6uzpBD3K{xFV`EaI%XX>`Jh-yA zW%Zg9Bk#a95Zy2c`c4>rBV~5#+&~`$;k>m0onoc9Aqyx;yy&8~$$G+Wj>(j8v&;j< zgRynD-~B?d4)d{&Z5vsHV{x}L8bWI|=f-zRd#}h#*i79Xuaw!dkxQ1o$&owtPg%j( z%JE6;>z3cpiyu1sBRh1{C57kaRajFGuk5;weTinPA-32IiJ==95P9*71T9r2{O^%S zmY6!&|IaCV`SZ7qmuF7b&zECc=5Di9LMf_BmQ@pR);T%l!o4f1A*&C;yadU1+of8G z@(ZD>nsA#&@k@Et_x3$~+Q|=+5C3$|3+Dyk=IFUukxeR+Gm246(Ww5rWaarBbBEe3 zH<}5ePs2RO(fMr|WKyC7F24)IP$4!kq9EDq$+yF2CbpR#K}e+h`L=csC3?j@b7+csVtsPJ)Xb{?Z| z+Ais2M~E-5W<#AN>6g#(Y+lb3(=WHYTtSb0*f^$rLG~6MaX&_EsVkGpGQQ!hXU@7jE*^40&vQ1CdjZy(O6_a8M8EQH_Te%Tl<|S-$0%DT%p(ONmE$!&@?beysd!G^rKr zTe?@(oqF|-Bcnw?d94q>m(n{dHOfTWd>%u5h{>(*v`(%nC>b63PrfR&raO`YuYCdU zL^L5xue5P1!%o<~2Fu!#nqu+&I*GliR!+QA6=q#mSF3mFUHLoo4p}Y`r;-Y=ukW~|d_9QR~em_N$u?vy}%QG&pmO~1L1m$kyP z2+cU8*Y){)qWx&iTv)luj$CZF2Jhzp+R2pX3T;>WH&m;nL0y0C_P(0ZWdqW(PGh~V zujzB%VX^wX<=&aSD(Qr}PR#L?M30>qO5S>7o7+k*tC?SVAx^cxLy%li0wl=UAH~arF^_Brmzv0{W009L7gHY0z1{D|`@)J}#MmN$iIz|c# zC}kl6(mi5GGfF@N>8{a8GkP1%ea-*>zMtncy!h@L*L7aUd7Pi)xL{)=&rcAWw7txp zv&)9nZIrayjV~1lN&PG?AZcXmlDsd?nm5w0O=vaoVTbHy4^tp0Q%8C?O2*Oej6bBF zeG6rou*uJHwPY{rMB?3k3Gi@M7s-BoL*~F!Tx~H={`^N%gqrawrS zPh)%SFZ+S+4c13(H22Izl|()HI3Rc|K78o?h~p@hvgNzlOr<&b+wD#n=d^ihK2;~H#T{_k9!10?%}oG zt1HmEdc|31v&&gd7h^CWE_U*p$NUm15OUaOPgZZoId-_(#!=&4;fl*W3ul{Mx>rfpik%7eMWJCm#H8(;{v;_?tf(T8~u=3^UcBVDz5H zRaCIj(4*X^+2tW^fdi7CR}O~dsnDyp+Np)!gR?OZ49m-_W#LJcPIsOJydF^0OVaB0q%+0pw`)Q{R4JbTNur+$OFH`5`spQcFL1l?xMvG+UCN__!b*#m!H1a@n+E%l|# zPkjiB45Eod`!EG?_&-2Q3duS!#Gf)lC6#vTHX$#W;%kVNU69Fpr_A_42ITY66?>@L z<_=>T_fy3f*462oPy7#D{7yGf3pnW*cG?kPpX$W^TT_ZhB21Clvm}IQ01tcF!TF#Q zCM>Yx{WG-y<}7N}@#TTlvlM~I7f0P6T&^3p_MIaqH5X-$Og)>@9808}ge`N|aw0Ws z&mg6-QPZSfO}xZLb;UV&1CFE5Yi`qkIL90|qwc#mzQ+M!@kdK2OgT5X_)5{1TrI(E zi`ll}f}e&RRT=|TG3-vsgQnR;x=&msI*uQBPu?8#D{?r64}Tu{)?cuod~?1j@)b@k zNu)^MJc|DfgBfn{P*n{PCa~RteO92=q<%0*3R99s?61@e=E;m%e_r8ImkFBke?D{) z*?pN}ExLj7X$gIW7j}y2+iIEV^9}YCm(NKP-;(hg=HW#(J@)we-zwkn5!l|$ZTx@z zcyfZGcJASUUFb1S_gQyAb=Oq2@(iz?mnvWJ$u-Wz#*r!iy>6_-m)X;FI;zOxQP1S$ z|Hya15M*u6$f;%e(^F1#?{EMgB+biT-(te;n$;G!;6|tJ{yBOCKxCi8MAxBrX-)$< zBa9qx!On9%)uHCi7YtKYJ2i09qN?lbRj|&NckRy*O~6TMa!Cz?fgVTx=59Qc|ca^5d11Yh#Aw(pJAIO9qA3*uj!2NlTSErWTH5+)&o;XvQmdTpvOv>On= z)I^zWkruP%jP2N`#nj~r(j@028EhVs}QtexViYaVRleb4Vk8z48XOX%& zKwU3E|1A=(^SX+(6p>f`Njp1d)06~Kk-2*{c`!iC>_f-72h9>0>Ig(@ya}}NU|W!| zs#{A>&olec@i8Ot36SdPn6eIYosLx2v)%sO;!`7;1k=ahB>T55AH61e)Ce-$C(bOE z>24*puc(w*ZtbR)YEu-I+AV(W4d1v2QwEu?aaP=CYkeo6nZ;xn6~;wi_*?}u$+ z+|mq!Dch(YKL(RM&sqUPv0i%73X`fJ*oP&AFOg`2KrVyCpNUzQinD1xk&`*dF>mJT z%0O;O5Y-qKT5W?~PXaV~!jXO)H(iKILV8XB(%&6IXWAJJftLtTzA0u=h>iVR9<;~J z@9v#aIgUc>kG9B3ehaaWM6Po602YcJ_3WusiU}+@Sv#OCZ%qkSX7p!`Cl#^A#bQel zY@m5dz=wa(?^NfQAKAsjM=mWKn-y+z&tAO3b93}ItK(3K1^XJ;f5H^px9|C@j&8jG zlQkP;((?sJbn!2ab~KtSb{cQWNt-cGHWG_BCHYR8bH;qrrujSrKL50dSgoS4jvgAS z5ih-s6OvcgUr%2cHS*FJAEpmFdSMCsvz+`W?ZrsRl7RFT)`z08#Zx2R0W^UXJ&5Ao zZ&jouV_B=xXDjlf@m)6Cq_QIUkVnXEL1O3PKXS59ZL{*AGuEmR_p6@ZWXrwy?vM9` z{kzbR;j46qN*96Cot?xbAgqfg#>FzmvOM>P0!N{MqB5c%Cbh z%v@9VKoY|y1FV#O-0>z{|gfdTH zF4%xRby4@vEuF6i*vJn5E(wmpePdD4gl8{(^nm?snSvYq2$Uby%&NbheTnX}Q1@M@ z*#QhV*Ep&82D06&mcgBlS;co4Uq8C=*-WB*%_D{I;`Wh$DC{&m|Bnc4owfDc`VH6B zZ1wBLZ{Lg>o=(V|5$+kuXOzaCiUt%Lz-3I5?IkXY$S^_AE!dHyeWeBgKv_?AE7=>b z?D)W!V{8b?V=AfuCo7yBG;f}ormlKUcH|9aRqE((=#mE|+M9-+6(%dJOfu%eQj@G> z)YBvH|GTh(k}cl!H$aw$8HChX#8-@6gqH@ebT@E@E1myuo90XZaK0X5HOuGO_wW%PQIjm^3$}fa(QW750`oBt2J4$i%M#C+FDWq{!&wmU1!MM-I5BYD* z;^iDT=;;R0oX^*DsVS?31!xFzIs$s@WRKu&rmjcDC;-~6BFDM9^=YdWcrkRc@0IH@)W|mOp-38wt8<4NXe^cOX$Hzr{EeU*VxV6c zDf%(atwB;r%F3b>Fww$$PDCz@%>ZLn)> zsT~%Dy12RkDxI)`xq6^IYLXKS-%H232>+T0qvp3YSbyK^h4YZ)X-Ar`X?Mc~#|jFy zWr{(M*4dWK>I+iJO~xc4v*QZQAcA~Uo^I1NK@P-L2RTxJJx-&5ZXa1cZsyrBXCLlhtd&nE6$L<%!&@g#rgR zN&c>Fsc(1Kwb+zvH2G?}NW(}LItYU@U0iW1epbQt#2zqBszCXu1qQe3>WiyPZqBtQTN12c`y7%`rax!DoDi&`pJ-HX)*@hS6@ zaOC_RMJlF-$#s`A63IEAEX9k(ut1CTg?|A1fbBa7Scxfpj>aSCL zpF3g>tzD~IP<8eZHwn?NlyIKzW_915t_<2v6(~bx1phcYPn%*9xO4h=K4&jv{hHC& zoV`v`$Za6+rR0~$Hj_L5k1i3T&|!;9K+P4a%WA=R!rz7y+2O}X`>!qfMGfzl%y8Wr zdtdB%dH5>k*2&sO(GYh7@Z$B(#8z`BE<6q>`WPZVL71tU-+I`CNrmVX|L8<^S-W|pZ43+T&|QwSqPG_D!hZ#F zzfB+GOJPzNWlPeK9|^VM@b0q&whIv7oMTCt-S>U<;K$|+%342FNW@{(-Z#*VBC{=Gyei5#iBCQx;LRHE=Xt2Ka#D>8LM>1v>zm(2s$~e!_Ow7$; z8EhALs7F&7lb*L>8~``C(PCQ`Wub7ZUJvL=HP+p_Ih&$N_>OJbuAETz} z+4I8T3e2Qk=y*lOIgKg{`xg1A%K3GA6O&2F0ad07UK!pxNAmj9a)9ZhDz@{{c2Rk2 zb754S3!N|+9npAIlR|F$U?5sUn?)EgpxY7(6^FcBMvd-EUH;#b=TMKK77JC~P>!>< zbpiS%?5)wN63b6mfd1hFZjHfoou;5BVIL%dI#sgipRvLoFvbZNcucBV-G$$Z=3zoIoo8v*J15Qvrck{%icKk#RLp!O2n0uWwZ3ubJ+- z)vr~lHR?8D2OWHlQ$SI7yjJxjwp@j3daXga*#4lG#MR5)_b3bdAMz6h|26&#tAC^fn?Rm1O zQiS2B7&)x2mBspjX0GLrZ>8M;hBbbc3Ws8Pd5YQWA>#@_Io!NYJ{rO_bk;1)YP2T@ z6#^cc)2zmVYM?-sbapnknA0~u-UEPU;k6;GfO=>?5V+yDR`PEnmCOx zE_7YzFGmG62HAf0J@$h0-1~f= zWm6(96+|Me={_jpK>ftOxpX~|+`PsA(_7NABN_7J(;Y$A`TvgBxYl*8?gZYrq~{9XC}@_*Y{peO-8}w zM^a;}7dB=?=_*l(4n|q4!@Wi-nvnVb=~eu$6k{0A^Z2?jlnwT&XZI@-P0b?sL zSe*4Aev9dhPFi+OI?tK!ye7kM&u&MEh1Wvs_|MKO_;J50TUkEVu*9z>k^flE4r_u0 zfAO#V*6`qQ{Tgdh8~*VE`|r_`S^Odv1kPy`?LG()Y3iZWEISb67A&fKv!`&Zt>569 zFlei)G7*P)@Hp5X#N(tDUon!`Ie7T$l#Fujp)GD&rm2vnb=wEB*iTSxCV&1BhPy?)$Ty)54SZK(XAKbL{f0Ns9>^F4^bohivJTI>HPVwe z*Hv9CA=*z<3Y_uelygrrK-X|hUX!K1rU-pA?~zq^zSPT8og>w59H-fALG5MD+Art_ zjXS?tramkURQ|}f;&kW{&?Voz;P(*<9DQ{)M{5OGhg{X=lFR z5I7FLfttL9;y+U!3RS`#Jdtr529s7!%IDPb-%(!+v5rCi7pjtV~?=D}6++@L(xC~T;7B2{cObU&l zXu7}e*mXoV!OKf_4GkZ5Z3L$2v96coK@1VF+(2>@;9LiwNstP7?wn-~a04-Zqh=Mu zI%R~8#9a3Fi?zVy`j4tQE&NT?H3K9*emPC07O3l^i0GBvQ-(5D(8vEtT)aGr$hQB5 ztEK1l8)#8DD%u-gw8xA+MEl5xT~6<|Oj89OQi)G&_?I}E4usH43h_)~{&S>Puwr~zvWiMz_w7yW<5+%lq(<~+~_ zy=I*|?)xW>;MVYz&ls_q?VhxHX|R5_{Ug!2-V#n%H9C7{V6>H)SIKGI>u~1kQG`P3 zpTa>d__6jao-Z25hs&v$Ga7K7u&(0?t<*)CED;*d>&13{UGL6%@!8RPMBiq7)eGYU zWr?7v1$W6JsdIpk1*TCqjYF$>jrj^p8v{kE{lUyhB0%Vr>O*eYI_)Pt0Xh}SuuQ!{vP5m#kdUE#Ty$0uxpw9|f6!mNS|8TaD+_yd^(LH`xX> zNqSfMGnY-C7tB<(Wj_ot-6bF)d>z2$3n3+js z`9uQ-4MOzc^*F~yq_GY}m&7!#f^)XOjlrtBz>hHHjrE{n1tqOWOyCnnfFOG?ES?HN zI7Moum7AuBQx8!$pIAFz0j7@G^GbRc!~X<`M+;5HKO6oGzJzhd|5t8|xxcFabA(4K zYt7uBc}DIMpwqAw^4d(TQG>Y+&hP;a+O0!xt7j9B0$fy};~GuED)KHxVz4RYitg0XLm{Zf> z;V;}REm#;H1UvrB!Jd;A&3;X1P{uBAgp>ReERz0%BDcJTpl3Lnmmr9iEq99JF3C!( z=)qDoFoH0mVabBi!CSCrL|z0YXu>XcT(=)_;5dWFVlcY;7VqvGaoA_WXBs{_jc{-0 zuO+RkIABa5hYD%X*Qg^s6iUt4*O{SXO*^|Zisi|2#zR5y9vTI#zE#N?lx&&*dX*6> zUET0DPuxa^!_z?K*49g!VlMZPS!T!(2l=gxkjww-)>c?QE7%yg(zVtmA%eLELlH<6 zZy2g_+(vK}Mn};Go8b*QT{qPdKFu`yk@!jj3^+xR`2GL{*972&_=8{f(M?lYcCY9M zuCe6_%4Gm|4vnWc@VJ5V^4%k83pquI+Nq8Tf)BfVRU6RIZ~d zy3fjb^fjCa)~{s*Ncg%b9f@1=G4r#wg5EJOK^;=byd+_@{{S{qXvOIx@v8j_G)s*9 zHAD4)hsLliseaDdS6Fr_=LhkCBM-l+{81H=@n1U2CyVi>6XpPbnvMm0zudEJcnF6; z!%N!$McnzQk$ZH&R=6K??jfh8H(2$OYL$yZM_ynrdT&mStI(vSSKD`+{C$rpC>QlxkiJNKx#><^dR0n5yL+@D)P#J#qHI)=OEU?c6sMmU4FJ zKvMt|(RsYa@Mq-Dh;McbQG(Cu4Qwg|D!lW>j9;++@8MC?*2~(uBfT|@6kvWH88pUhty*qI2 zjIVFFRCF;10^qL*3%~R%3m%|;rzsFELZ=+(2Z{t*Sz_C-E0Dvc=lg2dD^U0m$4a!+ z)yt17Y1GpAD!NMX^}lEcU!(wXEEemH)Gu&=Vgzi?T=N28E}qSezk9k%V6%FA*Hjt_ zB;gZhFZ+%-KkLzo?TQ|A8>Eb=Jy1)u1u8aVmml@oq$u^x=p$#*51xJ;b)VPeKaE9A zU#{w3Cqw@LtDbPyEOLU**n7%z>H`JUE|C)_0^w1UIraE#pCm>8ni_l$iLoK|a$q@a z06eOdzVu2d(_5%7!eHi;leL}Va(Q_SYS~RF9{KxRM{g-%s(6|{jTkSh`yD+KS>k zodO)H=r5xph<@=rW=oh2u=x%s?`^+H>iT6D+f~Fq?k#`j_C6^?e&eo%0_{~?D^u0&tG!x!s`EGr&amMpury2-l4!P&|;3}sFOAggFYyn}Kp z$Wb9CuXp3Uh*KsRx(4VskhQ+gYSMO3j$UE`0azHCYimy@zIHy~CD3q?k)&k>28f8+ z!bw`?AaCHmGt&v@fvg;>oJAjCH@Oq9p-cej1OI*XTxlu-Jp6mRLGM?syS~jW={10& zb26}@A#x&~S;sc9ytz{=*IdqSBwst*5w6WLU{|q^Cxw99r-`XDbSx{v>JGPqePbM7 zP&6r%BG!j@AWDA8mwG)~8Z73qbbY0ul zpmF1$ax4D7%B|GDAVH_qdVSNqZK+J`F)@}iW_)Wu1jC45R~daoOw3vp>Q%6AVeoR5 zUym(vx@7}{`pvl`Wu(PMN!y=P92Sa*D`9(N&i%m?0GxW;zvtPjV49g}4_I4j#b9Bi zgBqPLF{c1B?dAU73lMP>&P)?kF~==*GSy;naN-0htVofM$B6*gtmqoy?3o5I>ig_W zZ9>&bm`&Wn#hrHs;18UMmeD~ldxA;!-~HpPe3xc#Av34H1fb4py`zQv`_kk#jmgL# zh3;uG(K?3ZUZPa!)abw?RiSfvRZih$b8W13RWy~G0YB51sz0+(bJEL3 zyB~*UIze>grd+m#yKFGrH&_@T_!Gn-PS@;U!kjSfN_B^$+)sYkPQyS;VXJE9)J#=u zOVj=65oKZ~9y3n!OiJCbE)+rcIMmx=f*n4&JtCWc2H5WZUNKm4N7RDg0;jlFO@V6X z1(9RGIy9y$qY7M=?{M0i)=5s*@c)QT*ar#qKr^mzhpmP*B*9HOJXYP(#@#v_(Zs!| z>P?l6GPL0PkJ|rlE_tV=Y&H@qE!a}a>VTLYm?;djRf7rz`Y@h=*Gd>bE^}@IbC%dj zT3D38JC+n-ZuNgz14K_MekLdgTJCzl<~?c7@ypf@afMh?$#h$i!rd&*wC^ZAK z^iSGY-J@=bm)qgzGa~uz!HBY`I{@3%+#cTrl#3)bK$(|3-5<1$?HDhKpLNo{$f60o*Xra-pHb8O0NgUHYCW$-v%kICqZN4=?dv6BntxK5R z4%!6tB`_v@{Eb-CnQZyEw)7)bOmqnS=wfX%&XY74^TTA1Pyd2QBrN|;r#dpMgF)`c zOkgz4YzWMtI`-ua0EZ_ek2Kw2OVd_{t8a{Xbcd7liC_RtbV@OfSeg;DH85xP2gFPkvP3GO zFq!K#bk-HcfE|(ppZUH1ykBU}Ttg_;Wmfw<*B6m!eTo~cN-Ya1wOcae?I!Y*RV(VH zWm$xPP>W&sa;NYjjKR=mC4QAI_(9Xb1eh$XU{(dLDk61Yb`mG>`|8~>lPqjzJg6%vA+gtYNtWEF65OdF=d81IIl+J(SF9W$_Mvl^2Imi~keVH=%{+tUe9kI z9TB9HpzWxFt&9;$+0(t74bs$V!-ABlw%SW6A&nhrnmUPl(7TnhQuqHkhT6O3**Y7dG%=tcURGs3O&lGE5Y0g0R92S%Tks~5$ z1!*WarKWy85~&Xpaj1KPiO^2dYclV5C~5Ym^=n9r{;*tV`8Tq^Q{$B$sc9 zBkU@lNq-yB!?{hK4_RPJot=lf=b}tFAU(Te-06d#WK4H9*n$ym-NK{aK=m;59jpK% z5CbPb^(h-CI@-Gp0>>+|?BNy4ckKT(Z;+{w+8;bvVpYwujQe4slV1mO{LC3%TN?=QP_^bc0r)mu5nFs9p{FMRi!lrZ{{5)9WPN?~ zA3P4D4mBo4+k}>r6P1FF#KCHOdI08=0R~TM z%SH?dOjP&m>i7-IMSctQm#EiRkR*TaxnS7sK4 zx`3^NBn->WdXXL%AUs% zeZQ&-loXZ8ld;lA?G!80#~V+eIc~)29>ZQTF%SDtMeN!ucdCp0n4r`#)5PA<4W&b{ z2OiAvO)C`5OrM<|>jwDYPP0`^AQiG;Mx*Zy(sG36D_T0>s5+en{9tA#UB0rACT5f_ z#}`QOS6P<&_QxO8kXF=Gkcg20)L?fYPu74x0Ez7h_?>w`t?_o0^%^PEcUC?eIz#ntYk$y%DO8oW zg4`(QZ7sS@-J>dyWhVnA9&BiKbtEE1Xd3I2CA=#!hIUQZ?q&j$?E3%wT6iQBX>To~ znhfuSc2!|moEw=S_I&*AP@viTB7c7II|RqapO&;JivnVetV0>li6_iviHT9P(g$Y8 zCGPk0UfRMw79tb>C4Q7I+WEz;u2t#6cy&WcGfwd)9{tZiJdM^B(}XTm!x6H`;t*6U zZk8`|y@DA2o)RhA4E;nH4a?xJ|F%|}YjzOkw65&RUt9>dR{cqne+&RfIqBzzYL&wS zS=p=V7#L_QWz31YwQ7+B8q}!cL51jX^q=qq~az zNIq-FG)$t+K2{f#By68_01C9q@dPCL2L2TMoIP#9T1AUsdF3oTv zT#Webf=MbQH= zh@^EuP5&Y6K*J)!>khcRm;&x_7#8bXi`5yygQ6j*98=KMR_Kf}Z3K102rgr!RF zUzpM^_gDe%Hc{!0{?kx36NtevC?=F5n?>ROE{X^PCSH`b89l=*FscXPvvXc@UXlBv zT-8qv5me%@$)X8F>hO@0JyiZS`#UQW840s;CuT!Y*ny2>>YJkhkl(R*uZ^)ESy&h& z3Xsjaj+psMJ8W2a@`}vPfJXE8H+>F1z;A!W9J7SOiZ8#NK*3;BpC72W$q#6l`Gd2x z2yuRk^3TlE*zuad07vZ*32-cGy2D7$l;``$%vl}nsg-g_`y&4w~ue51NjA8vBN zSIm1$nk;oi5VbS+Ml8qGJ!{esOPm zQc{@!@KuY9mXaue-YvhCzS~!A-9NzZg9NiHGZH7Kr^%Zhi+yD_y(t#9_U!K`Uk>dp z_Kl2h8sYp+0c@sI$`s2yti*gDw8A3I5w)J{OWVg6dY3y%4#1HZnDm3_0iLi^y4`(-~LpLV458G%F0Eo)2$ zK3!L8&-X5%VFybM`7m&0pEOuW%yn4gyYjn}`@gcU`SyA}NKy3iKOlv;FzL{M>y^6c zxykH#lo%qH7I|F@@-sP3z%=FTWKRuou$_J}$|q2VPxwS2ym|7ly@kW@ri>|Vf!M6a zzJKReJ|2_!?_%y9d?P}31NR=m1-v=wn1!C}IQg7Sf8{fLf9UTk!@fJdCVJxGb*9hW zFt(PSTT6VbG~luR%>IwEKIKQ~bjhIk{6H^8%_!stcp2V@y4%m)MwB!18Qfd*&(C&d zqNl$HX4CCDk@CcbLvR9)cxd7@sd1Y=HWD`A0CX+pj>26_n ze`wa=fB4_j8UXU#G^j^Z+`xZL-8$S`eiqQ3C_I0NRJBQI8DrR1uTK{D%=q*9;UEUy z$Y(z}-1S;SX1PC8F|r3J_Q6BJ#0P7!v%8xCM6ifkuj3;kBJ|AR$9OE)ty{AGulwf( z9vN{weicy&QdRkA6>v{AGQ}aX2AZ#n`&sL)CFPza2S4?K=PP(ZAl}XH{rsj4MsGl9 zDl`X#%)Gd~YFJ_>*Z;>b>-p81T!-1^TF3FnJN~|UhJg)51{K$OKTG&h({q|(`pLK7 zWu~X6&+GjGj*J%^K_`#ufpBOMu?Egg;nGJdcWZLj=V}~$oeiWlUXz`a2pU?xEtp?k zR_$ei6kd`8^Z5TQ@EfN*QDhkb9bkEX{eDg3T6>uWwyjWS6NupT0*ZR>TR(!Lz;(LN z?9fb|{C#wWp@ftqK2S-FD2Z1~Tl$>iJ7z&E70D#PPjKM_i-IJde(4)p4r$&L0Xn5_ zwqpOMH9Q7&K97W*CbYYT#l1I;5MWl&cCy;lt-xX4Qf9Kh%Uyks@afupi`cwnd(kmi zZ+uXy@#!IHuyA%HLf-2Lb7yPq*xwtG?`mv+wF06yUVlu-<)SP|vxRwkC)3l~g zbmLj3ZcNTYEz8D=o5QyQF;#FTo23*n_ptYjeB1?x@*wiwRtyRG5Kq$y%97tNwHTePfcbwRqBnuDJ~wifWEmc zcOhlVuIIZLXhQ1h3l}GKgHJH;>07G#C>QoKB@LYK-jc?0PqLLTc4Mkm_p)4-SyPDK zd69d)+hRxl8T)M1W2=rnpk64+oE>BqjvX8wy(b8#=ypblI8FSATOVbjY(1DwD|KB^ zuNyOxCJLJZ-0wjbjCkIjXl-!pH_ehYA!T}@Jr=ID4P7B$F(cA z?k>jriN%JRID5>h`lqyvQaw=p&Z#g3rWu(RyOVTvx}(+Z%<>Hx3h3R*uRE6|a?$P=1G^R<$5R=h2Y0$%+aD7^q=9U(#`xHTt1v(3`d^6f$a~@o% z=OUAXugUi%xplXQM-I(n6t(DXK0C$<$ zz|8i$c(DHMmA6Ab_i%2CX-{;vX5S-P#sxVW*kqc7Qvaj7}h3FU zO@lh>-w41Q86F94fM3pheFX_Q2sP&TP?cI$m`E04;=%y#Sy6Hw;;qicxEv2*GovCL z-`^6%@eWa$E6KI4b;u=;FZ}YzPo(2Rv_P5Wk#fQ>FNn*=&MD>o!E^w^BR(EfN+ZT- z@40JIQFZq#m%9@_PaF=XF>z~WFY{=pPlAmeJ$!q`(}{Z}AlA9Rv6P}Xlglc@`irof zoB(mVg&0e|Dx-46J)I`*C0JfTLG{91erX4Nfodp{EV#CbwH{)2e{~Skka7+VQ1hA^ z?)zs1QLm}XmuKP~t?EEa?$^S0>)w#X?y|PUFT;Hu+lxgKej%lY^tn&ZD)RqZUeeBc z!M2;H9p)CttuRi-kk;kvcKa{+^We++W$H_HzMOvjxtvw-OC7pJqzq2e5$~(~UQ>+} zDa2AOWsgf#X@uJ~X}jo|BH(`{(Vpiib;9=;gA~e5wL>E^ohH>YjCBD9nP<(vaNuI< zhq$A*2P9o2#P$1E6Gx%_Xfd`#t4hDj+M?ZBI#@Sf^FFhvOWGtU#Eh0Tag6doR~{|o z!&mLJ@$%I17j6Wm;OsQHB(em~{p1pPhGQNviK&09D$RNah${P@09^ zhO4W8xKZr6`}dDU!0)J=^YZaW>J$(&3Ra=*cm+QN&oXtAcc+#@;6XX4zb@8LL~(^q z`|KM1dn#UAbMnkJ7FQWq9(}NOG*R;H_S4d!zezQSm3Maw!`^ zK4-kU>^qEn6Xuh0RF_%?uO&+d7!lq`8{}st-P0`4;d^BCKA;MZN{*5k z;M{o7_-L!&3i01FlRP!@by#kcSZQYw#7ty7WtUz)pD7QkxE{k6bF}3x3cg%@XL6hE z9eJ$lGv^y~3Lg(DAJGOt9mj4J?`3Pq7H;?T`lmuRxxvSFuGqFse%&Y(OAyUuy+dOp z|99$n$7jA+qeye@@G;T4MTi`HZqwN00O8|PUH9yAh0~u;_e)73A1V*Zcp3%9pMYDJ zmAwLPqqsLr5p}aMT#@5$NswAa+>Qw~iceS~A zsvyB}S-oFAO0q~RX=g#Cm`=C?8W3+MNx9zTMo?2xU5k&|KB<#z69|@2a_LKwf%Bt% zS>y!tW}*!%)2d`mJbV-Xpj*~$hu&+Tm0~}z583+P4ObdV5cF01;roh^hEp8TLIpcbpCbkE&s2;?V~sBIrh#`wQAV4fPGB37#7?^}F{<1s|mUKDY72gdf~ z`v`}$>|5s1obRpub`)k-C%%QUd@>zc6|D8ggGTmySRcgpR-+qF)`gV#_}s4xN{SD! zA`g9CGj3OxU7)OIeLq#_MBNT4+{n3%*jtwGb9hj6YA`taJG9la!T&Mt#lG7~P@A38 z?1WGJtZLId-XPN;CgUTYg18a$S36F0)&>)8s_(lxCa$e+9QgQDFJEtuhd^{%w=7Sj zoqO|~8P}+h|GNMPvZD2eRs2I-ps4|(Zj z`y9kshrCcz$q&xNK0d8{)6T7NsrTAYo@1sDlgw7NypVfzi;1Gr^Vll}P)Fm!>{n-> z=J8Kzd+BcrLBO$tG81t-RD%ty3ayy_<1zm&!Yl!GZRT)@%lc6+`*Ku}E)OL0f+%a8_x7FQmHX*p{$}p2k+k9Qrm* z-4|Ucn$`NwZyK59N8o6u3KmWl_ttn*$6m9Yj)@ZWSS+bpE=>8+JUuk@{KsH%&ZfL+vl%qf4nEA4IOP?u#HQxlfsJR!+T57xhU>*rjK$1g>yO=@M@0 zlRTL(sY-{p2wn1p-(JwspM2B<0_S@$z>Btu4AFX5 zxmQ+Sr!nzjSMtj|mN%tb=Sja|21u0hk-9MEQnQP1lW9K>e|f74$`{BibCkGu^qRH# z(4}zNnlHom1H6uISvvDRFb=ckl-;u0@07*ZG?5Es_BymS`QM)D+W_yKA)+dnk0cZU`-$! z*@1Jz-{p8Wl(#0}m*3{r$el zYo$Wr?4FyG`Z|L>)AfG&FXOn&!9MZ`9@C5i74Ts5TWZVU?lk8q^p__#sz(41^r|%n z>_=ZDyqygy?Bfc*b%Mr$ys-UHS{#oqK!MlaEBG(y{1hq$x*q#LP}SO7>b4pV&_%@yLJy?lY+dsQy^N1v!XIwThL#HPutD(AF-um#GuWmgX z((L9RgvboXGXJuLw~mD^N9sZ}d5(ZAP{5)aFu z^k(l%`yM(!MABuyGv7K?Y%DQR?^ktDmw98Dr2I_GHEJzT`qN{Eb|vx?hxvOqAke*) z=>T-O{q?x6&+%u0TUs4IAIqy z6|U>TnT12RKL+~mOfy2JGjn_Tsq4eFM&na+kA%B!LLfJM54KGaTaobmXPJrnjX$SL zsjS<~;qR{A=QJKV*W})K*3J@2_K@~BerrZ;u_Nv?%w4W8>G75Q9BEK$=LVi0S-c7X z9T#IA$F<=C#qlzm+~ES<&i6GyO_YC=$fHx31~ia%q$^~DUz2-<+`SgD%N?M7b{FA) z{$s_ucj;qv2#T_^sCaQ>x@_NdF?Qhsnj5lNmB#^d&{fgto@>HV3UTUA$})k?g(k%0 zIWN0&<31&c$CC9u2H%=TR_)*Qok<|xZp-`R=<*#nmF?~wa!-F1ok3b~k_t;3t+@YS zMMYbJAH)aOnX4H5u)Z$kbD*w6QaBgyY1q1jHAGc@WGEqx-C!?wUJ*xJ!^zOT5<5^) zz36M%($@`{rHTr(6#=DOjjjB&^xl#B)U@ZS$zQ3Xp9Hd+a0iV{t5bp~p0$4U@i*@k zYfTjgFFHPS5)HfpGCObWgpqw%Y?3n>=YMsVwE73@^jl7cvpON)Df=px<^&mn9aC#V zPv>}9r3T^#O2DA}dGWa8OoQ=IMR`@#%q9{;e#AtK*5CbG7wcGFg(W0dLJJVSCo1mQk(!yJm z1KF?>rm}ScbTgjRw2Db0zGWUmud%Z7HXB2{Kdz)z>CJ@(PnUD!7~h>C)MC?PGP(x7ysq=rD|h=ib^bazPS018MqIOGgHLwDD==YF2|UEj+;uH_QvoH_gK>$-lmU0Aky zi}}D;_^M8cDyK;`u7f%S^at-O=pwhBV258;!QcR6D*a

L_Czf5$uG6Ew4)TG%y> z7}BDptk)cZE4YoSI-#&qm3<~{h!dIKuGicC7%0E%9!&JZNk&mU_h!~oev;^ibyg1Y z8AV%keh)BEGaq_rOK%y6!;3dZa-%>2_EkJ3-}SpH(HtBJ%;`6J4GwpBrH$9SvNc11 zE&b)YKk*CM#q6P?cY|a8SA5{ajO7Q70X+$Gfw@tqKD5Ub15+ve9T1CE5`ce8at)cH zHp8juWP0@=Vii)-rq)?_$3W-{;WzGwe^6}pIh_Ru*#qy+U<|pL$TWwip3T=F9a*$dI2vluXaM{$(}KQ_?Gm) z;9ByFM^p^*6*oePjz)r79&`(k$^-Z>AgCqxs;0<4*&#*ono9@qH zW{W=U2$Iiob>vLXQ&m^LBY17^`nVe3yHmkx`-gN^~XwS6oF7b zpWe&oG-G&%FQuiSa>0ni=BagFlTz~u1Q1B zP@SojH>?-kELqyhYurw1q&qD*ajtUR-*w;Y*ZOUn{rY>GxzF)s-S4+sm-KUy?@~rQ zK%Q6mwb}X@y8Uw4fM&*XJPB*>alZue@_HK^y?;I=OCZ)VY|$E#-F!tegBd zCZbm{J6qwDXi~?K`7@m;HOI1M(txZ#08;q(P#Q&eo5+iT#GB8&=kXuZlP#{7zkYNd zZwZC(2^lUm9#4@#xLMEF*+l)BV|b~2Uuy$g*{n0>XF26|R(69&=V#mb1(&F9yx>9q#kfed? zG;FEimsW^$?Bs&vN0G8}UfR?9HovS0j^8 zI~Tk$@A0U@@R8Lsmit^S@f$E+NK78rAlrXn`U$*gM|JlHM;p?=c&Sx zqZxn|$iaSzgcxd+-#`>uC)-q-?OMUkkDp&`t=%O%y_QvdM#?aZlscDfc03P9VTWUK ze0i@kmD0X7aRhsgdn+`kakk)ChC8*d(~^z-oGDJ~PA=u;3B8!9mCrLql82xOT&oS& zZ50?$Htg&X5BHw@gDU!I1w*cMF&yrqbrt+|M6PQSYA_Br zxJaCnR}7upq`%Lv`#uSsF|cuie5uigykZ77mkEL-)j{^D`I8gQDMTPIreBfT)hwO@ z5-?uwO+^{M+ICl`o!Q(PgIQVws&ukc>z^MYp-ugJ8wK{~)M9{-_)?pFh&yATXu;r| z`rpunSfG^7-T_MbGSf`}3s2%WaZyT*pX|adq zht1y+bvY;ZJ^1~CX0kAFns76q6;%M$k{fT}=UjeACk=Hn_X&9q<`u(mWwADw*EE20 zy5$}C>66)w7P=x)H$MN5=9BM2sK@Y%So@P2lkZdQva_!%r#_cZ-iq-t;elsN((ItYW;Y-Y zOTe_EK^Zk&Iouuy{hJzC6;5cfvDUc#oRdp3GHa&9!%(pynd&S$9$D9)IrF^9!GAdG zR0LAOJ`o6A{wXBHb+-Ke^tgD_ZN69Jbg^*DdUZOx^6W*>H2%YrB!tsX?enrQ)Y-Z1 z=?b!HH0$3;<PKzl79crL&b{#9w;kP82n=~uMOw%sWUk08~3U|-Qn(lA|Z)$U17`6 zSvw%lWT}c7GGoiC?Is?f;G-GYLT-HUK5<$4t7PTX(L0fwJ(tc;79C+p$X5dU^9V}F zaHwd0l@Z#8f`C~KivvwNT}ZC6FpjFY|YkN zlXp=~%qRN0x|thCHFex0VXy5#MCN{WR@O1))jag_WBI(k`eUqCeWlf#sb$rSD3s54 zl@tk8jb+Z98hMp8NB{G%%Sl9Pe^Rro$JWI1$Lmi2mTbSeZI3JJAMY{l&mHIUTkO6$ zHQ%5txO!uL>bs2L-`qgvzXIdAP%SO!5Ff2`ZR#bZFzoS5qh#mPsP^{s?=yZ|?q_Cb z5)s(>z5cJ*V5H?EzPTJDqwYTjS#6^Fk4#Utx8nYPb)@KVwlp+&D{4zIf&@UKS_kv_`Y8dwR-r3P%DU#1h-l-Z~{< z`|pjz^N=GB$TN-!Nv1cu~>XYYpwj*v)|>jcRr4I!aokR|AI<)d3#MSd&-rm90?mM18p5)Ul9JgR_!$ z7_Vi&?8)w8j^U4~NBSr_%*rYKl!`3B72OiBeJf+AYVYI3^Z0SlBW7mvb|1gv^k?5$cX-E2rR22jzN}i$wT-!Iy2x@Q zO!z)N$Qw}ylcZw%jFdR$He=&hzx6!l=I&g-;aR#Hx%<`R$=l->+yiBQYUcVG8Q9^- zp9!UJ=gzjkh?2pO$P6cC%qchT`CL)}vXgLAsvSslc|pOhc{h0+?0GR`KTaFH_VQdY z{pATCYVnJ}>}krXzOi)+d4kryVECa}s9lT&B=-J*R2kgKexm$|QLWQQKzTdrJ*Ofu zJ+8V0LcToE3YWjGv>ae4(63_Wf;I|w8To2!B4F-2s0!S;iC3t`w3X={mFKWkzd!i} zxfr+DAtN+^wCe-c&zJo_B0rUes$o1Q~C|Hw&o|qoi^lOh~*;~5zX0?XJ-B9 z#7n-%5_$v2I}36xz5AQtjQGvXduWH8%jFJ_+S#4V4*rKD5Ss%<4%kXyyxDhbbH~*X zEj2n+gWws*<<#W=nLufa9*q4yf2x}D2G|PYJg;cQJ)eDN*ZK?wYB}H2eKPu{FfHfN zXQE#>jbR09>n1PpAnQAry!(6FF-K!lnyathP{z<4^O=JJZ`ACUEG{l?Ha2}M{CJ?) z@BG*qpaelhpHlvp;Mr%G$?!MtE2_<`kvq#-G_Jc(Kk2QhZ7=+53GxARh#1X?D^?5_ zgBg7A?051ffq7h1@xc5yvBlaI_mZW&!?d{#Wtib@^!8y5o(67KuY;N+Ys=nX7}Z-CAg@<+UkpYkt=&{5yOrSR7UISq_nsUVs@AN zKR&V9;esX5#F3_B*!^=GX6UI(b9cjEc+7GXTlYpo_bWV=r@ zFBDXV#Zpx>*^5ty*BIZVIbw>_jD^mX&mxnu3cuEXr7sqz%Yf>BbHGUYFv{E9y(ZCJ z#P3wR_{^5H&+weq_pW$sK@I(j(mS+D9GBDVSHbE8qOfAPm{)`}bW?sFzt%=^GfitQ zaQuAF$WK!G*PTmWBoW(}Rg2$IQ4><~nW6y{Sr(l=wG}lNL5K60Csh^5P!#!X!-Xq( zueksn)s4xjB>~#aUlP8jm4-?*mtsYJO&`>lN|{k8)UN)c@&CHmGr;xRsL>TZWF(b2k84l`-{de8gFAZ<}-e_o3&>D*Go3=p;3WwSavkOlNiS-?gL zI=Pb~{rX64ZhhuY`j*0z{vH1$9`%m3x|4h~(ku9|FMY0(dKv6@@x7tJ&NXatz&Lrb zTEMbK(dBca?HbLZi3gK?Qk~P!zXOJkueImyVwjr=&GSB~I=tbSi&V9NzpQ|T}xD(XBRRP{LJcu-hNSqP6re0zY!D${GPW0&UI>RjIgV5{78 z4}?UAqZjDKK6HMr%R_#WZEw z4WVBt_)lqil=v!?9&WLYpcK@_V96(9g*A*<8>o8s!eg<4qz!Du=JZ7^1!CXi4Q4a; zD&_6for?v41QF6BO5mzKb4)8NDoL*bZxY`V@KfE}*&$2k@y8?sA$guyxMOOQzfQNt zZ}{%X_joOkwPES6r$Fk#n8o257oE$JL*sUx9?|dmJrbHzO{Hj=INYJ8z@srWc3F^F zqmyWoAvS*bp}_XXnr$m4Gm}akHBn(J+nLC11S8vA?%$BnDLI!>ivRcByEZ3QM^*i6 zO?c>18^vD8>k_+@RD+eel&#?eF0uSpC1q^pZ$$pV9`W7XoU)8y!nX^P1A_)LVsGE2 za=Y#IORS!tsQC9Q*!E}BC$7H8*v#Soq1)a4c&8%Bj_#P6nErNj!f>vt>eYp%n3qZq z0LRsMTuX9(&q~@25$9@kByWp+Hmi6XU>tenqjutWX*2)k2&thz_ z?PnB_EV2W=D5)d1bG^@SUM{2h%3I`6uO$kAIp}OnQ^r%5n^OW{en&A?VD;jW2X`G% z@|F^~kumX*&aB^=x*S;99GGbm_i;s{coh7pOzay3Tu(2H@4PHkOcJY!^Se9=&a+j` zvmUvT5nH2?D+3V5+x2eN;nT}7;YF@1HLv<3Y>F=E2P&tp)71D(<2zSo98!GKR-E*5G%tv&WN#z+RtO=?14;NpIpoL zi6hoAP?DJV;LE2-L#j{E`@;Ty_!sAUu4+i(#bnhdO4VfUo9i3XBA;9qw{t2ibw+ZO z@nvVeYtk4gUT;LK9a1VSB3|uYwCFele-nH+Dw}Y$r*AV>*@UI(OXh=5U$YpSZYCjK znfa+=Tq|vlqEpmicI@WrB68i=Cm?O;Bq%zdJj3tVnKLmt*i>+5-?@-m^j=IT^^I!fo$Ia70s6 z)1&nGV1BHydRe*03 zVlfhk2~*MuNfU~gY4ZK7UE&j&0+bXqLMbxYuic{!?1pm(UKrKWWv)*Uja*)!hnM@R zz2pq>26nK-il*l$(WM|cq+c3t>jWoq_2as)-`Z@NtP zRho5hfZ{0TVuy|Q3m+hBoo<}h^nHHG6Tl(dxcO`hs~OmM-pFd3Qndg0m3TR=~|_gDE#YVnk^8{P&)Hy6ZPS6H7OIGX>!yjl5&xd^-ydhx!M4M(yc>|1>Jkl%g^=HMW{Ojm|vBx{UgHCxw`f@F3Ai3{rla z+#6yric4`%Ko*c4?y@QZO>+6P>H03$RM@{qwRjMxPr}b1zn6y{cOHt6w;1iv)zPg^ z^2mQV^w__UCPq)^6xzE@$BQ+;;GildLmJV4Lh-vDZF(h0H5-odU}S8@oo=2SkM}?O z6))*4zdC*Lz`W;>d}B%|tlHjN!J&+s#6@IKi>Z|NqG}~0bBPO}+=ChM85>CwuGSjW3X@D`$Nm^5J+iK z57$pVU7p$oO`A%{15CAQ_{MAIb!8@x&6!*e$yE6p5_{_KZ4AZ|Y1*@>{EF~(?GgW(m6EPcL+Lc0C4{L^=py( z9|I5w4__xm8|J;jqY>S8FWV$(738~)u%1OBl=%Jqs6pN>$yl*i7`rBxrA9dJ`TGwx zNbWDZW}TD=bFQ2h7e{b4EnE7mFFcD{kN(Qa!V&g44kTKBp0<7>h0yzG zV@d&ZzA>Q6LVn#7@OKP9RGzUIw+Q*h@*OB}<=l3GvQ@bNdU3x%*Ewx^K8a4`vwE%y z0RXW%D{YYvPBE!NF5xF4v^eO%sNRHj1x?PuXgC-v@+>?NCsNwN=9MuEeQ$F^0pe;GgDzh}oWeJ*V zGbR~raPO&Qzv*b%0+j49k_rExZuRY)CVB|VD^Vvd4)cc+Z z&eS>wf^kefp2s)`=ro7xTrpU10<+tE+ig+Ue%_DNxK?EnL7>)_0ou9@|H~72wIf=^ zpxQ1SoEb9&6wNC@)|mw;sbuY9eL2AW@fGWqeTw5YdM$Oaf1gYDSHN;#A`3JV=#Pea zfAU!asEyx!Rr3^h8m)%26ann^2Ba^f0h`4qob}`sB=oE-L`mg zoa)T~U`%Hp9D_Ro&bzS!c-8)l2U_jbt6P035{b*bKV@)ASIfQkvmJk2*LUA9bkxEQ zY_uJ+ELwiaa2uUtCy_d7>1THQyc{ z8y`L?Xkr&tT>p!19 z5tv10fGnbYa2QWGGSryEuMec0OM|GtY@Eg!8~`qH3X;gI7CXQ4!}hJ5yVeZ-K~j%3 zkno#cffEaH@X-oLY)J#eYM8?s4od}?>Iz8XN#{1Imu*I!>sFQ?fe@z`dzb;Ls}JYm z_dd&P0k!U5f7%;|dxDcp#TPyoD#pEv&nW8iOTBr0{ zo{jfQ&uYQ#mmMxV{Aqh$ffo}C><`QMm0zyT26+Lmy7r9FO?hUB=$*;euV48=ie26E zIN}oS1E0&mmB| z&%3??ERgKo9wttBEnSn#c6T}lK?z;8%Zn~14uT@OcP^ed#{pTMOH1#|RUnmD202r? zKtE}GJ%>);f47TezxnDy^^VvD2%h;ofG!XNry(>)jM3v#3I@Ti%CUB*&QJj!Duqf) z$IoG!x@W*~rrv$N;u35rI5SPgo);J⁡;01`nPMbhEKICN%WcPNQnF=#!K)K)+#! zvz6QqR<(BY(e>`(nF_P;aYcLFT32rQ^wR9GJb{cTYyBU2h(RbDH!Q$!T-nwvPzSHk> z7h*%jueo+tB^Yiaiul>dV@@xIf-j_@tm2jWprK#VpWm6-doyK1%h;s6GMsJQ6*HbG zxIJ-zhle-6?j77}b@n1&jHvc+Ya`xc783cYt7KLn#}BBqAjc;7Vl5Ca zClD3zTl794+qG$UU*{dyV0E&049xFx_&4v|oqOgnwR?2i-qNlkl0H-HeVxHkc04o# z^fW`R0}={2w?YUp?dMIDsQc<$V4ui`9js<7d{;dz(k;ulCEfFljk)RmH&(SzjR-{k ztFMptM>SN{K3==QYTV@WjYXBA`zId@AaRtNGRk(s{!V8niFs^dRm_@-S7n#M!{XK| zAU`=hRR{Zu?6dyl!AS=*+#_2XD`a8tPg=Tj%Ube zWj68CJ?7!L3|K#Zxfis(U-TN(9^26>mi@KTzRV^oVFnjg0shl+wesM`&w}e4ya=K{ zDA`)4C3f?HIJuIK99=16hg;pQ&jQyL@Tq`d=&P-u4}|r3Ys?b@$-%bPs+BpCYmx!k z?K6-=Vb0}~Ul8yP213aqW&c-NMIZSIT0t^%=bbs-;8R)YBZ9SsO>>emk+#%lcC|&| zP+iCmf=?*&N>69v`VaP`03VG?5W+kZT=Mi1$j(s~IrfnTWtJ{kit*?n%x2EZ4aumN zT7)Cyw=Rdy*lcr(Zh7CwUIxP5_707@9h?q1brVlL5Yca5@`N}DN-<0-_nGv>H>S{O zD)6KZZQVI|03^a(+y~p#$Ali#PMGTi+KqWr_*vI8U*NjS=zm|X88Hk`6wxC>w(_S3 z!;kbKziKHsv_qNlPZ0gh?i`>23RwKx@rXK7;o4(5aOve{id^+BON`yI9r5~AldOeo zg}_iTTDy~!$1`#@)crkT<#0p8MQL>|Ivz8m92TvkmW=S3g_xA?F^HcdKinWNFudo# zVg_gfN%AKYpP+lTIKzWN_|CRNW6Il)A3x4}C^R^EI7pLp@A~N7{*A|r_Q$cjq60s( z{RByF%D4c667o&}45qgNluw(Upc36saX`6X0qiX-r6MfpXSo!Yk{+0T`g*UuoK2q^ z7S)t2;By`N%B;}#t4(~AKdK}%dF=zB8!N3xp6WOIAs#p+D3Id>Pgqb+$>vy68@pU7 z_B_Z^v@L+=gWvnm?m2xA0OxRA)INy083adBwu^U)YxMw2=}T}@IW;&(Ja->-U*U5( zCoxE`Tfo1T0MF9iBiyqeYy9Jr>Vp=+)2u^pcv zaQfp4DnMi&j937-Cd30cjUMg*aZo_E(%SG+&lH=-raEXdne>$DB_)kI(f-<_@WBo> zM$aBO-(RW-m3*XSbISaGOQlhA?-k(JBOPK4AdqQ%Qgl(si)AIKDy!u99|ErR_@LP| z!RN;>VgRmDZGT@NWr66S2zBy{cewuD7JRP{hEJZOY9KKNneq{B(`Eg$C#Eve(rrF9 zpvkbvz%(qS{!H4N*~QSD1+O(GA1z#*eDLvZViZ7fp{1_qF1>v2J-zbrqdWH;6|VtX z?at}hS$N05Kwv7V6px?Zxwx47>f;n4DStou>~ zL0(y@pbRMtaEOCr4`KgX*XM&qL19-I;F<>JPAsw>pq2X|!RvGWd*Cj51EOuxfI(Fa zJlA}%y9|{c0ZE#wasq!kt&l^f|L>r=*@P`IV4r&=yo|wRHocR-1&f^sA@&8EFV{C_ zxW_1bhIt^Ry^|U0?6GX1_p*ljavTi>E}rFHlG4#a>)Zd zxK#KRXodEH5pnQu1Z_KJ2K@an(DAK+6JOi_C9pGbxVzLtPED-{!fq)5_chQR^MnWp z&BDbcB=T|H7$CNuQz+qjI?!rqX37(jRl0O`e>4xLyT+w!K9!+mkv_nhnI!AY3q1#O}oVw$v7omV{ya=KkE+IWIM8cnS>!CiO7nM>Op^ zRSCMu*Wh|Zqm&1eaiix~;Jl>DCHiTMzBoGyk5xE%zWsi#qb(|eky%RHkC>XE>UKMQ zCrBOkFx~WAj-~|h0mhlPNnO?&vJ$IU&wM-t-eGz-t-NgKC6av`1xl_md%MC!U@Eg(+D|Fc7h zD)0o1IkR9vJGzu0NunfzT{4LVo?#o|JLQ4_qa=a7ECLRwMm^9tCE37VF3*LC@GsB7 zMP6vPKD+`Z+ebl{z*yZj*e)JaMsxG0)O&xBPr&amEqsc;x>Uf~njhRe0fFfmp!-S% zxk4(q1X?#sPARD|>M4*}vpP}1g7XHB0(mu-+st0a4yZIU8=^(*9L9e!0s1Zqln7;z zt7DhMy$IZDUrS3%9jIJ@J%bHcN6YG?51b^xsX#apXqgmz7O?YKKqwj>t0Z!VN3T5V zR$GMV*ORiH_lq3`qE#oZ#?nrh=l%mY6YDK6rSI%dYQRGYD75-lPnPVxOZvT7Q(wD? z_@yJSh#PCr;YQ+PWQwfsEcykezgTI|Wxg#YkLRXT_gQF}yKTVc_4N4k=%bWK1fL`>mUV7 zp12_9HoLZO>5akpXR*%PUFjA;UfTYIAngm>@TRRAOP^V1^h-n0KzPD(tgcA(@}?O{ zJQzS*4k}kpKQ%7XfK?b2*bwe`~lq z$=qvyiHd=?d}b50_QH7 zCxHU_1F-&^2;5i+DuBG(Jy*D($2|~)3DLy^I#O~HE1fL^Wf49M`C5a@7VvoedupXe z(eybkgo~mENmKtW5BDT7j^iPSRNUnBw$Sb-#Gj>p)7U{l@o|)3dlKOWdZ>va4 zJ&iXc2}xNxl4~RLrbNYxcnPW+n?DS#4KAhHHm4qzJ&>>n2r6G4?0ZBP_UDS;3J6PD z+_QS3Rcc)0;ckMqgJ%a9rTH_MjYa)0iXKl_{^3E?Wu!%6UZQjZh(f*aiuc1bg;&W9MW$tZt|9+K*lBV@=x zt~HU=edJHRqk$UC)b@MLv+V^{CE##VJ8!(e&ax1!{L3=fH(QOB`6yFpPP1t8Q}-0vuO1o>P*aG`(d=)0Ak%o~1#AeA!ZJGr9!Nl!@R?o| z=6GqviCr`A;j*4e=i32rwI!bdUz12|IEUt|hJfcQ~QM- zs>PaS4LQh1!fC$S%Q8&FdgQH+hNRIzAP=pJXn?p??Z3AonzHuHdMHEAg^L^Yx4B}{ z9KZ=Kg?&Jy?7pTSdFZ^qM?FAadU0|X9(Uop^FbksBm2RPdPAW#(5gW!$kAA?bFXeB zQs;}?A_k)XemNF&CXnfY+*mYOJTv@D?xU50@Zi!4wflCN+ai;ey;(Kw*@)z+qrVe1 z@-qeV>ODU%jxl>jl~DT-xvd`L#4$DFXQdp5aMZ#g_cSG=jm|g(a<#80`%<$CHuyQX zIo$oKI~fNC&DUpQa;w>J$Sq*B+a(7)1>(ml1A($K%hPlH>HUOGfq>E0R>2BRz4A~c z2&53VxF8lCtsAaKv1BA4#oVwDNiqt}L8qh%Gzy-rdfqk(*97c8{$bh#2J@wa=P6Xs zGvUf`AmGZr$&fK&gY%*P_n{LtNmfe+i_sb2ik6Z6!hsv+P=-l_8@?+(Y0+3q1%-B;;64bpXuLl9V zm=Cgj_W@4V%>|yx6Lhc z64PWaZrHrH-TuD3dp6jaXyAaQO zDY1n(c}yPN4MukWi6R#_XkBDMd+{B&yjoV*11&s0fzMccO~tB=dmne1dzjb3Gk66d zvDhcsr5@}1#K>5Iv$+S10tx8b=!Lm_VZ$Pg+(<)L5_r+HS9|jm7{`a2*W|&x7imgz zD;|hr3&R$$O`zd=uO3whuum7IZnBRhDpdMlpAjMd?@JUrJ5t}AT@vxyny!-p1zAuz zNmvbt>mg2#9n5wtnyY=ug~F3?+j9z)jo5pmzEOlP_r@Vve< zg3*_*ItG6zLr1mBmGB)1JxMppmKQFnx;kkT-m3{`j0aG#<ab7R9t(1$~ix&7mD#NnYIR=RbSq)fLw;@tPp% zf%Dy8TfV!8(gnbLyIBk%_+9-wlGvW)H{xxX|3IH4mkftrf5t3{b!@*ceZ2GhtOMww zpAj+qL8j3Bi;w5C?C-R(18LxKAX(_XKwZd+01f5%&t@YODqm_pzBLk>3>jyrFVSdP zqk$BCL{p6eOsUDI@o=yJvFyB;)X)R&QS2 zk+G>?(sPZ-`DYB+bI>3w#E1G~&x_5l@}V+m3dhlBFHYEi`L1Pkn$Fy5WpHZPT4YM< zq=h!_&aRp8K(hEHpRF$}Fe6Ph2qMNlIt#34^3kh7tlJ9!3;2EKx7%iUP}_5w43Rqd zM=x-%9MM6F9>79RK?i4zGqIGtS5U(TKu-mbVk8LkP|}Gq^YX@c>fd{%C%#_hzog>A zbrb1lRIY6(Gzo_*YoBF3zC4L2bc?fn4y&S;2TGnVx{KJlZ9zfyXBJnujXxV~f)1Ad zU13lwYEUvAEG4=0Or*q)Q@BqW&VLJ3#f)#3NRdA8;v2lH2z2mzI{|Ux+VXq7)e2~1 zetw}7Q9qYZymh8xOtLndk@)XU+ugn>cTpH0mZ0T!Fz!91I+y%&yf*?^MQNPJehmbr zRnrLAJZ|Fq#;G@KGK=dcaNQ`*#2`spuFs=oghb`6uX6n~Y!w)%31Yv`;{g z476#{9m2PO?+s&Y1WtfxH}DdOK7TnE8`Rj?DEq>SQE(Ui@BsZ7?%f#Ga2eq|K2&%g z!g3QV`WAX}fN8rdcD@9l&+lKG5Xe(Ln^9J>#Y5~+;Abix299kB_tkH=JVkDi+`dh= zwFK5uoB`eooEw*@oYY%L&JH(g-%}x;Snqv#04!8tJph#l1%2Be-pi+39R!O9hdBPbe-0qFJ)b2rO+I?f4RQXcIQmX=>^?{Y zi?}x1_TOT`HwFhtp_aC`c!0S79VOj%!9WZ^O7E|M5Rfw6QvIreTb|#+>1ukJd+%523cPw;RU?pF+ zU-dhnbWepHWzX~iVA_m(`BW5BLjP6Fl_01^exm^2S#hI8|e8?=n&x zmUHvf>+-JCk4_1abN&Fa21gki8S`?)eVy@>D)bDfpK$9Waj$aS)aUPS0_6<9%7Z)a zp3>dJ250;aTsvBq_#+ZZ@_xvj827Oj?M4XsO#6HXXs9hFOlJRn@M8gi`{mj@_T_>du>C^^RTetrf+;64$d?5y1AM0_@oH@ z6nXbocT(Ur0HHC>v)IfTQlCNCPgcI%zMcad^rn$e$evi`=G_A&q^h9}^_bBOf_ixw zA!b~H1H{RQPXBOyBKCD0r{a^>-=ejULV(T|ZWZi6_N|qaQUs8JCYl>;Y=N01`cK!j zWCZ=Un|J1U*_uurNQzOE+>}clTREZl=aVHShzk@c-NVv$L5~xfGIXU#xbiu6fgrY&=GrHJpcG9mo|9=id-E{U9p7(-x^gA$*E^=adLOqmVO3CmfoQ?$0lz$q zC^4&b5kATd*Ut znD<8kWAh+GW}ze8ekWhABIkIa4hWa@!otP;HZVC!|MSXgmaHsDX*Q;cZvRHs+dVT?jh7>hKPoDQKlysDs{o^s zcZ1iyxUv%RbL9CiZJa(EViD3p4k`L;6}s$3Jv?;)kD{MdG1UD9-Y-W~a z(o%T+=FL?Sz4e0HL?m|aQ8QGlP&?xOHam9tMksJf58om9!BU!>)!Fd1JVuyS&@LKj z>cmQKjC(BKg0B0MD@BYFvT+j6u7E+t%43BMLYA zx%BFb8s#e;RePfu?XFNWyZY;!Q0C2hmyf_ps$&AoYIp(xXS_5S6TS2Z`H$SqmN>x; znDS78@conVvc-)J`v=?Qcc^&>69jDYfC#{$Y_vct++n(wDHZV?G0*}+*eFZ0Q5W^C z<=9fG_O*9n(hyMahX?cGGO=xA_sP!{-o)EVM}Stu?ceUp>(DQsbeQStCrR_yzYGq( z9a`#{X@#kzN^+I9FIgG9p8ZvGuCdg9;H}5=xu;UlW?EJs!6p9h&)$0Zy=>ohSOa%y zn7c*u7T5%qC}}ruF3+WXf6g58S*fX%cZuWk$%l#2Fk{()cJHO(cI?G7MlhV){x==Y zHhlqX%N`wK^)Weag$?d(8;iQ{J_gFNL|%(t*6`?W$a%12z-+}_x9msg<*Dwqo8}gJ z^x}`>wJd5WM=6?V&u0-(k%UQ~DfytL+wC*eK5@eEk}sHHt@Kg`hD&LCOz;35U_MKy zSLqnKC;W6REb}{lCiqBgXB%05P*WUGU-YdGE~;lBu^)Rj_69REn^Up2*M{PUSK@3r}!lP@f-xoDZIgvj8ZCqjg4)u6>hYftYic2Tt8PF5QV6L_H?NN8UI9y(u+&b!@GDr zKDvo-OoU& zt0lai1Lz|0`G7G|7(KnopZ|S#!tOn3b84kK{;-8I(teN2;cy+PC-Rf{5~<^Q%LjxL zKF_c$F|0Ea2x&lQLn3h-1J&T;fIpIVGM_kdrUPW>v%b2hu}A>;q6%+mB~y3n5ns_U zZZ0m7yd&{ipk4imF?^O$ou4*gCE~lmA8bdQJ}VGLJE>2*EB_@dT5E5WaXWJJS8xA( zddk>fe4E zmby{z;~QxZAk^H@@%vE|xIMg9K;h$7U!qX^tC-DCm_#Fxy|&a93p^z>f_AK;IwI@z z0ygBpjKQulyXF9@CNt=C$X|QLrTz0OZf`{Nc67i69Z{Smw$2eX&w=3*KLuvOO*)r! zcjrbA5Ja(T0lXkNVL-?IZ1=t9sC$+D%rAG6_>Y(P?S5hD(ojF;;=8+G6=hxj?+cFv zl!&NXg{SIRj~DSO?lpNwcU*6fYXkP-mA0_^`{4ZB&;!6Fe~ykfW^8Y54cxzG>~?T% z99JJ{BzDoVd#kfS-E` zw8x;!Z{-4kjGbD2Mp^}JZ`v&fB)6BgIESLC z<1{Pgy8MRh*d?A_R4XFCC0^{~iD*Cr=$Uic0jm9AkQ+u{Pd7Zd)sbF=*xue2KHIrx zd|cphWi#~QzAM&_@qw%IMh{Yh5Z*{3ubt){wOOatc{cS=f&?=HTCAfG5g6WZ|H`is z@=I6Yi<7a`F#Qi)z_hB!=!k4c<|C5g_VclLEDCc+CBBhRDBUPlq{4-VfUhqE-*{79 zE`VCfFGBtOb!A8eu8()7+l^z?OWBmH4_Cn{D~Q38uwI+0M&mTC_p6GME45MKlBg07 zF-uB6L$1jG1bP>fOagx5v8mDbr_i41O z$$d39nQ^fJG-@u_5o;IR2#rO08hs~L;x3_}n;7ahj!T~5r`c-?fi9#Op~_^t46#u# z)vDZN$K$yfxZBpUM7{R~_e{M{xC4;JBL@s~3t38rvqP2K<_2$w)@;!wPxywYY>3Ns zT#2eE)X-%!(?*3(;qDd`T@cm)q0EtndaNx5e`}W!vh0eH1E`5^JXl=UM`sBeFB(J`&dB!sqt%+*zG?Lr;r@d>;n+ibUQ&Q8M8SLM*D!w65sFQT2Orqy%o=wSEl~yrl zxzc&c?1ovTuWR?Z;Y0YgE8z)%cyqfY<(i0n*<^C=d}A|s+8x6|WWLuaFS3Wpnhth} zRZt`C))8ld$FB8Kyn#*`Hz#!dJdfHRqOdqoe&?L=t=^KQ^5ip)D@;zwDDvtdEv|^9V)RLF?^kgu%5y*m7kF)- zIf5`ztNFGteyhQUdQU*&3XK;G9DQr-D~B_C71aYhaACN$IN(5^a=g1yan_sDhqll8 zGQm6CK_K~bU_J#1B+1Q3rJT&oA-wm61ua?=p@yfGXLzooNuw>Nzl?Of@ zQ_mm;djrB}G6HQ$)UQ%cV~uI0>Yh};H;5VvdU_v=_P$b&4S4#EOH~jop7sKY%!1;A zZh=IpPgiLTUvF>yCBAx+q;lySQ_y7i{U#^l6MOF;5H1slcQ_3V}?%C zRYIe_V9uMm;bjCpq-g1H`g=F~4#|36KN_#)-Y11=mVbh7^Sfc+);llUTAc5kcgzp_e{%S~*GoE!cYmh@LAab&m*~Cw$qV4dK*)2+Im)K zZ*yXeva1sasrOe<@*&xrx{nbwbd9^PPbNdJWu!F2jP9L^KJ8coWyU!@lj`9HLU2KV ztOT&wCLHjRd^VL%+5=B@-bHgd7>SXXrdz$=#I{ns$3n_<49qhHy^@?W@)1q?HcC(8 zjto@0-~$^?rOjRQ-h{7_cEZvF#NLtmkv2cm+9kn%K(n^7X2rH+cU!b-f&9CzdgLiL zmSgMoe~bUWA@0`$60e3{Y|J{7qp4w?n_5sbOC-bB?+-Ls{Ftuw2F;%>oQ<{4?WCb* z76GQUa-&CowQO=Bfr8|R7|bY!mUJdbz*ZZGklz{IdV|;dlJ@YX0CCLN=x-?=?asv4 z!t3Ax7Q_vSR;(m!(C{A`jNn0Rxf z`ADN#Xm&fKb>Du?F<&;~-h7!^Z_ZtnZi5znPx`3VVv*x(B$ULv_?Agbn9L`IT^F3hp z((){s2^hn3^SkmQw7Ewvq2us6QOZ-&KDp{Ulwpr|%pcKI^taS!WOx7XuuxkgBG%wd zjshuT7Z=;sc=h{zt%}mNq(6AJ*V@F}{^v>DmAa028p8}10&UovlJ-1x^9LIpyh$W|%uIlx~P*U>aLzu}h=2 zKn0CK+5yEhCH(Rsx3SfbzF|2Srh(PoE32xlksDHC2e_+8>dk7TTt6ASxd zUkn?Oy^nV$n>19rt;fJ{(qnU(=UCJ2)r8b6J^1L4xrAM|&%3pX?)j$r7}fbazjW}h zhZG?k-HjZv)_lX>Mv&=V@;YhhBB1R1pdZx z;Z=J4f0Vs-RFrMo??0%Bih!tqN{fhqfT&1!siYzxHI#%PokJ@zBB@A73rKf&h=erK z-Q68S>|?y2=Xuv&@BZ!Ie&>&Sd9S5wu9@qa^E}Su_R!}Cd@LXhoS!&EJ~%10bKy~XOJFA)VSSSw=;1>2x)@COd5AUmap#+~Re zSmDLS@J{`~8SRH{^7i%|Zv|okYGyaPs7IqEw%6YULHCff1Uud_6Onv#|64nVY zSY*bQR>*_5M3G>;q`!_8@W%)^#|h|0kSWhbc*)a8D_>M0|UE~#oGN>br?l-4pCt6P+K}wSKb7%~ibMca> z3I}?m*{ zO;G+5o2`+hhoX1U!Ys*hUb5SKC2|rqn!1bUKF=O&4~HOWCBz{zUV_d zJUj)+_Xy%$wh$^b>S40bu-Q!w41If6Gg|c+DvS2szSmerMmY%fgMY9O!GGGcqR@BpI4W=(rM!gx0D z!>=Bds6VO~&gG$L)XuZzn#&If>th#at7Jv2dX;H0gFJX7IOWV3r1AJj@f&HbZa$tg zB!7)}Mgd_(evSPu&vMkDZEE`6wy#eVejTqLZybk{pewT4U88ohM%hXox#y)XRmLnt zCHa)NjlDiR|D!#yTytZo3K_#Awzv)yf%PUO{*w7Vx*#Bs2>*|rHx5l4Ry*PK&cNUn)W z{x3|F%#BLQvFNqAAi9{wR1|;L$<4(BQMti9oq!8(ukn^vcd|$>EGcO!Y#4lEz{q!~ zo}4{im|??@L}UCpJC*&Vb=7czPK&-LDJ*0T&!k zF>CBBnr%@PhqYW*{g^&Yx_kGR9|2KmQlSIw?__yL5e+2T#9?paG5%DIxnuiLH9~dN z!CU08yJe42_m{pe$|9o3L;?#o;}1w1{*n)>^t4&=H(~V6JpMfxtG<{u?+y!C_x7uAN%zM05KWQ%dBa~GhF6V6Mw9PS91EP-sd78~NWa@sTSmlK{5Jar zl2=Oxfl_>SIQH)E4M*6aWBU@`X|G8ft_iL#+g#rroLv_0Uvf~z6x;=ti6x88tMo~R ztbtNV#lU9#EN0vort8MZZ>W@Bmu1cu-}|#o&p00l z^zhY~@K!Ogx~i4DQh&I!^@aDVY~xaLaDN{zd`1Q{fc}d$Vncpa3SQJc1c!v8`r^bD zH+LN~Gcy(M=FTVCglV?*syh~E@8H@^TE315%NIYkB8sS( zjjHmgu%G)qx$k^&%ukFnySat4j>%S1IwSlH>yk}Pj-Nw{jcJ^0Sryg9@zWf0Dc?U8 z6uXC^-z#nZ)RU~eRkSv!p>7$Lx~shHf_!;r+s0bSQc!kj3Wf~J4^rKk#{)xoQCL1d z!?Yr#M#)*twtP0u!NtY(mRdcd6je=e$h25mD0L$p|2?Byf%)r*GI`S^n15`}uD59a z4pe@-FCn^kD5E_1&5~D6s8YLp-VFJGnAA6Jl!}P#d#A$ zUJ8ltzEOBpFip=KkB)6rrmK>nD=6K0{=h-p(52c*#cyf$N5tdG344d5HC^J(S;k07 z(`Oo4(vF@+l`n%t#xDIZ5quY<=zJu=8^3gUu*isdN3A=6i8J812xyhq*O&9cS-3RI zp52LO)G>AU@}r&@SVTIP=$pYv%wjiBbKhWTB2dB1btR6n_x168OoO&7xxtN*P&kM= z+b=CIg?;U#r-yc3o@%z%`wPWf=`+<*V8Bl&p`wz7X0cxZ(by_<%W_0?2wk0>oZ|K- zK*_YE<-9mX40qGUo^&sv6Hh`CT_H89cDtxQ{UY)j<>sbKc@?wa)ea9;-*>{UvPTMb zgu`W@?cRPkJ!kQo*6ifV!AwYZ!`gR#{he3?9syC>5z+aW1Bj%t*x04SxBYm0tlA)L zhV5p<>-SmVEO8pF;>WJGmci;u((K5LtOgRScLJ&u{XBVNki`;Lv}I#X31d=XdH1p| zuZpz#j8BAD4=lCEMMCjW!6EUgFQ;n!>L`j`&z;hyiD4O}<8vPt27ept$d3M;!Ea`H zix{QZ_8CSXV$&pbof82Gh+Uw0VJRgg};!&*ySJt`1^ zhFIMnj7}h6N9Y=OhQ+$dq?4#IC-+!UBP6289}4CS>|eJ&(Bc~&7cDJ}VNU=2BD?!% zU_I}8_FcE~RQuojUC6`B3w7o#B$~-jvGwx0rjA7OMCP=OW>$Rfsj~?^u#C-&%Oi`v|-H$-0n)}mKw)QE46jSe{&DPK{ziAHf!@6g&CJ4P?a3eZ?<#)8b#c4`WvDL==ugZCL09p9%Te^^C zf8`ua6u0X)R`n990`+*G7okOKqd{u48G2k8H!8B$+kJnKZOa3I1uozIY9PQwVWW~S zkCUqMBeH*YyzT5I7uv8(!7O4URZFZ!2&L}=?N9to=UE{a7TR*A??f+EbRDx z&0rq*Kd+^8)qn3iEs9pcKXti(;GDPbjGFUVnA}Se>0ax^LW5#XhNUSDDn11M?d&6H zNI>F*3#av^7x0*L4&ZxrbS@2k$&2rUX#*$-gyEIAIv>TEbsd~oF-OM+zd!lC;Ae@A zCyRXVKMIbI7?^xvlTpN-Pd0*j!W>?|zM+_*s;JaD1xA!fj|j*k|Fb^99y8?2<2-`P z;}A64zp%Ak=Xp=NqjeT|mw&V|#;>;8uo z6Js&9tw#$LI3tYn@rcFIRr*8TqbnQ>8-?@xGqg4Tw1a78Xy$E*FJP~U(%#Y0Cy$SN zev#K)>P25GKM>eu5m7>UY%wyLjSd}0Yka;3U)oE z08&I4iQSMA3>-ajo1j9TJeLoaGOT|YoGPD5$f=aLXlUHP#6rjXgyItR`~==IaOJ|i ztBG>nYz=t4-({9;gsXYTmCeSHx^r2t#VyMNkSde;USD$qenZI4QHTkqPu&1j#i3d30QfdC$bqa zWb17yz2IB+RCprz0m4Y?=c0q!|m6|W(xZG+K`|7TF@}0 zOV(3Z_wO6A{5!EvYf$f^^Ms`Ofb$L=&{3^08N0dGfOYc5Oh!ISpqAPj2en%JG2hU~hGSHcxiblB<05MkmAlgRFsnYp(;^;HW?+|7C<2t@kyyO}Tf zCG9>NtZn16a?uUF$V_I=Uo#ba+`oRP7?z<1NMed(it=lDn2*9&<~wK(3%I+JFO4+C zNSYQ*%q<&P4H$v*ZUk_Kh(JsD1#!*&95s7j07v@Q=j}FoQx&B=uu+Sj70Eg7Zvl_7 z?gtfNGuOTIeXxfQm{v;gSg2e$+mF!W`(YCdZjptS>g4l}6Lw31nS{+xz)#*x? zZt^DR?Y7T|sIZl4bcklw+4NU2@wY^ax9Bx%R1(`TH?c6%VS314@mo{Q2)YPgCTraX zn`rcSWaw@2R^)=;#H)=W%E^PYA@)^~S?yHr^`4~`{lPwOGqZf`CjwkMr#AKOXeFf` zp(w0$S{dIXxYs-Id3_hPY#=c4hd(9nC)rWRj%YSgr$9)GiOGZUPp{5P6dFQt@AqPs;`aqy9T*dU+&0XOP(mv*s zP36coWR?c;t9kih-9}Z4eI@lB$bo4+vB`C%#6i%Y#-F;83-{wAHb4NbrH`GL*HEAf zD7xR05xy^gsIC;)#&UKihJe*pul@9LrswI%x1JB!+5J=J;a1FXoZ_p_qC3HRjI_X@ zR{l{=bP%$hxJG*XDHDdx_>8w)_#hd+qVC&-J9o#ltWv!wWt#ctGJe!3a`&FD*Xvr! zqyoM<-BQ#*#u*DbQ-*pl7YNM|EZ$mPNy5{Cxho!}_}BVt-spI^wlts8YLkCUW&T9?an_w^G6m?6##Rei1uy^B&5NLt4-rRIbLMSN|Yq>C~rE;~ZoS@TT{#{la#1>jE z@fCBVXz^`MM7n6M^=I^EIQN^Qz0c(mIX`8Xy|-DfFxbyj?<$>y$w#?s^k`?CXj~`R zG}2(z5JTn>5M)SV9Nub5LQ_HDg2TwG_VoX|U!@Dd0aQv3( zXzp>DgTpjwsJAC1FREWWqhPLw35ZTu;xv8nBlm|MZnXm}*5Z9}E&+71Q9-aSn&W*I z*PR_}wOQ~g?r!UI!X>UZ~T=<6e@`2Ni z*W&E=@`B~LeZ9fHW*2*7xHu}fxYyGCm}+nBNXgi|KHTe#5op+9nft1PhXZk3-aF0S z8odCKFDgJ|fPq)zETv=JOczNr$iA63nb(+EIghWgvci5o+@{3JIBUqEx|^R#w`VQQ z>&jyHdGjcfPctj7RIejR6Q$*ofGK*scT9sjJQsB@bguB=DWTjt99G@f>Nc4b{ z+?ftITvkmM5*W=5qxN|#d2+idF zSXi!WzEL@Vi{(mQnrW9j*t(nXHsAT2yOd$M;8s)B#V1_4__CEL&-a@VfbZFvT2ZoH-;o=Ri5U>oaPc>Rhpk8b2qF zaQg~c!gF&!kt>lE7aTK^QSJtHdixW)lULPiAy{&Lf5EEzXH{bQ9jv*^oL-3<`ivLQ z$3V_|nMuL*`h0IFuK{7H6Te;={0yp{Zu`sw9FE`WxA8_EHEYQvo2$2WAoo+nP07d~ zsmz6Smx5NzLaz+cCKj;1x=%IdlEymroW79Smr(D(Vq+?;&|V?Ep*AXWu9+;z_;4Bh zq0M!0GwI$M^p=tn{IuKB;!tANyMJ zQZnlW<*?K=%aCyCFn690JipB(I{>Ha)Gf7=s}hB>PCe+w+`LWJnN8Ir)=<{lSp(+w zO|>+AhZ{t&Lo4S%9fr;wz>VxHk2<~CQrY~P{EjhYismz<&x^-LT>N?F?)LYOiuX4L z&~;?ZWIlwigL!S=+ohPWzt8E*yueh-J0U|sqO=BdmIGkdNnsq2jEb*8`HPVZyUOuqJ$Kspl&I2UdslO0E(q3LCA`S7qPebE4oi<=*6OMm!ec%Nx;7O-m>>Cy_s;U z$_npwAB6Fo6 zG$vk0{L-I4W4*eK&&k%C2U)C7YeaAH<`<=73xx-H;y$D=>OPUYZ49K%6?v>%e_6HE zIz>J2;^oVCsHv${LAsXS58B`8GiS~ugZoM+YAx&KkLMes)UQK>-I4Ka8u2{Eq2xtt z633_4n!IDl)P+_l3eRpsItn})2y<$?%{oGPGXX#;fl2OXnOd(U&+^OzE6pu~YuE4Q zF$;*#a708Z`^w2q(nb<-q~1O=v#-vm@^P0VjTH_q9brY}6LXP)fkU0n8@l`*`Kpn9 zo@WguixjxhdmX8$!nMDvh|G$EV08|KOelx3F)-&U$rC->`OLB6X(iXzwB^U& zHlrtYef8F5u_u9@8!+g%jHzPETA0$>k76>~SE@aKuNd$vp&<=b~zXLp}(>j-a2GpF`N@Ge_-)cziq25&8 zdW2WCyMsMDz@B#*+dt#&9N<+_s#$J=gh@^32Z31j`fQduU78lXBN1hMidASwv&_=V zFfM5i|Q+|cU`fSr2OtQblhtE>4CCi#0q~j8Svp{lcn^^r#a%( zLv_wb(@{7@qXs4U@LVo0ZmdsDt#=QsD!H_BcPkdnf%pYB(uR|Qg43cY8{~e0d;pql z3P0l8@k+PJl%qyLR?vSwBE?JXHJ~p<-Ka;M<8fq3c(#(XP>Yk*akx@uC^2sd88H2& zR&374wYO7M3Mia6WHnV}s6fz}?tw3kc_?IAbZozzTL4B~k_*G!xn?sR4QgCcZc zqIj(5g|M_c(6%=*eGXNgY`glTR51GqGtr1I^jG0qPZ+wDOQOwoCjyp^W@9n&+JI)` z*trx@cEE{iazep@wH`52QOzVPruo5TjA^wY@r_3ESy`g_K4q!{#8*1(u9v06xG`%0 zm0+CBkZmVM(@CnzWLUP=!7lbJ|R*oZ+o=A z@z|gZR$euT1ucH1QPwv6&ywWg>k!ZmyrS_od#X0M=o1eS2ak^LHfTc-$_-x46*t92 z*!9vSpf5NQW$=4&JJPC9xE7`tPiuSQukbQvioQE4P1cU+S%MZcBg4ow3dRrTKKb%J zZ4T{A^1W&G@xak))|Xd$_P_OynYo;fE*}@`5SWbS1jt60-AfZIv3!&C;b80Kp>;2} z;54$7{OigysuFzyGPcP0h&>Z(FO}#>?)ib#nPg8_7Kaq=CL)IBtsu*Oo8v3XszrA&1dby)Cxr0QwSw6tO`*gym}+iC#XL3T-Y z6sRlm0DOsavHQP=z-=5ds?YVQRb=Ytx}LhE0>{g~g<_sL)wI4L9W3mg*oN*YX6*D$ z-CY>bZ3E4%3s8AX%&YOh{+g`N8pzelovgH7=9i8-+t5+HN}2LO?xG5AcA~SSf7i4M z{@a>g0m-Vk)G9Vqc$^f=(ID=COs6Cs{zdsJ>*M6QM$)(lqUxLfZiKInl-12qiuVAU z^4jsi)%1l$@3d)^p9-1uZILSx^TBIXce6tL7!@)ppyi~s{NL1x=z!LByK&(D$gd8U zK(_?ixyYvvtanQbv8g9h!u<0ADw-Xd_zYd!?C-Z_V`R5QDi&YSm{B!F@S^EM$_C`R zysXFmXx=nfFy)-Gocr_a5=QR{zi+?D6nZZySV8ayrBvk)Gf4v3;J`iy-_pU3mDyCT z^eI<0LgSLO7iH##X>~Ye(3sO*sV$o7c#Z4mO~gvY+t8MOozV$Z}Ne1>kQTG7G|x=ComKn8xL_1;*cb0mo9(1 zKnqq&bNW=Py{gl93@3oRdn63ImfKc7E!&pKyw58CgCF1_`Gak2tG)vZA+hTmYGTP@ zatOV|r{PVNxn;{jMS?cw)B8j$iMhc~mWSmoXWS?d$*dbk*b7&mVPEE*UBOPH(m<;I z>?-eaMu2uCt;`BvK@c)*{{t7|M4>7sS+PgSdOk?>)z7?h$E9n^ix^SOk|b2RMp+1~ z@OLw}LZ`7ACBPI*7W2LuXPjv^*6rMamGTEC$eCf1jj4Sh>k3hQ#P!viE$n8Y=?yQ7 z^Ia34dG>!H`O8_LGw$?c!ZXWCrumz5KN!EM8NSZgWHOu&NURae(r@kWx@dvkTIjNn z+b=pJ!0mx{oYNkIi5+Ys5O?i)$LFHsnob+?>7#}$ilox1#ZPRpRu1jopU4fhna;W& z5bNG<>h1|#aHHUku5HC#Zzq|w)ph1 zoLdd%qatB|$lpD>u|pLDqRwi{NJ3s2-DoP&vHTMWC2-S=zKFh?1l3|L=yoI6b-mQ- zVCT}!pO~bT2Q&I_E0)NV9=4Hv0@v0FCI^`Q9UKSc= z6GIOw39^P_(tk*-m_KehkM(c{-UpGz`PK(*;7;F(tZ)fo@=X^aqT-KL;Wu~@YEah5 z^5o_pgIL`ds`xl6@r9wCu|KgL!j@8l+~Ca)bKHWN4D26~TvlTGjaPQU0x07_m)KP_ zCc!@|oU#>G5+6F}dJYTZruPN}7m)4xxu!{??E2PTHqcnLWf1}hb{?d}F}&RdS6FO> zl!w^UGSf`jmgBoq6wr{sM+dxth$7RGQox`PemKZU5tlNX*B98Y03F<=%aseOsl!**>M!3E@5j7aO)~s5`0RQy zjlAhIXZX0^;V9!RAKd(?xU~=@32-V4zavr z^>Xaub2imM^C6hz5t+Vd#hJj+xX}}@O!DV-(X4li5MkJ~JA%1ZJ%2AjrJ=|H$>xRz zhEl7KY^V`p!gmFD@hi1R$BBuFNv&;Uan&IL^!7e9%7E%#xu{W282B2FGAgv7JFwoU7vDVY2wgpK3{A9-fHimrOVDl$ z`(|5F<&$gBCM)cEuJa>3-E>H|74X8a5vRbUkh5OgT^&&~?QHmt<+|Q;++E%V&gdV< zwF-tJkfS+u3qQwbbwj~`nEeXN)coX3VBb)?nv$Qzy>j|DKI&()?;4ak`0fH1>HYj& z9c;w*ef45_Wc=bEb-!2XL|AZc!`z)&D^^3nVZM-wM3Ms`1I8MXw3?a&~Wl$Jt%w>RM8lb6flq5Z%yX^B4%M?ku*L z0trrEy}@HknxseprB}&)OU`S0>iK_J?nB>viET#L0qQNC(+bzD_RQYy` z!0#Tn$YnAjcrIidA6}QU(0Y75FXU0t1mod;S($3_R-el`UyqZF^XBJ-*%B@Q#^Fom zXyx-t>is{h7|sPhFS8B?HrLxlTuFwban|co?q4|+ln%E;<=&2JZcT@LwVG)nA>M=p z51&zoB^IpBYj~1^jg4)v%C#y?Fw`uqtxeXn_g3jQ_gfX&waJ8;)k8ySmx&vM$=HaA ziAy0ctmsHsWu*b%j%nRhYVe?LztHJ!B2X|gMEjR`()qyf2d*ed%3}NzCu1=aD}8E~ z=qhCb;@>f$1y-03x=|l^yt9J%9wM;7*S`7&zkRMN=o~-?nj77l1v6T`Be{TSb3>T@ zp+F)fw`k`{#;nv)hF1dEz!=YKvn8ApxTm=jlxn?IBjZppy0k6RXEq(;!5ETtV}-gv z^YYwLlU-KFPuIzl8W~ow#`qudv&mrx;jlqRRUR%fm(Xj2i=DBpf40OCWs0uzA!}y& zjR)t^ZyV-Z0NzZ%R_&L(QJE`q+!I8@6r+PNEWfwnH?n!KnL$g#Bh5uKD8=i9pHZ14 zCqjh14VvX)$5lW-lip`v9O$d( z>PS<5RN8k;iZ>r%+OK#sGaqc(%FSnqAi9?I6B%iJ1~DGq%}#ql-Z++nnn=Wv6lGr; z@sg~0P)b0w)~R$3Mbx=t)(aQw%_zZfLBZ&iLX!{*#D%s)BW`|8>Tt|LAA^F%nUt(U@L$i7^H zpGvWZX9XS9L|#qKul)Uy+|RSRojmn-!=5etx>E5>p-^6BaN~rqDU6n`;2@FUnBoLP zir|}JmV^kKE8nl#UA&7|*$(_-d4OR5!t(@j`e?&tEqW{&UFhp!V8$6u45~ig_k%_y zi)%F%x8)n_D;Ik8XTC>tLQ{YB<5_Y-eGm+J2h!)@G-un?{)((rJsM5X*w&)n8*M1m zDa%f(2$*+X;mQjj7P$FYZgHk+t9;!CvmgemzmzkT?RLrQ1%L%^A7`rM)vr%KXQ?D` zwVhpMFoZT8I^Eo%P^APct1(BSq-z2d5z!~x3(1^y*4xdo zn)9BY*cw^98)`YI`RwJTs|8(8oK$24hFjCTcK5NY*OIyDYkff<&>nz>z7{aFEF#)0 zU-N+@*1GV z;T3-Ag55t^#Piba{8iv4q}O-P0Ym>}NZOdsLlXo-ziy@v5)x%@;RsOq-=mG9PMLrj z=2fw|cKAcROJIkS11A~)u6|THW13P+ra^Chc~8*g$X+GqcQA9PJ*%e6!H@Lfzy7n+ z%uuZVY}L47w6>eu{4&Av=x3&Vz-J(g2koZ0WTFcKNu`fIUgB#J**ZJh*;NyTaWy*r7`Y(bUl zpEF#9{v~I>)gr-a8u2jw>Ndn(iVN`?u-VOQI_X>_a3CR}+FGe7pFHt?VF z4)A?c3a${bL-$HTpoFY&#}a(3Hr^*ooIF?Z-Fzi(<19&q3Q%&4alqi0NR(4F_4$5e z#f|!bk)Hj0uM4PV5~k2NTDB?Ei38_ZAKK_}IU`vp+e6i^CPMP=?dciX5CyQT!9znb zafL|maMFhjj2YgJEeNHb+Udx~=2yj_`B1V*LCg7$$G#4@#6&qlmF|9;@$DGp2Z$N$ z%Mn7MBC7&S`4iHjXQK`QMKWA_jNdn3zp9&W(>{?rbA^;ljc|=yQqOjV&3EZeD~ z{rGK0CyG{wbKQckm|PjLAoKLZbiy9qj>u7~`OYcHSK4oId2Cj`!XCYvJW^mx23YP- zrsdt$qN44PG*886Pg8m-8_ma9bY~a{t&9LqvLvW>dey*U7cht}zhuX=>3Yqf+vy%( z_ag|^*iS(@*X&@=cL?Jb+D#)%c6t!wX_B%>zZ#ypxw2*5vz0Rp%ST|LORVEI|4756 zPBZJF@(DgK44V=zdQ@DAiKgXW=yR@md9nTKKMYWwQofm+v2U(h>)K9qEkEVn|$uH_l+-U6$rO_LJ+LfVhC7TEcy7JrgmRN{tTL)S=S0=hy?r0}Dg zL|K2W0Aqf@NKF6rkp@|vU6qqg%M$wYYw?T!>@?fE7I;VHC>Ik)^{&b%Z!6?<>_gV? zWThe>TaU;$EkwwHk`94rISZfirbmU=o9bbl>$w~r#wlGc z2va@G_}b_$J}2J#SQrE-iv`?h=>BNIcPZ*;-vL)nX%y*L^pZr^C!9O4N|QBPrZL-R z12263jQ93n^YAOXE+O#|;AQq|xBgpWPWiEQr+oN2#v|FxP>i7I@l*502nJ)STf0XO zQs)%pl-`{oJ=d}NsB9*D>u0-1R}Zf;qjHG4^6 zL=JONcFB;Ek*jm<$`v7PZEed|6va!>{rOqWwXt|v%wp`6uq{;M@NSx@M2R` zu(UBq&;)7%mgEYJo1^_wyERs-GSaG~tqWHN*@DMi{{MS#FRqFHcyddQ(w+BZ6jhEO z9k09lC@GzqeDjOh!${oOg8zdB%0j{iXYbMf+rr;D^e@%tm4?S%xA1bXZ1MOS2$UNK zI`LJRb0CTRbb@RP1q4kj&?UwCxP~iSj(Jx4b3`dPJL}B>kseMF(3V``YOq4h8Sv9f zE`D!b>Gt^p+&tsw-;!_Y{m7K-ZF+tLzrweywgzU-3_OkvO-#k%fh@FzfuTR>2F>4` z&EU;v6>iSW*2`zq30e_&eD{R?h27~sDIsV*@QNB;%LTU{}?qkfZGYqtH2gb%-o0kN6noIH$zg3N}TnET+jt+U<;Oa#k3!hj1&=8e2g z`|Ga@t})2U!yDJ_KqE==lmH0rcu!@qOb(r&qh+#}r})m)a+M`h**J6rr2s^j?`T%L zyGS|iH2R2Pt#fuFKH1@`oSJK@BdzL2w=(Rdi zxu5gyfPsZ+P@rC4W^zNMn?Di|2IJ4WapYVC0RRkxCe*rl3gQZx9pBrkt+!+>gq|=J zWa%3Y3Ktzv(Uz+HMKPi5ulXzl^%HtI1?wNx;MC~9`ctv%qqvyZuM}XOeRXnnuG_)p z&~P5C(`TK<3f;AC6=vJHU$X+~8#m}eX$B{1(c+HaND*IP^|5Ni_F!reY@ijBnRM>V2vArRM$o2;- z{go(Gn@0s7r`do+;rC6%F!3qD%mD)SiWD$A9nOZjh+ z0?rrwzgh$*L=ZHrX8vgyE7jmdV0}^1?yCFEk77tN$f_3!fbj*V=n^#hPM$p>{mM#7 zJzh0VwQ6x~TV8R}1xL9R9{MyyEW^Kq=|LQ&-&E=1wl;0)ndY%EPnJ3iwX_$IGn56_6FOfcG7{>0TdlNWk0 zo=Y0jS`K5JTl^0B>0F6zakkyxnl)ol(RWT%U>+T;NWQaGV4!=}?Z5&Zb;*%oUk>Wf zy;^OSn0>vf^|8wR^)a;{P}s&T^#!9~a~$(3JRpvGFAMKvPU_mey|LlVA((ZziUR5a zmqyv}M6+uxyC59M;XzZy>W&dKjQg<+c|@dsi~2wRX@X>EL3%@6-cvcKCB^q%SRO#m z*jva8!cvS$|7OBhGrj6>#&;|GL%#BX%s^Iab9XnSZ&);n%Eqw2RNIoJ(4z$d?W|a| zs2ZVT0k*}NRhP))^zSz|f;WB%JVIC;bY^1vNGv$bES*vm@p8E-dTX}`EYVkqBJ{*e zx+2JLq#OJTdJrE<;F=kt*5XYKkfo;-gpL)*6llfcKRfXx@k;Q#yY-)h?c=pBa!Y~E z4@Ls}_QFn93!8QdE7vbdt93odFn{T6Prt`chcah5WP?w->0?h zR~z$g`$zYSSiJ;L9W*k#iQ|NGyrcJCB*(32EC-Ga)f$FezuddkRX$)nIZtfi{0~x~ zTP*!_f8@Hw#moTSO?xl~%;E?+?I#3g(5i_y4#70~ex%xkq=0YV0B zLbtWB<^lTQym0ls(n{8+RiuYb>BHmAcM zaAr;;3y-%=i7wV!nOhpVYrn41nD?{&PP+2-9G@i3np#ONhLEIv?IQRjn>pfg{hD4v z5TOUmauDM$VQBiJ|K})yY|8-VJhcCxdf*XJLDh)}t-<5_M&gcCer!4Y)S{Z3W4&et z;w~U4!d^{C$W8q$bE)Nmjx{Hnf;JPI1CEJPqU_Oar3=mHcUDP_FBn#uVVv#z4Kuf< zavJthsC55LTcrF#jef$kOrUm4f<>Y*7Q23Cz*&55YpR`1!e{r~-DtW%VBUgmiJG4iPDK9RZSRv zODQ%>y`5QAxrUv$*@qw6P2BApE^#s+f*x^OyG|HQXId3MnQS)4SNK{l6Aldxo#;dgpiV_113Xpy#8PC zPw!W1uCz~jy1H1N-hb-IWY4moyEG|1Pf@NA z4>Iv70mb?mME_J9cCAAwW1n|?Z8o9J$ph5Qf69THXcAuCjKkunny88+ihQ3@^%9DD zO9NAAuAE>XpeX1bF#aJ@U7+K1~- z7O~=A|LCjaSBglwQtOQm<@yTA=9|{ZAWoRHi5ZCEld^B(z+Oimkjw8AV6Ovi79#T= zbOlRAACm(G|JEki$Azy2L~mPvrU&37sx=;8G!(IM=>BYs{dbuch1p(HVb|^KTu2G= zVXcL77u+tXcB{iGN;K?HRE>w{i{92OTuP9+jKOr+&V_7xe_OH{i++G=)&CFf?}94; z_2p~>mSJUpM`j6DAXZw_en(YP@Auhc)$G>WXWW=Yv@VU8b_cfdxn|x zJzdWlBSOsrX<#Rq=1gGv*XN8%Bp&PklDGK1r;z9*&OXK(!L#8rUt)h?kop(5hrMt_ z0^IxYhdStr9Wd|&3Mt_`a3|3IAu`)uM2trRq8@90O-KZ6B*@A&)Hq12)=X9Q(65Oo z*q^K4J%=uY_Y@y#2QWh&J$ZLoL_gX!@uB(r1yn1$iDcHOdd=TAK_D&yDpCEpbiX56 zEf-Wo3-?v?pPsWB^fcc6hss$H$?vGNoac<$eZ3S*WVL;!_{nP9Or}~!Npqik$tT6> zaH~TC7q$DUyL+{QQZ~fQ!@rwt49ZaCk6i>xd2jrE7j?BaZ|>lpJJ$i^)i<~_2Ow_> z)x~$@1f2(jj|IaH3$_6F`TAGQKtdGrD;kJ+pe>T_jG71!4GkSW8(E{xRb{&iluK_6j zCCbgwWg&~cMW<_SWkV&Ic9T$mVP8V3@v<$=gJua=CoGxrHgtGQPx!c>V*?TFz#^+>-ZkR;A-%vt%UDE``6GldvI&>Cb5LW7CA+vn7;c{fGF<{#p!TK)% zfv@h6ge3-A^{6rPsd`R`dSU#hRcTh7{vr4Xv#;62NAt*e@KE8_#^ePRdWZdaT0PVw zsmRis=42*??*``c+6AuR zIAWDGi!dPsDM{C@n1T|RS(fPQo?1woQH!sXfh7gxaUo%Ip=dYRw@3D=u$k_R^?!IR z{HX6>13C#EUvVDCa5vZ99>8-`U+YOD^P?6-dQ|EwK&X(zYRTL@aQcEs$U&9jFyTq2 zgZn+x?-nC|pilee5){&VzA1NJ)6y~bgA7?vCrj9F!DB+~P9s4}>7}YDH z`e1`DRjEc&3Fl=Wc(=^LB=w}Fy;vBU4U`|I0t$cy;Dh(A)TrqAdd60!TzCCSAk zg1!L&qkg{(-C?2-2SzXnO{1(KO^EaQ2AQ|x=G2ndv8H2Gz`$LJ04jb%nC?Qg2Yn$0 zEiD=XD!$hgS>|s}i&58~INhp{ESlF;kzyY19Ex*RFjD{Vi1KnkpdxvJ$#mexV}ASS zbP=cUmv@aMR8p3L3UaRsg6KjGTd5oYe^O|19N|-|`WJg?v3p)=PgJ6UDM>l9P-GpxPcw;{!6M;YOF{6E$n>qwB^(VM0-OwuO0`W-(G6x)lbdcPDbC3{+o&=F-ndj|K?$7^j< zR-hl-2m>%HD|0W0_4LxD<Frls$2(RQIV7X2q*k6)(q!FShUnqCKWUEG;DS zT3^O_`2K?bHGI-ClF&vQqiM8coOT)UtO4&CLwSj@LF23f^VFm00#TE#>~BsF&z;&O z)SdEMaI#I&W}4^zv(CF=CTB@7tEz-5C1r)`C6+m*#@rugu6co|B1v-6P08AyP2&@9?oucIT!ekin;k_7fSYbhh^T;yRKgJTm7VnPc+2GZ*Tgc zR)K1^>~sEA{iDFdf_tieVc%-#)+7`~|< zb)^i@S`<^x)sAvL@O@NF0wqfV#p>`3+hvFEtV9gguUrXa+FCB9gS~1w6NiJy0w9k= zQ*6_G)}cyy`mMiQm5&_OZBNYpWpb~6S8V)^_v1=cdzxFQWYOe0SLFdJWA@vi;&j2U z3BqAWk6rw0b{=V0Ia|2*d<5 zdK*`SoI)7zp#Es5>9J)K*?f3O!f!FK5K!B6UOj&%Wi?jkci^l_a`m*;+yvqqbeti4 zS*Ot;dWh_**}qPjl&n~ikmEIzeXD}xx2I|lfIQOvsoToxyrA;VVe(88DsQHD8fX=F zr!5Apf?b*aE<1TsS3>o$*;bpsPcpBsKgs;VUFxXB0wFzQHB9a95wES3Wv+&5L{!kT z7Hk&=Z|6{Qj!%TG@cQ;#X&s!1;J#yv3nhRFy>;8@`nnc2K>KMV47EQBiIthRQni!E zEB8&ZYFF~}yr+a{geCZfPmxxVS-X3u8AYR4Da*?Ju)T*@k7BsKyPPWamEUT*`EnE@ z3*NST{BGG=!1ccvd&{V*zAtLnLPY5jqy$8e6p$_nK|w%3x}=qqZcu6I?v{po>9}w~ zx;rl2-CdV>_VxdJpYeQr`Q#WnUVE*%=9~*T4bg%z{2C&V3hj^%$|GpN6*ZN% zS@A@l*^4?cCF#?_1S(zkV4P-h6l`e_S;DJF%JypzOK zL=S86L3%lckADhgZ9G8LK|fln&Ayl#O<#L}aTNzvE!_ZFZ|TGds&z%tYJce>BdI?- zS|xH@w9vhk)_mg_QU=&S%bNZ2~a1d!cXP=Aw-IweZam~9fJb(xgv}J>FDbK3|1|CQ z7&m~sk8o3BtJmH(y1VLQiS&qsQUy+0jwnp+MFZyWe#UkDX@BqF_4bu(Vs+tgv2`Kh z>+T^}MjxOj62x9{9`Bls?EhGAZw%E{Ko-DGojFV>b6{}5KB2d`o!qz<`1giyo4kE| z0@7mTjUB3foSpn&%}8_v=TQH8dgBSr$O%Ap9HaTwk61ZB8S|vxt#l?-#@SF2Rp~_S|)eo_6 zKAYrRH~oBxLpxnrw$sgnwAi9lC_`B7PYwR0M=$$`78lum3q~Z=`YF>h-@0Y)D$V+x zjgmEu5B3}MU42BZwISDqc*f3sVwbt_ZCCOU@1ggrMVHoAD&pS8vQ^v)73}I_|F}3P z?(*pOmvIfDG+E!?Ysorw9{V;TF~a*-S+q>W4GPpQ;ODK_h3YP$&}WYRi2^JQzIh7; zrVH`!H_lhKI|pv{F4}(~cfgDY$^Z0wqCht5{tr|&1coNm5MY5i4B|L5;_u^0duLf4 zT9@>9X4ai|U!n(3Pju;Q%;;)y>}sw24fpZe!Hv~8u&;V{El9j&a=J;+s_rH-jE8MC zYEf|xtdGs+=z2m^^WLgzGcu}a-?m%bn(PVR$;=&NxI^{+(Tnl{*GN`4!@CWChIg<> zjPKqmd`kHJTX9=BUqAC9(I2lLj~?NFO7MRm#x`^>oj~I`_1|vKGwca-hasML*}kC-;oxwqDWIc0upzsmOMlkTr)s~RE0@zwQ? zz?~8N7;0m>1SAy$Rl^dyiIpez(#I%M4hh!2ChRhPyeuiqj{*379v!;vbmZUs?BCGLGd;<*oD-_0e9*^XUM8rDhgahTy487W z%*c19##0Y*C<`kC#x19Si*5zM!*MDqHDnqD)i*0QictMoDcBFu*%YEla zd&wjty`I3M`#E+qcGyJf$@`tyWy9OJ$n5Lo;{!vygNsS*?V0N|+VKguCN8SH0=9SI zyIQn&ZoXYQnzA6WrpDp|Rr!;!f)j-D*!b4Ad3PH6j@J4%Wh$wYSJYOj1N^nJ04Z|Q z{x>s7eBaH$6#9KmrwrqHt!cn?fTF5|IR{{RICvU;=Nu%~K!vaL4Rn6-Fu(^Z@z)(U z6ER_H*0IqghsFC3(LBtSz@Vqdk@Vj%XXpP+AahSX)9d6U7FJNv=oGZ~(j%Rzv-yU7 zZvCiEgAD&D4!`f2;kwC^a8N5rjQTGv8)A3_C zc>U5(F~AF{(k}jTw=K8~D|`+N`TUs3Evrr37eWUy0>ZD$G1U6+hKjN&kdvG$x-_Q6 zf){bbav}W`IXdAODXb1-p5 zI^=(LxXa+)*~UKLUj5sG*91AQMnX|v!Y&|ZqML&!DDx;Oq1j4lvj&(XbDNLjUU;1P zLU3zzz~WkOj=XYb`E9qhJ5h!X@c+^1xNWPcJSF-hUTZNd#B`mrEztu4u;}4fUOE|0 zU&du5BsP-mv^zev+hp{nu=k`G%rKI~;n(R)qlU1hZ${-X=EOTeB=8`&a%xQ zhEYjQ)tsD)vtBomoejE#c>br-rF)m;E<~$puHmQly6J74HP#e!Pss2&KZX7JwqDn}~P!W`R9sCYWFD zVm3YNfwbWAE?WxgMJ;j`C?NiyMHXb=&MKD!qp(c+3ZZy-Sy)M#u?#ma9z^|k4QVA& z9QU|=RrXY>fE0m6k?MNTSbu6LlF1ra_Izmk<=Fy5dMJJU?YBWMi&9?Kk0!c_r0vkg z>foz-euIXFYvI$-Z*HMj#=2k@`?rzc))JY?ZD9lCY)zoj-JD{}MSk~Sf5mR_oC=^0 zx1aF9)}fxMDJf|v@-IRHrK3NCkimdV)E)Nb**J0B4=Cd)HedL%!;AHm;$DfUvDdHZ zXry%=SSJEP&D?`-E3a~xB%+=H5Y-pJC;SvAMxZ|Y3cSneiIvQ&z!9d&SSLBgr~7nV zT=jFfZ`KzpXUYdY=tqS5o2Vs-DBFEgnhbBG$&JW4WXZAGb5Gb(Yf-CQ;#IGQ(<*Sm zq+wuKy}+lo-R=U?^yb&?XO*a(`eC$G+aRgt7Fe0H7BTGxgMCXQ;R8>X^RtfOd8wec zhwE^Pj~A{P7HQFj!EM0jepx>IEV%@_B>3&&#A>0E0pLiPjxR?oLd1Cp@D!S^gpgJr zcle1?;sxz}{1qd-s}A+vAY0?SR4dUQN>X9#=!idS=4p4(^wNsu2YXOKv10G^Pkj_O z2+-0mFkE%r4g`S$J;Z!MzmJHPzM70H;it#-Zl-j!C`{T=dzag;>?(xMHPcFkK4Tm> zh@%0aiQ9J@*%&Y!H}_(|@LW&|AWUy-9d<@0gD`988!b(35NnTx+wt&P=kohi^)8Qw z7dBP`!jV#wzx#6DzXZ!iLnEyOmKHC(i4ROqV%x}OP|C)PVO9raE(hCWnyA+RIOf_V z;q$7#2r@vM)ev~{>mBfT7zC62+*$1ZeaNYpy4nXazHDHi*hdog?{92~`i!Rj<~X7L z_Y9{3wjCwYj-)tC+ zbjNltsI!y&a7%WMJ|kaVYD9^>J2YsED7j3KofDm*iCsJ9N<81C54~;Qjay4yKA=nE zYH>&^3D|Kc?bTV(M;m4TJwLowVw%?gOVR*K$rqN+w9?rz{#{nDNi7{fL)N!rdgwC%Ovi$$gn0`6uhC;llmDMyPPL{~Mk zp#WT%{zEA>Rz0nIw@3;db@={5I8Jzh|L!s!jZL_Dyv1JZ-aCn0E<6RT-8p!{7#~Q# z6FTyRQ?6n(LdgZOeK85>s^$JD6VTQG2v_N@SetgP0%; zOcpm}4h*i`Ie!6lB&>zstqk*)S-au>L(GBbsFnX6W*Sf}_B39yA!uE1w$InsrS@5t z3#xGOYUCP|fOkS|Rntgy8fGpGop)~a#3uMhC&AAmTrv@S;0X!k z@sl2BimO0kS+)6Rk4Up$Y>>oQGLf=Ig0RLNLZ$yZklnm&aD~b2!qtG=tt<}c4KDW; zOoKQU{>6cCTM_sb0k<3cZq4tNrnMXqDPSLs+HeTQu;x=Y+cR!29h%=%&h;IMLbdgh zhO${*gi2dGi4J)coFzN7To;0{l2B3KHx5zb3D$EQTBVp-<_#p`3^KT6snAxCXbJ1x zp705*j~=nccS`szNK4Iw5$Mk}m*QCfhn7aq$%D zNPg~sD<5pP3rz#N?XEcy42vvd=Al8dsr}wV5{`&gphC5$Tj@BcF)%5trR2d2XOi6z zMDvupAaIsmZlrG)`RPYrYv9kYLfH3>jOJ!{XUbGog7E3aI+x`A=QIc#%!FYAa7+&j z?T)3}E%jG9KVsuQmwBoT2C9zQlRi{}<^Cy9le>D%Cp;0#kj`tzsc=b0y$!IclZy4A zhFA8RBhCZiOwB?v<6lwvQ?UKHF}0_Z5fz535=XA#7iozoZnw+zobi(H=!Y>~fuT3Z z_rX1HC88qg1ceqN`JU{~Vk3xXGR8a6#eZ+&1mLQVmeA&mOioPK_>P~3CrA*q2}8b2 zpXE|39If%Qas=6;KK6iJnZ~F3CI2XmV?Psia(=a95V~XP>$fU1WOnSJg`3dKY6swGEWv4JiU+^aPKztC~ zVcHcFc;$)|IsW|!nqOY5xfRqEs8^~5uk@$vgIoqbtFL#T$$AhtjLFT$K?`hj%h44{ zS~=?+5;to>>NAg*Ti~3=_B0vG#3UrSzBjRJ6b9j8s>0KTLB`ZnE~ewf>GkjIY&0h* z$!e%Dekc(B>Rf^(EtY4p~kKAyDyfkQVQuvxR7rntTmS&)M>?hL4<$gc|N81n>@6v zowGpG2esi9Y{J)IIE-#T=C2zWl&c6OcgV6p%$Yd9yvzU`3{%svsK;(*glqu

(|+Yvj?d6FfHrm}`c9NX5BjQyKt3V%+gB2G3-Cxki7OG`qTI+u8gCY5yqhib21 z2ayZv=muV!gVz!U*nC9wDMJi%bvLS*wd~wXW7TLGlj6 zEagWSFU#wR-i~nP`oeDus?+Y0nt`UhU1^ZN}H>!Yy84Hhn3KHB_v8}+*bt?R0}bo9c!30G^(iE z<3X+CUWmPL^LU5HX;qnSkFOiIm{F#|xSC8dy?cOvM>J?-Wi~0ahrjs4>RDUJ-{ehB zc3+8x<_z~4{%;<)xlh!425>6zJunr4EyLH(_jMT@NAc}K5wcg@x5`(1MuOz_4 zB$oNXJxC7x?GyS$)`QsT)35b=Oc)H$joT9heU~h@pO#Ul22V{yZYjnRjD`H6RGt55 zh&uOC#5HCE-KZr?EHk-zJNQ+a>5F3AyE-Vye#6(0z?Ya{W)%B(?z)sdkOE^ArKJP#pIKfw<Sk8Lz^P#Ly@#`3>AEQ>zA=|^gUyI=8^-dB!d z44CJzw$+EEE2G0qx240*`p;ig?%M0-2CC3%EG*GdWtvXq#~n?QCkcHKh?j}d0DZeV zo}RaMwGSRVNE7$NzO2PdX1b?KTfMN~D`B`g7H^yTsrb=j7a}y{xbC=FC6*CgYvu#qM;jdkMGl3D?cx6g8`CUn_VE0*WTZcvxR`l$I5_y z-LYdMU%Z?dkUHigRaZ}B^Hs^J{`SrvRoh-?gI_nHC1NACI@w$htg-$WFWd~Qb?J|= zu>0o=er|CBRhVMp2G~eC`V1cPbs!?=c>el(1_Z{&S5yC`@t!+N7bvwyxm_iDJ;D<* zfe&lTxID2*=+gS}#_*u!FaSB=bPlDuVpax5|3e6zLmb-E5Za-M{tWC*w7S0>bk82U z*&zRVmWp_|tkA>htox|=LcMO#Bi;FGj{bOfGx#tPDsE}2@~P5iQ7%=8f^1W{-PA=B z%s>bMe3sn3pR}~|SdSlzfo{D$*M^Se_(%IwoeM`Oc(uF0$k>`?ANP{$t8aw!(FWsx zuXjgx?(x^DQ+aPc-PTg0(Dp~JD}OATeTNl5#b-Xj!7J+xKVa8udSD0m9`J8m#Ll)a zxh7V>0?UQLQ!qM(DaHL%-F&K2c5gweM87p-<`g9G)(@)y^H>E*TE*vboSRPvxJSb_k_2H$-o`_k zTG-vrB_g?B|K*y2+gW;5VQUIuS-^#tRR@?5`RVaHHH`CIhKKttYdf`zs~fh}_PY@f zdVcjwyIxsy@5<^=2-^#`Do1w{VzdupzS#McL9b3I}jX{fN!!7Ee>Bg@IH z*A~cW$91ziU7tBdXBzW2>_j}m;@fTfj#ruT-9U)cgMLu~s~G2CVB&B+Qok!UK%er@ZZ|3E&;)6wxY{p6FKa%?t{&6UzaYd8igFtfDvIm(KJY0Ipqbio%P+uK zitI*TA&Zr-%z7V9v*|%`>p+6I;PGLwCz+|k-|s?iQlbG*WEA_F7uFb+tnGZ=S7MzhFLAX7*0|@jR&TjiMDb&2N0r#LJ+l>$@7*QZ_u;|67CQxuhfE zjoMRq4i}89mKbl7{kj%UvRUk-K_U(6{?goaJu5FKyHm;D4@-SXK3Vuzbt16CW8-fWP2Wif+_g4hI*m1vl^ zZOHYktg1-cYCgtujMq7r)e{?mvu2tYwySY5ndDQ$;cY9{Lc}c7!IWGF%pLs^ZuOE? zQ1Z;i>ZCZiFHB$$N_>m1b!huvA}$S*l22zouH;>-^CLAQPHE0VG1qka&Mcj+`yF*!lo6FIB zKbK@E8vybB^4UO@m98=^4UL%|s@QQjzD$4m?AYu_H$AI?+Kpbd#{q0sOu`VW%(ebE z^cdM?X|BTa;Ditfa&W*au`a9MG4p`6499?1JL%5$ccEx#VR5O{0jH2V+H;^LEMpte^T zzW`O{`!VuII@eFdCa9Y!$*Kb zu;|7ZzlID5g(~X%@t7G{2B>rnj^Cee1h6jE&c}zQHYN`UIDzY~+U_vo-#XhkA-~Mb zpY6L0$5fYY-C?~t!P%Xw*d3vkSe{NMOXsb+WSg!f{6%-|r*Aja=kf$EoD0Mt8zq3# zeu208>ao#1K$UhhHdHk>#-UfYnAO&_BP!2r3=o#npSPwr*Z3DwJkGuyCyf#~TFx}0 zuZa9@HF#=4cFsphQ~D!_l;g`#nb7OZ_HICLzLH1!Rij(YC_noqTn&fq`WT<4iDqB#1jnM)&?CPmZqVVf zMUAXyQ$pg@Wz;GtxLLA^^O(C2It^l1z2_NZR$4-Z0Plhy*)?`2Nwbzz`3bSIcnN|* zM-hCIQsR07Y8zXC0Z0GWMnk2jmaGMi#7-_Q^DyiV|LJ(QFVto#R!*DLodjEhyP+BV z{qEoQu>IcA(U|4y!pN~bdGXi~R=>zxah8sU?5kbo8Fr;!@6(n3uC20MTCBYDfaUgn zJey8CqW`2Vrm8*dEw(Nk9WVR@1qa_Z*Mo{!&T;Q;Ta0{t$oP4^fZz3O2PtPoU8*O= zhNm8XMG?toPw_#vl8+OlR~52jeZX2z$HK94eC}oCwIQjXQ?U%c`AYr7piIfDIC>t) zoZ*1X?%w7}Vn-}fPJPUqP(kD)9i8J+7f4SGeIn!~&QcBHfNvZeo#l_S<`e7(6O_EC z2eIoq1*~EYyHfjyBHwrB*{2)Yaq@Aqh%ublEarmKbjN6x;$_b3nr*`yaw7MoGgm*{ zyncokUH~pxY1$Xt7E=!QE$8Z&-)s|Mk;#c}4D~NS8!l;IEdPMuqbiYd6Tlw1!iC0C6@r%4fZaTWOHoEOzeQ7om z%VdvBB$3aY_U6v^Kf(R%=$t!j>#rxjsL<2=mc^T!j+w=P^ELKL*f0Z0 zhVn~K(Vjh?NA$wUK?fAInU_Yj+;19d~_6q7pzem~@cDwz6`U0p)Pmg2%mn z!Xjt4=klys)+@SZei1VXTV~54th(4OrAEPFbTT^S7PWZ7!e}SNiE!73wrtt^1NGMq z%iXG)sx!K35+tQ{F=(k3x0qH{Zknn;ryMPtU4J+R!HB$lyOIpm4;pT-aR3WFEc>_+P>(GVdI4J_kh2bcXC8IWQG+FVf0Mj)>JRPW|Y)B`$VvZ}pXDrLYvOz>*I zIZnWl6;)Gc2j|~j9rdpR<|!nb660fmO409&qqR&R^?{idsDkDRDnn3_m&3Q@ul3x3 z?SL*q5F(o+=@1}TB|wsBw?1$e6h%So-es7b)5Ut?6;Rrx)1h87`Fl&Cqm&;q3k*}% z^UVZL#|<|3nt?f!U2C?-^<_tjkbnwQr-*4o3e;DlXV{LZ}tfKjQVViE{t0#!gu!q%oUId#9`yyq+5$SxtFv-HT| zTd>t~!#7q#i7MolJ)I@S6Bk;?M?$aY~?J_Fj_6El&(Ow$)Db+W_ww%bsSgWS0?q;3g$`As@hs%*Ab{c)f0q^$`Bb3S?Wk zfHoNPd^lI8m{HHz)HWv#;o*tlWOTj?EXv`dZOrRjOPJ@uL`2hl-&B8v=R zy}C)1RO>*LBMy1aduX#iid#|t{n{n}&GIzNj`TJN`7GXc^>3zCLwbQB9eO`&V{ma< zu1fh+L7^eU8|`>O!B4Mq*dFK6#cFha-%w;)Onf4&bM@mF5&L>@1HsYQQpX6<<+Cj1 z-m#G3*u|LKG)E#!1D4%&nk=G}@NScizBC@J8YgR$WwPM}r|l9b?c6pzzu>LfIG8jW zOFp(zR11Hsal@uHy z8P&WVuEfb{x^;U@1CXNz1D<~Vg}srQv6tXl=h-xA8PrGAYEyrJY`CB4<}bQ#Uz7h` zA%*In!dqcSh!dku|{6DhuTnp#ndn z*;-#gJn_)H3L6%nmtJ}0b0Urakg}>3T`8*h7toICPZn=a$mE~ET|=mPim^7n@1)4rlEVa9(z#-)ljhM~v( z6sn#)l*1~|C3z!QA6KPc1lR+isj)?(;rE;e76RHq_tw70uGy~+^6JZHeSRH} zNsilk*?WR}LE}<62l61JjRyFrBibmvKU6{OnlVW^Bc9fF2tpti@_5f`3A=kGt=I8kPz0MX(jIt&3IFCc8-gV>s*BPAmRjjo*? ze$vqEK_ci`{Mh;0-UR1teP%nQz`KBlblplshYyGLJ)Xn6k4p703PsB1ygFkne72~)jhFEp=>Cj}n@ds5uz~~tDrL3lX zai}1`3BpSQH0vge!{!klG1-H-8 zU4&KLhe;J`pt#)6f`_NB3&x)TnSn3B@eF{*!!(~j>M&gz2r;Y# z+@|i1{#I!oQjOg-C8XUZ8k*=Xj`e4-K&78ize|mK^ZCnw)I6Vw8&HL9HF6k|`O(te z1=3w=5SH(vg2AQ$&AI%kZk23xtI(bFSejpfrL(6%NY`NkKF_m37pLz@gOr4Cn7*)B%wl= z`8tYKTLWuq8q|qy7b~$YG9Lk_@2@zHkhf8HOu8ym2PO@9nO@{w)p|szst19FLTB-l zz2RGa5Kllk2K7ZoIj9Qp@IWge<8wOB`k3ca%g97<~lN?8If`qB%{Ofl%K`qz=51q<~GGpfR{g2g~u3gVc)~imy zsinwQW(dZE3PV995grXj#oh%Hop)e=u>5?}Pi<|3KmF?yE?^qjtz&?a) zgHosCK1aTsAGn$MST$S|LmO@YB+!|6UA2RU zOZX$}IyQfwoBGd@YLni-6-B`m8H9=eoZ;Hbd@xknk)xIDQ--f)IbD6w=uyh7R(uC= zq?Gk?L?HsTA~ohjr|l-pijfA6gi{C>Tidp_i6s&l#m<2unON3QgntB;mk#0?@Av12 ztGxx#ci}Ez8hylya}&|BVM3V!X8{4JjdA~Pss<-1tR;Y`c%E-hQGLJIttZ2b( zl&`NScwO%GS6PHm-JXS9Uc3NMM}byNX@XT1Si^I0`+_Esppa0B)ts!FyRXt`9KA%ZDeA($y-wq;m>myu0OwwN*MqRlz zv^yXJ#{jJ(@T92~S$ZLvfV;vZgG95j2g5)71i$ZN}zw--BpyCbp;O0kf0xj=sgwD(^~L1z~F z&P0T;#QQhLZ7?TC;Q1#L>?1d z3D))y9Yn<37La*um?`vZsx0maMPBUDyMREM#)F{=j^$( zuwO`WOHxNFv`Pf|Y>WHW%eSK7%jj|cz(%L93l88^mae6G>e%mtyq*|&wucz~^Gd7w zHE?^)?c)j}VZR5^qajTO_A72=URaeBoRVb3JPh(O*nOO-S+svzPzeAfG>#~KAVYLd zvVf}nZ{k;q652fX+CiTc@F3di`*>$ll}Rb!_$q;aJZ1vu?%Dua(?F?_jJ^BcA9wS& zCf6BbmLlB&9y@tr;V3nm5MWT>sg<#${g$*E@Cwo zLg}se?#ZSmD#n~_jy@?f>6ZjVL*>_rNrwC{N!$2d*3l-rou*a z2=r3Jqsw~UaB!uF@2SH_4FF7w?D#H1ZBkA1FEv(K;2vvoI1C@c?(bOPG?Y5&M=mT> zrIZnM7Ww#SHx{bbC_rZ=KIa|!LJ|-&Gyh9|z1a9Ye)4Ea^xon>qx@ZXzpO2{HlimB z&?U4VprP?$y~@%ow_WQq-JJkXe{RCGWK$mqessL!b`G8x>~81ZN0rU&PG6#vo{pR6 z(j!HLtlgoQ#>m!FUJgg-_5N7M3&R+mWc>54VuWU;xkBi|drAY~T!7QGanAq$uQdCK ziLL@FGkg6E@K7*QovH-ur8Yg#u&V~9E2T!=*#!zGW(Wv1I1R7_m*ulU;HD8L;^|R7 zhnCm9=iif;JTMm?^;~=rq?;7rN*g62%j=J0zYoS1Dx^b4JBpq0PrIjAPJ!9$Z_o_Z z2Q?-v!ea!YttoVS3sg=pv49ffyyv;al0%_d16t!#)~)>DP)FkB)84y#J@NK**-A*q zjCpaQ@K?5*LH8nXh5f8(`+c{n_u}t1CfhDps^GwV@R{BmRsi=-vub+*7bhJCUCVMy zMVz8%2+@^NI(se)3@uXs&Z3tF=amZ#CtqKoO442+Zyv0)&_qqf6G~OI1D4W~?I9E; zK;CuY(*ETioTsy=7F~zE1%O`{?Uz(KbkhEyVAKQR8U~#@USJX-0&=p|y%kVmjra{W zH#HRlr8}rYMXl1S{3A`fIgcCsMq#Uxyfwp zT1U7zfP{s|2SL`-^rATGlZwvYalcZ0-j}`;*L2L4VQ>LDM*wA)*C^cyT)jYA1E zJD6U)4x5thU@|kIW(zL>`2j*-icP^zxm(1$3Mm{Yvi7kh11hQiy+34qupW(Hc;XJ0 zsj_5e(?vLwluAx_i6_sOz3jPSy&C)Q{ zD3F_iVeR{ehl*6V+F;(~tXK&KFHxHB=a?{6n5FgyepdvJHk48Z<~K1RBe6^gULB`6 zlV?Xy3K|^E?-Jani9wX?6UJfk$Dk@n2;=2;t-}(m;r!W~ueeuNSGa(#!t{YY)oBmZ z(sdy+^^kGc-4!GUAo|oD56Q?0xGW)g`#O^9@QFzf>LyeIE)#=W(o`Pj)WYZU zUL@(63bD?H$=6!hZya~l-H&>C4gd`xa(ktu zYTm=|K78NdI2!`2a>)Sm6AfH^Ani>THu3}lAV4|U6e=`Wi%3QhS~neCdm7o#ZM#y{ zjvBc3yEc77Lp;2b&}=q^0v1Cl;NQpuTwV!9;8_~NXh@aci_HR&#}*3&aPSxfftYu* zRFDV!Sz0?g?!|I6_Egd=pE5o4LCGsoepj+kvmkBJ+VKgQSCV}erGP+e{cq=p1$|PP z^-lDO;P_nNt=LC$)XMK$S2B}Y8}`(;#C-<;N6n(Qj~fmk678iIuJ9{JM-Ipd_sn+` z%3;uohL-hnB>?tKHc)r#`qa(N&hk2JlU$zdL4{vXADwr8T2v`Dn}DEG?~xVEy}jYM z7(56J`N~~Q+GORsl=+NmL5@VE{3D=yCc3RF%$k{iT)+>9O0FbKwcLC{5q?Vy?6(yf z*;-%dnXxtK0D{pRNZPa2I+%j^T#bakpjf-=RQ;6rcv*Kq;1||o`DtuUVTC{5RmT;Q zN*v4cnjYtR{BDqLmK)JM+j4Z3LjnuZ+MvND={u!pl3cLBD{1x+omb?;hQ6 zLoY&=-}b^kGDvJ!C~NILqCrLjl@XeXA>MEgp=%QGdNp@JO&n$1kwfm2G+kzrgzH$C z^8$l$h4)2yROIn#pm*izJ<#$EOFl(*>=<_F(~fZck~cY{N78*ZMTgT=LN)JAjPoLe zNdhr5cY^R3$&!akW3Gz?Uyxh3NXWd(?EGrJa3#&v;fL1 z4038MtGl4y{sj#4m(CBCOyjOb98Txe-L#GjrW;(Tu47N7qE*;$Qyi~LnJD*=ykc^G z^YEd)1HK>r{zDX`9|}Np-?RZz-w{F{V1Fw&fU^I$cXe&JK202UH_)uVI+P*e=tfdH zQ?V+Eg$4I?lHn4j{ZeTUb8Jq>%I+>?DSPeG`jv=KAfenc0;Y=*mdwH>T=)}{&BVW? z!~HR+S{c59G=&l@lLYJYW+s_pvmQDoiUOON34M{dLQ%2y@zcPan?J*Ck6%>Fu7?eQ zO&v0)USu0Ia zA1MOOtg;YJXHs;QbZe69F&Iyvn5oxM=Rw3IY2Tk+ek9dr@Ueou+Hs9iN9UX)zoIC+ zs^z#T>ggw_s*o0+GumFPYifhMghZ4jV9Vs<@nH%$?zR9jFn-;8p5ja(Xyu*Zfza{t zs?F#KyWO-9$UlGa!uW0cEM@}FqZ_}gQ6mgv3NO`o0fhO+27(|nCbX%=o?vum2P;A3 zk%0W}XQ+D;3*BMV-;Oa_*;u;k*gw)H?0^ssFe^|QXMh6_*B{u@KigmG zaSMo1nfx9-J&8Q>STzjI{NVOgR|Sri22a^xU06M5zM{w4L?1Rt#STZ zl&^i_Am^oGpe|wv-zc?hk#lG3J1LwaxM{vhX63-y&*jei_>_+oe9M0va1`m4sPmH% zri*qv=sOy}mCZ8(H1Mxr{w%BxD1e=0zZIjvt%o3*KjkuQp(uX|+8xj@%gwZS)&ln^ zgtvZ7CYx=sSi8EfY%!>0lJrsWhvG1DpoBs+W?!}HONP@%)eLJVnnE;bGL8Y;?LRC6 zY6kcbzZ>Q}Zz+m2DimYs>WWl)-5wcAap>v-JYcjq3_#JN$_NY$Yz1*PnU1N$HjP5>=2_43@8Do_te-9UX6`clS+a0nny zLjj4g1`13l(f}NgKkN=>P<)-LESkml1pYrQD3}1Kr~bhN30Ht{;>E7qHZQkMQSMZR zHt9K}WA&k0!BsN-i_fn|vt&Vg{O%|m2RsMui#IRE{@U+fHGbuQ1Z>zW4q=ctkZ^{b zoSe4$Hj^dw?U*rhghG1`%qn?nb-~AX$8_lg-Wo0xWIU&X2>*_J6xVk%{4JupTShmq zDUHXug*Z;bdEJ;)*b$I}0p%W`kOn|JfB8(|kk|R}PlB$h2fcBBN-*Guud`s#HmHK| zFL|)oy0Et92U4aDmd-WH7VSFZKrLuAzf8b1{}rNZ2bgkJ$2Wr=y4)fTtdjwxY(00* z)gOb;DoqDqMSUzS6U&sm*||6tq0N&|;(`JZ8d|njl*nb0UEmWe;vm!SA~d>VavGQC z>j#t(TLAW9Ez=XH+MYoYL3D&Nm?R99QNUTKdK#1M8UK?Xuk;LAb*Sluwn^3jxBP|`IzAiG09eZPdC8_Y|J>JJ;exiTHdW7BC?rgJb)?9PNyxG^020WO@ zgtFBK7(06V^F49rlARoj{jHt0>Zpra~_*57h8p zAhTTpUV*?#^BKy)0Z#V~s;!3J!nIYPf36m zZm(V+tp^Ce47xRdjhZ}SR12^7N(odTz>iVMRg}~%3-R`F-~Ic@*>;%$iw&9t&@q+O z5DK`B*qHiTga6J$Yg%ka4Jg*~!+74jAw-G(bzC;+;Gje3{{SD%yiXtkQ9Vv8U#L&{+FN3Ymfdcy=tzV; z^ASaffW-h+`I1|m@ktbDGjgA3d0qnD#ZTD(g`{QxcQA8@zWW#2lVcScTY$Yv)!3|{ zx+9oW!sO7p!{4(Jb;}j4pl>$6vl9&Fhc6~O&JJqguX;VEnqM3YWKgJm;9F?F^InQF zg^~nr^#;Yd#G14GdqsWpPc4%XWkhuvqQkDCs?9Y2`HsuQiC9I(D9ItnMKHS2!NBKj z$*sQL@Wu~AOeaK7#x~6=vBv>>yWq>&d`c$lF^c(&mhBTrG!lJ2g;&neHqd{_t5~MH z{Xw;4BnhjV*`Cx_U9JUVY0Ea-e$9BWUbrAppo+XN>A<7|?CGdGAmDd9^{$N9n5k6# z0&NI=Kq1^5H{=6OW*y;0Xj&SL*iW`T%%5 zY_dQUfTcA#@AtPp^{MWsq^mt2)MB^KvzM%I2Am0tR0#KOt|1VZO2`%8KbZ}mnQ>ua zF*Z|M;lTgCeGJ}dh=#Bp%>~Af%-10|T9>S=OUjXMjDs!Tx+B>>igR7$OIVhKZz{ z#<{P@b;4=hy#_`X6~P^(8(*L*MHjVI^|#bTm$RQn#wY>?Todp5)!0qlP5f4keCbW5?e>vG-<{oe%uP?fFv zI2r!4U#D}G?eLD<<%56Q00(S?f|$z!%jq?jDp0m#DBR9eO6dkBKPbdcU`?#jP+hFl zFPQTRL(~hLFLhew5qQC;a9m%%Dc2%i%7#P7^jn)MzRtXI$=T)9PW`MK=qB6t;T_lz zb)|E?6()lxeEWIL;YQK(YD;8qMwq5>h~dcRNqKkB1@ zuciD(V%=@nLc+>gE|_2y2hc$;9Kk={0CUs>OxMi|2*4xM>YPeu7pF%cN_fR@?p$=Q zwy$5m;{2RWJ1168V*3@7!>H4n3VG#UBw{)G-%2nw>tHx12ATb0N>?rR=y3VWrlS21 z*ZOjirpikOzW<2sY8%D0bccXT(1K##5aM=y0S94oVW1bXVo3q-`v;p{ zNVh}u06vr7ty+(*PA>k1Mv92>^Ivf5C`;{t{*^tK5vsETnx#K-a&j&|H3ITmP5s)@jiNTre8%3yUW^`SG(p(m$nPYXoX zeDCOA{7WbRL_p{JzwQ;6-zttU=m5CEzeBtF-2hWF*;D4EJ<+eGm_N-i!_AGme)WU! zR~D5@Qi;#FgLafhhy>EX1sJryHJLlrsu}4_z|5YGIy8_0W0K~ z&gOHbBo;Zp-Ft1F5`8p4dn70)WKzKdBc7^Ya5xxN%@5ve1%R%q6eovAQxI(d^YLQQ zxy0VQA4XP{j|qQ1Z7$8zo$XFy|aVRR9#xFn!xc|!>Po&J2Nc* z@7UGI4w!jY;@3_3a)o?==^53kQSt6IUe&bG=$VU=%>1R2_mC-Sb-iEziT<$(Gb!0l zJ>8#Ve(R7~rmo*;X3Bn$iQ-=0b2s=++Ym+3Y(32}BIm zZN9yEGoaO8UMdE%EW3m6pq|41QTE~JAZaUa`kGqRFZA|oKU}W3QEeX}yUwD-u!Gmt z9ak`5x$C0bWF)p`yYqJ=UZcDZ9sh^2 zw~VT4efNeH6A@7qq!AHO8kDY$l!BBEh*h8T?<$=JlA6X z&w0)n@AKu|ANJV8!3LRY&U;?hFXa(nC_X|zO z-_zjyEY`6b{h`Th&FhG{1E?~>Iq!AEcIdT8Mu>TNd12&nG?0$Cx@b+6c@5c{K;Qh{ zYN}1P1MrENq3V6L~{ROY3z!*BwOFom~Xj z0o_4?)0kfA7ypf%+u{)v2Y#m?D77;;+26nSqCKkJy0IxMkt9fq$K%aLNuX09I~z($ ziS%6ORh(M)MeVQN^8;;`w(4#XjMB?&v70IaL{S(b2B>z7M2ww+f`W+k{bh*M%ckc* zIUdwqqfDQaq`&+WSOy`02Narro`lrDfx2P8SeXIi^y$7w8o3xjQ?b$D!!xwOV1IfA zAKp21-r8n3n3G+<4uvM7N>6CugipsyaN6k+x7$GOS+N^FcMldkB?3%0Cr1^t$O$hs zOQi1M^(V=3YkiQxbr`~S*GmZEPf*> z1NnCW=)DkQa7%rHsVo`hHPFe$0o#+^#MLQIVgCq)3;|VGTun`lL*U9P`y9p~^p-Fv zjX|#u|3EgbDkvPUiW}n$V$fKwlJ6$gw)TIjL|K^$V}+s(&KXsrHJ1uWSV)t^ToI-dF$tB z7V!)KwvMHN?QG=q_L9#Z}sA@%OjG>JaMAld|%F>=|6_Z%SXZtaJ_qz7$!X1BWnJldl2W`9s<&TcuDeunI=)T8Pbf`}yh0 z&`ae9xx1^;kiwo3qFk?xEwr}s;)QG~VN!?^I@IjXb@Ta(JJO{7V`+Uemaea;sB%vR zoj?~r@M1JPw-A7mL)Dqq56_{Bt9vj7?$axv(&!(2!p?1jrl_$}&!(Bv5Y*)t#;5}z zLWk*LLKQx$t*SDpK}apKr$^1oiGZwyhZ{BGOpX%BEJ+i+hIgpl9wihS&GuENIU%E+ zlM!eLTwVtq1HP!Lg9sU>N*s8XU*&a>k76}GgbVMD>B>_wp{(6Rql4sRq}E4zFyb~$ zN+4L;u3~g2K$(GbMXf^ECk1#7>oOhjjn8b<7{zP%QS)L#rM`7$NDVgBc>RK|&HlY& z*RxZQ3?+4x_|-sNJUQD}5CYGcQV{$4rHWySXEEdfw z88!z~1`n(mj^#R+8acJ(k4}oY2srGmlh2yZJC|JkOay&hks5zh82Y4s~en1~tV3cZ+Un!h{PDiwhbOhkm8)8OJmwzq}9vsaj? za;Z{KG-NG@3Ul9!C{cc>c}KD8k2wF>*gxkN zqu_vl{-OJybExd$-X83MGeEsBH{8rcqDkO`eaH*YlRUVY*4rEaGINk@3pY~;s$(UZ zC^Jv3z9;Ig)f}SqLfamf&c6`v_Dc;@gH>wbXK|t30}LWIRSBL|D5{~k$J)pzY9(2! za08t3dU<7XzW+TaICG$#lrq{a!%&l@Vs+K}nXSl=n<{+{Z4n*PdxgEI-bx+TIt0}K zsPsGIYrfSSiGZEH+VaueB?BVirI~C6qenrMS{Yb?sij2Je;wQ%V_%G; z_rPdvsPWsEe#RF()w;?ZaI7xfxO0bCw}>8_&dX{Q0wfhRf|!>qife+ueR*aO#Bf8#>opG!=d6=f!$YKXsHp59;6rB&4swTOA|0Hd zyAom#!{h{^EcJVJPLY1YWaXyv;9$?;{2q(b>T?FI8iM;Ta;Dpg<4p7SC+LFpZGF;< z3)d9Yq%UjL28d>EEiW?nIA+NYg)Xd|}71mup z%N_oByznv>j#jTC`Z^%8gbiK<34XD!^bJWPI^A(j0kX~G?wZ^J2F?14v=#)mC*&5K zY{uJ=a@n1w@(c{l4?R4KUbstW-;_7$BX3o&LhZG>geC`s8)e+VmW1wuAGyOVCvB5r z*vekUoD`!En(3QO1PyYn)+MAWJl9@bFm@f?4?7C|$8n_SV+DTWb(d1(;go?_yBjrU z8MlmLv@`{>BEHNPXGl^FZZy$v`og#^^+5nSSz+BCMrjoqBmgdyV_2Lj z-s>pJ;Bko~mP7Cox#Ije`S{dNq@7W%w9B@w5);gO0ulmm@R>V;PLDq-mSV-66{;2+ z((&2-jWMtyC^MVJ0)fZ(zr<;M*4rql_*;B|GwlAPI z2NCZMtLCAo`<|xp-em#1wJS)k-iMu-6AN5XX^)0X{`{4(v(p_&K>EfVJz_C?*qM0p z3>D^-SW6;lmRCda1IFG-27qgFFtJ%r-Gn(S6Dw_~EkK*MBl?0XlvakKnByhO9>nfu z+|>kqTwu=$$^C;1MJIVJ1ufe;PTq(p7R49x*vjOU`WjLcj&L+DD+f-8%^O7xCI|Ve zu#jq@iW><~kMCpq`{0s#!@FU2bGqT9Y0F>cADs$Rh~OZZ*%(4xV$_e6_~F8z(vu{S zZPPyAYjjp}PQV*Qy#<$=6-= zm}Lo~=dhT}UKy!anA@^39$woqdifMhj>N0kjn5b_GsoKgt57>$sqMSGy1Tut0F|rR z&-T_Lo)Y)PR}~uu_QJhg!7GU%M~W@1?{|hGjAO--`QYh%qAZg>^9GZNkO} zX)v@pAd4YSUB3YnH#yMmH*MD!*@Lz~#UwVE!xrY<0Rg;n$uGQ!cKaUDrjO;PDplZ4 zI&SdyJAa^zC$%PK>Nj6BrniGfU>fjKz`iwr!e3sx2=8%7^O0`?OF*A53aHE!A&;vd zdr6D9U&eMjTurKJ)1*Oex#tZ=3PXaeJ5ple4}s&E3-W%ZKxixuNJ_+4{@D4@b> zynTf{Gi*@1$*k!=uif=gSYI;CdQTf{@!yh=SK+_20V6dof|+`nC}3Ry`^_4!5jn2| z?wjbmp{?g1-t#)FY29tMp=`P?P#_hx&llyyjE@=_*{5h+;J`+1?EIZX`t;~^`=r0A zey-`9oSO5-u#(sTCzV!8oFj=rng7Ic-%dQRPvj#eq6oihZRFyk+n@@4q3P&+&00R$ z)Tw0+hoCjLUd3R}<zPS* zIG0F-6(*W&H!pQ?Hz3>|O^fHHGERqiyI&5i8ITt2GKMWO5HZZNKxv@4X-RkHJlac(U;v3qE{4(mCaC`jjH1S8o!1f@}VBmNQ7j@aloX z{BHWm-UF&fFF_rG6;@WSmYO;AW#!BJShh1I-S%YS#H~KxN>CW5Y^={;MRbIoPW4U5YKF3H^oTUrv z=r?`puh8F^MiW9iX945q)d(=vq^c{v+>QY==?AoN9QQJ{<1b+efJDg|<9EaXA?SBt zq;o(^kV}?yE}1O%tHdmLp}WMwq<~awo$!Y?F4{$!;J=nwq$jWFJe_Fye64_A;L(Rj zmbYlz_(9HO-J-96_bwW7^g0_`JsxGYSVafZTJAy=&0L+0fkrF(+gi%m#M=aaZV6Spg1qFt7cih_ z)V0`4&aeGB=S#S(0&bi!TM>#nSV7+CC^=S7d43=vVS^bE{+Y!4kC^ZoBtuLFKE}tc z@;c&C#CL*T`tuWF@LurS;{H6J-cXJv$3df@4ZQ;l;3s*_$(HTHd?KN5S@RVt_j4|P z4eDCKFNUURVa=b!kS^!UUq7rv;y*k1 z=+6b%ZZx#0#iMi78_FfAo~S>_%?asmsp(k1bcS(I>6*nAiimM;0H|t3!?V;Ixye!8 zKzYVyTMW3PZk+!>;^o>Pw*t>R{71YKrDV~43$JAk)wSW*G00O%GdI*3l8oR0ZT6F0 z(1XsBce14ka$b&)f6Bf;A|_Gg@#W^sE$8)%PGl}I3yQxC_GdBBfATVb-F*b4sc{3K zZP)h915mTl(g?pzqSjd7d5RD6>4N_>sx0IzlW{CPFTtW--9^V zCoGFr9G!I?r^bVR&=h?7cd$#jCEsRh5)c%%<+bbUj`sOlzFj~#d7DK|N9k!DF==2& z%$u+Jm~ap^a2n)EI?zP0S9pXAn}wLNIhmcp682~{9eN6_}4Rp%p zlc|p~fD$N=xnY&S>W$#wF%Q&E`p!G_8s11LX5J&x_YJfyx_#djGhrZQHI=~}aSBgl zrjqUFtj*aikqC=Ni!3~-RY(HLYGLTc#lurFYNkqfI{iBlFYA=AE=V)wQAm@9LCq`- z)PQ2~rsc%fds^S!ocVnp;{kc%ED>(tTTx7wK46YJ%|Kquc0ZT(ZNcRR{5hUmqsA=W z2-C?9je6R7 z{Lg{MCp1L4qAp{H)D_Ze8BA&&>7|qZ_*W=&=T<&%`Soa2_rP@KKIq4eNJj(odb$J` zv*iMgf=zsbFFD#amnHPgv~QI()!@Q?81URas>S8H!I7zkL4d4Mg{9u-I zvmLa*n-JWVooyhgSgvMD6ijpPofXGhk%-u!J(0OmiA}RdyJsYZH8-fWoC9Q5Y@yk3 zqIp$NVwRG^`N}fIA(VS_lmQ|SqrpYjlWo+r*c-X7j%}tlF){R#MLo}~`r1VcK>KLL zdhosa4l!`>8k4a$g4i1wkr5zslPB>)O|B0?>5Q-WA03XLcjZR@-GW&3K%6-9bJAo~ z^5+MP!&hXk`j)F55dn^Z2!LdCfmz=&*FR3js~m<|#&I6I1-b$NKEqsc6nR0#3KBU7 zjB(#eo`^{)bPVY?l}(0yZx<-buFIE<0e^S1Nhki=5PrJ1LXgpfhGWz1PV)oP)!+dJ)Y~ZT_LNScjZyNi zkUjg=dN*pk$CO%9ebvXn^jJjF8T-SbF1>T>K(Uej))-~~Ve7zJpK8@{Q=FlR6C+#& z2h+Pdr+l;bi%l`Fsvta_>kDN>8s+$TO&rFBb=U1W{-UIAEYU?xCyz&3p`)13@EgE@ zT@RX?^LO(Y`}vi{7dbWL<*x(&A0CR*`@Q*zFs&f?w>Mxtc}rI{`l<@x=P+98&?ak)d_lvHBW5@^CMymjw}LvdMR zglf9jb4d8eDV=^@rhY;q^6EoJbQpwCDgH{1I~S=y;cCu6kmcT+dPtW#4+nw2Sj5PW z-7nrsq)0z`CF$haJghRa6ZeU*f`2ohJ6#ramZ~F@BgCE9q?J-$E|{v1BZI#2?p69~ zEgI#AvkdRc#$WD4H*jNA8s!?ipDrhV%+IvNL`FK*>kG?PW;RnC;Rli)!An?I6r+~G z<8{#Jf}#f?v1k$x$8CDc&Tp%fqJu zc!IOEZcT=-0`jE--jUM+qVYQag;SyhmbNC@t{0~F2hF&h6ryQa;~+jEOT+Z`F6Jcxt(i%&@tXDINYZ94VFOm&a9@ULi_`946 zA$;F#hgJZWA^D+&epPr3$3`gEeE9kg;6ZnXZb2kr=lSgL^6Sdo6pQ(gOcD;mC4!a_F=3gNOH1_aqJU1 z+E+fbRHp8H-+$(9X7fnn7u&s}I+a?o(U7i$id|VF?AX8)+}xWElJI7Ds5Gkr|AvYG zJ>eqTqLcs(Fz1;pFjT4Zj51C(tw!t5+Waz!pj4soamQO?%%O2hQ~7i>zcb8pyBJx` z`FGx$V>Q1|H_jQRlNOyg>!tN^I5KI1tgzczxx)_J;Wx&l>%b3@paJE`|F{E7*vZ5} zBLqKvCwVk=oF#XI&r{Shxy?sm^Qd}qmvE2`OTD>~p(ugP(LBKU``-_J3*qlq7s}wL zgkBgL#)v~(3}*A=$$e%`_UqmPG8Z{r9Y61v+oG|cYwV{`7Fb-C>K~zKC&rXS#hc+e zfrr^=v%g%GiV3?2Yiodd3ZC_QMOy=HZ6y{XMbo}a&N~VjA|2)0ing{&2o0}|2U@RJ z+3p~o`yW=kcp)5OWR^o@O<(48zy^j#kKF3R8YYG-;o1$*&msIt?BJ|`<19&^`jqv_*BUlBi~*I{X~CcU#USC#oKIE zg6)Maaj4g|>Q@A2x^6hL>0*LNv0_g!J1rqwAPC%>@#dilIyD9qk=PE4DNN`s7 z|M7sPcTC3h{(Q8SmDihkfbXYfXFa+E&&Uu+0`|*VA3i(*=-ZFEdLIi>z2wAI+lPW| zkI>S$nmby(TA1ZqF%P;ko+Bp6Ao)=Qd|to=t!N4Z-Vof8t*KyHy+{zbQZgl%N%y;Aoa6`S?)z1 z`KQlM62d=4Z*Sv&zg5^dzPV|Z2IuzSf6u2$1{|4pJ2mT>s)`*2 zjeNN9LWVXw-s9N9UZDhiMt_4xodZq-4=r0nX|a^9zPHG1C8{>zlHgaBI1hDjIdtI=m3m zvAi@+TjT6L8y%F{`9q1crVXh3&%J?Zbb?;}xw(qM{{&B-UNm*Mwgf|$$hrp{u%COm zVal_|kM6}Pq>9B1eTDxFW|lH}^%oYQe*rM~N#yHX;v3Dy0^W!_T2&>h?Em?kJ90~ z+WqgiaNM6D7fgUA8zT5ij&fmkhJ1L|dT-8J(g)G5ZmbO8(kHfX^6Q6J(3`=e*4F^5 zTKIyzLDzQxqs<0qA3xl)*lH3j?hI!PRwcE$w$_yERx>lQW(0EIDm3l0q8 z>%&>_;Y`Yr0F`5Ba%H6dLmGIJ&!s!PmsY_ykX!kT$Cj3#7dw~JSwqPU1Y;qNX6taQ zv%nwABnAv>`Y$t;+ig7rsqK9LDIqxo2q`cQMgwen!X2l3gg~ z4devu5j2#8r$pR1^S?gL_lU!s0#B#)&S~|AZPAxLELY^geG2;RFF;8DDg6IWBw|7V zmj6FYVoFi=RGzz`ZmF8qWN+kt%vqO{Rl~*mW@bu(WFCF(|8dK8iext%mZqvMd?P4Oe@{H zSFDx?X6sJ4Mkj}qxG01T--#nenlPid4n!wmq6Pka&i;+LhCc{Z=s0k^m6&kIz-F&s zAImwwcileQw4tK^Ff4F(_gB~ydY;o*-tuK$)#3tWpWfE^FXkPZbmup`AaHqT2@@1N z{r{!ZO{~271AcSirT|v0j5shs`N7o7W*T|E^7mF#mK=Xt|5HgV`Ga9d&_Xa)!T3k1 zvevuWTTpkgyvr z-bJAxuK@%*|7(8gh+e4{!KeK(R(nzBnow)JcPZpE!PcSCO&@ zjt|ZXHtx%$_GbVZosB)v0V=6nHQ_{^XRNXWlUaDQNSJPsR~ zmYB~bvqh$A4eJIjNVzt8;VEBsSv@!qrLgpFS@TuLIMUaf8ybYO$#IETYM0h#DtA_g zscK5raEhyq5=m#&ATPguGu(3Wqx~$w8e{cyt zx*mnE9dkmVXQ#z?i(zuguE4|dk!=z_3qZ%RkHB{>yhk=rzoWa0$QIL)@GkLH{TpSk zGA@3#Yf&(q_?dmi?%{n}E~JK26eW&D8Lc>|d|(3o{cmg>ETuK<|Fx7p%(T;4C;gIV zidEpC*BFWy{PktdLkIsOmU{KGNu{5=6XO>RO{|U{N1u1344bv+Lvj14l{d?R<%lh23qzYph z_qW(OxVWTZ6qcziqmSR&11%?8X=CDy#~~mfU^g4sqGMCws_s9gIQKi|F3gl~qjkbn zg*op(?Y#-=rNF9)J2B6WQWP?+Km2JD6!Q112%>N)tHC(7REt&pU&j;(@p!5gDZ67` zSzd9xH1gIceW2W_VAey?nWeyb@-kymkt422#>jeuEQ76((;t(vKPR)QhWF@m*Hd2| zv?LLSTdvTI4#*khs;kHu=?-3I4t7Fe`3Y)Bj{8ulZ8_Pkt|(!Csjy1bSJsrGu?h-C ze)Vu@TMpJnfP}=Cwq{i9wn-NT0Tub!Wn`(@5WP|(f@T;t-$_k^67mOLm}iC$F6rCk?4wMC&`Wl>g8fF)@b z$>41Ll!B4q*n9W{~&lTY27vbr7d1U^kaWf7WvJd7%KTNohj4o<*JLV3VIJg^ynd3x_hQagg!cv;SS)89c0M2rh$)ox%@e zLwIS@C*Fdmi{9X`hh)=*31sE|$)0rRnT_k$kAH@rsIWOK*wkDl->eBjOi3(S$Co?Y zp&qRYki%Ayox{M#vpwk>MqyGd0%B^{;Qu6?^lLP;-@}fu`*Dlpj753!E-?mX z`5)W!&+M)&fqnf3&X#a?ywjsa!Fw%B)eU%p>gBPJW7G!KO{`fKsroV*#ni;>+yW?q zC+WYBRMdhF73;N((I|O1RbpH1$_uZ~Rdx~aeN^vhdx<$jbLzmgT{SWivCEV&w zWMZde2fKs|kiqK)joVWo2}+lxvJN_c0@wx!Qwd==QX~@~v;TddBdDMGL}~rX^A9Xn z&Q3TfPfz*Zehz)}NIB}$!7pE}?y@b02&Qobgs-Wx|9zGWDZ$rAMo+Jv9((2d$cl7} z>oys={+#jbdK8-Snhf5kY@2=tu2FF8hM+%E>&!2^K_C8NJk?h8r;8l7L}L{j@8bAS zr?%dnUy1=^kT4HK>Oii*y>*f=|H0%-!lUn=V^9*jn(+q@e;^Wr@a-k0j)%5e;>J1j zqAJ6ze-VhkGH9XW%%jBT$}5rV_KK&RKA~`MdMM+BFh5vFop{pV_l5Yxf|q`bN+Jt z{P~mVpNgNBJbI|;y8Pha?=gcNO?*hP=4|tE;#7Gh9@m;Uq7#p0^xzt=18wk;h!&QZ z6CWY90C8HbCG!^WSRW@zqUIpZ6j5U5a9BH7ip8Wc0^9JLT&*+7c)kOA z$oZux=l=&`o-j3qJ5;hp?#$?NO1{NRN08xpY2nsaRC-&*vZ~tb+$UxYezxd!I;S;D7bc{bvF^?xAP)Uf@jGY~ok`vwn9jQ{$>kF3FWHhSk^X z)NVP2of=n>OL2D=d9L=r%?9uxHOw{T9?O)9&0V9eVh33B{XXbFy+-$R5;Z+$tsNs* zOBfT6s8##2QSU-mypMSnizy3K{w|ty7hNF{V`_3jT96X6#llcPuPua_qim_#r4TFU z!AsRlXjAVUdc$eaDqs50$#3q@*;EAKy(hAG3tfmmgDG!w_-=Rc6=LtLi@xhgAsMPU zgV^!|VDrgpPDildag>40xhtI?0^qUGS2sk{HhAGaW7s#iSRu1PwZtwBR4?{N0*=ijFNFv=KZBD)y*$ z3s#yrO(1z~kE@r22Jb&6Gd|(#Gzh)5=EqKr zPnd&w+3jW*0~zmafb-@app-_hr=+q1)d`(Zj&^+wLj*-QKuNr%9FZ}i6bYZ|Ph>^p zJ|m!05cSE)4_1CWswb!|$hQq$Xaf5at$GbB%+`ajXSVpUiB$K@^J+*a{dnE_wVr&5 ztjGYsp=jofrWDcQ?!4)H5zLd4N~vQN))$QiZC;pdibXJ;kdbgE9=!XoF!w-)Rq#~# zb}1q$xGL)6$>Ff{8``(!d+pPk2Mvbnn#2R#<&4ASm&t2Z(lxtHU2S;{33I^&rwN(9 z=cYc0iP;B{oE7^4gJu;Gm}>lv_fWNPT*&=+O^l?`mWW~?KG>Kba&d8iMe$pzQoZI< ziPVSNq|xNOVxml`3SZSr*Oeip2U{&M4o&fQW1n1bha~X+a!IdRSl9a3hV(O0#JzTf z3vm;%L1QYG%Z$F3f~YTp{G5bm9cMU!u0#PA%+Gt^YrV+D^Qw9(TND|XM@&vAt1R^U z)zl@uC7HFV`7riSh>yc$BuaoCkrhP#0VD(`h+w|^&YN}Di1;0fa=r;1+?E9SZ~wK| zbLGts09egqxP13;B2 zNAGele_tax!VGGV!Dn*`B(n|BQ4dlkn>7;9v-)D-9E=ys5I3p+=;j1Ba;qtW6SlA{ z(<`9I5e8*pzWJ;eMt=x^M(g~Zb4_aFH^Tjuj+#y7m}Y>i5)-fF-264C7|!Z6Y8K&8 z6oJwI>K~xy!Mgi@Lmv_S|Ig6JhJQmJTd&KDED6~84a$jQ#5nU)?*%ly_5=L<(+N3eV5*|KD{HISB$5lr;Szf zM)@Xnx^u7QU8yBpP}T4M1-UXD&V)p^nr$wmJZG|9&j>}#HNR`{p5U@J{GKDWh3@p> zFyTo5bhOx$ln)SvdX39#gj9t>rfOygr|{LK*OkE#4lvB|sJo8!njD+VtK*_I+8vZX zu`+EVEc;+CqQ92&8iXF0d_J#qd^XU@GOO^ugjk{6ISy%n>LqFS0{Sr)~t} z5nqXk<6TGe>w*4nqs2y9H|*)(E`~3LD81wyj~Aevjxh}EZb01odr~NdctvsK5uDsw zrX>5sK+~9vgT0k1x8=6|Z>fcwqWNitbv4Z*WC>7p9>&MCCJ;m*C0?5*%TzSH|IyE@ zYJDAq;Gkvx{uqEUzPa*2l@MU1urMS@AgqG}-9~R@x&ju2f&+RMdO0yChDz(&=TW-3 zY>gC~uos${p$}|325LXlEvI+U{*1kYx-rbeu0l3B`tp8WeuoR|3r%fTM^L4{>=;TM z!5BAU08vk|`s%P-8p?@~%2Mqoth5;x@LhOW5tHO{XgdaKDxCX@jjiD|ON_p>!m|=( z@idYb`*KWHBrFLzntiI?@uPa~z(aWxtkRpy@k-``#GQR>{K)&{)l0VzF4PtbMoqU$ z$SgCyqNSY)CgV==mQUodrqgs>V+TL*w@cZ8$}OY7c<0d%+SSvyE&*9_II;9`~z1B zvxS`jNYtuV%Xgx_wJ%P)5lT*qhW=345-&C9Do0Vm56z(v@F0+y5RMuf?zWjt+w6?q zf5-EncGuEdO;lO=iz@Hcir(U7wMVFp;lw4Sadt|DEU-#>I9|2@3Z}8{rK8e(8`s|l zd3R@q8voGE?FJmHOtP#x_V>h%@l~-+w-Rim*6I-C{}`vee#rl^Zn;=zAuns1*N{nb zX>Rvvgc`KHfczKZEd<9H(OF{9Sq@-gEI3vT4GsOO-izPASvG%-hMnuxy@N~>CzgjK zg*-7XpV+tsl%XbJ?uMuZL0#?RORSlL3>aaqL=r$3PZBm!ZN9)v_=;1W+!GS2(dkLa zD6`P3nINGt8h8jA(GGZvU&q1{fHF}jvm>+~lHFx}+`o3F(fT3txOkzyWuG%4U7xZ^ zrNizgRobY_M&bf|?pZN~GnuReE?aGmDHGn(Ri+MROuF z*#inaky`&1DMzFIjkgRO7XYZ%)_a9Ej}2Hi8xs&ebC~j_B}`GyPupy!95*}Oe}kks zee?jmx8a6QGmDl{xD4c`DFxC(5(jd>Jc>(@9*zv~c>aE`5}YhV+dXaqHh- zSbP4u1^EBVUl(GoZEHKZhbHxB3qAqJm!#iXU^RJmN*;(8_Ah&=$hy|}aUZtSLs$~z z4l%cI!cR?Su92c)_@&g8tI8gq9wCw^@M(0!WY}Fl`V-bn%`{$MP*=XP&;_OEO(w$y zS3~z)$>-a4n}qSK71^;@p_VitQz>+RVaGqfRl@XZ@^am9x`nlB#+5>ZEj*3JrZ0%b}8y}tJU_m zB6-E|1HoX3dKPlS3ZCAZt-N!p)tjoLnOVsaq<6RjBSwWwisoBUYM%SD@B)lkJ zv@>6OzvAi!-%!2GMbxW`v%wVdz)&2&Xj;6*1&G_PR(N&KjTEW$Ubd#aso zF0jmA4Rd-XZXyPsRja0-!L(k(!d&8 z^uJ0HmyG+FIm|S{$K}rbha-V;hEfBTYll*xXB5dH8-_lZ&zCU^neY{y0VUz*u;9W7 z)}-Z%^mE)Z7WNvUS1DlRvAyM4YU{$FhUP-ACuEg=87)~ei5ILP7%mj_Yzj>EiHTv; zgEOkW!lUCJiqR8rx_aJlPR*E;8=wbDoxraQkCvH%o=0kihp%xr{*;$6ewN1ef)iXj zx3rWKF0lut%je0eLRuLyitUEbW->x=h=xstm_`RlRLD`WMK?VkU)AQ$pUey z%sTOL2?p2z*w=-~XY{JMXGFu2bIrLOlg;19n|Gsz#;ct)a0i`^P`E|tv&-D=gac|} z($cj+5o%c1%EUg$zI5$YpW1KY>1dt7&~v?K92+e9u$MqrC0$g$^VDJA@HXc1((RMA zMKd(*35$r_+Ru8qBwgdOCzmb?KWzSH^-b%D*GGk}8M;T?Qi z_);MuA;26^Ul5Z`7~>9R{A64TPD{hXfL~+fneTR&2e@oaGbixnVJ0s=zu1lrKVF9< z{NasTZiy_njtg?V0%OGzW2Xkv`chysGT?5syTVKL;twhi{-oQQpwX2bheJK+2va)c!ATkL1UCriJVCYIOuuR^4#CadQ2K3QT)(w{ehY)l zY60~-KfR?5iml;VN8T6JcfnwPW$FGZ22>f({>;}Lw*m22M0+jPE(%@mVMbdo0!>BMPEN~^lW!V z%j4Fp#<2U71RX3-KZ7r_H65$>`$28C`;tX9`{ee4VI-^^!FP0D4LL#p+wSyrY)3%e za+g11drU-32MIBspA;viyu``F=K$lQ3czYMB_4(;~}NQgMdDEX3|yAFRO_U2i+~4(49XkZEfF^vdrb;6jQm#RT(^XhHaQ2b_nA>cf(h0&)43?y!h^=t3j%eCVD#V zasr!Ru_toUd5`=My>|5Ax-^KPL4*&3S(0V*Ea-#F@m(o^gLs0p`?>w6%zlN#Mfo@` zCxl?^Cen*C`q;aw+#WYWsON7h+^99yg^H-b5#Y3qdwo{lN5=f(vFI^%h&q$I6*z=Q66AC zIz`U+8I-@GBfqk9bW$`chY3UU?heh~+uVuEMIZ8s47yIeyl{-BW<=GlFC9WUGTfp(mGd$L?C90TbbM~E$%m0RP7k>K`Bj!)F*uqKuN#yF+e{WUtbZMU zvaLxRe~UY?I(V-!TBD}VQB@prr1Ak=w=M@Kt>H@pY4!QgaY$*0k1zvpP! zrc#o3!;uW+gKv$O!TK&JpqfDY{uKC1ZXs%{s?nK zZ#gsBC5=?3hD!O~)~*P6G~yaA$v1aJ z10f-a5GEaN4qMvs3dkjYV5zUgPPyTB=?@&S6fXM&R*Rd=HwX;f(QC7u8#!qP9G;$J zeS=|InRMBC`;m=hj%Q36uFB-JIq|jr)>^+J?*CZi&q{*_YS}=Y$9`V;CeYL(ke0I5 z!8y6euii}VV_Fi;ZY0MpQrHqwcgbYrI2r35{ZHledjohU6w$)D)5*4@@8=VxzVsX2 z8&N=H?d4GblhAFrCSK-zO6TH|&MbXajU#1%C)#TB^qELl;q7*y@4S#GvK0vVf~byV zMp?^)8`z!+teI&Xsg{GR-I)A6i~npLsV=1nRpcy~)%gxFn|QTgoZy!8^Bj5HxU=!V z(7S2xPol^%X2T7koO>>`Sl5CQYwIIj-~EpMbH@tJcXfC16P~7{(1sAGM%l(>vPA+~ zf;`obj(aY*S4YC{vh{)uB_||24irwVX5*nZV;IIU`ECj;n9>i%d_ier-7|=c7AO<6 zzqv#aHEk1EtHR?O*c@RJ6ucI+K7rc+1BuyG?eqTtbJ+0SbTFDZ-jTn9LG7H6yhSxF z$Fb2~yo4z$MLBjwbF)N;zZSU2Ev^{kdOuif)4QyNbmz6*Smw{3J zE!4s9zy=rEB^B6jqC2q?&zJGnSim2do*00Em7G~pEc6C%Q6{PL z@$<>%Tbc8z|G1nHLGR_`r?TSla?5&mSplL`Gw`0b`Ox7~QBk!-(nmW49ygI97Bkob zOr8@G^RvBgp%ngK2%XNc6iX&;^yJ=25Mj9LR4(UPy^dar7zx~X25$71Sj+o$Z%%TM zeWzgjj**|JR6CU)egci~s9a@1 zk!R3~=>uhSPB6Slvf#W6{M5hC8u_VMIsZME_43;+sto7FSTdp95N&I~X54FQYp+Gm zcO;ryD6c!h3ZD)+%CXoExZ**->%4K9MNdN+F#?~PcBYyT6 z5k1}+-n=zBaUtvam@lI^o~WX!7*o%}I>gR;+?Wv8um z_W5;oTzzV+$p;gOG`6wk6E$s6(yxn&EWVFGUBO9Jm|wP|v-qglV@+E=$F1-}1=~PJ z9zvoqNj+Wy(6aNE3IVAdyNYoT-Jiaoms#DXQfb4OXg7lmYBJH24z?_n!mBa@2ahmS zo2NgNy?}m1ajN~bkNRgYQEsx_GHu>nbM}%RWL*bx(0HowSG#v=)~--G2aaDmlOHTR zu%mWORL{^!44WKx+%wxk5vW(*$;eT%ODC!(W364o(ki{_KpL!2GblWW2hml96$C7c z#R69$Sr;Gy__`Qhk)}`WF5bl z`F7{37b-M2hCZ6{yC!et$~Bs&=CJk9P4E@@m`ot$XYW`l5H}5!Al%=o?4nE zFV}VRv7HN}`8eM4QEtEW8P~~7T+3eF1zjVCi1CtaVZ=1L+#l13 zI+DmO|M>Y+Eo_s_0ZcI-XxAtdWNuktRReyq4-QJJ#(2IiNuSvtQgMCTIY@XKGCH-m zq5t>`!3la4VF$9Z{y{pe!f8mx5Cv46(e`1K5TXraT)p3cAGg}Q$nK%SFQAw;>1Rv( z+Q;@U!y@`MP6UJMb%9V<($?K?m*)Cn3cnn!@LU!bhz@cKS9=eZrQlb~7P~3^`7VnN z`-l4(D|~3p^RkLJUyNk>O4*PlUuY5$1Y;{j=X#b{sKGR0;#q~i+E!H;WO+4> zz1%_}z{#WX8ESG0J4^lGauB7=*x<^FnoxGGI``KBU-PvA#;W2E95-${5^MZ;T`yBv zGHvRn-g2fa6|uPU$d7OQdbyE60GXa-ecH>5;I?lK8T3@zs(&&s7)Qk{8qO;J*lzxJ zjsQ#ON%H&6Z1r1L;`+r~4b+m~g*&vo`9U;r?ZiiE;rBmVwpYKNl+K#Xz3AJNcttST zEhS(^4OvP@qno{w%s*vRT+zb@74P}=Ew?O!Cgx~dXA@3d$Mk3a6C}k2U?@M6R@dnj z4}pWL1Qc|>cP=?jPZxYALj8EK(K7g8o`TM8I=AX`vyoC`Ib6DT0#4DdC(~tYm>{dyW~H$5%wQnX`b8j| z{R9jrh>ja}kqqt+vq@50o^^zlnp*2J%3UT#R_!E0^C_F1uBUBsRf|R{{tdzL>ohz9 z#P$c;SwnX}6;NMIK8s%huS4tv@0KnT`dbK<3DgdG171yHk9wq4YHk4m18l#sG~mf6 z60YMuW%|;uQ@Bzq_j*&!^YN}>%7$gv14;eUgx8FkF?>Bp4ap*ti3@@ZC**Ob-c#ec`Lk`PUyP3?O&iXdgvjiG#g&($#TsQxIS6P~n)c@u%gRV&<6+`&@>H6g|%LTf& z=#6Y1$GZ*flHPu;pH>F%qEqZA1l45c5-t)|Y|?rj>5KL#N`>t8WMr&_e10R|^jot< zCI7i!kx>xYyu|d8;9&B8=?N@*%jAY|DXYjgqv5zKDI%fnM2Ew+WiH!MIp_V_hM}gK zGBPsG9sHFJCwPaMA*HH4hIDi6Lq15UX7+(o-zPOdtthKKN_Va+iSk@kzru!NHQWIygCM01omoLr4M$yZT&$_+L&TIN3;7#CWE3-Ndr+zJ&lE*i*-X;|IUqqpehB4r0d z@1P}G)WAq*=n7akFZA1}g@qqLJBJdjQGn=+iG8b{w(~-J2;=#&_kY;>%CIWeZtI20 z2Bnn{Bm@)zX{Ad6MFFL|1OybMyH%tc2|-GbPC=Rl(%s$N-3{Md?)Ux9`EmH=wcVGj z^*ndXIpzr84$Sa?Kpj2JLLc-blj`q zRXBaeGjM5#@35*QFIw+NlDEN@CAJ)Es6;hqc7%DO(4L%RWAf>K&_wkLvV3pg=6cge<*GnGZuNh5f@>~M(|PEML$II_PSDu;u0Ea*)7zz{T` zVYaA}C3s4S&*qj$jS_G5+p61EM+1OQjM)6gY`Zk}5z1@Z2CTOKt)Fv5MBTSX&6xY= z0rsn@rS&U|Aso&pf;>{E5-099CG#23K+5db7F*yFG#x64zICJD;SvaWF-M#~*Y4pg zErh$7U%%ZK89$w*O|r_o{WYxX$-+Cc$x1=6Y=3i{7YUb7a8+}MYYK=6f;A|RZWxqL zLatytWM{mnt{9>`HWOpPKh9h~8qxea&6h2k%lbYzg{z6A{y_~XWs)Ank|(U}I1V^q zSF_d$qG$SbRJiajwX)xo8xzO?fYxrKV+o~XzLYO9r!5q6J`yjq-P<;k>~fxY(4@jc zwZoO2>FIHw=5SUWNwd?J9f%jfDz?ii3<0E#;?AN>kKhh{4y1O4A$2H|TI2c*;dFvE z$?0l95!9KrA=OlPhlkRd*aK^>pC~`N27PC`C)}9Fg3h&9_3v4H)W=lm?NVnP?#r$0@Ucl;gHp6im>>cUTf7wxP zrNbWpKWwTSWQQEuo2$V&z{dar_X7=tOrlS{|>kFY3&I}xtin2^F84W0l7Vsr8 zOBx_yy+|4md95XUzE7f3bgDgPCUd7UycM|la~l;{bI+?&0U#n}vun^a^(m0z(nsS# zr+j_Dod*zZ#0{*N@+Mg8u;h&K0yE^o$~W;cfsJldv}Qz74JR+Vce2r1Ykcq^z8Vjh1jEV_kTj^L$GLD0m!!FG3T-8eye7 z@|czAXJ?fB6}R(!GA=VpLI*#m61z@fgSLqSl1hzY37E?i@`!3B{$`ZtqM9?_qd$nf zF5<-iS!lily7%pl=*&h=_m-1tCUon4r$O)GD7g~)WKeYwA_?rXcEx0Cpf2~^q;vg5 zY?E21vL;$AYgRRFO{F({)JTR*4fs`+6>DMZW^fwHJ3HC5efU=l4=GGN$?6sM7W-P; zbIo5@YO6hCc&#$l$24sWfR5Jfi;YExH&2MqRI7>c@Z80ak=+W?5V=q;87H z^o~zs%r`#HuQx16n9{OD#(*6|OaG3uBX*R`L73$3_@9Xh51G6-wM``5+1pD=@jqmf zNS6lIZ)<^qUOkYq#?N)KCROF>T!x$$6*@t(qUz54^NF(lUyN*sBxR-^#XHLANL>hz zVO)b2S}7Ju!cr%woR=Aejx?~5AO~o*S1!*MxP(M`EODnvIbw%zks0h)G#*hQ`3X@f zM(sy-Z#GT$zkx#f$3xklbfa&nP^vr$x3lweMe~Q6Wd~@vwA$K}7^mS(syCsThIg?w zy5?2Ai;)?uyfFXjb)`@x$Zu0-zvmZ3dN;MdEisE>_f6fGuF7VWRa0C@R-zyH^`kQ4 z;03*E=0H=^{gc#f@Jwmm7@z%Rvnpf5E1v?kp(WRs*KFwY8rrt@_MS&DIe>N1Z7r=~ z*)$p2w;eGUFd2M$u!grR*iKPpkJc|l76{RC(7QB-RM(1{Q78W1=m|uY*lr1*?X0l< z&Q_A_uc@h_iI>k$03$ab%uXsYm+o&)Qcb!X#*%qTE^M?%vc^w@?f`P(iAoIP(P0Cx zNU8sZ4H*v=7~*C8-(j)EH;x@b4$21J37qIX4a(5@#o>fYxPlGt5>FWbLR5k`SIggAoZG0oE zrpQEv!#235=|C(Nu#j%4ONkA&vsEA&PMnmXn9Wizel5t_Y$f-vKrT+hb@Gs3P0Hv~ z)x;TAP`HB>(2|x_|L@${oC{k>Gok>G!~sPP6c-GDpE|&9`c^62WhaqN#g0fl#T~vZ z7(1@ms3uE)I zZ?8WY_=Y{h57Af`A&SD1)raqE8M@9l`%SvY$3@OImnjz{DSPxxOxIYEgc+h^Y!ow; ziqso0GJmqaVwR*^FN6ZME1&iFtMK88v&M+#h-cRH^7{d1Ctfb0XEazL27hZ+}3a467Gdik1uKmGpECm9* zj6(h>zZiNL6rv_-4y7^bT90;Fst%{}H21i_>ndlwT!JExfx^IO$Lub(Y2%_+pW-4* zjNhaehd*_qo|DutU7P1uy2Dh!ZT;2tQ7RFde46WO_szqn6g`z9?hf>?d09j>Mwsft zUvM4rfPDx{q@dGFm*)M?IT|%~cLuBZ-6)R;Um~e*`Ow=qygd*(@M@i!Dt*&-;q>)} ziO02ERAQMZR*Os_%xOy;cIhB^JX=KO`jUWvz|{OaIu#Wa=TB+KaFfkcV(v?q#|RQU z__i_vSwajbq)A}EPu_^We7e?a7EX=EZ|r(o!-nxXHD9iSWB3jCiN_tl#^B|ews(ft zoxfRTg0f;@Naq>0h1SCLf{#Ce)};*4Az9x$+pSl|O6^EWseWyci;IPESSrvbmz_)k zQGsS-Lb3YOEX{73M3)md`fHTizCtg6G^;i|hv^#h7=F9g=rurl#Vax$_pQ1(!MeD( zFw&}pL+K6p_RsXq2MdKmQcIjSF+@H2Q+%cx#=jibT~us<#0o zlaPh3sv1w7n`TtBek%M?Icn*Jch_DmHBt~WZz7U9Ud7XVMFokYId4&#nAfXeJU3T( zR(T!+ie%F;AIG|5>cbNzhz5xOvc`2mR$f^d5YJ^dG7cMp@0*rOjhmoW3r}NpV4KV_4BC9)Vh+NgUs<2s^tUk0Hb4iq8(o{s(yR?GBU|@JINp0 zB@HQ(;Lrr>d=$Va!Tu>#T6el? zGk zALv?-c6Ue6&3_kAu{@rW+x$K!Y#3VujVwx$A?tg*64bv^uhVfO8QgH1=p-x0wwk|U zeI3Z|3I81gO_X_Kg7Uvm(s+gzxPVl?o#kQ8W%_L zu=3C*Y-$irqJy0$LH+=}k|^?^So^hx&?g)(ZUL3IJO-!tx$?)Cu(^nr$!rHmKQKLi zke9`4{fHoh6GmW(gaz*wC!0cr@i+{2`iN)}>7)FJ|11Z$4pBL)Dfe(i`9-2!Hvq^{ z;&b$9%e+IfoMnUUaZA!u_rmhzgG+nNTCL9a*+ynzdwho%4cpKD+5phxV_sJb2v+pe ziCF!`yff0^`W|j8vPk2sO=e%~EBv+?t@%GMZ>GjpH}vEw=Q8nRtf`Y*UQx5cBO^P`rFq)GUO0Okzrpezl4zJXCw78DYME zad@bwx#p$AMNE1zEZcb^$ez)jcH8e-X?|6~Gd}ysf0&*@1>3g{2TJtccc=2}RJ*W4 zEiq5+76I>0OVrgkRpc-0LtM?5S|Ig*hKl1Y>?0u{_|z7q*P+Z}!^+C)5)j%#0deMi z-NsAce}cC#&q*AWIe0Po=Ucg5%UXTeO@2K$Ren8TAfbL+mwfMcra?;OpZC|LPvLHF6z>$e@@x8f#LflfuAl2wnT z*Batp;`mTOIaD03R(97j`xrhO31zwXYh?x$NR<5+fKboz=TV36-=!_V@1IvJ7IzaO ziC+48A$#f{Qs-h{Z3mt9ziOh^mv0KzhY0LfbyR)4+l~mCy`2s>_1Y`P%R;TeWIzBV zXlGGR|N4-L2|F&1eUXVfQ+}od)(&VIedI!cq`PBn_U|o4cA8h*AkL}aWg-zQQyQtw z+Amvyy03wWpoHp=<}6!nhdp)L)qV%VvyN(x;U?kGKX7ClbCMH09J4|>D&!k>nwC14 zwR^r>=xYB<>zloLJ+Kj;oaOxs0Tg7GjC-mRlUzH{uao3o440U;m;YkM|v zFKu5+S?YR0HPAgtXcYb1!EU9lVZ zj|aC~0YoFDYvIXSldx#~sdPD&fy&@*Ys4#*`G6jIYDLlB_I9@-jf8iBAvj=GyBn3o zL-fo_2IrSAo(XWuqZA$}902wsuuN%#sAFsY$08d`wk3GE2vRwHGnI2`!~@A;#cYG8 z1C3=V)?jXJ>!`XmEsbxiS20P)cu7X?{nx-5QMel=?B*K7V{rvyr25sfL>Fc_zb6eE zjW=#c3H2^9H9?X2Nj3H7e*{yZDWGRSRi(gF%X&C4z0v{69QrJ8t~(6ksdl0^Lp#_S zPy)*Xl)B0FKc#1Nd+(VgXQ#_&GpCX*RpC4f!!Lt(s~f;{kOfc3Tl1dIX=bH?#T zaPnwCc}rW6wXJl3%Im~Ga3U(c(&wMT%%zO|7m?qb-z|WrX+vgiWk%*7Q1r+qJV8S_ zNi0oPRe`7aph?y9re*w!;#tAJMgrAfN74lz&L74~2>y|HE+en12YGGW&C!mqEm=TK+&Q&>hUt1X+4@nxrAJV&WI01I0kHB*}hR7R158 z3wj^$5ZeD>Zh)Wo#n;|8Nv3%5rr%j zS&s^!EX&7MD4jhndg>_%ivQIpn+>p3n*yB1D3)DsFLLF-C)cS)_b|Wx#T%%|%-c}! zNN}48fQB)TJA+d?(|I1=S@-n}MlnQL#!7Mqw(nB|ivvR@QS3Uoul;GWS zRU)m2D0t$jcUYGQ4*nBIEWxHotHX)69K*wFo?*l7yNBEx8&SjK!y=)vhMmYal#FX8 zGWpe#UPzZKG`Us$ce@wP(Geeieo7!g+#I**?)HN}tR=Z>X;isE)9O*{36IhzxEO}h z)(2~FOvF53DgiDT@<>U)-N=U>Z296t(mO8&C9J`{KKx#1H|`wGfM0^Sy?hpXY)G|C-9AU- z;?!gp?20WR}+k}Q=35&!#n6UECY6@9PFcny5>!_JpcW)tJoCCcvnHKxTLhZVbY?V zF*g_8zVWgS?DE_6@TiqdDLXXlnqP9iA5E#MbHIJ=a7QqQ)T6-JZG7}`cqEgp$v9!5 zGm4At zcuY91GT*?)4l|DNlTGl0ufPirT;%272YwafTZX)1l{uSwm4($x*FN(vW{e-?SsD0; z>(x|bo^j-e%#Jtn#Zgt>@Xsv;D?vLS1f6v=J0AJ zXIw2e&hDO=%*-C~k+=E2auOeS9A~-M{-9%5C@olR+QiPR5F72%pz6{`zF~0sZj{AP z);XzM`P137(Q99Q&QeYG7m>0Q@KydiOUvVaWA_o$X;Yv=bUpQVDoMzt31t~6H7nvH zmPi*Cf_)6>6b%3>2D8eWWp6YDn>!@B$w1QjvnKvGe-P2URw){@-yjDv6r79lStp(K zmdOFNL-HspbY

o>4Eo(iowR86Ldl7O|+?`jxdxz%Yb+C*KjrRHKTFXk%xmzp++K zkR`)?kgW36Gq=f;))ABA%6`|aM7{ur7w@vq&~G$bp&mP8;RlYBpQ}b#$GE@)K8H-g zbedxLugWt!Pd9(p>n-p2opX_7qg9TJ1xRPh7IQn!$f)`>mpfbhiYvZqZg98}n^J1E zD`S7;po)fgK^e)aO>DI@QRNo@4-T0akTAa*lgmS1JHZ}!E%7z%KvHxM1Ui{;7!aQu4#xn2UMLoy^9zQU$LzNx;V_WK1#qvZqW3hn=7go z5T`ZjH+U_dD`n44+4fGOTTg8!DHJ|; z$Q+a{Zp_grdoJXmeQS}ZGN8R0>-~Nx&f~mZOjR3P(~wpb%hZ-h+@JYWs+;d@(R)*p zX{h35L;T{iRBrdnN7s6tzweBrRw!5yD|0!;^!U>D^YMEQxk#2q21#P+((rRr&&kxW z+JEF;$6JQAmw(H;g1GHudx_?eJt8Ljdqax0tb(D;oOcRNcjZP=J~yyKmz|D`BImXI z!l;x*&ld^Lls+@U5rUn?xC@F*i9x`Y0;=0Cm^JIyi}aV$j((V?u=5A{zq<2}KadBj z6tFr#&g&33g5>uFR^}6;*0A9IlH>EqDHTyd^;(?|hg=a=K2Zl8c2}jp7c0aV3Y`6_ zi7jKSQ?!|gTdY^4KpNelY*FnmDHz-weK{i_f0|yEJGs~yKxP!>KKv;pNV~na^|Z-q z#S;JgX%%H+gFXKOcTJ?N$uNCKCYk(c^X|z-=V5JAYlMTR!-iJUvG=;g!rA>3*As#0 z^L8(VT(v!`w_IoXkyp@fcz5HVU0{N&s^rOwsCSK0teEB;9!L zc)C-+z6MTNaHabRjHn){Khr=;mv5vYO}`qHox1Qfx;GHdPA2xI&D;KxxKQ*B>3WMj^bH}WLx-zTLZIeF3^=M0H`!G;- zdr}A1Ke1aRXsuo=RVxZOpM0q?olKOpGX(*8@$$}ilZP~Ir19Zq)K02Qde zBHV8*Hjz3+$KEjLq>d07wvr2pDV^BbuukcPJwh}lBq=93RTa%VnasP; zey+(?^VIZ{hy#w7`9J39IAm>i%{E>4&W>rVVLykCmg{`Qba%I=ROziWa zpq7Z-d#umQk|)4WD@3vCF2| z-KzwV{Zp7^kerA>4w z9h^)mdG8|DxmmhvXrJ!2j}Yxu*YNgPWC-_P*b+JfI>*Z)#{*UZcawgFtm0~6hhNSh z5HWZ7963MNT>N~fGnl5>KJnX88bL%K!>!bqb8yhmdBmi&$jax~jz@tkde86pP-%~- zu^qtEEN4WfM9F;tZ+?211O%C|yK1WS>8q}q+RSxb-6u61~;<#N4!AX02s$bF!+amoq=2~C9=g_}fEJe!j z>bX$+ll0ycqE)m%MT5a^&#pOhx2{@6WfD`XNIhZdr>dH(sjeox1PL=ylp$UaJ$f9*Wl!Aw{y9mQz!{2 zrC**0lE1t>bh{J>Baa`Lsz6_msI08qg9x!MXnUnmNnf{FqTK@^iCqSAWYd91qPsK} zC+O4z;lT`LX5}`k5SnED1L7Ecu6}|XDSV11XSPDcOr<@*Lgb+@UWV~pG5}7`E(AL@vsdFFAn#005n0@lqUD}DnrK?#p*NDQa!m$E*aKbpJ zPd;NbxLuUos`%5U9M2C#j`~Kzh19IQ6O}cC^2OCyn@NT1gq5!f14&GpS`{=ehpGjR zCW{I;AKmFkLm)z1n=_Tu_UA0-_P0;>E1sH`W4-V41eH{ryIx|?Z zDt+Nt=oDSfFQuJBH-8e1z09B)_#rG^MyN%t$InuUS<*wx_(hyqg@nVZLb7)S@4F3Q zr?lS3ZY})IcLOxI;x~j{@8#kkrpV=_y6!|4X)K| zDKV2ol*c{up;m<-wiA_~PE4-GF!dk;agPO816AvITCk`WF`=WQH**F~vw@7G>L)m# z`l51d$@p!VTn@+WXkLJ(C%)dLElyC~deHK45!4aOhm&rpkb~6)HhE70+xY>00Dgb$ z!7cDNm_?41+vN^XZCvm;?$O8cSbT;zcK^yUP;Gnzi=kNR0X|lJu^exn>(1PDK`;sU zVsmDXY6rI4`}G=|G)^7 zlB!Bt^7BCpGXl|uCGJCGvpJ{~SHO~EI=;a?L6UmAhE(oK|8T2#GneU_XC4V66dTX1 z0_tIcu5GraF?}q25<_f9he@c5{Z|k^*EhxCLwq6F+030hBz zs)`BXb^MOn=QzQNh(Qn3@0VQch8F<8#gq!&=<72~7Ab#B#17*n$YD_A0p(i+ONjN=0H;m}3p2?2)2D#4~-woL?S2 zk*L-&JKXpYM)%6`3lb6h695lU)FiXCv{V+jS?_>cVTtoZs$;18KivtpTz5IW=E-43 z#We$~=@vys`7F!@4d_P9W%1$!Qc{GSMYYd=`CBSIlpf9u3pYmmiTe36GGga(&a=*f za`{J>?0e(dnRC%~wc4f_h&*Lqp^Pcb%97irQC=ns(~;S#<<5TNv1LY>h9AT3K}o#Q zGk*>B%q$^RIRSbJ$je+tsVN{2lB$^#(H#TBaPL4ZrJOG$vE}w2Ea!gI4Q&ez+5Ci- z3j*P+%l97!2g4pPrsclV2PekOk*HPW^d4o}ceCBKVdVz;EovEQ8dnh=^o8nVErVM` zElaY&7n_Gqj4pTW9U-_v3N~bKe(6b-mIe=-BoOS2 z+X!A^gB{ZEq*CSf+=fQchL&r_g~E)RYnip|KMB+SAk@oMLfSyoz0SpBY|XuvDI zsdzw!a|iR-c{0Su5}g<}L_lyb?{6c;Btj%P|G`&hF7jIx2L|5Gl!i2G=pXONgN1cd zJU?|9SWlizdr>Wcp>Vv$ty^9MnB{VmuI<_Avd?WEy+{kx>im4X)caI$sb)U&x85bS zs>fWB@DWcepIwOO{<_%2Gm9y1S+R@WqLbZ;G-$(upHK?ANVK~hdFD)3JuJKAAZmFq zi1_$$sxuhKk_lN8&)(N=zahIg6)2^1<(b+CYzxf{%tX>~?r{0%8#Zc8Al?XHLn1;` z4b?5}4*dlhG2G-fAS{iVQ6>Q`oW-QPcRYG2kDC^?Xyne?m2sUO8MM8Cu0IJXh8E7? zp8vT)OqNd^X)_k(V*;A*+p@D_s3*H5D-*>94&kx6HBJFR0PL2wfmGQuYl%($&r`WRXwS*gyU zaOp!j*_Hky#{nzkRz{L?)C~8xvSL$_huj}hf5|V%G(}0n>~DehJ~lY6@JZ(h!UEM zat<@3Q5cso@e0uv*17-%&ESv$^He{XkTXx21KJ;*bQf6>;9L1m5j z!_v7SoRFvZeW|!|Q!a?iM!(-xI!@pR40U>-g<66n%AhmV-)eo}z9Iqauw*b;_idfJ z9fws4e8k`Hx@lI1ekEn8t)PyBdOwoJwC~TrP%0gyfsa9lrTR-|A97>stv`+0O}dEx ztt#=Tga|cPd}YVAoNy_VsP)`_ta5L9x1vs2kTlD{8C<7d;B+v@p8P8QsTPOuMqH)E zD%Uuc8$HWnQ?y5e%N`eJmh4LnTVeo`QeZmc(|r>nukL1w0Y5kqYM$P`<=%8RH>-dd zj-*p;J}T?DO6+4fB__CV^1yn^2I-~3p26O-{oLROVC=X*Qkt)@W)*Ke~)A>hMBXMIMQS31rHaD%av=*%X? zvwrw$OcxXE4=?z$z~y6RGau+f&5ZYwCohL3DN;}5Ju7$_+-66@7&$Au(1UM^3D}E8 z4tz*vdOx<*v^d*DYsgYcM~7<<7?o9-{dQtj9k?mOxQsCc#s?^%3I$q?1I?AZ3Jq}z ziYhB>Ba*Xhj|&Lw7<1Vo|9sM57EwTufe0sGFf1jII`0CL_?N?}*2<=)gt z=)sdjIy8UkrLu~#{IFg*yYG0yB$C6P>vBh_Cu+)NuJPRmz;~yls0j2yg%fji^a@d)+(Nc2jv{zaVvgYzEF#v}|lLrl?Xr*m+@X`1ud+T=}AwWP+V5Ki{bO5~s9z>~zmDyLH#A4^(NO zRILODrV|xWD+7hj>6)j*9qsL}u2mxtfdF7L+_c*Q|B5HsY9_=KNOUYN@2s6_d8X-U zlKQOyFT7K6E!&vnuZLln4tE}Zqs~MiniqkCma_5ZW8J*}(_FF^Kd=2Bj*RjQsMvcF zp1Rku^#kR0ujOGbIPEuzaa%z>Bxc9^Q8DE5cRvZOE*lE;sH-hlB-q>D@d)FxqO)Y( zV8}!S%jst>y&~w0?_Cm(X!5lg`BMyFXJSMAD_Rw%5et}!{ zVf+cIh8TY62)$9xIRPBBz8e$0J zsoBldt|Siuj43{zIn9zhZ0J;8cvkd6J%QL&K{|3WtK>b=`W#k6>aNvanmH*9t9JUe z=El%`BRB%svNskffr#@RU{f;!omfcAc?k>3Cj^(zvpDz2P=y)!{?YK?=0svOE{em6 zC{z*gV%buG@zq)S`qz0ZW_12{SG6g7NHvj&DSEj7x8!uaD#n^uM=%o5{x~S+XsE`y z|NZ5LV~byEFt|(PBdHeQ1g$e~A9!p$AeChZzd8vDNT1!{ts|Gly-h*XH1LT8n@(-K z_2Tr^7THoJSCT7F!hWlAe05^SQ_FMXrYN)5Qd+P5#Ol@^E_`dds{?^J;CR-xiYiz; zRLYlz3vkqt4?Y4SJt|5r|=bJl~;dyt_r#uZiwe2%Rv=BHTADp6bOO zgS)m_prN#e&}<7zgw@^^#1q}`6%G{oE#dAQPIHk&2!!9-yrfU3iF~nHFj1rVlwY70 z!dxt$ieV-pTvS>Rmz_v`bc+vp#bc)@OMkLek{DXp-Y1i$JE0!kwpXo3w_QHq1`3W{ znH0wO?VG*+fxT=Z`SPIN(HWig^5dM#TV)o_q{7zib;=i%Bf-TlzoMh&Uw^`&__k?q zaaDcrItE|I1pHQR>muRCvJ5b(7>C%*x_xJ7=Owru|JF}WW-u$QKjn-eMWZALLx>O` z-65`jp0&1y!zliJP=84j+-m`^cvh6%@svsi^g@y~>PKsch~o(N!iJ zdjEyT%vx}Qo`3qKRytlN8HnJ$a7@gRy+}VQNGj}n`FBPxen#N@ zB*uU-OgiQYVo9I=n^(?Q=__#-%`o`3bzif@eM{~{lpFD$#cT*`E4_><{t|oZgJ~_N zR_c0&B9DS%-+sv*CDsF5R^1P&8}YS@CWlP%i)0wNZE=md0qc#$6DzZi%9ua?G+$^F zi59N92Iqmf1jN52qHYwZZr`G7#6GfZO!=7*DXNNV7%$);0$2MZNEVULvB37K1ux87 z#qvcTRLjh#KSR?4hi;w{`He(t-h4R#n)J~TcT=R$cYWpe>+#_OhrtK-jo89ZJ+-5N z3F^>@!Q^YnS0+hY!3~bv+3BMT)1eNS2J4BQG7EQ=Oi~Y;wTg0z-3E0mGF+So4oL5& zn>UqP=-D}L(_DceBTp=Jy0S2rSORVe;mw;gnNutOuAji5ygW9P>j9>r7dENL<>}<* zT=Wr?6#VDFdD=VL)??Hx`(5JlBC4+H)_=eZgwwdoUhqL2|0`0gIn-hr8iRVydU)(T zgi9e_T*=`+Q0M5vXh-BU-Q3wZ>%XL)Lr0`qK?}$Jm{Z1~P1zW_h1sil;?_;4pQ9f~1;JquBOxP$ub8W)*>;(}aG`*PUQ$`| zS?iHygNyAoyRjYol`+l9ayv5^P5NqlWve`1xYJGDrem2dm%IewKG1Q)j}|TlGQH>L zkG)c>mK%tVHspKx!rlE?2p=X@_laOy!#bHdIGd8uD#>Y7w`7_G9`CFOqIr&PIpl2f zP0;;HJEan|xLx>eP)3Ov4mZNn<~0YVH3^lrACV@)l?FZ+M~In3k%`Ceds<&lj0CSxud%*yQn$3Km)^(Fx5pa}pF_Ws~KrVV_Ul^!lb6P##u zd;E++YEIbXf}7G0)u;Sy=$bYD}TstJbWm7*eMAp%=OU1WkuRp9Rx z{GH#9Wq+w#^qL;*@+4r=`SNKSbdX1U(nGz3`arD-J6v^Ejglv@mQ&$fv~v3Rd3jK> zy+L?*c=((yo+AbyT$rdEFL9>97Z`HCbgdwwd~HhF(+cay1O^E|jSmU-t~{CHs1Ko` zj8+le%yuo&H6B&z%`hD2UR8)c5Z9QvGIILMR?vn` zjeTTs4qP^gjX(xU#H43H zUd$~lJO}Orq18tt>Zz9w{xz~mWuzr);%0y%EZ6zmQuz6TfDddF@&z`}(D65Rgsm2^ z!&x-dl&bZgRn})+RB)q8!=dSDY~!AUB&hzw==2=RKEa**;w`3QHQ4Zu{eTkfs~1>d zc>@-nmS)%->H(s!dIxiy;r#Fff70E*=hZIwA@`zYAn#!>pPwGe19Je%^c93KUzZ&2 zzfUJ%OJEo#orI_0|7zk0EI!)Hh9wc8TP1Q&*o*q(_U35v8}+8(z!=jPWfp7Horun9 zHlcB??#%9iSAm)UwiS%|>%BPwnVbbLZZ?6b9ULVRI|Hb5WX8?#yUN71bD0!1##yt_w4G0G{`liN+8-eS>s=tBEv284 zUqJ-l#^3v_C~(O_bvAQsSE_edc{Y$(GcE`B9gViOw(3hB813R?y!nkac!Pw6src^7 zNZ~`k1MfY@Y&rTvJ?rl2c!%o)eyV`=B&suV@L;tXC$3zFecS_kCh@=+DiK`@Dsu%+ zmjr&NgAd*5HwV|Pyej}$NE@Bj2VcJ#i_FuPH#Ro3!dPPOR|wm0B`hucgJ3IgJwNFN zUpg8$+vLCHFDnij{n;rYn5s>s3-bJl6>{M-nWz|^_PEr1w2v+-i2J3`jhnY@Yw{gx z0US8q+y>s=>s7kfXo#867UlpRGA!l?od zJ8+4**J*e|3>~qkf$RDHAlwu8qS^KSX^$6CIOA{wz(I13f^tDCrY8jUKP&45!&(y#G{qrg4Cm7I5HghT+evI z8RVbm{0gk4Fc|oVcaySep@VpjZ&paXw)Xz6dD~fWqU&varwC{sd`G)6kSn}wH$GD9 zke-h{Mr~`<&y${~U0CdI>A1;ykKJfW^v6n#=KvSj173RuH$tKGOsycKSQyAqlpIU7rNF2mzu>?% zR_jm05mX? zPfbnjfBhcuajvGy5T3qrO9b;Bk1t<__RGc4Zv|WO=)GHEq(HJtB85)eAi)mttU^4i zLhx@@gZgeAH=eTAg>vc{5C~WvGTZ5}xlFAtEYN)x7Ru|WB?eNPI{61Dn9q%u+4!+& zRlGpe{=4@qAFRc@T`=&Olu90@#=9oM&^8cy$7iTwE)BXa1>jpbv<{>PYHgS+t_xuqUsF# z22x1&+^pi_;@g(FKpyGK*Ow&df&0mC!eNo(1g`w%&d#99%L}Iyn1MbM&*QLOlCeNY zmz%%I5dPK}TRMU(53CerrcGA6!wmfJ+}!n{`7Xuw#nx2kVPeV=-W-#?KDPFi($%rj zg8u36y!3WrP|52G3TsGaxyO>5JK5VeNk%M|LZqH9uAxa6E+SaL9(Mw6Zh6p~E(4t> zjMvJb^q;$2N#=ckZY?bp%H#%Jn2{&(Jqc?n_U=FQlBM{AyJ8r0VF!Oggif|}D)op= zdH`?*V>n{~Oe|)moq*l-8mRSw{i-c!Mk3$YbUyPSlCsh4cR(sF0+bBnWAcQ`%$6v34DA)yK8pOSL5&GyvJiQf52&{U}eZ@ zr!EWtR*p|RYvqwhoL?N?X7Qx!ty&AfQPkSzu@J$8N0MUI)zveGi}1A=^cwsv16=w# zCE_Ht_(|v^N=Pm~2Ng~>Lc8uzM11>pzh<~&*2!Tke3`rK>G6Um@wKpeU$`0`#wEY{ z%GJGR+6x^F)Q|hXjV(t(W!RIgqAca*<$fb@u7?(8e)S?+FjZgAYxj*#jT~GZw0MzK z_6gcK6RQnP+z^L5>-+1~)I5_Ib`x7(u39BY%EHbCWtzCj0b3?Z{GUwHm9oj;=kv!rDK9FDmYH=p9~+dcz2fUcXBw;k`rFA?d1$Z9g6q zjd;ok?xk9uq1iun5Rx#%(OLdo!=A@rqiFt_@bCQS)WH$H25RUwgOldggV%(Eg+$L+vo%WP+BBOfjK9*oN(2v|XrYTE zJ%WL%gArpI%!Oe0t8X?M=BM5^22%V6%=!c(M#V5TL7yUqB6F1BvceJwEv6g=yT3ZF zXMV&)qK;P)_wHTjUcYSPb2`X6(!JhEO{EPAjAY;vc*iTMkZTWQsor{cZ;{}h3Vgu& z^r*DEGE_@s{q3I*J4Y%>|1OS|{hmh|qBR^Rhq?+F=88sdX>BrY_oMw0*l}1)x+;m+ zb%;}i0!v`;hcND3Ejt%~LBowBHU4d&M{ndw=UV~|5A`{Yh_UpY;;ZRv;^R#9Jm%c2 z7*%7)mhnVZzeUZtAJovH(mX7(D9$E3`6jApGMEjgbryNp&L?`CxLTFC(FiZWg=6=A z{d3{#6C}6+K&Hn106YlN)yiYOvoR+1A}OWBZSzKQa;uM-^)?Nnp^OzcovLjVtwyF= zg;i=5n*zVBMJP4w;Zj^0nwQ7@>=37KY#)EbJKNYf{)ha?XcCLNc2j;s=PE<0G;hm- zrj!yI!e6lb@?(vXNg|5VBxux^40C{P047<$UyLxIeJN+0G*RlN#j5%i>U2%IEEl(75zoz<`J>m~>k_QDf^qsRRnh&w*AuZ|8e z-L^?|XIKSyUnm17=w{=6LPcTcBlA8(+eb6A*PNw3R;hHj@w?Z5GtyfU=|Yb_(PeZ| zU6#DTPfjN?$@*GMT6*5w!O5=cdx2|WP4*pmwZpdj8;Cb+rcJ74MAl)Z{_)RC^HrWV zU9(r!X|?MbE?u3wZ?3o>>B`Vqj|0%Yk961fE^-`4Qnw*S*~Bk8X)Ox&890uL_*o)q zNePi=dVnahf7Ym1>&i5ZEVs@U#Lcl_GhL65Q%g-ouK&b#EVMU$E>!Y!+>nwlbTep? zf|BdQH%$9%s2vc2Js3!U_3EqBo4k$WLwHrmpS3RT1f@>P_^$->;P27lTthCv9H5YT$>x=w zb3>Ph8`D$P(}i#|dTVX^d4>?LN`d3#TJ5{fP#*!V0H5ih;@#yb@AuZsINexnuVyVd zE+c*O#VWHvcped6qO)YcMs%??_oAtlr>>BAhXbIh;Q0hOoKJ1j4BAT6j9#e&HOiHh zg~5^AChyJM(?>ZS$&Kg@jQjZ36OksBAF>O+8T%0J?8w9dhnVOvyB{U0sBkE-cl8JK z>f;wSgSOiQ2RryX0+&2^)7Z^^ZV$Hh5ajvWV-@6e-$PEulZCwv6}Yh`gpE%P6zmjN zeq{_wzI+LgGyp9zA#OoGbvgaI_j?DIdvC_mjaU!@&E)_PBL`f$P@m4t-jc;>6^#$W z+cn#6ouDK6lLGuC?Ks+&7~X=VxhY&+N|q3Q7c@j@4Mcd}_Z*tXV}-PbWRTXOXivQL z4r$64#~$_D9*Y%=rS`{%)gRHWrU9WX@ln(Gc+8}f?La~#9^XzAsUy4$B4yygU!^~z z{B>}F8V)>Z*>)?x43gkx{(qFcbySpV+c%6Nq9PzFh*F|k5d}u1kx&s(kp__trJJFK zR$@RT6aX7CG znl}h1@@<9+k96xZwe?1r*H7=FM8YV7BhIZI_h4pB2*SFJXN}7zO8Du1E%nh=Ja$!J z*(D87iM6#qikxP9@Qwlo$*xfn3^nvqD1w5itsa9K;&I6?qF@JIP#wW|dgQdkn=JVu zHpjz^g-H1!<<$B#%4uYGyg$IfSqMrVi-sL$B}*OQGS?N}fVC@6@v+Q*Nr-0Fz!Iha zIxWseZyG@&C-Z*tbnr{$qbWnXN)^8dypH&HNQRY!OCj78mW&iH5Atspr;Wd#BN9Vq z-AnY3jp(u5W`xj%yOm%PT8X_@vJQrVqf~O_m5;97UY(|Gl&nV)&9P zp9Y8+J$671B~is(pY01VL=Yu3V){p*%P0pl`a-gf%$~q&AU^d91U+g!fKtmCmkXzy zdv%~mbT^Viv#brSQPykM-a^%WbDE4a=clTt*8gsrIYelbL%a?ZX}Ktg_hN zrXlucBWVEnX{7-S_rr!=H#HG{6_huBx6w@vR6;lUSYlnSwG#jH4^R$po7!&GG=om7 zj;To~^lof1>D%~Faoq3@Qi0Jx1@@qgY=vfi@`XF_?WJIaDwSo}%A zA^C0FtHPC%>rg0UjZ61Pqx((~x;cUfcwtW4-P4ge1s4>DjZGXleb4f$8w)+=kP z2dV>nKsG4^DIflTz2#RkJMu4%s9LyTDs9=~=zlHdaj^Df(K4I8cd+`wE&!EFAQCLl z4}`?V#-2JueFE3|@G!|dCOurc9#p=5MB2DOq80C0WCuCnF7EAm^NUxCuPxF2K*TOryB1W!hY$A6cb59x*Tj=h zvkJ>MN>2h?D(tlOgnkKbPw!JFC4pn>c^R>v&;Ih|E*n0&PbicC(8uFoCMqhBWb$(; zPf`-^ivE$XxDrvunVD2y@Fu45TFIH>27R_t#VJctg}$IN)ptawKL%T_zl6=MB67Na z^&K9$hMP=sy=l^G>LU)Rk^yCTCb8hrPynxFoe+=c!Pa%SY@BTZ>SRUt|1p7t9tPK~ zF>KzMtT{j-LSZiEm%F;h$szChs7Oc`%J3ISZ3P5tc=8MF6 zAtmQxi>*kW+-PCvFvOP!q6BI&e^$hvcmBpR-_jq$E(B>+9_;oKKG~J9+3rPm;r0J7 zsXl`$+RM#lLGsG>=9AU5#T)7E>(`Y1<(xLx@=QePEf^E~Bn>)7(>zmioOM-6ZfrT- zZ4u@T_t`m{bX@gJLz?wa!!mmf_(-5A@~1Ks1h2%McE=&;$LqG?{b~oOr52M}QZz=q zE8&i}x_TEFA6jjzQrkc0sW~(v0NN7cG3gBMiZC;;Ax+E_rV%f%a_Zl=wXN!d^-2YB z`yvgE1Ykbz>^{4W%sT(3Xm@9xJuZCO{gI;f%fs_2?4&C6U$y%WAEgc|v>%4;1>G)8 zeN5O`jN>!hf9$Q!_pM;@^Hdl>#*02tN$L+J|NPuC4!z@Fp3#pLEryY%>Ekm)K>F8K zR5&3ZBG^9KzCI0^^`sODR=!JjP*Gc@0{sm8o%SsPhkNTdewThWSvvAX7N`B+fo)r> zTJ9@PH$VI?jr$fFrY3iC?m#a;qm~?yQrPA9pwkowch@&)YmP8S2r;nF*R|@-Jgt zXN~c^?`O6q&OPu)p@l{Gxu$SKiH_5h-aIV<)Y9_Gqb?N8III z+k7mJ110dyX5iOaYnsEXcrDqN-xg=~^VgV=H)v(30;A~CxCByI8tse%C{1`KQ9c&D zeCmnll}pt$92!pm$h$B!FjxYFvF+NUi|||Tfg})7bNYf#)QjAAV1}Kr+g=26(6%== z-IR@CJ3b2kTnq$L-8303E7|1%vwZ@W7gk&Wq&)2zs$86pd%(bqY}v)MEf0HWL|)mw zPuqdHQ8z^{ijCX+3>+q5VvEBOHh$MewiCiR0XL3I?Afcf^y$bMtVx*<(oAi44tU*# z$xthNhiEO~!cBw&w(<5YKq->|vGs(w>3<}!@=DQFkOG*Da~!xX8R%OjiHVSgXn%L( zrvsc#$50XlL!p4T}+Lf{T+J~NnIjUoU!{9PgAM!Dc zkB?8d)7QRlFt;)=H!FR%zMCnLNp0`yM)I1mXj?lOk-fjH#LA(V`1Iw8RY6AV7Ji!iGooGfqjBM^_E12A8Ms2r-z+#1(n^co?7Tj zd%|8b;67bnnq~jxTUQsx_`#A9_Ls`{_*xj%$13J?R+>Hgg zH77BRZ_D-OJ2?+N{sd)oE#9)w$eOm9XJJ2O^h>#oK(q9zmA<7(xgu57Rn4V4F(DJN zW-NF)ix2>`>FF13+Um8PR7-7=Aj2X)u}5He%(C{|ZviFb2eJYMg>CUwc>g3otNr-y zhiZP)2m0I@A(>+_8lMjylsXNq{TKSSk=9X65#4Y9?h!Ax;miZG!GOdCg|2*_y<9az zJg=Hi^>NaI_p;l0?DV~>Bh-84p^|)l^OgytqdM);&6*|M)8_-pus2U#S!FKff zvG%SO0ylAQO)fy(MD$(=&@F$O(>9;R{X!AwcGi~1#BM8mebRZ(+JHXq(s@A9i*Ko9 zX{^DxVPEEQxCvFcO*)^@I}YXP`y*|j=BF$7_^)2|0Q~}TS_5w4i?RY1=}JOhvzQTz zz9M*IuMB&0_}%3K=oyK``0iutH<>yNlSC4Ilc_p&%}CP*sR6p2r!5+Mpv)pz z@QppCuWGAqYsq345#zf)OXBeuphhD4Pi-I-BYyDdw(|L7OcNF-)Japn^Q3IQbK6^y zbXvk~f*H+%1_Bo105A8Yv_)F+x|%QmK-gZinJQsx$3h=wFFooPHssqL*$Ag5gTn<|$pmO%r$m*PqiBW8SGx@w^ZGo8ran*h~aokFJtps8*H4wjqvS=yeKwL-APJmxnw?hqh8}o<>Oar z0r4~Vm<|sT;#;)@PMp9z3sliMe9mvRDAr3txL~2irEo5PtF?q;QHN)vfFXdLDf{Aw z+1BQDciqobat5da;l@~E{)Q2l&^Of*sgm`uZGP^f88B(^%dna>y(ENByV7O+9#$V_ zSsi;M5|N_+|8$FUlxtU@>-qRdCMb&AYV5(zWUOq;L`k61H{;7TQdoieKimd$O&(|F z8`7~;yjEsmcc+r1YrDxZOiA$#lVU`Xy?)-g3Uxv=PPB4QOv~nZL)f{UUo&^w8+SK8 z7N@Ei+Ex=ksGiVu+9taP<4w-%#$0DcDT?v2{N$uyH0kZfTV!2!<(O)}>=@mC@g%+D zs*|bzhG0?A#EmS}A|X7iV1Tf2gXQ4w-0X7yp8hvb{d80v9^9#1Zj2Z4pt1$NHNoan z;IJT9cLSP6QhPoAK4bgH*WbU~R<3+fzXUeD18e#CTi)Hb*ikt8Y#d99+_C_sal?(a zT_kL`G{1e!zHlnZt90KhECQeW;vjK`b)c&F*4L-hs&6Jg(lX$Ff#{)Dhy|?7nfxR@ zKhbn6#aiw=e^{Jmq8*O5Bj{?W(Nctp=SRR05a66W8xT#G0#!!d70uZHXcAvA=kmXj zTuNZ}H|qJTIqA+~Fatg4S-4gF$i?^u!a~LPxI|_%79x~~Qv1bh11)MuabjX(bxTh~ zURq?{=}l1&w`7U;vFNs6yR9+vKxM%{aku5~pV=-6zbqJ29>J8}j&~M55Kd%}ezXuS zOlStdrnZp%LUpmBY)gt8c$ztHcR{N?h3gHPnV&L_a@;bYaNAy&kOXBZ6c-Q9vlh*G z36Zu2dQQG;a*$scs=u|rF9{X(JF$BQkX~e?uX;@7oAAH;^xy@rJ8kDt@3u2bd6l+{ z*_wa8>N*fsg!T0#_%TgV|Foi|n_|ohpy#+=tt1jaHWIcY&`SEF2~^_q-<=+P5yIs0 zcQN%ER#e@2k&$Cs6;gd5zH2;37Z$u3{b}j3cLfpAX}_w1U(6_MkjwjPBFv}>dB&}o zQhUtSGBaFh9l$I90rJXrcf*|1mCAi=8yKtvvCwj{ZU1{htC!tBgeBLHp&Vh@=(|Uc z9!+N6_hG94a9y(Y?jF!r3w7FiVj) zs*fAr6)#8J%MeFiH{V!wXWQ<08whxb&QV@o5;?~ZH@a7%-n;)(6LVVO9RL(f=+R%D z$DSLKrTiECaa2!0fy-8c{zQ3}u*9vkRpAyPZy=1zJb-BB)c3Ex!iULi%TF7Ds}koCm_)do?; zrcl=F$A#2u*1?PLLm0k8=nW|vD&Exj)vBeyF{#X>!wE%Hx| z@IYSY$KuHdh;NdE?((q_P(uO&%a_96yJfGWP`?+`IZ(~!NRN*xop6Mw&u!k%O+`VN zRXBF+7&my#IIF2h+d;OQ3{wf;Sr}4$!mLqJe1NN%RYGnXlA~&a2ay6e(RyX64>Wo0 z2pF??M+B}g7KttRM1EVYn2jqw); zw$l_E>-RmYY-@G79TxJSrH^XxGGi&tcYNrQmo)kO?D3D_g|$ z3$^>nX^MrzYqHy-L?jPUM735kV+Zd4F%v^(w0G=Rnuz+?yt>l|wsx@#_N^ zOQEYh=P(PxRIeEDsPuZxpB0*2bpr`ScVGzCFW3Hi^nUCsI9IK$d!paIF50}vSWsF2 zEWat#?Ek*p z0Ud`Cj9%b|pt*LOAP59@0NW8S5zzm2k@J1dl^91bW$U%-EG*Yrk1eXO^O)t&MNBCU z|Lk9G5egMOlx}ST6sLA%RzvE2aJc6*;{6@y2~zs8+h8Zc``R4W2Ln)_H(zMZ-mZA) zrsS2k>>*Bc9HfE1W21GRoh)%d6(=@s6>bL$84gUCef}dqnJ`)5s2StWy4iPUHL9*l zVS`eXc zHt1~Q#P|l=qZ1W%4ov>JsJ#fxq0+gtMbV<}F$jnPCXDb5k939jlrtxh`g)mE>wmED zD^!n_v1$|(oVnenO=qmH$>T4@5DKX zI`BGuVZ~Lv{&T!ASv^ei4%NPYgqVow8>8Wl_6u`_eg1p07Nv!|uSjy#=xc83EX+6lG3vQvsCG*W8r-@oUiC-*!-G|fs$QZS0 zNKfI+XE_|DLpC7?7fbYb1x=4*bi(m|5YXlxnv7X!!WmRp5)xkirj)=NzYLwv%93Pa zaCq^U)tBNi#dUs1ZGOj@ZRbc{^Jjq2Uqn-&jhc>eU`wIPxX6qmt=!YFI;R0qe^loP z6-@}q4aJ@UaM!g_WqZ4yYx=iFXL5m}7`J!$+snL2_J9&u`f~^WXhg+Sx?R!DCQqKL z+k2tjUL`h8Uly*(s`xl2zu}UNd`$i*vrFN_1@<7JRgFRZ(GDLEDhuP;=b3p0`R-Ev z1cM7@O7STg7ewiwnZjDM?~NB>1ePukaMcX8PwOVy`e>O^OP55ohO>ixsOt!Ep@VLZ zW3CGhW)<~H_=~x$M?5kO4P1{nT<4&-8>pan?UM9bDJGk~i2uak12a7u+7>lq>K={F+!a0+O4pL_s(FZDYr{LBPDCg`$wvh z8fCVuCM5>yH4h2AgMXR_mRYr@@ex2vB|%+OPy5>m6h>q3ue)ZodUrJ$MA){L7N8k9G!97RT<4S za!t3~k?HCeOQ+Axs2Ai{NWNco8n#%gjpsIBd1*Zixk{zHH?s&%!>x>N7ku6=6q1bu z#gu8QlZi5#W@z$d)kh6ld0imNxE+(sU#&$~(iA54(A!gjf_`FENKBCG%xw^etk>{r zr@ee0Hw9 zQ!)zcBsGccBtF#z4#oq=6!HNmFL+$ELNy@ejMmC-y&(AG7G$8jpKv zmta$pdg(*Abc_^;7L2jVl`2;SAFHh4J+IfOh_+rKYy%sbPHJ&pj15g{r;%M;l>b>< z*0jb7Elu~azKcB5ot)uv|NW$KOCSk^A7M<1bbIjTuSMvi+`fb#7<)6&*<*+<##s4aLdQ zed(=0+Z0~2UwojnX{OYm)352+?QE5;mCNQ$cBaL3yWfKpM>x$M4+R#A4@p>A<&8PgG>jWPnhUXIo|k#Jq50 zvNfsADfdn}+wpsK**DmXzBDsjYx^$2@7PJvlkQ{LO*xPejqhQExGyGs{55>t#TdS^ zgS(^gX_yFIq?sRI)#RNClxEur9C-9&CZ+W~PcBX7+SrEcosTP~84KSH_Jj!MnugUW zLh$3}@;|ag*19NvxTO19UrpCGG~Jr^av@iI3!*>;Xawpoj1pKet@V1BXJ?ufZYTEi z|6MwkNcm=En9C#!s&k32sOKRL+igv zDxFqNVpzv6Zm?aI!BTELi!w?5UgQ)VA*~uHS0gIBN%{3nbOQFK3jbXL^YY5uGA$=X z!D4iidPC%$<3H8IZS(Oq3;wBGJ6Iv1w5)F2C-ckwqPEZ75J+@-htb;#GG3gU zqI`aK>|6xH+hJ&iZlczO<|&^ak>$_D4&LpQ?ey3>cIp0lag{D$*MS~%3wL=$?0?kX zef#!p?Op~n7$K&5itZuTXLIyj63*KU_;r}4C{g-TBdk^ZPMPU?4Ie?M zNP`lR7+##0>BTfz6LzH2{S}25%L-}Q`kRu&^m`ZO#cuj4;t-F9>ukA4%W+tRt1|sL z#TnYFwi_nPE}56^)a@nx{9&k35dGa`%K+qTgW_q?WZh>SnZzS5pTD{Bx%?wW6u%q# zRm|L^E+W5|s=rlz@hmT$8$)Yn`h$njbN=-vYy72&)@pdHMWM`sU$d(f?pRT=D&)m&1qGz`?O(Cr2s~dWu#`bVq?}>iZ z>6(NMf6u8BTH%{o1wAwIu@_87LXNu~C-Tr-i^iRDPF#^|4)lo<+RG}s5P`Mqrhr$d zzDKJcqZJ@%R!BH@KdrO7MxHRXTDi2;9~_8#;R*MNW9pb!Va-c|8zHz&ZHMBIukBCt zF|a+h(E!sP%V?_K|AeY|d@cr}8V=o+B#bKriAl0FO_ebzxx$cs-Z>jh8%Wm+MG`6&C z^(L#nq^tZqlcSld6I~IyT=Gh#CA`UieOKgmfwXTa8l}Cb5`z}mI!#1mKau0`@Q~z` zb0)ufd4`Z-)qGvz%;*${s<$V8zK)$h!9V^`#sSk>-G8@w!JH>*g`D zpZAMq$T<^YWlL&X6XkVLc;(2YEfQ<3)A(rRnEVq7{c-&BpGvSTGPhht;(4BRl&Vzd z*In~8pwL;kM6|V?&%4RdQ-IHOlhLtiu4i(84kpy|H3Q4ocyOgP^0Zq8i%!X97lMbT z0=lCXV9q*Ubsa|X9BHYIFv^<=dr5?jo_KA7~qscl%) zukF@L$kNmB;IqQoUyXa;520R^nDKSB zgw3CZz0>JQ5JgE7v->CkdNmo`Moiq`%=ziar}T4aZ3<`qRG7#r6=x?}V1EA9nsS}o zcE{W@j3IvMTuwhXSFTw|U_eXeZ2lycuVDc(b5@ySWQ2OJT3gzugRxgD8Y|U3QyqiJ zD8GSGjNi6ECq+wh5U$}3*XqZ*fP{AUiy9nDtaw#NOCj3p9y0`ujuRVCEw0e+R9J5wg!W3*KeeRBlQjDDG`(u|d0 zVq!-&Uos$jU}1@z1@$l@$S!l+FVpZ0)H2jv$QN?w7>oacX)pi{2x2WW4w8SF=wmrO z_C+<4qouCxSK}Kobw+#D5#7J1D868}4Al9bOfTy057ruZfJ|cau4`|()ySjLoBCv# ziwue7+#Es|bL>m>r@nD)6$i~OF=QkCMjuuAoDbDOArFl)Guw!L(x>uQwqI{= zv?@C%J*O&6`IES*oDy=adVGADxoJ@JeMflFM{ddAl2}f6m3AB>^k0p{zWtfgvcl!Ktn-E6 z`kH>@M{%zT?=y9KfPP@I^zj#7b^ zEfOLe{Bw|rrwRF+@b`qkxE_I7Pc86zs9OR*oNv?|!8z_2#x*_`>1v{U@dpd`>#jZH zN7DrF=&EZn^L(!2QFEzf{jH}+GtxIt(7GK=>V}ur@K<&QcXXG%{RD}ob;b=JBBVu+ z*7O_-j{Sl67N?xATVKj5y!tz=N&l6-iwzhfbX>f-v-HrFIutya-c1|)%J?mHY5Ibg zO;%QvYD%feL^Xb(y+_NB>+e*cam;lU{O~+shpX_{&oc^^)VT+e556ShYulRp8tKrQzr#qlY7Aml5+6bt{cw=3s1r-M_k6Gwags3dUAYul4 zM>n0txd2q*68*G{Iz3v;ogz=b$e?4NxGuF15lGcWo^jTGe1OgAdF%N^@~zUoMny4q z&AEC~Yz%gwi{{NYd(kZ+(p;=s&sX1qmB_YO;@@yN`eo@-r>(M*#$)??sDd;H)+0AN zZ(ukq21%NVf4oWA;N21$8EIE>oqdiwlXrzq+ugm#=Nem==%LGJOO-*l(uf~|6IP$H zlX2RWts!ie>o621+XvgcYs`Y8ZdogYec9w4A2AC;B>`QJ|8%fo&3=b4Ki!J@k zYkmde=-7s^r?N36hve~O>{C`CCj4(PGpG)bMFq2I2IzSU%m;YOTz7f9QWYh=aBR|7 zb|rp!PX3716nO6rc8o&f4j)7p$Yt1ik+3Sr#Z%9Y&5)?!MQ^5`ku>CBU^%W>*sQjJ zOCju(l)Wakzrrjd@V9H&XT#oS{ZJvw#GFEl*3@|+p$iO%*1v)z%gIMhPF%%w2A>|U zs77BP@S0?ePa@c<*0X1)ogFqTFBe(`n~;&Z^)Hx{IMSarDK4ZoxL3)(upv>iXA_q? zL@9!Qm~rNszH0GtUmU3h=Q!JG%uE z<-_eWL!V)8^V73v#f+Dn0Kweg;`Pxbjgn^C;OH%W zfZ%cTfWjrg+-*4|G6NJh6s{@q?k~UaOnQ2~T2qVM7xswjslL^Q=yZ`^te3I4!M;e* zD*ZA}kof+L)$9TL8WM1d#E1bBHgyHv0$qIi+-ej-S4_49&?YT z!bhp;{$=*o+)>KAX__u)s&4j3DDG1C=mj`M_1E?1biSXj(6ZxW30L}Hd5@m?nAPzn zN{-~GbS#ZhflV>2_mwwN*ie@T&<2#5!bM>>?Y}&!ly=qc61gw46lZYIGTWHX!d-Rf zLPa!kwo0}XOa3)VWa?IA@hd{l@dv-w{vHsYQ7`m!o8RSFPmx!7k*J*U^21wC&s3N# zj>H737LFjg6S??Ds%VMfGz)p4y&UkMK*ORQls{6cnTYKUB`A2XXeFHUhJ^xkf z@!Hc!8W#jscz}HNTKaU(-wFK!w>_sXtFPZ3N!L9ncYtnDqR)X)!Whu0U--52YCd)Q z>vX|H4TDnhV+P3Q@gxAZ^@;X&usiBSy1{keSeEMG}^PDJ!;C^+Bt&g`urTG0R-ee3WpFEl6%OnP(T zw}iio33v*8LTSge#t7f>F`KSh(C*H)oay*M)nW9{P_kj($*e@yq$HZqH)U166!?j^ z*-k|KZ`vZ`0q3TSF1MC(A-*NjG#%VBS^Nvts=v@)_!#B;Y|@Xhs9VcUsx#?=8_O-R z{<9JJFiwDksboAjobr1e3q)Rq?L$r{H)wj(w5uv#ZjB0{5I&g9{lPdQxzS4n;m=Ex z?hMwjD?BE?QwUfq1=GFis!3&BU0iCbHR~&sQWeD6gu*FMi0Xk%^rY5S95ZSUD~j5q z#f)A3c!@&6aV*aJ5=AnGRXObBk?ME&{nOuOi z#n?c#d`SxCZi2PV^hK_fM?D#-JEdTYHbxE5)Z9AnMf*?;;<#xBgt%WjcABhL_qi#*;qXYXU&!Uj}R8# zTf^FV5=UCY12c;0y88PiiG0k^J(>b9K6)a}P4!dju#gm~==~>Jr4_HcDq2VQWs~-w z`L_=Lv26WzPz4EwD5BmLHA&QAX*H9MW5hIw)IUL(_?b&tAFvuX|f(z>HsR zW-*>sQO}+M@i!T<65aDU{m(ZqHipu(gek)0<%)YIB6rnPPXX(-V`Za~u{ zsw(3iu)%~@;Ia}<0=r2ZMtX)*qsJ^?q2qWVdR;a5E@bf_Xl$05>;LFq zmXe!{hl=NCXADJ~-g$$>;2enh#M(?D^eBfEurI5NZ?zC(s;2rlDegn$$!`|VDHW-N zpS`MNE*rfeURhZhbK!p?%h(>-^qo;eu9(*iCYR-7(qAqfmM&emK*>6ksm_P6SV;Qx zVj3h_vH2_?K*?@|z`R#9CEFso|FviY_nuqp_ldjo7a8C|589yffZKs=?%|S}({s9I z8XJM59C67u)AJ6D!|@4Bmu}!SVhS+52ERVAVl^h{9ZUWY>yoAzWhK}y8jznII!k1q zPqTJUqzxJC%=w-RE{h>D9hBQhbCiJM37`ZNF*po#A(z&n(s>X-7)9<3osb z3*vWK(;q_!8x@*wo>=DzJ!A@HZJCi|ZX1yApI>S3EH#~^vRz-un^%SGO|ot46r$re9G7qsVkR*>W9exWzU zIL5bHNj2v36>R7FSrNQ=fx+6thLX+~7UHkL#kD--Is>y$?KTh+a!0V001 zkl*lZ&$_o(At~>@tsXvAc%b6%|NQY!C;W{zdNsBT2=I82Qu_78Pv)g zYZwT#<&fi60Sc$wi|lGjY%tDPZ)I)mA{jQiVj2D8=(JTxkz>xay4orQ)2eGf!i1#U z$)@n2)#;WyG%@*ZknDU#_UwjwwAWrE3 zE&Owa)jXJ)Df_o72H|18#~cQ>-%BIDH7=|-wV-=sc_6Zq0DOj;85J=A>h3!0(+8^p z4-mocW601Jps#QYPIFQA?tft-)ig4;ZT`xHyON5b#PPdHvgM=Ykx^MO8p?RT=$juc z6}43hDX|sF*|C9CtHWojg8oNclU_i>5AZs3+8uRyd1;#u_gv2&hO%WXl*SM8`Lk!cNM1TLzyLk ze88hx)FafR>TDCUB~+cp;3>^JV^Eif&PAYfzztc2gfujKCOay3(^sQR!4IQzO^k*- z9%_+mlPxi<#Til1~CZ*oqxB3yy~&7vLVeFv_8|I1NLij%^oigmf9X&a6=nEJIj| z%*Z4J_efF&om+(&Agl0}>stPNf4R;jn#pzTgT^bm>eF}c01rlc1Y-U_(EtWCU`LU- z7s+Ev;|gOZxb=U9rr^a{7tje@<2|xC3BZ4o5!<2{PRKA@6>ziL0&ATU=M-^0X67Av zuGcZFYLLiNCsd*a;bW2*vRUezmUKlPhO z4YGjwV>Om95Pd(ljJ{wn5Ebar2V?5IkT7wd>M={n zRXGWXHt&}zZIdimei4@+k$i~P44P^ueUP7b;pf%udfPn!)HI54aR^I`N zDge>nR}Vu(cN0&eVe@OLj@lIFiBz356TLA)vt{);YZKGRY_~nRsJZ=rBguMFA(Cvo zUuMXmih@bP97*tzrxTsvvQA5J%`J)@^d5kO9JNA6T*)A`j7S_=OZ~TQW93Zwm~XqJ z?-r15EWMHRA?m?Bg66CgX$^&1boeHyRJfhGj7$_$$+vk|K6OocLqbh6Et z59%NGuSqee>EuH#6zJ;?ab(}<-!y>(&o3Su?jR&@cR-)hu`0xa+j>= zn5dLSXQ=sNFvL5)G9!IBgC>*J@!;aWDS6i>HQU^eAw)_vOg|L&#)Ryl7?&+CA3ZvaE`W~2i)Y|ys&%OlLS^&J&hm&R_M`wf1?kyGAr!hx zU|XF0@>RLO3(G%LObF&L{MpT`F%dLlLg$U;?)I0J9^#<<wntcur$C`Cd$c%Ul9pg^xx@9uU;GDPg^(RdKx;*rlWohq#fV>WWrdp#TAt|b{ zqay@%z>Ufqso1zn&CRp>pMMV*pK=O`b&6U4H~$bmQ|$<}OOG3zVUn?0sm%=pM#;*h z5aWx~*2tCzT*MecSQ3omp+tYm2!U&^@=KW$$Pe5#rNNgPaWuLjZN2vHpk%K z^~|kxGCK|8wg>l?)u$xYWh|HvTMv}_67w?DyoS#P%&o1PF0iCGN_tn&KSQ%v_RIl# zK}3X}uq;?5{R*UkpKf58L-E;}<2nX=$AbS>$sq+KS zG)QDKN+V6faA6|LWtD!}T-zNEcf-<*f0$ew{AHjI;dPOVo%y@Iv4MaNiqQN{UTHbz zPILhh>_akVMK}ewv2>%EIm5PC67oFb9AXrr$ zCehq+_I05&e3eX5ingO5wAXJdUhB^1rZC6s`$%Xf$4R(AKc`2I}{c|5&g;*u(hx=r>BEAy+%%_sV8K?2qpe(u*sw;rJjdTrLr0lPfi$k z1r9?K_O_<;RLjn$FOr@CZq3gC;Y--s7_>%xMjBFRK|)Rc0zX2Sz!L&1Bp~kzF6}>1 zT|T|CvASH_kFmtGQ>vPo)0rZPlQ0n~Bs{@7pobN>r>#n|q%6jX%78~N;fPF2-?d)L z{rm@gQ?#sUCL7^OWiVjP0#?w>!mwy|aW6n0TkcBKvE4RUR^~^6* zl!f5A@lzz?l4rWu)^4i1=BU_D2##8gLBd=CMFhj}*B&kB0HhFqGz=*ujXWC@RZSRQ z?Zp$)4c?Z;5LZ3E|Ib?BVICMfC z@@hd_14fWC$AGbOqYYfbwRihn_GUo}h`@A6bW*es=A%rkh%}tL)Ia9IK>G*GlSebb z1U^{~SFpZSwct2KNtp}>Tcdih*9z42s~=r~%j57_c0*>0Id4}Udk-DtljEc)#;@(^ z5{jN5$s3COvNI$mg2QKiOfg5UM}r|;Y<3*;4vG8>_1(d z7lfI6zCPdSsixYQ@6R`iwG?6M;dSz+j4ES0@|A z5D6Wiobq98s<)uwg#N4SWppxq?dk}=-`f;Wn82O#FGqTMJ@0gX8us(aa6w#3RudB9 zj1+b*I%Qb6wFBBfA8Aypg=HzqXAOMmtW`~4_t8}7O z5j?CDw1M~Mwr!zGXd&6#_6&#r;jt@?^@*x5Xv(PKIhUBQEkxbOV|cBnHS8gBtpQp0 zk`9NaM)rgdm61P@^c6PF?FT`dM~{FPRJkkU%0&6{Orh&c#{=fF0-3U%{(>h2*@ijn zEfdMt8ZrxP_@*dNU*Dv2n7ZO`OBpK{*i@VX8iQ+VQ+H_;vNBXG8qvA>I2*+nVoB@b z+oT`qui5Y!LwY-`uHE0>49n9g}ow~8RLiiP5l!#!)kW!ii;947^Scb&ngrf;X z?`a<%4JY~yap2Fvsug2IPs?w06|SBjr_Dua#Hnt#G#rhzD_UfWS{9JEhdbDr?*zv* zC!52>&wz;`v+ufG_wuV;Yu<}_*X;p|%na+8)NvgqiUofD=1+Gnf!ayhw!7^3BHQqPlE!Sp*|0_ZcJ!yvTTPB4 zYF$I=Ru7sPG6F|AblkL{N@ly$-g&n@Z6X33hgTGwwwA~KRR$x0god%M5^ip8rx|0w z1*AEs;$kJqS*21kPzKbW?X*dR2C)tRTUV)8qAHG+6B{X|%XhZjH<*d|65hj=oJ^aC zlyu)y&^;-Ob6YFdj^>y?p`GepOn&dc)F8Dnv8ZLc@l8XZI;#oYzO_F}v!bDOT+&MA zrbFOrRMsH-+xB&E^ykyJ zUA99}_uqPI#N1b*6PmY%uSo2$vg&3dnU(M7>-*jCat;K!!AgHU1#~sqP{|>f^aqqe!sm-E!Wq?oF8AucYN1>aU|1oHKn+c@#R* z&I~5AGY2SGZ*!z^y$XO-=7|TY>e*$EbeM%gcbTV*H+!8Yj-^p8hnI-Nu1=k`w!KDJ zKf}b&Fj0vaYuY#~+)@k^{s`yiL11G_?oen_42Jt+Qptt;qW1e}gN1F*vi(V0P;6rY zZ-GB;s??~z)Ol$d&y0U_-7)3JlZ^z~apFx~Ry1<<_ykac3!lMagCyHcHGft-O9onb zw{~T9H zb_*TXqZ5l>K z86>_cy!j8@i{pj5WW(EU-^tOe3%?*bvW<-HAbr`i>M<)Ci8mI{$ecbGdY<}Ek>u+q z_MF0`P=+_<37+d~NVwhv(M!6GT#cCkFp@aaFdu);IITJ$&@3i?>5K?VcioMSmU1QY zA2h#Q7e`Wb-@qeRQ7a0`)5t%V(#%rPEb|odl&PCjn{KL*r5^=99B{L6h)f?&UIk!JQy>^a zDev`Dm_SL3adJ`sdM5S3o8zH;mRg*$Rv@r!92$zg2a^c_WM$#w(s4rk0|WkwCm_h&XdJG8*&elw^~-ldo?c)iKC$eGfw?tpKGsqpqn|;YNRfF;PYWa z(4=~^1o9kyjLk!;i8zc)p2ae`#X+IdaK;0Z+B$@|ZWZg0L&=iq1a9<}oBOG<;-k{= zdl#Yx!>d|(T#DgaG_K_c--NlWd0GKOeW_NoDU_;(&?lEGqw1&BeF&8{xWQQWdKfOf z95%n>@gk^4y}UBXb1QCa|MuS28TzWLDAi>5J^D~ImU|-0fZ}7o@&ZARhJM)OzFpxG z^FkDEb2UD4Qy;Ni=)D|6+6O2^U`)!M>W3f|%f7rD55rTcq8Yx|aH4&G`MYiD^T=iw z+PxRk6IslJ6gNg8?Yr*0N>a$o973x7EkhA|yzV{xL{oDAt8FlPvLhCpHArNGF}{fX zOqLYbUlGK&jM?B7szC;r(E0ddB4< zliAbP_lQ-UH4l6gG=8uj<_W^smiO~1rds*l%}iBD|jc!LrngvOXKOMAb}qpknlYZ?D@Z_XfpN#{ zz)(XUjAr5W;DH#dYrtYj?S1c7nAjkcl`LDG7n(dlDXi<|E>F-n(H|Vf;yS~0P_#U` z){!h59?sS?2K{;OPo_Ya7;@9+y51?D@0U}qs*IGHLSw$S)U8$mTKRMTdo2>Bn~^V= zkz>Pkm7n<%gqD{2z9iLQZV*~_SEKCc?HNrpxlCGhIJK?NOx9YBZk%P2q2-uD&4R&) zO$4&^dC<&tQ#@=LFvVJR`xMjvUJdSg&$RnTaHk)*lCN^#!Sc~qpy9VGWu2*MEJa%t5=c~j3z^UfZim&?y8}cLfF3{D z$=$w;&4a+o)!$8HmSmTQXej@f1DeHh=Exbmi1-ludkKdGX|zZYFQa)S^1iUY^^n*ZXoE z?<%u!j1EIKD(om`>9mG4@5G0EOUZ@vM&-JfNynY`H2x1`Zvj>1+O-R#peQK_(jWq2 z5TYUtQi7l;NJuS^5NRo4(Ml?kB1nr!cXvy7HwY}cq#MqB-0yqd?|kP!|2fYXj?Hkm zS?j6$p7WYluvn|CwM@;SRxXRI(FPdLIn3JZ5S$^}SsKb^J%@wiowW<7bK&jfnT}5% z$+tGLO{AnkFiU?zSJNkLhNq{G!hQh4FeQjv?WlV0mm`~yaLoQzVeOvqc41v;{$bEJ zge7nMZ32IEtjw_IIv4IeS9avNSq~r>Rc*mdvE#x+`M#Z}j$!i4} zgoY9xN9$#u46UHv&rgP`dOCz0H>c3x9Xz_Y)G)ARbG)6m$F-?ZgY?M zr_-JZe?IGiuFb6*4p-3af~#}BL_@h+B_z5TsC%oKw|~0=!}&RmBkhhbTF0T$nuz4Z zFc@x4OH-Z#=eAQ|txO!UEpMf3Rnj-)RdE2?cImN`xVN}Uz170T`>Qs0q|L#3OnwPH zX->aRi|zM2HWGc|HT|a{c_W0KO?^740X&8EIvQeP;;yC$a2YPXQpJ~qC3DK-4H(J# zbpDm*zxL5sR|^_Su(;=4u4XFQxEnCTU69C`)WCMlXC276eue#E3XK#=BQBw3a9gOlLm6Uu8NOhQtjw33HJ2AXEj)= z+dxFJBWzEWdr!mSr#e}Xl!hp$OTo%OX3QJBCB#Nevn04XA^&&{?;*Y@XHj10g5wNU zNG*y;X@#m;mGG37Vihw(q)mjLrd|va=>9yYhKm&t^e2*=c4H%82dQOXc=&4Y+FP{? z_PROb^Z&FZS;QUrDQorY#mC-lv0*?1zPd}(6-!^burL@|>ep<2Z}#}+!NIX$NUZ<1 zIR9oqOaJ`RqP-!#Nc>c(|HsW`=mGLF9dx-=)+%QN>o!9!(a-ave8qM?+t$n!V-m$Q zoaQ*aCS@E;KBxvBGj3>@9H2wDGc9ClUvV;+&t??@D5#9k>BAXZqInM3I(+ewoLdmc z|Cj0L za<0YwXm3coObIvmj~DIg@0plM*yw+_ob0of=;BvhO#Y*AD*Pa<1n}*r{Djs@FVr z_zSuQoYhEE)QHZN-u-h?3Cd8U!e{z3^E?l9DvCGu!1dExPQ{Jy?PWaM&x^GN6|FWN zyVGb->#4GWkzjH`OH{PaW34$q%~@xm*Skr=0eOi_L-fR!ufNW*ZA5)`A_x-j$!AOn z8||RmM8EQX^?zOq33J?xgiS544EGNbMgzdpnf&{2gyvhNYzWizp=EF18`09+; zzPZU$b~NN6*10)n|KTv>`5B6q0XwuPkA&%wHzV?VE@=4l?S1#Bq7$-`01Eb+6`2(r3YfAI-7Ck zEi$IK2tMjBI&x23-Tq>Ttseyxx8Kv@`b3K+{wm9}d7TD?rDv&Y7=6%1y7UT41s~tO zaZ7vVk3XleCMW87bgp%<5w_I0IngDhmuwjfXw^fzJ-!Pa#tRqvr;C01Z211{jN3hr zbWt7fq4<8Ga6Z7RR2ft*emeDxnRCL^90QnyHR;#3n4iWba#U>}a#wL)tiE(BZ$UKrPrt9-ww^38ydrg4Y@xvL>B1N>( zo<9ApFk-Rwnz`DV8XfCj5Cr@LC(DQ?zc*8BVv%?#R@|$8IHXcuKULPY>xbl2@32k& z*e^k5uN~oiNASdoE0~efJNk|58oUZKjwyp_=+x^v+JHI+Ifw0pv1(5q`SZjJA@;;r z7boBN7!ld%+!EAEFR$IIV2c*{HrJ{&$)KfN6tSxluLG?3rt{>w?%uRlQ+|g(%O9&M zqZ7exo=)S6!LQ)7(IhI{rYl%r5DuB6t)*)WwLWZ%ecd+k;M3vMWL(>DTg$2%m9XkW zya~R@35X5>>CsGiem}*5#v4Wl*K5WB7bdx6`MmMcR(Q+_cL{p)I#^LZyZ_UIVhywm zFkSma4A%rrJHJsazoL^a9xASO{I36l`iXwZgkNY;jf!z$=9QI`xASS0TG6hWrY%cn zuoQBTnGj+fK9vA6>nQ_f*Hi>MfL}5pVh@<827!@5#@moJ^mbEIcPIqC$=NO|YJnKk;H-Hv0Pvn6~ zbhcdS+o$G>Kg@MZ6GOgdiOeV$Bp=^bOZ&LQUzRq0`D($;ro{@rc?&pOWBt63WD|j> zUN_7)>fY{yl_@l8#?L3?D|Gvy&w}~bU;F_|OVPP7d-5AeFPumc7QC#WD#n%~n%S{2 zkJO7QTQ*7-yY_PS5ZYbG<}-gzG6)I1G-eM(=oUXY^^4F~v~IgxW5~>3vie5Zou%`6 zY2B*o%pI?(&|CG(zuH`;eh32RX}oXx#a_jp4R3FSTpHhpwh!1ArUC79#j`hv9DK)Z zpPXANBNS25)&%W|A+Q*%5$YvmgdiUG-3d=`4}73nH&Ai*EwVsD#-|4RK|t|$c8Bj8 zI=!W}{rkDKtGO-uCiQ@#osmDJY<>E(rB58aZc6ZHMD{=wLb%<8PITA4Ahe!_Qdu-fp=&N8LHt^mLQKN~K{nrK9;(5cXVKDVE zG&l{B$M-62K&8G?p~yTb>3=h@xuZsV&3Ir_AGLR~3q)%pN9yjMGLhnY8}{P{$HMC~ zMf5Gcq#imN{xR4@uKN%6(cRY7#vgY!$BwZ%T zV${lFjObzpxW8Moxk7|1=c+1ZvZz@1xCUUCdc>-UWs zaa4WTGmbIZVQ#3Em0vb=LaP$90VU5D7qf}9lSiiB^2V-bx@BYJzE;vn>x+DHQOOZX zFbNYISk+aYajX6LN zUP&-I2AU;UglAEz)~6xVak#MwV4n!COEVBuI{d%Tt_Aps&RjLK6>slO{~l+pdvw3~ zYn`U@<$f508N#XDcP@*+NZ9HnGT;dwNx-3~J1XN``j=bw{h(FWw=%e|JA=Cw@S7k0 z4BV|6ge|t*Nrg+hUGDU2>h=7LsVdU!2yN8kW1E6oT21<)jUvhF9uUXv(o2gzk zTQ0A%c3~5%)8gZWvHi8~Y9Czvy3tj^GI6KbEyj+>Xw1ZrmU7%a$5y=CD_lvedq z{)OASNtmj05aaN0CWhJp?_QYKBnI4kah*iFKS^F(nQc#;(aQE& zq#O2Y{oZ0E7Vz&u8bjCcnTm!v7Y#O=!bwU*l@V|p`=Z~q#689 zwV{PM>lzmXl$lolxtZ+^nWFPt2(_7PpsR&@dDf3t4J_qpJyiYwL?Os;5`763|Fztxvz$d^~XYS)a#LqvnxG9Q7 zK|KVbE8e?mU*nyhmdEistO?q|3Wde|-ipF-gEdZ~k>=7R*8mEIGVta7)Duj$aaaAX zAuDp9UWW!SW-7DFJR7@#eT72()^oLeypfLkqMWvw!?kY&h#d0qr;9Do^jboz^?l|d zAU7dNvm97!xiufC746eBe4HZ5Fn+#WgOSK6nK7P<7?&>ZFslrs0j$%Yg2>TpV&gqp zQ6WlJ)3NbhY}8_=xAR#hu2WrR}Z> zGuFc&rOvXEz?gr(*el9P^3w#gtPr~Dbg&ipHMsUhXI*F8KMz^}X?#nd$6foG#NlXq z#fIEFa2lT+uKaAR!)sI-5l)~g3Bw)&-P<&6i7G*+px%eHVTAlfej_pz;YES{RfO-V zxCkbPdxu~wjp5x;^wP_?ozPt=p_5ZNUH4N5*cM-m-G_+U!E?XTzS( z?3mI3l?t{WX2b}i+D}28ho{IgrXb_M4MN*FJuk2W0*X9{7hu-|P)`9o1t<%OAD(GA z8MJ+O)Ha7md)uAUA#_RsbkI6|jFVJ^T}O}!NzM&~`+5Fkh zCqws|z?7Kaj`cm}2Lxj#G+;dGpgsQ@crd_Q@1b6*;BB><7KKDc#;K}z)ZRM< z-q~lgN&Z%~DKL?ZMDpKTJG!B`Svf^!YogCdNM+)sUl!NFDZhp3^D22wY=4Ne6$^x+ zJoNl)qxmt2^egHqY*tZ{NL2{lmi-Fxq?rozS{)6|&0sxM8r`-A|v)?V7?oZ2{!C+3~isdJCL0tfI zN_Ji%BV!)morUHr!@LJu){aotG<^BS zXfBq`is8=Pc`@AM(|CIJ;MZzD;UM`{vGI>ltR*Im#{LU#G@T!aBff+7D5w|cMN%MO z{0aQs7hs78d5pV5VLqyBH8VhkH32?eFo3J zqb4zSFt!@17(?r&t>pO##b)Inc60PY$(2tzY4eef$6Sn$_8spngn#(H$D^zQ-)TX6 zP?U=~SA~O9HUBpnjjV%&G7lgoyCNst(k5Ap_7x`$HQ(e%})Gw!^sK{okm^qjd#gr<@ZL?3fxU%A4gp8`d#mq z3{&PDqw39#os08K{7#{jxf;r%G&>>GMXp!Oaw{F^v94A?uEJvkg`RWRnioZw?Q>_U zxFLgm@A+izzsAqVhrLz4U_Tje(KurIi06QFL&Sgp&DS_nY>P&rkkXO5&HQW3{9hiU zen+sT^84hh-G$B5q>&=u3l3+lKDGwd0^*gO{30;{47LyvGjN~Zau>i7@Xz5IOeD%# zMg|!k)jRvga{`(W1%e@muTJDmj@gJT1KZ+QTXEHM?BqKej4$2cF;Rpe#}k*+V;*=6 z|_kFVb7^DIaDI zz;XbY%#J`|gO?pxk&j1o+q32SHSGGh_A`Jl|*riIs*UNnc?UO9*3+ zt&f@*+tSI!FS{5@)4`Er2kV`)54)3qs|F%ikzi1vt+$=nPB^K6YE-2f*LfQxM0DGN zn^qaXf5LJNP6tUyFGM`5<>-A(`&B<__VVSjE^&WGDS*NUFchj=ivl0f9x#oE`wE9P zBsadI-Dn@>`*QbZ+aCqSwf%@WL)ahJ)vlXHN~k|Gb4vF3_oCT9jYjjtjI#BkXEuWR zFyvW`?h5(Qj|inQu2oiD<+t5NVQ}e$8z0>lu%sIx)lofsMmf_G@}63Sjd^XznRdss zeOZpGJF)ssJ63=m(&B=&=Wjqc1QO2wO<2XM8j6jhn3DAEOmp!^VC1W!Xf(PD870Jj zD-zgk3}jM-=0f%3W0x@?|0=wBbAynMKREn>>8%=V|12DRF)i zLp$}0f^VxkpvKLFHmW^d|NgbHv(FW%6D4SjK(Hwy(FUyGgIGEWC4-;TZ@X} z;GL5ODNkYs`f1zn^4XO!QS!Qo{r z4G`>9b8uHAzX}fswU8d^ES;2PKL`lj4(st+6)a)$G?PGw*qneHL&~ zSKQ9hC|Yy0;>C8g0x`x<&>KV8ZSk9vqkSDePOP`6VYlkPEIVmC@csLVh-~caiqfzs zr~kZzRg3F`S~@b#xib)6l!1@D4%zTF{TN)Frz_LGbDXu0+dLl<=;tp?f65r~v=xLC z$g%{&36O6)>T~apqW?gpk>!3m)b*Z$U%`)U0Yg34>C&wnUd-tJX|_#lZd6%bF2)jR z%Sy|hNM&yPuEs`K9)O_x0t}9LQ&Q~j?RgX3$9hXIh-(YzuOYPLfCyykNJ40q1Rw%} ziOciH`nS&!;r+BY^@~f}&uK>PJz@^M0!a)=Weof@auH%XcQTbo!pm$BSEWAbm*!nUD2JJ-WD_`_G+D+Kqzr-hMDY zq`B)v;eo=Zh$@4-Cg3#Uzc0%+x*kE<(sG0Q?fVO8q)k1%o*$wF(x6)LB@a(e1rWnY zG~#2mHz|W~i*WmBDaHyxG=H)ow8P5Fc|I`J-5!R*Ril)4r`|@>!?=lV1GXHjZ{#3Y z9RZ;cDf2R6Ih70uqMVcUyXzn4ZDaazRP9_qhZ-$tW&epWqD^~0`Z?a9UC<+&%~(%z zyyld1z!_%9^&^Tb7M;r&zihR4eg3Zhv)!K0Hmn#S{sfHcIqSt{A(D;g=y4?ohYLah zMuX6Fr$$Z*Ug5YdL7eHCZwKhie->Qislkeb@AFn#%)Ok(&-7~LSLYCYrK2kok`=vg z9cyt^KRIhCx|hSGY_zh8eQVKaak>(U)3(RXV@`V9)R~}1n2D*7!F8FJ=2Rwp(y2d% zMgQO?xrd0eQL#Ag+eU{2Eg+I>b0AR_;$(|n9@to$F#i3!`TqU%tMeXqc0*Y_M~`{u zymdH6DPCy(GAq!Y3L6%8{NN(Uv4AGm5>MQagUK|7u_lb=gQslfWOmbgje* zx;e?OJ~Kf|R?opDav<680{TpqhMh3@+Z;5>g7Y&>@Be-f78WI9br$rzmbZbzcHHt# z#3k9a;c}!L+X(qWK^#@avWK@%oFs|b*OBY&h^i2Oy_|4<20y@j1TV*k=oV&Wpf`f( ziM<;p$qoxE0k}{4Xd z*&=&t*RcP7OZUQ|;W8+)EKk&U$(Q%l6&nR~-(rJ@F8JxpFwQ@9hQbo>G0Q(7Is7Fv z9ZvZlg}hhhs+Bp9$A^|~tqR)7tTd!CbqK27(3WOW^{tPp!0j0OtT7OfV;~1acpvfc zyQk{XDrO?ca|%|+HOk+8Aoeu*e-8EFFR_0AMC7~ES-Z!N)>udGv}b5HZfTO)vyU1D zl(OvIb;`c#eZKJKvlS!zCZi3g7@&umCP0tf(<4jdj259t#KN-J=e#BsnG(Zr5u_&q z8?;!w_<*n=zZ(wZnqQpq$`I-NaDsnnr@nSWD3&a1o!NJBR-EuQSum)Cw^oox%6^8q za z+~7yg5u1x?E>eUVFTc27F!F8N6kb`D@E3PH%_IJ5~* zVFCXxa(eUyqQ5{K@36Z{o(aBw#z~MN01JV@>(%dCho>^SoPP1N9&u7$cTys%fjpl4 z{{mryZ3sEy)&n{cDJYk|K=zSFanNvq>FpE0smer+E|4rO`0|W@huCEKx=&qkD#-^> zq9luXU`|O30--d10rdU_q%zLX;8XQ*e_*~wWN+2~OtHvDS7s?%6$u0#Bjl4U{NUH^ zyWVp{CFGm0FxI-weut2?^WKH5(h#^yzr7BOKHyT|oFmY+Vq^qD+i%`8+Qy1-~63@QCH?7(&)pW&@N( z9K;rWN?z`BpGDW&RRs*qDvP(;Jj`z-O38uGO2iqkbTGMKZwmkG4s=}qEw_^M=`Dqx z9@i!5-3k2WKMeA_6gyt~(i&IgUs28tdOn$uj2)=CsV!aml5s8Mcgr;l-DrYij(eG! zy8jUOpPk^fx>u&TZ~ZXVG)k-V?#3t>MM3dzhmhPmAjSp3zWnUZfCq5PbD z2FckbF3X&udDfj|Cfu7PCJJDK+=TFndXhp{BxXQpKZa&}U~8efGi+fDbqk~KTizl+ zeBW?>a>h94ESC1z7n;HwQ$zQRR4a1Q23aBJ5WL+H8#m0t!c8$04-b9nS**w~`A*~8 zSm(XNd0y^b`43KV8`df2yjN=g!b_%`eJq)}AAh0TUh6XE0ESp7R(>ZZ8kYUCvVJ}3 zP*1s|Q4hh**MX485c7bYn?uu&UbE!ZZ7i&Qq0dKr)gt$((IX<5Q5bN8VsL#5sqt`N z%HpSxSRccSm4Wq_4q>Gzed`~-6I`IH3%_sNV5TD9Nl=7-i&2=q;OL8rK8sqF=cO)D zfovD{6b-h}wCnyye0SyhpBP?d!zigKCCNN9n~0zDk7>lidT2ts^??0FboU@tuQ0^s zS^q(mSbqe^86+@UY#!^k4kG0GFYH73(6pR8zA1&JBpzMTr^M6jEajY<6QQQqL=thNE((hQ~7|+@nQY`%?jj!h=i$Bmr}r-s5hWll z8UePTd$|w%WaRgS{YSP56~1*cir3Pe*|Mjq*Vm9;D1p%3Oi*R|O7UkF+mxe~hqn&p zd1SfHO<{jRL`nc$G=HiCK4cQuu*l<*gSh+|BJ-NdcXVS3Tz%JYVO+dBbG; z`mHD-9=a0~ws?hUBco;T&N3RvcuGP-;wd6KT_fU!Pj=%f|NFKS*y6LDceLOQ5)>5t z;Vgy7+7McA`%>}*t6IOa{~H&V1@n%Mj%U%>cf63euH8TI{q^d80PRfY!Y)kXTJV@d zpzC}N6~i0YHn$d2Gn;R9fvHbj$1H57@_<_E_t7G;Uaxl}pK3+zf7&2xK|1++gGClh z+@{09|JRNmEX;pAFdg=;Oa*4j_0%1RWn)3&WMJ=3g53i!@DL778S}FB^KhxWp(DMK z+O-V^1U`ZKt)Ki~L3~}9A1$BQO!L<-O44usTfm||Iabx+f3w?Cat*cm|A|P1G-zHH4J^c*Q=AB(PyNf9^cVjQ*v zZ67qNWR|3zeJEqSrg&p)l;Vki2=&u^pU|MbH?&vtjQV8Uk>Ov$UzE?{30S)?%(g{r z1o2sX`*AwdQ7KaI&%i+bTkVjpcF$E0)QGyheQWF$n%kvbE(WH9S)$g`_bP;lF7;9b z@10<^0tJHqv}0VeipM7Z6_$%d=;W#}?fE+WdC!)&h1pz@PDR9n+ItUZ&(o|v$s(i+ zp3J~Lf6lX1wo*88uD~!n?{P%lnDM!aIUIa@5?*1agZnR|X#GXa ze`$Bhw%32>(Ic>Lx$;gl#U{kT zp>fS2n{1YP$(!vW@0+@17M*lCiN6OXqlRp2HuT%Z$6u3EuVk4jJ!rATeSk9GaS$Y8 zE%@E18J6}<#ZVc=-p$%@1vc4t#nVoTC?UI_sS;#LWe&%W%vSf*Nq>D}-&Au-Nqyg0 z-TU+LWpWJL%dCfVY?u44Ce>Aohm@Fb{meZhY6>sHcKr9wWFHQ}sy8Is{5kFx<1eK! z96zM|+rRUCpmZ_V+`VRObM2qw6YtKsa%YDzC`96+-ck;QEZt_9q8RLwvdYos=XP}K za43KNwlOky%#8lvzA>>=IkVEDVoyjSd9Lt;|Asle$k&OI?Ju93f|iVsf-|`XbOw)x zuyxp~8!ydoa7Wcr+(}E}uD1d6q!c;!i-vS0fg@bhwr#}cvy`C@K@Q6oJ8fOEWanPu zu{@c#kFg+r8{H^n( zN(5DA7XqtQP*Rky1~>z#|981NHsUlqW;zobuEVielqw?TOQ5MX0>&9p5?CFcM_V%vjSypwgFyO zw)`l$#0ZNoKI+5=<>!md8&f+#Q&ka|W8$AbXMOn;aQ$xJt6bgW=2ruaRo?gyGP1cz8uyBteoB%RT&`K zG|uAdI4b?)hrS)>o)Bsu6oXtHr)=_~{Zo-$05CIBB{B$K=rKQwjubV=dE4-PcdgE) zW%P;_kU`{wZW(BQH%?#0qudJ0<%08bL*<-vLr%{PWqJO5d9<%6XCOB3wRy=EK#y*9 zo@1Jq#J$o!Eu0nTeRZ(gZ`T`&tZOwW^$(~$%WWO1N<+7ww^TGp^`4}rN?;zNM4WH& zJXj4nYk045;#ew$an$rZ$t94>vS;hmDO7(b7hpZ3S)GY0-nq2C7n!v+Ztf`e&8zIZ zV+Na6g@$GW>GZt|Z%=2nj$1|IyhkNrYT0Xh-IC*cIf7HKbd^JW`w_LwYcB>IU(x)6FDUc2WW;1x&8d%#uKHQ`#COpaN#+NvVOl8s!NJ zH#-h39d+R#a)dpE9%hdy)W59E)-%l_H$?4_x2qFs|a?KDe&mm&?DSBy+7m?)COg6HOwTr916kgU%lKm>oe-~uoY~4K z=ZqC5FwU((CWP$fHuYh?`2-3y+TY)G@)&miGNMRLyi>Cb8wk!}n&<@+yxNOXn+;q1 zd!K9WbS5xz)o2lnm}}t9`DSSSv!o!a3MYJ_)~gS*digxU7rIU_SXm4?X6Mz?+UUM~ z(pu`>Qh($#yNh3xv0!uUY|S{%Mbe^QciL->xP!Sh4;x3+cQLaGV;i#zR^^`FqjjZ) z<}*91*p{b*s>tH8A2)FIF)e2Wisl`{%7CmC)u@I``%rQ#&I!HWcM##Xu^8&sS=c-i zBT}Hzv9)>oC-xU_?@@9hy)$JUVLAVE=~IC(d84Z73oDD+Xb}g=PCvVbM%gKkOpt^R zW8s69Ad14Z1#St<;&_GKP1}Oyz&T+aeN+SovWR`mu+0zOLxGWRK#t}Hr*=^ z@z!W7pV2I967|^zdH7e~@INc_GrWvrbbP~YooT%C2d}B`PX;Al&)q*jv6a?O3 zKxKGq`FP5Q6M03EbLIQQ)oSrjIz=`0G6_lXC+M-H;dfyAE>n}f%P39%p-n%BA0D59LdxYfhWrQ2V0!QfFlPA*}gZVff)HU z@mY)v&|j!_NCO+*OjMLR?vB|m3c8^Nb~a{Y!7BBN*WmR;-A-9OHztZTnM^*1c(bO~ z?gAMzO+v-f)V2@DlKA%g2HxF`u35G)0$)6WB|brpNxf_^d&Y%(v9T|^NB`kA|Hi=t z%~bBY)Y0)06_2Nx3_|?_%-0O6k4pVHQD4;sc3bkf)iEcNFBC*v}>EwebG#r66!a5Q*M@+Zp}&?au(S|iIT;WJHO=Np=W*^#5{>- zZ?RzQH$ zBZ&vyY@M^kQpTvryGLfG!|W=`<{<*(Qa`PO6z|4c+%7)Yw#~_VVcQgV%eO)j(-^^% z87b_f1|1hu?(4Q7aHIL>9Y8kqYad|3med2SNy-cN^2(zPAO2?&7`aZW14u(_f(=kf zY7I)SK2f&FM|Js=u5my*mah9m9xv*4UjEjy4f%ygfo+ov&U0df@AHH%?YvtYdZJ~? z-gPv7sVGdA>_c?!Ze#E^tKP^rHHGYl{F>W^$9p!(_y15BzTgYRvlluihH7;}FLbjE zRXCNBacI2E%x0)~tC;j$bj&|@h2Q0oGv7Pue%c|yFw*vgF)}405e$?%j((`>?Q?IPF0#H@cEpxHoX=!)Z|77ZG*^YqI{V8>RMrq_=nRWsU|dwx|a-fHWi%Er`Z=Oz4{Tr-iYh%3k)ZqZC2i#%K5Ed&v_C ziGuy5%*x&)Pw)|u7r03P)*2z;gVF?-at0!xdzA*>zO54t+iqf`a<(k`*%qp-l0KkW z4Zd)(kVRy>s_3HPmR}NQ!j~_Z@-+E+>ETMqUB2e|lx_avOz_f_hM+e+pqVL@*;#1j z6ME7}u;NunO&$ibs+HU4-!~b2?o0Xt5|}j!(-23M5nk?6HRwsviEZ2TN zF5X;WdmMeogi!3wk7U){gyrFUS)kzD1d5pAAur;T35&dKSRm!iA{Yrg1dKNE>;ce% zTVU_FDRR8^1u=})Vlt6)DwpuviebUVWS8}G;}OL!dp~xMo$imH>aesF#;dU&n8Dt;w z$01L%wKkmm%Ve9+LW+p>!IhP4g*#_!0}Xwd4L=Op`#MSr$#em^;5 zaCUOjz;bXImCBx=6p29Al8MT`-pAu#G;Y3-?I%lSR+p))TT_hMRqtlbUYodzI3`2TdIIMV z(HhNsD|fptS36B&h!LfbHW))9)3JQFCAe%xiOl0tS<#}LB!S0pQ<%UxQ2ssBxEA4~ z&Qc(JZ)>)Fy)&Ob*59KZzlcf6nR9XYsaR08R^Gpesi55Q{4APjK+R|QlYr*I6KITC z0dshfIrGQ8{BP$8XUrgE|Fgnv`kvkLV0L$Cri|PC<0hlvtIXUFhzEd|ppdOMi9sm(QCSMAH8Ufba}xEGaz(Z<)4hJB3- zf4=ne??qe92S1HqR0`NGS`+bSCmi(0UHEa%nYGR|L+kjN+1@DLe3hwIWu}QnsnBnW zu)F2y+?3H&yZY?kB)wKSZx_nU)t{VZh~e2+UvTiP^vZ>r)$%G%v8n)DNNX}_b6~Qs zHTR{n+Bnr-iT8tRhJuz-9CBGOnpxWKhaW<0f*S}zq*T&tBW&$HjI*icB)tkjO8eXG z9-MN#*V@0e;MT?>Rc#b&!~S9Sgu>#I!bbamOU5UTnUcoOA@_RGDjuA#K=Gw4P+)~= zj7=pYrB$^*J#lIZzWF6%@Vs~$(0`R@2y6HvYt_t*B8c#X#*S7#>juKc}LmJ_ddkUuT~qA zr`&o(M_?~r|9#*d&~_Aos}%3aYucCcHN}H{t{f)7ZCc9HZ6~ttI-{Pa=d8Ky)vm&{$NkOo zXF{tRs>gLOl4Ov&_6Ci}z=a_3l5`RrbzPj?1kF;$i|q5~bXQ*)GZr$rv&_%XmP;t# zr_6o)mh#uIXrB#B=ZACyC9rOrNV>8yB`di#-=(xSl&vdOUeEVu^A5q%&&OYSr>!11 zTEMCwjEA;xr{%}9z;HewYO?Ut;Jc<@c{5dP{5?0WOyoBUz1jA#yB0p1e(rdj1nJ#~ zFCBU_VYu1~@bdEdd^(iX%Y%f4+dOg;onO5@u!TsOrLTr^Y84o-udmCW&YG%b)skMS z(8Z0c-YbUILy3`-gv7(&;!jy49yIHeZl()Aa{<|dc&y-xfH?vbgDkj!C98S>Vui|&w7*};j7P9rzh^APm zPa8yx_rEkCtkHDuvRj@Xulw+uSCD8`=(=G~Vt1$pE|g~Y*E0n;M*PPDnxbSLhxCg2 z7nC?|W^aMm{ubt0>Ic*_*Q{Utawu9u_ki0_I?E9|kYrs`tiQtoNLatpT+!Rf5BxcF zG#|j8=|yeq?>F-hNuSE(3Pn~%=Hp3=oyuGV9g~ab8a}f- zDeuU?&rGd8g9Ssp=W`albhFNN@*8`*Q_UGsW!H1VTZ0;$*Hq*1{7GYUh3%jIs;<;B zIFDr~0^aU{i=#res~Q25T2}#{P zLLf{bH5_+g6-?J6sduIffZoZiJr{JZ)PB8Gw{buv6V(Jv#&}RDruY$w5q6i5bj% zPnSt@raCqEwf7xDbVrN`0~?0h!{c1Vnd`aiM{tIuIfQKpL_YE zDxXUpuQ*AH&n{0qWaZ?yhgrfk$V==s{!r^cOO(YrpwIqUYS71!0t&Fz(V>|dRO=UG zJjP6Po3g6a9*@@Y=~7a&qS%KR-R7-=+0Wq?QJs`yRrMcMZd)IOzatyDrdfagAkuhJ z;7s7f)|L^ojdx9vcVk=ER3EEg6KXj=_tPl3jc>0+(7&+cw@iq(7{Bl$l5U5HUhrki z=3H6^ih#stwH01w83d7oOKk5ef>ZUa0gs_-k51D@ny_l~;~bt<@eqE;sW%BzZ}L5j zVp~bP&o{1ePE-WPG7x_?`+8JsU3<7NL9uo+erwtEUZpSFzQ7jxawK8Y_j+UO_t$1w z+#r7a{6zN@llvp=?t4}JfeBoioA7}2g?f88#!(4eYPDs43GG*))Lo*G>YXwc%IuHGMaKIq z_8b!0(L2jwu(L7^zQLIt>{>by!<$|oWn8YSxCNx3r+0PY{ZHO6%4GBnRwP_%6*4jA zv69e%M^tBT3j2)cs>4OyrIgB*hRhak7Tox!Ga3pVw|z27GPB&vW+TbrxdblRQ!PBq zdkjRy<2g5;!u7)31ns;K}ma{T|c1%gg1L%W6?`~mBb&U9jL1LYfw_9 z>%ToQRN+#nGBjgU^SdAt8@AKWI$=IdYhx}HAFp@onBl8h+4-U_uXm35&e6SEJw4eK z0ezPTYP#e8a@!YH{}%Uh^NF&rqI~C@mJBlEW!7#fO!nZVp#DsM=w1mmb9Nbiv!S`- zjqku^ofGHf`0J2hwp}iW`Qu_y;oQ8E?3xuc(Rbs%^g3d2{zADbBnncQ)q=~K#g_5V zL68Mzxx@h%(TJe|JV{yVK6wahUWKO6%Sne(Na|%F&~(XnbnZ8SCDlB4^mMmJ>f)B$ zU5}#zx<1v2u<`y#`Fk0<7d;J5>ICc(UKKfSi!YMMfq}v(!X7-onx(gK5!}^Ru zP`avL%ars~8}t_)YpDol2Bs@hHc2jO)#Mm-a3E%5AbHUMHbmk8jz^X)i0Bs|o>95r zu)b#Yw!M1e&#?H-f#S&fClBUnIrfcbcZnU2E0h?Qg>qKCQPYBcOaU^dx z;PN6tplw4M?nd|V_m`FhlJogVNYKpF-+KZ+pzaVli0or7zuO^|cZXU$6zP^$mIh00 zGpU8zVKAW?!`?x%(*w^cnLf1Un?+d^n-DWNtLB@66Ly)xYRU7;FSSzk_Bco^0g=La~d3u@`?Ev8~tj16fAL}KxNs`#VPj4xef)m8v~bzO{lq0V7^SlQ_x^JvagZ4CVFCd+3l7G$Ddp2vfY<3y=)3-JE@zPvXU>Z3@;6*!v)% z>1!8ljs3HfNx~qe=4LhyQ_R#&%8=&hb`8hCJ0;gF7Lzi@dCVuIcis=pETkrO=jh3X zO+3Kd8S5;v)7>ww?O1dyUt4NwGG^`D_x`|PPO#uR`Cgpnfj+oeb6no>W9L&|)vRD0 zYS#M_a!-BH==lYQ%DrR!ZI%tM0})=KWgETzLM{(^21gWX-m4+l$4hVJI4 zySJkvS+7|ZAdpdta{4U*3tljqLw?Fuc;}>0d$fEz&=IKXr*m-+fB9w&P%&{lN)R2Z zkWZ{--I1T<2r+Fq7BNWl$LDjnW9AdkSCmdtM7@-@Fj`c}FF9yD+W&GkeVw@X(3&=0 z?&)N9nAXHzSgpMijZP7*>Ym&~OyY@31P<;_CY_?D%31b7du5x$A3cR{AM6rci6q&e zrse*ei{{}Jo`1sVnmcC^R!dS2hE&gYVZ0jUO30_qZ9cBye6%hFZq=7 zwCgf+Zf5ahScp{kMMZmh3x1=QzK&Y{?JEvR7++u#oZ^Y?UUtD@<(08FB|T+3{h|L8 zicQAVY?t06{+GbFj?W~yVDqHS;Ns#-b0ThCGI1*qRyP;QCBjaf zgtQN5wVq{Lth`HB{QfvA@ayy1k^ss=?obZ3_2=gJMfCg*ZLu_zOUoBcEslr2gwD%m zu!K)Agib5V2R}fMSuAiHWVWu!iw-L{rKg^7OgOSh+NTAHseWnM$Q9apgzf=wOz`=X8*#2U^w4k9G+zJlKBow;|fX1bi)3*jk{CIk40< z!NN8h0q!|>BzJ}0AU?xwKHRxrm(?RC?(xh?ku@{Qwo$&nMaxH;dl`|`7BV>rZ^tL7 z#O-vG$Q-MQWL-rd=!i<-UD_{y1}&Hrq@of@CKEYCnle;NnN?@??#^~oM#SWPiFnqW z7v9sm*{3f_adS8;2{p}&I0ZvY70%%`17d<0-~HUnEHXdGD=9ZfNhH|_SiIKA<{wnq zKCT6BWZxw#a9T;k6W6#%q*GJ(kIi-L%epvTUiu{B0c@y5BQ7wj9|+YTPN1rJqr@r~8L&Iy zqGjr@JD0QY!BluNJo}~kToV5k*`?>=7mO=@`O%Hc+Di{ehSDb7%&~RQgYEX#eBDZx z?_gTk>D$24_L#tp%a5ePo8y^L)MlZVerrC~Y_sz8xMM2VGO+@6P3oW{=*-4T)Dkt??-r@7k+g>4D$Rzo(+dLo zn=%5H>lt{KOChakp85||ejeT`w%*L94I6%*^RwU-dq9ad_samOd-=SHv46d$X54hb z{7ZZc=hvc-Q_b@}aV+w9hvSLuN9afYgRQTO%Bt(ywFqetq)|#ly1N7k38e(2OOWmk z0V!!vQcAi*NeO8XDQToZI;0!UynUYc{mysBxqmpsF%b6NYp*ruRr7&b5@W;m$2*7f zZ_sXC)4#~~Ir4$%;rzWZy>DXoQf^3Xy1BaMVg1=(y{S9cE*W#Zr4{zbiFxy%V=L^& zZr-t5-3|-LD8V?m{>X!Pv+i-OY38@SQF@LBF=Dt`cBJvF>GhjW!2vwXDMaaM^29VK zxfz@Q=y*zr0kQf;hPT%};f=2y86o3x5y>0|Gn%;p+HFr^ZJ zffY0Tg5TO2f?W5OkTx_c?(W|>G@jMV1h4@Kvc5wtF(xCfFDteTIV`1iRAWlAOAJO7 zRb3aP*x=!s!Z!HE&v}iKrV{z=5a&jq35;!tK(pK-+8oY#cJH97+3Vh39tQEg8#hoe zPT%V4J|J5}o;}m~4yc=NPrZQ0ju>&-Vp<`wiu{_Z@qp@)A<3?RlvWhgll?@|a12+> zY<(7C7jbmAuwoTK~SkKD~%Jwn!MOp&fyHypIXRGK+l3nm577l3&Bjx?fOK zg^uaP<1srgOT0BYt^cAKU7sf)x{~Hgv5xFi9dbs&==7-g<=n~d#ju!Y4pjv{p0$s~ z0W&MQQr(dU;xt}`$96jfA<_IYX7vxw|4e*@X|9=a2};Gfjm0|lbNVEQAkLb8U2=On zwa(b9-~>;=%YtC{flRVQNm&G%d%>wU{nnSv7<_AknefI)l@c9ogoGBNepS7(-P7%V zOstPi&2=iuij|ZN7+T!d;6KHGEbxdxswTimH{9(W4OL&w5vn_tKhI65Rsr7%D=L)P}DPvxkn3Yj@59EkS_wL5YJ1-?NQx>(% zul!08a8@8EJ03Sl&BJ2ZJ5X;vi`VLcH|aN|3UM<53Zd5e_+K9`Oi98;d76W)9`*=8J0&&fPM?ppz>ZL^9Pg*sv?Hp(Ma`L z1>#LQsIFy(%vAiYJ^F^k0+)Zp-iA?|<496ZKA8;&v$!d&j=K_0A@mX%lO(g?@{hW$ zwkE%{@aYQm$;Hvk@WDXQ>Pnc3hgb_C*T$_U#~%UZu5YigQAu>|U}|WMZ!FSW`@)vu z?3eZHIu;JAr@~_;3kNnnhl5BXnUp8~W!2B5*6MOU|Ckoi#A}nu_n>sJZ9uo)&V2Xl#cM*TgXrQ0h_5Y`=x92A~%Q@@2?lcb5LnRk7GmuVp!x^E#lW zlKNJ9I;L;CKEmW!`kq0*-&_E>UJ+#}u}J%CB^j@cD5O?q7gVx6o(D~ehM>(@a(WD! zK(3{~rMc{{;iw*ul~;BjA=EtAO6PbrCpB|Zw^7!2QiE1wt}b6v0v|7Rrm|ZKc%zA8 z&msKl@sF-G%>a(M&!rV-%UaWPF6t;QEmm^kg|)#T(H}Awgg}+Huzk!S6n5zO2qjWI zV%kqn6`LgQ=fn7^t~b|j4$Yu9maz5Q^3&ANxVeQRO40vE?Y$IYo3zTkL^p0LXAYPNLrGJ zu3H0j`Wy6i(fp2P2xze(_V=%sKdr z*OzBkHXg_)=B8KSwi~$ENU;Z~+d7Q7Z?M&$Nw(IWPb}!t(*mLmm?Sei&Z}cuwIsX1jNEsmd)LBh&IThfflAm?<<-i0F zcl^c-8{4xH2z_#Fb0pLDR%s|XtH5MXY?AedWNS z7u)TkxR%$=*p)zj(GdgdX!-S@r_#qGYG~e58oQq3a%w`@zLSOIcV(AUZvXBanic56 zy+(~H%vqC;-$l{DT+{j1iiONl8#v+N9&=_$(D(y&_Xhydq@Wha2-hhm3@AFC3%obf zuX^l$pVR5VxzJ8kYhMfDZ4)eOH{i;{ zfmK4R*38_^15bjU;~(9@?WcUFp!h@IhtEB^ZDpy=-t@=oQ0!9#@8@}(5rfyrGeSJd zkz%ezh(1Cr&JV*S$4ilx{5o}if9f`jarjT}IQ$r${+ z@PcAuI3OAk5P(6&6HEN7y|SE>DV%{7+YMLxWg;EUppSaKA*cYI$OAY{^rfrX3@nA# zc#lVL(XlqTOY{|f|7rFj@bGRAGF-_#Ez!d|+1$9@)t{Ew0IZQQ%eHXjdXiJu#*5@k z!}0I6kL(uOF%RmosMqxKYal0X4az(BNwC-tpFpvPl%y*ph~D7$(y&37Dl-j^x>U~8 z48rXK-iSWJA4nbmN$O2CB2%xl^>JGH`6-lX8*FmFSr6bOAsM*>fMv~V=g3~wG)2Do}&#Xwfl3ce{jUXeIj&ko?7A%gadLzUmR6;Lg(hIwc&&DQd*HRvn zloL0xgiAOcL=u+TzQcY=R^(6p)nXVFAPKDczKM76rJN}BLZne8L5oEPv!J5jS6|Ox zAi7?R`-kN6^33|+$!+o9208|Qs|R7}UwWJs7-5ts2>FWwl6!$(D?Y`p4;#IsBL#ws zVO4M4;!~w|YYG;6yzIz=h2p1^>bQ5ZNzD|B=t-Yhy%)^8xa_62JQFZH28FPFfgkE0 zV@PQaa0|01rhL%wmRhcgXT$Sssc64%Oqb%~NIHMNm@2Fh^CNW|@s@Tyowz+Vrt?_H zC|USqYZJ1Ir-tFVC#xF!W&I~*(A#;eIj+6C?n|wAIUjjL)3D{XH{oDdRw>yBv(1J- z=QyyZ3(S{50okBtIbEmGvmLx0#Tz|Cz_wCB?l+z5Cstw%%n~_0Jq?lN8gwX_s1JL@ zWd~_955gOmDwDeS1si!;=^0CVg8XWBoI6nO0_giev9UNdeO*numgG0BLOIQ8qJ%^f zLQS@HPkCb69+GOsWJI@qp`ATveVod1Ka?v~^1I&Ol`$%4 z(Pm7&!u42h<5#P&1uT0_>znEk+x?QA7HI4JH28R&m>OtJo7$}TRI#P;Jk}{-wi64J z2zpN9?TnBO674HhySVkcFV1TdERHZGXpCSTZZC1D{@W6^Dd;-;Vt5FJ~-{KC~7-0FUS&wBNr-W z1Qbsoi;>mZKPJr{XSL}OCH`t#*cw9c%u2qR_Vz-+mGo+9E_>d)bK50s`slJCG7=AI zHKrCUGY>Y9AtX%jh53 zGCQWbW{(A}vB0?ZTl!kpf#DE7vYoaeydO-ye~a}xw4ugYBa+Z`pmQDgPt+2N_v&ydjAawV_s$_w18CsA<)J*iUYMU?~UXo>mcWgZE*9d)` z(ywn`tDX;9`KK54se-PbtStq|Ff1)N49*64Z4Qnr7?eznyk%ZKtfKLp;Zweb8)Z`6 z;0j+HC|r_?h^zSm(h*D2gMpG!sQr~&Z=X+d?!vM^P0UOrmqSn5_-*FW4z8~@wJ8^~ zCYsxTW5|~BU>ZThxQ92Aq-1LzlURu@xnXKh#V?{iMBg0H7^oN9Jk#dd&adT{GRI0b zi1G?pjFqyIn~HdzI#f*gdv?bMbbrD11^oeNFy`jF#8{So7jf$Oq1mzYnKR4Wxkawy z1ga)>gDx=*j@-ndJv5<3J7Y@BaSMxYwQDxYOE{gB`zJ8cMkUV5wBh1VlWT@C?dI5Y zvCJ)-mA71}QUrT70mej2a3tkFhjfcl@wRagNMtNcPJz2frQp>JtJ2Y7!r5WVv8+XW1H#vk2@z8DBS1 zqLRHm&ZC!FjO<_YtUoW*H8702jN0$@SO`lD%!|FOBGoX>)Dm!#w|n1BdEpdrx&19l zWh}`gx6bSE<;xx`SVa?rho4CA?U@@ETR4csw|M*{y2L@`fRG+2(+%%(u4s($K|y}HWRT!E>^4Op@uL6h!TyUp{+j%alNk#74@@?< zu+1IqbU_^upzz3oPID0Cx&-I?CZ8FakA!*$NVPx>He{+WhV`WbrpabO0?wnA_L;ks z0eL@ee(mmAv8K@;F2$?@sr2?#0VtQghwVPeT4S$xt*MQPbyiRsaTjGnkMs&8A0y_E z1CJiwsvo;rVT|S1?ZKw$aHsJ#vnL|&NA<(Z7AqMb4lUOIIDxmH=zIs{+czi}BpEo3 z`yRfY^XUlp+<_KknBW&t*c~F7+rT7#j{S;M|M^8|46q0*vX>L1+YF?m$ks~sv3|mh zU6`qwp!7Lylu~O-i)(I+@tgkN!moZD>$9D8rPs48KeO$aHTt^`TKXd2avO1Qe+MlU z#YRhys(#AtTLw@)W24#>HEjn*-kGy;i4S~3^mrtem6>xTw#|mLcarVR$*Z!PIQIPp zfoVcZy~zxKKfVY0SsKbvN3QBklPcM);JJ?i!`sRxGC8zA_x-YK@7ry!3du|h)HL8b zF+KefnaY2j$%53Z)x)cVmrlhmO@3XV7SbTISTq7fNB2?f$avqd>;mW=4f4j-d}9vM zp7-JfSTYkwgWvz$iQ@RNbzy#FEWJg!dzyElUt;^G4dxzX0-s#F*2i0Y|4~4l9{maz zw|b%DZX()du8PCaFE?FKnYM!p`j#AO;-9HzhZJseM=7=&Q}tKB7<9(Zm;F%wT@;mW z2WDJF=-IAK&dTBl?KeIjQPyp8uHtua)_|r+ExA73(m8=$@^;I|MwcGV#O$=AU4Qn~ zh#6Y@3=%w{N^?iSJ5lB?pzF5U=415UCt>`s_x8LY^a1WhU(0eIlp88^MNFj;xbi|P zM6{!RkhaQZm_I;^GcoZUH5&#}igR(LWzpZBqFw1p7Wrx+&>*LawiWk5Gs}MA@-*6> zZH22XZ8XExtpDrCS^3bF+2{S-7~KcXj{p$wU)9V!ds_G9cjp($CVtPUU^>_mM0o>P zG4?hMu=*lrk05FIRs3>mTVFGBazz^9lnrWh%MJ48>ImQ$1P-ht$lnk>LQ1}O*t_YI z?kM26hQEeuDOF4n6;j3W{e!!jLz^&ms>u7fMvS=eqF1sV<>Zd4t;-D&MjNS$iTLJt zOUc2v=V>B8=Gi@Mn-s$y`-VkKjnOg?e*DRp#iOh_oJ~0#b(3vo5M*p1TEFY0_0YTL zLRRV3Gx`h`-d98^bk3=r(@5^WHw&tEmxf7e9Oq)|T=pOLTtDAB5O92Ve|o6pisE~W z`?JL^rmND^jHY`sQ;LqmC;h;5J|TB7px`Eh3ZpYN>&aucxf1Qt5@hYKc;Sq6d>J0)`s1cHtO|W8>!Bv_7)kb<->Pjt z_g->TgBxCsi0$qvIfF^a+P8@-gUc*KDQjV3cXsw=nNdg0pwiB-sOWMzMVa`7nS$Vl z)tc^DGGAaKS<_+-9<`f;b_Ld%MHvhBS&7%_D&6Y|&QiW+yt*p=dxW*FWg;;Emg9dr zzXbh}V#bs|G8=ie-nU$r<7t1&BHR8b+AX|&og<+%1tz50_FDb=h7UlE<$CejVFge1*<*7LRN2c?sw^6rskzu?n{(NLlJmEEgcaul~YEOaYTtoYE zSDhEFR%qbhWXgG_3kGauBl=`h7;$M<9ak#Y*N#&g-!U>$W7yJ+>Hz2U(!rl*t*1m= zw|s=s#L1)v$8WZ1z)g5@dW3!Ie@o07Byz)KkB;puEt{|?$z;M)Ly+vX^gG0)D;1_6 zF}Oh&ZC>b7M&lN`vW9+-d11e&n`i!vc`?G;Vfxd}(V_i`!QaO$KICbYL4fJ@{pN^ZF1jwn2yjCp98I%Z;yr&8OZsQpt37^f8%~McTMI)RSC7=pz}GQ z`3dOwGo@uThA!>3G07$Gee)99_{Eh>I*Awh;tdYYSsgMKS#H7NQ@}BcCCggAyoxtq zr9s`=@mR1&9el#5RsFo@gLRm|t$OMQ2eAr5N!=S=A;#(@!L=lvD~Cc~wk1mcR7lpp zW4G?P<=K^ba&bOiFN#p|`BxqD>0zKu<(Y6arrsOljAedl8-eX6F7okhXV~zS*`4rb zkw`**fjX!zWfGVl4rz{+u2Fj8 zmOc=yax^AlKLfuuB0#4iEe2O=`Pb)b;mx0K*&E;QY(4+XdrGRE59zpy0=I$Z%XX?< z?23_6%9hIue;^g;W=gsJ8KrNrGm#pPMMf|>p2v9QbN7m?mh=$&7LMiP4845$Mwj!!7AROogiGD6>gMm{ZI zIiC6^s;tzWoElR{Wu8tYD%vS<3&H1*S0EvAnR4kauhZzpB=l%>h~QV+IMSK3 zt?1oD6a5Ao^Uw24V z_{hx%)^TVjgZT$r7-IOoS{Cu~eckBrTExIIEx;L@x}l6*f2iNTPIjC$D;vk>q4-$^ zyX07AL3W1R(|Gryi~aW{en>Zu@J#1ew_y>pYr*1&Q5N5OgM`#CFoIKQ8s2X!>3sjf zKwa}_G5UzTj_$TH&3oS43oGV);kf(r+h2^jqTfUwLB0TnYj9BK>(FhkrMcX{+J)?X zU!B6f4-9c6T$JvI8)lq2{a8P^_6u}0=fRtC6p=DOKt?)}xlgT%B@oT#%MtvDwAbHKxggBar3v69D$i2IZe{Ro*7bRE|x z3S?7b*YGJz%TylqOAHG?RPNl~&ggw~OuVw+=J?L|SbDg>D`b6^yM2?=@>FGQNO>pu zjo{Cy5a+DXkM&AbMz2;is@@bMoADTbogs8{IIUF+ETBcTE3@_GW9gxsmiF0+8 zCl;6^f~oalCHD6VTO)aw3IRe0c-j7^cj>wJ1^Yb3XTavvcR;&ako*9K3%&;zK|aVh zqBw|V$a@f*J$NYO#(FC%!$SNN*{Db)-!$8dLR?U(xjXNF?4rl147;ZTceH6g*V?>xA*ZS|!>^F7rwQ+>ezr(*E+okNHU`|F=H zTo_e3P5s{wAEoRpys^2<8pjggg6#0;)N(j)4|yA>s-YEw(CjAfh>L%H-zm^;8AG7yiU zRb%(0$3LhhtmTvYZ<1(6eX1IFR*Nb+s=nRBVFp*5`H!3oiZASPWO54h{Ysrd6kwKW z1%_l_e~_FABG(r)WU^B1u|cAi1_DrmlDUHSY0lS{=ie`z3O#W~s3y5$BWF$GzsJ)S z@gGdPswb1+oF?jy4uZHPg2Q9yI-kc*aUr>ueDs5$zg3I?G&Tr(0yH-KaYbL*0xXIl z%_CQw`zymg7fTxZ%Z=YW`D-!7{>!z=u$43((8|DqV{u9;jRAETe5l@Kr5(X6>u72z ztQzRv95%)j5oa&_%C?4Wv22baQOi75-Fr#S4j+O(<)d`;$$Y8WUR+0(cck?IQym>C zj}->0dm!Mrqoo<6ThsLn2y6FE6s%6D<1&HR0q1AUoV_e&5m_`iQVLjkoG&+O zso0$lTs*O+YG;s%y%Gu+C_Hx`n%A>*gAF57D)}6282!{aP^(=P$Vc-TKTepe`BGfV zV%Yf#quZi)D$s%(RO!!LnqMwh_oVUgn)?(pU{8@TC@_Zjz_b0F`Sin6a(eHLF}4a0 z|Dd3URJS~wIZ4yU|Eh9hT>BC67+iGQ5S1~sVgi4Tm^T*#>J?4zidN%2EAh>V3-^hT zb&7CI$1;oT=&mYFi+h(N*SXECV6zU!jsPUi5**LhKlq~WL%*vr@hrqI6fy~DVNB!) zV7_F5aXBFA`)sxP!0{c#zbOb^1oH9(XmAJUaNn3llqKESVm8vnIt}Rx_1_5$J}ipLrU98=DLZEx5N=6wl!@WOxkkr*381egZfCD_N zid|qv`@PhA6OX|SgZSLmQ`?d3Z9QnoU%>DQ8+eHB-+XAtc%Bq@)nyP4BDuJ_cEOcF zKmn7|=U4KoM=FxiA*{|L?`+rVt~V92F>)*oavg~!JU;y>Vi-Q%4{CdD%z@C<*KgbZ zggF0^bn?0WMdzbE0jtwI17!vp`%d|SEsoj3##!-uFp*1kMX zPqW@K0?+HR&1iZO)Kswn4o(l8DOBHp&+q*}wfVG$F+zMwfi5sMz@=Jgp;4h-1bs~9@hfJ97-bV)JFn4C`#W}*-z2Q+(S8?{HuJ-ErQq_ry5}nhuFwWb0h(!1R zZaY~B?NJRA=lRM!$OO*i-VD2kn(dJexXl2rBm@zwlRRp4QAq<;N_ z{5`!}6-%Q$nLRjeYFnYVLsTR=t$W_yuUZEEx|QB;?Lzs*F(&X$E|KmhONPU%nv~uz zE2gK$*^M~DfN|xK|6ACk)zKZaAq=`e%-W*y6nzvU2L^`1 zhinrzQKb?cA+EQ3fU|rAx5YfxRHjWfBlzWPU7a?wi}9jzzMdVixq4m1Vq8@FaI(yu zU&KMz`5r=z@{TxW9h{51$KqVTrpTqmaYzZzSo0lW1pi(SRdpNA4^)R9eV3(|I+h1n zqHP>rg?&hm^+M0S{pn7}TnJT|$HF|n`N}UVb>VfjRO;mP|MwK)e`hH6?C4(mSS)3d ztq~!&!K5~1iqd$UAH(J0Yp3^vUHLa*>ue!XJ@eE6=`ZhH^i6br%>5=WyF_I&>7IW+zwd3?hTvk%_+1eDcV=$0cz53CeMB`F-CywOFO4y!Y%0zT0qZ)^G%^Nd@R~Ae*Q#Jj`9=~p-Wd-dukW2J7U%JE zRVzW17x0Oqdm4G)=cADO3z!O(&d?h}rEf4kZC=_MLM&@#HA7dDDmZ8!)Hx_v?MsdH%zpk6LYE)VzaGH;VLRAr8R>B2Jl}C#`DME`1Dxdz$3S6(LfYYxtO4iwU zbJi@HQ_KSF7YZ}DvRF@(zSm@?sP%8DIpa@6_JE83#rmXY=MwxS|HKaAAYpp>rC$}{ zF8}+sHF*f@fS^JGpH@97Wc2Tbsg(ZMf9T6|Ad*H1mb(-9i_S+jWuw$eez(U??XERZ zg9KEtEv8%8&iqKME0VFsVryF0asS1$QkrYmDo{81+U+Zwz@9~;@KIft3gNn6 zjD?-`f&<+RITc32HK1Se(jnYv&Eu0-LBzLeQ0EFU$3w$)3L$;s25hK$?LCaz_9rdhREsEST;OV@}&cREnPn{k0r;ASi7))j&L5_=31MJO<IPs$YGD+a~e;j_XS`sYwtntd{T&lS z?f!c<$UG`=$6jn_`8E8!cU#NBJvvBYTF~`D)e%MPRpljZut96Ih#PjSQ`VHXHwUik zgRNn@oKwpyf)k_3yPotOp{}lXIzpJx-H`5;y8?KfKjUHdqFYO`0QEa*yRxKiYmldmH3gPX_$-nj4;9jR zV;?`QV>eM2=Q}Gr6Q@YIl=7I_71g3r+gTd7haeRR5AJjNzN`A;05f48vuKqcAD-#@ z1$7=s>^=Ezz|dI09Im6m4W#a)Ntun;rDxtBX`-8Tont+8x%XHCTFR5Jq(AR?OV8gb z``z@jvX;b2$YeW;e*IZzs_t;~Q>4LvT#>6~PbXA*vwU@&11XaRrubj~%+#BzLv;zk zr~edSq4U+L2+Rlc%GtRyxZ)}q?tJA4lbceG0@IA=QL@M3xCug-^ls@#0yTJ1qal#@ zDM$z$hPidUPO{`+-Z|t+WHa>6+0RI^AND=`tl1MAZY;0{YE1@6cM8`6GXuCmav3h6 z2Ws-4A~f=-+4*U1&eFA~PXVsgI5Xv^(I#cWfv%f#6$gCYFp4V@`XX7FH19y0`+-62 zDWb5W^@a#8C77t}DKj*KRwBDsOK(2fbfI}R{ya_eI-l+Q+XnoPCu-z_XDvRQl#o8v z!m|QCghl2pty=17^!lusVz1~73oLB{zP)AQg#EcpJx8@aFwjgICi56UAp#-8eA*Q{ z&hMFWDy1vvhmD*Yr<5K@5yQXH9aZSJARk;f{?~@v0|{iqhja}`cbQ(Qs0npLF`os* zqaE;D^y;N)#V<>~CV~RClP=ZcQ^Otm_l!rSJBx~|_49Omo-I-aV78XoTaJ|AU-6DPS>)F71P@-AY0b%v-e@< zsD`Cw<{mQ(MSVX(H^3}I%M#=czJAY2_d1ovUN(ApI`#*zjs`>55*!z&7Wr!oZ~vt) zP8EE;W~*-4?TE27ipjLHiB}XNEF~eaMWgVEmwoXMj!c43R&mhBwn2>jMU2Zt#(Rie(kT8*1gx?n}uN%^NzzR|skjQG05$wZsp|1yptznzq z_y!-<*_z>BI(sJc%ZwC0JP(({q+r+MT}JZ$7}KIm@^sE(L||z02_okKW~1lZ^T@_B z)~;cTa~n=igSc0^-tE9)*i#iGg`14L?uUgm&nRm8lId>MbG-Ty2~OhgV49TqXkfJ*_mjR^E0D-;-| zkj$}w;@TJ_d`-SO88M?j)ovHIoDp0~&K8S-jnXw-BW9 zwRgQ(3>Iwkl1*M}2I5fIp_A@gC6}*R$+^hMPe`=wfN)hxpey;Yh1(U5pu!0T=DOQ5wd@9uv}f~IDd8>vvTU%+-=Vs+|k zRq^S)HY-+azpyl78yj>iyRz1iw9%gzlq+1`azvK*VaU%ZI2l~u84JY*A3d99U)`e7 zwgsDS7ZB-S)@G@}+YVVa-i*3ge*BH1#_cG)_%sBUuCg_VPz`Qkfr4SH_-M&$wX?)q zjGL5OnvK7E_Ts#9SQe*}c-*o?N;dd@$9&THS!#N_>pi1?F0`E%I%hF@nbz_La6B^KulVg0pWBKE={-{Mc%yfr(ye?1;7k_^ooAxyLo$R}ICyfgnXh^h+R7=z@yU zu`RWtwqT6^bwS}u{o|LtX7s=L{jEDnE7C?&tkkJnkroP2d^N~s4YVqU4$NhP%+34J zmqy#RuVqKP286~AWGZhQVQ;=nnRKNR-^2KTo#=VLC)?jTkpwb}{u`sFD&%sgQat&U z;cEKprnlQs<@rLDR)c-FwZJKSEQ8ZkM$no813i}V-F zbZR*X7i(pP2G4k-+`)4CSJCj6ZiS2Ab&w{EZhB@!jgkev7W$9kozWacZFE>vGG{v~ z5A&Zij)qS^BYRLa`UgVNZ6F*YzaXmnj_)++>hr%HBD98#8tjnBa03t-!h&D?F>sR* zF)|?8>x5Iwp-mUK3S+<-pcwQYq~*6O|HYlkQlHO(-KvI-7AgIEyFSiVKeZ-Csq zkR!Q@5GR|Y;?J#m$(&+7hxNqi5v6|f)A-O6|CxICj|8Q&rCUsMec8Mc47F<2%f zl-7rw!M~d~vTN5^3jagoYt^2pGykRXTSv^#5e835M!tvU$f_}JI%49Af4iBn_;$$} zI*jo;m_b}&%WgHvdopu%nNtwecLxMkj&F;#+`l%kE$$&ALU>9!Y7G0&K$7|$I_ROv zj%+9cx>`uFjm5qq*_jQ}2gk668!;uQmU~1#F=)Si(y6-V>dAyu|K|SCOBl8`k%&^i z)IybnTmlhZ;$Op?5O-zohu<`u@VU_4)e!zri|A`Q6FwSV)?1oS$lCO+jNZC%I3+3e z|G#cbfaL)~>1o*yHX1Rtt~+G>4$|_0`}?cPj&Jyc_q3ly%^gATqtxz_8&tEFN zwCHX%R|BDnuRE6zu2;w}qJ>`k(YNr`$1RyIkNZP<+h8ZprDlK}jlzP;)rpFNiC~`$ z>Etfht*oYMy8yrQ^`C{k%Cyf{$j)w1W_T)umXpKNWX=8(ns`d2!W6uHr{Iw%h=%G7zJ3J&QXHtGxw11%Mk8lB6ZsZ*IC(8xjHPzN`+TQE zZ;z1r;YVol1YQ1!stLwbq&WlH`4fWq-key_JdS2%}v*wpR4O;^5guYj6Fbr2fHjg1J3~I;ri(WEjsRAY`q?1YNeDR67-Kye&48hY@G7GO11*UgEoqi~c&0W|Nil zZ0KWs3eaA;+8#bFgpR<1HL*0b8v0G#S^C}PQHSaZl7_7^0Te1yU-}@5smm&-fR`hX znIo&yh;>sLD4YMf;q*O+`G8xaY@Qg| z=(P@*mDBhBw#SM_-yULBn2)|7PeJ{OlS|ysHxBkTWOFMtWf6Um``JCGu%J|>&AzFa z{Hi>0ww~h$=akwqHR&OtKIuL3r4^bEX}bVeHpp*>fqqaO)WpSAY+catEDyomr80GN z=oA1e-?-OC0ERV%U}wF@o~>vO%zk_J=04%|hrU|&D}SCyv5eH5)zz^=2reQ63lTE{ zCqPcYqA5tWTV6tZ;Na*TKq44hi#4IpN&vXa-$K-cWo>1itJsiYmt>T!zR30>@`ipP z$JXFayq^~dh#)!~90>b@&l4IlR!snV>9wj$(ME7G6IvRmLJQyO^{gDyjyi**fM6D8 zH1=tN7wsTXl!%IAkXsMcWT7_d_OEuAWc^}OhaH148~b>Ej0oZk#|qPd$MsghK@SaF zf9PCjFtm3;GF7yIx0Cj5v;*_)!-Dk$b}JLhGNYF16Ekga`8u|-7j_&-%B>YK-`hWt z_u9dtSgS#&Ufg_6TSb=g^SK)N0^}_GH1E~PgQSK1LejeK{HgbwUb@TxnddX7lx_<> z0@UM#4+VqhK7=2{fKzGp5#LRKxkS@oK)I$TJ>;gVl6`mR{q9~lHPMF3M4INrR$1~Up0^JY9ebOqG`(B+YJ>MIVLuFHMcY799 zV6WFHkRyep?TBHhGflH&*zJKX&W#P{9fCBC5%>_zn0IG2|E%1k^VKsLri#M#B(uG5U zp!Ws07Ug!gnzgFB`Ri3K_Y#D^$Ze>Lg#bNsu<8%Mu&26~(Ld<#eD~F90>g~qR)3%07L(KNuNp|=R7#XZ3`n+^Y;M*>ah8S;oH_~A$}2D3gtz& zv%?}zt4Vc7E$_V^9<%UYrH?sK13ZLbXIq=}0+*-Gf=hfv70?0Kr&`;+u-y^UaqAxp zIEIh%>c&V&^!~PWKd2(t&0ZSj(tVC?UPS`2=#z=Rs-3>J%_Wh3$)yD1rax}7?|`tO ziQlzlV!6u8)N$t`>+`WyX@kW*O-)^aesBtv&qmmTQ>aWYxnb)OVh3TdM|BCrB+YJ^ zRD^8hb+QqDH$I1dK~n!V7)h^s4S6ikm$~x~YrqeAK=*5P-*)2jm2Q_H22wa}zO2wK zw4P~jlONOXG;u&OWL^R~L*VzDJz&#hepOm#0kv%ArT6yBToi|i!a-u|pJ5MqJVyj?Li`m9*f@kQahuzWlylN~Po2 z!h{JwvUzX>mZIP#0<*R0`JE?KbpJ(i8%blJ(YSTLV z&gI#@p9UQstz;-s?Ng|(O6&n6_~(t0s`fmqM606^_Q-v#;UL5x&1SR(#?7I=8t3g4 z9dX<_P)kQ5wzua_=f^v>YrK$SseBY-rGM+Q{?w=?S`*t6o@5I$e6PQN66D|-0o!SZ z$iGT#ZM;r}mKuM1{%N66aOQ@4SEe9ggl2htoQgq?bYZIHFNwV~(b9`MP22e)8EUa% zyN@g1nPaN*nYZx{%Y=v?fm#Mq#Fhpw_QsS>9Eb1ytg-dh#=LN{>0jnSP~&E<6{>MO z8_6tfb!fTQh)XGw>#JvU>j*m!3a;|@juVL3-5>{zy>PTu?`XjcMP`>Ok4 z4VwG2K2xd$W!n8l-x%^57c~-(3Yje-*Q@}0=8sG@I^tXNAXicXPt*xetB~$SU%N&D z#XT)_kFhY7T|xM4g98CKK0$2$h@OO;{`EF)#<7w&aO8Y$`?=6{_j%sy8WYL*Va27% zAG?{0(7#=?pZj7luGB*x1MNEknuKRiPUuuN{P)n^JnpQ-jjbxp z?~4yJ;QJOESTRig8zfkL)qtT{q}!;oHd4d@>7wspKJQw-iN?Qqf|l3>jOx!3A%#8Q zIb1};<%%CChI}DVC+#e+=WO$LEhUOF!`-A1|%FgQfyaktX+xx5wVU-ph!{TXgYoP)2 zjldcwDMmh`d0(t)giS4qqJWBK5fL_XT5epM_9|c0=SEYpAtU4u4UXa=x{T77>gu)k zKJr}Dpw1V<$)^;#Zg6|su$(ZQ`1Mq61<4~*fGA*{)7O#LyG%W|`OiE1>5nK1%MGp{ zJt2NBA3bNU)jotA2WLL#t&jYAE3m}fF!@?QhXkoa+V741i)QP1UbZND|tr z&+5Ga;xGRs-InzY2PC!opzyAsqI7#7&jseo_yF7NCuWU`vl|{iB$ccy=$y=7(Mr@% z(^smnR{j<1mqotJ$;Nek>u?2GqgAZ#sowNeZo?`JU5{_pe5Q_I)Q?i>OjSU*cjA`0 zoXt8zMDh33@4x4~3y7|23%@cvLkv41#$02FDAaAK`C~74uLWoz#(;X%EL#;aU;c$! z-bBJGsW)VbkeB}mIOJ%^9(oGztm6kNB^O_vIxAj>&&K~#3P396Cts$G(I%WqRDEh+ z+(IaNA@LqhJ~f99-;37i}lW;X%pDxWuSJ;GVBN< zzCqZyfH1v2S3LeC8AUCq&$PT!!3;^8Yx@W5Y07sIVNriS*ZE%$a0TZT_v^3!{+%@{ zfpNb_QI0M2YXCd@#$e>t@^Y#73 zwoVV+F4R`G57%^J;5Yth4sx2pYBdr3_`uOvEN$x9C(b2wY|T2R+`<<6B?V$f1$?)% z5g7|{RQG&enn!dvNH2jVTsGt`(>?_5r`OpUw$@PyIIP@+OA6ZXw|e66lLE}f;8)4wx1hf1%Y{K#=eYiY>l1n975#aC=m2E*aRmzV=Y)CQ z!o4kj&&6to47w6+N5a5G&`LZ4rDPpZB_F$9(E7>Va)JI2Hn%z8o)1VsCmCYea2UEi z>pa{xz|bw}N~!5jE|-F=E7dMTMSt#S(sg9aarG(SP1WkL$St7^*;CKl8+w{FmbIeE z!s-(*k|ntvzR$}RT~E$kS>Xzti-iC7US`H!8{)bAojzo7>IG9d*&{#EyDfBvmmm5A z+_6@@FpkHMm8@=kYrhC|ND6wBK?vcx`TXIy$4ZM$=Zw5cN3b@;`0Feod;k-nJaKV% zUw>zRJb4rqdcpC1xKl4~lWCpbL#Id9nPnf{wBv#48w!D>->XrZa z$sW>FX6#zK@8})?k*X*wa84fxDXFIkoMl7^D=mv0&-$^->&G&vF(+`D$2KflgF9#! zthTGNl`Yp-+BX3q&%9x358YHGtj+vUQOGoECfl8NG~!QX5vKkj_3R5l_L~;1`ko{n zHSGpy+PE!dsFLoFT{xOz2Hz0~&~!fhqDc}k6tt`}5Mt=iH*2GdbVa%p1p+&U_ zTPK-gZr~-ZD19s%mKw%7{N@c$xex&K!dK_^j-2u=x@(iszZgMJB&s*_A1{Jj{4? zH=ZSe5fSb9n%I3T{G3v;g*FhJ4%?e!_*k%zz4wV6Bnvoh7vnm79BC~`;qV=(%NHfL z-_9kMMc|FX&vS=-!-GW5duHP=r|$B)phlp0E7v(e2WC;NmTGZ0fReEI16zJlcmv6y zjjFWGz=8Es$S8ieBqWm6zRd)M>-A9%Uv-E52|G=59EycbEkTOOM#?YDb3t!d$w==V zS+AF^1Y@>{M2tY_>!-x@V0E=;0dsSvj;`>i3nl(DjR`Dv5B ziqPAQ*c2YkIC#l4$sUtdz*viybzw#5k~h1O1*#f4L{Tr9v}Z<;&aR33D(K2qeReDx z@<*f->-Wn-V&5bENC+N_@LuQILZ72=)*+KO;lCQ9Y$21}hMzf=FT{f-5ZpBiZA7{&eM=DqRH zh+4MQ18Q*Rv!39Uq496rVmxWESklF4LUhn6#odc-1yw)OpIRkMW%$N>_sC5+ z`0#s{ektM)vq0U$X-#O{P=w?XSyA41Z%TlrY^pWwq1+JfU$>|p?)S+g9|pSylUu?_CIn{AXEXaI@mb4Mz^j}KAZ*hV8b zPX5=f75+C&1oo6iaK^vbCWrrMc=($e&=E{nA^1^NR&i9ae1j<^9~W(PMis5rx{cymw6_83(sbhiU2l z=RdqaSr@XLphK~@1O@t|$_f2s73+AoBxI|Ckpf4 z??dEzm!hT4C~?OxNfcl7&?v0{xAUtfB)NL^!&}GnYI?&{8*cCuTJUoz=|``Ac^L0k z28J`UKx;_MaTtcH`Zq2(P7AZL2yyb?d>sK+1|Rhv?V(XjONMed!y);A0QY5*nA|_ z&S{^eXo2zi&c=+65#wRA!p)6aYcq|F{4O`+Hhqp59oAlw@=uerrdbaVHN%*ct<*t+f{gRx=;C1zrA-fK8!^@Gn6`}`MM zJvQt*c6C5Me@E1Kki7)s8YC2v1Q6g^=l>z>z2m8FGe*?Vul*IV76&-d{gkKg&@z90QjocFk{>-C%uhjNt9 zqx4_u^~HbT6a67}4-VK})R;wXuG|~oI4G8Go-#RQpfw3wXSSL`o{G_ubrBRw^`f~I zZD2!&xFTNOXFmwEQOdP*J>+kP;u;$V<|x*D#y2cWwB9BmCphXUSZYicYk+q832HA8 zkNc+(BF~1jVa{_m-HZDb^nF$TJ1hS*(`Hg8?zEz~_WHweZvyjZZ1aAgepG6w>dsV! z+^pE-QcYV+q9Hg$R6(H;NIwRi+z+53R4ua9Mu{tX-1kgZivJ0ZKH@}$@%Ew)ebgPf zeBxgW6EfGV?%pN^&u+0@2J9ZPnkV&Xs<;%alJE&h9*B-JFrJXo^V@kyJkVd-t_iHm zy?B97vyV|MNqZ6zpWS8O44W3(a}25=Gbkc}PJ<;j|3xPYzY9Z2CDg}p+KktB_xg)L zK(}UVaa!+9oh5<{o-LtY;&ZTa-qsm(9DbOk%G~#~(=iD`@mwnR-mNS(bU4##?QR(p zhC*$LKZi2_U%OZv;AWA)iKy!;cP3ktxZv&V?6ofY|Iz@#^d2%lTA}OeS5S8>0b2O( zbvo^NdrHadqldXVpJa1IV00(>H$D>;;s)UgK{kvlU?_!Vy_`_|=}GCD1^I6!v$}Nx z1E85<1$eYW!&VTMx0ihBa(qTmK4jb!M~|cdfXx5y+nX=!yPY7_n&CW%CVth!nwHnw z={bUwg20%P2Kt?RSe^7Qhl6&hA2oTOs#*R zf#CWB>m$LX>6DOGg89%YCtGD?kgN|Ex_?cW$k&E5in-YEZX$4dQcz~Eo|&)r-BT|a zzoZ+;cN8GLC+{eEmm|Ut%(o(_m&;L8sBUM#6Yyy}s~wWw`+Z?KO_bMjsLgtM(*G4^ z1R>-T#2vY;eei83>gl19JyyhukpCmD_g9bJyqSga@^UF^Y(I(49<&ar>F1U!y0iRU zqN%^{*Rq5ZHe) zY)HvDyttfVc3w_|5pM-g^yU16;Xvfz1Q6p)w)6MplD><)C1=~;JfFYIr^|u5n&Q

dpyxc>AruTxTbFgSCCW;B))e2n8)Tg<+Ub7duV@7^-zpcI0KFh)`2a?9L6MTC} zfzCiao7LFU|Bf|dINWfyg=&nddcigP*`W*b6#>P z<=W-D7!DZi-K>uP5^}A>L;rnu_&x7j1SL0s73-Pw@vbf|A0UYbRFX7Vx)oTAEK$!% zZN~le_4k5eMgNddhB`QV!@p7ZTgR1w9oTP>DgL14Gvq_UHlF?Prw36Agx-r6Uqe`EU3s{#0f;jf~T4D16%R=L<)em4!*z$_tdTt5j=b^{#J zyUWU8Ve0A5#HV^Nd7Dcsr}XXesq&!*O#jZ}E`RZ>CpNhf;rPi!{bI0>gi_}3Kt

15Gtl*b8`5?(E2wsW{YeS29_s#k`Qc*Na)Bd7{d8hHXXYDr z5X|PyQ8WUL-h~2!f^33U=Db-eE@!-i73{UWW}fkX5z*I~Q_;Ei7#Oyy%6Ccr$P^qu z^o9T)sD66P|Dr219CHb5Gb=t_swd`6|M!Kv;Ee{&;=?_LApAXx2k}BSDcFZsyA*Q+ z@e9sT@J^eBu~)Ad?o#V~v%c+9E@VZBGYi}IYHi_9yg8K=qA9|U3-i(_?_+MXz zM^@&AibcKgG?adbK&>)HB<&V~2)NBbALD!cYQjq%zK85pgf)t3%1Juiu#e}m)6aox zL8PF|<{k#ORT%`3xQSeGkWf6p^@4B?DnIDWdOo(3xw%OC@~zYP5)h(`XpXKPoi3Dsd22N#qlL;0tV+h{$J2hL3A;l*5tl5*rT? z+Y4$Z#o$WNR0YT%XS*(qm$dN0@?u@V0+ijS`@jh~K%MISnO>{(DE3~dd}E8`7~^Ky zoPn4dr#A|Qyh2+o-blKqI_*zZv}URVb~&w{Yj+8^@BjJ#b55is)YalXeJaG8Z)vh7 ztQqN)krIf%ko3ES`ztaEWx7=$*}9qy>agB+a}Ps$gcoKTc}cQc<9MVrpQ-_TtR99m zKjv_aZ~DVfF(5=OX!-8{&U+A1Th?dxa%w#ZFlNinY2h#1wBB&25)+)Hq9fO-kBh9; z>r#AFa$~aNuLit+zobu#cj055S(D3i7PI9;qcX`iqn6vgW4qLF6;5wURD`P1_dN+B8@Z1` z0?bIk`ynh*oNCuq@_KGhF$3N=we*jh&PgjvEnJUyLnj(zh3l6LynBKvqhr5&J&})K zI-IK)2jSWY73OKUH?U+zLuo(*yz40bi+_)af6BK;IyJTmLBN-#^*QAn<;}Yw^ZJxy zcwSe?47%v~Oj^1~fwWIk+kn456JQ1v-?7Lc8NfnAhc+tqha5A#xk*73e6pJF#t*;j zMSRrceKTN~?V_@CR+|)kI9qH;6Q^M*fz4uXnG)@E|7HpyRMaG%jH*hKyut6UtaXvg zJ-`*P=Uy*;(cG8EGwe~_Do}pI(&Pm#t=+dn*xhk`6{{Aq)w5D)8Kvi{=)WOD)XUeu znIgukLlh<_-k@X*585|WxAsbG4eNL@c-?AAjTgPjR?)jb5qr)>33o*L z_3xd7y^mR*L+2<|XU*^+Nja-2zNp=5M|&alX})0|p;yCyS6SxT5QH78o0!FLJhJbm z^EIdCdFD;{xQ%)0j1Ja?6-GggDLBM^5)o|3hifK}G$TW*5o{{D`6@|BaQZhEZ*L^- zE@2QL1DyHN=Z+{c98WD>ZuwNcg1O82; z?qIyUcKu~-t@3laM#rX@knMu0@prJHTxYsmq!=Z^zE>YO!^L!;!&1`m1v5PRWna9ag$|>X(HR=wa!U@y%e<4}TB@4Atyl8WVn%<@aCfm@!7G`h=knCW z-^A+}H zwkONv{q=C|%og-nZ7PJ)5*cnSva&fAGEd;!?=k$US$b6o-mVF^`N5o}tv`&$5qJ?d zR2Z_tuCtO|c=B`a2G6CsSaKVKxobmT^y(+!yl~HlkaT}!-m|6gtX3@3y-SavvbWm1MxwZNuA^ZJK#yRi48KY^*G@;y$ z8x=-yDBC0OL&`Ha4PX>+$EY~~Xu7%Y($kCuq!xcd>W5)-_+%+j!m6;z6+X%Qc8(At z^>M32Zc=IywjsNUxYN4c=?|yByWxTS|8WtgUIor3-TNm!Q9NlRcb=J?S>S(tkmaHj zk#Xz&YtFuGjlit2;A)2ale%(vW$D)OXD&-N_#MYvhLFr1Q}X4Bg5|UFe3mE%G2FC_FOI(*td57W+gXrP3GL*B($KZ zP5-Fgj}zK$E`woCfQ(gD8pfSDbO0hdPnB$E?t^x1?X)m*yCJ~T9%$|xwI*tJlL3Xp zjyYp@uJ_|3HRG0dFEkw%0f%A&e$q5<30efEv+cB@R!4+${`!;qR^h9{jnH2Ah*_%R z+$FwK#%DvxtIaNGx@V9+oSf!QlIo={vFB+G8ublUvRh9H=_Q{$A!sxdI$EpZPg9{M z;gI)zeTy8c{|$qjO?(y?N{eg{zN0n{&ZT0anjWiO`Ko;t-7(SLdsVqo7^=>M5dbXZ ziv36o#~V#lzR26usb!*8>axws*4wdp;%lUlW-!juf++@^MjC{qY)n9ffEJ$s3eFc` z+W!k_jJUYCFo8Oj?cES0!C_RN1B}AVEFTq?${Yj=NY4*$)@?Q;Lq;{rqA zgI?m719z&rCI}&ce}kim4Z^n=`t5Ba-+gnt6S7O)-R(an+NtT2OCBT4ahr>r{>EW5 zMKu{Hif{OQm2Hj*BMVA0VV&OC+Hv!t*Ibk&Hj6IpWc%Gh;R+KiU zJZMyyqX^{ywclHNDg2Lo(oVgTBbqz$ifx3Ek|DDjl%N5oDP;w=dhc;MiCZf`JC zu0OktMh@q((g}ie5&sYbWKg23GQ`Uuh=Fm3-gU1F*c=!}=nsup>EF@S4euEr0fC+K0m7a@(bGP5r(A>%NT zsh;`~)-g;o;dOzh$N4QN*$1!{wtoUJ z+fp=xub>sHo77g0T>pCq!5J8AD&tt@;pQGYmZV9Z-hE|dc)HA2E#t6zsy+cpCh@sS zrX3gK`P6Mmjpvof)Bo-vGqQ#2SXXrZ}}BIV30XN*r^!wK-7J5ExXEn1)92 z-2Ae$kr(It843)v6x{_*8Y@WRqTsjt2Q4My4m#;!t?Cd1y1Ae5bNc){N(z5}yjkz! zUEg!88_c$3U~FQPsrfs>1NIy3cCc%6Kam^8_s{Kygec|nPQjzX+5a=DA`TVe@U^Sb zKp;n&_uD?uWavqiQ#Lx>4>rA>M;J;csTpe0m6_y8G()Yz9h(>0N<%6g=?vJ`s?hZF z8nL*4UW)8dVc1RBhSKvs_Y^}*yD4H~sQ@$C-ytle-o!lP3Air~?n{$Mz-gGwYN?ZW zpgYimOzI{XTh}Amkf%(Vxg#-UXuh2LBY-n0q)4wAE{&)?oLWW|MzcF)*FE_3m`9u5 z;ky<7gw4f?-)C(Qi7bK^Aju_~3J6*dJx>Z2l&sF)?*9X#LJ$^PPP}pgez{;+id%ec z^~ZUUB`;#MBmWeQ*8cqXsJ#0@vy@-q!)jrJ>B%>I&PdsT9y!kEFJmjPS}6<^9b1jNjG6(jRwA$O^Bw`le26kLFRt54h1ajZ2$6AU@rDyzi-eiu zWm({J%HAzQuYCZC6}TE>ZA8^#7Dv}bdfc!DsPrPxn7QTE^+NNk9{=$@vgJU2@fJVK zNCfkmP(cn^LjLs6ns=27vFBr4c6jIblcgLMaw|eqwq6xGC*a?{d2%UP>dEK$UL}As zLSJ1a({&`Cc?seZlgl4s}y4qp3|K?~PG%^Sh;`xcMVgYOvo=?f>mw_>L)cgCY zMvm^IZJ=xSbq}vJOX;fC zH>7s6g6z@qCO?Cq*Vx;3w0A=5?-nsHO*PJH?SvSjTE!F~iqtI_}?>uot4B82Y3 zjMwQ4^6e=ysO~Qxb;=)83YcFCejn1avvE(rJj0C*C?qC|;E9&N9| znh!R+^FO&NT$m~NPGP5fd&|%jIroQ{6;8c|aZZ~kz9r$>PpoT3_YgK@zC@-{+~}ui zx3IZ#5l=BWUb*z*JaE%k@Xc;~0!jvhr}52Ne-v7`Gw09|U|86x4J2zthNF@@V;T@j zv*Ez62@O|BVZy8eh8;w(Sg?w2xIzUul*Q)KyHHz?Rn@En78N<Vy+@bI{42>t@E1!1g;;DN&^_^dqkZuU^Yp{C2AGHXYKyZjSQ=xG#3Z7a`F z0+6Mk;vwT){7en!Ro9q71Aqbbv7bt{3QVJSY2Y}MeQc+1hEqlNxEQ$KF=3^M{M_p6 z^L7`j;gU4=L+sw7=*H7g$aB%Gr|HIM4;BG;x2t*;5L&qCl9|0D0Mprnl~W{K6urIt z+6pCVw{2)W%o1LCosU? z6pMG#$2X$^R&}GYL7W6TvpKm;z7EwJW+x>0G6u@x)A5rCNG$r{E&LR&DI^Cy4?l;)v zB^$D~p<;!dR=zi(U%nm+-mZ2V!kV8ED0>r^Rtpy&lEgZLgu52xytk9rTUw8`dYH3R?6K zCGLe>=H%hO05roX*hN$P1>IasRyHMWuxl=MMdwk7JB3S3^}X+nizf@^DNCq}6D6mq znl@zFs+0B@y5jlNyBv0AV{aei3;_DwoQobO$98J%f`b$CIN=CiM83`-Rt~kbvz})g zVQM8qw9wtJPPbIOkF9r&W>u5*`8J8ee&-Pv7uUw2x7yP}yrP;4*KsEa2`HhpCJ5j; zdCFJ+RHuG|ROyZ5^;qT{vVRb_HnJy0alDZuda*y$S}5B=0XJ=Soo*Pm_&zvK*mp&1B49xEcbMz)9h09?F`liPtc zEf#R!Mo`PnzrEZEuYY-jkj?LUq(;F765Nqb2r`NCGj{-8EdDZN^#2V<1mA9$vc!%w z&5t^-Dsf!d)77^RkzOa;HlbOe_tc$E%n&@I*)Xh^#C$$q9Q+vw+u(rz|Hug_zdwQD zKC&pb74I%9An)m;CGa~w4xouC4albzV%>VosxPb^{+5X4pkQi#>qbf2-ThVj?bN$LZP}}))FQf!QDfxdcd5uLhB}pdH=aM28Lc%Q@Lv}2=`_`~S zwnA@Wjo5?_puSo}7c5&NIJHGcR~cNyT`A>kgt;d0Um{E&@O*a0@no|s}b3X!J%+^sds~{fftMQt8Kx}B3mjNN_<7qX+3DTjMn${iQ)t}efWtO z@>M-h1}6_q8PZ4t*tR^F9N*^{o(XXSx;0HCG_~1A+D^Kfcu6TjyE5J{Vj*9Deu{o8HZWkqwMu)v?$?tcFO62_Pid zV?lwW>?{Bkbep}qP%SpT;a5p275@hmLAf?y2>SbUNGE>pt1Y^+ZabLdUylax_bPHy zv|Dg;PU`3mOIEwG)IJ>*>~CPRFB)q0Gh3sy%cZpNmUXax+F(&`GW!H8B-!=j(R>Xb zrVp$O<2QTQfcTYA&7=r=U;$wUMxnEl2?7>xVHK1@mJ#r%cWLC;fN!yTlmm7tu;lX~ zGD4kk>L-Qf;jr`NtWgP=Kai4;i-Ij3pZc6faw-h*@S%QXw{8oiE~5yT1?uR|*!d!p zR@#ElF%Vc^l5}&?Cf$Mllr-?(D(0!RBNS5%i3a z;!<%$s08Iz7#t$COVg(Vj0n7VOculFZ-7wbZMJb!#$1rFlhV=`^M2Y09s~JD0M=r( z3ejsgGaW_|L3E=sl>BVDITNfP8OubZW)*_r4Z!)vqnK^Ga&>i4YqUV_`IMw{8}gN) z0a6)P87_-6fzGe8*|W5hq0D>qSLNhxV$Gisn46&beqY5E(?r}p8aWTMFu(o1ap^~# zm&7YB?6G!~J3DCqWrGRnPL;#llEk(xWd>kuwT> z=ne}E&YBE$aAvl?<+%hfpbNwlWaJ#~V@WbmZd8dSzlGtrG)cv!BQ^^4j&hpUIUqqO zRfiEc@Rf4Ml@yFf3oL`(Yu-sKKmtM3T8Z-(W_Je^ik*=53ZIl^2u@EJ=n-;UevffX zM6T}W3NSAvzgs~y2n`)i#aqDC07Hx?oZz#k(hyzEZy_ko-f{&S`4T`4u5f)8kSx&x ztKV=`!oqyKEN(X$ z(bv8;R(-AHQda<}sLL0_7mI)@+|ynWe9(!Z}OQX7eyv{1hoDJ#~w{22+mTtMbG2?a$mml$#s z*k9(Kz>1mO8ZW3!2oBDiLu-m6K9iwZEo?SafuGLQGy_ruruoPGI7hwDT+YsFRQ+%_*|(!PjNXg# zJVe{fn@ZxBlz!$SLi(pR6ZEz8G#BqXTtiIx0}flDN52P3Gn(D~0m8vgh&OxB8Z5n( zvu$Z`>&wtoDCV$#eCJJbt^4pme9W160n54!?x}MRAf0`W zn}&gf_m>x)es0=TGAVh3y9OWEKA_Qb;BE6At%Qa=ltg-s^bqAx#Knt;z7pcpa*SuBrxvfLUwsqQ?R* zn*HlDEEw6osb7i3-j19f&YzyFLlJ$WQ`oX1-0CcKutL$UQBa)T_%-zg%cWn3GkL3O zXtdAf1Qc7%A_1#aJ*qT^i5?Up3#=fsBtq4-jm$}D!TbC z+Qm`UCzz+oIcr<8UDV~L?8(M?V%VaUja$}7N4GBXD|s4%u7n zM1FuzxOomIE=iDga=J#05gC$isAq=3ko@_X%*Hosapip1y_Xx*V044YvK`TD9oEAA z(6sC8JG&+gM;+~9Ie2yL`E3!vLYx+cIBzUCYfk6j%!1x-EdeAUkM%(9VS3vY-W}{Q zv4hJw{&Es(eJHF)C+C8b3@XuGFdBPm)6H>9iqC3Ys72+)_1e&)#%&-!VexWB;CILQ zZSCMWstWdBUF*BwkiOh?X7_FJ;EL!KyA|3qwMzzvap%&D_0~pMH}* zMATmgGxKOz5oNrA8_AqvW!PkdW@eS<>VO01zEXCD%j(5>c%hw$2Zf|F%Mk|H(0pJiin3)y{OLe{uwMW@+`Zk6cvcu;)kAIe zw_BWUph1TEft;Sp*9`^8ooMW5AZp=hn9G)g2t56Jz&+%=baB4qU5bR@wc`76*>K_k z-dY%qR9o%bGbeIharzO~O3ttYhN}(@hE*onwt!^+>a+CMUIzVMBb2&Kb+PB|q7c8Y zj-|+_5SI2L-=I+5fXILjm2D$ z+<%ZL;hNnmbjtStNRaG-7U|4)pp-B7tv}G?90AZCFvdvr>A_4Dba^dGk5h*(NtA8A z#$bK*chq?msI^mtng$MIcxzpWgXY7?w9BSVYlbRgCjXd$@@e3eIUwB$31Vnf?BT9i zH}hlAerYqC+^M5I9D#07Rei3>PiM}Qta1xp_B=;TsvwF7}hzcVeGs?F{_|0}XwRqspkDRzPxeC z%^x`5uuYT$ukyBN2h49BX4e_$E9HI#PF)$)2=TnHZ|^yN>lFm*&So3v4PMwQ4xy98 z=m;h+(0w7D#F2FjQke!B2b^q~+Tlr41GXd0v^!hi$~eLAYZ_#(VpDI72c36CF?eS#)km?a*+(;+EU}f`nYc{4i5$g|V2oZo zA9r>FmVCno23R*b;XzU-P$2exdpeweD>ymMCZKWBn#z9uw@9t$au$pI4Dvu+M$ zf^VgU9nBrzIhOVOni>=DB=_zACnZC(DWW`CpIyvM7QL+fb__I};-st3-m(rAWdwUn zS#p2i^?fLdtKjIT=?nVOER`8+j}x1(pT+-d&r5jCX|2erUi#7^XRpp21*6%>#r4Am@3OY4O#+@0!tmS*XNr{T9I9C8kN>K-dNA zLysVo;$Xr4)2_j=)tk|J0gF#)znmbtB{<6Q=b>GNzaw;{5`$>URn)`nin-D0r9 z-Cdjhc#Jafrx7irEI&P3(f;W*M#)(my(&!<92j25{f^6bgSq$B6dvO?YNkVmsN6hv z)NN0RQqYnE;6v3^F_|9{toB~1>@JYNI%`tlymdeKb2AKWX~0C!iix0uS%dtC5{kB1 z9~GF!0w$v{Quf9Wh`ja3y&iSb3$Ble`iH)lNI{WoMN#eQ zjqf=GD=a`dYmktfk&~DVC!AFfa)+MH8zvUWgQ#xei<^f_?ni2N*+^ZtPgx%UBg3j8 zc_GDV4WFAgZz3}Yv9K(haFK|7(-Km}El<7Hhk!~Tu|o|2wsqso0>IZ{Rd5B%;{(2`)QV`4*PQhywQqs9kitdYBnllbm#a-KlGYRB;zva)-k(xM6 zSA6uzvlHyOnT@d3L;w#Pjb3xpjMctf;l`(NVi=ZID6)7(=uEtCIpT6l*Gr7lYvg*Z z*aV6c&aoPeFdTmXKpzOQwaX#oJa=HjnX|DA`t`gF2+^F;P+hmDxRYZw6_=@BZ8r;! zB4qvqjHZ_aEuXp)9p6LvPu<-(?qqXN4ZxI}<|&Tnl8lCQmM-9bnlntBPAgy<;vy+h z>*<^74qMycw3UOl1u0JU+e-`vNhBrJ?cqW94egoyYT?TP(VhM1^j;6dhyRQg)zA~s zzZ2_`E)3%mM4$1Ho-kM(sTTk(+{#LE>dEK0Cv~}U#duA-7-AiRCd8oe@FL@c%;_w4 zpEB}%iecnGw{wM|B0>S8TOf`A3o&AdaT!5?O5`!W0J@HVj1ss)pQ$C?o+7!)y?=>t zxOWd>F;qWoxVt{1QCVa+b-$eD8ypnypPJN%(GO)zoZ_BXg*mV5ViWm!;Sbz&Gy{MF zXzZPBUkJu5)q8T<*ayPRezH*g_0*owN-1*Qr1=`gr7MAKfAm*n9z4!Bq$OQ^dnYqs z=p?wfu-Oqq8Y$u{>*l{&FVhF%6E5U0fZ70j zAUh`!NB0M?D$H=inJCNUoCb~PDmWFh7ajh)JtkFORbZ|%q9{S}l*AQ-sOgmb!Ly1> zvi^))9y68Pczj^5xH4&gF={Ffn)z|KJ$|8kfu_IhhJ>;8 z2@%5Z+)-Q%lW`U^)JGB6$Bo{czfGJJsPVw z+xK-&6cXhtTb=>))lQ|KrIwTq-bVzQ0=jE1VEpPYnYh6FBXIwZ&puBfLxz9e??(08 zZF3MaxDexWkh z?PO7l4Cij@ID-Zv5)NQFXdPl~a%aTQg~^Aq+yM{BzGs5RAUjFI_3_V`8|+91%5bSe z4yTo7$G_%SO17bChPsQtrziN2wEe~KJ=<;nILVj3>^7Qi>nWimDS08e`}{pfTvTH? zC_d&KO0gPfO(9rz^zs+`Bw&C(9IIBo$9U>g8gM)*^aB;`&@(+HpvQAhOVtOCnegDa zIf|fRflmz)vI7j)Wul%KvdFO4sU=*r@Ue+q&4F#yt&MZNx!o7P$Kn2`%V#(Z#lQRn z2W>mAceIIj|3C*7vJ_7$)L54w_KjX92X9~Mn;uBFz#-(w-ix{(9>wuUb>ZlTk-bAH z!@1F*79DECwqiSzo$c|^?m0UExDbTS^#((0ds?G(f9Y1#=$uOc#LC~&^cpPN@fby2 zYiN2?t{z87Ou8;$Ch!>aW}j#c?gkBVKH|OJx7;#u2tgcvw(9j~;kVWNbky>g!>24! z%#hDlwAg+o0ut$B=@G-u@dy8vs}o4U9%`3A_kIplV}xkpP2LHVJ9z{}wUt2$w^#)v zDXPISt_al~Ms{%-6pR}9SkP5HsK7n%uV1f_NRW^pFG#1JP)6@l=3z}{xBZM$*S=LY z3Ir3o;w_z~m|t!02L)YsN!&tLu4&UN|LzJIIjC#>>0Y$dkZ?M5qCL{z`IU2o79g>! zA6_%pINxJZE)0s0KoOSLipcqvg@2FqJGTFja6Z+7$p?aAINCLOw>EbaghdP!vC36DwsVWF#m-0JWsV#2xvzze-ib5wu>?i*x=EHk zZ^-Z1{i5R(ymyyeGI5~j4NHx)D!1~>*K~p*I^&NQ4_zN0YGbu^1IRBVN`~KWWNGNs zY&Ej%l!y?pu?3TQaNpOvJxP7+qdf}@q;@178e0#Z8;ZUrmc(GC4IyAgoJl2Rdv(yt z0L5$=m%23`divD4j-@=c!KcKs(*2eepr!#5G zHM(dn`erlD9@5_B)}c{D-MW=kmJcA2xTQxGel;`|r5`XQ8FN2ez^bDO|zw%WgIf*JAGCc>(AY~`~j8klTS z@MfoP5K>X!-mYH?oP6Vc7|oc`($Gy+q+V{6z}AuBYH%;=>h>rI+(U4ra1C@WIKb-c zZ3j7~>h*!i^4yv}*S=F>{LSd-+V|8t+pR-f zVW-(LYSFb&F}GdCjYvqM1O*oyC2==y7O497O<9_!KYq!@FUY$oGjT=uK497RiZI`znH6*fr+P~@M!Q{^MS%(Ui0izBu z3|ae?lS@!g@wa%kXgAdbb|L}@G#ZRE8NE)YAT@~p-Al;h>ROt$geci-f4ywd(&?~Q zS|}%q$G*g^Z5&f0`*3Sc!vY{HltB7D2XWj;l~PJ z@6z55`CA)Yct>*)7~8I}=1u#bltGqyP5q_tY-He-cW0AEmOCqFRSMpV@OJvNP&GiL zh+!YPy`(9*&#|Uy6~S9Wc(-wPNS`*GQ>U1vlMEBJb?I7E63e+T#TRNb{I95qH;p0R z2wW5CT*9b;?$iawk+jfXPnh5iB%k(F??wm;SMEh5@&&x==^$ zmtXYku@^5d@y~RWC6ctnD&!{n=UF!1@Bdc)#8h)N;vTMKXLtSg;~-q-CvmM`s2)zo z$xLwwF;4r?OFfp~+teS-ePK^qapZR8n0bm2J*zpmFi%>M6;>pR=7I(9>XY>KRioG# zQ-Uagqdi$7=Vusz+46x}K_BiHgWOCCzhct~k}nAjY!p5Ct~50Ua`wWm?QB>dNQ8ky zV&-%tMKSCGQ_2v6WcqLqGpdAV}VqLHn;{&^<{Ix+guCLI=L!atEE z-9P8pWWL^HjchczLG{z!VX+}Y>RRJq(bD?cTe5w7lg(5JT@hEMLl}>=+n~`l(hIS= zZb<3j-w(+f2|6B)kfc&3?Z-DCG?S1B|BSuPL8rlX<7}^Gc)^n+z*JKF3vB<~ht2To zIhp}^&8ill_}`90B(?~g7*2O*G13~O%Kp*N6N7VTcaYrT4aM6_ktSRp>ZX^N%zVFg zU~Fz^r`1RBXq&#!$W5OYeJSfUvh0UBW#nDHE!UVQ_RBq%+%^a!M4zz0Kcl)=osaAjGkY6~#i*@Ua2%33cg{%6=qDS0E+VHx@w)_Z z_o&c(nLbzB)+45dDb4Hot`Dx~PW*g( zkLBo_e4@B}R?cmn`Cu);|9OF+LF%(ekRFM@1S?30^Yw0)Sxs_8e$9$dh~}l6W|I*( zH%85FtoTOAJq>e_SSAR)CXiie2U|+XB{#4KsoNc-ob4rsOf)ydw<7!@zSpDj+cA$W z;pSdtt}i#2RaVN*0rp}V$Vl*&OkJ;sCP~B+4Q|fLTN5}tEDSIMuBYEO zCyg8$0m|GiPd0%h%i8JxyAhYPBS^wSmplW-C$!_;%$sG)nZU{&IUfb&j zp)QRuCfw>9EJNE-aO-*KNR6Q&0(1v7A!z`?Am+$_lrK=2_1@uxf=8%ZtCRJ>pvqrj z_UEGLOeZXO?c-lhe9;`n#RooR1V#xsc8AaIPQ!_6fMzo#5;;lytoBpZ(3}4V;tc3s zCwZ6C8{AK`PAloG!kez}i7Py(Ax@w`WOboS@@O^yCEEvK0Z%EwKZleF<|gM=?brQ> zM!`ytL_z%hFbsAdSvI6zYh_XssXO0#FCOmP4#$+qr{Q8 zy2fMJU;OsAty@Ch;ln2m|8liWx{l*yi@!&n1DJNQMT_8+|KVvdt!dvhqW?n#euz?p zU(pVcySyuo6Wj*1t&li)cW7flAe62+_OyJl{_y?QqU**h1q|!GOEl{v?jP=3=nwS6 zsxXhp?=JR%E4L#{?HW>~X$Vk9N1??N*S|00&}|UZdA_6k*xled?7Xd&z@qf-ZbHNy zPh$LDXkw-s1A|E)9N8%`eXw3(gy`IQ7KhagC!2I&KFuHUA%K|CSA@CuvZyf!YIpyS z0?L$~aUL8uXR1fIXTb$q=63MdZGS~hn;w2!fR&MEzzVKsrS{Oc2%jMwuaV60KRLa# zH)YS2I_qBd{1HH^mLTD-KZ;cXo6P&jE82zOIKyAQ7;nUkx>3zJVB;_Wig9f+_}>W} z5y@H(@oD!^SVgk#o7i&gKa|3`xcRKU9Vjfm`GQVJgfs-xHt+Mct4KaP=8}p!kM*xx zGmyt4ax~k`j`~~Ui7fn>8Uo((veoQP|H*N?CxFRk`92?kX@@d}qMBuEA@K2qM+I!F zlMOZ8?a9sbiWqQ4;M)Pq?vYn?+v`+`d=FCMfuISb%Mk3&5bzku3!@Ny`H@L6?g5Bo znow{_iZH-Qfm-P}OX*5`X>y^baA?Zl!Bv5|MQEn}oC_lebgNn| zJV(Y3oaOm*Px9`&i`&b5unRnuZOq|dIoxHoKbAk^#Bplq0_V5{2MQURn6 z0u-ShcCTmS?^crLYaT+;>F!98kAdoB+u^NSVa!aMPX#}^t>|1m?dsMUTV(=Ojo)d% zeAe2dC_GfEvK`g`Q(y6#@!P;S57e;9V8OtF42%f(1dtjjcQej^yApA6jQ_i>D;GJa zaFzh1>86IhCg)9a@`=xS=SS<$yMSLdw>4aJB{O7%#@)PQYX6Nc%O1Ht*Q2S0g&TI0 zO)64_PH6ND+oMjXZhli_>iR`(w|;_MeRpzvG{b zNkiSf>N1k;tz>iiVf4={F6dFV=WPs^m^my+i7(=xWqO?H$wBB(=RytDe_9s6UpV}u`1)zw<|@>dLjsMme_MA8os`e za;=`sKIhW@kw3?&Q&|?j{E6=9hm1S#)?RyNk1BpTl<6BxSE3R=Snu4p#EV?n;+0ye zG_WSDW=I~~<6@SSk~_E^oGWzXU@IFO*u^cl#9ClJ@$I{*`FkhQyb<#~^D)x`^QtCd zQ)({pe9Nf9U`&_YioR|t#Ub{2^kYBkUjK4|3UU(gl4ONzSh3DlpTKS-MUaIADjp3MvuTRf_yy5~Pjy3LY(LHnJ9%}PuD z)ps3ovUugOPe)XO1wU%1*80A&vfbqBj!RjC4W$uID(ln~;2n%98gWw4SWmXPzv?%u zuAac~!)2~n+$pR6+Zf-(uUDaef@(=C6x#}2%?haJg6UmrGmXS|?K>38l1oVSKYw{- zSj6_o#p_mmTT7MUy=>-76GOFTrRp7^T<*A_bv6xr!LyCr8SiWZpxE!fPZq{usS$=d zCAOiUSV#P_`!9b5(vI(Ll;+yUQEycWO1k?{I?ULHQ>yLO`@i2>KSk77HIy(|s7_w( zL-ys~uvW5d^iQDPl+qR7Fo4S-A}1I7815YbuL|1qbdiqYiINuvJ4>Hm8EKJycw~T= z)?ys4JFsj2-gSkt#r5>mW@y&4mp{tAx*W#`noX%2#Lv{JA7vXj+Y<*allB_LbK4od zH@mYPU}5o%u4SBJ^02>|Ty%*pJz?7J*B9(Nb5IaK6>(H5(!q8=|$zPY;?EzRXOnNAf5M#&d7|(MZ;9vUsAS zX`r@1rA!dsuKtB0hNMZek*6?L&G-)8J5aoocV%lR9B#QEX>z4Kr*D(GzTNBj)76x2 z=;(7I+f-pwqtC+QES6xUwc4?_(k};|?i=@G$9L~FEtD#33R_(3Q%g)xmh1k_LTLl9lkNn zX%^TN#xHMe@EqM+YY|o6Xbhg5Uokp%Q~rGyB?l7W7s?Q&c*lQG?|`qJ37y?=Hfn@6SW>d-J8kY*%5sP#M81YLZd zB2V(_*HD>{Q`X&1b-NF5^pz)ziCIN<6S=0&3g-VbBTDw zi+vuISCnp~UhGyU8SI@o)y$4t^|T!*cBRnj8z>OV(+bh3OW6TLDulWx;S1F2Fmgq})>h>m7P#25;! zlmt{t?`O_YZY_>vWb7vk>zf$m3|E+C&P)X?kjGEHujU_}fB19Nq z!F7PrZR^LC#XieVXBgkhp!lv%OIS16SG+q|E_pG;)RnP}b-0lI`IUjwaOBmk*8bDB zY$CQ3{x>ZK)JM=$G#k!GAh4h1|L={Hj%pz!TnzUmn#;~}==iY1w!I#~hLanq`72Pu z|KRGy#gPL}R*t6`n>9Aq#f=o(o@{;HH9A6TB68(4CFxPfHP+ z7GF_a>03OgJwL;j{_%w&ZnLnaM!o6QtDyG--aT2rL2d|sqRVKg!Blr2f`e)oq}l%a zTp#YnxR!C~9(tJ8QXFg)zTlI#wKdK>Gz|=N$jl=dRA;IF0wuq|nx$eIC!0H6i}M2|s!cI=rv@$PH2L_n zSalJ*XDK}O4n#`0RKKTEsj<%XknqI3`PsI@Xsn)TTH`VKCb;d8R7%-S zvGmOE>?;$AKh9zXvAUVGr#i*HP^mSTu{jfUE?M22pL}maoBm?TI=ZL9zUPriwA=Lo z&E4Caa#y%?KE@tvo|);e*89Ne)Wh3;1L-}8ii)ZSo@)XLMMsi8kR0$G$RPX!`mGq? z81G8#FH7zG^16U9K-oswpy$+eeYFBwD2-3uNcb$^v&@jySU8(v2qZEh#py4!h&Knd zC?b-uDqHd0pVK{3)g}Ye^*tTu1^(_TB^#U1yO$e<7x^izX>YQVO;;+4W z#_BZf(#ibi?E~_?UTnsAReczvMiwV!c};#d-UP-|9!l>0e@@Metf>B9t-WPjlwB7+ ztb#OxA|NH9fS`1@Lx_@sgh(pgT|-HifC17eIm94c0|F{t0uG(h4Kwt>d&cL!pa1j5 z$M^a${?HkLbDeANefC;=tu+nt`@_e4^%e6=)Jq?GB)X4f`ZRmONLKTLUTOWh(T6bn zU8=|NX@|DxcdOKqdSZ{bheqqx$Dk9NJ2U6o?5k!RDUUTbcok^n<+rMN#~tnSBTazPEWiM|ZHto6pxuEjqJ z*wlC4@Qm@eY+SxGH1)};qZx)#HOI`*T41J{3OGaNmou2mjJ|G~BdYeLc#nqt?Wf3a z5%b#xuV-a&5rwNin#GVY9L4>@@I|}kiH)QoQ9YYZDVHF#rCDyvX_P*qY6>eL2bk(u z-{j8H+8ItVDb#x-3L}78YO(U(Z2|#IV}S`JOHF*-8_fK1&FbhNCDud6M|=Xa3BDla zXK>SdG(5Czsm^Yr4+nqKzPnXByPj#G#7a;HHkhvzJGQSh+7RdJ4Qr(yhBt1DdjqG3 zJb;)&IqFX)Q)2iR0%dxRry!aw+eJ{0ypN=*wcY2e13eS$mQUM(9PY30lLuoi9Crn^ z*}8OHI)_M;7!OK*#(Dn?Uo3z78Itb#P&wRhbZx(@d-tn`g!MN#&>=8iw z!o_*O4!OCIJUBo|nKf@>Og~(@FmiHL^d)(|B zWqKe3+zjlpR~G#9MXfdL6%ant8hv*sC;gv0_5c0O|9;GN!d41z63_wfOGxNzi_|)7 z8RI@rxC4xfvqaG5F2FqRgy@y1Kxt~=iEI<0Si6)!#dSg`CZkm}lURWc6*O7zbsaI^ z-&Oja`4t%cdGN{HU{K;B_BB{F)PRI#>#geEhpX2uDa&u>eiWeu+?AG`92RT9?y+e` z0~NI2%EgIZz>G0xBwBxvxW8NkD0GgIF)|tJUp^V%fFhpo2OFK?IOZPR|7hyt>>uHA zCd^tljk9vHAfv>~Xb(PeL=8c6nL5N1PgcX6q`C;8L-B?HeAepp>0t20vSCmubL6NT z4ur%`(+i$w_Q0$H`66B=*=<(!4uxQevzlUKrc^rjnYXG>sb!unv`D-7v#klagZM}L zU={4YF>Lu8{qH7sO|4m({(YvZSW${}yFa1Yu4J3|AEfEN>Ib??54RmqNd|unUU>@d@;3^#tt)i)M9&I_=?~KVN&6X>#O-SF zIeh*rR$MRnk$sR6Q5eM07t6w1*Kf3H06NsuE^UOsL~vBODaApJjRG~%ckRV_^4TU8 zRRJg1p?>jTHd9FmN6cgMWipoLc(({N&kDN($}gLA&{aq%s@|eEP3#4rb7rr|4rb~D zk}P;q#vQ;pp5OP_2~ou&`KbAD!ge&6PyhAnY{0QBXcM~w*m?0l59TR=SJAfu3Y)h< z$8cS)UtQaPy1x`KfNW^f&eB}EIbP4EzRcfqH5gS{rF`~nP6#a9VU;Tlp3~&-j2pGm zzy95)wtu&>y!{6D9Y(`O8#GW5XM$&XfovmMJ3I@iwUhGx;DhDe_r<4fH+}f6zAN!yz=rOUCgHcG=!R9K&7@(is!@vH|fc zK$X$Cbk+rPccn8;DPw$$f71I%^TaI&8-d0FdT<%I$UavU0`o;mj(UD`r>S6eh54P} zyt#(Phbmj78V}bjm9hUGk>1VsSMG|Ax0dP-Mw@6W~_PQFhB}8&cO) z;+WPRFkz2fBOUpv0%XB6Bf1PhMg-Kc4UyG3B37YxRS=$<%!}1ArP8VsZ4}!^@+~m( z)@?=t6(9+oIrcu=svQkrGW1?b*hjWpX!De20MNr)r<22=Qnsk`22_1(+(=CZ<3_np zb^CT<_`Ok5*h{b6T&?0deEzeOf76UH=OL8koT9c&KU+Y&O1M2fREU*g9 zrDOVaky+Gz@i`xV7k8PRH`=9$)wI7j*PjJNA2Oi$X2im4ifaRa$MhK!yfBB-e<;hTU4yj`HgWZgvV(gAk3Xy!_YV?(!ZGUR$&>Y7)J<)bp%c z&~Lxa3U_6Aa4UyyQ+EQp#NJlyhAqfKN?JPOWf{F8gpyKlPo`;Ce+AihL8y;EmD3!a zg(PrM`}*I_8OgSa*sSQ`#I1gN`SxpSvi#sAD9Ds1lf#jR?I@-W!N4+s`%lcr!Ssq` zYM;tyKv(Orubs~Sd5M|5EKSrgUIVM(?JPWfz7Wj=$d!g8vvq(jRP6tznD|^Dh*Fzk zEk?4g{JNojvwwMIrSZbYz6J+3i){`?EPsy>x>sunC zz3b}(Y&Ok34w4{ok>P6u9({3Hg!IA=Q>){*E%}-5Sb@nAn+#VFqc|=Z-MYSICGtlK ztcHT@_7u?dM{%$=F9r^E^LW*gnx0e6;Y7@>7q#~i^0&-AXZ>oc9A~AU4{nqw3B9)Y zpe)egMS9>Ub-{M!;>mZ==hXi05Maslk?0kCqivSuQLTcjp+&l1=B`4H(~hdRiYYyJ z5@BsKXTg^Dil}ye3+7PY9nOKE_u2fqeuNWDNWel$A-aXl3q``PIqwj3>x zGez+bMR0MD(b_0gg^zYTifz{K1o#XTI)9jHGh_)edTj0-{G=d(LF6t3UjL*DPsC*~ zHzLT$DdR;6xV0K=rh}=k7idrmkW;KM5`8(I@b;02opw&oOf~`yNNNIDCxVk_c6g%^ZHdvRdqp8Y4o;XS|rELNB zklwD%+^h#hM9SRl1M;{m>Hwa>g&?GuqUI1?kNf;g_PDK6BR2($gg*S6Ge1MyRRi`g zE1a;GU?0H6K}Ix|EQk|de}Hzq)x-Butgk#eB0>{94s&-<`OWL(sEN_Cu?|6ZdTxRk z;Z=puN7s=CdA5y|E{V?u%C)RT=?P`qvMP&={q=0t zot5qcbnvcybZ_37GheCUGM}6ib@&(Ro4i~5I(IRuLl&IVc z)28X07F#%?X7ja|c32ZucS7HxUZG!Xg?==Rqb%;h%|oDkR>2``?<0-ZPdN zdrRlijct`J>M|EkxkPwptNk{JChsi2l*2=5UK-Au)dYy{KoIwvr!ox1@p%F>ihnx! z*7_lg*bTF--_))!SzM9ygmgx;rKbB0%=js}9};Fu-6kzP z@e`VytEAT$anl$p=9aV{qT)Nls%;Hw39m8!-t_CkXP_S@>?yx7X~wA~NaJPYAcHH? z!$RoYD$VwehT^nbW0b5N5WKmtlVXy4-zi*r`8rnf$z?OB7n1kESZZ-Ob>JL01S=xg1mT zD7I8Ay*lNOXE0`ee;<`5G8`mV0<_b&#@|)FsM~1s?l@~u$wYWDoVoKc;r=!9$U%KY zqgA1t-^DVYMndzG)PP~{)r>~bOusr(lYE4%w(BFyYIq>nx_!a}KtJKo+kZ_N8Y!YR zl;X-8tS>P5!GI!Z3sFXl3`RQ)6iylSY^C+OLxpTr_bUC)e10L$4EaH?gM)KIL)Zi; zdl=}v&HvEU^kZF0E-QMit<8NM@rdK(i6bPLg*AAF&GJ%HhswTG&`Yn@A}{0C+UOCP z&F1;rHwWU6!1okut^gu z8?BNquFaEYCi~nf#gZ@h)1)wgnq8rZ!iyFHv8}DCW=?>cj(>z~`n(zE@FQb$@31gS!S!`hl#)$IlNkb|i z7a2hIAW!pp8Dq;vTNTnhS?7^m5}Bu==-vG3u&4c44~2*bSU+o`rKp%_cf) ziVBs~1$fG4+Vw{=mj^N~zn*QrlNl#pWk$JGw5!4GZ_s;}Y7R!SIjFo4#XFU8E@mRF zD4jiF&Z@p%PsQHimxjc%6a>oZ_p&(XYME}IF_-()2=+y(-+h(str$}3tLuQD(>_BdEue=7o39nzqAdkCk5w@C%B!yvy z{%~{p0_9I00OYm6D0kDqyUytygiMndBxb{ zs?7p>1xYo3k_nfO7ynh3Q)?R+g*hw5hFew_y$)_0yP8(~gr_q1=h{;+f$R(n7y0rT zTm}z7f8mJXo1n-V{pKJQV16y=RokW%32p@69ey0p@^a_L*3_bqf#wE457sQLNYzRJ+z5phd%`?!*Qe~Uip!Vvex+EQ-i-Y^T6WFJ!%}p-gsX7|bQ2DJ zHhMNb;E&a2)_%=%5wihc^MBE^WP(<9JO9$BF~(jV$+Y)6RdjvJl;romNgHt_%tsSM zQ^Q|Su8%5ATt~$9rf`z2NENPh%a{e8;L+6ZZIV6m--X~}Ex)kzd_|M$M?xYy=``9Y=DFMlAZjVR#W39;w zb)GzSIA!;6)hjSA-arw-io1st8B5z{1O_Bu=#&|7tfYGaC(!>O7RmVv#m{YxL6oa5 zwI&?I%~7-379+46?&^x~T!Hb}O?|vMpbhkW(AhH9xD5bSd;jdyvT}?6r#!jv*T1UP zu3%fz?`Y8xx2eiT^(~v@NuWdW5tYIIBx3DPiqTdTxU&x`Wz4+4$^fgVy`f9oIenYO zojW=@danTTVMC%WeOR6W>op4Z8~h&W*S~xW9;Bgo=Nx+7+U#@h`B_e_;Re#RHn2m) zrd)csP7@+nR!H6q2kKvmW~L=bxM#gRuJ!N>p(PIzwUxr(CoI9d=?8v4B^g1%1T032 zEeX*(1lWT0=1p@d$rXXVJJjc_Be&?6w=Bc9RDk!PKFs4Yz69;^q7_cM6d#{Z zGS>V{V%{F-cg#4PM_m!-%Qzp#KSu;jHu_}J`k*t3{U;6Fo)r?BRH`;5FHT@q#PMHT zrTgyI;QaJwvvS}wkV$+7IPQRt zcn|s?{hgcUM8oPl88p|H5jG+KXUU+P(Ee(oJEUW-0Otbtjhg2?It33K^JVJm$6Xd8 zJJ!V#j%{J6`-L(#p^{uV?7MfO4=-cc_-0a!*f>3q^l3FQ}?yRpG_G!`d$Y;c*Pz{X>!N!TZnF z3T_GQSbR5JM8|i&JChqe9y}N{B_63_v|Ai)B9PvkYrpwZUTb{1Hl%qpYH$!0aQ5qW z!Dz+!i@Um}wf4L*jzcN#k#Ax%Tijla+nPRR-2m{zi1@v!>aok$Axo-s(dQ=Ovn#6Ho# zgQz#nZ&(I2<5^V6!#d%mqP4-f!G_*s+~tf^5mu9t3I+n#=U3Ea(m%jm0J z7g-gDKd4dh5@+pqnl&s^X!$Uv1}@%;LXPeHCB&y!VL}ldH1uxXWLYSn4u{2B%5fmM;!AihT{54gtX^9^I5Wj znl1evW8(8mgqjdQ8y{iFrxbv09h0%|UZ~MO{G{Y>k`&(sI-LUV%j!usx&=S3gb_n> z{L0pmz5;W1qymn7g!)!sqtwk!>dDy}U!brG&z{eU<~uXjZ6q!G33T>vN=$1rnfcR9 zJ}4m#yE19LqT2hC^U0->RR7|{pWC3>7Z1F~jMSviS|{L1L}~uT<8!_P$Egq4ytTia z>Zk;W3TRE2gIXav^Y1tTpZDs6bN#1Zpf#0P>4Y5 zTESF4!vDN4uP(F7S`v3dj{e)yO`)CW8T!c8p>)XJ^Czi+eJxKunTyBqYi~-m{6IYz zB9_#vb1JbB6G*>JX`kqi*&cS?cCx>I-4tzLq1=<73Y>fxQ=a?`-|!NeRhj1k(ku=L zw2t)4f5|Y{2h7u^Ux{5G$J@=jP(4db6#8HnMkt`DwJJX0DM1Y}o^_OHV#|R}g-^s?R@?AvytcnUl+IxQyiXLiD0vij`CP#{ZMRpCQ2i^Tk8U#Vda82q;jyFC}n?J zs3-n5oI0EJ8n>$m4P^*xQRxJwJP_)4xlxFGSfj^3Lx=%jFoJ+h?zp|Z3#pR#9 zaz39_X~Fe5;bAbopQy*qOk&YStd3-=!wqN&lPc@cmc+BDXwP*q&-O6%$EhhhDP6ty z`KkAA+6xR|i=ZQm%L{e%$6Y7Gp$mWLYXzR08ey_^K7iA8=RbWSkat;cHv7iCrMOx` zD0+3+ODC9j*pcp0yLcn)H}CwzB+PTt4K44+OinvXBgT1{p;WZ>Be`87unIAk=u#I% zGf)g(1FegIpSSm~1!>``Gl>6DdOa_W5UhV58cp;>i(yd`C@H~Z`>kY+9!D%sfyu=h zXt%x~WxN+zoAp?^L)Lq0W)Ya%O?t&!``6lDPl-&mGp)#Xg&yJV^c8Bv$=}`&I>C@o zrzr;gYhi+|7BtcX?SH?FxvZZj74lfD?X%sG>**E7gZZZC7+S=}EPourt&~b)i@*6j zWvf^0IuMqX5wX)SJv*K1uWu+aJbNicDS`WifaYc$8=Y+TxvwCEUhm3s2Th3wU|ePF zhxxp9jl|_tXz%K_DJy77?w)(u?lIM#mX^GZ$Q^k*%hAOC_1rg=$863|%I(47au?0N zx@~`dxa<8{$+v)-s7W8Q;58>hTc5LxeGmtaF>61}ULFHzAF-sNQLg4d`?*js;Lsbj?lqL#+!r%mic3?S>XJCQWFu-KqOg-WU+Flxl4Qz9fd(O|%%K zv*XrNiPp8e8Sc42BE{yBiLtaou;PLR;%rm@ivuV(#tR)zmrH1_wTf5z*`S)!_rWGL z@YQ|pem1Nwv&Om?PBf@eIH)F4w{ozI$XZz->xj+cS*{|4cEoihaOpYwVp)r;IsY7QEyO#41xLraoQ9k#p0(00`~yDd^$$sR0Q zg1O6;1k$9q?+ZWRt3{|!2}?7%?(hAfR};!1C9kUW)V(*R#?OS<)#R7l&QDnnKW&l@Qo&uEIv_?!UGSSX~$gS-_c3S4R||R8b>2AG%@PBrf>}4u8DFW z6CDQW`GS}QpGkUb?wEt3<8NMm*?fML$?v*9g?i#q&|RX93k+Z(Tct z#KRTu(v$t`0)v-(MpJK{kf+V`{Yz`T9Q>AG{v~+QqnNW)lIsyGFmS) zrgxw;{8_r8%V~`L#Zx5Tk0rv2-0$p6)#SAu=AW#%+v@1NjP-7xq3WouZQqM{a4;{& zBRdR81izGJRTx)`RyV$fT|ATRL%thSmMt$`+xSl4>HAIEiVeR*U^1zDk(F4d z6Yf9Fzm<~SuZ2~yF~03Y7Zn|i)=5al@CuhB4(>R}0VI9q%M{RnhU3Y2l{!scsc~*z z26!ZD0u|(AK5MEEMld-I3ur!`%!t)9$P}tTcd{({Qp%1VbxP4n`+DX1yvA!eYOOED zNCdB8?)^AM$-+$DIHj{Q#%DrZR zNt0)!NGsV9yb72+AQD1YFH(&n39sodE+|hHI)gsM=$-Pr%=^Z~-4f6viDo~^#{yzj z`7}4~9@lM7CfzY@M!t2h$2cN9iC12mi*1GH1ImK@HHo)tW~;aeTG7bvpa*OJ!n3CcZK?h{HS-P z88D4)PQV1a`Nr>3tOx4AtiV6(Z-rZAr&^t#y2xyG(DzVRhdZ8caMPvE#uC@f=%}vn z!AnsvurGvnV^gPL+8NrfKZwj*J;6-f$v%2`eimilhRI;j`bmw?lArB4mZe(NHoo=ScapH=}7dccKyvimRJ1HPdH73jKFRer}hsx zcrFyyP%xU9_Bz|id}AXaAo(Vd@$awEDL-rSpIO0|)U3o$n?5g5dJ%+Qh4A%9M)2dn ztW+sFEs}Tzw9qm>-HR|AV#?~m5e3(N*8?h;`&;Wr0@_Xa6~DFiQZRQjs80E#ih6%Q zLt64%C@LA+^c&%~RZNpB39avl_=aV`R_89%N5-0{^2!7TO3q8apP&2I14@mu%za@k z)7}moSw7rUhh5s2aY)oYP$J(b>VDo8@vX;#ld13R`(BHbdZE6}H|43V*KzF*`FQJ` zn?DN-x&@mqUOagS_Uz5AJyXA(w4+McY$M=o6t270n*LmrdVK7NKc_CkU}N1%vrk)? z#3*3#F6C!)VTO7Kr}ck!s}i?X3b#>{nnm9$7C=MBf;^OApt)7-4mr*4(=u$RLi^^M zFi9T3CP;tbRv0HyKO!NSl_@R-Cu(%Oh*m)UtCpT*T*}?~6#FN6p7)I_2rBHW%T_U{ zPy5d)RUb|IE$4Wf^FqqE-aP>XYXzg8^z~60L-o)!i@wPfdHH0*(F!&<`-w-Wou9TF zv(HWGJ_F~%6JY{>Re`>I7i37g#a+tU0d7u5jc=RL%Sq|kmDV}qHym!>@)6s;fCve9 zl*FnKXe9(QhUgJwr?uW};|r0`7km8be`Mf>7^HJl=T`af*Yk4k+v?V(^ zc{tL*EH@P`1;f$$=CSRYopGS^vQ9@mfq25M(s+_WzWpCqwcG1Un$(qw>I;e{>WnM@&O!G@yXHVE~oz&!&Sr1 z|F}t>Xv5&1@{)uePdNJ5`s@B24o)Y;!uf21_HQWUvK|z9MfoXPQAUpi1{N*f#i#nj zXtwe$YutRd7)vkm5?wF}N(}FsRp%3v+3*UpRwDODf<1OYX0E<67C!U^pufv0G;WuK ztc^1^OnW5s=dKt;y6Kdj<3t+=QDuWQXVsQWDeokt3@*&CVm_7~Eyb+Rk$IBSi?#EF z=(4F0Pn`4iy*Ty3D}u`=&Y0ll&vZ=}V8Bc=Zn{_(u9Q&rM7zoJ1O2RO&a8x8++*PKJPjrKCoDMm+?|VYC z_bt=hcblom_(%&8uh|vWr*D4oam9S=lR)lkOas(kZOTjo?e0Ufr(4?A)z{ z_n6b^f|aJNX}T7NoIzg~wb;vmPxmANIr;ffCf>G?thWVnJFn+N3M z->wPQPiTmt(ndiBt}MMNXvO-|b!C(RFAW7MC;88XZun^`$*uCAfNXQ{vq9*gwgO+4 zqp{#wnhIcT+yv}WVyK2{G+Ty7sYI@NVWe8SH+?0S?0oi@i!4shq27JaSjbh(e9p=P zbJO6n8#@yXHe<&_%%}{eCImF5xxYA;mb}%6i|Ci>U|V&?vv*B+&bh}xjC%+-093U=^CyT9 z`eF$Y{pWc8{sN+%PxT62+>rwq$F$iDndNZu*;BX3sq&1F{&LWZ(&+mLo6%9=ug?LlVU z0q*AP59`K$9e!)4{Z!1 z^d2g3tdKJTuoQvQkOBWSL);>~{I9*+jz~Kn)!8!G>~xH+Nb%CytVH3m_L%<589RX_ zKk~tx24s!(r3-|jA0i|vpw-pjc_b~AKN7r)56L#%vX#9bqD)ZIYjRBt*YvCGT$qiP zpgsvfZc|DtDgH|I`(9jgf-O6OhRqG$?CEB|R)1~{!bsCaUuQd4`r0${HCy|!atL>0 zFNW^Jyw(pN>Yc@c1E26HH<7(&MJ&aTcJY-HgN5`h$PP93AP-OpZms>CmTCF0rqMv- zgKj*|0Me-=CuT=*^g9*)LSIIvn`72l*e~Hgqc_uBP3Wn*#Fdr2Bwv1pEBs{Y2is8u z>`S8~pykAY>S3pW((H@27*)F3PVBsr^$YDrEHnsw%1hzK09Ks0i;cTFInd{$ zR7#u!`2wX3vQ$!4O%c>E)snfEqWJbw zF00E*WY3?B{K2Bv+jVm|+t^iR{?lGpBRbB&|5P}IP`OX-BqXLHPA12n&!~9(71ZZj zM%zU`Y>hsuxLL(BEf3l$qEZT@dSK45FiU~4sW87f`xkZ39=X5_`CSPdGr{q+&1Ub& z2SQBc3J1MvRzW8xc|2?Na$Z@s;`t-8vTrZ8w0?mWbQmA#Dvw;2f8>K@DkwtvzxKJr(ypN|lxS74yC}ltyW#-(I`2rvGZ+h>j`T3QxtuZ2e9(+M5weNz{zI#p)W-bpHdCVeKIt`(owV!9T3)tCakfeB z7UgFXLgl^o)A!W5Jq)*xpyQY_9v?0eyNcuou32!ykg5+_&2RKKP01X{C*BywmC&I- zlB0^FmyF2d|$p zVL(*ZaxB^>>L3}I4jZvlfI-p= z&04hJCldNGRdw&4fdHdW1c4vM%+m8c7;iwj&X9i#rx5HFQMr@O2`JA-nQMEu%37A4 zDk@SoI2;QLpIr9r(dQ8E2*7fHlU&<|P*&>s#;AQl+iMVT5Sv#ax7w-!t*-bRQ9^ZL z1Bxh&9Lg*zJ9wK6Ksnl`A$pMcDRR-EgI9y+Wej)jk;w5{9JPo86Ul+7ry_MC{ibu$ z^VOSYe-2;Oal?_a=Eb^9t3T<7NxFP@7TnKY&PueLt+CzRVaT7JGjK+*RmGt1CL@J# z`mgW651`Jfq5<^nGk2XFzh(v=V3h_k?)|N6bJo{`$)ty0%sl@}m#g=NNGCAb-+QYW zioh*h?(4S6E@%qfARgoBJb`G7FxV4o2BxXZ2c0_wg`8WtFzj6Q$6FA>^)>{l1#HXC z`qKW-*cM!2>nHRrm<`ZB(q?`?X`)N~=I-PvA10la0KT~>-?q6yUFiMw%upy;|67!AU=S_ak~n!N-@!Lc%8k=@ah#NaWVu z3=M(C&AJrRH}q>#Z5v5Qw;M(~(cWA>nXL zxnG?TMSpFIX>{V`M0?i8LLLJ59;92tF;-&1{2t+@keB}qPJs!aHP_WI^6=33nSA^+ z@|>I?>V(Q7ysIc6WeQutcFi6n+kBQ9{^MGyWu5^CemSGMSy6Md?9Jwa336 zmyEW5jXLI8ChTB*IO}_so>APa6411oDU#reQC&rd6&(`VsK}ei%_0Bp>xX+I-YY5qP?{)nCr5wRO`GY#MxS%Qf z4exKJ!iLB^byF=|#fkeagG6%x1KRVIxp~`T^?h+0(rKbvLcOBm6@VzJZSl|AdUKzt z;}OXRYYi<-nUYEY_Z9;Dgqpe){}vg*fs}+Z1_r!ePL)IYWi}jUVfYr^_bLamoHMgd z5`>`mO?(7et%wW%hJVS*gHifpUewHpM8f~U1wLr#;v>$;*qSFIaw;#|lnL0`O(-fUOrOa9wIGf!i~uTXSUhCeM6pbwdb z%ufs&^8{(XbLQ^nQT6hRd^7jW;ijQTlFyp2Dv85u|B@qCu(8e@W&NV;y=~)YU#uUm z6=a(Etl^KUZSlmv>Nq#x`B#96B?su%b!zKYC3+tEG0k4?f}*r&q11CGk@50?v3`Gl z@W3)>{R+gfDxu&H*;T{bBdRlbV#unhi2JB(WZ(wKA0ZjUJQ9t;8ASbXP2pd>5+9s0 zupPzjhpP%Ece|wGbRP8?D$=8Bq>mnnT~6g!)T|nFzRVrbK%EMo95(Kl54!8F|DOdl zJD;EE&%3<*)Kul{YIQa59W}BgKgE7~Z2KA_q!5}UY+sm><0bo;x~l#)0orF$c0gfe z#s^L|mFtwN(nrCn24>*}VnrE)p;G0=2#&*T|d7+K%5LJX2!1 znVS;FA4+`C?uZcBgy-xfld?|JecgC}a`DTwd~nS8_oA^B7F9iUYc$9R@cu%7y8jRn z51XKq@aXE7+Ue>H^!rozB?oGz8ec=6q42`{+5FP7#YWL?MP;za^-U~r7)C_DMIf0+Pa`>EB7pg!J{VfY|MoLJ=ly2!@w@CUQE z%Q%ts#Hw3;gQ*W9z7Ptzleikyx=sMGd_PF(SAMw7(Bee3vx0>g4D6mmqTh>5D82Um zU;^L>oa^zBYX(}ksc%nx;!i-Zy^R@-W!M2J-m4VwC7yOxvsbTKEUJIO@9ARCV5-b~ zc|Vhpb4a;}^UumAfqqSd7I@?-C^>@-~lN*W!f87XPcr#iO0 z7)Z2@zt|a|a6xP4tP?W-0%{qoxee5N+T5X?o5gcWJI#JYt3i zD$NC)n|@xG8{^qU+t!Rz5&3k$4%)qc68oz;$9}jdS@6V982O4@zBM6)d~x9v*IV6D zTtU-;1%RR4E<*lM*x(I?zi{xwFQe0}cfbN>j=@4kPcbmQ4bTn~prb>bIR{n&&} z_0L^=?&`mkU+6#ULRPpev5hwaSLS&sA>WgwT44ud^T{&A{@iNouVUr%mL)ke-qk!6V5f#H4k9AnB}UJ_pJW^OJiIab;R5NA z5QaAO8B=OKx1F5S+&xNgaoM6U-_D(PIZU<$BRD{e*+RJkO!cG^>c>1EOV$er=oMml zEY#|t4Y?D|tan6%jM=DV-IxAOkD^_?3zelh$0&@ZxppY?d?eP-c<8P+FO#x&_%n8T ze|=-p?4YJLR|C_)e>S6^H!7xzewFhb3{obC{F})rS5#+x?`t-ZJPeq988 z&ReX^`#lg)R-5JZ;AGzxt>W4j7SPR}8NiJ6Xpm>S(fBO3*!|s1&N}aEpWWX9rXO6Z zp-9io4}8On3DY|a&kv6A3=rb%JQQUcq74=!x)Sq_#F8$$E8nX)|WqM<_sT z_$O@P_JDA}Vda-m{;1yCSwHr0rRLA-mzdC|%T`4jyfm@JzL{R7Py1A@(usz8E)b8+mIdJRpE0)cyF!weClHC!U>pA|Au8|D;ZqS>Gc> z$!wGAZ>kn{T`jH%S7q?o zmxJ(_*KDd^aCVFom4f1uUrsjYA0yqrWj(fiqAOM}sZy|M#*E`*&0P^S=MT{+m}fPcG-0=o{;h552B{>zRU@e3`6C(EkO% Cy;52L literal 0 HcmV?d00001 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Airvolute-DCS2/DCS2.Pilot_BottomSide.png b/libraries/AP_HAL_ChibiOS/hwdef/Airvolute-DCS2/DCS2.Pilot_BottomSide.png new file mode 100644 index 0000000000000000000000000000000000000000..694f1497f67f626381b880102f9dfd7de3346d04 GIT binary patch literal 572645 zcmdqJRa9Kf+BF&if#AU%f+o1TyL;mn+=9C&K^u2>g1b8ecXtTx?$$taI(vWF?;hX( zU!0qBa~KPHtTomuYE{j8WX`7=sH7l?jDU~u=FJ;qX(=(4H*a9o-n@ZEe-8_}a(yeJ z1o?n+QjrvSQ!!3>2swc<7nT=(^QJlq@!9Yl<-#+Cq0 zXH{EEdwEl5LlZ-1L&&u^Z@kEizgpTW*;(2;JCX6|c#*l2@i5Vmc|iX9(EaO-nS+J- z|9*j!i{pRp`S%ll&h>nx*Aax?ym{r2783@z>z}m4#ZwG;>_0NvwYDrjogG#uLowlg z*%O9g)q4c8Kp|Df}N@DJ(1lQ#(k!1zR$8#tJ}2Y{k-M9s|J~P45swdH;Omt zLA}4m-WW6aG8MGD?XLFWq%7&_5ozgBwYIiAJwY*Nq!@^s{P{6^X5Ff#j2j}v4Kn;+ zM{@4sZ6{I>)Bif;&@=)6`&Qf_YA9^A|MfiNROXvF*8kZq`WNNE|D%NhnE!jTI%F|} zha>;150KMvcs`Z?_pSVY)VcrPHd{rB4ovSD{ny;ro|zc2CJVlXcBpT=_q;#n&8_?g z6QlFwEWXIaIc~T0%XzlvXk6ZgJ~l6g|DNDvWK(cAE!TY|$-;tFTJcw0)R(ON4V16H zdkFr4RoOd=0>anxS6tD7j$l0(cpvLihij6I;MQVA106qi5aYi9l#DJdZho=0@TzHG z{2!bpkD&soD_@Qc`qy9l)0i*D?{CY)@#sqa-M#p(l=D|S2?e{@!{Prtg4++1pDc2% zefe8m{C|3hTOg<4{StLU`43W;bdw|H44LyO{$i3E1HZUC?;nIGkBLoLc4#V5HU~#gX+tE1>ogGn6_&h1XCxpX_h{ihne|jwIdw_bYG#j1ZJl zUAuqC6jv2>|7%E8-z}^?Gw_z1|7SQj!i|g&5NYO(Whu~gjR>R|+=LC5Q%zX3F6|i8 z6|x$>|5>L9$()cZ(^K z!%tW7r<=5k2)PIj12|yRlh=#$!~cGBj_Bm88NW+3F{)Vs0S)Jeq>8G+a*C1@Gvz+a zOmLW%6IqOKy5K8`!`^6?k?mP-N5Y@}H(=Yn>@$+%rA#gS)6;%!DY?hBb-|GH7k__i zsv@S+o?L`l+vuh%@RMI?+^1I!Yz@fW$@D{B2Cv3Gz<&%@nIY(C=qji0r}I0-$e8o(O#eJPHt`36|2^JxoBkTFGNIIhV1Kv|DNR%jMfp)! zItesD$2_Ajq2?H7h-qA6>K|DDb-C>q^8GsrSwO}#+#{~haN6tH`7V&!D&M$oo&^xg;yb)kT}(K~IGWzueFD#w4#n2M z&+uyNI!ZYA3Eh&A-xJx%3Erf(-X~O-0WQgm-EO6@;5 zcw3>DCj4cPG7GwaVuEzw3w zGPnM}t)^u5 zE_$MlWJgGqcYA?o&3wEBrIrqXVhQG1{MnWCg_z3u732N{wiZ(h-vBgW7Hq)F%l8F^ zNfO12H4YD_GZ#(uw{koYniMqS%GxVRgP~j6rB@@e8g$x?Nh~Tf)`j!C_NFS>1?@k6 z)ZMCC-)S1sP)gE*drBe=nH|-Nt<8|x+;00-sqc7|;ds(3$O3ADnW&2)gRjWPLqHp8x z;AsM=6~;now*A**M244SH5`1{zE2gKXk|FsL@+ovdQPtHNlflfHqvNP4h3q$Lgz^% zg;O%|CrPO6b+wQ^#R-DLJL=NCmHV>Q`x30g6a3+LH!dyqE$r=4$jPr+)_&^}x;ngD zSa{mFwc>Anc|o?YotOALWw++Ojj+b+fwzrO>$q|>tG=Wqp%q+zHIUW-pc{GUPZGN2 z)=V?D=e9YpbIa-M0oq4b%&6VPnKL}^F3Q1b1gYYt4+1{dl)=@fR?3G;J7C+|j)`4r z8VMPc+Nj`tR5fCk=Ft-ugMnn^P|%E7={if&1+NQq&!fYv_o)aHwH4`1?^W z#Cv9pTM5RsxEa$yJY!>p%*+YBA`}tsWML*OVd;a+@6fRh>}0;CWyxfd9{jTN=|FW` z#ZGjPJsP9FJ`ile?hC6_*vL1K>)vze-lk_kD1ce>essIZ-^IjGL$VUrEtUXWKIt`G z_H#7zaWs54`$-tU6NM zyY91%v)WVp)zV0N1ExU6b1LNwLtF{}^Y?!ZT5?xzXe4Qo_mg>?Bby9eV%LHD+nHL+ z-YvYPF5(N`4g19nOkr^S%7?q9Db4*}z2Kh38H0nSj$TpPTA0B+1R(E#;@IX+^Skh| z{Fowpnl!;DK|%P&ZfPhW4I7p^wSm1|U6V-eaQl4;tpi_X_vB>Tp~FrXO^~rCPh)(+ z%we<$LWF{{vRswN?mo`te06CqA!loo3PzH-d~FUTV1C^CNf$Pq8-@t)w};OAVB4~p z#?YWr>?xTA~G5eF9xBdIyE&8eYu1-g=`5w?wiYGFDRdS{xULf^+75wYG4RQO! zTMR%pCmtKG(+l%isUOrTvR)T(iJmWWvsu{i2WFiS5Ygo2EZ?{OjE;qbJTAn%#Jtnt z9ky8=_0j04NSe<5K@PJS2IGeS5`5 zjLmN@9XxA1N%4NBnNOqV8oM>g<_<_Dd<2sC3KG@Z{-ytlt^USQNIl7MzV3py?hk@w zv(B39H6617MUGqbsM~Or@`j!Q5h+WU6)3$-ozX!nrb$0!1a^q?DGz>uSA_|ib@+c6 z0{=a7kaw3DP<1~%V5^AiRS(zJ;{G8aZ|y`5a&so7eD{q~N-5{CQiSw85kn&sNYi_^ zDsN$-6lPWmq=Buijo~xDBT%I}7SRfBc>b4t9DC?b{K4+UsTk<3q(>rmV2w{vz!rSs zeiUN{1HCI}+9YFpJ-SPb13awk;P$_UwiKIjMO#me9SVj?$W*B8DCkc0X$T;4KTxWE zNmj1%^SNCOlh(zR8`%xEy&SwL-?Gz>9PZrACW<0a-)*j8@whjV8L17a*wvyhSuDWb z@ZOH?=!b++xd?y5&^_JXoj7o|&F?t*FV=79kHcKDn$-tSc8+mz<)wuClCNm7Cvq7M zbV-Zc(>a_2(%tuf4d^flxB2CLffK%USZ*hk{_E|}?9tEN@!gBPm;!gz&|J<%(BFSe zFN{${j*j*+GcnPE`_-{zkB)r~4&lk=1Q29C7?$-@xk~4JxQbw5VTsDg;qKkePk`sH ztV{%f-bDWPV|6{BCfs5jb)`trwcZ*ee&Hj2MNGL)BQ&C~kJTnr68J=DqK)SpOXHiib4O?!7MU)aY6 zQDy#654?R_iHB`y+0WU5Su*jRC-CtddRhHphDA#yl_D&OZyo$;IdOBjxB8If_vYzs zd_38$M~y<}jyFHC3!zKXr(v-Ck0vAx_7w=1^`!BvpIny)zKD7=)AmbYwXR0Mp`1qN z$K`ms@ zOc3;BZSAZ`ohzfG^P#=nN)VN<1XD?!U;lC2kCC^t__Mm+A6@5y3ukb~zt~--6lNPuPBl=J;UY!#$I#fDWK9s*`F_Lr6rBGWV|8#^J}}1FIHIJnA2WVl zsh`nxxh?9*CdHF6=ch&3xWWMaC`_8gppEa3OPEf}9buK65iv6L`MguGg-o}Dub#o< z3!8<>uv^xI;TNg(kJ=SMpnNo%eTKaN{;<6BvWO;;w+KM$q)G-oK`1{IhQbB`e#Ev1 zE87&Gr|O?(CVlzLd?odjC~0#)LIX>r;dc;ech6FuWo#sb`@WD)MV7|hA6w5m`hcK% zRpz6<$QAfEQB9lu$F|@GX(5JxM`VqmE08ou9625e0@4gUe2xV&Q!`PZYyD*9UV=Yx zw$L*ZNJ3s6+YvQ&LZE@ADC2Yai6=avq8!KS%lb;S4n9j`F=4U(ggwcovl~hq7(FOr zSyta9f^uq^%D6m{!n)1n*#3=#PvBVX7$nz()E#R{%y!~rf3)H2l z>c9t=DM%8P&$lhSW$R2?G&6aO8&^-S2nK$Jgw>j`Nfi>izaQn18Msb_%m;yrf-A~F zs-9Ss#Mz5<6n1C1)#DNSD~~+6|wL$wq^@e z@`_t^8G>~qB~+)S9Rzk7f7Y^6_;%_V=N)$R_tzmb^F{oW5@nFF@MM^y^-Q0WOpbm44@W9}N09sx^BkIc$Hk64iVDvVz@7H-%fTn1}?{n_6D z`KvkDxdu9dUwHQM^x;BJ;J5p$pZLc*jm8Ro0;-Zx`Ho1$PhhD~8mDVZ-DcthryO?9 zmMJvHjiF%e$pt-2$zpdQMPo-J zTvZHm+%{L?^_FyC%4ge-7wMA^j}tg*(+;1eS&yj4T0HNwTQ#l|9JdxrL&R}*90l0W zS@vzayH>KgzgLjZVW`Ej3YcskJx%M~3sSzK=(bvwyaW&UZg#PA@kgA!xY{zK5tmEXm?}J`zO{fVCVO zh;Q2{S|Ci;+bf2tQK=v++#B9)*(D`*c<^32EvEnWm^GwNJrs|^WbyzP-ROW57(m6R z#4|@2jKEWIcgI8hCWajBZ2^M_&j8^D904ebi0b^%J=%B;97+0#$cFe+Mg!!ii|Pu9 zcdjTgAr15-=&Bthir3;qH2rJ_69T53H~`F>dn-TAJUc8}p4h9GqDg?3HF?ojy2jO= z9^}T)z5+l>AU&lb_*4FWV52JfEvZF~y*%!3A$<007BWFK|qv3jP+s}W0lT%qKyi6AJ zvx+fac=CM$zgH@@sGlD>AMvTI`SLyxgPdjT7E?nC2A@DDdY}|CZXb|1bDLWggVK!? zNHKLnr(5%oJ3p7x@46W_0=XzEq_Sv1;Ua-s2rultm_K^s;b=anBH?#yr^h$@Hkqav z42D?i(GFDchQXa7jO-%kJgaJ8yRBo3$l8|&*4A^s$LBW+K`)7+2-M|%P3@@Tk!VqY z!6Qi=F$+gFkYK0k5`y$K6Wqz>qI@g=aJj(sxwXA?4e7KY%0a|$3?A% zZf{y!XJ;CU264E;r$}~%RM#it^%~cffzWWvKMgR^38ipzs#2RAw|beT50Oxaj(+*0 zp2d^N`r=bmP@wmDRZ36hJZJH8GR)}GIt0Fz|FmbXwC@PBBu6-|i{um+myDMs#8B?j zm8B@^^{K^m{iEn`E3~B@s^i`C#Dr@uevFaB&M?{vfas(xkPBM*tGD#Repn?*y-d!}`!@L>Cx`JJp3|;$xy6FB;(NH%}aVO4-{k@uO5A z%!P5pt^0pc6WJm>Wy-XnF8Z~fcPF}OQ*Vv)oZO$rXx(pj5g`u${X&I;k(Cit9L6;Z z66(apNi%#K2!!kVFaw{?htt=4v-~jLwBG>go1)1#dQV8=%|uDmr_uc#y4?M430lS> ze-WT%LOzJrCZmf-pgOwy^V>9YZ^GeWa>pExMIA!KXfa~*W!D@O3{lRy@hlhW%KXZg|1~@%Y z`m!4dZqv!>@20IM)7LyzKa5!mX!m(aCF3@ELg7phGxCUQP)^Po#WO@`R0V{ z3DOg-wqi^6YIb$4M8>lj1^<)c;TB*Q5h+t9_Dc%>eAKLt1zvKuJ%ZlpcCdv4Aha!W zG^$Ig)#%|MFgl@2yel(kB=H*}vu-O-gh3lSFsqY4N-K;g&dtT$!Pw7Kz<96{KF~@D zNV~m_SQ<(TOXHAFXhDL*sJ_qCfx8KMKTxBzURL3R zr-2bW`8@R1ZSYg*$~(CU^-pD!H~MTWeHT+AN-dc0@vE<%!(_=dXoUBa-6H*Z&Q2*y zcA``c&o9YvtJE>&@@u%F7{<>r$2ECO*@hg9~av)&+a=v3`dnVA286CzEN%ey9|#LeTk zg55+N7HurxTQ4qr*+#wA(e;QFl2mAfQmjH&1(&s{J|zA?hj(U~A{^iC&`eI4oYm9ISiY*p;HIFpsFhOkxGhr83b*VKcuFUl;Li*EM51@q zEFz#zgQc$Tp_ir|S%8}N@)gJE@?`6C0*}W0l`@TgkFstXUs#=mMt*e7V&-0bX)ci- zx@HZFlwn^YHfJh@nHh%rHpRu6N0QV)OT&4;4^#l>QZtqLIYmMAfiStCI(Z7L8Fme& ze4&J@Q;ZO^{b_D`jWxR&nO4f3Rdk4v+>_d{v!1NSJSV2`$TeufZ}_i|fruY_y)k27 zi>j()p7ei?8~5a-l@VZlh@x}=?XZiHOAjgt2J69qO5Yt}>K?tvG*teQ6GNN&Ypce* zE{3+H$?@ujYt7e9#<$$&oe#fn9eYT|{2Q-3HpWm|-%g!S+L@WDnqI5|SWVH0vj%@Q zni8#-077p19%u0fc~@A5I?D@|lh zHN~3uy5*Adm%7f?)iw4q@O+{7!i%DzqY;dkZPVP2fEp9Hi~i zyG;#Q#jwFWP{DD%n87D7@xrbM3^-alNpqMclG)f&nhv3Xo1;RuqFvDO? z*)oKF*4DJ*jo3|JtaxD$z%r&`3Vz@0j6TB(|NI=_(mmYuBH-RvZAT>)pFM@Q+U|8j zKQFu`Sv=#H5Jp;|c?xYxKm0HG^xp|(a`_MjDo1vu%eKIcoA)lQ!K0{;$0{Dt0}8A} z!6aZ`$S;Z=<)~6O1^soo_m$(a6M`Pu?;P~>Gj?@0{dav9EQ^Pgi(-DQZoh$Pwl7>L z>(?H?ogWrHl-Tt_ggu#`G;alXJzdY|7ZOEhl46`ZOD~@EEG#~cMTJrE(4!`ZwW;{34aZFRz$6yBB&aMRog=UM2E6AIke z@7~s9Yra?{#Yvel^A?U(&mIhIRm1fHYrahZ zf(66;8~tGK`JZ{Yoc9YICj2|U6QJ;g6WDsc@A?8=!;Mpc9G+7T48XxFH}cjGE@E{U z?Y%+vP|74Yav9)1elI^{7Up$Rzl)^b`dJ(%HTQUQh%;Kj5^RqE>{lHGsz!h38epCh z7&kWw3A64o*C_Paowj^T5<^{%3Qd<{OPo9!6-k|zXDqOpXxgkRCp;88jCs$-o-^jEDlJds!UigNEa>{we=wMi#?6bX~yYAb#py*mS{Ri+UQklxYHUG@E+lzX%w^ z;hgF&;5;be5b^f~@nC}l=aHzbPq|}mH5)p$W4s(00{mw(t|agtBAo;i4E7PBv(lt^ zV$c1nfbTJh!LL))=Z;K}43FCjDjC0Z??;Gc9(^7+Z&p6z!rtW{kR;_?oW`rvzbi5m zfi}a+X4TgQo#MV*G_SRyR4Msx(4|SqxK8 zcd9qeTUcCYt@>Wsdry{eBd72c#$}U%KYz~B;^0?~7x;}!L_P@2Bq+%1#bYO zDdr#?m|fg#fk2P{xOu7VMUq3^2}w4~hHebvGdW%~TJvZ8Vw!dun*O^WYiXHnes>bR zVZ73w8={F$e;~`r14WJ=E+L(`7QSCD!bDe3d}rJ{oI7b0Lc4sUjwyo7|1fLU5wLRh z#Luth|OM{P2?T zL{474=XXz6{h#J?*W!Mb_~NZp6%cf2p#zA)2U%M&QDD5IBUv0(gu~TW!6Vs(nZ*qe zA%612ck#YasZ)hUwEYB?FG`{46y8Xvy3>u?(E0M3r`G|~t@d|K=?y2n)fyT^#VRO} z01(p@*X*gA{>|T1WOu8|d~&W0SsbfzCRL-zBE3MAndh0XY6$Ifi@VB)L>O#6lbllp zxYT8o4GaT!s4f;BSOP7;QXPa5G7S+M4c3kp#5JSb!7;5oLpWH3PZf~T84vbOr&E4( zu?^QGH5BjT1>K#EpYEq;W>Y63=|&PR>y&C>Vds*`%cvvJf(%4;W8RL$HeDSIfH6E> z1w=YaLWL|)pUD9JE2g4@o!kNSt!I8RAhet*8n*nz1iqWz!rgTX=dS5GOJ{_LZ#jHV z^q7G6sS4o*qW=^sL8>*7z5*3n_i-#hBxw%@gpsQU4|zhlz~*1M@`!t4s>e`#w<&fO zzyzoW_3G|MgxU@{#eoZOF(gsGp{E;_JJiuYcgEtXFvo88c#RElI2v{A@+TaP%k${I z=u#=Js&Q+?j*{pNk6>J%Xb$6UX51QFO~~(D8oF2Ayx!s5Pe_myL!jX6#ye zUYinaQ16vz&#j(S60B_eo@$?g!A;xm#>Rt`Y-1v)Q;|VkP6v^@Vj=O`rwIZ}u(ps45`Yd)N|^GcJ-bGTGcvhB6DvvV`;8Dx=2DwSiaEfV8`zQ+4GQ11zWI zR6VR=>EketmxZ?Hr&+X|o3^!E{!HKE*5$(yKe2W1Qe#JmiIE%~L}X146N^oM z`zeX%*(56UGKpz=o(G}6vZ{8Pz=Z#Wu(v%RG-Ck1RSXP$L&l!8>nw^hc zQ)|wCH)^E3kFg`RXE9)p0z4#XGtJ$;DZ88U$;Q6g+z0J14 zU6KK~1=Un4y~Ru!+8B(}U9{gXgRdo(IwQP{-tSXpt@1vOMjbCJy)}5bq+@B$C!DG8 ztX(LqR2w-mIJQFASFxeBo&$ZT422ZQVcXNDTahf!ez{KZGRM~zb&&Ek%zn;P2 zeV^cwV!m~q1rpV&1U#5comK5T_&cFV;?YtP@oi`gZ-iVxTKDfMgkA;pN z?Ta_$YAVHaEQd%nc;q|LBW5uPxxfb~mkQ-iC@vp{sk?5_=uqHzo`~a#0_HaE8jfV= zw=TKz7qbyuT&(vZQVfU5)-CzrY1mQ&4$gkY&^T6G;deu73WW1i2O)Ft@wLK+PbP5i z02+xf7x(ws(eRJu(XuI523W&M$#RQD`xPI9sig9O?c>R$P($Bz6bH#tO27RGdOfv3 z0y`h1)77V)&p#_7^Ig}Ekw5zxSXo$|_S@Y1B7wg^d$zV+JSIwT&jqH&JIEmGwR3)X zrAH;#J=aMz|8Z9uDoU!k{_{2Tzq9OyrJGy?Zj6baGg4vELm|825460nw?afe90Nja zl)o?&GOW83L@*Usz>RO#%^TVYu!V|ZS-`;d%)U+C$f2KkkJU3Uq!(O%y3}!sjbEKB z|9X3L9As}Ssw0bho2?^7DXE4t`2qxJQWUcRX*`7M(!x}~D^E%mH}Si8A{}2oEZ^o2 z+qa6ZR503M*|yy(Qni@RsH(DGL2Hjy9>Nw8L+jO#+XY~Y5>BRW*5 zLo+XX8tLpRY_Xn}?hZ~tgLWJ_v5(BU{_IP~_UR`XqevDv=+)!Fy z!X1mVHgb@q%;d?J4*o?Cq${;^i#HJQG;OLEle#E6IhWo#Pva(rR^`hOg90KISkmnk z!xLdHPFnJY(u`Fo&&T!j@K@H8MP!S*oNdg=RLA)Ix636U zAMUQvM)*_J+b72#cxW}a{qgH2CEJo4yO!42^G z4Y?eIX%OV(3B4R_7zc>;piHC$VCC-^*>io@l|{Mi8xo|s<0Cood%Qog5Q zd7fvkdozCI5ioLoWoo`{0`N-{xpO^A>2pA~IgC$)U~lKk@pv7j0qRyHD>yI#s3ThRU`H@`w_a9PI2}`>EaI1$Nu(;M-oK%%^2L zN#i)rS$Wkf{IirtSx6;h@~MbvIr(3(t`NBb3@B|Ip%0zaBV}T`aO-19Abt`O_Ivix z2vauLYZ(~LzeNXldi4wo{eZ8%jAq2j&Cv&UEe5>bs(Js-&%g9@UlM?}!HRZ&z#2U<~n7fl?79clXoLVDyd zjTIYy-^oc?M?-pXOwvXTBaY9Ap^=fu8U~_t@4y#DK;}MxCNL#scdMzZ`$l>8Dfo}# z^dI0P%j9&Bl9vgl=>s5wkd(O;U(INmJ%nVrOOGYl{PhjJdI-PZE>v|E);A;FBDc)s|t2ZRA zsqt^qZL@`|;U=ibZDPffS@@tgR$360YJ#}gK-FrG7yFzqse7~cbF?bfS)LS-{7E_e*c1) zCM?0h)h&^x=%4agq@JBxu#d3o7}RAyOleW+HCfycX$H11c#JG#7)O(hx$nKcK^Ti* zLcr3{!maKs2T%-le>`IQ=1`fsLJ4o~En8p`RKlm)W+sW^n|mmz*Vq}*p%%UtnYMFWOebVpZI9etj z4f|Rm8=K|HN^r&Us39-(k%WqXz9RaA8KmwHLKy5OUBX_vn;NV$(ovY|mh8wK#^)Uq z`$*F2Bq26ERbj^kB(%5g1&5*cMMiN>_i zV~2sJD44Xsy3}YWCJWihx1K&lIqK9Vpn~gzLpqPLgfY?*5qH>48ze*=lel4X~ zLgpFIB9Veg4a(1A3?@-1$61*mu|Mw+p$ilr?F7*W1H0^wWfQKiaU!<_U-}3h#@*H! zx!YdBMVLreeZh{T4uR?2s@nPJz@Hak2D*KyzV-?!jA{={6AZ>?RA#9f_{Aa~r1%6r zRV$~sct9!TfUorQ2~YAlEG^EK2t7U51zTuDGf(GHo4ZM2`*B(*5roVVxr72uZ8|%9 z&>YkiALbBzb4#L7?D%*6furZiruPamych0YO>B+G*}_iP?1~oR9e8Od;AxX)BvqeXblNB z9yU_ro5^E=W{F zL$VEI?1&Pg*Tj*@UB61mXg>^6_&#h|{`QsR>^7|YohV}(8f3!aKQ-k6ktNjVVRoW0 zwIYOm1wxqIxIe;|t?DkLAO*VR=y<=w3ka#8FmJdmw#nFjXAp(&YLMZ#yD`D?@()eT zqBYdf$w|UU5)$;Ms6(B^Y-1k#Y&GJjh2yS`4Z1K|%8R38?MFzMp9(7dV7!Cys9Ox1 zDiO{!JyKX7=-p(oQhv9of*9|JShHfYqoW`D;dC{(NJYj31GH@E9I9GZh$+TP(V1!VVoRYw)^n1`_#2Et%;?*in*4_22xZuRZL-2ebmXY zHb)}%@jw)oqC{!3qhb7LD-=^xN)wF~KSi8Oe^p~)Vd9n6r1@IIVDpF2IBG6X?8yx237PVmxqu z{>`&5r-TGH_RB8-VuWu_40XxmGvEg3ScG%y|qKDrE2b)NlAh_H3o z`!SGA!emhrSm4$d!hb&5r$E65Hxz!@n=5>icjO7ub%|Vq??kmgScyqIEmEz^(dOmh zcGZ6ktcR$Wz%G&_>)on01*8b750%Qwre+*A_*aErRhMvjbT@sbgDluuw>Te3@pWX< z5)n@&246G2AGtw3_~AWD)^T&9Ek<|lYpoa7c+zbt`mTQg*x(#wyIigw*^qUU-;OK1 zIgbjnE({kk`p=4nki@1^fSh~NT6<3xao_@U>zMg?3Jp_!8pmz5FB3z6nS3)+jeQUXr*_mtd?y~ETM8d$OJ58CiP!N z=)v`(bYa(zH=kY^Pkujz5ZCgN)qZj~>=m3|pb3@$J`2A3ys525>bOiYh+mQVl8uIC zY>em_-~a5b5_$I-t8<-_=-#Vc!AI7C5QW#awOrMpG#wF#N-SB7O&j#7tt*@0`!{pu z%J}=tOeQ|!!uKeL*OY#kh)YjT1iJ=5hL29P9I%q4SXd&ydfyhW6W-CK-y!jhCy0_{ z3i5;w zu0?2)AqLaaFOMO$c%f|OWr3XxtM7u`Px?N^NUPDn(i5$(gDnuugVgoY*iy~SD-{iD z5w0DH@Dv#$aUDavB3Ep|D`zOEpq6^H&|a@X@m3OcJA>Gp??MW+ewF@b)_ayuZMim` z#R>+{u#y-}j{Feui6U{Tms@7_Sd+SD$LSgwD&U89E5ATOcRnq%iJZhe{RHc3+}sTp z#)F&`-*>HW+R2ciVoR}D?p`q+Osqy#$5IJ=fp^n&Dn{)OXpH7|7?V1ckj-YQ%=2sV zf8&s9bWd~e5|)p6@Y?g?ZPr@pp--x>sK9sxF;pRu#l>4a((ENvm{lR5-mGby?~X(| zq5ak}fUxrpsF?e@q2W9N+ISe&=(q|7UA3@sToAQ^*WMdBNuL~C_DEA2yqg7LzUN}* zVo)fEm?nb{1gk7yw6|FLSt{Jf@c`R71*E5j$?!<}`nEeE>FYo*0Kc-m(C6xP8)w3B zW0}INAP$!xZ1Avf(80^69mmCm_@|gWy(tC4OJsWcfDtwK53w}j!RPvf6Cxs6BD;j? z*`0w*{xL^qc=;#O2We_pdE>+^4Iak0IAw0Vg<{n_E-zO(@HiI=4+pxD1qn=FR`R3- zDED(zDcBL9v)+EW!*2K(`(q9i$9|abSo{kwAapXPozdIEu z$f?;6?x#ZCGve08ga1Oa{3e+Ehex$S_m89d$D$L7i-&ak7NRDG)cxuurjzly&-dwr zehQCID%XUVHfQu}Az)c+dv{UXtkf9Dt__Dcce07_t(z1J5t-gol&$$uCONF+#@xS# zXZGz)rnmSjM+WHYkiQrUa<915L9WbZD_evDFy!9u>X(o!Xip<(nu?ny3>XBfOI(wpw$>l_H414<@2OW+@pz(??S4mATn2_oIlTyAy=lx zBbT!9_)bI&If*W9IZCXMk-bLoQ?vNfYIE4igk`&E-4=1jrD z;bIKBO`+`X?B8TumtB1e&epf-Uf1_@4ho98&mTjjTBvNzDUBCu)0~{UHm!spJCH`Y zD>>5@2vjT!r8<$hz4CtV*#p)iq)8YjH9k|{{5m`gm{Dugd@bqvj9NOlqzjpgI8@J@ zUy`WbTpb=Ti*OU)Rofx_odQVOOeefLbfYg%LL2L+43eFhz;R`rp=o!UdHa%oZ;x*B zS+2LvUH$sHagUi#tGzWuX6Yh^=F>!!p(jURt@)n)tDg3NVm-{ujcE;Zp6Z{F&_O`F zY6(ZO(t;?0gDb=K=7dX5Sv|1enM{~6slEVvGHG<(*Fl%YUCb#@Qelae9}6pCg0%1# znIIVjOLVeOh9N~{^rFa&X#xv+z(*1mOmkZXhUqc-NDxz%)lV7Hcu90k9^T_!Hog3v zq$?S6jf2LW853`B;hhDB!lzv7sn0|_D5>ZtM{}0CXc|;LfgQ^hgwS4QPWyFEcTfMQ9$LeHPFTEPzlD6ZNL}IYwN$1`$db$i^7U zbtdrxtGu!k>+0WnC9l+k^JHQ#kxO;vGsVxMhajlEFNemb9DtMb=>r=@w&!|u!?!QR8b*~ z8Hi^hr22$Dysnykb5;0y6_O1i3hd|MwLNglr8bfDa!04%q=SVuvOiLd#ey}CSFGk! zwV%ZK$oU}F!caFG=A~gz2-L)%3XH$HAGuCvA9IRhjetIzmL$gZC*IhDNc?>+!VD{N zI$!B^!j#%nwB3k{yP4)x?H~VUU#iBFa0!L|Z?0r=@Dpm9v@aOsM{e2__3CSQHNRdo zzlrKuM#b;E|BlhD^d{$OS_xSW@C%)cQ=P zH$YO=STn$L_MI%jsWQrAhg{iJaSc8zt3%uUTJ*E*jK3CeRr(qP+Jg z!%zqJ4Ty%9+C{2g&VcMyIMG*5sZ6(iSx58 zp{B0dVf&t6dHzuVT}T zqx8#e5X}6q^c=_B^94 zJS-`wcREPz@iwQdN9WO4?M5YICQaDE08+?mITrW<|ENCZGXsvik7Py-H_~MB6sd4v zKtjz2yu!mF3j`*a*BJ6SuJXzV9u)-!iGjFegURK1Yy<30@DNA)^>T}`wE0(DTsMdS z_YB9zaXQ^tfdZuNNdjY_SI1y26?3>5Je}b(#Hm|#ON7z5t#0%~yJ4SyXUs=Z+3L8o z>*VN=13ca;HiS5pH4%@{%|eQ!f;ALo_Q_L=9Pb5i&I~9g@}tq`F4w^>zL_%*xBIgm z4f6EA9ByJe)VV2kMtjB47Bi9yFZ%;Nqtc+GtA=;p@KTp3eHaPr4&`#8sF*w-{qxNZ zC3(+<@Bi{f^J(77rk6xobhsn7!FvIj0#tp09+Tg}+>2h!w#FXVCywGE+hnRKVG05ksh1<;i%9Y71+NxW+ z_?7cP;L5#pO&LHBsoY8?xSMUA-A@S2x`R?o&9rz=;@=}al zf~#RuY&AgHv%_X$oVg1>RnBMV1N_y5DxcSbeUbz46+5U|iu5s)Iimq;c#_u6aCz1Es@e{G&f`nuRZ zKWZpbSoKMDYo*j!)r01xF<9q3?J4Ssi>co0yER*@2VVqoL~U$#`l}!XF*8e@&MJqL zzuvq5!f7Ti+FMc#uRvBNavtw!pxHh=SjazC4u6~{`C2L4fcwEYSek-z=`WS1J897V z`MGlOF9|^&XV@F}#;9xOZYf zt3qFxT2Q^=4Yh=vOz194#r&yvnnWw@Bi>{I0i+XdL0V;K8*7Zv2WvcA>fzz#0&^kW|RaCf*9hyk6HAWP^032M9NWY9-@=Tdi}@!R#k5uR@)a( zD84j9SgoQ*R|;-Ttn&_!+Xm*ev)-BhakKW*4-b($S-d}v_AbdP_~+(K)7w7%=SRd1 zr!3?4@wF}q7PoPzHJ9}q*KS!1R9D+EaQo9DcekUN0m4Ff@J4VEw9cgv>}4#RBoh0l zr0OBGaL$N9Jx%xJujm<1!>jM>7~Ypq`nyERSLXdYXu!^&^3Dn9>(p{$zLAkc9v#2? zJo?*`_)P;k+_6|vegf&*0BaI!I1GoGaM7#@(JARb=SmU`65`j61y!f4~Stk4~!qV@}YRs2192 zU02!6g;3?%fo{GXLU`;A`XyR&ecw0J2-7qD%w18Wqch$H(_4|u-scDiJ-|C2T6nNg1 z9csMww{`nRyN!#-4ed{zOWnc|)}Rl!#FDhR=)sR)a>gGJzgJ6dHa(@3msgd1shDbh zO@fa9MtH+vQFpAoHLLl@H7SPo&patu#I(>|71S_OeNRhF-2mB3;|4l?{vfetSlJ0G&KSU{??`msw2rq(# zQsBB)-g>7UAZ4*yTgB25o<#o3ER-?bDEOSx~~Nm1X#wegQU!uvq=jJ9*;Mf;Z`zza6dCCZepZRhKH#ba*&z1$v*(aG^EW z`Bo@&`YPQWd{wF87R2@vjyqGn_5gK{4XZHwpA{@^#8SpKk^{DYgFUeM=?p4Ek zzsp^QM~PqfZM#ZkKL$6wp1DC5vI?*6d9sv1Q=j;2Z>02aV9qy`3g~{dV^GuPY}=Rf z6cM8m=*&BXoK$%xF}%&bB3;aqT{4k6KP!=R_1El*jKsk(C9?FaMb-o+OoQiP`ND{9 zU9SCR-<#h`_2*Br$b1A8VP$!vbkW>ibmdm-aT||;&E$Z@@c8EI!6qMTX?gq8AOdZ# zckUK+Nw4*wb=^v6A@rs)Eq;b>FD|cQJ2F<;#A7P3-X$SK@#S@NAWys99TI-!*K<_3rb0y{ueFzPjDJP{7j&w02X-Ff=i6c3 zB{9S9A?~Jud?jmjc!h*B`HnYW;UTT;FFwp3fj0sb*1v1_o1J?6DuJ@OY`#;Ib?IWL zKYrGg+&Uz(t_H|-s29$~D?BalnvHBfO7#->F(fE|G@^k<^2S!2&5DcO5bM_&oBe_2 zHkqI%pI`@^n9w=MJK)Ea69qAR1Ua|?R`Sno>m5r*6U)qQs(s^?HOU_N%3_Wcj>**g zwrX)BjS@P(2Ujy>>9>H#z z!V&8}F-LLva+Fa%W&)*Tpm^}GUH+=j{l)j+`HI;WN}mpVuN%d8&W+aEvAyfnvK))S zsrtMq^-*6$cA)B2q65wsB_W+|&kMiUG(1U&doSj@*?eA13ff2LQRNjGgoEMkyD zU6{ab%8Dv}Hk!@BvQfwX`y!;cS5Mh`%(@P+H z<+$2q{hQIV;OJp8!8&ACs-BAbZL1oD?B?Ibf4#A;jt-HUjDF@!Ytw%tXmOaY@^~Ty zZ#5BFw`o&Kok{U?1L}>L@Ko}(4nEfEy@Gz$U59-`{lgF8@W}qE5D|UH_4TVcUWIY= zqoft%i_kmLs^L8ud58w-Dm4aWZFPaHWg(#91FN`i?(~NG(Tek7?PG_K*wHsmoh@Eo z=RA!@FI~cPCEtyoQ*Pqduf?;HhQTJ|Ho%u$r;xkk;Jg zZpVp3GP4KFkFJtuL;tpkQAqK2Q9k>*GROS;ZE;|?t5HD8*{2!yk2$O!V^u8T zUZ+|9Q34whSgXbQss^^f)19r@U`3H|CaG_MyOdFVhGe%=XxTNw>&qZDqyMX1-1;m} zt&&kB&|+;snRVls`cdcNaSuWKXcAGR>%B7S^+E|x%F&8c6FQ03rcep+r7szLx7F-2 zuKK3uL5O%*vRRsZ`>JF8BC3P*7A7PmDbsuU+>QI;)g3MFPE?v#uV&RyH{;r?Gki~H zifU@CP{EruAPTk)wx*yDWuHUbvUUC(t|t2ll!-qKEVYVXz6YwQ+&NOH@&A#X?$cs8 z)Zb7V>|I|x`=QAbpwRs~T;CIMU50=5Jos~SuWsbtCpEpM_Y48_rf)rGsUXqTvVnK2 zR-4zfnYcuMPKq@bRRD~G(U*k zf1gzjav!$Rk&}JFhZy)H??u67p0egYM~t@qPO3MU2)+(gJS|7FkFsuSuUkn!3df#K zlYi0dPTap$iJ1S)ooUA;V7=&NthlzNG0qJ&eWGLS8Fh+)zP|n9UR9*#sN&&O8o_X% z+83r*h2}yK^w81bgqKs=FZXsBZ57bwyttpM2W2N@`*wa6j!f~Ydm0IUDQ-umZh1bG z6*d52U)#JY=1a7_oMre($%z$Ju@?99e{CO_QM^shh}ML*zC`5=XUQ3PX5T)z_sH10 zfEv7}>aXMnJP~s^QzrG#KZjRN{x~z3M+rwWEthR)NZAJ|#+;w@+gslmULNBk#^$vl zZ)$(NcVVF+0iX@9{4~~YIQE;#j1~wVI@@ZQ<o*Vbp8S5g>b9=eA1!$3($+H)h1QmgOy*GE-rqufCqLBpn7P_#aB9`{ z`4>PWj^92kw)+bq^<~WOa{x?k9^-2Rr0vtRlH!WDsGJ*Rziw6B?A+!!3%KSS=^eYV zVM+(PN>A&;NQD}jvU&5%(^odS;?#v=yN}%E5y$glp^l?WFo<@}-=4W-2aA^u)oih5 zT)R^U>t3^#D36a)Jbz!S$PhXyO4j>#rv+p!$Eclj?%h9m51T759UlLw{zQ#WvE|0! z=^8Dd{;@wbH2%ZJM>$!0<(a!=_*S!c1V^hi8HcWO^7p?GvOQ_`EA&BuWC#Vyo`nVw zgB!cXQ;uKPPaixAJYgK2xngOYuqMC_>F} zWd!CKt`Cm8cgH3XaWm!KE7@#6AHT!lxfLz%!cvzOfk9IgEdN8w{zstf{x8&wqc8nd zfj9i9`N*#Rjn!}ep|QHN8|3RCK$2=>%>V0R`={85%D}285!g$C>pw4^tv`qapsXOJOrhZ`wW5 zW~y(yQE2~JKgjbA#h!7wzAVyJ9y?SUeGPHGp477_PE7oiV4M3n zr!h)MdSgoLTh6DDKL8srfGa$F%=o3tqPkuEq|agpJmNA{<|e^WYiFKWtxZ=rC+Roy z(a^^@e6)RrXt=Rvh|!_(y(EzgMpk|7zU19GLxZ^P;34TJo!v1f*p3a^L__ZzgeOmWyU)jBiv6<>P zZqz8~*|a)Wx0}8NvKdtIy?EezOj~Z3X%MDWjchT5Chh`O&EW;8-+;>tNp22CVYa&8v(+V*_>~A5>b}UW0Vy-KkTZr#_TCJW9ZB zzvGD4%N45Gov16$(7)j$yA<%R00u|Z&g$?n}N14(+f<5^EJXe|eb~!lsA1_$U%=Md80=73#lsPV5Ps7>mKR@j){j*zv`aV<9Ki{M7N9tx&(#e-uuWz;MZVZ z3VeAoKcUwp?gl$Ehlq^)g_aENh|49E-cdzqb8oumdNv|7_e<@MhQ9>?RT{smDjb~KN7M9-YUa9@E z^a?23aCtT%^IF)CGSTU%q9lDM+UQZ18K8H2&FM5k4*}(aSj9R+sRT^3SA&CXgMR1@ zlHKkU7Sgj71~Mjzq+ppBF;894zFCVGAN zvSbf2CAWA zk2H>3ePjp~2>1N~TR?*`RTyn1oYVQsoStnH4&4^w*L7ySd4K=@3uGKn_q6BD|V+w6O*S)rt!J; zWNvepn3NN-Cpx$Chwn>m3-cCOSZC}1_-b^Kuj2FeH?*ulR4Ze-L6L+arrny0ujIf| z6z7ud{UcFNKA*2uKvB}^Nk-0ZYuDCUZ%5!`K2xOKZBPaHge{;Q9Y=Ss zFe)%fhQ02`i2sce${JajyepP1;+gGrh{u8+X{{zyf+-+5?UEz`Qz}8$-VuorX|xX# zo_O!k8_FwEkM471N{Zxk>qee2_FWchOFxPYi!sKY7tm>GHg=AHfOoYz<`&m`q>9sW zpGxt6IQk3z+daEB%k7_IWr*M_xaPCe>J+04y#vYnpqv_N*=swl)sZrpTZ40 zdCAdio8V)dtIe~hmA04U@#w)Q)=4i)kivKm_dLI8G}cDp#LKe$;YUukV`jf=snk@` z(oEM;Z>Ppt9_l4WW)BI8w-}3|+cJ(3-#&Pa+dPu_DFqePWr?(35n^yh8S`u>Mh#=a_0wrY>L9EnS@J# zs2Wbre}=9XyUwMJ)A`H|kU10c=9$NPI0*vLf>i&fmjrlsNnJqBAm~h9ZX<1O1^v<_ z>qg|y_5LLnVw{D4N0YoSK5Zt_x)h1dv{=g_W)ct33#{m4Id77F%Eb z$l&LejM?^Az?Va!!*vAx08Jb(>7nGWZ zC&i>ogiNX$!iaz@chd^$rNXjBh z#rw{h553({7E8W7>)Eo?yFNt{+pib8uG;9nfq@@nN|sthm8FRt#q?BSz>574EI}}{ zhT;8_%`U*ic{(;DmS5x3m(91HMS?_bDG;2~_nleSSN`J&Yw$_&WIhuPThaZ%pNQ_B z=Wfnq6y(D!~;V!rgBy4=2B2lDu7^ z{nxJdf6B>H1&?m35qE)T6rLW)aw zZ+s0{^**ZT;mbByc=y2e)0g_3E|!;Hi2AUG_4v6*dcDdG)>KkbQvPd^A>n!J^VEruTo*g*Z9!#d8wg zvo`)HcN?x3U77xVH6kK%*zD$IrHK#R$XZ-=IK`~^djI#s;8ndcp-)3~VdXf{Se)UE6(7^!11W`&87Knkl8s5h@f@6K9 zLC=3I&!}83=?xOB(rwr#Y7GxV8^oa^hc8W{UL2JEUlBsw#HcxUf(bb`_O|U_dU|H~ zU|rn_o)(Y~H~Ha-{r;TK>7l`Htnm%eK#G@XQDSe{rYHNBXn(l@kQFWjFyO6ziyURv zNfUkAmvN($WyLK^c`dbPm3IH1;(gUcdT0!d;G&@hFzfVdhWF{ipT-_SIe#ubgcky7 z{kkqwW7O>kQcky=P3I-n{_#8D3mIh|kN$n%>hZ-Kh{tnWjj5?t}1TSzz`Hr3G_-!f^`+dWnVEp)DFSDNEPaVy&8C2Ss`<`G!Kl}$1QZ>?$H41MhzpbzL{UkfSv^dHoSVd*c? z-TrZZ5n5ax%$N0|Ee7@Na>x1J4P|lZnDx-mDLNwOYR{L9`(^VVIdVwmTKmF;lwQE! zn3!j{F`Kw%Ro^f?T>#strovnNblWns#=d9N$?Dbd5NgBNu3p*vJf+`cT@i-G@=8yD z9n5;);#9wm&AnbK}0I!+6Y%x!?P>e8pCWC zgACqPbO-{g2;yW@DLFa&&g17#Y5AR)l9QgM-RU=fELw2%2UDrnj{}y~+;_I7)Guny zWzgwaHcEMVZmf+GD{;nLPHZ_x05lEz7n6MSnFUxPe7$# zgQ$elwv-wSQdMHddPpDZEPjvthPqT8?I?)~cVXV8K~yy>o~N|*x@!ezGrY{T@$2@G z?~x~wInvPT?;!AHokt1kQc)d}QJ<@|M{T%oCg5(qtYEv)swO-GDl;(mHgNsbXPH$D zq~6P384EL-@Sl!I2)G1$=i?lh0Le3p9Cs+qv%4Q~6&9~#%jGwqfeZ;>i`#_Q-%~%~Byz%mn<#EyggRwDwte|q|)6nH3t5aOP)(_DVn!>-Q zT>!Id-ejGYUj2sz^lJ>8-)S$Ta-?a|=arE;=fC?Rd-?UNOCn&8Sk3M-2B&P~enPKq z!34j=E)Q0JfJZ_JGh8p6l;05Qv)ae1N)3)2`}$p-f7SfCXJ@9jaj5geyl@iE>(CN* zc7IiIWA(t})veSg5RFRvf|$pg7vf^uGg<1{8jGw>K9;=<+?Idc*aJ66_WpQ-94dZ0 zLc;ljl}!W*pa;yQ%|uLmrZpb6SbGqcw~`;`KUNIEK(?TNEJw4`{`#KBagf1^KygjWZDwTKZlY3KAwDQ*g%Hkf#GBLv_8r(E_o# zNeL-&%G9q;%Hrb1f_ag=1fS=^zMF^5Xq`-8BLmbSI~ep{pgv2cW55pfqQy5MqwyVU z#P*fvZDMZ*-O>sfaZ<#pPvH>(D-=F`rVpb_)YVQGs^8*dbh{O)f|8|tHtY6NaF}8K z@#xF*!_w6SIdJ<>aMshbuGbGg3WQERiPZag1!r3;-RQ_>Ayy{$pXg~uF+acjp(tnM z1=(f4Y~5?3 zINPtpcCNAGtkt!(&x=D$+kJ&pm_0IjA~V{COY4& zStvnxie*-Uv9RfW7~|K>M6S-1xU7r9$^BfIFAkcDVRu)lKc!`dCTlRQKZZD+{xzP& z>UloTZJv-|7ac_j29vlAG|<5zAzRJ!t#7bI+{gU_WcvZHC^D^=SHW&&xf2u7PZ8;V zDL>w)!e4-@-XFqokf-C9qu|(ubUqGv4ve1#pVjF?U8&gmN5Kq^+lG&o3qI(K!0ZY` z>GV-uv<$xYImvchI`g?@H@K!8uZCw;Hr#b_*)4ojYk1v0t&GyW-$TyTNvU%Aum80P z6$bYgX_zYudYpzcxoI%X`(NY13Ww)~O3PKj_`_v`c0$q6+UKcOl{OdON)l1BU^VDrnS>yvQ`dB-p%H-n6`5cBPYS zE-}+Mu96fYAMdqpCo$u?k(+_a>B1Qh$WyMM#sqVduBdUcodoa`VSx!ElbRe?hohu= zp4hVqb;6z43PJZpcP#N>6SGxItlRX+5#IpYhl|Fx)E52A%rDHw3mu4cgb-b;sw2Mg zCyh7JZc=33Vo=XQz?e!Qs%C`9yKk7at2_N(*WJ|1o*)e=&L7}=>74999nH^!UGyS# zTD<0p7Cv}B4j9**S3yi?WX*U!`6H6qrBO`HD4$M}Ww7si8y<1(y6|I1=@?Q24=*nR z(8&t)CB>>}?4I8rtz7a-=SW!S3Aea*?X!e9W7^9H5$XYZR&Z}g`6?cqezbSU@+_5g zt72r*k6T#m+nu{5qXj=$R&ocVP+nZa?g6|g(%QB19J>7Kcwdw6DECFp(5{jQExBSB7(b_yVZmXO@j<)Mj{6*;~Tj4L7H-CjE&aoh%9fkP5 zJ|uL$GZsl8+xCGP^GLAV7b4S)z{E!7I1q=qh(R2(hu8X|7ih&81iLlG%KpA^3i2oH zwOL;M(5;K%-%^bsty(9eI}RS-x9kIPlBq~ABOCrn&89qgCAjhV=dk`V_9WDs82hRU z2aw4rcef_=HbJ}wGRrfQqBENU>O6}f;ZR(d9u6j7gG8{&gV^c4)8RQ)+?ft0%1*l& zLLlMdWQ>0e)eHgTnoN@skD1{u z$P^LXv5JCp!9d(Og8dTQ;7(uTJ`npba5IJK#~!TA+pFwlwbA}q5ZzYKPhHk`30G%) zH5A*ig!&z2!Gn@AjD;11l?~&X;#CkOg06{`9^VJ$j3Wuoss5TZcrskS9#1~D_VS%c zcL%%-37kmHnwA+yle!Ae6d{tGpi5SU?z!0PmMc z-SPZR&^av(D6NLr+-CZp6+JiF2=={xUosO#UZ%#dCy?iQPNTicXQ+pP^@nLRUkQzKwF(hV4I9pTfmw zkZ|QVWIHcNesBzw*=c2n>w!ewH;&?atIZ45#*QBGqnA9GiGp>UgfcZ}%9;<_Q6-MR z$}!lk;lqk^TaH17=Rcb~KTyP}1)Dbef@2>uJiupE@hmToyjSjS>w&|OUONBWW{aQi zX+Q{I6LD~Ty%No@fb2jKROiK$sD7-(-lyih!J3@5o>X_<$<>dIGqbFsWkb@DE0o5m z;oBL-0U+6=q(ajk8pP=1hc8S?Lf02+^puP&bH-bnBn$j|t7r*u!QnPtoF&uCDkmd6 zY6l4~v;_XdHmS8f+yWNIq$PT~nHO|q+~23^O=hkWX$@n^UpQc_!oz7~dK#WBUWW8( z`f5$9zoh20y8;KjK@whsuH8)p?-x%Lp!~`{3bQ{Vwn5Y{yK}P^+gx>*tQmgUHzJMf zoX1z|IO&7XvZ}t}NWmD=*8))(eF8Z#14Xv|VU|k4m~eo9gM?2~6(it<8}Jo0lF+D= z_-@MA0rXUc6a%<7kV$Y}j5=t1fiZg>Frj*ncFjo(PR(plI75i(L%W#FrOv35>M!yl zJq_uo=_FO=1%XW!ACErd`t@KCym}&J7Fq>X=3D$9v1F=mk@_G!ZyChC9p_a88 z-$SazlauVBN(x5bzF_Gu0V|pQ`!x*V$#aPuF7QGNt(i}boVvOchE5DWl}l%MUs+xQ z_)pE6-z$XRuYnX*0*`MeZ5cx`IoO_MW)LBl;H?KD)Dv!A|LPC|`zDCd0&M-Q8IOxA z1B;IYs}sb%=1XIB8}A4gE0upZ$bMvAV8>8OxC{=x($+^Q4cxlZUNmmxC*F=7?J=)}J9U&+BwV`15Cm(kOu|QAdgW zMG^|EYKobiQx6&2xvAuQ?@|c~*N(HZ3YATX*Ce7x?JSu1l`hfiz*_PA)|LUWQ61i1 zvxG|F!BE7~Q~t6#Ts8YpDComOym`Oo%|1aKw5Lx~%tph#xAct5u`o@JY0T5jRfySe zs_$#g@O_sFIk1z%gaxof^q$MGvK3NSL$u(Wdk!wCyuQla(oBG3^yjd9E&C1&QpH;2 zgVDTz;g6T7b_9MSY{Ni>-v}c`C+~sCmdDzE&p{&IS zFA>JltrYkt5d__|Z6Dk(d&t)Vp8NuT4=lgw0Fq}B8mhR0?tgC(Q+KJ8oOIg}I&S44 zgCVfX?VaM0DU76;iRZye9POG;MpuiS;8sr;_l3z}X%Z-oT|#&Zw|FbXz( z*f&HBX;nUNx70z#s!AH{K0nnrQsiccV4&0onKbD*K~P|m)LIldw;;sEgBwFVeVqg= zbfn6_3PO?|RpaG@1x%{(S2X(p9o5NE7>!*(W{iIX_{9cOZwYw)u^9=cX0mCR#6rF$ zQ;$Fp;w#eoIf47@`~KvKVXA@5;N*QurgBGkLGQyp34e11L8OI{wFYgIu0&N}vFUen z2vWfXtp+LudO9lKbw{ZKx12!O7q06edJ!OW9-;#pohs*9&xz5E%MZ$&sReReEFZ*D z+zQt_q}hE}D;%I~x%O59LrdyOYuk*7JD~BiKID!MHEZ2C!Of7tP`_Ny9`9hELs=jx(%BwvzKzC><}0mG1qbl2|wWn+HXiQZ-q1xZ%Ja0Fatp4Dy^X(8JSEg=v04EMbfXDIRV@?dgd%6-o4=K4u zg0Z~@VdMrpI6-Stozu~+#GiLkiiGpV(jvIe?^CndB*2LPkSYCOa9rI= z+m7|%Mvh>`qupk|GXF}SQT;aVE_f#hIHqKb7*M4mWmOn8X<8!t>;lR1jnlMxwg)w1 z^h!Nd)AR(_yorO`&9~rTBbsRqXMDUl$AjZ)288F)@UZjUB-^W z2iM7eeo{A?O0W~s@fq-l{ zY1Or4T@vRniw%0)?-rn>5Ie27XJq@TSrqtri;SwOIJgyQdBn+NjCWc~inXp(nt-FF zr#7q6xlsJioiAD-`hW=<0&Aa_X^u<;sl!N3Nx9fJeGtqiE`|PB)Y5Y2rsA)ES^ycq z?;NLvAz>>yK#Sz>O$|Zxo57W2EuHHHMUbD~2}uPR)uIeiC*2BS3+`+pu^o;HYIFzFWf zCuZs`?=d&VLb{+2}%sM1bp5+OdM`o&E&r&Mol5 z8c0L>Ft8fGgP4LDed|APo{A~9=+j)Xj7owRgP73Mi~A<8Q7zvbcI4+R-c631FEZdrjXjJ)v$wKswXwg)i0Vwlg zr*KXNYDX11j6+@~_1u>JU}|(WkI&l4EH1;47OOCw44T#W?&zy8B2>wi^RsH%YO87_hUsn zY1YySVxsu&RIBS+(_RrKnSL%j`-qF~w;$B8(uKf%f|=@z!@*T5blq5a3NArW7ZXLw zrDP=UQb8OaA=~DJfr+I_QcRMaWSW{`uZNl9YSVm4L!F<=9*uWj6oXAy$M}^*&=;%dOr=lnkK6Y!a?Rg>-V+~cemd6+md-hW))}>EhQ<=9=S`=8OSWWryGR7mkqVo^^+#i-{sL~F4FqUkMvoZQwoKbaOSf->7_A6L6YpC4D6zz9 zO%@lNiX#yL=7JAx(+b$~ydhEcdICsk*)PI5(9Hy-&~GiaRX8XE>%y@nFBFE9*d8gY zrb@1LTC;C?rGa_B!l=5zUDqXu86RR7{MI||{8SA%#F1p&*I%-DNm&9&os3H9yr>yE zPnw}QT;x-UR{0aE@-c~9YluV=SZUY`_yFW~K4m}uCUD+3>k+2P=>vMu6OkxCe4X;Q zzPpsj0E2`adsj1#V_Nz#x$&V<@SoYaQyUA8i?3hdPn*4OSA(Gnawk#LhlBBsu?Rt1WgN+a#c zkQfJd>8CwXS$bMYXWj5dm8w}`aCHXfZ|7>Y>WoK3hpxvFiWI?e9MhVhaU4w>0MS9? z5=ItZ{9~d3!&l%IBb-L}k6_!PO5XJJNZW>krjc-|at5YYkVXbmT{K|KBYsjC@)T-O zXH1ZJux!&fw0#*6{^OTHK}rfb}Rpb2Ws|gHtk>7nFv30tY21xiz+qBM}UknS2r>?~7|Z-`>?O zsVmErj0)Zr-x~9c@rQ%xUHiU$60D8}gFK6qRVbO@AVI#JOZkMcvCqSvrSnYnh!rgv z&bPo;nx&@zoP;f_Z-WcLp+##j@%zlCsbrR#{rmx%JCDk5ZGUiq zD!l@BG-@DUTWzZ(X%o=22dEf;AkaD5u_{wxTMbZ>%J`mnnCCS?7X^|@B3Pow&LNe> zb>|CqI@cb$kuVS&S5i4FkbDd+7HD%t5RjU-u>Jg$Ai)BWX`C`s^({lXDjrNr&dqUe zD5m=o3C4&r>(HD5j|x|-2zEJuM&&iP)r}tce(KXi5C+&D`A+m{z7S>}M22+ECxJ~k z;=D{dr3U2c7{ZMd98)ulV1NkMx&(NvW=8O%)9EIdl5iGv)HiA$d z?f{rE?kBaxK}j`QYn)2^oHvDq$x*6_dG%Hwa%_{OPGB1G2A(O=OVfYDqz_BLgvFJ} zR$MMFslL5$<9iLz@qdv&*L%uTg)dhsEKhMu-k>9?^M?_8^P*OK7xmr85H3U@J~c)- zT4{hZeD_xY#QG+Q#U!)yKr6cvPRz5a7dYT^=ZY5;8+)zuG8i@)@Nf~>X2~k(e+xgW!{ZIDXV8p09^|` zX=G3&Kn|Q9ZD(&Lj~iVCW(F&9jqrB8zGO$;%h?s{nOYWtw-Xf>Tl5s~yeON)mgd|DjuK7LwbNF^2QZplcDI5vE z7*)%pSEG-Cn57_MHXMaa&0yOu$+d{m-aMcj8?2P8foXFYV?v|IF&U`KNGVp|o^+Dn z{j^>#qPS2R%5lkV`{t<(5VX$on{jyq>@|(XeVVG85R4%An{jee4}6Rg2oyHh4MH2)*?6+Q97ME@cc)NwnsM8O!QE_H zU2fQKeD_N9UHEp~6DSE6no1O^xYFbS&C2ccr=FQVV0C$x5Qg?Yr1zI_ST$^4Jd!gSe_q%OK+8$?h8&5SBz~Sz*c9k4*_fm` zD_G}GJ(1%+@swzD<3YxQL1FNIiZ-0N!r8U87Nmb7wD~yj_lBC473Qn4ptR&`>_5Bj z+p2eE=)v3t332wW$%j`qPSm*&Jib*=oU;GfY~H;gXIy+&JCS=%h^O|&-Fd2eC8(I_ zPN2z}bwRz10YJNM7e3q_*2^J>f2_o_$E<0*LC&8u4GlUeh9`k;d(z~eCZSY0Kl_dA zmDodz0mwS!H}1($N}5pU*L8=BrIvO|1(G;fKRjf1$Wl16>Mj7=4R%%H56pBk35^!Q z?CvFbZIuF}jGu&as#KUdk$}U4xfZ(RrGtG@w2WOq!mqne)5$~_T+C7Vm7q?BVRj^$)d%y5AO2Pk|q=)&4)qbSc=AY;HE2FmCx z^!Bg@4ox$+hjV}G{EF>_W^+6V5oDFqeo!;avc34#9N`Vg+!<|W68=0oxyxClx+I>F zC)U)D+?%rL)9lJGNC&S!gUz^fBxm&V-AU6$8bCNS!3PFlZV5TmxKi~1i|iMw@84{ybEF)Ovdhmb~Z%afoEJSobBTc zSFnfL-)*Aq$Lb~xgyMvFiSmX{#8)$4m%Z`s(l)79U%$e9lR=QXXwvi@;2VNIs0<9i?>4U*o#D)j2=xM=eOGViIDgsd(@O+oMwDnyG>0 z)hTBmYpQ2rgDq>IsWj6lK+!u>mSejhe-o%IAY zc6uH+1KUQv9FbGyYJm~PLp~K0Xr{;CHi70s$Uh*B%nKEjSKe^heu`$e9L#<>)c0uG zi=P8dJj&zn_2mq9m;3biAK&}{;LX{q%8U-TtC9K(GGS|K(!PpEMj}Qf@slHCVR<^4 zC~*HTOp(RhSb=^r+2%do&_%mDxG}@mbB^5BSxgHo3v>Hoqv%Cag+u^>E@V7X=(U z9yzuQ)UHbK?_8zvn3ok+DbA78ywi6HTL$%3bJbyUeDl#>evPKnchr|{o}PEe=xq>Uh@XwgG5e{OSrL&}tq`$9o!K zQpI~H{1#p%Ph=)~RY{6`4j|ww;46L~DlQ;|EQiN5kBn#fuyr-O(agPiNuY2fmc&R= zn#0OcW0siHyAV0bnu0;t?J1xiW92MCU*ak=mPY+21;YjsY6ZC7_V;%vbIv0OC);j_kL46B@yVu-d~tWcCC=uUsLK;Ia?otV^>$CaiN zdwL(R2%gRZm{&1sK+fF|GfmGWMityk?*rxy2m1z%DH}EW1UO~F%-%-J8gnuJE%+el z>S+lfU)1$~J}pLJWpqDlD0WtjHWd2b*04|z5c5pJa^-eolfWwSsVGv4q zO}1+*@)+S4tdSR4=NJcf0;l&B^XCxC{rSaGu=9U#XT!c3Ozw|3r6nT3tkA|@ zqpC)0^`CksqKkB+y~Z>0D$91-oC@mGk6Yz8JDpm8pM7`~wr)m9OEn&*d-^T2+D}eQ z!l`p`J~~cug(C3(QT5Hyku_bvlVswFCYp52nRt?PY-eKIwryK8v2EM7?M!SN9o>H3 z=ezHB?^?b3uUdW1soJ&oKGi>fn4wv)rgU{(_aEf5kDG%m@oV)^an6^b(jvZh#L__>SA~vj2>`Bp0Qs_3vXCZf=gx8)i>8h=2Y@} z8=B|g!u%J{ord(RE$Fj*Kd~sdtNLn+ zUro@va}nwq%Xfoz?JT6nj*NOv9l9F?RA)km7Wz0PjC7AupOOylokF|mDHL;G4 z16*Ip31fkXbljL}&!Ydru^EK9L@kx{@&QjJ;VX>O68_s)HIEzMFo!x^Cakg8QP@8Nc|EqT2R+_cy2dUW$0#?7lI+Kt#ydN16x6?6!^S z6cfmu%3@xj3vXkkrxygi50BnQ6=NoSxF2_c0%O6hBp(N1lxC|G{!(19Z5Wf@{{sLE zJq$Sk;gp4I-hyFpmXwjd;qRpgo?cI+9e4V}&_VKUkx}UaizOYAvDsfscd_HtgHNEM zwCy>puAu*3#ZDI{Kj_-p%IZ*|d^O-{_QXRL-;^LtYW`J`3^<-q$JGmJJN*xIvL?|H z%f6JJ9U#n=`^_H=U||e3N=4+Zco9K)daK?y@2;W!4=jJ})Ad!&z=}7wuf|8ZwS_-_ z(izj^OGdHHU3S3=^`bB{{gIf@?F1_WGjl;zf(S>(phVT{m-uwS&wvvBD0B#pE zohTP3npsba&;*^NU$H*znSKo!qivMSnEu>Etx`E`)?IsNtPTkV;K<1Arft6Qyz*m1 z^1!xhzfj<`)RR##98`m;AYd4pB&~o9@kk^^_V96s7}p45aI!$xucNNI2$Kz0E_gzp zkN-^Sc&e0n!f065XL9WeccJ?Uo@8F(HUdi8>N@semP9jZf`ZMXTs$!Zo zyS)Puu7?>es9{3&p%k%KjEt_3Nut4qCgyzYQGtSV&FSmx9XLd2g(#&xuBwEftJ1+OA=0MX@VX2<6YKJRYfVRv1X~ON zbyQWm*Vpj|2M2$0Tv2IzzG2(Gq}K*ya!jvj{AKhqc9@>s`xCwA#RJ>=A~?MA2kxo% z3g$%EYq~$dWrIDqnC($eP;eB)N2*{792*{n>wJ%@B00yfDT4$w2r2Z`3^y{@NULsx zz`$sQ2;0+fOA0Ze-~RAnKY&!iuTceluG-o6stBRsx?H9G=#)TEz0tqq42$JV{cwl~ zs`149iWOS?5l(y-M@P_f9W|V&GvMBd?lVAryUNCIh){qGFtm1w7ngB3Zzhd@FkiyM z!xLRHqUX7rrZY4)G}(u1+jCx<*EB}&pX60y$#~@G)M$QKL44L*>7^$Jdp1mVxcvay zMhf1SIG$nM5MoUEO59S;BPl5|;kH^Nc_hoI&^ zp*AieI8`@j8b5$WNg^b#9!hcF1>%U(&KbhEX_`GdJp30uU+$kt{j}mQjA{ILWZ(W9 zKK&G>D>;~fpBR{cOz(V-(s!WBXKxJ$VFTFUgL}6{q&PHi-96tGE0`TN)=&P{7I|yp z6P(rgjt+cm-hSYa!*AT0|4fO;4P-^fvhK+CG%54-W6^4TgE;nLs^Jx->lYS=vfr*bKnpIMN>nRi+>(iQg%e5vYBwMyj$cn+FQQ{PJ##n>r3*?Do z51P!L?rK-+>6JP94aibMPsXs8=lZj!$nUkusHeBLltKr8#QGWGVDQ9>m~30m#6mq6 zSpQsNO0nfoX0&p8lEeVdlZqao6KZ9iM&XRU%UP7$e^PuLq(H9~NaTBC|TeY){b+ zzq3%YUxk=#S)a@;EfT)(Wva0%qk~!hN?(S3!Z7QBE&DvhyK|>Cd0?*Gd*>(Tvr@s$ z3siq8p7|yiG}EiRngtY{Zc0(2>EU>MZtpusx0<}AAyUOgIBT$>`?)q{XzWKuBUVf~ zI?%qLh&OaF`jbEfgyZ>_hn! zav4aLNreRif*X7_z%6x6QP@U_G6Geg23KZmvHs`l@V@_H|0(f#;UyqaDQBM${`Bu_ zs?ia*uKG=dNq9V{oNcb!mJY^;zt_osPB>2aOaX?P0Zjb^t$c*75faDaXYPV?Hbj zp1PqZ@lA+PT_J;QhL}f+?B?Vys-oR?fPB0^p*HF!RRR+|!RYp3 zuJ|v@4e9EJF*kV1Q{ECGFg9*P%WKD~TR!oSJz-HO(bKfGN{XAL;J>%7g!c*FN|FBN zy4k8$dmdpiJqy4ymR1Z|8i)xpckIZSaU}y;K`ZtmM1YkP$}zzR{IrB)He1hc-(vWj zWoe|J_hBBGA&8xy|08N3i3t|BxiQX1VdVyuEqhIg&a~cUcQ&wqVbn@2awu8;4P##L zU@*EONiiz$K2d4Thqk6=%IH_TS12{9B}l&Z^^J&HgZTdB2u)#f(h=xQJ@w)HajW^8q2d7I5}wrb1ZS_V&j`}Z7t zhWMq<`0B_1WhIqZAv6T4BQ%PU)#`Oj6m32sWxiV=skNnJ%cM{(Hu$OI=G3}P8K}iO zC7%%5fd2e{Pp$(Y(UTewIZ*eFK!PMqD|16R6=57REZ4{MQwZlhl2P}Z55pIQFaPC# zibz#RemIR~iQE;e2Jk`{(G;*iV+OBqSUyV=UF=ig{O1jV_3U9ks4+pL+|gqe6CS*p z|H~t{7!mk<#((0a3Z(mOga^2;mi-%j|S@8pR=kLOn%Og0XBN{&ad6Y( z?>g>BUP~*)*?P9^0YEV)3*pS~yaQUPH6UrAqn3`rjJ%Pw=G)R)r~dQmqQ<6TqS>!cjiQ7XN9~jsI03`?%+Pl)IOCPCKfu zqK)+rJI_3Bg06f$3{k_3t5JW^2b~$ooWoB(Z z(yGLgNZ9S3C}yS_m$%AUX*BQpKt&9GrFR!uCp4CqU(WUr^zL8<7wy>=Pr(i-h%T?7 zpYq6Q6K-!Nq=)wfCu$O+_en*5{v-+0KTqLnWD=tO8=ET}s^qz-cdIglr!$gp%AVy* zThI@{V`@yTb3EA%C3OQO@7Il+}!uD9UL(82UVi&T6mp! z65vV0Y4jX!eW`=b0eOPfAvfGz2oC9o`a4L1R3+C@gfyrw;dg$K^Tr<8U&w#9A;=oy z{EqdL^nyI0Hbvy0$e2koCuExGzl2PE1N~nuR>pDOJ4^=Gi! zr2XEglHAe(_H6BL5=TCcF_VCTn^q?vp%*-L?sA%0SrYp8K#~hshi|Q1)V*JVtH$;B zR`HA}^u_x7--xNb(?-PY-X~lRuOB=R?S)jxEn)P?W2F|_!FE@DzdCTp$^(s>v|Ak-^&L9MY?an47 zr*l-5{S6qbM%2PLx|3D+Mr}~>DIbwL$6sPJ=kh4y_aAL5!mdW0dCfN*pw)Nh3dcd? zxpqXn=;$D519|RjRL_e!3A%~;Dj~20F?scRv5AC2=L>`u_KF@u4UvE;ZOUn&cG0BJPj-R; z(uDramj*h@LYkphzOL&IJI}`fv;1`Frz3Q%3=JEE+=`WossvG51nRx?cfbDFPGfuv z^3pGpVfHk3B8?2!uT2DfmH(cw{8QsbtJQ^wS;WOgiprz|V>{(3f^x+Rw170F#zG z!sC4j9M<{>&#WWnA}M?(7BG9dq(? z=PKK3X7@;5zP_pTbiDM6+)TR`^B+{TG? z%O%vY!AiSIAzC-btY_HFg(Gh6Bu6Z|57-ykUiE

V#f>p(V}nbTdgr6-q=mM^`SG_0-D>2f3H>G22Z z=;_BAsH?*%$_cuB-6!_0-5rPlArB&=Ob#CZQ0A#JDgxBs5UNklM7U2_XbZoW$`cCw zIR6G=Ev|FeP2!*-XdB9w{=3*T)VF#z1ik7xs;q!26ZYdEZJHvLmc3UdBJI{#NLa=o z9o7x77=b+s*Hqr<^NEQ|XA`g!=Sy8PK=!Tvbj#lqKAEPzK1$VL7Sp*XF0v ziW!?Y9EZ56@T>u^A*16VA?L!o!wn)lad=dP8xAU6L^B`i@#$pM!&rf#Q24eaIDj4CXdi6|w|rsP&W6zBERc9<7aGrUh!Qo1>QcdFpHpP?aaj^RbuvK%Cdl((6!_ zOO>-2ppO+}u@Vj!pXa@XO-q%ck)BC6ao6M2X%n5lWD-gSMMI+|o`{p&H&cSqztT^1 z<+_c00iQ6Vg&8a+BxvQQrfqcovV}KdJn!>dbmEki7io(iZJtmL-~>!nS_%H%ITKyH zlKWgO;rhN^^4gW)m6IlBoDkCkfh)l*rhi~S5rW@wf>f190l&S?Vv#ANi1bZMm9?}~k$t-qOBD!1mBl4su{V;l zau>xT)BG(vV6P4E`>m6u3ZARCR1x6U%duFwO~4$5`3IZv;n6V7%*KSW1?x68Z{HG26`byT`K@`H z;V~)lhwvmA6M_*VKmm|zsUrIaJay!=RJndLK&Q_8h5H;Rt&G-W?89yjhlJ4l#!yHI zZ6Qd+Jd3qnt@jA}3SkfCez*Y93*Ipm=cARtNTJf+Y8QMJ1od#as$FZ0P>ezac|b4@ z;o#AO)xrXzx638gIRO20Y$8`k0s$1R2cM%Q+ykL0csn87xfP_N`>ObPrX`jtfBQfF zn)%^c8WVKOhaRG-sp%ptRhCvRgd!?-VX>AfXj5fjfpxs9GCMEG z`d_(11@){2+7xXFAkWE}sF=S*db&>`eTbi_<~1#l_l_k;r~0NYajzwDn%gXtwp2-p`CI}00%H=c zot1#m$l65lF3QRd^^7${)u*%uDa~R9d1CIVueH(sJyqPdq^q0uHixk6$C!nS9aYZ? zlJDl{3qE~$eokR6ELMsE4&UkDVL4!}P_iQh4AuSHJ>;x8PBo2v+}2f8-_XSE+)mYX zErKe{HkzNGC7Z*ONdpDp&O0_I#_dqvDc zm?I#^!n`mx85aEkZX;pk7~s8bC=BlhoK|nA(Xp^t$Cc2sxydfZTseX9gL2N#M@4_w zy`z%b&BWg^k4i-j+&6i7zluJ;i|Z~P$DA7Gcc|cgXBSF6$mQ}0>4Q)@a5HqayQr<% zPN7g-#I>m9HpM|gD56lO;GwZ^SShcr-E#^{h3eeBDBji2d>hJxu>l1!x+TU7%8th> zQf&laY-iUGSzfdQ<|g!UD5d&&u0_46SY@r;R%%@+C!pAXg$l+K)-0{k8T=kBGSL?J z9qaCDc~0Dq!xCr{Se~GN-xvxC{s)#P_1t$cmn&c%Utm539tpZTUDVUz6l(;=BHCBY zZLQqjOSOny4(P9Hyo>i|z5wlkIcS8}7L;9mVvOQ&1e8?hgHV)Vtah}@K>FZo;8g_k zs)EPa%6$dOmBN-Pu^8{E;15s-1e90Gj9tAq>CmoWp1Y%Tr9VJEem44+B+i%nP7Bv9 z_=CFY5bf;sa-GeR!#2Td)-3a!!*p}}7Dai#Szpu1{S)hQl;-B7Yd9lI6(j2ueAkvM zpQVZd>UcSe6}Sh~@&y=wo0cjPs~e5?4AMPm6U$@ORb`yPdbPmm3s7G0f?JoMPdt+n z^x-Gq%896d(7}riFJio~Dglc+B?M-qnG;r zDC!zLed=SHS}3tXpfJI65M&RZc&^qe1y&UKp#Sa3<4G=$r27xcg5Xo7Jq0g04CMd( zixuL2-1E%i2|BPhNLzctywNbz#miP^IHeT`ChMk#6g~Y|oO-&v%z!R1^B3fLP0@g; zcUh%CC*_06_4I zQ=72RfglC0lv*0?;vNVju%U+V7d#E(1;CXJ6!1`XAU~~@2u?M`eH&*wtI(12m!tP9Vg2HC?!sx*O*~5PzIcG#c57Gq0Ha|wJ=(pqJbG& zT$mI61lCPZ#G$Xias{7X`N~)5(&bCyx_E4941`kpz-obdE@q8gi9$swYxD{g#Aq;l zW|6NQ4Eo9C@(5CJ^4|znUMl>-<*iM`*e#>Q3WV|yAj3)p^$AxzfnZz+j61oGF?P!x z{CzbRD|VhQJUmw_a@#7&Vc~VBqMB?bN%jg4nN8e3C`+-ZT^v$TRO99`XsaTtsg}&C zYN|+92|{{zvx|0i@qE%&AZWA0Lshjc)V=)(9eeZ_=>Eq)w=C`6ci)mz`B11pNDm8+ zeY>l84s#13J7S`QA_<`|fkFibD{<%nuE8-+s{W3)NhIaCvD&QUc00-8l)_LbrnQ~8 zoXZ~i1w1>TOcGECmXiaY5eWP72{{Z7|3Sdp)#eng8@G0If6)-y2td1N%Y^%9 zXJcYLRDsK36$YLFYom%c0|i;Rfi@G$2`2P0thKPb7#;J`%nYn5(0>r~NtOZ1pi)p_ zt~Q)YVNrrP3a%cZ2!nzXJOGq@S_@(T3Lo^7P96`Cc{v>>Va;=Rf3;9Vq0NC{dQB}S z(5_nkA*|s$TAJ;m&7ouw3Nrp5>psSFJHH2n{MEePVBP?2pP@0G;um8P)%5)9v-Eeb&d^WZoTU?I7X|%5q)pSU=?J-* z7glRwAuMM#10|6bs6s_XKtD9HSW$qhyfQC2cMUd`D$8QC=M;^*psJuyaXC};)T0Q{ zg~Fh+(^-JeitLfO0hsWRGHM;;&w?Z7LdZ!3@;p^&J0tIps-+2M|jhJ?gO8UwZhC279*5YTiS^!n0l6<3E9LQfa1IDCJF!wmdR;p zGQWwngSjG13o~aauy{_)*PB>Nly7nf1;;5K^HD53o=({SFnB%0{=hm4;VLYD*P9^3 z$0M9(pF_F!lOGv|S$?zEY=WdF7LV-z< zhhE8{pnfx=e0?MPdoB=o7YYD9p9CQ=g3Bsv+4?#w^Q#V_d^1}-LZF0Oa2EuK73w#u zThtSvPLD$Pwj3LVlghF78JLJpQz{Wi3$K=`?AwHr z6e`RR7pqV~TU3}i;}TxG|H>KR=1I}q%(#f7QH<*+BNU?)DYs$;0&TeG!HZ+Rs6nJup6JXQO1|A4_#FSuD^8F+VB`HH=5GHt@Uw%ME;o;sg*@Slq{8u>gTI z4isRlIh}HYFBE$P`WO`NP}m29a8-nL0P`r~R+uRe!0CB;9rnI@%c62YDH!11Z2#U$ zp}^m@-7VTQAH*Cpk~=rS#TH~atu0Retl)Qwk=Glgom<^PL4*Sa04(~}0w@#ONY0-r z9@`eGtFI!LM+#RUS3*4kIP`%&sweH7ss8rV93fZLUVgu&Yo?H0ao{MXsw+ z<}X0=JWr@}O*0n6a?jOTuRO$a*W(9ksE_9}7mxFNKtF9$ z(k3>sE-;=!ikw%<29JB`qz&Oc6cYP(XHN|2A^d`CCTE?ZbO<%eepfE4OVA8RWDj#iF(b=JeRu*aZ^|sPbt~V8UW09F?Z{0Q}5?c}5^K07265 z43txuz(TQt6Q5Ygp7ynYH5}9=c9}`FALp$Q2^o78EhxVG{>FV7&=z zHF!A)4Zwq7ZH7`st60H)@-M$NPXF~AWArC~_8;iq{LAO)|NM7frf+=v-_p^;7TSN< zMtcwC($Ql~{M&0MzCwTWAAeii^GE;j--tYZ@Y<}#jgv$moD{zq(S`ny#(`TFU}^CC zUwwB%1ilBo{_Y}O8VHKNaZhWr6r_Q-0fA2iAS^+X;LwoSTFrclg(@u4m6+Kg=UTvG zs~5kS%`TyU&;q! z6}|E9JiYPGJiYz?0^J(P3Zs?4JkFbezxdjypl^KhztjKzFFqyckN@PKFmE_PeTVGa zPjczlF+2Ae8~w@`J=A~okLZI_zfWgQ{1*M~-`%8_PR=jsGaCWuCu)DB>Rk)en-E;{ zHA111R-B0R0tyxU1}iAU5zy|l0Id=+9?N|m+}ac(E%GTO^;jRp3d&|m3+CZkS@u_0 z1K62R&xq}V{+at09UIf%zTvfcYENR3auvdOy6DfCmUD z^$}+aYuWg?pJrx*LRkdBx)fGBicn4{RJ3yp0J#9x35-?T3Qrcu4}|qc?a$NMmKAVW zg}#L{K^EZi$H-#F=#P`#Djx{>gN^GKNTy7p{q&@bvlK}G4Zbg#h>+7|d=LQ23RtW_ zxzgTZ7u3akP&coaI83pnOS;VhM162Qna#{IRl2CM+QWTD&fA!yp!k7e2=bXx?h~UE zOY3<(fwqJjHOOFIeyf?@IMYpMu56(jqdj!-dLt!Lon*JPaQ&bkO9dm|?e;;={gR49 zv2$Eq{TAx&=^?~)S`JXGth)gA4o5C$vI!kFdsER^byXQ>un}7z8kPPowa_b60PQtk zFp^0#GcOQ!!1p;^W624#qct}(bq#2VB}s`Df;^zS>DvXRMK)hp%D|-={$5YOcfYda z0pN%6owL#v1{gb>0)Zj|3>`kTK$>2$0)}>}VnuuvP(e4*Hu`%NVA6{PU$0mJwD|*l zJKch@0(Nfqq)%o@Mn|i-N4ymD3A8&HJ@{g+t+t5I9b4VvG%ikfK!Jqv;(Dy%V8)?b z*~C4H()g&g!8$*`x683A>frIH1b)D#Vr9K?yF2XNh?Ui;_7or160J~g6U77k0$fSp z01X6Zu=2oKui%TBXfB+ejD+3r7GiX*BK*0_vV`Iw5nH5WB1rM*jQ9-#H&|&vm=cf9Gx;bM zoy%BmXy;!jJMsypl>%ou+zy2b0KQDc(g3drVIcYf1XYnpLMWWTAA*NdK#Y}(m%S9> z@djZGP7hzX?x*WFq)&DL0`qu?-#JHr{`C}p z+zJZIvNzx1_u#Qm=p=qQP>Nz@BcZL~7WHj;mmb*r3bnZYGkKE#HZQ&Y!XMDT`uD#{ zU;pk`G8PYj+Di&6p|n-5i2`B{fdvNoX(5FQ09Q%B{Mior#b0R8=^wxRxej{v$wt}K ziq;6V+<)%dSxF9_WKvx2PaJO$RL65!{|8=b=YH49;|uGi{lx-`Y#nRRSPB0 zz#eOy=PktMu$q%(wL#(69t1`+C5@S;;2gBKl}sv>W&P0-kM6WtoE zB$K(Fs+?Q7UU6WW|Fzkut4qe(x>KN!rIHVWw9{=t98;4Z2v z1afyW?+(ijBh1c4Xr4DTfgm<_@G}?_f<2{Bfrh^SCIWhzskJF4n6j}+8((XpYXezA zpm!*i5A91)cZax@88QS4L*Ur#bq+2|!z$)K1h@D3bMsV$cqVY=wR5XfuHf1(E{i@; zeISU%(!}p6U3_Wb^~)gsg?`)Ci;a9bkpacZB=6Pd7tFM!8?jLk7#_YmQ?#u|Zd!3d z0;gl3d_rBJOsFR;@|Z8CW-PqH$ElQ2j<759N~4Nh)= zsR&0n{{;(gN|;e&<^T*Y7#9S6oLfL!S8yH(4i*=Tgz_yK3{^0LW}?IUD!5!`aq0y^ z2Vo{#oejbV6KibH!JH`H?C{BqjXfB%FmH;XG_%>{iMi=n{=((LCP{7VHv+&cq0SZV zKu3;h20FTsqGfRXnvdQ%IZZFUIG)LGVj?U8Q#SA>UaQ2scyWQg z@wHo->(0DCNBvh9Go;czl~zH(^kj%myfU7-W^5!tbq#iEYLbB(wF+&-E8l1P|0e4zUJh7ixU#W5_H!^BA~2I@vD3D)+SJW{{D(GVQm8-B-YQX z*o-4UtGWhrFit$;x_skc{R7oUsJ_lbIf3f$03?%`>-48w)*HpmWoT=-@Bq;MIIM#C zQSn0Prx4Brf>~E0n9IR0foBzNPU8XY*2l z5|S%G;D~v7ITTi?NS8K+fa^Njq%}h+3KiUkYZNYA_K5(qH*O(7b&PpU2OT|7EnLDW zK%sK!nxEQRoFcG20{0@$1?mweba99VzUcwsDn%!7Ef!Gjz!E?KZCOlRf~Qr7gtQhy zXdAOx3g@)*0_s}0lu73ezE>ZRR`Ig=0Nz#wkXC&U$fr0ds8HdeX%#98kQZQ%!&PA} z4iq6{%s-EE-ng|TgBw!us{old0@YV*`t5Q+p!OT% z5n-8vQ~8(+1UN4Uh7sV}PynxLBN4P&kxKp(<91oX7n>9Zeiqi3IJqQ@Sr7i$0ru|?2N=J|(~}Q3Wb)tA<>K%4LK!i{ z^I@FFHPY31Sq|_9A(Z_5Fp%~zzCKVrEKyMB$lJs7ULr2tcwsHVT#Rv|SI8Ox>md|o z7@wHCu^u5GbiMN*_^680kSCzZg|#%(XI23Wcv^TBEbQUYR_Ob%*45Sr+`po~%l%H4hXBu~#uMIgX`p)7 zW}x~_C@h_*j@5D+Dur zs83cZCU$H<^w3+BV6s;eK2C~3nE@DCy8!qddB86$ELN&3a~UL@z?k6Q0d@Kgj5e5H zlwS$ojND9uDO1mb-~tQ??`N68I$ zr%jgwOyGekW(>NzvjX$?-klYS7CnCU+GP4K64$TfP(Z+#%SnP z_Eao@?y`pW|qGF%^{%# z(!TH1WSB0VU!d=PYdD=!INoJdO3<(ETR63?4qhmr|Dg_- z1L_0$B0pn=O5rv@zsLPp2QWXEqEOKa?kA@sLU@CFAgIId`*v4~`2&hI@cQ7>E?)78 zXCkmYs$hO0Dt_zZYr)HD6&Y|nqPJvN84Ax4#bA0SO1FlCLRhW^>PPjDasqSGiWDlk zb}<6nO=;KtazMEZQb0NMN_7PY%vNr(f^viZhc!syJRro%j&Fx>ua!@svKA=bVnx2w zod(suT4e~vHs;2mkr17|=%pKjKH<&^76a(FP&jB6Dp1J4>wxUn+%~Ezn8Hyf1;e%_ z6pI`8tMVd$duR`W;9a4N@7uNU4#z-|pr;z%e=9;PQ&@AMePAg8w_V_uV6C`ko13cn zccVOXOCLe`iE%YO7o#^$%@bcD@~`B4?40g~k|oc*<;1Ukx}E;>|F(xd^>j1!ZSj!V z@^Sjq$G=Pm`#wcS4}6;T?|7Q(?d@a^m@`xnvXCY0qM0!d4GuJu-SI59=aaOxb1(1N z0%AQXW*yE4xI={tcUbP?5Gj;ikd46N75%8K)yd_nX8yoM+qbyr{v$Png9TUX!5SY8lDC9Y+pu=IIp9lwGX@kbN|9JBX$3&#QmkNXV!UZ- zit|vIoy-1?(^2;nGF6+~p-Svtn=r)kwW!t+0BZ!+H9hV$#Y#E)4&JT*W{}tD$Qn>s z&{_zaVac3&j|#!_atajyLL!BkSs5b%yn7puBLJt-kp~2Iu<*e9qTT@r;FR*kX18#;RN@24Xp7Qn&FFn-(F;h_8XR;I~AJx#W}_iQN0D$2}T zqHUK`sNfzZ+>=kC0;L4nwWpKovc^g?b8yX*68*f`Q}Bg=b`xdMK<~Osi`6MsB=kxP zqdWkNXVC4yTDbxyojP?_L)h52l_io_{> zBlv>#^ueuX=<@KhG!y=%9D3@Re@35w?w@kMtxaFO2|du=;lAv{_t$0U*#|)Nf(~!5 z6jlp3z=*X5)`RCRdd0!BM-J4`7oKgQFMPN;=YG&0tY4ftT3$<751`<$pAdD4;`yxs-+_bszur?^G^DM1)C@io9@4sV6!7>fz83T z4m%y#=A=VAo#Jy(kArr0*=c8|UHsj*#laf}X7bag`w`50#r)81hLQU(rBJy!Y$v#! zayb#83#a~gv$GWoV6H+1Zo%Ll?8pI_*b`m6!keaQ#7>dFE5KbAeygdLt}vAQufARB z3$$2aw}jg+xcS<%Bb}fDev9!so8SGHe5m@ZT<*VssTmV9=cvCFGo~g{?+tY+dh$4| zbFy@JKX0y_Ca%*MO{4{z5PHrn*mx5Qs}-N`J zg5O|eGPjTt?!VyT%bE@X2Qx;T-U|dRG&yaeeS6TSrCB7*?&0q^l`@OA+Rb%3H65nu znV4Y6!Dzt$x)E?%W0B`Lj3=1E4v$6X=B*H28wdzruQ>IH6QFnx2*M|(q|aAB&y6t6 z6haFwgOz{R3QX1mDBIoO{>#txfB90@EDQ>epZ{bh-So%(UujTtCAY3+uvM#{Tx6v2% zWy3fq))m<8asLIOVX<$W9}rNYj~ZF++zCLr_3g2iK%a%17n{vWUhjeoK+oUN5D1cs zKC*keo1B$9$nNaqxub?+;Sr(KzKVWChFol_(g zRHy(rH~~VQ({m15^t;4iC%9fhle(Y<=C`#%KOEvx z?vNCqu)&&OG~eX9@xq#FM+lLI3S0(oN6ut zt_=i*%cp(2tAuhDLP*Rt5a5egOWdbnp`ty+2S72a_CQVIq2x#D%!I>>-s6*y-*G-#qnyO=3f9V z>>&777@L(s9Q2{;YPruGx^a&Di@EOa6wGD|?K<$d_}i44qXRofX?%`(U|yqFYvG1N zsaWr2|2B#J7V5382A(_2WVJzIZYK-31Ln4QZXeVS=4|adtpwUSD%Sm1H}ewU1@QdC zd**3-*9g^D-JqVfF=}m`=XHFL7Q(aSuvIg!@8tTilHc!Vo+r%Xq73f8Fb>reWdQB| zLc4we<#zwoR69$%w~X*RGS9*NcXlx*c$XM2=%`mH%TSkCj^*LxmAe0OZo2>4gdC`w zz^N)5efa)L`h~}<>F^F_B5EzX@yZL`rM2i)SG`}erSJ%wRh-?y_Bp!}HP zHR|S&{H_!#R|g#Yw}mG=lQ>b=+$ihf?e}qQL~fiIK0o4xV9~-vDbw=dm6I}$riRW<+aq1U~H>^lLxa#NjmIBK6 z&v^xd4(1iglqyetrV2vHnrdaWWT9r>q(kV1O)Z4AVAjEOK%s)zDiswe+Rd9`xRp@B z@R2^Hv!vO?+T-yja-ILb`_8QRy!64M5V8PJ6dXRhz5->f3$1O;_(OpL;7~$$kDGq( zxsD}eUoEP*4=aZJ(!~WscW6e?TDvs2IHGZoDs4qQfA(dM)y%>wV+l`Is{wv#0iva|@YBK|% zZ-< z2h;I=RrKVMnhdpQ+8IC}8XncSBTJ)nixpgp_m%IgAM-1?RsHK6a2t9vtR?w*{z9qkp`{ew9w$iSxXe;dfU=?MzJIPaXgvYy^`)CF48-rq8 z8!1%usHlk2;`|gvBO#tUFn=tiwLTdhjyfowtfY>vebl?8w%3J ze!ut*dg0_G1!G}~B^D_ZLF`lEWB$u&Ajt()CczyU zlpim=s-9ax-}zw$Z!}Ra2;`o=xJV#R#BM>J$Orj>5GMur@Ds&N+OY5dAP`#gS!jBu zfj94PvtXvN@j6}zTw*h<-4Mg#=f&4-^!_j_ciWF73Ow?3kre-D=PkBhQGHqfd$o9`-0sf=4d3A~v zt$Qo&-U%B@oSem};>&{SXQ)wrA%coe$-AmsUiWQzm28XqCmZaC-G(I`Mk&)v6AWSstsu=B$t`AQG zW@`A%ed+JH$|S7gn0G+R z(xV(eT|@B*>xx^<58!~o>^yjig!mhAI`BJCQ+a#p%gg-B0>AgUem|YQ>Z9`me*TU$ zN&YmC5{M4cjQ2dR(=o221jS-8?n7~Yw`kD>OA=5bS>)ar-A>!}blotP@YB@7`xK5! zc>~IYGGT0%N*J3rXM;kKY^}0ToHur%P=fnDk;7>tr^~^6h6zbj zH_6AI8&)bGdZtC3Ow9-Vv*9KTF2q&?ty{7{ATG)W z;dd=Fx%tYXcmH+f{W;;9OA+e8#pBCr&u$cR+pzw~H4R#Q3YLvr~|n+HwGWu^g_zAOuwIzv|sY`*wN6{GfopLAOT2 zG&F6ytKEOW6%XLzIq$)}PP(tpL&y4Dw7uO%y{%TNuQb!HZo6=Q8BSQqlw4nHtx|vu zPklp(*S&OSSO#nF{>!-k6$3m+xB}yTs_on8yZUls9OzwvX)!r%C5KJA|7vP#qHlcT z8`RU&LodJl@)~Tcr2DU`$|QBQn^weiW8N`Rs6ZHtF^yrpa$4>E%M;vWfR}(0T(t+< zFiXP$l=m_p z)nF4bY%uP@%P7SNfcaMCjpq~s6c1|5jEzTxWeC@j_&zZy-H{c8<|g=chZ0AwZE6e% z*Q$E|SUR8z>uRI|1mj0rAJu7Pjfk_t>sp-iLLK6L8@UcJFJO&vGoc>fhaZ3&D7}yl z77|DIS5XB&Fp}C%_09V;H-d)lzjpUHX?mfV&RpF^10yXNYOM9q#Va!uNV5QW-G6b?t{xYS z&9u|G>)UmC_|th9w+-G~xc_44-G8b62W5wHA*uEC-&k)qT!)r}wyxFO2<+YB7Or{} zz+Yd!84&Z%;oXRdk>yJfhhbL3=SHH4mw-7+y3Z=j6&R?n8!z;2)DQX(^3~_JT329_ z?=HXlFFo}061r2A=ZK-v5DkxqX>8IVtlaXst0{I4gHTX^t*v5&t`AFLBlcCW7(spN z3FA}sH)MhSq5U0uN{n^%Q`DL2PiP~|XI7q0>^5nU8ww2a+>oOF8v!2k7BLqZLF@j@ z&ugzaS|P^1%PHHlxwV`5krtX9mu@k9$%s(UtcCk8H;<_g-aAbrgO|xaKSZO0=V)l) z3{8(;r}3c=XyD2zy4wFf`6GUDy`3k3D`(G(>lbGRX=3=IxPFGO$F=zT>gBh{8}W+S z8iadpUcN-P`mfN!%q^N6k@sk6;M%+7i_VKWE(U5oLYwupb<>3RNt*L-C9C^EikS{l zlnw~8x{lI;y-#uy_?ftOwNUR16zl$LZ0M>` zs3<~z!e_wm)wutfrSJdXH5$b_#&aC%zg+zc{0!FE3jRdi==V6tFvjaQ>Jm$wXm5U8 zrMoo6z7e!_gf+Jq_g@N_AF!@tp3?H}S|m~-@&_j=o?PU$b&f*ODVmwTSrRP0-hq}FV)h}Yp;_;jAze>aEdiPxeIY94K;4~v#eRVWuC-8CumM>7+ z$P@X-^}SJA0WQC~+9TB4nWdu#rG*NB1w_SAsi{tg-@Dtx)YcrLR;Co3ENg%mDNrKl zX-jwRWCO*;lIsp-$uQQ+GJq8fVx|~D{I+fRG89teKnZeaU*VSPXwA(Jq*bT@eY*-g zC!IY$I@`>2WPg%&?}&5R<85& zwzpX12}>++DtNuJSgEe8pw9NJ-)%4rS^-Zn08lXp_i*?PVhmnv#3&izN z)+%`B(4gFi6#^77ZjIm#xOjen{_3kY=-s!bXrAZXa-bX*E7;g>>vanH%qPn0KJ88h z>TyfAgY243(N_MBv^xdMZMxPEx$EvqfKB{rELL(M^B5T!p*P-mgTDRkZ*#sIZ+n0- zn@^#lpiX0!Mi9VAAlnkz!SfWBl6+)iDmUsJDLS^*F6hHYJankr zM%x<9^!caisJFI)s$CW0uv>ktbaUfM#KdoVS}pY8PAA_}$@e-0ZK*51&w%eyf+z?| zu!&bdOcc~tF+d&4eFfaZMya7*3T`nLip^s=Kw$%g3Hlk7O*mKrVUhyMptU5>{#Fe3 z?Ab$azx_6Kbac=&&pbmrcI==RUwo0eySwRI-}+Y07%vu~h?5ej${dO(iW6okgrlp^ zBL{d5MTRI3e~W$v>yN!Vi}!_(HpP7)xMR9_$w}AxWnTh6UYx~B_T`GPHbMWq(=Ar? zz^U*P7Z(M+du^5ii8C}8I88%iXJ}@AfayktCTFhD$i!J4oim_|G`j$SW%l0j>C5!O z+x_XMN&zeC&WN-^d?;6puE87!VW5^*L|sEsdvzd4vvWQQ2L^bqNs1UPP>7*DRthBq zUk{AT$0*Kw$7m!#6Qlh!F>;-vVZWe-xe4(-;G56%-q}EcV%#UA;Q&of4rZ>$wZf$n zfA{;cmioXP&$qr1uW@|c^u$eZjk>SW;}L()&5Wh5UKz0e#YufApN$9yM-~pDq3+oa^-i0v=g?#)@ zaDOgk9)%&V0qOU2n9uU381m12&FL@RhxZYCG=v^a5%HZWJnjV(66U?h}~L<{ws zIzgue+7#`GQ<^x@hB-<2ALk7%`YZAV!!1vlO5c-!{=`}F$ksLb4xS&0fN4yL6P$1p z=62$QK#B%#hQ#}z{19xYlX&X^FkqOY748;G6(hjvq)^a!qx&B|-bnUk)~vO#R6#%7 zvaOPahXP{G(PC;cOjj;@siDD6HR)5hfZkHY2wOSNLY6AEb#|WLtTZ+p5PfxFAxfQH z9x*oZS*qZ-p598{V8xd_AJ>oaJK!4RT`bV|FkW%88gnfKUl@N#FIVvT>dHejKG#7r z-qswNm}{iz=>?jYPu|s*Dt4ZOAaLkyx6}R|PQx_~b^6`~{~ckeQd1k`zLA}G3juQ& z<~~52B;$I}0`ILo?N+>{$}0H+4NA3G5vO^14Z(?AMFTf^tcXDMIK610mtJ~_`}Xvj zC{-%VDVkXbQ&WS9T6G?eEY@0bR_zh-I+6)Z{E0NcZ!M=#!2t-wU6Us!OCjk3Ypn@9 z1*`}$KcPLc7Ar&u3Gv)h^|W`Z(~!1z*=cAb#N$l%AGBR*{6^MNMGGf)lP~;yD=8OA zM-NofeTSsGOXNQ?6QeY%BLtHBwz_ENRvGW@;NB{}$CaVsu`rD<e5{%S|An?X{K=Il5j&#-kP)|mdDwwm3)}fVR55L1= z@(GGs?xTolFL?uQx;}74aNc`%^isn8^CBIzt81Kwrh;M~xA8o9ZGig*7p1vTju-T$ z{1z)%UzXNKG1eyf{e#Sp?@J3pS8A~$`R=v1RM7+Lke*B?-VY?1_wH(J7BJH;EW1hDd)oQev8F!ufkPLDYPaWGq( z^Yg2i?=wPu{?J>hR8`k=nQb&TBZZx?R6!poSKJA_yPC^TPZj)pQ_4gRUgyowj0o^P zIq0K!EK1Q-oT9Y!db=&l*PzURZxMpsB!yGiu`BM0@jXcszXSM5xhLxA+MaPwmEeow z7CHWlftrudbX!`hcuwazBp#>M)>bY#TpEGz$cy0?EsC*C?qi`*BW zC<70Vei7q21(sGT9T$4QniKh=|HAtQT&cD+Ie6Ze3L>P#(*~?PSF`uk)=@E*Dp(I2 zn9qW>*5mir(#{??bu`*(lzB;{DGJBAJ=6C9)!d$+`cM<|UT)g8h54iI4%*sTM_W2- zsn+A+@rA>BE^^r18LF?UqDKz3GOt!IsJX71)2gYvwVK)+tjwPV`8nFBNMOzT+%wJ8 z&3(0_(MFwZ+xS`aw2f&?dkv2rE2T_M`5b$e4)187zHN=7T#9z~R?+UQ)iggFqs8#j zy*`G10~FBAgVr;D6XiDRZFA6vAE_6gQS7Jrx?p;JS!&%Q`^%=KiZM*Hv$IQEc%5+V z{oka&{qYqV<;er5Kp;Ha4U;#`iKVs0ZF}_%0i{q`*4>vvS*j}~lq#n_;LU($a@hzi zQK~{^oS7_4?qG7UU_fXGMi?9Y4&LY&>k=w2ZcC+XgqFw!CUQ*JYU1wgatf1vbt(e= z=+!socp-9#4dT{rr!VEdHeT-kzeFw2$zeduph6n^YpqGlO{QE$Kg7rJs9$hQ>#wK(udvEp_x{Pl{q5 z?QFM;x;TGsUX)pnBlkB_V{_qpLAh|c6T&wXQH(eK1LIGPPXMR*wWm5UPmGMoIa>k0 zH#cUPLjb=+$Wc|ZDMtN)cwUyqV0(VkA-c<_3?WVQy$RW&QVYwM){ zruGDEZe2-a>jbX8wzsz$t_~*NivP{``)MKKqKf#obn3=~-|y!>Izv@e20JeUU=CB8 zYt&7fPJjX)VBl7^4zcE=4;DtTYeQ*}C!VE6r2@)qB=nhIgnLt1bYe3{^!y7Za`OhQ zu5y+9N)a$sB^1@BS;g%%JdC|6UGH_Cl}t=&Yw z{iP1^u8YZ!(Dr>_B(vE5X^#X(}kw;BHODjRCL^M<3x=r{^B8 z=R7*|)EI;ZXA?0f0YbP_Ub@dsdFX(esGfa`+nXJ zLc!41lI_3w00lGpy8wS!eHJnH>ucrMKwxoTbm+SLj4g_MAt){fAY`7^>~YOLvru@{ zR5>yV4+J*9e&vi%c=!@w@};tKx7p9vCrrG5vx@^40D_>OKm9YQAh9t2?SVz1RNi3D zHV62gxKtc@5O9ytcknn3Tstf7i6#>ia>(&tOxq9hUI8){G+B++Lf&ba-oSN;cGTA) zRmRBbhKueBy3X?o)`5;XJNfy(6c0D21Mb6Rxp42?%(yHU|Cp?bP;Ir17I~gmvVj^N zlYtqNxEFPXx&sgheuSSX6-7ykRfWa9tA%>sa$!W<2N_t?oX!d{7EpgRRc5NM!#fqX z-sS_^|K?CoxC_Ri%bnXi1kWCjpWu)@_G=gqI1meTwIlZMa=fxJwBrgg66GRoa3qvf zVrqaf_nV(=6NfMI;afkLpldweYuS!^=FfiT^O7$LCJ&J}{;2r-@Zlrk(>wkFJ^k@7 zay{mMkLIQZ`inpNBXT!w=l!pp{^kGrF`8WPrhm->u2ui1FLq|e@CZOLwiS2vxP2c;-f0Gy6Se2*uO*VD0s)pT%gr3jFQ zlb~1>5&r@U`igN|DrF7XxvQ;!45<6g;(#2 z&`9V|HlXVj*~O&-S6Tq0-IVn!gz&}jPZHW#F6i&-yQ{6kb?Voy7Ps)Z&k*QC z;F#=TCRaFbYwl;2&9&S%n&NKAmrWl~f=FuBdTH`hEYVq{&y3kc@3xL7Wc(Q;%A@D-SwAcKLD1M-o@#RvrgQ3?iQf>*=(SS}cq zD1YhJ2JZSEI&$<_`kOIK6=w1@^azDYA;21OYC8X66pN#Z9(e4-+}4HP(q7p_^-Z_y zkl%W@z{bRFcK`K#y4XJ}CPKvoub=y`(ihgd35aphT3>=iP?@U>ZosDI<063D?MA5z z6=0qjGzi^MF@C>vXNHr9VCJ#80~6(OS%h^#$+)+><`O_@0_F&oKwuJZ8W9@u8m@0_ zV$d#7dMK>K{TJpRY;D_-FK3Z?swkkk5VC4Qw{LTFm{T2cLu~Bt%Uya9; znSk_K_g?_a&Y^TxfXlRP+bikD&20Yo+_qB}a7hDv*jtG!FbHrFsNQ0>Ql-^JbJN3uLV_CV-G620t%1QH z&CSPnzHOksy~l;1N>2;(6Lf3v-8;hlS8d%|x&JbW^&f%;W32s#V>wq~P^i3eB3llh zAL}00LLQ4&GxfCd`ciM=HIOo7vnR=9PEZr4H`Hd+L9tYv*WwhlHRawD;tW$2an3VN zU7V*%w_3QaDxx$#9jDqFzE3AlN~OXSkB(C+x%5=EpW8yM*H9dFr!5G8+oe!}0AUNS z1$DKyq6i9Tyn|{Rv=j2c`~>v2+Nrwj%hcQV_o=bt!%N6fxtrd6o-zkphI6@@LoM6-FBxS;|@inK0K!0A);d#pcL8i8)^?NnFakP`!dOd;NPEr@Fix&MM+G33FV zG1b>M=Hy}GckzYN$HsNQ_*~-tEA1)-dE*&qr?qhZg?<3Rc_heuM+#%EurMnh;O5L1 zj8HTlrTu%&nlhqdq%ttSE3mBVE-i|2;{~1>r226n7|;0~{Sp0Au04e{;*#%Pd-q>x zSJXj1!rl$mN094ClIv8_#PcKS&M0p|c)pf&zia1#%>In`Q}|7f*;yVN{wVM3N}pTx zP-6+$)8S&iI3eT$%KewqRVjLt*8Lay#7a-_>!EdH1?b&>K`BsOU6*;j*8LZtcmD+? zP$(D>RqfB#Kx6-(e1kqbKWsoE=p0#o)CNR zeD#JpL)`&*Zj7Icd-+aE+T%G2(3JuQb!&MoDwVK)DXQds7(8@fZN>bwi}zRX60V_m{{)4+mHQ858gN~z z+8y!Ju>P+E+CG7~MICI#`=)r>)t3%^;Lz>{3Ywmyh2R#7nf5VbdzfMs`!nRK-bani zJzV}M=PzRgxp>|=*2j!1BbI8VNU~e}-P$U>QdF32^t0DrqhrU83XcGwUAuPC1LD)|c2iY#wNTE);t7g`g7oXZ z{_EnmLx&DgOG^tmolffO>!YJbk5YSAFZWI9EnsS*pWZunBDXRa*oPn8*Fp2KkMaI> z3q?hJ9LcGV%DSCY*VxJHr;`%#8O@rLT}NuFvsQmtW2E~pxpr*^s=rOptaa;*+xO&+ z05>x#y{#n(XLZ#j1Y7g53>Al^b$GsuFtQe;| z>?Z1Jw^MyBZ*&DyDwR4Ac*1ScMsT5ZF9Mb*T1CXM`|5=|Ep4E9Sh3t1EdCVfS^^u_ z>ar# z!gDBV6|~+K7NAHipin_IV3_Blw9F+3E4il_;9vw!pUbw9nLzkII2;o6;%hUMN z%a1Cg;Dcn9$Y;&#@wlm{r)LRm+uoPHA{W@q8(rVgxxD*7ltJ|8BEmnL{q8a8ZXF@4MGCIiX$34Lmy?ZrCue|Tg(BMo=q-(s-W?(kE z$s2!=f+@JuGgD1XO)k~$qt50>1=-E_@uGSxLrt~EMS4r)qqGpcpYu2*1f=>r>gsmL zJX#)RK2>+9V1?sD54Z`_lTvJ_>p%4 z8tUMR*e%@e6(YPNtbJBY^)}AOnV-4}6BO`jKM#ognSsR$6lE^AlRT9!{<}<_IE~JZ zRyun8leGKbCf10?}0RrIi0 z<(TyFJfXiwS*Qd8E3=kgZY&2me{K08%x!J4Q&WR&S)qMhLrd0e7(-gn6gU2q>o5g% z??wRX3`z&^NsvduwUmh4#_3S3K%>?&wu=)oN1?4UXamalBVr6<+Ko*1b7sB;f z9F`6w__C>P32lT*w zA4y-$C}JAkvu6)|>s#NVEnBwGm%sdFdg!5t#P>%ZeU!fPm9J1oM@Ra~Vz7LjKneB- zfA9y)565YKeqJbD?z`_k=HEOtI9S9!Ed7Wi*~!1a{6mn(O8Wy#>f?#0zeHd7-2XyP zJn5bm=0x91@8ny?1tzzVZEW`m1k@()WHcnIWW|I=vtm z6=N9JIW*-vyH<9Rs2o_SLIuF45F0`WF>H35aC?Kr%*zWE7BmFp(h4?;#%A}-3%iXM z<2*uvQeoq~v;b2u$_xeC8XF>5v_R-OH7#Sg;557zt5>WT1A95R0_*9(M#3Qo$`tLU zU=!;HFr%-%GMWA+tyGkC3ls`kzob8VEqh(5fcvmN|I>c@J2*m{#=ghG4Enbq-kTTw0Gn;ao5JgSqY%P*`Bs6ftAVZ%u-<~{OZ2^;}JT4W>%C{ zy&FF99z!>?t^pdFvMy7G2mSPu?+*#ObY7kwQYR5{FFr%j3Nm8=GMXB28dlEDdK9Zz zf%OJ97e>GaP78Hn{7yptH3{jtziGdX4PT}oe*NDH8ovG(T|4)Z`1?mpZ=HOFqGc9B z+&Nh8z1P29@+nr@T0+co<@W8J+rku%M9Axp(8VkMoI^6O4mo?#C)Tl3r?Xaez}w*W zI34%+iaG_IElWdPT&$VpfL7UJgnCDk9^L2EkSjxbJFR5IPSn~{IoD|^-#x`5SFs|Y zPN$^!>fCaG_8omjP+QNw%-^888n-w|w-#uww^7%YgVfx% zm1^o*xh&0sjy(7gvfAC^@5-udoGf^O=-IkgTwht;D1OIv-CGY*JdqUNU2Y4_O`YWW zO^7+q~D22~T0A&m;b~Y@yTVtw(+zx%* zY^mTjuyL8?{t5@u;3g3V8RizEG(7|5id=tj&;u57r2uOv50eiP^{F}*3y+LS47$a z4?IAjP>BA?Klvv#GBP64$^|Iy*S9aP9@`H zPDUsc$mQ>WL@Z1JuZ)?xiQ;iv1Jz%B|2ODsKfb!of$DGD>uw0ZN(I5`iw0NMrK?`v zL>G4~ckfOQ9qOynSrII)bCm+7^!q2hnGM!@0UJ22|9zlXg$e)$9_DV3J(zWOg6px6 z;GUjNr#MAZvSMX@t09fs^3WAwWLyTQ2B7$WRR>Oq4Dh0@P$*D6Tn54P8*i*m@B(Nv z1ggg=4g@3yb1=^H5*TkN$q=yANLVX{B&7zgzjNvvxLX6&=K~Zazwz7h#4QvQZ=TG$ zx%m7Sd#Irys|eQrj#wf3I3a-k+4?~B`h1oPWUs$IA7Ezvna_6%2*uEZn_t#Np zk5sk^+6 zQ&Das6CLb>PxRa|iPKke^YJA@4h4NccC0)4;Pna>{9l_x&hPqwm@^AOirB%kRNpay z>hk*JX_RmiP_^1W7!-4()nuV&dyPm#kWQQqJb(Ix_&&Mdr3py_(*-mKRWzv|J8S=XfbM{ zz3pcD9$AjUKH2jDZG%G@PzEUAxgD+B>1S_a%sRy89JqAp z5-rTnQUeb^muGAZ0@d^QPPI_ATgJ(#Yiy;tX(_Bi)eJ2T&1UgWPLCJ!#1i?$Gz)5)20fKr%Sc7pY`I6jsECk4R$`Pnu52@VD zS|*iRE-kcy-2tOO=L&Vz^+fTV)ZX4saL>4wz@EMT){Eo|&ZbkOU=x9A0THO4_euDU zblLxk3skR7SIV=V4wtwO{pHg2?CJM}ZVU(JYbcfQi1;Wgg)cl$Z5@7UYRD~%5x|G! z2CtVWHh4YeXcc%K!pXK4IXCLt8PCAnSV(E@>t7)vt4O$ zc>o9T6kmfno`7pOjq*+G&$y0Ont!qQ=tH~d`sh)z+A77Vb|d`swSUEX$CX)o8v*W1 zA>ao3c%E!(|5fofEDGT=NROLCXX*7f{!;wi$Ma!r<1bJ&=AyQ?Hr_|bgHu{8ER4{} zQ~yc)jpyv(zS-LLNeV`)sHv%m>g#zP(qYj%L*IV>U-FnL?lA4Gkzi(xw4}I=ys|A- zpn4V8L@8J1;z0^i?mUgAHTx_}0@ZJ0J{F1<@bm~&ANNG4p4TG03tU+N+IzKu>hW9^ zUj~8dBc8ChcOw9E1LDoX-4+gmc6Zo$UX}AP>I`!d-1;I8t+JxT96dY&ey~DVl)!67 zduwUD4dxlFozt_J^Aci4fF&tBC5V`@{A@fQJd@C=lnmJq5U5_cSA^SV<)RbstmUT^ z@Z4YfWDf;mALV@>?}2ziH@ljsu~qIT6{ZHy(_j4Uza?)#Dpu+}7W(Zk{ny1lO9AdN)pxiG`_}jVPI#^{n=SM&|JRT6erc%!1NidCTBswv=hp|S2gXK+ z=`){vPOQ24@PGWfe@~A*`lxUhCIZ!e)i_Z7-~YwET#n=1SFF_2-9Ybp>J#P8(CD>>u*jM ztxy55>BNRR>r=LHor4)|s?9QJ>j6v-t5K)`xE4ZvE!2t4uC%Z~3G9o;X7^lkpiK~n z8o&k|n>YZAJQir2;K1qI_s@BSe{ZCBv`OKy5wMt)X0fu_$QvC9?he4}8cjg5^$tYXJrNmhJf!^@yFa9Bj;ZA3WNS zQK%FG7<9xuIq}v!ow?wncg}dpn-*MP1Fk=%uSGEyD@N!@D^>1P=oKn3$JfG0p^^`n z!A6Gq<(E4QaDkAWi`Np%)#BO%ZK^h$TI|^wqC@+FISLgZnlK6e?G|sYL2taXK+3iF z1oKPRZw5vB2iN>`lRtr2(j+#}3bM;M&-sFH>Kb26|Ve14!fP& zI(o$4e(zk4LIoJ}r82Jn><$M7eDhRO*C4MC6&Btq9vgsSNm;F|)XG4`l|WweX#t|w zm&@DVE}%?UZo72Wf@>D zTZzSrkq~erL$6R79!fC{Np z=jl)Wum3>*<`4hBqHezU_kN3BedU63OI;7F~DN zxbX5^p*A8AOyE=(+DaR=u~49T0Bx^=SF5-sNCPv1{6HQLPNg8Io0XRH{|WbC#Rsn! zNp}>mVbluF?$ki_P(++NyI^RQpaqm9M~>Ff_3J(w=$EGLku!`XnRr z-m$AH<3Cmbf&4CBkeeptwRd05l51`Z_@z}8UjSa5FMi~JS6`GnIw0loAJ@I4%1i++i|hK&Mz32Os(YoQ(g0LoQeY391Jh<8#{$>W*AvJL=jz*IoY zU^qrC9cIpl%N!_jO}!03pnA7EL0w(hI)_39b*7Lbh!g*2F`IS=Wj65`w#fQNfKQyz zLy%4&5ROvPigveb_(1jH_yUC@G47W#kaQtn4pV}ET&ow3$#qBecOV<6e)&lrLLBs8 z%#mwJ;3*8Punb-ua;3@n1YNxuqRTfzG_jb-2=PO46WtsRi}Zn!2rWcp2Dm4|eIvlr z!`O73PM-0JYXN*hk#dRe0nLR?8EylDW~`BL!)a7*Jz>0Ky#cUJE8b_h0OAllA5I4w z)dK>-!HHN#(W8KA`PhDAB{7t?zKDtJPKyXCin&7%yQ`O+o*g`YEmA63n6JeNMzyxW zg*^s~fX@a3z82(HD$jm)Me4a@b_v^$o4U)u9N& z%XQ;VE>)B`$a;v^l3{ZvT2volmvTrNiZ|@ct?cdI8JJX(>yJ*{%-E^pLH|^QhNmd?^qmx*# z9DG-noMs2zzrUHPJ$2OEwTsudZfb7qqHP_#{?wbOe<+k=X@!%cktnarBm>JYjSaFC z2+F?HWU$V^QTtAKL zr*3c`%(|rPXtGmF-2yqSv)o7H@|bUMzzTCrFa-XPd8>Gm>TB&Z$m@xkdob55ci2o1j4{*$ z?o0CXp+rM}hD@fV$swM-T44Q9V;9eI*il{?a983V?USAPA|TELX30p zR#1RoorL8U+*-P^53H5#h<}HNnRmVBr|Z|R)6l?A>1O{sG=A$9-V41&=P$iTR(Fj1 zj+H9w%+%0grOpl;ZSQqZcc-0>9rDnpK2}X0`(--w-plmLPrpM`GvgFVmtBt_zZVWH z4UL6pZ_fwhFrA_PE3eVZFaLl}zyBg#7&uKkb~3`!nC9J2)C1kUVZ&7uFnMR+_{q`CnrVBw3(S1Q8x}} z1@&%`a$K?I@EoOpwLrBe`WTeh*wLH~?5#Oww3JD5O1J?#v@dsany)3k{n}zifU(wqph%f_LZGCq z6-rU4C~WJ^o}Pfkg5J~{%$(NE1>W%%Pt=Cs=ay0fP;jjd>r>z5#A@AtX(3$=$ORP4 zZ^@QLIv_7FD|mK(S77;1(Qj1TE$+YWbztKNS65o7wvlc*O6&j1{nrpPXizFDX#4rh zTs-5eS3&QBOAGWV1dK0qauAzOFmQMd+_T^i5c~kA_?~@xJmQ@IY-Z(2VdK0Cl>O`p}20^zLOlO-(e4w2cTb#?{pk+Ol0L2lWaSyc66A0oqwf z3H>pS@q?AJ?!WdQeuQSZ9+WGzJIVc5Fma12s}f>e#{3UKN_g}zIPWfm-bI3rCs(QFzuuvp4OksaE z5Uvrx%V@2}V!>LvcwV|P`RD)qpVQ^bmxWRVB7aa~98^KzX#g&X zl>3oFZjuTC!dje+9UKk{VKdxk6mpGa1PJWP>;7wLn_yme?umNZ+9BU}G5IWQ-}gl! z)bNg9q<{2J{|%kLD1EXU!R>a@xBvD}$zF^21WuZ|^7|sL$+upbrl77^7IQUKIra*n z(R#T5S`55Ki@q7LCIb+_l*9ekT$*>U;_IG!tUmAF^YwS;Xxy71e~|N!qTkWZn4xnG;U z(IBkFrX&vtH(!e1Lw&EcD=@8_qURo|r@gz374`q)JEJtn^9ukT0|CD!R#y(ZyV@%s z<7Xe+XMDII$_wBRPRx)m&FcUU_Epo4Ze#fZu7C0EIhxhYhevl+(%!Ac@+H*utMARx zd>}67)qG=F4+zS!2H7kX^z1{sX?)=kG3V^swTs(nsq*RUh40ef&>QJ*5>FkirIEQ$ ziNE2J46e!ah(rSP;;a8ctOe*RN;v=M!D^cE|2&t$DunNFsi;SiFaGxT|3K4j8w2R$ zV-vY9v9P{jK4@=&5Z=Yt$b%L*WCr=y`{x#gTQC4~Q>jXo^}z60C^N34`!88ut*baA zeB#M3liOKEfAIhQ*P`#BJ+&@Y5&xvA)k+<`%gZX#|l{H0$w)?X` z*IIBPbn;&B!;jZdd#jv8fHN1phNp9kP+Pf<3sRnW7eaU=g^JD0i+Ub{qDoOEPqZq% zm;*1?3QbdN7?*;|^LlpMkOsA|2 z*x0Jg?Ro;r6!?oT7DAb#n;VOP_Ec#hVaS~Ye5D@C&sNY64^)2ad#( zTnB~9S^!pj8x3#`2ZEp(d(TkVPC*0O)?358zM1@y4vJAH_oa%0{KHxUYfP!Gz&0*S zMJrU)oLGn;AVloSVhFsMQ69w*+5mtuv$aX`fN=Ar_&q4T*3%W(#jAe$=JVr1IR~o% z(6@g$A=1E`XMujJXm!9^g~Owup^^LwxHnGCQ~zLq_XnX2y?aKdNY~(<(+hOvx-aK? z(0ga|yDuB!@c@1YWr1M7Sio8WR)nz1L=2*2GRS1S?gCH(KuM`3^nnWU^1M*^xk|Qz zzM}4h*PK)miiyJaZZw4ofIhBYS7E`A_)|F810?`r4!NAL;3B%(@8>#}?}2*UhzgZ* zLRqSS@OLQ)gi*mZkasHf^f<`P6KFwjbs;tgVoE4H^LT>@dRGiE zx!kxF$hbbjVuLiGP)h`up_!U5ez9E*aDrYjGMF?JqYH*huLKgO*cvM6iTkT*H`kw@ zj_z?&Z>vpEQ;nInb=aw;#zHs7?vll1KInoM51H2E4)ZwuG$ zXoM07*v5dB#>#PLj*C*pJOaw&eFOl)4Sl(LX1Ub_Az$#N^azV&A?%}=i%QlXA8HB{2aIy zn@hW6g8M$qy(r&uuE5a0k&m8i_GbEp&;KFqIrJ25?|VcL{sz@HZKwH}OZ34&m=f`o zpN3s)!2MS|8KrQ{m$SiA3Kg{xz`8dw78Y%WdO{uJloaX#^O%DfYqv!T^jccG$!fJ_ ztai-i1T)_Jj0DfS8{GX@M@NL$kcc>KDK^{u{zh&aAOuye&j2l-pdi;B+22r$(*2h) ze+5ATTyY^^oG?Q@V?Tzq0`Y*bf!7LnHXI5pRc@|7j4=S?Q){)h7C@Vo=Kjn0gz!q- ze_iPh(A(#I!VLnRZDduSN_Z(5hikn2HaGgiwQ*u`gkGtUkKQX65!f+EV``wF9^r6zf*HA#tfjWLrMkQiESMB zUxnKu5lPTd?pGE3z({Hv)i>|wGFR|(EcDYCU!don`+4&De8Tk`+W+&P|GcoSL;F`& zR?&w({E>7{yzb5Xn7oUNG%_6%mR3p#2(s}!Z7~(^{tLi$S~p;&xCDdyuShf~>IgtP zl*9d(0_GQs^%xCK-%m-){S=7p&mog_FHO#TKo&u}MQwh`)V8lWo20GX2)a_)Wq{Off6 z<~ux2mRh61ZQAyZQE_jz>n2%J7nj_7rT-1Xd)Er++vrbt1!fFTgQCn-Jt{%CDVn43r zJ*dBW!GDUcVvWJLhs!stIrp;rFY`b8NB`*dDOJYSTB)L&_3v>U+UYd(0j)>>&7feC z00_k%I4s?M6a#3!!R#p}6oYL07Wc9(fr)r%vNXnZr6^UY(#n(U!^dib5<^c~RB=8? zi}5>O7?AZ>NU7psCidw^>cu?}RBQ7!A}k>9T?&**sd8tc7^R9}in-rn;)ieDjiFfK za;M9n6*#Y!abFK$Y;G!5?o6Pct(AoeHrGz4+_1tbq>y3-o78eBR=`Zd|9)?`Q}j!( zKgHt;{fn7A?w4>wgnLxkiczd!BWXldYb71r|AZK$dcx_Zkz4Q3$aI`cDPsZbMgSP& z3UiFC_N>`91aGkL0do#u&4b%ZtWBVykq~*gj$@pT`bImsoh|g?XMd48diRmDvQZHJ z?&$5K>iSL^AHQ%%C{@}!BHS+%VpEB=12RXokyOB@6mBN9sN+on`l=RcW20v9LP`}V zQZWCIFkglKc=SLu?b+_8E!{5K+T#+ZW+5csCe6| zdeT2*rGyP9o(W*Xsdzaflv}9+A;h)eh`0yiXSJ@1F-NMk71JP;DwC6bF>WDP2fhCK z>*70j>y}naro5;N)OjgTLTxST9K1%G?7TOSYcvAzDy1pfKWYl+2+%rfDkv7VaX*&V zPmT{!WmO%8Lw?SKH{OZ-N);$GQD;6b1Ippy{(^C#FH^DDI7*e}+rf!(Z=h5G#zuze z|M}xT7IAcrA3siQZEf`RuYX;fpnd-N=c%Egk)Hk7$Hlb(lq!|3D8-T{N^*YH{N9Qj zHYY{HbtNfP6jXmIR-po{l~M)nt-#k$Pe=H@I?3to6z+H2Zg&njoz-;t+G}J^jgf_B zMSG5qn<*K`oPB$gDgf5fe2Nv!tr+{aQ>g-l%HWWV`6%XRe2A+Co+teyqZEY-(zQVO zE1B=Z8Y>8UH72YRZOx7)YlEI}ofUhh^nIle_8U>In%k{dK|fb{DtNd&cs79c)AOT{ zA*_W`#m|2aO+^f8av@5$m_LDB0=ypL6ndGa7NayW6J2us9Qvew(PTup-sCl5n&o%D zHWZ`_{eHSM7!dbF({)jbQU$J_=F;xkI~!mz1>Ph{W>YAK-gsw}*X0>5f37eeRK>i1 zYm-#+RG6YU_uU+vp|{SB^TZeCamW{#s(36)7w}l?o!oaiTjgOQb44uY-naRgZ(kUv ziRpRadU(C8RZt&zFQt40VgAUhRs0*=F6w1j=yw>G=wBEUuvme+rZ|rk97@yj!LX>* z=3fk{xeVh6?lNiS zRroc;K{6}+(SySlp}cfD zQZ&YE)##{|TAP#NJ{$(#-t89m;hF&Rhw47G5$agZ|Jga+S)i;S#O~8qi(aX6^ypDK zd-km0HNiVT>4Z3=o!xe^CxRCP1t`d>(r&f^tT9GPmG<7xrmwhnP@dU)Ln6<}x`$!o z#jGIGRW>@2-4u1FeF~R?tvn$pz?`<2mcT;0iPC_Hu2cfU2c>wmvf z00timfHKYOY|C}SWdxksz=8~bp*crt(+NQ%VpxH>Rb>N~ za|LFEXe>}Yc!1WnM(WzK&w%z*O-&tr`0)mwXLDVNZA74-R;FEzVxxh6q6OASy+Wn2&X%*` z)S{T)q=d14zuW}fcc@yNI7_75yutN|4ctZ}^b;{&uzOqv7{3$gwGJ@K4`b6PeWg?^ zAh192_MD*Wnz#sOE_mtINS@es3|#-_yV>!L6Sw+2%8e>pin?1R-vMDd2>z{=-)|=r z2$|F5`Y&gMOBrHn%cIB->d68=;*_rAiJwZd`H0FLcp4F zcLANT_zs!xP}|Jxtng7(*-DjR|rbiCe2zus$dXaW$yGP{h^Hp%)lygBMj>85#2l3wcb9lxx+54V-uuh~s zcDP0y%E$-A{=s!d)ZLgX%K{HlFBHbJFAF3fL3rT|uLsmq-5c-pw%0 z%*?EIK3FlXz5ko^wVzz2QQpW8^9Bc-+&yIpRDauEX+z`lA1YvRqN%bMUZ11UG3kTz zejdzwcNXhAUS zXO{*y%ZI^{F#V4g=7lyHj9R`x^)0Rh{rVT$i|(yB(fB9doT4aCz~wQT=~*9L_LAV>w{fOkY4L%^)RMh_V%Q!bcbsvu-s4YY#cZ1DQ* zCS)bT-t`7f{%;1VFCB#xDgWRfE)`al6Kkzd(E^qa=);)naN=()twhm6+s~)x;fBTx(tC6g_cY zrI^nZ(2sujvjqyK*SelM6FqW&Z4RG)>hvOAn~?Ll$C9F_AFj!%E1Wd^&P#K&V+Yrd zxt1Ib3z<^GbmoFjSgJHP*~Dquj&vNjdDZMS6gSdJgW6ax7pPvV6N0c!Z3f{#9K2Zi zz+(>7Js2)~cFM7ZQ+QCU0O}shdkE&b8i);Ry3Zj%{{G#E=%*(ZsJ5|{d|n^jfB*e- z>eMMpCZc3F`^e=PqlJhpV7UU-!&2qhkN#6?YF;Xofl&X?{^EC;=S(LscD2>eLr?rO zp#achc4mvd-Wm?IE8_%{fiSAyFcsJ^ti|GCHOY5#Wl9BrWbcr-x2 z{||nT&Yn3delvonvXXxElOK`U;t=sw5U4&8ouN}7_~@o?&Wgo6NPNu_ZBT0`u2n(7L6)NeWAgr0yh))SCrEc*0wRu(v24ju`g-Mq&K z9~6(n>LJDb!7O5@KnaBU!5pb9%a#M?;g+;zh*24wb~Dv;KPd((_&BP+(Iw}y#~-fa zekR9~k~7759-0jr^8rer-qB{K2aZTf>Yu$eE8^P$bKy93@VIhU?IMePz zEigCt@!E-d9)GxAScJhU?ydLc#XZBYTFUeMl>*}vF?!kGzF4=Z3m@i92Sq5{?9y?*bDU8G!l0nvd;@}9cEtBi@f{EpZc1ydDt z!%OsM@5jaa0=2dzbyu0FlWAYGiH_~AB3qS%>^=4L#<-c@IJZdep11JYlw|%QPD8^M zUMJ1;+*3qf__;Qbhl1~w%M_XL3b%PduKT3LOaXr8<(U-yx6|2i)$UACqq{;p^Y~U9 zZRhcfXWF(k)7Re)@jeOib$Kn`?f1XfNn`ULqgX?tk)|{A(E+{SLzIb^o<4F;zC9(6>b{bW4!s zMFrsgOHH&`XjM#z;RJ7zVa|@ZR=RtTF2B$ZF|QZv3QUiB zp7!${D!4TgrlA>TY)wnaZH>@l_c^Jlo;O^~JcIa+=|aDkVkw^g`I_zRNjkLGp7|Yg z^VT9wdU+k>-#whiqsNx!asE0p*(tcYiPFwaqW!yVIeA=@3-WX4>UZw zNTc)I54nske$V4a9MsxKncuCJ7@fVk$aN*_b8AbIjvjF2l*YYZ9I@d3Y7@2#Yz|sU}KkWokZV9KSX~= zy~6Sb{+OX;_qgz`8*tuF7fHBHDRR81^#F%zw1jsrCqa;>>Uuf1OenGm% zZZRh23nOUn@p!D_ddwm4Igd02@Exn=ja1(NAWQ!FPy7OX^kbi+kALb*^wE!hf({%y zEIyxl?0!19w}ak0^BRTIibkBuE|q6MAJp?RPJZsT?T?V#v-Hpvgy!#``C*RosiD$A zoxP75x>gDW7wG(@lj(29K=5(28QM;{EP;@DCAfX=ze=n3cHT$r>~T?T+Ttyi>ZH2n zLqfRYpSngbzVs?hPR)qlj9|4|=u;m(P9|G5&ox#G%>0CAXBX)CS7vCE*FU(YQWOYS z$Zly8!lGi`e;K*^(xySdVss6#R_?!4I{IELW+HO}?ww@5i2Jj+Fe_Zn0X|*apIF$* zo!4gAM~lU3-G6BT-bN{l0M*Yhf1qCEzED16ZQXyF_<3lT3hL^NiBHhhUc9G?nw!kj z+nwz*1r;h74;TjNp`cf&j823J0kPqxMoU}q$4x>;m?Dj1A%nshUS-{IB@JU~aQ(=Z=BDP<{OR0h;> zu~2a`&>Ddlj~S+U?jI2F_m6~VcseZ7LIo_-@EfjK3@2!k`<}XQJ{TA25H{o8&8B$@ z2ZjVMhp~w<6OJ#v7w*mA&J5{_Cqn(eCDKX&rAj>7B$OzKp@lWKy1JU`>gvela+O3} zaxzu8d2Cm4o0{m-bw35UoanlG_gfeTP+p>q#dmJ+&wi|hc5L-fN7p`bHUB!*H9bIm zhdx6)c0Wm7Ej#I@7cNl9XQz-?l5f#QBjaZ3AGFgeC;$KK{Rfz&$8{bGpU!zwPtLQm zIp{u#7rV*U>8{I zVso6hlVi{HbWZC+yBF*e_Ywo-fu{;nX?x);SfU-k~Piz3+3h=kSxX zefNFz=9|xm^4EL+N`bmUztqkHVT^&@X*RKrm+9X!6d1y79@tS!;p9FPHtpNHlWp$1 zY5$?4v}4z9+O&C#NXL)tp*T%ZIO-=em&LKY7;Cd*UTk`S!o3qhamNCf{cNvnawlnv zJ3)W^a)fm&==f|iv0NFLP0;zV1U=GWp!;iMR2dGCDZ=f?TuC>_BQ!FOxh1aW3dklY zgST%Y+LKLUAA0DUZL+Y=-WuP0?1^H^w-9`4kqh$#+h%{iWXdYrENIbw#O) z-?B|qjs^Z%Y?&)TImS4z6w{P1_hmRhoE!$;T+;#UoR9oLbcO7N@#O$X) zB5L;l-^TT|}mFd}4 z3s`ZoKB2(mO8assurl(omLbAm0NzeQMFC1K+A!V$1LIbQ0t0yh4?s*-!63xG6foda z9suPX1EpKnz4-d9Am6aU3?7W_8V^!T^npZD zSc*`|U+rJa6HiSZ!Yc+w<%KJL9>qL+M}iFIUYQoU6dwwD=>zVt=zUxRe?ZU-GWo}2E! z-$9SP$4U1dCvn{${N5vc&wcdge{-6?{gZJadv6DpyEn_N2E0^i>zdMkX|eqJ`T0P$ zTu_xDQ9Nw>X>oWz(ZRjhvMWfajHL+`4fF^V+=~SR*b7RVpnrihYH74BN_Y;==igIG z!n;6#Bice%*Ha9va3oCqLm^HQj7{X~cefI2*@jMEs;4toI_TzD3y;&R=Qi4f?F2$mkI*P& zZvpU@ak?w1bJJF8Y2QXoEt_c87o>r~v7B`6#t8NF_KSpt0oAn))WAASee>b;lhz*a z`qNJC!~T?BX7YQ`zu_$b57b@TJS_c40>i4W$a_dWIqRn}Cdulo7H zd*1UfJ^1i@Gv#pK{SV0Uc;6$`+L4ViRESV1BNrRcqFW8hlaj>{2<0k50y;&82?qrz z9QocGi;??~)92udEm7*8EV_Anmt(D3tH)uWU;k{gZhGjrUdXo;S&b=i{#SmXiR!D( zBJJJk5XT<5w>o`YE{U-bfK}64LIQifl!=uxHX>FM;%hYo%X$$i3b&hB0bn>_l3YQX z2Vk|t%Ft|zzVp0KHw{eP`Y{XNmqGEYmV`otNOQ@h- z!iXybtgOR#VqzW}Nh9n8_Um}_%p9HMgn!Rp_KQiZ^-l9?59NH|`}F$r`eSYKgGn?@ zKxk7_L$-~ej`PoJ!}+Wg3`YHSw^k_NY(O^CFuBcdEK1hY>p2sQ06f|}*0X&6#G*7i zc`|*~yAjK8Yl=_-PF-1`zx;evzN>9KGvHNq85C z5~1s@idZp<@Ksv52fb385Ml`XZQxt)RGSUohs7PR8w81vO7XX+Sm%@^3)%qm767`- zdH|E*s0(d^XN^MsxnfCq&jIlG%0KT(d)OeFME<#@?yV?shJFEZmRY+P<_i5@i%bq zv6_r7rAO+l2Ko9I`X#)~3c+ZEXD{pFo@T0VY)K!@!co;qM-Dxb{_9o%1+a0(DCn9f zkA$U)TH3nON3*b3G}4iykBQ%9LZx)9kEFaMC{IQ%g+<;V1&XYZ6%Fl#?<*&ZZOEJZ zkp7zi5&A`8OIK-Ovu6G87V7}zQKT)VPZzo37Gvo*SF+Iz<#tP#v&7JEw-*?owQ)bo z#7Y?(6(CkrS}vADu&g(sq5#EKkr%g%SjmSr55Q`Om0;XhG!+B9SrAH7CH$?$LOSdZ zfIU8N4Z>F_9NAxy@p6d9llspH$osTO`wT5gB~%o!>hra?d}7icW%Tl?dHVCOjV?-m z@poesOBOCe5E0ioU)rSh!BG2|00W#ic|Meh7mv`CnEU|nUD{`4Lz+ln<8keIgl7Xl zy1}yv3FF$z2^I9C-13ucXz6jGo{d_RA@%@k#`wj*(Z<8!1R?YYz7hRmT@%X?5I%aL zm{7aOBNjDm929PIcPdhIe?_BbKcSnZuKnNXt5%L;vQ7_J6s6s}1>uVBIU-}r|9oNj zZB0w4V65xExp>3!GFFD^sWA%WkSceoEVvcz0cEkg@_?=e^bMrw)e|Y!B@H=*%9-;d zj!)0#=C>H3qCH*+=nsmhSc|@)h?3#ELvFJyvpw6+H-@fS-3K_G{>t$TmVk z_Vfqo^!Yh4{$sxo?5BcriomE&hey2KfWDufv}2gw`9eu+@1x%H&nw~xb)SDudoS8V z{`r-VPSF2AYGALu+X=K)=*l1lb5MfFz#eaxE?p8t%9Bq%N$+{jd&J)#``E|CM(0P5 z9wlu^(&`GSzay*pt&oDj05y0oP+h%`jPc79o(|eSIY6}WGD^d{WKWelZ$MiQ zU;?+vyELPYID!zkY9lY~0pez38mn1~0jnLJerYECmo&&q-Q@m4Us&v`ayzhL_EfQ? z=-?Xcse-*5_wLjWkAj%Cm--h^s1|!S1Zdw_T*Q^Nx^|Gm-9holB%jGGoAm-#TYB6U zF<7dYrig`)@CwK~2$y1etYF152LAFME2W{lr^?y@d#4~3+iRr|^!8v8djrhG2^+W1 z%;rvnt_Pu_02y~X_gK+`HV=@&FqANHfOZKvztTNcN(H{BXE;h%2ePT3Wok5OU~NVA z>xFQN5=IjZPQ+Oc3e$;mLGp7|#ra<0UBTnh@Kju!fBLm~I)6PZo`Fs30mz4$`DD&J zkQSnb%oqVr7knT3>T(Db)X#~xeL_~Dj@sLtWVD$nlrZR~Vx-DEm+jSoNKTq#d&t6u zDr7Lm{i{4iy>!Z-Io~%L6J=G)`XK5Fo4SAh`5C&x*J+=DvH~DJdxr4++4KEl@)@dH zv62;}hQjg*mE3-Wc8!VCQUDSK^{Mm=tRlqX1=N8e&ej#0>O=oPTyZs_qODoz1USDQ zsIjN0#$}+!YBN1{cQtKpu~9P0dP*ct6?T>fT$TAYIO<0|bws^aNex}A&Rt0F^cDE>FB<;cxv>QxTp1&4Y)t)MNZa!&-Q1Fve zksLx&B~(84rk(c5y&bR-d^PJXufI7%*t|PG&CJHg$8xP0?yNmka2#Vz@x6QUu@s?# zbB%R2(dJ4?80(cjwG@m78yQkngiY$B(I}6ri1%JR#pBp$H=0SIP)PSWr2J+J#$+SQdF`Gm4NV<1Gc`)_n3UiCWUg$E zg;_5D-0i6XS&)?nC|{IwzMigye*rd-fx0?iGeKvH(5%l$6O(4zvDL(N!S?JN>z{9@ zI8RAxZp!x4QVA7|v9Q&U2bCZvE?o_X(46QSm>`{D8G|rWSR|*tw$y}nBXv5dcV=`w z?rYiOCO)S2SV39l?!kb3V#8}ZOYX5^7A1=NvIq}{MzPtJ0z6WuXQM3l zvA9VdL)~Q-Rq%Hx-4JaE-&RKHfUHL!EtU|j3JW*QCL7gNx3QjX7kjDz*k1*IFBjOX z9;vD#P9DcNJ@d*G4Npcy`$RorzZUd0?O3EpA}`CL{o5-<8&0IEDV*HOvdKt|jg9Fm ziO!rpMd#0*qfdS6Q`FGVAo6+T$`z`wuNQm3^z`)72OfVS(+~Qu{XN|r4~y@GY+8%% zp$HZ2H(-2$UZDW8YKGgl>eKtSxT(T9OE%*GMHfy{XzpZA`rh|`NKe1=6zljm#QpF* zI=-(eC%^HT1&Rzx+Z}u2d!6zmyhZ=~ZGHLr$R-o*u9xFk++k1esS>8bd#Yeg4$qY- zd}Evv3({_LVsRMjvA|?7MPIw1|ISbCGEtK|owq6vy)$c}87>0_?5T2muZ!%KX;B`@ z(3wT$@%3+fpI&(58R{FjM73-)X?0OOV2qJ_sz6?tM17R^RJmi3?O0_L$Aos`ZHZz# zu%|L7^wTRRX6Yx-O^VeVS;&V(qX|Ag&F80b9((LyY4HhRFksT;&c_mknm)b6Rksk! zdowoDH5i>_wpR0?xH6;nRso(K*h@hx?DIWVq$fzW4Fgad%N{FbtS46Ey#grjmH+u? z*Mx_IA_i4^Sx-Vm0S2e?3VAnptSlF?BrC*;#YszuSJ&DFX@WF4m&{xPLIwMpP52Vx z+=;URnwrm^mj((O7yPd}rcF^!3LyA<2SUptR8SxA8i8EGzBO3rf=Tw3LNAX7iz(x! zf=%wP-Hha%udL>Gw>pHu2Y_S=#dDv5q)@oL<#{|uD`Rgbp`ri+5BDHpq7-fTR;H4n zQ?-~}!NQuA*ZSJSWi!w(f1;T_@qq?P*&nB*{gbqJ|L17e&iAqo+Cqs)6Dy;+DH3XC zBd?P_^u({y)}5cHl=CxGRozaXd9smqc01Eg-WZ6pIQq-K9}(%fH+(eAIs($)d}mY~ z`^JyQbNcpLVTMJ+>E4KL`u;0(xpo8NCvVKr+k8$h_06Vd=zfk-3Za5)uz0Z4q$b%* zfzg!UvBk(Taf%}G3Eh-TP15#FL6&=QLB1fYi#8>alR4L0?K5O^$docnQaCm)Qi7jD zhGLNnRu3EN_^lc;96&EO-3XWq^6MCFVSX9{47i9e`DRdp!aUhq1d~R?!Bqo5h*O!{~JX3_OCywJA z5QbBErodw*n0LMMSP6^g0T{FKP5BAo#_H)jdM*Ryxdc5YKXgVnGxZ z+(C~+-xPX%9vK0m1q&tWyf*5@!l@-}pckHhfgXMIQTo$A{Zsn0Kl?NK%2&QZ$B!SU z6DLkkb#*oE+_@t|r~psBILY4{(*|B zQA;04!|1k?p}vY@CNqzZ>4O63FJ_UfAY?gJcwoa>$*nc9mM@|yQR$*&rJLgXPUwdU zC}Ru1MLs%fcSwTjumhUSovOGCnrg99?D}l zFZi^aNR>)7fY3?#*W?4&D@9r;@%-G?0MAkr!`XahN6uR@*}D>8(tczt`>mV1^W-*d@Brg0OQ2K&9E@A6rrMk zI$UexdnrPtkMknRAuV=LKOk20FgcCM_vPge&(nte!ZTDjFaUd~Xbnw}W7s5Ckx9T( zE2p%8w~qFG>p`fj2M`Jlu$xj;$=TI<#Khw1@8x3jhocmT<(4PzdH=mt+)iBSaz}fO zQ~zLy&Ry}->_U?K>3eGJ$whmw;rY1DWQ@`9oIIw5H+_%FhsBhwf7k&dtg>k98)&N} z`bVFT`jU6ceb%HIx;C$+0y;i6v<0%?W)Q2@kw0Kc z$f%{g6-p&kmJ7MZMd{yE6#TvQZXIu zC$GH7<7c*AFU(X@BIXhV(MnNU@1x2ZzsT=u$6%1?+C2bNJL_z7uzq3`y2n6z;t_HY z`w#&6ZMm&QE;K;7V6j9oz(z+oD`nS?D7S%xlsl}0T)3Q~i&t3A z*1%q78?z(Izhyqey(JPVdb+_hw+F0j?%;2S_b7nx!92pHs|!?BZOQ0l%Z1SO_?zYZ z2GM6gst8?A6V6K=$EyCeW~a{al(@c--l?D^U{->v3X2GFdOK}A$T1K=v%a{PklwM? zEo3LWA)zCjy)@7DlN9rC(4E>?rrs$YI2!>VRq`XA=mBjFdT&!*4K;g@2su19HYU!& z>!YelZ$I3^fEUW~J!iRp&Cum*(&J^6Wz1wi>Q-oD+OY`oK}(pm@bCNf%XdbS-8372 zoMpC&_U+qGsbqpChpy0vKlV9sz7Y2B-%J0$|L||As-au_{k#9>A({@x#n{o+zL=<3 z4v_bi5Gv?eHq+AbBot2yLIpZRBilONeN(p%@uJT@g+zlhV|O*4;^CVKRqB(>J*>jog2M_6uF zvrdTd0%ZWQN?{l4DbOttQKzF#j=is)oDmC+;Sn|BXB#liRUOM*hxA^SOm+ZL1!+#ZO4rLSqI#ekkzyNGw*3{^v zu}QdlXB7ts7r5I(2~r_jv^B9DLIrsBEE~2gjBXd!JN%cLK)Su*zp~|v!S$CuQYXG$ z4>$Tl^vW4IDBCP?G8tBGK;LQ<3I!%ZY{^hy`60Fd41Q<>P%NM@!st;e{tE$Z{^v0i z7zjwY(o3Qo{_EC2g$G+nh_I2t1(B{@o}=CSs%dB>DrDDs1M*IV;lczRCZsoNC@_qT z`1f`sybC~{;YETn*ieKDz*$rTh~77d#AT_%7nOqL5-MmHgKVT~>lTwf&@W(6m69Oa z6@Fd_6+nfov2t;K{4p=xd!&l??{rgb;{)Vv{s^_U-%Y)jZ%}xS$M~ovC#515nwf8* z%BEkWg%}&vWTobsQNrrq9jps2aDNKL|e_V1EoGFd!ib9w3X z>9aKFlZ!qO?gt5Bi2!V*iobvDpZ*q^Em9{9&Av#9*rb@KMu<2xcNo*!c5=Ibey`Vm zv|}dPtaj0e!div@DhBj#ZAdMbOL|yAZtCT!6m0D9U)k_>(8*N(N(ujUy9gCAaoi|3 zPe%S$lJ44HMRlyloxNJic14te!JtU-*aB5K&(PSkKjY;GpnOzQ)0Qt51I_tkIpZ(t z0eJ&dJ>zd2UrG2cgez%p*+z|RM``EYy-Q*sZ zVS}KXpdD%x(vayjxw3-k{x=5zD=Z7^+55A^wp3MW-KTLiJa+VEc&`!3Su zejoL5{~PCe4r0Yf8d@D1x`mcd0r5RO&Ha+|g*l_CnIQRQhFPx8a6V^gY~(6kzW6#_ zymp10ZX?S^nZ&jLRoJi4BvNyui~CQ6+meqa#(L<|#aCHROp5kXUAeM$g#I-(9TEA` zj;E0GOA#sn?uhe!OC?39Kz0Vg33~gApPpwsd<1i7eE~XmBfw=F5ak+3m#dv^PY2?s zG9W{Q%wRbK0z@y(hFG5SyXO5|eh!3IPLaWw;(o`uG#9>aik}U%aCVa8c3`=r zijggc>%Bp`cy*yj3S?66V2I|zvV5VaA$Gb#KB;oOHarf-f!!~hSE0qq0@1aeoKo%U|V03N5F{!r!~T#HqVV-ryt zoRlu3P*9iWId=P@N31}|mx-0t0q^aDOKNOXVg=7u*WIp!Z-&f8KiY7F3Ik=OB|!85fOHeqf*i%SmI|~VOyr_pWBkXx(C-W7sT6EnQbl@Ftb|lq zicnF=Z(B(CcJ-coh*n|08tQm_HeI8Ev1m!8 ziYOQ8tLas~0O|pgDuAkI{Eg#Fkt&$fRpp4u-xTWsAXPSTzcyK0gsjj*Z~x2u>^ynx zOwjx9u~T=epSqgoMRM5|=-S{U8B8Ji@IzMG-WAB4i$(p^H!&;Dr3^uu_Jx+!j*4OR zqzVdOF3^Mgedj#U#VZybYjgVz_CmRK!^ZU(7kwk2RKXr)+C>D{dr?0I@_JbZvZe${ zpmePBmqE~gKuC%6cpmf=1x1_`I$j8G^gLB>j`y&)#6%W1$Gg_W?`IIGV!w@^Of9}y6^2HR*-*$A4~9ip_8GF z7>pLO*`>EQ`Y2Yn%Qk2b*W6~)^Nzy^w|Nz@MFC~@zPr8j;9Xuiu(M)O+SKZx=U<&B zo5Ml1Rjb=m1s+#uJCRr)%a({}|Ahd(BA-w}-Z2l+I~=6zH-pr3bC&vt26-I2MDLt? zh0b1hovsgFr^*^LRcTU9t%a(*W~$)dND0FNUGJCoAc53DJ4acpgj7MfVs8{NpMU|0 z|F6cEVuT9%EBaba|1FXbva6+05-I@X^U#R&1k{t!3L);dkOPpJkPqlf+Igr#sHujn zD=)&fU+VW#C`76#U=JuMI}IYQ$n$c6Dnf#sLK#-FPK9?C1ICy#sUmTQk}9P&z%ulK z)d!_|t0>g7;M}vrP3^6A?lf5aX%VYaFoAMtZw1|VyhdzHzg)a@=JtB20Lvj&fQ6WW zW`eBzmzWfx0zfboB2^Y*#zpr|%%|x3P>e1QMCr<4lx|KXGUsM>2o)g2vi17Ss7R57 zk#0`L=(RHobg4H?W3!2jaRk8#LIwYV%=+moK5>sf%!Ai-oL+xtfiCuh#c$;egMnhB zlPZ8DRxqGtCn+H4%f!mcfPMgC4nSO1DB1YNeY@NlV*+`cn2OOT8{kkRK(=7w77$8M zx?h(`mDOQ21Ph22l}aU8U`S)*yjUC)iHj5Z8WI%G2+O(@C54<*K)XfVM_InX>l#fq z1{pe=;`>ZI{$RsG6Dxhm%rh+(d5>!6YfY>KLq^W8f%OcT2PY3zT4H6^2RCV~h)U=t zzn=|JPB1=ZSf;Aq`AP5G=y>jP)wAaPa)NV15-MCSt?AGlg)k&0{IdB};|uBn;|A(I zKPfClsO0Yf1Bg7WkkmlC8qtJ6K^~hMvxcP>c>kSFr~n|1kallz(U$h?w?RTaVe1PkkWk}FZy;t8P zhtsY5{LU?h$mNlfq^luShHl=ZH(q~@>gwufXlO_fE0~aY`st@Le=kLoMyw^W+O2^mRPeCHYB*bSdQi;yfc(a&|H*dN*H-se4XC&N=f<8 zDVBnqhX|KPnD3kAZ;zSedkf{Ml!Rya_`4Poaq*pV(HPCgV!GEZm0~7YPRLu7|3;o> zxSp2towyIrK|W?9QIRikob!oq$MI=?rYH-|eJYvV2JsABhtxkA)P27y|NLZ58L6gn zv24cP3yR=AkvqOBXn6S2)XqNR(90#d#_r3_VH%^f$*-NIxrJNKFoTqC8eewZ$ z*xBjKkxdwnFZTt+48p-39`POpOmGfPay@e%@GUEukSc_glPU>eA1EkN<>nCdauVc; zruta_07-z5Y4nkuofczL6mzyN#lPYJWD81U(OWNg|#g3qJ$paOHY{+GYK?G(6EteM9wh>AIDVIk?|=xr|-hj+}x>frl*!l6+Dn z&iaQ|PUl0l8IUS$d5OM+ew;s_g+8Z8r~r_)m>VpV^z5qA?tv{J+tG5GHp&&m`p86t z{51!Qg;EmakjfkS1U$LWx8>Z0JO`PAb2x_np}q~{ zA&x1#2lIV+Cf<((*@(RBmEUqvh*ZJ23o^y!zycuIPLN0BNqt8)&(f=Ed@>>yG+-|) z90t*?+L4K$fzXur4!mzEK%SRL6^V^Ss&LINO{%Ox%lvtSrr6-E(o$z32P+fHLrSbn zY^=lPa(0ng8ndx+my7lAQUR7rs;mT1=Agjh*;=I@f>}G6ln1yhnWr%*UTqvJLj8F%uq5TZ9;9L_x3 zRpp@JaW~5eR>%xNexiXcTye7!XQti(1NHP9XyB$X=b13x?e?`NRzRklz2wZiN9DoA z*@g@Qv4TmAS5DYyiq98H^>qjp#YX=P8x4(GsJj!&qx8B_>Ecy9!%SN@N%@a-_M(-B zN3A)}3WZJ7-iiqdqnPx@o zid4ab)-`VXF^xLr?_k5T+Ca&wYzo+uv|vk8(2>eHek)VNof7XvO0b;LyXJN!_5JuA zb#q@@Wu9<<*d@yn&knNe&%dVBq{<2TiE(ql?|8-X@|LJXo)RL-eBpl9x%fHic+8VM zo}X}!x(-Q}P3g%RHd3v2M_cYB(EG7!UqO#h0Re%@5qPpJH(8A-YHf7Ve4v7y_9)we z5s_TZ5XB=Si%1o(W>qjIbFc>(CU3C0F*fbSZ%lk)?8O3sYT@})m{fthSKbKF6Y;%j z%*F&ao`?Hz45Z4QEpDo=i1F{)MQLD&^E=M@kQnqvi*<}9xPUVCv0=vkLTb$YJwa#DC%K$)+C;xB~^k! zqu8V#VZXL-i_pS?NqE3CHzxUAvb>O2=xTsAzjORdZGQCt5(YK}7FM7lFy8}R;++eA z@f})wb2V5ku~G;iMNoJ7#L9Aj@e-@b*MnGreTi>{x5_-11tvq$7cmZEA0yNYyo`}Y zcmtqp%FstXp@O!6IWe?h%w^tlK(^l4*8o9mLxyfTeSwt)*v)f$U4&5vtY{F9z z`>M>%%`GBTiV-St4dDV(#bS|!Dr|TqQ-NZHN~wVSLHJ#d$1K|IQhi+k%^9{%sqGs5 z3zPn^6;P&-TL{fn%k2^4je;JbqC$AB6v!iFfJ!RM=nv``{}i%Cg7pUtv4Z;{YgK|Q zfgDCYwe_I|o`q1FauH(TGAcx>z{>_QSP?1!#y#zKpuS*BV_z5K1>b{l3GzF};}Onb zEXMm`Git}prGR!&CRHTvKvJcQWkaVUPtPZ)y-^OFr9odB6p#^1BEZV`GjA<#QgE$M z3aO$5IRs0wgzGi)Q37z8Yj1H-inTgdWd|kWm{^q0h2YXoDCJ`%q>2{ueiF)(RC;CR zFvx;+hF~2S%AK?ViGaZf{c!OhDFrwbhskLJy>h}t!=rEuL>%3XB`lG13^=II^&wU; zxGt~0w8-XjeTfwqBjc0Opoe1C(PpP@n_Za!AFsZ6H7LHd)@z}Id)YWm8x}Z^4K$$) z!FWPnz%|8;lrl;Oj3IdTp{=xcdFYA9o9MvdS~`7d?L1gU#t|YSL9In_DK;vi zESs|ZM%&I;L#%`&25zTv)4tBO2+J$^4G1aH(~n6GNvt40*Ln=p*`A`^+xfd%7pF}f zh@ESqftv<4rVX4&BliiTIHuCzkb(QJk@oGD$4|U%rdgknc5P45wr=?x6U*kY2_ug| zM%uhd5-$oHhEM^4P^7y;HfYBs$XqRs4-s)y#L)qsK9u_xE+rssDpJqQHESaT2f`G?<^Zs5efwtXnb^#Zd^ITMi$qJ z(@pbpzGZu=poDWhRo}6bD#b=8B7*37)=>c1qLd-a%a*j;(=h54C7Kp8Mh1e1r4c^ZhDiN zu!_*35b{f_@_|s1p}~^+iN{Ob<0>u0=;*!*YHgUL)_SA~ks4}d#B;Tz3gjQ`0|kU- z#75RTw|fNn4%-5gbybyCA-^$!gfLS;KBcVcf>7DBE6mT75e&ur<&Xl+g9x$6a zW&NNIRr@TKUp*lIsBc_5&0`eW8z%D64(c?MzH5P%5i2pFW21hw3C~h?j+R)#zbH@b zwZ#%!P(n||n7JOr3ceTp2H!48)+CKhMnoOpyRmo$<$<>&9Qj&j17(1^UnG;3k?;+$ zk=GNtgbK?_6SR1lp8^RwY_jPstPnrfE$ERP^lmP#JJcZ%B=JU}oHwG?nI<{nU% zZ7mMk!sRIJL6%RdUyP22MO#upn_VrTQYt_~qOYp?Ldb0pE64-N9p{iBGeleE_Mk_s zOz=1l@(BF_9wV?@F*sqo&_f|orK*aLFVRsUr?G_t>b-*NZQEuyZQbM+_FhwiUCjSM z9$=wCEXHFK*IB7D2r|D+sz}_1=C_v6w8k<@LxCdm`4e>VA}0G+j@8u0^KY*Yp;9Vf z$Y2HjQVDTk^W_dE0#hs-4c2CIxVMtU(IkW*lsjz*l3S0(H3T+%Iluq`7eS(#)H$-1Tn{Rzxc zA@eCWWXt9=E2d>0<#*gFCWDnlP?rJ&O(jnckBY;vBUU;W2h=%b(Pq+|CtiSx_B&wenNNeVVglI0tW{@i3T zMulvA;O;6`%B-|=n>&3+E~W-93zDL?Mk;|;OEmio{sgq&IyU6nTG)8siuRH#M78a_ zuEtE2tfXmyb6SO33-rT=I(Vg6g*vx$Ye*0(>iylFVe#*qrwutI1_+jxrj%~V2Z&{) zLO^H^c=T=U22qoJ&e4M@>f&<2xqxQ)-B5%|5x_$YD;yP2Z~27E&}epy!>YDsmSK7c z;X;=pR8|`9D<4`zMsFbr%HiGSp`ylZ>;nRWPtUdinF7*7B>?{p4_+6)3jq@_azaM# zsZa=bmU;*NRcWc`7lNAn^v_R{Z+4W1dfudk`C+arOw_TQvE?Ql!?~f}x5zg=B<>j* zoss3iz(gk|8}j8(8D-p7p!sQERkXng)dsW2(FQU3nV+yK zUaR}GH9LfDgZuTaFO=|3rMsd(G}ha5Y$T!k@-^D>T5EtTfu7vjQ636j9_5kv%E2Sja&a(@smI6H7(XTM~feCss?o0=1e8SIlpA=r4 zYT+kPh)}^Z(ASXGy3HW0Tkhg4gOCwu8!8Qr1o_>vtWgFskFt@V4v;5&Ul+^5t(#p! z7NT9DpX38=%!HM#OJI72^?vLXkO#CyL>|H3RagLl_ktiB9raTr5@);EDdaSeOk#mx zwtbg^<&9qNUKpmPrq)e5U3>cr^o^fgO>dAbH}>1P)y);I$7HUr5WQouM6n&)>7=ga zrIeY)4_QrZfKZv3T|WgDLI<%L0XY#a2OJ1#CCs$Pivg20aGBLk+K7930Gah$sIlcB z#R6x=$^ePZOn4}$2`UU$TB8Y2tA#=M6q=}1=)Y-W zMaxKAyF=nT^MQ9e9aw?A3eA26&})w{95JD!NCE(P#zZ3qHk=rrILf zf&y0HVf7rmgU}bXM9FgTz7Mshe`PT?5oOtCrLGP;xoeJ-)mlOS;dlOf`fM&f^vSy^ z8X6Mv7LzYc={+oN^xHX~Mmn-TB-#e@iHX^fG>M{xww+JT#A!~mItS49yL^B&=^HfA z{@p<_;ZO+hIyrmMK^?78s;?_PE?v29BZS#d6Art#hcdr$F2b^L->#7OzAM-5v}IF7 z5IFh3N>EE$&B_1fwZN(gl>%Z#gzaF1MxnbSYb4|oD%!EE7-0C^Njmk_lG?VD_bmYEI zh~LBgPt*M5i{dwo>I*#~nvKYM-&$v+`|qk2Ml&#P{4FuLFf%z!Ctvuo@Ja@7pK5bx zG7r4(SE;79MHqP%$^RmbV*=*o6FwT4%f^3JaB+Vz7STKxga=&uk2DJ1gD|1{cU4gT zcy?7XRt%1}#mJ~xjA4qi9+14fx=b1GZX}HfN|>{9vU1E!+Z%HiC-n9QGkvA5)|y$} zE9BH*fyHpyX1gSonwvpi)gx4}0e>IcJMc0&eyB>=6PTPve|E6m|H_FO;q9=0PldP# zV*(Z)VX_OPi5d^G$3e0zKCT^`Rs%#6z=XX5#u^Y(YxR6BAVct6EIPqTW9`aec)nv2 zP60X^Cg2da9xK}A_#^EynP+*ecF`7q#bPKcyayiPKu@1l5G(ulW_1w&D~2&iF6@zs z2%p0O2pRTrVk$vr&ZWeCfYXtpR@Q&IJ1jg-nmDh}(_}k?*A(pHnkpw9-Y-3WFJE5} z&qMu*{HASXya$usm{3H6L=mX6#suWvogQ(0E|$@7ivV?tGR41oK)t{&w^`-;MO)+i zinf_YY~(}xY}BKk*OV5h T>_B7t9bXQzIrXhF$q5JYRx5CELq5um)^uE|6JMw_{ zBY&6_E|wR)iQroWlv}CgQo(lUT1LNFicmqjf(?x9efoV3)Y0am{vkUJj&+gA3}PZl z`du!#_M#CLK zs;pZU?`)JrJQtx0+Oe^46KRX+MYz7$8ewqmwG70^T}`ytvgU zR;p!UW%)pv3=T=d7VQrPUT2$~6+n0#$k0ru&-sPBD#ASM-|c2a0jp7@%j=o*er~%6 zABBAoEMkJcjI{ws6UZr$8!4_I5ETZ4lWfjLibWiM4m>kX;8tgkkU-`>Z;(R`E-_&%B5H2L2R5`FaC=K0PM64jB*O~JO2MF&JOe*M0 z3T$A1;j)vzE6V*X_u2Wl)?*i>3Z94G%JW5?1F5oSM^IdYzcI;y^H}Y9yRar6Dg{J} z@DfOSt7-4UShG6DC{RA9tB#gDt`jqBG~Csi(ATM*t3$SVjfG)-)Zk1?UT zO6jC)++fo{Ip&iSTC9dx0d9`KjxUW^0kmEzdeA3U3b#vbsVQ%hl|ZcapJx4=>&eTq z2l`Pql+n8jkVhaF)&h$N6_zj9<0GF?0iZ)Yez%wE>-2S5=+dv92~s%jrW(&qs;;gk zzuzxXAyNfIiXu_8z~=S{)pX(dkJ(Q5i(_j^r~n}1A(yP_zJq=+RKh}Gz~zLeivB)^ zdO$f33}L)sS=4A{ozf}f7vwAC<(p@GVobz>PJ|Y#*UT|s4iB;wb9~t6ON8Fyege`T za!Gm3sP9+{px!|yqfC%bL^wgDk8GdHC06nQ&mW&JB-)YJ>k@TY2(pc3%iZO&h&^us zqmgY+YZC?hz5K1Y&p^3gt`h&&dChE>%7q-T&22Wb@Ju;(ah~OYEX&Sz8S-7C_*e-U zS0+^??f_C{-LiLQW0}QxEXEXhtSP>~O5Bfk z_Kiiwy&elIfh;KRKVD4>Ec~8%d769?qnOyJv?b~8!&SnS|4lZCt`BGLvE+?8GvVS2 zXFgz9K-pgFN&kE-)gH^l%JPB9a~M;2*X%6fpqhEGx3Iz&7v%tj0R|S%BR(<)b%d-y zo5jQ#R;AU~vT@y|uSlW4;2ls<*UGs4c>>A~fC59tDzZCjC=vGyVg-h{9;u?R8gd2r z>@Rim7;WbIhEd_6WWrDX{YzKVXBXqpJ&i)Kg;x!rB~^f1NvtSum3+X1q^Uu^Bg%65 z#M`;D9z@K6J&R{k&tJ9@_Efp&XoTgymHUD*^DLYT1PyfjkTk0N0TW%gY!O~5T7Zbz zyYtq})S?Uv)jP_xjrD}e8@9Qa48Z2-|w4`i3vgIJXlBq zkCn9|RWP<^i3v$!T)8GUl0S4H*Mmt*svtktZkQ<&$&Rg7E5e|Lh1cG!&rI|4*vvRP z>DSdcPk}&8w1s`UDui7d3dLFHGl}f;W3s!@uZXLDi4cI z>c_^$#PNJmr4X5-kWZ?tgit{jw6QEIgd`j75pFZk(E*f2srLZOAyzOCH^k!{WC@BF z1a&>jGR!-`n;HE^**R@3PL?6!r?fZtJV;!~b|F{z^$_#$i1wn-a-G<$20{3)R_-hX zN${vPQJ7dsB&7|4@3LFv!c~wR`S}AGin`RItHaIpP}(@w(;pCXVUTI~ek6=Hc;D%> zb7GDMM3voc=C)mE{&VrWAm7TQip2VoDyP0c-*~DRsj_ZayR)&vVso*u1hGDA9FMVxn5kXSL_k8RzuTZS=0U`UP zuZ~f;1X9IrO3{7$9CYlU+;m!dZ=EAazx;{DjAHTTJAQilRDi5}&s{t0bl-8gSuF1P z)4v^~V4MdZdy+o)kp`id1J`;(^y3pt?}GznO&f<51MsaRR!VJ;WnyJ{z~BhEjPk;} z78bCHT0$r_Fodcr&4M_=bubX2P@)Xc51{OTghBYP+{sG`JP+kq#>xTj4=9igtiV8- zHd{QDN(Ly(Ml3e?L)oi|?P6Fh!SeB6>=Fb|?|_3wZrn&8&Bf9Co5Y5Os(t2@D!{EI zRxVsIP*5}c%+47IvBB>>Cigi(4Dla5ZDhRz`>M!y;y3m~$;S(?8pQn{eO&fG+y^}R zP?BCdiAiAtJ@II^Z%#}R^=n8SybJrOv^3%U%Q0g0`*x{49%Z>&LIo&=R8gLfcvnw4 zL`f+?-Rq6HSS_X6jx;-H)9^3IcWtA?Sb`Ob@YGGP5m{(*Y%PF##zv@s9;tFH^(0l6 zNtH5g0YIu;h`zdVQsvf&4ceUETp55&)ej&Glvqe|AnP%bMaRkSv#s&B|kt(U}!Q%SzpSd>&bacYj+RgE~_ z)lRf)2PTQbbhRfSWHMwnR&cksc&Kl{BJ>uABgpvc#iQ_WOHv>Z zqH|Xl$e%a&Vdb`SbXNsAU0HoE7K@SH7Uh2z=*1H=G@ag41Z4#h9`Xb74l)3;zL5S4 zoqgUf_t3$DO|kY5C5sJAs;pbK?rf|U#57x5*v{*Rb>7)uO|C`TeV|5k+Ce}eB zXo&|*zTGNfWjSrKOsp&q*hdBVMhsX$89_>sgfgzmGXGqeP`R~$F^kQjQQy^7(lEj? zDEFunc%Cg6t07owJ9e-E9;4n1`oxNMe-=Gb1-O;OiWVR?UOj0P#L6e1#72ga967Kj zrAwq}kx!~%^5KP75mPzE<&S6Qk}7(5^`zY7{;`LWg1lK8`hB|8o{lnH)~57D9(*fF zl|q0ah6x|Y4j5Vr+7M%yq#9>~N+Cb|m_DhJ{ZQ?s)=D5&o2JJ~6?Ur>fP7d>nVmtA zN8%Lf3UziXfbUs~RKesILPtt0&aBy1M~UbxMY&TA+$_C3mkYF!GO1F=dO(pXO+Fj7 zSIIW0B~_~J2C{Hl#DsNMha@^+x4iV)wCFNZ!Q`Sz!%CZhYy~E#f$2~(Lp*Dt6+zoJ zXZLr(ir)pciSpkA;2!AAP{N^qDBVv1_sB6_Zs-k2Vx=&FawiijkZr*rCIAyuQ|+Mh zm*<5ZQ&SDkP3%*WwegCPD)@GIN~&=IUKA*|=@~Qi4_ImImN0d9nlr=-!g*cmp@O8! z^lXgYJRPC=dCaX4J$R2KM?4-Yk5w_gH^$G3Qb)U;I$9l4r+Ec(JVD-?IhNCA+P&Q) z^h>lI)HPOmKl}2OAdnCOZs#`HX3k!m7n7g}0lBHeEhg@9kJD+UKp@WN{cMLCgjbJ~ zbp+qM3`v8@Ja{0!6qj?&x;YM<1>i#}SSW{V5-qu)H!F z5^eMG`)XuV7Gx9ORW&O(Av*hD; z>vkIHpMRz+eMbL!gh~^6=lb8f%|lPzUnh=>yw5Mr`D9h zgPxa)Rwn47kW46sLf!b$Bh_@|fSiXI3I3{>oNaDwV7oFwftdmNFaPy_a@&wHK>~ZevCfd1c z7bW9SnjX4DAOG|h#d`|j?&F8)xBk^{QccTt@%O*~-N!Pd3ceTNz!f0>K-7Y)#3Iam zJs2_(_67(Ev0#%c6S7j3Eo6rBGFG_W8xZmmbI4maxdrJkGZW-{*iL4deD>13XfsH# zD?pge&mp=-g6iu%;yvgOr2y}TYzNc=1IUO356;-`MtFfajA<{h#q&jw=_mu(HhXq> zGS5OEhwMf>D+RE(Ecsz&bRgfC{WgRW$GD2}#QXBgztD40mig@)oAC=$1tdG$RzJ_A zis`q0>$iR{{rk3KdgO<6p=VlDE|d)PRZIr0<)%_)EFS?D0DYrT8k&p=r3r!o|CR!u zKS4K!qjd6OP&@;Iaibx`hJ~77fpCRT2OxA5qpUq%3=l4GFRfuA{>a@`Vlyv2Bv_`N zJikDRRBk!i%_-Ws*(o;M%7{!4=Ryes6bu3=df{+N8e9w*8z^rG zZat-WrC4su!k~dVg}hOE0SpBU1jsYW2d?hgyaW09$Eq{20!wpEJ`g$!gQ6P1@f*ih ziflfyNjCCn76#j`EMpiQQrVFkW1{>-3{wy$^;V$}nt9L_19SSElk*1xO3zCI`O7C% zQ0`*o9baEgr6+{ns;{+(@e;;0>K&^h>-ZQZcu{Y9_Z3SA4|_$rIn_YHIkv2q0bD;j zF_ZplF>YL)qs`kSgD~SWQ!I*=e7Qy=z=Zt zaM-~86DxMJ9xiyMhu^K;JQlFCh{ki;ThX6kTo}aP$Pcc?`7HGNa;ZHWeREla3Q*+X zC|}4S0LB2?4FH*{#(EsX>L=9O>|Az|qOQiuW2J0s2%Diun56&%3Hk?Q9rQ#67-*1n z7<=-)GSL1Zj}&m9l$DqeGIIOLl}~7UtBE&_@mnogz~oG+Kq!~B91{hKJWicLU7^ly z1@JxE5H$*zKtnkLFi2&Hp~ac?)Z9%rM+=|gHWZ&(R(UQD7_*F`tpL#fW}R^{mMOH- zcCuTG^p!HoSRwq$8Jb88lF4VFTDP1~!Putc;+7UWedZ(0)Y@pLVCr5nT6UAuwUxGS z>7t(A5GCT3WHnahqzY#>ZE9w=xwIDiYnUFWTnk5Y)kO{ z9;<<7S++pjCfSz2_h4gt$YY@ovz){@f{7S)9ODJT$U-LR9Y^2H&-ZeHiE6A&Mjmbj zFutT%AF z;E;jqT*}m@rWory389~3EQ5aIauGiZA!D+IgmT6>hxhdKnK>^e+OZ7_o^aMclaoYm zok4g~E8A{X+PB-vM_IoLg=lPob+j044J@iku#B__+sR-^iSomO9xP78SPl{ndBHQW z+Iw^|BI?)Uw(xlwdI>|^>2q^zLlC!LkI)4$Ns6%@WD^!|VIhVh=d@|>W*6&J9`P)_ z1k!DY---5y5KY_Kox(oCd-bjdkue3Lkn1MkPtcxi9zuvVyg&b17nk4J%YF)^>#L3J z9u*=i|5_w0p1jtFeKKILaaptNtyX;NU5`m)k$27u2%sItYsm5JJTieal)oc~d@bkOiWrKc#HZJRz|HJ5Rbx?DoET?el2${?d+Oca7 zRaMoH$6=+v{OiA?(XmNxb931=J;%0!k9GWMzTQlq`qVE_T?>!bt|of>#Mfwo%TxPh z_$DuxnVV&RUc$BT8d9j@{#WV9y}qN#K~FqXPn%jCGz%{ZZg2U73MTqtmq7I2;b~H-P>Ja-$UV4j5@-wuX!*7uhUh^vatv6y&yB3P9i= z-BTgtQ6g1M;pA3f`!~0=i1%A;4tn;P=Q)plQEz&wwziJm_rZ_wIOP%dyzt!r7Iluf z11zkKM&rVZ16~>M&VaWD#)km6N3?n6H32{-!luQ){Aj{gKs5uQ3z^|flMq@=u}s4A zAUm~9qe%Jzq`#qDDGW;T)0Y$3bD&hJKqjwH=;p3o->Cw>P1E1w}{ zI^+)CYhe*>=kJKe;;iFJqC!h#Xd%WzPJuvD5YuQ6z&y()wWuH;D2IH^^Oyzi42w08XhpVi6qyBHgkR9W6YQAQez z$HrA5%nHKrWQ;ENN2qrsDmIw+vrxkRC?HQ%!Zq+nIejfe*KS6{bsLdPQCLe-MIimD z?G3E>u%On%?I2a$(DnFIOhO<8&~>g0MXF#j3&)W_s*KLUO`R17C*PpC=LX-SNR=v& zNsuX6eRJ_zfUe$*iZUvcAcP^HA*gRPv9i+EwYJ2H40%-u+6i7H{Km1BVm*izJO-1n zP;Rig7!yz^A4Rf4!9iK5b9lEprv>trPpE*LfvYGcXUl2%N%S?Y8*PH3gtn%4eW?lI zvi2XUr4N6|OGl5_(wirz(>1m_C{hLSyRnZ+KB)rq^xL?d7}?k~2t#*s7xx(+bF>pG z+IC)ySm_%y(c5QP{y7oWD}9my50z7AA)_P#vKmqaKqxPHToN{TCJ3E3P8r$YljpTI z5xit@EeIW44^J0(uHc(tN7ZMx0VsRDH zjnQKiH5?~{Z67tY-9rNxPLji5%}IuYg@Owys;l2g2k-hM)i&Nm+c(WqS8Ghj(Sb2c za?5^%K96tOD8vdT*P!R%S!gy1y2JOU1)3dmS?}?#Ikr&u_@K%N{!eeY4leR{--{5gB z0prwLzxVhOn^^`0$WGFUn(7VlE; zbZ}2A1tN92&klt7`jIHj1>|J6f$OKctCO#<;p=m+MVj?HX>eqg!qJ!*VYak6smi;( zaNfrZG&w8tZZ>k>w|ZGw>?oS|*#JDZ5?q$cBURA0u$o-dBmagC3BXGQd#z&b1MN`s zIZhvbw1K)iUDV#vf#0DGNnH+)r8O zi-n1f-t%dyZ+?K<+P71ax0l|0$456={va9%@__!2ccM>LbGz8FMXr7dCJwQEZ>FZE zX3h`yRc94F`^?j_uodc+BWex-$5QnXC_%J9b`1M=Oml0ndbae+%H`; zJTXDN+z+$>p#t5eR3uWY4_nv}Nz`+{(nK_&d7muDfV*axzo)4?OUI`1^w&{2*Urr^nv^1e8GWOhu~TPs|ad3}*f= z8<{My0}P@KfMA3Cgxtrmd_n=`i8&kS`_L;PZy;0k052@aRrx;bdBoq6Nb-0i_xb7{ z400VxvI8E;Xdebja+{ZWD{P6S^Yu1(d5ksS?$YD%Lcq@(Dhhd+oa&8#Mfv zzOhwC5v*A)E`HFuHIQ3`wG96SV801?Y3%Q|(T*-`R+u|s1FR(c7x3!2APrB(MW`F! zT;UK>CPPYWRLYg$NZD9t>ojA~VZaf4p+i!AdLIS^7X4sH4Fvg*T)x z1qcJylMes2KQH_jaIFXDWMAoOPtnnXDM1{rBor7X@y}htN=7KI>4OZAD(JiKy+6rH zI{Ku6e)6m&S@7NYuv${IYdfBoq~~8X5;m%T^8LAT0TU1}y)K{ef%nRDAWBZ2Hn5V- zMr!)GGDH~B;r&VReE>p_VIl+oA+v86`aH)}?-mE$wYP8x5*SAccvc}`!O1^7pAE;b=Hb5zJSzV% z3^Q%`uP=T~hD=#5^1t*4FVE8WbbQJ1UuYlMada_~DKi-jQWv|?7ZCpfAG*Jqn)2$d z81zC_eE%gM=TXWEv=OyYemVSC8MhNE{8#0enYyawU<>;Lt3iQ19d`QgV-4c>OzMlY zYw!KyH}J6!Jwclut}(YH@6*N34)nxN`Fz z@>K5?;b_o*zWwFjPM=wfj?D+@=mVHIVHp_vd$JjO>CMw~^wK+XA{>(zkk{JKUeJZt zD-_sT0eQhnbr2z#_`}A(Sjh}o2NDHD0Z=IX7m#aHupHv!$_}+!O!UT^rP-lN0h<{= zaBo!PoiATimwm)nlp1rLoRmqk)c zC}Q6N?5%={P1Ly>xA8P=ihp2tg*YZA_Cc6gv+`CCpM0c&hUb5o+Pk(;LsLuoXfDp4 ze}(?yFMnH141ebFy_B>*Njvu)Ay0)y@zdbj-~Dg&!b{(xDjtVE_lXbCeB>}4I(|Qy zO!{+A|MgG*8C}0|hIY0&>E8Q(i44}wwD-V~^x4Jur~h2`)%PE-q56)0LDk-R+PrP2 zIF^s;nNj+8zyC=Qw(qka+DlR6hpBV(j)LEMPJHX{EIa%c_LM+>TMDRG>;?0WKh-AM zFyIf?(AB}?;`fdnJH)?3{TJzt=e{O>>)`{x@PCoZQ$wjFkNfjqqJQ~&m&l3zHa&9j z9dtl=D4-8Laj%yidq~Q<$>Tv|DIlW{(0KEb*uOrp|P%9xk8reFWfe=g1eBNu;(zVrM9x3R2Uxvj%V2e!$*Miv4l`o@nM#c!w6DZ*_n z2Uhbeox1Q;j%Ukq2^9d}9uC>akl4Q_d#c2_pCWa%gsHRXB7OTOqcoY8B}<`D_^*BY z_ouHQ`m-fk{IIBlAN=44^yyE3n!f(^uhakiTfapg`S>T(R}=m2 zzj-(l{;R28Mj;A?;l%;3HxdMGJ`lO0a@*YQ6vVb3Y!+*Kb;lKW#&lZ>O?>3Y@Ro)F)+=o|) z#SdDuM{gjkrKd`YFUKZyP!MJ(!?eBInQ`OOVkMp`z~FdHcn2W_8{}-E34GKOyi&AD zA^*5Kr+1I4Z{#!ooF1TD!x+H7=)ZtkDGmh#O5a+0tf)M$2FNq&7qUm?JF_~B^Srdj zigcNj9xGXI5k08#K$}9sZyZ}GviZDy9xE#a@==UX!6xUZ1LV1!Hb(NZ!GUH2Ls*-D z%Gz4mcfdnC*f2&&ujK;XDuIBJWn_{nD;D>GUVUK0wE&qRVf-n zf~OFSM0qZefbo#zd$3wcJ`2*Ty*0weqnUf>7qD^)giea(3HBxd>7RY}N)qIYwyah| zr~q^G2{925uSHDC9o$nP$Z>^%p|FVEj#d9idY&p;?-9r^B?EEfeRo%gF-|WzQ2*&v z=r~;NUpt$fe8;oot1IPnWy&Ve9|Iun;UR{F9InojU2!gV;0gf?iiW(%;R z*(!(??fbRKU@+6{JeNnxNEL1)RdUk14l8MUM`FUzL&6v{G>W+S*}SYc`E-tP!V2X4 zW0fAP0GA<8kRCkb(ao<)vvUrX3l_3+y*7AdNLVCnXsNyKVo!+X10XAA>t*6S--EL~;u|xaL;>olqy>lf<3oIJ|w8yfi zN*U_`<*8zu=do>;#{ss1F`g-CJyk+Gr7 z6>du=Mm|u;Qw4zDF7y~43-CPr3&H`mC??`UtP{cW1i<2uT5pPVg@n+dkSg5Rq}?dI zaq+j6brAgPaw4pZJPrZ{w1#hfjz-7BEO(_BiWqz~siO@#msyNSSQKKlrKqbTyYB(K zMltz^?@h$pOYd4p>zU;nq`6TrZTw?p%NPBm5 za{1O!OUD-0!}RB#PQ3Y3nwc4=I{wy{=IxYB*r=&(Q~K;;{N!hUE&koo>L9CqC)u4& zs;zGl$MO*hEzpZEeOq{{?A_MDwp;_%)VGk^qfZFQZ+%|W1IoKpTKF@XyL6P{)m0`ECkoq2vV=Ah}hR`I*8PVW0M@0+AlBFt@3wsZVjQCTBo zL``iYwRY|0_T%7&7pF+z1U>We6m8q?p{*=$u<9NghGT<%l=*IczY71Q^;A*lxps{% zTsTkn-FF{#cXv}mLj#>Wd6Jr&o5}5V)8#9d=_4Qgc=~FVt&`uQv)BAAClHd4v%smQ z(n^i|PV_P8>KCp_*$VFtc!n$osIw_wpD06MC4>rqyqHWjO2i6#sw@W}Hj&oaQ$^v$ z=bxjIkr6s{=#cPE@pwGc-`_6?p?mJRhb~{fLhpI+BjURN<*5R|14DXoKwc)(1i3hs z1IR@^kCjrONLD(M26!OAlJ?J%dP z!f6zf0E!I-AaP?=cK2j0IFp|adE!1uv8!%7Y`o%Q;*cQa~h;yex)PMG|Mv0K;V zqI>SGqlX`EC^sax}B8V7`jT>?jJdNi4rc8=Q5%--9FtUr}ak%)K z95f%W)6Fp_4NrJzbjn2&vlaBr>t1^Pgp6}pXRS2n zw~>#ZJ2`9O??U-t^L+@&z3I|t{)qRrzN*hYZDvw4U|f7eWg<{=;b^*$v2;sE&H}QGaCgfoV(sg z({tP|xGwb4%$$P;hEn9MN{D`Z=1QPUs+6(r$dD?2*5Trd1#dA@CySc9f>4!i3p&(W8+wJzy(c^ceuV(#o;=AJCYlERho^)N!_M)W9Q13hBt!<>4 zsZrXw=NL6Kb%=@6;lb;)ZTE5VRLMyotgc2NWm-dh zigs)@Q%f`Pu^8DMF>xIFNJqPYHg#eT6qauxoKJF@C)s96aK2$PWanC{Dt&CbhJ?pv zZ@-<(*C@h`dE8P~B40?bH((#l@YoJp7y1P@y~iXUR*J(b6qEPLlN3OCqfB7uB7`XR z^+5e0j2IHW6h2^ibsOv@OaZtl?eNW=)&0-=vv>U45^Yxb+YY> z1r(e=S1vgbn7B&Mz4TqyO{OKOva_4*samRXaQh$|S@Vb(|L6t!;nQEIM4WXr&P!YC zZXT;#?ERB^g@Ql-;IiHM(^mAM|F(ZDoadgoa> zcllI?REZ@zsJ4Q~)L?*|6}jIUnjNHPp7|P$P7KM3SnfZi01J9xA6l%K(5;|kDk}Os zCb+j?9~Xy{zq^Vmxc#85VzcfCkJfPClsbV%Jxa_!$ogUhI@P6)JvR<*LMq}&t z45?zHx2VQzArrR|i?xzGHOFXfc7pYKxi`?!Jyn_hp+~Cx$shj_?b*Fs$hjFam#NIJT(^FA8vZqqC;nk8Vi9|3% zsz86h9KcGEN?F#FRH^dJ(f(~iEK{OuPOALLAN`TY*NGD+gqO;>bLT{R=6$SMBl@Kc!A3&&}Z$M6A-&c$s0A#EhGwQf4 zDiT8rT%$-8e8RyUSnQQ6%a;!Wy?(|g#vS}#D^dmJ^XOe(L5fyl?74;MRnEW4Q<+pL zj&k^~I~{9Qdy5~mZVlrWW6i>UaREWl^b7`t#|lDeLDpabaQAjOU;~%02YHZ)Q#2ip zOAB=mfXS+kRymL&tkXLe<}>#|$yTAM5StvrKZ_J~H=60;W1fs)hLZZFua1=*vMV26 zdy+o)WP=cp00xAo-VCr}m7OHRDkHeM&n|e$Wsi{E8l(a4$J)H143T$Cx~WiLQ1B+X z4&V;Dxic@u&=SZizBK{zw(?M5*)Ut>P++;}ACxQB6qZYzYi_LYVLTPp-vj=%BJ7%P$4KDKE~ z1#R6?*j0aYI7pYy&1CL@l6=<#je-aT^q#3uTW_a^Mkh5kJJ}e`H3IP5i7__rCc>F} zaeYgho0?jj!mxoWwvyo`p+G-^OMNt&qQRjM?cC<#=h|p$HqL#NsG%05a-2@RGf&n7j^|^1OfpX8XDqp12LRs!C_@2 z3|qCiC{|U%K*rxNLhF|#V*jx9DA8#ga+T$xf{MWzz z*T2Q>-YDb`CcO|grnR*-=U2>&(4 zm&2L0XF#anZ%m|ms+u(6zrK|Y|K-yS|D}Z-({E2GFzAt(@X-SLBUUOy=f}hr)Z_d( z{a7rfCghevB!Yd^vipj`g9Ew>-VH1Y|HZnj3jd{r&|~WLLxJ`5f)F>+y~nXK9^Q=+ zQEsrqur{q_U_w9@mP#5UAjbxc$lBrN3NO$F){p$?`xzOeS*II4?m$0+Yi+>Ug5okzJcp~ z(_<7#jghl5Mpbq*ee#LDG&OgOzWJRWQAJgq7*EiL(6?|8u8*1q$>}oEjy4A!Kl~64 zj#SfA&%8uc-bO)WqVM7Qxj7$=jSP^dUM>W9^hmYH`-My6^!Axc*QSR_K_EaC`anDYpgU@l@S*V4deeeG2^xaf2{MXg9&(X}33|R$0E-3l% z&=X(Gg#U6I{s#@S{CV{qA6aY-pOwEY$Tq$P zSp1+hd-Mjxns};c3J9BH0m&5hBQc17Emji+!mMa>nwd*bIHq5s>K@?%!j_bQCAqjS z#LDMvmcYQI5!hfTQBb@Qb|afibYz!{s#!TzfT2+8Cii;4M)mu)yE7yWbo`--nD`E? z06+rZ4HJk|Q!LJdpEDrJ&99j($HckTV+CbD#Df;{2ND3pN-IH5tTZ)k$w?EFW>z!}oQ$l98pYp}Q|6p&M#piDk$MM={M*Db*;+JVrBZh%j3I>S zD4s-k3+`j+YYYAu4fbb^7GQQJLVNdCvaxIvG9W)a|MW;^Tmhgkx3OZnNo?|J7MrzR zxuhRTEf|Q?7HXfpmxzST`n7ScbI5PSEWdsId!(WxKH`1 zwl>IPLQJH#=FQw@7Oxgfrh+s+l_h1go+>>f?c8Q^SMus18jXt8mD@V~+*V^{Pn9w@ z1eB*ryTd{Cl{PWXs02B`Ym+mh*JwReV&QrE!$15lVzo9xuwa!i{_W}M5fim%&YYo! z#s+%ufxF3MmJ|8#R5^2DjxO~FL_5bMt4fJ*g7)o{dkp~jo+_8lJSSG5s|4U*OrBQN zG*L_EE^(|BPZb5||9CgX5A;Ey5A#@sF<~t|RurKk`Z<@YJ3T=K-4O%=?hmEQ0oUT0 zklRp|Tbkg-hfVF5PPh+aA6D@q!EQjf8#Rfy$Ww*ig?Hy8qp$P*$Va}%3cOM}T4f%w ziW$!ldNAt{YEn)ehrR;fJvN(xhDMBhosqiQEUZVPjajIjpVi%IV0}pDz0PZ+8+{fo zZ%jO_|^}_!hj=34%7eoUw^^* zG||97KV84kOLjNw7#aYHiwrtr<&pz`EjZaKb zb)8v!S3H{H@u7)kSm%5CxmU#VjvhTiU;gr6(e~}z=$WUV=5uq@)Fy468Mfh(_cQNY zrMJ(V6M2}KnWmrq^e5EW*+DP7@FKUpAk{Zp1u2C+ACUL&|LAGz?H!=5u1@;e*Zwy1 zt*1}FLk3eqe5+X9UZUNDHUyi>h&cv>h5PS}cprv3)P>nn#ceN2iP)5wOrBz0Zd<2| z^DCcU$W!I|#W%!n1tA~!nRwQgU3X_ZRpw@1qu>5dSIJXlB8M$PkfPDZXT&BIO=lfWXOObEpCf)3Pn@+ran(S=j+TpdHPSAtVme7W3s<5HAjdj8Z zO;6nvo=ZNK7uu$4=dwDor%JSuwe(aGAyggcd(az}pA3csmqUmwrsf<^6_7nr7L}IZ zRdS*C0*%Zp(6}!uQXwxDlpAz-%(p^TA#G}RP&1d|i?2`9JLmgpu=hC{8NN>ay{G8X z`4{Nyg;&TQo)K+NrCOFFU2QgMZn9?5@aRRF7(GQ5*0WUMo@TvJ$|jUkHOmVS;~=w@ zY%B)IuH|~HNa9BR#@rZW6QDhg`4BzZ2zgTT7F?ujZt;` zdyH*7c<0?}ls#2S$2yZLKPZR)S}B&6MlOowbcmUJ^%Dp0Oc%e^i?sBjZXyXeFn(8)|CC#jRwu{r48!HM`s;;gUs|>Lc6`mjXHyrbddz7KPQB%rLCGr`H)rh~b0yqEL z)c4`rkPN08aZjMY_qkjiuJ;xm7n?=$xEjf5;A54u6pAeHxSQfO!FqqqRvstxNfk2O z6!nU=ouH@hCZ`VFxHcFdQZuu*{e z-P0csAtK@ZVz>HOzOgKxo#XLtlCEDnMbT7(Vwsd=6Nq1KOp>?0n(7)VIbS{s%$=j3 zJkuxkm<+H^mL3`l0{Oqy#LDa}NFW2%^O$6{TFGp|z7YrmBXwqsJx%opb;WXmb!6zt zf>`1IVdAS8L9i6yVWR9lJf{>=1<2^@EaxyzYKavimpPmrp&J8=KnVnk6DtX}4;L0B zsWLc>g-!6DVO!P2Wx?lzK?7a7O7zAlOzMeS=%IV%{$Rz*7l7T0GQ&6KPqwWE!to?^ zx9_G47kkL(n->J)$3OmYv1$3U&ps=z!6Z8-d67?Czh~<)df}xv*ak`nFAwbZ5Dtfh zw+B#JZ5E^oY$S`#O^vl(^y=&U@eG8sdf)rrC+-7L33%%zSrq1asQ0#0B4(kp=P!$M zSX_WGd#}@VLu=!&?aL1AWd&(-e!0 zaeFYZF1JAASop>^+@)&^BK7o5()9FAZkzmmw%Psu8P+j-XmVK|mFzeHouKGnds43QqZ?J86j^B0a!cDr- zcZquYUZzv0pQrOz-=Ruxb|POTZ=IQsn?y46xPIySS$ga3=R}$h#WR!G3J9;}u$pLW zGQ#bjZGdUCRV(Z9Hle#L2a8FSrFGR}Fq*<#NoEQLLY!|z?TK)o^sx-V0-oG7H$Tm? zd5X(zI-B^|{K6Q`2L{tmER5D>yC9^LE-nZ+uIq{EsF?ikXZbztkBcCLlOsedFa>;`zbqitbqLz{*D02u~ZUre?D zkUz^IR_;7fB{x6l53)=^oad6xi%6Bd2tUXfMOCVF3s5FiO2;~f|N6Cb_^)U={MT}@ zW;M3>LF?8SZX;G5{!3Fx5Hvjl!JL5s13+h6c90$#jqt#-^rSh2ty;|wVTa5H4CD(m3#GiSiY>!3)&>9lOKgFc0EGHd69{N` z+C8JR@K$$Ig>y&2wkak-u-kkAz-YvzNg-g>{mq*<#Wk0D2FdN7qx!mB(z+1px$mP5 z1LrTy(@W3EuxALh1iPW%==gEYX<;>lD zeQuZqtN>g=qrUjlBcCzZGC1;D`mbDIVjjjdFgB4p?kRM4JedBqF)=c6mO`P~^j}#( zPJ<`|5Vj^zU;%*M_o3e+l$aJM$5`?tMPgGtPKLx-yJPd?TxZ!394bs&JTXPVh+GYe z3B`vGx~aZewy$$NJ7{=PfAe20u=*3E%CVhisHVbK4*ylghJXtHwS(MLL5s)5-K;Z3 z*lu|Jl(tW1+vc2(e(7PEj0w|1@bg%Vi9kKHV^eL-1Wy0WpwP#1k^5{+&ef&ET0sU6 z@IA`~CWmfSC@@43!1&_kG0Eoa6uA#B46$5_5f&UEl!?J0%YJq)M3=7cSY46zwm`@( zER zBdWgv5G}3EaXNZH+7hCC`8j&!d%N(y`+kwW@y(~Gum7g_`(ONve?d<_{dATjsWH)} z?b+}C#mD~{{qFz!$87(|vG||<(|=0OKmUB@`qnNR)i+7~qTbs=`?ozzfAB|tF8)S1 zy$^ig1LFDc`~tS@c916>3F6?+`zRW8&{w`L_bGbx(MP$x*yyE~UdoUv2k*{?%R}B@ zdie~!2F8kkykIX7(b*=40w0YHjmqKlg4EMX1z~^96 ze=*GBThYAXjjf59huRVBQEEWC>vT@cI6=e&V3K>?ce34Jc zMd*~MW9_vFm(qPnE1i zB$uM$zdln!_%HdWRiPaIt8|n%s=w2)1|39V@q^av(Hk7A@>J0&Bt_7`7PqiMYUSIy z+p+nhQKSVPxMHycC3S?0y2r##zJdquwkE5%$H{$Qf(LL2q*Cf7#ES7;I5%lGm0vDG z@x{+Ws4^|E;#+yGOwYzd`JwNsRcG3jQUHh)U~nWt4jWbp!6>uv;2;hc#O-XCP+m~) z`W`F#o*)1QN3pt$>kt!iKhGX3|*#&+hVQ%BkJ}pU(J$n($ z+CVo4Wt)W;N|P{d479+yk9uY$-@k3U43CDA!pbCd4(~X|@Oa{vGSJB5m93lK`e|f*deM2L=7xRgCv8lOOPqWJ!1!!k$(|}8Q(NoC_*vnyr%D+c0?JdxGH0N$UoJe*rkO(ABSPwC?9Oq|Z^L06)YY@-G*oBEKkRUjx5{g4j4)$|h zVX;BxJlljye*o~jQax1^GWt5}$&jO3j}?_Kna`y?Rxm*iLD|{aDZD2^G{DaKYDQ@{BMN-E_nhzf!UvM8y`*+jS z{4SbV*rS`aZ@Hg#ZIh{`@i6PtUHt8GZ&AF<$ttGR3KH8)HhU}UsUGeRRa8?2ukkAW z=1P%FCJ*6tHH6!Y6?>}a6c7ZB@>GGh$dSDs!7js#Lt$Vz zA||)L|FUn9=SUUbbByo7hLn{RrVR0biOAl8Fn#~U*#eu*=VpfW62gjpEfPr(E9pO$ z32dOBuh76tr4*&Qft4mqjALR=3$;@D^|$9lTyzYuSc!!Jt{7JM39AAoDD^#73VVV8 zKkptZQ1<$7$`$SSj%}NrVim@Gu#%ONFe_nUx^g`z6dbg5v;i&9ZV*Emds#qv3WgnG zlFMZeid82V8)9)7(jZ?F^wt@_Fr%6pmtf|~xFvuxjL?9nZ+I@CZJ}M^xC#M?P?1Yl{_YKVe}%b6rS&Joh745hN~)u{JnqRu@ab% z(s#ZkUF_khvU6_@z5J{+mUr)|q6Z(An_mL(9C`71xq14hKGR8q1A#nG6}cb8=tyXh zr;7R#gz-}6fZzP*+ta@mBi~cy7eCWQwVKtjOQHmEpuA6%d_g7R1;8u-bVE+@l@Hj>1}GNofc&BcVF6(F;o;#|4`CFt^vbi=efOJ z5HbmFj%rrqvh<6Nu44dOEG`~X7JnZ+PV|hUVE7`%64KiZ6DYNn#p@v$o}tUve@dTwq9(IZ{q>

Ps^h}IRn6$+to>ouT)ZrwD zyOZqBP73&MQasWtjzfM=vV71!2QpCmHz4+0W4jFisUpg%Kv9+IseyD{mhuofOG z64}h5uCU^LWDE^ojg{wo+=2P1uqW}4l0aRWsNz{Q{^`^ zo+`icE5AZt{_>Z_hVLLIkcxS#eE##Fr>}hFEA-@(Pty0k_dRi}n5W8zKm1|({`bEx z!gPK6+us()3VEt*-;MF(bjAiD^8 z!MCjy^kmR-(cLLMqCgTuZldn-Ovsy7mKTp4_lj?X-4l*gQ8IzW?g&4O&}@F1=Wo)& z#`59*gH^2mnJAu={R#55vz1r|CFq?ietP@LypYw%Ki-MDh3o^di#BXSNVWnVE117P zOVO&3OL?rU#8c(|yML3%u`OH{Af-WoMMbzkL^wdo*NFjTqvBtj*Sn^S)d4bICAD}G z|CVAKt{2LlDt8iACr>q4{Gc^^^c{c|d8!mCAVttP%qhC>NTqOp(*hxH@T`;P7Z!Ps z*!iC0`#sdohP_(l3qV1s@R$nhi?TQ~)wU$v!_PUq!zJR5Z|iW-^#LA47TsGKs%kV@b@GuV(7c^cv28HAZGxt*COsK-mT&{ zR;oaW6|2ch}MAXeiH9MH&we^gVr4Evy>nS8p$nldu@V>k5jxwhZEhheecb1LeoS7O zgu#S`3)l+@{SuQt+C9bql&O+&cr7-nU&>Pj^@mA%ZJPC0QtwDBr%kLkF81O695<;1^AKp{d;dPP<6c;3Kbb4giIjg1$>q$3w%Vw0 zI$bg$J8f*NNnD=blr^Ucwo}h=vq(O_ll!WyU!YLEl|5C;*oaV`Dz*jIgW|=7FD9QbNsh_8wMYmh2~Pw7 z!N-H1I_@uKjL>Ixg3aW{0>I39Gs1*>1G3 z%#!!W7pSok`np=smC@JPX2N*3e2*1;SZ@2m#5z0@3F*j}-^M7yFW& zyKp13rwRxOc%UHU769*!np)QL_%m_+_U@w@PZfA~95`@55ECFJ0OhHIa;SD!a$R<2 zJXNrG0t5{9O6l+K7sr&RiiKa$+R#Cm8S}HVR*v8Ge`Ta%k@-2TMBU-G8!%1uCd^b`;FZsY^<&} z7x$ZLiY44^YlTGH9~uhM=Rep?yEeON$0iqbx7D%UvxDlZ8>ptTnj#^#(-tC>h_G%I z<95QynBYF)woq+l9rue)PK~s+!$bSG+v)BDm9%rKM|jHxLM$hI{ETpb+m%7I*V!pI z_rV%6Cl{#EYo)&40HwH%w>LS+X*E%Z_3nIBar#Ap=x~%yoSLWC-khU1-s16W%0nN1@}E#`$EV2SeUSd{n_s6% z5oS!z@rqE4>2|vifSf`*EbOsz`I?n{b0(_wN*xbC9Tf9eS+1wb=1mXMrp|lCZ^&2J zi&%sO8^q(m{(qHXQ4WA`eb6UiizxC1eOMhUr?pL35Cxfug?8{VgnYeni@3$EyBf>CtQS;=BWy6s)kye8+@l4W0pfMyUX(kYg?IS* zec0>{@5O{I&f&WdpS6&3RmPoxd{PBKzflwGDuEEe1gcsUl%H@86W{83Owht8%_mhR zW_r0z$(2!s5{MP_jeKGS8{evp>b+hYb#C&Ab_rqyFqlo$(&Au6FiI!im=ebh9r21# zU&|#`u3ej_*I%2;Os?E}f4z989!|eKP1mpc(|-{?@u9Zmh5iCc94bJnqaa+1gCr@3HlnN%rbLqSWbI7NTJgiba=55#0P$P_g(v{rzAs7RG2ZvRg_ zSVxC;RZvHxJ)IoX$h!WnZWsTy37svR9*01vyyr+29p>xzYcT z*mtZdh`-?x4Pf(sl*P540FU`>=kWDH59fci#EQb9EpEE+XbtVz>ZYw7F4lGTQ#4#l z70!Ax^TTJR{FIFHb2Z7sdO@|PmfY^GWV19=XOo%lwbGs~P72J&X)3+?9fXOR>|P6E z1?O-d{#6MS*=r{abm|?Vo5N-r9kb*l?60ErTtRuQC$VyDyN6m^chkwYt_o7+;fEg< zlWe1-qhhmq{1zdGYUSqJ4;`u@yK_&5RQdF$KTW;8yn<_Y(SAJ?X@=AziS(fPoy%W%5VI}ZwL<+gbl-H^{5|3svOwk7`!`PP(8(W*{H$GiQkKAja`;S*s_ty8(J;(OaeaH9G&TZXfG1Uk!Qj5`@ zlbXEMv};QP+kmaqP}@NF96e6Ec5I@1jx^HP=r~QX3|fmOx)M^QZy+c_e!*J>p0Cg- zge}YcT!mmmpVgc9xK)5GK_5mG6ohFM!~%aC@(F-2Ji4cn^TqNqRZZdK7NJ{pc5UJ| zYUXcr(BJ?4ci9$S;4%QIusC_Wwe-O!KT1_zmW5Uiz3|*uatJY$pCneez4N;>a=iet zGB(cgj{mKz&7BKT&(X8}mrJTVbl<;Z`I-=Y{o1u_BANjf0x7!^x+QD~d_VpLRA}jP zTAzeEK^@J^%urKPQ&GF&cB4$H+zD7S1p zs&s_}p)xxc7vaG$ZBjKJ4xd%V`eJYQ6%pR6!nKf-syspJ8|^HUDrIaaC{o29Fj9AuOROT+Cg_aN z&!9`KH88#@Ql*+@^!>-Ro@VlW2%Cb0Nw`Zl0vS>To)z~WuA-(!d(LDcbWC;6#jE}t zQe_j55eN5HX3pm)VUWM>i1Z|F-)!@!Op<@@H~Vugw8rSEj=qy z&glE;(byY|w~UB_wr&iiQW`rB+jnaIQXh)SurnWiV9 z+f>oMqn{+Z=P*@Q_{m#2N0+ZHzG3Zr&UcI$T3T6aT)+dd?9V9vUWu9&);k z*%rrUNuI92DWXTrLldjEvHz?oDj} zro@CZuJ>>m0=qZ6MBWi{Y+)ftt*vcz@#00g@BaJw*$B0npo$77IV)nqd+DCT?G%l7 z(}jyy$z--rZEYP*O-<3R-Mi`1#Y-aZE*G~A{#Jcb1${R^aewD_f(_O&!4JLI!S!t9 zHiS8S*iu8o(-e!$Q%#Low2}USAnn`c5q205jX7v~u9fRM#pT~1^yz?qhDHW2@Nekq zi_`YK_mSNJPv#`e&Ad+k@lURko%3E_YvwUE%t^K%^y`iWJC~d6_Y2AQlfl|ahwgfk z8e5N2TSGJbr$6{B8XBBs{W+U1UY?{^PmIusHwS2PGDV;IEL#s=h5Oy|BGvt#~4t-I=jbarj|M@-F2Xv+F9O3gKSf<-izyFd@U}|Csoi# zuiRJ=b~aLo^=0%G{EK?PG1WIkU*|een4huG)ToW-r@4IR?6lyst|$fl7D}?rF&a(W zj+n?>G2PLoL?c^-V4wD??qllC<{rf$o4DcI>Nn~sH(y$+8@RzV0;qe-(pe) zP|wLHR+dAm)Oj~kXUAP)0iW8J6CP@?L-9>xV`GAB!Ee}+UavPNBvm=BZ$f>cUQmA< z1?4?eHaga{c5)xKZWX`ISk|5@%P6FK_d0n1)^EF*p!?F-#&q{o`PgG#5i>U*7=XX@ z)v>%iRrE82{ahZow<@D#;ok4P;482n%hK@Lll0!ZtHdU07-TWQ|AUw3X+F$@k1fPX z7CZ^!V$iB*MH3z^FiIw8;zD^-Kx9qVpB0NQ89x!RF_7_+R+Ppv!QqKUO7~(xJMitaG@M?m>1Vs{t;pkY} z<-NAF_m=VQ$Byog34=`$AyC+{!d-@3%Ep^66>!Ivn}A~TOS3S>@$cN+9DVi!msn0F z=s*4S#FCQ&avVs9Eu3IIhnQZ_g~br-~Nv{JAxiT^58>_>A#kNWegM8 zGX)b-=+Bc=*i?{&R|;0;snx&mU_qZ(`)K9EH^IB^L(P*~4OD6u^Q`tV#zt0oyP4 zz0u5b-gB^$jvvmFP^YdwL5+=#R9#&y{{G%qf1hGe{RJD%?K|k6M?Nopo8vzsoAEMz z=SO37WmGOE!G4t5#YV8>Q2rQe6@*PuaE}$6AU+gSo-vs?$@&St1$gJYgKZfDJ@yd1 zQq+6GIq%T}CNXdQ9xJ)+@B_zdsJh`-sH?q^?5=96ZrYMQBN6ru(TgvCmwxozx5dQp zryt)-k;MJ9d*^maS*xhJUg~HHfr)GMKfn5i)H`^Ms#r()%*P%fe{d)5*tUg??pAVn zau=ldM=#Rv|JVPM!r>6@XmikA$3Mm8&_tabZDjXuCaX2u4-&C34fVW9fB5JBkNErj zcX8h9e}$Urs>xGXO?BUnw4g^qt06gJp)1kS6vzO+{#8vvQ|8W;T zUoM372W#l+;4$%g$BrH1-=Y4CboJcxte?9n7+j!G&`%DhNBliKHA)XX{zWd!8cHQY z6q@-G{mvg;A*;tk^>sF?t+om~cyK5vNCuSCzxFG? zOxLf;J=pZHW$QNjUtj)fvfAWW{_Vf{5WUm0AarnrM*hZM_&~Gxy$~?b*S}vYYz^2P z`3tfNq0XD+_RsBpbet{^4vKwc^7mBf9}H436c_qC<_nZ(3d+5U+Yc5uqM!8+@O8mB z%Ta5Zgdm!mveLqwEOUgNS}ly`7&)t?%>i_GxNi1?R_?VjUC zmieXcsdD(hXJ||JeWL!c;0|`D@_N|3d9#?ff8m7}1gQdVF&t}YX(_qAlyU2UHi{68 z8wIlUl<{+bT*YUt)u4AJN+={u%H8M>()GR|eg9_@G@YJQx-}@ApI0h@!e!TB zFj6p(pea7CykG!ali=sWpqulfETjS8;BUf86z#QT{Coq12UZFxVg-bXGBj2KwKoI) z#dGnj{LSsUI~}ySOQ!Z#gjiYJFVS~YyKk(wiU|z`tf-n_ko|Pu{_Mo-sW&Dv#@vo& zdW?WX!DjSGU-;q{df)q-3lb{uYWeQB<)--n?p+a~vP@u)FvulLI>9&rkqVLpD~7QW zu7eFn5Gra9Ed^{&KR6r~W2GWg07!wq`rZ_eUz1{0*!96M{q^_a^pzi2>D$j%)AwJh zrysp44em0^D1=we*y+X74fO1rUizEw5qC%aGq+MlE2E4% z5i1{S*9ME^HHn-B{>ENRa;3Qf#wU#1V&Ttt zmdL<+#kenT)5~fOTHCi!O>GnHJ$N7Mx^D3sY0LKPyhl8MZfor?$+z~=3y zw$^Rwza%0FBiZ@5mQVpq7CSX zYIfDr&b<$&|0*4*f2`O?yBV8|(C}DTglI*&bj?qv&&>&9^Yyo8#6&+9$&>G*vg5dY%u{I-t%vvZqAOn^`D`|-}+fq+=RfVKzE<;9Tg0YnMBW7Ix6&CSiU zZQC~S_s*R=={JA#H~HTk8A1iP>u`;b6%E{`Roc>>OI%|z7L()fKER$hr6h-|lcwgn zDP@wL^}66}gHV}Yz+R&=wE=x zj7gBekl&I(P6%0~WYtno9(bayl-6uB=x948>_XUzSa_!h6#(J?kRE&NG5YLhKP$cu z`y0VN1>sdr8zaFR5p}XrU_=L4uT;hoShFH3m-X#LR>(`_|E-7o^VnoC_gL{dghvX9 z6>VBg7gNu3daPn!7yM>5m5c^#HWnA*o3IxONCr%%VWRBjs8sYptSBWP*DbJ;hNz-O z!vfzM<`fei44AOQ{n}MB8yR;xv7(1k$0F1*fN)%Bm-}|PY2R))ZS8i@fjw?&Y_tg@ z6`RZhimZW$6WU=oVxw@>E(kTJLw>u~>!*w|))Q8XLG(+s*L-M+6@;|XVq!8Xh?VyC ztot!SfGOD0EB&+v^I9MrPNX-cm;DVMF^|1ZuEM(=z`k0LOBOD-x>_r>HQTA3Wg|lU zfn))pqV+f)8IR;lROMrII?ggiZVp*py@M($A0SU98$7nXWHj$0vvp7U$}-B(M}iK} z+`?w^2e*>jbCf(4_p!nMC>vc5iOGOq)G9nw%BDvdWhh`=THCQ{Eg=bxwIWus--`3_ zdI2!ei|{=N&oecH4TmMMf`|qgETf1(pny!lO_*H9#54YGY0vdKSPEFQhE$kX$=Ve8 z#0tIxdW%ZxIz_B_+)3Kh6=7RuJ&BdvI#JL&>hciTofTxZEVhHJRy!Gt*$G&qAwtfo zI+pp^UoWeJDByZ6EY=v?xm9E>u=+gbdd`%?W#YUz7d=NI|G2xtNLD95U*~$^jqR#P z|HY3tM9EXl_Mx+~;I}#)EAwh=Nqcc&tr8+yz{A2@CHJJnME3jwmjm~MI&MqavM+|~ zSI*G6)31p1!c%{r`Hhqh^fB1_g6!bb+$cR{@V-{oAB&-_t&N_3`f0I;&XZ3*Nrw*~ z7Jp+x|I1(ga{8)`0rZO~i;i%_z_KLU{@hL@1wsziQ5-by$HFh7{ktpZvmbAv2k!QY zgbDmx0hi01nP&l^rep>B@^ThdzWU0m!dv6d{_M}hK0-(!Sl)W;EjoSrG}lLN#F3@i z(Ne?;qNKn}W#{(jlIidP*g~bYTzJ#7ZDBNuq&FYk-``KCPMxCHUw@rmeDOtk{`u!c z=su81uv5xu<0Msw8zC7c5sYx1aQ*Esl*4}&!kX2};s>o;g>Mj)9R7=y#ihV~h5=uuKkf%lO^9RjQ66OTyhl8iBw1M>{K)(3Sun_B=dT3mTF-*` zoxLX|6lTp9G^XuS3~ja$G9d5gOrv8bJSr%jKLuE(T0tocLn2YpY8raR3OF z)93xd{TIXx-0m?+2W*_SSvV(mYACQx9d_~VSzkQkQ3Zv%t!3$Uj?hO4=LI)mDC8hi z=KOXFM7-p!oFXHIGv9)VRsh~8AfV7@5=k^15No(bDst-FMgsaVJZ=h2{+5x8(cvHs z-&~-n^!_1EDDQQ4>fBr*+}umWo^78L-YN?VaM_n_6W%3uyIm+v%LUxHv5_5~0mBQS z!0;@@r&i&=zWG9SV|Ohe&p;mLL-a#dsK4_q=^awbO8?>G_2PGZot1v}qam6Y&xZX_ z=UbX&C@gFyzf|}yc$<9q$=q-idU)}LF*<+FCw_xa!98}39A7qMmt8i{PY{}xXo*R%}(byGff$JS6L?28P^m7VZM{+AyL zEK5Sn`l4ct+Qj2+O?sgO!t`9ZF72)gk3~!{Ba9`075;c9Ai{qgT50&NopjG5pA)}} zh5zygEHp7~C$}TWc7=Q|Y^}wiz;a2A@u^6TU8o@JliKWcqv`NE{sklT_F+MkfgZhW zp}?~8RblawEZ%>-h7RnhB7;dkl<285K00}6o_zj!5&rA*A8g_>vuCf*d-#u@8mF_p zQV&D;uYdfRc43R?JwL`}@ZFz|(T$NA@%N5)2Yuvy()&g4ddy=z^~w~D&&oaW5Y`HL zM>s1JR^8>{)R{Rtd2vqU-DWn@FFn~r-WpBb^YEjm$LZQgkV2saF&|KB_%8+6=_>43 zF~Gaw3!iLdTTbTLAE=?8kz-uf#+>k9Z#@4s@mmic_{9H}3I7$H`)~BEACDFc1@*|$ zYC5uC_Ni?6ufyVR0AZ)b$HqhmCiFFo=^&)=H}>*4edY}P$N&6C>8rU9{_RKTwez#W zo>OS3w$djbZxZ|NApF-if7Bq3BfM};jdo9|r4fxx(Urbub;E!44FtqKRCtHomf(EK z*{kwnjFijPxb1e#m z0(<%eKADoFN-4l|&YVl}GmO;L5u?prat|$F0HNkswgK?4f8@b0QfJ3uvET-FBHB_h zzSspF8`bNg6uqP*EPl|MJ^Btt$s5(X zN>f-AK@(xcG!&O6ET`uNNMg# z4+K15z(@c&g8XYIMkpJG4b(P^ z=L7@3Fnm~UDWwerLa|NZ0hA%?Y`r$GudXtS_aa|d=>}j`x!S0=807vaoc}O?Bj+Cz zr*jK-E-5x#EfH28<=#0+Fo2Qp8w3k}!z~vHh8U9e+(t^s8&>r|MwC5i3d27irPC)T zX`s)aklJJ47b2yAN zbW?6b4{X_9C9Xk?VCXb@8`VR)`!yTYWApp%+lw1h*hl5LXUEci@w>VFv0sbY;9jM( z@5~n5+MK>Jon=$+{arb?FC z`*v24)%^ffH#|np%0roCb8V-o@iU7ys^7QGO-@%W)wO*-=X#`g^d_CVIF_?feJk7b z-JLFS*Zu-kc<;%%-eh*u@bLBQM)mWuKh}BUG~)}?0_Puj4ySDfgdT=2jKx_u5htJX z1)U9jx!C6QPNxjx1%d&69;6V$9L>&qxO^OJ(?rEJn0Uql1?bw!HiZ7GHc#%Xmtlnv z(ipn_(Bx*Z!MV~?uAF;`k_o*D9v&+z>!`h3PRJRP*C-jEpbMA%G|ToApf;+H#O!SQ zIr)2IVqzBe%FXLxS0pm>D`Qjeeb9B>Yee-(ARF$$=d}J}Uv^vOJW2Ho#Wq3N73|zjc7=LGkZuHI3&2hh& z$VM4qgLNzCC6VB3k@D`rzZZK0;@Q}!{=n`EQJ321tLu%%IJdV1UFnw#C+jLL)ZO9A zxn4aNX>uw+S9^UFPWP=XZ8Go4Bwv$^@wakars8ruipON$$B_4w*ros07#UAjI_;}e(2H#bGmc!0*n`)FwN z28~Y*Q6!ZRDaPNH;Pw>ff00afCrwNa(D29&dg=AE6p3Szr~Zq(TO8EVDEm(^aft0o zGwa9F^BViq{K+5xFOPC7JUJIM94aBABXo;5;o|^K5G}RNg^BM%yMmvL?TF2zFzL5lGxO4RFB1^@;Ky! z)HR|}*v@g*d(GTmqAZUP9y>Ez%&dva8}lBrkD$EMrlok#eRuteC}YS&B-o6_fHr~y`l_qt3fksyTZB*$BhzWPZXGNL8P*J1` zfcL_vLEi?(CZpmy5HN_(ugd>U0*@6U-**zRvKmqaeFk-kRW8UsR(e=0F|OBySWSoh zQ{c_g(;pK1>_j3dnx2gdWpRYt+r(5%oF5)V7$9tNonm7daz7zfy7%&ZIF7cD<&pap+%xi&r;ESXp-M5=%YS&4B0Z!gNj90sh6Car3qNbe?rI?iATKdl zGd&%p{xl)8|3D4*M=1~C6?5Ud@;Y(Q<}JA{^!b3CxpH}a$+ijOyd+ZP77f>Wgi2SN z+`9&HCqE_PRXi4!NtH6z9_ase`xN&>=~1clJhZzqsZz#zK#?l7DGOEDN?UwTDi8t- z`&^+-tM)FFoZwT03ZO_8Pu<6;z56k$sNR-IPFFqkUHfhUQl*8q?f;iK*CWl0KSyWJ z-_#{lyluZu&22|>u7|w8e&yLkq{^Ya7S3l}jM3P80QsM1Jrk4E%Hv{uA|m!e!C1JM zSdlh}B36(v#zTJwIio`G&dgP^&S4^lExLt?Ty zlzz4%Rcuz)txaLhC(EO>%?I3B#0v7QQWpA03uBgT0X4agRK<1-@{I@x-}&*F_&3Pk zhIit-`UgTe*CS!yQ{1-@;{L$bUQUxLW^PyKFZ*?`ce8yOuYV|xp?0*FHec%5xzE*o}^w0se<-{`_MMDG9VuydGH=>3i22_ADE*4o0n;T z+xW!vO^SjbN~Z`Xw0D&Thp&ih2S=`p`$4F{zQX&_f6;c7?cB+FbXBEAw9kb|JEh1* zEv@`-GC>Oy*XYmx;wz$V3!%EgMGxJxkL;d0VMo02@>gk^?Gx=6BJ#%VAXT8x508e0 zU5_?{IRe<*_!sgDb|wf8$Qf^qh33O?8t3+fG&~%nXhc41El8Cx+d;nIEZgD;YnbA` z?GSww-bx@;w0%3yAEWYtG&u+F-ch>Ve~oSoT&LlQQF6G9Imzzi_6IX2odU5S4e@oj z2T4n)fXs$WL7nT#6qHpyvEpzfXvbEQm^(t7RWeu)Bcod+AnlD}qs^U8p)A4;AA_UPg|>7_m(yNWdZDxdD0>(K@~@46<>ll~3I(>B z@Ly=d$RiXYkRu?(I@|1GvKZtlo(cJYJfVGnz>)WX5MhNo-3KtqjC0!lp-6S?$AIIp zIQC^=V>*@)eHETDAfIj*R5_#WM#l>81M%~UOXp^2Fik8h1*|H)|2@ruWGII2whwYW zyF~aeC`WMbhmwm;B$dH~<2bKEP3Zxy{4kPmFE&rawRrB_+?<%a0jc6!c$ts0;g^=N z3JBo^d8W2TSt=mcm?)&fJm=-tA{x*I2D^KZ!|Ei~^ZGTD)jkz0e&rO}A zAOFL@rk}o+8~*Dt&I-a&A*2$<5=^pTA=vI66&ahtHy@)*SNwti0okG#@(T-~un4G- zJv!%i3Voo`6Q!BiD7|x$Wq{E|?JX(l?v%EdHvE?YCMRLLP0lzuKQZ!F#WMNo9h6~q zfR;uX{!;;y>S|Gw7MM`PxgdEvEETKTOO*eGA_n}L=f z7wM_6;a=BbQrT{o6W-zQ0!_><{{AXQZkSmRqS|}%Lyful{g2#LD}MU}Cc1E~o~?Z+ z+YFvH4gUqb|E)7VL6QOa%@fDfF_0=+TX=5DN(*zcEY>3Ym(d&}XO#?frzKQWxdX7t zZ?%2xa!8Uoo&dQmWmloTQYaJ{JpPN_clEke$gq5D?KaSXy~e!oUp7AW2;FmBhGK-x zI5Q(d{1pPiNMlc*^XJdgfddE9N6XjhOaj^kf(~=K(ZYEYb~($gXGk7L`<54 zDaNXLD7aw1u^I{<3fOA_tJQ-n@GxK?92Dvkby;kM!Fph=Jyp~yC~eY0{LO_iG@8qV z=MpLsP~JmfRez~8IVC+Gw9xZZakDLgl^&=QcmyDnnDSJ?CTTc6ImPG3qBQ193InCe zX%LDyl+?bPVY=GS!YS>k;93cN40 z%GG*!tgOaU1=ryoDDZth3`jxFp-Wn3*bHwFZezrd~bgLz{;Hz7Y8}KCdD`(0$IG57W!x?(Pn9~dl8x3z2i7B0Fiv4&7?Z?$skP2Z+cvq$>e@#(XR8=D zRf>dtG}QaU0-h>fs;GTHjH%jtd=t;p+4FsQo+>ussp6=-pT}5)AlAGiG(|nvo>}Cn zvbhWPBS;7{>w~Z(^@ga>DKP1b31;Zf+K^u=6c`rmz)n%=T5o`Q z2ZBNlG}glwgHD{FQ)h#0>sGQXFw)4FiS09)2QkLyt&+z0j`FMW#QELu_(-2%Xl)#L zaUd@WAUd>O0uVPHZ4O~K$vrHV9*|e-v2x+Ei7s9?(DfcH95U0`xS4e*Gd}~-6_T7E ze4F$rMR{ofeFo~E`aS>?u~u0!3yhQsrHT&MZKL_Q{f@rCf%$!{ZCz`nuzQD10}#Q?jqs!~qWV^I(6t$eJ+ zQ$-7q9F-n~VZA*G{WBD?(%^`V%QM37HVNAi?N;j%qmn-q774#mZuu$76%vT=Re^r@i-(J`sY?rXC$|qEiueN4{8ANErTbJ zFy*mwqsK@+eMagVz+N@*Ok~+VZWLj`w8>&gQC%$-VVbyYWu;A3rGf4}F3VHvsbVm2 zn+x3}Z%qf=i%nubET2zC3n&CcJisEqTji+&9Thg}MoM>zEe0K=9R7<@CRH>jK`AH= ziyySwN5f5VAt)Oxyd$tV@zB5mO^yVqrN&H+)h2TB0FBiZNv=dpLWzk;z6ArOnmFDl z&?Qy4kRZ&}WRN&sBB`o=n!VJ{c#*8)J9P{*$iMQMt!ONfC--s6vu*!ShFi$R)C6FPBzG@gO$ktXKkJ=lOA zubVfe0I!cdJ!Lv|4xJG&3V5Jk}BL;jB z89txf^d83*c>$#b=O!kj!s|kv!|~;Ypo8Io=U}BOlx>kP(a$f6@wkuBRmhtos| z+$xkwl`=LO6sbZ}DXMX<-a9X!P{G7=SG!A0?up6M0_na()nakee5ixYUmT?yH*Sdi z3Xu8-#>g0dhc5Tb>yj#$dmME2>ebBkNU3-)-RK$64gWPZ-9#5I$^8&i8Xf7Qke>j# zKt{ixF|?pds!UADiD-*CDf%ix0|i1D&kf|V2ZjC!n*x*DQlHF*{8GdU^bMt(16ag^ zaSDf^kAOHB8Bfy9VY$*>p{Jko-o#@QE2erA=8ze%74UwH^NKtvl~jSKX>WB1ong5H zG3*@ZAIO7xSH`AbeFM5xA!22A)+nL{*lh@jhLE>hRu;CMObISy?7M(H4`rUUq)KC* zjcrn!AP}TJggnc9<9gUZ$O9IUE$?ee2fh#Qk-DR_gU|-F^{a>Fk}3dnztTt**bKLx zRFNJ**y!BCb#~|JNg!1MK^}7}xfffYbLSF_w-TsBu@_EWiYH>+N5Y(s+=OFD$y9{p z3H13e_w@x@2nH#Z$a>BQ;y_~utGdOWv#}V<1-opgt<7wQ@O88EZZaFgV&i(qp2zR? z(tGal(!pI7ROLNRXV0mL8x)s&4@B zbdVm}q>z7Hom2N9G*6WEfIvvbrNs&*kSa*(`d}m_h=uGxCY5(B0dRP4g{bFX7$JBJ ztoRvtAWevUGO+p^Zk>SE-~jL(C>MA(WC7|2^#B3~$}i5N{4mjt@5W}>AW?8mkrz0J z>!5t19x=IJN_&G5itt@{4)TDQ&Dg&K2AA-{;AbLV@W8^}ABrS`GKSDrs$J_5EBIH1 zGQ@E`78K2Usns0)qgnM_@$x{7GRDLRLqjW?_7^G+9`F zv!Tw<1F5o9!n=|06lVox0BHOka-2^A1nkV7hAPZf{5>5fw7%eXU8CRNJVXi%hz zWq$P=)$0)|?JWpPl|E1eU2JEFeKySPl%OWD5ib@os5I-ZqOpk^6vBYb$dD>dGubL0 z6q`q5F$DS;k}uFi^K-K_;gg=DfFe~)_U)81cxifiI&*y}Vy1AchK9zjv(69QUiL>t zs?7N@35N+W=*kJ!F*&cCQ@4GA$9;t8#3U#@V&%9|3bBF-Ht5<2+Y^tQ__Z2^!Vbf`@O{b-T8da%IjLe4&()g*zTKn>h&1fQS4gK?DQ0}!4|UqyS|;>g zk1I(I8%T*K(O1!5iUDQa)?%ccET15!T&^fJ)F){74ijzLY+_jy<319nsw#wqHq!Vc z!Yn7mHBM)WI@&;V8@QZh-9c{RnMy{mX~^SNf_nR}Qcv$?+O_>Yd7=PrHL0Q^Gi*fs zxBu_|A*-pH$H(BZL*?BLz}7F5DvUCz!YHBytQM<%GzJH(E=IlF99$reF+pGY4?F3| zfl4{Kn)d?4N^GpN(7qimGVlO8F&h`c9Bmx~Dki!&0+u9I_`8&XxLU;G2*;IG#ugJQ zl61)@RF+!Z3#AsJz5oo!(!Ia*gsM}63+hKrbVG?mf}#NL3S0waAA|~iV}*=T4AZv@ zV8H6`aPU2>umK^?)K()CQEe58f=n;5=1XdZ?1cFOtcSqTwk?&LS@Io*f>suS$%&5yB^; z9csq_^mlFFEbOVGPpT}hcicv-LB^I#s0@vUMY(B76_c@s>!GY&0lR z#lEmQQe`!S3XmaHC_q-%As#C$sj8|fle~59G%$FUeEvCcy&_dy4%XvM+sNr|5R*X& zyQz}fQ%x7Ho)Fgqt*rZZceuF!naS$h%j2Ol=X!5#8};_T!#03_5vgJ_CfOc{(bRNQ z==VTPm4S8fB=z(MMR?+B))ApUD!`^GNUZRA?DHoV@tF9Ta^r3*>mmLHgs;jixI_D4 z_edSE5U~P4msu{Uf^xTW9)O|IkdQ&zF;Saf58*!O*~&v4M2p^B60Tc{SOM@%=svgx z&ry^8(0kC1fGnwE$b1W~gC1UPlsM{B6D+Da+5ks7MFP4nXddGCaH z?W(g;8{dO#@{`^@`9NOvh?SNaD<_+Hj+G6v1@0FpX&c*CpLx8Qc5il5XVd?mz5f7= z<2>*D@dsG!Vi$|vJ3s*Jy@*t=wk1op;ubrJV>`YizDs;5SDgIf{4Tk>09qjCKQ3;Bah%faDyR$R%&b;;M zk55juPtPZlC!fbgoiElkIt#Sj=sUNLoA} zz_X?oJ6zau_&1_Xux^_fty~bl9-d$ZXT3>K^aH*Jwk8+=On#HDLsMkbZmfS5oCez7nbFz;@C*91`xwGF@eQ= zQ=OG`*#=1hoeC9zcAaoDX!8+50-g=U21+ht;j7Qj{aTxpIVrFdAuA~;1MD`iTp_La zz!tHOOE?>lrC1^SRh2SD2X+@4K{`pk2sg&&$k{M6TuU-B1Z&Y)uK03i#OomkOT-XP z5FX5Jkgil=lSBE!?;9HPq@+04$oU{L@N_}ZLA`AotWX9JSUmgWq~%dU$g!q+pJ8ec zWb({5BjqG^(lMdWVHg%YpZd3K^vkx*ej#x!?~jKKZtS$pu5J1HTb^z#xh9dV=~w-Y zaAUTz0`RQ74`9qMN2vl3I72+Z_&5c(i@_H7Ggc`}DOT1(sp16pvfq0(!1D)&0Y;U6 z+`Fs5#Fb{9u&oYpxu@OiP=c!|D0Dr_{Fs=&`rhk`mDR(i1o`EQQ>IOqi=DfRrK-wj z+VR!bv*mIZR#{%T^N=#t6>izDbL)|NiexrkDx;GH+Gp$+*}4{6F=kPSKrlh9Ei~Tv z9cx(#FnA9wd~%j60Ie zlheu;lrUCN@WLc<@3(|fWepyRJ;`bLxg3Rxz5Y0n>n>YYs;uLhU|p%QjvEbYp;TF} zLWOfM27;DNFD1G+ks~oHKCRoqv@~pZhg4Kl7y*)9&R;kxJp-NQUh_&7rKhrI4~xI# zE~#&5OF6%wpirLv(bvuSz*eec%?)Th5v}9CE9y9V{)k+<+;fFe1tYKvmjZ?cghoba ziFXR`&YUGb0rWb22+9WD3BY$Oq*#F#fd}Fp;6)IE78W9mo0G9|_8+SOH@1bPrqbdE zx&98NWyX~cL-_84?$-N8bf3@Fzq{I$N6=EIe9%CDM5551dhc7e7s{q)zd2r4>6Hnk zd&iV_LMXgrL!Ru|RA7D^9l>j7&RkQBpw>-M9>!4**KBU^$?h$M^VdL^Kxz~!zn14o zUc+0A>w7MxSh1BVPGNtlQiWqydpMOUb9#QZUibFfOXb%6rBYQ{DScCqN<4d;)HfYe zUTLTF_bVSe<(3>No-eL=vDR0j^%X0xRwj4d@u*bQ9hBXBwrg9&DhhTklt*yy1HusFF>s`KAzU;&N}uC{HT&w?lggt%K#dOD*Um(|&>E z_u1yT2!qZzO2@TUs*qQxZ@`)pW=v>3%Pnsd3{Q^|N1xFt1Kq!|KyKexDqCCfrM0m_ zTI$QCt)W;;iOhy|Z;obbyLwW}*2W^G<;xT2mYA}=O?miMpUi1D4Nc5A#8iym)fG!| zX442(1PkZy2>6|H211GB)aUhB3Q*pe{y<(*RERQQ){H6Euf74i0poJ~+_Wjry>ME> zYnW3d+chWIxdAgj2tS5r9tsNmYG5l=0Bg(7yt_uWZ7z`J4V$F6=0j3kx?LKZ4@q_H zPN}WjB$qBsh&ydA=j4<~I8vZ(Qz}J88)f(Iw@KTUTXpTMljA2&N^l0nhv=GXDf?)T zm4LCblwxIK(pn=>sw7fy8n8Yg-|;CAMyN~n2l^5op25NIcA1_Yk)GajI;UTjmkxhd z|Gprt&0Dn}EJX)O6_g%$a^6fz6@Pw}y#4<7$c7CYq`to1JR=3e2#hZ5@9^00?L>tj za>PR5_x}EVbB>)?ZK3kQ3opozfBa+9-thGcVO^<`z)h`GS<`(i^=4~v>w%$2f&h!j zaMzUl$?tDV{G!kbqBAk+xICegV@k%y1G*rQoC`uMxw*77dSz%REd66KB^E79bciw* z`0I&9l`78TiH-DXz$R=HL=gT6&u#Q;8>cH&Xj}xrFa`)NA;bXpL2zXqH;1mc-%7yd z!gJYzKNKq{Feqlj(%%sVLV(g|P4!;g3}DtVu@Qpu zTUn{a9Pk_cYq!rr;|+xm;CX7Ra-~tOQrdU}>se*9$dd$h;5zERBG+zF*H2EH{-Nz?m(>&$X7fssb;Zh6BOIEQiSgxG8nNczd3U9_blyx%$EBlF8GB`T zf+2(^x^^h-Rjy2NO<9g~4K>JgD9;c_5N8P2A(kN4NFoRkx6nA{8a!2Or3#<9p6@7D zAc%2Y&dRBhvcf(o$P39!uTROq*qm(Hm}llSV`XBB5CtwHz!@7S^b ze&=t@?_l0j#b8$ITiz=L1qCVBoH+fmoIcxrg;IsR1VJ);zu#}=k}zH-%2SjUdknqK zJ2xtifWa6BIw^`3Z6o-YdBuwE$INx;cX+IPKXkLjZ%s^uwH?Xh=92olsM5xk0tPE< z_WJv8DV1GY@@4;yLfNTpaO!Np2n|tUyzd>AQl`&SQs9=LwriL2cPL2izokU#t9^Rh z`t8!?pbRQ)fo1q3_f$xAxz`*g{AnlQy!4vA8}sFT4^^9bC?`)(OF-+%b#YC()K*&8 z#I^f72!Ey(ZEMPt55B7=dCi$=qd0&Uaw=AMcPH(-v{EIhNJ#foK^VEM#c%q7TsKkI zow8&1t`>m5kXitmuU-2Gr3!gs_wP(zbGm&xMX548nxp(4^sMr2TI}ZvhO(uq;!35- zS}0X=J+@GIM(NoZod?jk7F|V%>NhL4>loUxrBM4p$8`QD#O>cN+jhNA>YE>sjV(Ln z@BZd-86BFF(ZOUncRnI79iEm~UYpP{S}cz|@(HPF{h&0r-6OBR_FWm8i0YVRF|-y$ z_;frgGI_O7fKx7Ed&0mEG}PpYA8!)v3uHu`Z>;I{JWHvFGHWYJ1n6DX zB#dNx`y(=_>jH`l)?~te&FI_>&(4_=47l|EYo}C+XT>BZHy~xDxkd)l(e2eb0=kY8 zo-A(m5F5PjK^^ZXv1j8I5|-WK^OwoKTke&b`i=_nhzt#9 zU7=KA-ruvYR4R*e9+i9Ud{hqXxks8CcFM*L+oic~ zqtw=ImfLQ5Sn6swYyUK8dssJw7p<$SyD7teWrEG8rvs%4`~N~fS;9FOOD+ZGfUSI~ zuC7iTy%IN)QYC9>XvndQys>CM{0aGo@1K>P{-|{I1PuYSZBzcdAo4AXHEr?Ko2|vI zAucaowh{(kIyWvKd2hAJn_{393=B-l=xD$YR8S=>ki^Z8M7`28zEK{$z1KQdak)Dr zfB)@K=^dUiLUl`Uetm@|2)@TAEaC{_xwbObeC{72{FFuPAOu6uezia#j0Fi`14xGc zvXa+dDQHiAXA@~|uofro!?V@sGjV(=uvtxoip1{?>G?@Q&u=c(jid7PyQs8Owd{3wWO9&-yuUlAy`K-f+D26yxjbS2(yXtba2hY#DrmVuz z9Sglmzt~K#?d4|YA_FL8Y%jf~zI=Wxb{vJ(yyAoJY)>Q3QX1pqKWF6NNtO-+7Q%YDIlX%vk*>7yRg}KU{1suOv z7BZfwHV(z#BSrq=#J6>%_$i=VXF8lz>;~jg6Yx4aQBHPJGg-r_Tj_Z6i}1=g*(j zc?n&gB{RxA+;*o+ii?sj#9qVum=L`Q{sF*S;8E(_GokMcy_z@#om!)O9`ha0b|=qH z8=iw>v>W%G*0u_1!8$!1?D-pNQ-wumF9al_&x$~DYiqI(`v)U3m@ququE(9vcBw0< zyjd*cHO9JL*Q*+(7b?n<{O7rg0V8xpFuc7jc?}AWo*~Paq^!`bJWo;(YhMG5QYo=7 z&#!$xm((}=Wm8MOp`&SEJb(bauN`9Sd`EDeOsG|!ihFS$JRi^Vfd?w2wK-p6@j@A% z`Iv0kx>b2Gi`V<-FE zz%rzx@1W&v{_X9z6w57p%gpDY=r1Uroh$qHACUN5Os26wI3##n}skH5Sa|sO0GL116)F%QD9*BUOtdxUnqxnvLUOzRZ{b=QD;9gjn!4RS7v56SQwyjhlyqOV@Dv>j+v@n($6(v}4MC3w8 z$au;?bdTwfh5;)ripzydA){D<@Wx_}u}xi0A_*dYt&}Rf4@xBNiGm@W7z0kl%EVO6 zB;R&oA*G5F#MWhu+4UIW$LcCW$Uqn}?dekpCBh~xq*Pi8T|Jgkg6E;G?OXghZgV8t zB&5VR!hDEPPp&eE9?RI^nRH`5VBQY*CkXP%y=D5l#P__;w_BYlR@@i$mQVJFD zW>BgeKl62E$fwO`S2hf4rS4IKx}T-4wP0)8Bf75Lcu5^^Ho)lFN|oNhF09I^o74p{D zSdCJps-jHJo;@qiKmWYkamO7-n1;1Cme~jq|Lt#n+MElFQsu9nkp8rBYb#Z%%8OFlfK_jDANRLcI_e?oG-c~Vh2D)~82%U^z}OD+v4 z@1IaiVU(Mr{99b-^4-cuzW3oebKI#^vGK7F|Fo2qmdL47r{*pC5wh}~zcb3v{rPA9 zPvUG{BTsx>zV_6Bq1SC}YRZ$nn=Ma(>3~Zf`{zpY83FN16&Ufk5jlJL*`!jX*pd|y z%>(ZtXx*vlr>xvnYoS!Z)2?lku4f7McxV)Z$XQ(jT}CNk z%ew%5{>w`!Ret+7|Gm<@ez|brg4EX58l{8nUBO>hj$3~1-+jt_2cP=&d!%PHqWm`e z9pSffOvDw&EXd14#*nT2)tr$%&|5?WVO;@T-EJA1NS)tyTiJbUDK_JB-(48hrmp$v zN|oH=UzC=%?TK#+UFQ+<505BKpXHUT>{R~cS}0Y(x4->u!{@yH?Qc&Ux$%`MHViGD z0PBI1U*j|FX)9Iu%sEcLt22i=hrFkY;mxR2Sr7m9MkBe#UnQ=*(OTUafh+={aBx1_o@hJ1DlPR0x*3HEu=X*AqNirG8m$t?+T^KFO7eU&Y&WO1u zE{Jxxh3f^LhuF0M!Thz%slq$k0yj1TD_ob=Q+Nj0ntNyO)s$q*yWdfnlF;4`LBsi{ zFE33%g_Tj5og)-iSnFMSv9Spq+{EYNS>}4?Bf`WneNL=&x_dn`G;CP}j7`kxJdK+6 zvKbr%fe=bFF`rcGkl}ig<)J7*_*hYDExrii_zl3g*zWm+e}W(>@Z&KPGs0Ka2JVYn zFxKRL-Sb#0I=aI~7>@-8VF(~Dy-L^MTH7}mHJdbq4Q)?;8ib`hr`@L{He(zhT%k?z zN+EAcQ30XKECs@u^Fe*TxN)mSkj`&D?Gh9cC|kIedm@IE5@SgmJGHNl`-G#ul)W@|bI(hd3_=tE^`#vn~7Xs4XIVH79v%Txy68Z2?RLVnl z70GQ%fR}4~1@(DC(U=na*88BCu^HjkW}l8Hw;9VkuZ@&2URN0kj5UJlZpK0gwCy{K zrKB|1%(aPx=U-8gTQ(}=^3XeLr8bd2iatJiB4Ct-!#a1EGgtuH;Q$MC-rl~`FSV6b z5{Opme6-w(A;$PjXb}EF)Gj3G;CFJW0B24Wgd=wNui2StIk0J1T57$rtvOfMgt$cG z#NoA+atK#YlpcP4(yR#xVenKTMB`K-E|D2L?y`*%76t%etjFy#^VKHsuQvP_>+0;B zGRyirY@lhKJw=C~7BYZevMCcdrXdcrVvSp(8PG-l?u4aV$x_^)+b53DBq*VQOgh^b#$ zo@?Uj=PE5tc$(O(OG4Ao-5#^g^7n=*xwBGOluE+__H~4Aw%~0cz}G?7!ovXOJ^X<2 z+R%AV7%QyBF%~177&P59ypFaVbzp@H9r9K$L8Wi%bPV~Grp^@p3*OI$Ilf5vui)Gs zDX*x|Yb`q9^vRR*&)@o{l$4angAYDvj=%QWYeqf5fyh6>v~H1Ivo6-jmLL`K=>s$#8 zbEfaAw>I|~(y@ZoKcUMmoSTs9{J8w#Z@0<^-d$;)3#A*DT4g0Uvbn`8_Z%va#%izh z^af=zsN-Av3B?L+MBi{?KPH^or^{Y1>?6N<(vj6c*CU}95BP8EnxJ`lpqn!~}94gd7$tgd)k5 zQ)N03QHpS%v^GphYvYXM7r13I9G|B*UOPUm>lGd`R_tEJ40)FDdJZcShC&5J$9WX0 zI$jWFu}`d}QUwdL!u)K>eIvHW%uTr>Fn8>=gtaHr-i{}sbG>h@!y+upj0-1jbfrpk zCMd&W?dCIzl+xlB^V#Fc*ZugkeoC$}z?)m7OkP9c+d8f%Y^BPmGI36^&DiyV**WaFDzt2+^-2UzP#6-bhBJ%1W>t#R}~LkHa1{H8Eq9D!>+Y-3(}M z@f)Se6tup6Un`}`v(G%E{85b&u08qWlSV*B*qe(NFUs5A_BLaQY%5i$H#Gj7jE@aS zr$bQyhK6&5@XtjBxl&!8^!~Jk;Wr{?X2Yvis$iVN7zIwH3N)6TsGg8tBMuK0#yL?R zpgZBI;fvv2;p4amb;GBU6NF>%qwqnQXlina?B9-Jh-ZL@&XbV|%ag$-<9Fz>x@yY^E0a>?@GCD% z$E8cMd-ra$R<*RW$m!Fk&3CN(pMU-ZdGGr_kT_f9^0}|bv2#;K_Qc$$5T2~5#){V9 zRH`sm7s~;W39*>cf@w+>)(@B7%cI1*ZCII(Oh>nF@XyO6#-rWlcx~nrigc7vtQWS|6}&m`%h=`| zyxur(`}XaoUGX+?j{7&GQsw5M8m>1SLWQeG>dn^l)*x}i`3)fP9R*5MX#qBGwDQ4V zR07ixnVt%pGCPB?d&U$er4P{x@pUc00z8|D8=HHZ&gU447-zBD2IUSL5=teMAhcUWsbx(9frbFxX2|Y1 z7?+3cv(mrWM7Iswl{C+rB*IBHZ+SE%4rBoLMu>?k{?QXt<}dZKu@bTi!mGPKYLZ0b zF~R-tP{FeVAta%8$bAAq$@zPB6i9J_i~$HLr_zYA43pvn ziW|l}mM*?5_YfWjOD5-2D=e=co z1`rlIkHdfA?GJCdWusqi-CwLcTdC~cUT6%J;cub6FiNXVgmyE^mc$&eKnL1oc_=Nf zk^07svT@5^dH6m5!hE)i6U@K&K3r*dtw_`@y@O@CR#`@z@b?v^iz^UbeDNi@_10U> zSfc#tpZ=-&{*7;Z!w6&R>n(+kjptt(lm4M_N;!MM3fp?Ez?uy0PKattHWMeE*qYQ(k;2nO|rvfa3gg`?RTZa3qq_#TeC^P^XS#PJ@zkM0K7X zJ$l4=2ob6Z?}8I2PH5k}Xy*6lKKD84?(CG%)NtYoj9GMiDSO0iV=-$D_UBuQ3cIE( znN$8d$9(5JCy!_&7|NFM30F!vcY$aobNU%0N{`L~E0PYzx7C$iGqwn6wqry7e7XOQ z_sYB8{^6AJ&ij8#Zr}fQ*|+_6+0nK~8XLCAEqmWC+qT>-@wu=>gRkl&{IZ0`{z1kD zzF~M#6ay*={60bMbB}s1t)=uW4NWIyb-Z~8^3=llpz)Ck9ipbPt zNC~8n{tfHjuuM%wBp4W%_{_z5rAkRbG7c+3C})DVwE~MMihw{UK5rH5g#8=V3JYSD zj}-{bN>KMGJB--sv9bpk7)~-w7GY%xkjE!+1J0JA5fY1A9uFK}sj!2mkaDH-n&M5QnHi1~cGQzefw}H?e zVLl8Mn{Y*$+bCwZhWDc$enYuJ{)g&>5}=_r*9cR|0W&#m-IHtiExnG_g7>ed9_>Rc z>3AO)!ufjiJ=X#dKHQVBLa3w3sW~%e@C-qz0+A1~j^KMbU|BxlEdqgWTL7*Wv~hXD zgNgnNO-JR{oq6*9cUkdnZJ^Ml|E8v}vPmVnN{U?a3m+_(`qC`ZJ}8NXM^Xg~MoGA? zSb0Oi*dTr`9#e#`v)2;fRH(FH4$I$ueNfI{9x&f+;B8`CpAZgYDR4d(D*z%k9k}ct zIrf}<^T{6h(zlg?d3{<))JTE3L_lQ=sTl7tp^TANk50;w<5TkNkH?I18YS)S?UwQe zA(oRdwUvRi1-1-y7TOX++$M#x8=)*MnX(kW$(@+x$QuyY-uZW z9M79C`*#mA$)n!c#OEp^J% zX99`p1Hc}6-fotN?cc8QTJQ(@0yYsE}{UrS`VFJ2zt z=!r?`=nR?C)g6*vUBfSTg>;St&9P2BMrd@__1Df%%Hj42Q;wcGXRco>1oZwx<5rk< z8_cW5I_>9%JgKen>bhr@U0bbiZ_MY*mpf&k`xzMv2hnd8sueF*Wj@LbMy zN9E$VS7l;sKw{Bh`K@1VlO0^A|l=l$Tx=dG5uy@^zUND<~8ny02os9J=lO^5KvC=6v~?pZyJa z@B4p6-to{U+=2&ep>$3$A4em`|f`!?|kPkOJUV7NO{9AOHu8oB$D-zj7;q? zyePcpN{cZzU&o@rBjwGG_3&TU8fzn8O(6AVYkF%3AT$XP!Du89^0R3F%fSs|7;siAh3R z5o^^Femg;e^+*H@V=M@gzs-mL(gt*f`C3W%FNDv*5JEI75&A-)9^2K@3jdY7=Ry|# zi-rH{ADWSKT}i7R!2K_E<|+Y}s~aNsCk#tW^0Q_nJUuI(tho4c;!;!Ml3VMVx(LIH&f=i@~~P8Ks}6g-!$bQzn(#nh#QA%vt7Fe5XDK!AwknXe}N z7eq&4A@#dtVhZJ;^*+qIerpLt%M)zqVN8Sfjsa=QB>=DBF^32oDG z)C!kCdyp%E`9k;<``)VoIVx~Y1l4@$-7Z_w+k@Lv$3d|pjX6~1$>GyGQ|FeNjQ z3wm5vNG&{LRM(G%z}U(2qNKLG+_36GdAn;{QlY{cZUZF|`$k;Xbk+eIgdn*gX_|#! zec52`u-6j$H&gg8_F;RyC#M>10Rv@+|Kc(3-j^>m6*_lACCUi;=apltT~n?FW@bY3 z;lFY{`BGM5CCmkVgD3R=$#n&gq<%g8*Np+fe>K*OnUJVQ&IDvSA%p_ZDC8o8M(mD9 z*290T;|;-b!hfYIR4n@RY85Krv@T=1MVc@_dAdKpRl|Qdv7As~lgiih_E>bp&7>^1 z!++Ufso;GXYhbbPUkt;Z!Kj?=2+FyRNx5+8lsy0Z*X7w~zap<3eO6q#0V%C=OJz-J zX=uom>N<}pue|;vdH#ieGS^(}?3Xd+*DzK@2?o#P6bQRr`6f)Ljki+xuS^ORXCiUJ zYumXfFfel}TcE)h*TzUt$NAuBvGTvlk9z{zkCs;op}J>g2-yyAOlUBU#f=<^XL6QY z)*0pDq1ypDRWgPDx^(WaOiql->`c`B4F#v?|2o5eO^m!C|KShMN~!W_MFoV7izs~* zGwpHVazOff!qR>*U~-inKmMw;pSvVE*+J>-cuh_m{eiS!zAX6#E*+!Ef~*ieoOUZN zhF=}hc9@dh?lW@g#7ia3~7PfWIKXv#MGC3Az2^IKb$uSn$40Xe=qq^c^_ zs|h}n5K~Km(9-M)jDMRaT}c5pKSRC|_|msx_^))pgTv3kpVMx9=9m-q{ImH!8*j$& zUs*##L#c1~2BQ7&C*&W#e^z?>qtewA)J756wkdyJ5c#IZnzn4}&8}sqL3k1x1)M)I zBLDqAY&IJhVBvf2)k)oCbrTbpF50?rV6ExWh1%tocy_7WyKh|b68TiX|N8r0IeA$L zWF^{KoAOc=3s(z-plk*#*6CowW9}yCf_acEd5kbn`Wu8B9uS~^C^}EXIFB!c*%;w$ z7VilJO2dh`rwDrM6V}<_QWtqUu3QKG@(dxvvR2)4Okbi!`vJT$Y3}hyr$+N=d%-BRgzPZ(} z;}XHY75?qDV^c!z4%)s_i8@=kvr>>t1>zK92xZvr?fJS%qRg}2g?g~eCo~w(524cB zU=cusomIjvRRBR4vW3RiI<5^+sNf~y&zY0=-Cr!>_*OaJ+op4Q#xTm{ zQGr-0FE2O8un<~E$jp?qLWi#FPGxy>gD*w7cf()}9%*!ZW_~T<9eLMu5Q5TfkBU-{q3~~pmqAM@raw!lTQAYeb=5xNkO4^zpFrUHkGhfraEOjiQ zbZM@?J@IWF*9$OktR;8uy(o1RWAayDAC$f{Pe%4?!kwNj2v{L85;zopj}-Zf6W`Xc zjp2sC+O4r#j&Tk|X7EelD zV=4{17QjQrDUfFF^Y*Qw)^^3sn-635>na)@Q%-UlkAtkPpF=ox1iQ6Urtgg~`{ zQ3-SoVWyqRjn3j) z!vBa_BQo*BC?MMEtehiYHm3cN(=5fs4YF&uMblh3_o^IyNf#0aauR(89(w=3mt1e2 z@|OYm&bR)nJon0&6jiv5Ck#0?;P*SaLPkM^Q3K(mG5BL{^1c{Xt|fRU);k;I0E)+p z^%*NA&u_^lGJ$dE%eAgUo)A%fbarM!x(ALM858tuX>pQH#cRu6qv3CD0W$As=Zyj9 zE(T;+`*}lMo{kIa*wBDmMux3Uw)0S24RW-v3(JP}C9D8?T?Vc)nfREM6fq;<{Jn=-TC$2k*~T9u2-SVvPB2+g&UzI&YRlHv6hq zUOzn}v+ioyw)vpa@0C(fUSy7E>F)^l;YT-b-fVc$m4f^sHjW%QqT@dz2M!#V-)9J^ zMhL988sOtlj=-Onm6e&#=?W0?ssP(C(gr!VP(Yz<+O}<5;^>t?;dP^U0JC7ykb9Nao3 zes6N2K6Q3Ne(-A02+QePLMtsK7+Vb>G93GO3aBR2NHU%(3F}&?N6Jb(Re(+4EQZy1 zs^m&cF874x%=y3-1wv>nvF;2hGeuu*Y4htQsf)b6aA`5xex2BQygWZk?mA>GRsidt ze|lgd^^jE+TRTT5Pw(CqN>DVfb81d7!GeFGjT zE5$-1Zme>6HK*{}Cf=N$D*UA{2DyAO&Y}I2aK2B<1kZWZjVwmGA^;ChWgwXHowvzs%7&>(>m~wqjUqr_O&o(P( z+Czp=V*HbL2Bp_(64e8qh4*EB=)N!^zxAt4iC<{586$XS7NfwOi@Rhp=$HP{q{YJ6 zRGzfdP3Rc3+BQoE)a&gKU|FUul2$KCEab5Qu;#Ko6V}V>3W{XrBWuUZtXpR0yb=j3 z0k6jx!;H0HaBf~0@5zqK)(u{nh-^$rR1dKUp@gt!Vq(Hrxh%AIa1DeN3KWcuA9#=pB4L(Dv+E3*lz;RI#y`#|la6d%7(K>t^#*@#@}u z;c`&h0lL|3#vEA8Q{`HKe!)l%r4Dq!yY8-(nvz_pE6ws6eN|Ez)AnN@o|E$(0sR}-XTTer&`VbS6~;Y0 zq^-PiVph)?9FNYI;mM#3jrU4d{~3Ap=o6+~=sGEZcyzu5wM@??%h40hnDh7>P(C@X z>k)lRK0_2j@R0DekjwnV=#bx8<4~w9MC-2>yi-WWRkB1SJTs}ZK%b0Fb}m@L(QaLf z24yDJEB(VAGN5H*dT?G2m+q;8q0wAidH0~tc<`VsqKzBs2uchhipL$-H8f&EVbPqU^ydh?k;T*C{p2jP`C@X4 zl>ok{!0$FZ0miQ6^{J~SB%RB=HxVJ=&+**J(S3;V7>O`Ot@Z)~LoVH$2nT5K3YmdS zgZ!>8-6Q98K3UNa;5R#aLehRIAg3=(XDp}ea(-M+wGS(eJSvyEFUql#&&&C9PsyH^ z6EYKcMxudNWHx)hQH;Qc!k4b3(5}w@T=!H-9b<1LPnC70%C*4StVs#1>CKi6@;M-M z%*%Jn;Ui;GU#&!q7Qmv{RFfs;CFG&dzs0lCS`(4BI^95Y5w{Tt%*bDTWl+WfaU*zz zcvwp>l_jx2)2)?KWjP>B8p3w4T&2p?OtuV8Dp8Z6*a{UkKD;mPJXoy#ku4WH@s5bg zmbPp|^pcS7(9V3>knofM5LVB;JSo{a(e`ck8^+7VVoH_QP6wq}@3&*4&sf6P7#WXA zzZM&|QpM+uo5bME=cSY?>7$jsIn=kK`5xW0Eq(U?x ztb^D@;ba}NHfT0>pD(HKSPf7C^&c)JdglPD9S4CyP(2r2~ejkm@RNCf$8v4AuQNTOqmcRP-Ami z^mAyoR@}Z#hWLQM!3(Uua!T?OVZg95e(_j93E{XQtTHK{Kqkcs&%jt*FIJh`v zV(ozGLHLmAT)V*3;l+f~1m-astB}Y{z8=^4I2n-3U11p+vy?6{i_9gIDmgMIx?hmK z!DA8#4eK+EDJ@c|>tdtccfcq=hDY0V53kNB!0+mNRl2p<*Or%TGS`oeqoBF0WAwrm z*E*FdSy?1l-DIAVGBSRCNu>&kh7;$$Zk{i_&dETpQF(ht;YIfhkLPcGb>fVLW-4X-Q)ZFEDwO2O{r3%v@+hKkTA$$ zu9s2;I29|m?kpB^g&>5E$Nh4-C%GQK8I&q0RGRAYbUayekjMZe5C_XwsBmqvFrPV( zacje^ydP@@#!ArcC@v5xQ=hH0fVYHB=Q?=KmCD*upCYv^26#^BJp}m(*D=gx^vvlP z;@ucm7$C7;L9_F`(ADW{-t_?de10Oo3~PifBeIdMR2dtO>U-oUy+QbC7X_?)mXxEO4h33{}HvkyYH%59xR; zEAg1{V;Bx0-=Y86qZkjfb1tQ`d0&^c9&20K@&uGBEW?W{Rp=K>sp8LzYG2VGmJw~S z)|nN{GKSX}AXiqkNoi@dwo8R6#ai-wMM~rOv_Je>weA7osFan~N|CNDTUv{(vF)mt zxNDnKS68oUU%(T?$-AyARZ{nkw~|t2<)dRA*A>@}j7bHa0SJ*nZBv2#(PuBo$+M|( z2aEG#(p(jl#>!bK^rt=<3Y9VyJaaA9F;N7=4uR-OVR=nh_26pFc)s;O zq1=A3SXwvu4N*WnYh~%deGo`Ogi_C)w-yUY2Wc;kI~4*~1I7}G-BHAudJYxKmW_VX z-?p_QgyX(l1#ZPt~ zpROU5(p-O+`3w36UN?W!F*tlW@kyki=8)1mE#{im#`}%p0W5Sa@aI(+rq?c#we(ut zH+VAfDN$$9m35+UK!LHAK!F6PqqXq?(^eIwo0Z|+X^sOtQk*~$<9v>-t&f`L<+_HN zTg@@NUkGuMjtia7BtD63+VIZ#>!{mC@8Ge-r)v+w2Ub>Ari5Qu$2x9YSf0Z+EDPeq zmjo75r~vkE1gm`mBuEbG{uDIyjB}5=*^w!E{iH*neKTQr49|eL@{YcFgTv(j;eKOT zu57CHWh@nGJR^WUY%KF;JfBjLZ|#K$|4}kn;eX$puoWscAH}>T6c<=rp+c?=m(q|) zWy}@eu%kGI{mk<8>oD4bF6A#gHG<7d^t^pbk3MsHL5OabOmP10ETf~kR_WulDWAM$ zV}aCG=gIcX1+r^WEh-8r-3%MFRgZLQI?b1)o} z0)J5a-Z8NwEgm^OA?+8YjgpPB)??jPPV^61xw$ZI#+Vkqx2rECmvmpS3!&OQI$hs( zXSuxV!F_Vu-M=Jz_Wg_;xaGsLeaCxc|L%85iEmR%De__%v`IXkZKjl#-XaGNJSz1K z_eo22(!x!T%t?`@3J9FTe9UUy$GY&Ckit|H2>3 zCqD5f^2?w6OZmOueoX$|zy34%g`fXZDX9K!$u0jKnRUOo`O>eyf*pN}I0KXDB&6`W)_y7EoeESDOhS*sQC|`c-zh9E`0|-E~jFk!Z zT97!n3J`v2W+ub)Xk&4l->-#Wlucssd&i9%=tM#gp9v_NRtqDrObFFyXAyoRnE?nl z3iUg|v%)wmqzt)UfS|%sgG6<&zCI-<&P#USC>VzA#6f)s_y<~F|)`*E{L zZ)nIhuEZ#m_#GGN)dEX(fZ&~+9oshhwGSbnlu01zVx`B_vldDQ!1GeiuI>4T2x0ov z)p(?)I@i>*66R+y5Mm4umwmenB-exGwUzL&R@;)X!dScGV38CSxJ<5|awUA58oWl~ z6$r(QfPA&gy7Q`Z!NIIHV>n_FSy*6E!l4oE!+Q00=*aB)2-#ZmHH#^c5D>o~0a-h8u#%l|2yBTrY{v!FnyK3aUk8GCP@BO!O z>mC0}?zsDta`&Adl(Lfj;&*LGDZcCtx~CB4cavnh_Q;)g{Jh+L=P$`4@A?_};7_y} zMU4%{?bFW<8$l_B@I`MH5QQOKpQV{r->0eGh$H4&8F6 zJo)5nDdq7e4$EJE{(1SkFFs?+b1z(w=9W8U+bzE&oA!O$j3*Q#u^4q(9g<&Yg?59) zBp+>779rKGHJJ8rZg`Ci7QcD&Y_1HCxvVmpTFzhcDBn(G89dvp=Z8-vKNR_UQ%CmV z!0XNF`DTCTdC3Q|8ju%c9XAiwl`3nAraiz zCqI2!zWmL8c|kV=lGybRMdbC9Q}Q>D^~lft`U&|@|GP^jXI&-?5h25{cwZjC0w0z~C2h1@W2#48FaqYg*fXgPK#YiO2UlQH(oJ)-zr|=xt zVT84Kq%bbVCoMN;ymt`xvSCBytQJZm8PJX>Zy0moNS4-Pg*qY(7WJfz#j5~H1-y~C zH~D5JrYs_@q$o$3AUrtMW?XasY8{KTRUim)71w)P_2AhA5e}vUxNyhyoH^swg8TB- zdScm%)?6j7?Hn66_-Q`el#ca)wm~F3rN1QS6$FnnQ9ZwV85YLwKlC8QgCBqaB zIJ{owu|)Ohb*|u5R}ZZuz21f39MiO=^BVHLEEmq}EN1l$dDDeK^^QltumyU<8P;?i z>v$u9(V2zi&5iV}4FwBI6nGBSe28LSE*{!`nTzMhg#M0l1!D;mGALeB=J!pGb;XKE zLEe<1nMZUCK?klDE_b=?-2b5LzwJ@kxbZGIak5vQd+x*);^>VJc&E$?6_3)^%z0}wT3!y7RHXBm z@JWER1S7=p$$S|c@f(9b?ghV==fk)#&&Uq&4j}{{{EcPQm|E~=*uA|-`JqBnHZ<2s zartdhU3ahSKlE|=iT8b4?!WUxQk?CZFaCJ0Obm+*_fAS*N58afdQj?GeqQP}d{}mF zEi@sZ42?c(%{6lPfT{|weEdVX@{2!{BOiKiqa3{Rm*s;W`lLMau3wg2dp|BacfMB& z+#99Py(y){Vl5I5H_LQzqc-Di*}eN`6w|_1L zBjuNV`<(p#XS(F6BSFb3@JUrop0Pr$(v2H|_B9Lpr456CHyDO#Pwa4s#zLkNX5kL& z2AB}qtR;}~P3yhw8Qm8c6c~e14qb*wLPEP zFD1k0*no&aIGT#yi}f> z_leAqI4+@tnz5{zKy*eVG^683=acxqAWd|YVvfVY3o7X75!tF+ZR-jA;7#NH!>G8!_!qW`T zCdMy}dOW*Way%uH>$4bVm<^Z@%k}-r`w>Ug1_|hw0y$UgIK-KhDxkV-+Qc&k2=m!D zR#RY3uEs+JMH6{lu64N@&%A33D}NNl77!Rk%3_j)MZn$x^JABltcn)VF z<_C>Zg*d->%fSeA^}dogBY|a9zT7(35?T7sSttA0a*=Y~3i@cZ*S%3-on!640UvE0 zHwoBJmbGYPz`#(%c%py}^&91#_kKX$`{2*Xt-IeYd$-&z58eGianBV=a5`%88?tw^ zXW2EbuGY66YAU^E9k^Km9}5k}7+ESZz;fZQ+$39f?n``I7=<<4#p}B=@0krk0!@Zv zri9nXknD|wrBFeTot03iBzan+P*M8Vo{Y;;sDN~(sBQ4)Q#u_GR%tfoHMBPdKqxM1 zDm~I%pJndP_swnj%H#OW=k(In;x}U=9SA)Mr)ighe2iwVEWX?P_l-ut8NxAjz_sQ*t?v!Vqc}<@A zVQTsI_g<05zV@Pg^&3Bu=UzB1n>Ov1JqJH1b(?-Qai>%i`f}ta?yZ#f-d`<`+*KnD zWgDcXxIwCm>P>M=mAK-S^Ciz!ZI0I#*Gr-DLX?fQRr2ti)v~Lla6$eXB?5`rtt9Nw zS=Mp-6qyZ57k-2GwG|213gkb+8yvX-3U$JKt=8xhr9ypuy?o#UACPU^w#hBG+#VzylA+!w)~K$F~|j%tm9K&kXHLoe?>HX37{&!k4^!WZW3s;lX2a;ObxUwIciR z=cSH26f4`eL}l0Z$bx0>PAg10M&RUCwdWK0lmFt2UGwEHzi>kS^#4Aq<%fy#to+&k zeL_C_H$Rlm{M9$)=^uVezVPKgl;8iupOZiSpFb_Zf!~$j(Elg7SuYw|A3nn_e0LUG zAz=T8LIpknOifK09@Z{5Bj5oD%gtYmB%N)^cRQi~n;q+{#9Cl=Yt#Zr+bk1*uO~{2 zUDBY7qd(8hieZS)y1G1R+f*c*w-?KfJ*Bc`Taj#N%9BiAjqz% za!Xwmf-XIf)>xIL`dcNIm5Bpuh|=O5sjJ8~#Df#KCoiT@K^X3g+nY(TQtOY&Ep48R zWqW;+;6+f0J1y4s7LjEo=PuXH1xu9rTAyyB5jl4;AYDq-q3l6$3JCesrwo=|oSVDz zIKn?05Z%t-)`B1)EL^jWliF$ox;`cHbPQ?1hqwk@4`cRZ({1#7h5D@#dq zJ!gcU5VlxNTn*!7TX5y+rcc6cKs`0(meu)%j*w9_KrpQZc>e(gL3r5MRVK+M3$`_aT4ka0m95aKa&7=E*6o=ktgJ<-@PE8`^N$K){~=h@p5>H z5?Zi08C&K61U(*%c46$KGrw;%hDM`Cxt>yVjpQ%P4c2tm;~8n6%UvN;SW7^mf7bMy zO;|H-RsxtBySTD5hm2SV&TAJ#QDM2UTB8tSnWXF~Siv&rtTQWX`FjQl?}OpdE6UQj zSd#Uvv`*)BE9n*Ib?aEiI<5ry;#LC$m9~ZZ-G?5MgM03k!u%4mSCT`hxVTtGM@MD% zjswzteoQ7uL%PS4GcKxpKvaCbIaAhQE!rqnO!%vt7)A)ZN?Lv){K~KViV?yBgs&g} z_{YunPk;K;^7gmC-5g&G2(JsZUnt%LulHsFbK6p=WXPd1l2E85fB<|s3Kd|&GV5Qv zz(4VqaK+GbeqT@u@Cul`e2)+pm@Ku zG~X(lTW_B)4Go9P@hs0C8JyT+%J9@)Y418DfoL)xT{_^O5b*naIZ}}Cmg=fpBj2Fz z9a{>`bKtqNRi6=sLQADjZrNO9N<(EbwCZYr(At?#vQ&AJ>atwpokF7etHs7m8|5os z`HD%XzGcf6*|ces`A)xgbaa?x>-r^ewn#yN%kV`QWTUV}7S+=qHnJMzDbV=Hkx(!h z*;Q#~Z;)J1e8Eyx?v~mrpRQdb;CCnHkhO-*>a&Dqm3L2+SXQpg#NApvDJ3+c{BNQ- z5s!x@9@D*Z*tqR70 z^SuFW0>4C3e%>AB90}+#nzReN{#%7daQ((_{KkJwe15|*+V@R4abd&=?Ix#aR6-q~7dC8e#~lu{^e{`m*%dwCMVSVuKBxf|UhsrsRR3AJ@#1emPh{W1+pa z^HCs>w_QaM^w`PXoW~bJx>9vH3YCuTuu)Fn8f+h@J!#i)*b+Y0lw`|KJXj%Z&Auy2 zBodc%-AUmI?ayX3Ipx;HDN7jxD`yJFbG44M9U(d28IjW$L(+aZEYTR51w=0QM&#uA z(0myW%*o7LmU(~YajuIbuIcWNru;TCXpHbdYs>RhKWhq!3qtAWt&~+ zYJl*WaARJ-Tb_G-Yb*`{xkkf^}c`Fyj zHx@+9C7)LtDAp&l(Ge47kZ}WXOy5}fgBEUE!qYKEIL9bd^jh`>i47>z7dFflW1Vr# zIz_v?bIZh^-=M#fi;M7vC@$uV@ETy@vXCVU=W#yB&(AmCITu0=t04%tKwwHbd(TQ# zrv)Xf!v`9gwP>X!9q4jsJ7y&Cc`*M^S%}_kqab15?-+8HP za&ND;wKmy<~YxSqAdLxmjhcF2bgQD=jp(6(rz<9%#>H>v%Wj^0v_k?efc`S zT+%<1Z~8CSgNNR%%*Cy~PY3-wFnl8Mjl5iyI$lfl8cTp52#)H0-luCSVI(&t&a%Mo z{X@qS-*jCpY}T=rJAduy_$3{)p^Vq2qi^tpw&A$>O#YDa(#__5$QhES&r@93V15JK zHxea$;gxj`kF{%mSRPcBWm|Pkx^kaFX>zjto6wKM&Xh5&A6rALBsVd)UK7*;iptfJX`JA2Yl8Vx;^ViMB zbdMOdLZ0z{dA?*QG+@^Us>*iEU&lNg7_pM|bIk^k69xY3%t74LutNUQk zV+3)l32$;Ok?V~}VNog#yS8ASXDLq>)b%uKjLt?!qB5ohux{KeXm0UKp3-9WUe0*4 zBRq_0yVx+tm9`_yF7yN5j@$HFlm$w8NHDfX$}1{#FLayMJ$>?|eCu1^l%}R8*|TSl z8Iz2~y1F{~+rRx=snByDdiW9R=8E9>^Wt`m%BbF-Je!pF-B&4hA1ssoJBp;hU#NU& za({zXfG)fd5uFLkh0ABmFw3Y=afbX_fkFkKLYbIK_6sy7Udhl@voS(^lOKn0$TLc7 zlL$Q~b9x-wk+9(?G@w7}Pu-eLUpfmGXZyDoYCl?S8=djV$b=R8i9Q39;IdXN*mdWf)RI2K?h$mP3O6jV_C9@sX>t1Hhn3G6{I zwok`Wj?~m9*R)q(eo=Pr*kRTwa$B^uwHd`6pYfPLfqeJ9_b1L)dM5fExzH0be2AgH zwKUfHq(N1`4X94(eec+wce(*Ezhw|rjNQc-)qyzt^Fb06F5e!1AZd9!Jg#>PgI z96cNkYrQcUo)}f0)|%IgfskegbdJ$xv3QAu=Qf%(u)4Y?afZl0|I;^Q-@bj)-Q8_y zI_Rstd-oczjJxl?TgJ8CyY9ZndSS&gPyU_E=y}Lq2rJF|!tUVvxBXA~xsQEH-u1}G=gS?pzejfO zdQkT7dqj3_zf%s~@=kf^Z6DS3>JiED9gx}V{mLiS$<$=8Ts;4Z^mIHa=g<6;oH_Aj z{ro)%jK3fg!%xYH6Nlw;=cMu`t}7G^H8nM6+}P;v@7H-2Gl~X#pFtsovg*wOj2JWR zk$CX?5CSd$6eyenU9uG5>1j*msJ-rFg43Y#dSi8?c#V)jHu2`dn!Z5l&2H4TLD+^i zxxs{rNqQDgh&7LA%FSr)Gd8h2g$e`=KuDeLu|k_}+>j?9e6%`oG!2Ukiq__^Y|-L% z#peqOkMsf%xJ@Zh;Vgj}>$mjd6lknW_acXhv%dX1f=Zmc@gp}qoLNW-h~EB)Q9jWA z{7(DYeX&~jyvceH$fFEE(EtOCk__U|_GVctKs=K??poKw-bg(NKp}eVdYnLEMVL7l zDTL*?*|C=W?q==HaVKOd%f@%DhGwnMw&358PTrNfi*>g!YT z{L2&OJM9YL>&}kLJ8mnKJNBgtXBSeStQIg<58ks|-v3~;{Ne|zq`-Ua*DA(;-+-lj z%`_Kip`C3$`Q;DS$VWb~SKfZ#J571#+aHm)-E~0fs<%pY+2)i|Rk~T4>bJ{#-g%EX z?;Q_3BJX?8PnvsBYRaxuwk`&gTlO;|ELlmxlWncgR6C{P%9_{FnU&EHv$KS?VI8tc zc3N`v#o)Y-f`VbCK%ug=?NMDfc1mmG1CpP2rI6E!Io&{*#*Le9i=zU}v3tUl!7@)3RJRue;uG=cMi#>sZH|6(pqxjkPUO zR$OI1XF^d?kr86>7xZ7AlyGoX*ZNe0l$#6C6>Cddyx9RSLn8RqA+P&n?rb;Z*lRyBf7{O- zQT{Des0{F0FbVU^tb+Fj@*<4i$X~e_5bS^JTi?>Z)kYBA+S)3QKmNE;rkp-~dfuSw zMgRuLcGKm0EJHnul}YB4@%b$Jl(CUV1emJ?0(;uV25kgTz^@f%!;|vTOD`JFlvAfp z$x}}~W%_{c%+qRs($$ODWgb00dVS^<&w_Yb_2)+-!K^EmNGjiO^JcaItAi!izqEGSswF^ zHw(%?#t=y=A#|~V<2#l~5d*6rT@ux@S)Boi~`QlfO%lE!} zW%=tbzAl@#eN1k>|2O3Bcm9qPl;4@Si^!hsg@$2Wun>+w3s#^`@QedG=T=hi?pzrb zCKM`5XQZyuVvbR&U`@DO%*+Po32@5Ftgi8>N?yAfV#eo94ckyw+>-dT5K`-0j#YFZ zm<)~RtgpDBDe;Lt!wS`x33GEZDRsKt%d>=xrCsN=xLXR&>nPU)8|p@l(51D$FL7iY z>v(g+7Rnyjb%*)85LgFoPca)4BSAwuE=H5Rb#dj|Zqs(~v!2C-%x_^hy;0T*v1mXh zCPs|l6`?EE?JvIgqCE4=GxE|)FUkMNZYR_f z(LyjPBeDp*cugYw6oztmjl;J=hey(k;g&)sBaG4EWbEY3qe0~4vA$jKc5mQc|Nrtmt3E+2}Jde!>trY#r>vi>pq_3}A2K#kx z&R8MC=3-IlzHmh8s4JCaPQ+$HGT3t_@huf~HF-uUIyx5A`^BWL%9}ENR|^c9^SlwM zEE$v>*W&#foBo<~o&T%((tY7`GTQfbnF%~6v!TP%({*H73K3{vlrHu4tY~Qv!aps#J&Rj5d$%JJaX{`XXb4yE$G&CeV{%>?#*YIB> zeczIkZ^rOnYd&_8H(dK+d2PUEYztKF0=>GZ<-;{VI5eY#0?a!h9ufx=h|a`hW){oS z)Zf-3{1=LnaAa1p_1;+e+M!Iqaug~y5Sl|^I4$9Kv?LQW8#t~-AlW-+x$UNx2M!h~ zf#wnNTx2R(3cPwMAhCp2eZW#{HR+0fw4cyCI6p<5<(52o#SUt-BRh0&S9fAQQ` zV|~PZY@zSi*sN@7%`*^*&|0H-{@N;!)N4P7!!hli zxDgPO?47V zaOXS|5~{!>1EVo{>}!4I9a|ccRxM6E_1u{Jr$6eD=TC;Epwuf3wO%ui>S~mM(6(F- zcqZQ8#BJ6-q&}V><^%BV^f_Voxc4gLt#3-;t%Aadcc+g@yqK#DLUlz{=j-wX>5S{J zwjI11>ks{Gyi>G)?6xGtRk1%yf)S5I=c;s^Tj9SLD+ogg|Aniv?Htqi!!D=)tEs+@0cPrTig$S)|6pZ)kRiN|ZX zP>&9Gi)Z#Z{iJ(|*4xoPYu43_MaMCJVY)fjxp!R+mJa`wl?eZpZPp<6KI^Cz{tHZm zHb{7;(Ddc(tTLxLnH69B?hOA$2&&TJCNpj*q42n_U7b44mJa__TGXi5m&{)~I^Lo5 z%w)!E(=j&DspETG->FdR-(be4Sz{xUx}Hs$@K`pS;lCb>*VL6Gzh zS@kU*{wqtb+cSS1r8n{08xj7Cd5>^mL*0lRJsFZMtr00Im|GA3wT>GCcK9#vv};A- zzow^WOb=k+?cD9)4htWO)j75A{oT$J6rI*H1{-K-knvIdx`QMwEsk zUuI`dmeyr?U4a`p{8v_1RQKHO#J5z13Qg;|3WZ7}0$-MG`h&bI7JX#_`i^}Kegz)X z?nh{PXg$7iIy?@14YaszJZFPYQ0FfO<;aOiQ%;>7ka4ApqPlkEdOh0LBQh}1A$@)4 zWj3y~nij(eXDJ2&+F*6Wgh_GQm-*pxHc z&e5QJLVuHglQD*ZamEb) zESc30c>*6I@~*y+w)>3q_eZ3sCv4i9a_Y=^dG+vXDdn{z zugZxNuW5N%jvs$PzW3}u$&uHeka+UX`qz2D9EkSK0~${t{-53$=6?nxZ@A{Sz6Kx`W=EHms259eXCapbzj4kR zVFjgYl7w}041}y)Bu=pAg~H05ge;5ywMH;ZJbH^rA103UMpl2@7viOGD1Te2xv25E%_FPoKd1g z;}X)o8K1O-b_mXSF2QGn_?h&Qc${V1z+GFm4!31%H@q%e;NGeDONBE;-VL6u&W&nO8?yCKHIZO{0 zG!S7RlQn%<$Mj1ld*#bdjL5g1o022#E4SuKWjz-MiplMp^NkyNZm!EPQUk*?#yb%v zU?F((3QU4dEb!{<>&-F#zW@F2H-A4)qSvik&3P+E+6(ZESTfSaS6lRdiMwWk^&3J3 zXawd`Ca`DQ#PMQ@)FJ4zWMN^79l|TuV<~H#;M&DPd}U`ZTyI90S7+}_Di0{>aJv@n zFK3;Zo;e-PdTb_VAuK1Hnah5wR^&i2Fv0%<(y|mWonW*kP`VsOmJLhH~Xfp3h1H%!^7%+k2Lbq&g zU3%?(D+7fJ{HeW_+lCJ|Y~I!eLdB01~|!~p%D^S&zg})!9%5Pl?oO3G?Xfn6CvH>7Ur$ffj2(=S5dCxyv;97^*-~A z@MajxIYGkifvIRp=^E~rljnaZU-{Ob$XCDhr}F%3|14v3q4_cz3(D|pvV7;M&&gN5 z`6u$t@Bf9lelnceuTEejh|-MG*Y#tWn&^{Ac-n-L8tgiz^zyXs-%9bN72E42Cu>%E zJ6_kdE@ZAFzf9(NpXu0YVc#qDo{ieBv)X=yS;IijC?A!VX%H9!!JqRCdMtQ06eLNl=i%dGy+cyX3Fo&TB6wM#TMXU1HE^5`Ht%X-PYe2Ye0 zD_IHaILY|a0mm#d|6k`)Z(%W-dVv$qEgC#QkBO!d)_U+qE4xgPncN&_K zu$ma`*-DnTD&VV8jF6E3?Af#O^2;w9k3-7y&p$7(z4n^)^z@kXP$1!1a`50mx$nOF zO#%z{{Jb1pNVALpjlOg$ z5Y`O(42+kN@mYyy6s~Qmlw@9&v_WyHJ0f5E zVP?ypJ&i7T;I4%=x>HJMeC8hqb)#E(e-wG<aP%e zbv2gN1w=Z6cNWk)M(E9awGma~jDF`>k+w1Yay8@jMg&%Cj0@-drA?jfu$HjrlZ}efJtl!S3KWFY zSnfcqVx@w`ITkBMc%K0fb69ABs;VlZV6o5TGr}b-U+oLOh5c%Q5){LNTlW{w zj}eG|<|BIy;}%aAphH*g+@33U9V(XUU0+b<%M$#4?JHlF|M7=^VB(RJfD+;GV~;&1 zcieG@Jn_U6@{x~xRDS7Ke$AW<+RwZw{?H$o&jH<&|M`Ul-tjsN*$bCL+Ruwuy`?!< zD$6`_;!KNF*K9OOF_bGXEDPac$15^6WqDfQG11n1pZN^NCVI5qCuP%ycj#JlWzK;M zmyXK#wB@bR)^xAZDUIecIN$NCj8Aqfc&!r`yPng!E?M*9KjG{RL)&` zLdRlMHn-@#{mB^EXD|Lh_vc=7pVr2E6Gu~V?95kn{k0U22X=nc`~|erYbQUS_$IP{ z$43&MEOhmplEJaVMgg*G^ZODNCN1xZ#+V;C!BjbbGEp2T59T-XJwrki*I)4JCgVI=DK9ZrhEzMzWv$1=`hDK z8D_jyv1MnWwzW4!p#pE;+n-coV06?_YY9W~@UcCq(t&3);}@{bLgSHVqC&?Tw4`l- z=mY}Y<-q5ul0sk7dlXvlM)R<;5u2NksnD}Vp<>Tva5V}QfC7XF92iuXPH9CJoIBU-L$wqAYjbP>*&Q(e=!$ZL%1GD1r@=V<%6a zeK91jvEXxOOMY(h9pmCtezI8d{B@F_zqo=Lc@}_nu}+U zZBTi=v945EF4nx2Qg3+OI$;?=2ySoKY=T3>5g8i}%k)Il%2|=`HjHQ_M$wHzUj{)Z zf@OrYSi-KUV&y6uYb}&2&WAu?jxZe9N)^U3N);ziNI(ot1j>|ApVkd8Y6R#UbE3H< zE~VObnSfjAMTaAc6Se-BR97zi%!FJyKZy0f%KHMPN<&4CZWs$++cz{TebcGGFQ!nj zln%?Yh+PalePKg1a(~{DFjh9PiDKf!nSc>$wlw(+0p#>XSP2G(X3Y42X}}U@`xd|P ztN^wG!d5cyZda>RfoVa3vU_`SO~fJL zl9_WKC&8Hx-lwYEZ4_y130$~GC+1{wnl_%3Lcis06V-My9eV`0YBzP7xiS?fxkH#yxSh4~fA1TXE1Z!1-b3hJe$;hw}%_UT@|PiKl!1q6dr zGB|QkN{i}J>KvW8sB21*(n}78FAYwm%HC}sHh%$1mDkUFDe>(}r3&C(02V>%zQfT8 zT`Q9UDU>54D!l$kgzHPkFjs} zqq1|yUFLHrJSAWL>VMWbr}ZcJ#@6aw*|#e(k4zoEctv=dZ+-Xg2(763lK=)^lY-r4^xPvAd8BOwrPLvn8rKQfgE)*$~p24K$ z@{O)kx!C>0{5%F%t5C6lQ5#{{oM23&z{#ZSf|tTmV%N4pL(5N2hLx9@k)q-}!*k*} zfw%s(2I0yuww==YXJd0xROBpQfv~nu zwrQW0yffDjUf6!-g^;dPDa+51fBDnNoP+Mt|D2-8uxZ1-zCLS@Tm%^9L2IKdfwvqP z?v%lS^U7m(=(yUn=?eWpel3AC;oQq=9ouNr^Fz11MCuPkDK{l$It#=ibOl zl^Y%FN|glO%1RYBi4l|dHDZL8z|gf?SX|k_%9P+JP(m(UFnS{a0?8(f`;^EU?3tDW z+w@t(XdfIz}i=Z=F#I`0uA$0e$SQ%z-#5uWobC}2n=&-1MWyfZQIokSQ+ z8^rF_kDn{SSi<9mP-ww0p^>z`3nOOD*w~V1_9xocjD_SQEgLXD%m>Osmt)yiROmJd z+}CW~Tm2wxBoQ5FhyWD~~# zC5)|90a)4Co(~XSgJaJt!<#BFSWBSz=H2eOwM3bhSreWTMys+kTV8p6(#*ZqCQF%& z{Pxj1^JV)ce~MD&_x|I5kmsL!&UowCK%ruPC#TBypLo)ICRCVHsdD;!P@X-W;r$ZB z$fxt>YCO7D1}j8h-{8`Um5P$h%DnE;wz~Gr{aV3Rs`!1C($bLhR3WMS#Pp>rlqy#P zr&49-rVp9FHjbZrEb%F`QsrjG{MxXtR9VLjgw-ll*q>j1ZOqUS_ucv~DJ!uQB2I$? z3<)S-{>oQncx2RKRJ1S`3QIlG&{8;0n>Q*w_R;s(%baVsgyVbV_B-E~vIm3D{GU(D z_n-c{p@pz?PsgJVe_HOm<2~jxN|oRJy$6i9CVL_K&Y{iu^0vDxWY+aInTfZ`9d|u) z#a{krpZT;r_3SqcU5P+`bx5|sVleaFp)^3L0xfy@{Iq=k@d0z}W>Tu$`#^;>G$j-l z2tU&lDm7JJGY%JnNpL+7HUeLiCyXz`RDoQFhrmklp?4%bI@>Sh$+Isf*W(*msS*s2 z$(f7aPkdWDh00>+?#t{!gqMBW2EQ?AV+}C0m`-NKJcdojPfr?y!?i=^c}RHlyu2K< zc0td3bzBf?+V*U^5wVz31q03U(p=MqvDuj6qpoJGuLR>0C}c8okm;>YKFi`Fcu(#B zxrpKAN5`Xv-y`gy4d(tr9%!op_2eczinw>b_VY@VDR?xM6eXiVEOqS*FVE?^F7lI) zT9a(EuIu}@B#onT@_$;Inwt~f6gn4zp^)xV`Z)_PJuTUp4Sj8;igVxMJ7L#Qj+lHa z%2#?kxl&SGVH7p&!2s_LlsOpraUT>jgbri8MbJua5*BHMgd`5UkuW|1QEUlNySsxjHyx5c{C_tZ z3*1be6cEE38a%RdbD_+HXJu$2Wt=+*W(4T7K!SeKyYRQ!7*MsjAg6= zZ15chJ~D$K)g^`gpk!xZ(Y$sGL4|KlYRht@G(UU6G8LMWx%l!J4=4QYxKt|NS5>_5 z{d0BWn~qo=w3I>xCBoGU_N=;STat|f))Hg=t^_0Fk-QkVn=`-2A3$F>g` ztTa(Qn6F1GLI6y=QIGS9d47_?xjokS<{SjH+>?U$4&G^4m4u??`N2{=Zj>q{@Mk_1 z_+9hQw_HG|LfF!-b}@ZRTdXlUy23^Q#QV^`E>~RgyjEg5ybElFN@uq+kGiH~{k7bJ zg(+^~tow zA=^@MEntuJTz9@SHS95jr%i+c2v!JBfY8V$oNNV4dLe8WN*KJ{VSuIsyTxc`q343~D9Sn4q(giLlEke;Amow)BrY~(q zh9P|0t~`@>#ZFW|-gjDFc>V=BeI_+gy|Zn2w-3JiE^+&cB-@oELw(0(X6j`#CZBz2 zT)IbMMzM26QN{*?5BiyX>e|A(KW#t`rhwLO(*ow0GS{pXcFD^v(|KNP`tHqwu}LdY zJqh*8OE#J@Mwy$7=^8t%{hUlxf3r$HTw%5kc5Qwdy5Qx!XC&tr?j`9mv8;^w~fHZK-UNgYehqg z6`mCw0ew#PmC5??+%;(wJs66xR z-_S~+%1=TlI!t}oTz?gHY~$q7ZTqrT93rsV2Af&tw?WUyl;3P)(aFW zG%xE5v^X+ByTI?6e1bz!qj2V(Eg1;(BK(e3kPQ<#YN_JZNAl)oE;t$z&C#b*#V)fk zw+xLH>GRL%@5%$@x%J%S++jV$uo(FmYxi1|$!RNOc8>AXvBK5C2iSb&Lg1Rl+C0M} z*nB?xBBAdx@vnAaAI$TKl$Ov&aq;T9Gpz4KyLa`5<#NX>^7_#y9OVac>f|$W@w}FH z66}9XUV8n<($&*0fvFLxDw#A%>Lt!vg#mo(zC?ZOUF>Igp43#=Np*Ft`EDnp2Pl3~ zppc-QYdDTKDC?Jv8#Ph=n*q>1$O~=+tb3{~g=Mx5RvMRd;m zzr8&1%?Yc5sleP-=Tsrw+d?3x%Hi`-^ZtZ@0+|#lFmzRG;%aQY7oHsmGZBg)h_-Ti zSmSJXG$xn3f<`Ee(6qIgF}M=qF$o0RguLRNP*@O_3q=JWx%+wTPeLA055xlmub-!Mvwkj}xo$R6&4`a?e>0&p|!odM?CFh2C?QzAu0{Bp(KZ zAwnra`~jW`Vv_UhHonvuGI?fDz_7lNp!`Ny-!g$V;2p47W(+$$YV7`@T~VmeCd&nD z1No?E8we`kygF{~Ww~X$lbk^#^FXnL>pbHM1eHPi@elhAp=qOKW1(!?y0B$+ zpYF4#j*ZS=gTUstd#aTHxB75S_o*NL01F$77<8h%(kq)b709;jMW){u!uP-1EA8i! z;k6FjQYN?Fe&xCZgMz1uJ10+C8y_-+kxd-YP6&rkhLBHWr66<>1%{hqGm?Zu`PoNK z>AD${|N6N>)1SchWXpu*j#h~H4jmi(C6`c9flGF5DVQJcFTFM)qb9DkM+y@{GWLdd z-(6^wk#64x>Fx{5kt64Ioe7#T7K>*|a5nV`m|1@JoX$zV6qi|+O#{8>%wNEMG7(*1 zjdR=zud!=u$dUTo2wd#EY^+1j15Sj4P1+8-l+k|kd8*`jOJ&=}cO{N8wkM3D<63#D zICGqUSC9W);?ugPN;+6eY)_TA3?`1I0s+Umr^-6sNL-Dl3LXK_wa^s3m&T>Ipuz}g zCMTzKtWPS9MozJW(arqdEGet#0I-rxz?o+|F5k4j0!?ejDWn2QCZqx~E5w_p0A zj4M6LZCcYJ6o7qu9+kG%J?3*bJT2e+_8%*~obXgp*q$nRm7kV^!iJPOqLD#4bK-mQ z#jigmq1ib@)2_@@C3T-!4*CYI927&kAEBhW`!*{K%cc0)2=ZclZ2T<5FHH78k*LZ>oN+36Q`#PJxu?bA)sAXUg9ylHi^g6fk5?+oh61o z19+;OIG4;WQZZ8=oTUuixCRBLO>497 zA|D_>%3_yJXW&Pcx`v!886I)PSjr!l9XWDj-Vn~|sY2ug6fy9&>z*oW1KRV3 z3I8=XIJgGO&g#&9_!IKj<2SHUWf?7lVCd92C1e9JBTS*7M41{5%hW_f_H8eeo!bgb z%)|N zqKO-6`r65Fw5QMKPT71{uT)7s#EfnfSR&*qu^89ByWA5tgd!onoJtj*X`|ABc8#%)@#w`qx$-^bbU(t%bZPZezvg%E6-{%XlAj^+b$N9O1Z~ z8)T)pbXge&oufm;Gy43w=3WT4vt4+ZWg7u8ib$A3*08Hps^GGXGJ^#2ybl}*UVJ3v zN8!QPN_W{_jZy{A2?)C#Tl`wjtX_);ipvmMr_Wi*Ja4-N>qXW$G0zZ=#O2i4X``%i z_9ge_9k8OI{{eL}?y(HE+he&fxpK4)yvUd{Hb@+3w=v`CYGEmnErt@|8hx>4qu*F5 z!CO#ArZ(j`md*>|vW`70^0>c^sWI|VMP#q;3nuJSr4rV8Ze3Hb_KQfjj-x*9`|)60 zX66!BOjMr0Hob9BNSXZj7<3_~QDpeS>glC4fK(PW%F%RAM z%s+@kW5kywNi*3>mD2iuFRhy&NF22g4G+lozy8zmmG2E0r3%1Pg>{=e zcIo>EJm19RjMB;0oU#Rqwo;{G+y9o@+70HIjj^F0%Rl|&Z^(C_A6bP`CAI$LfM>ki z9h_IF5E2RF2XM10RSw-zDy}p-b|nfGfXn~^J)u4;%W`Gg<^t`VxVEF^3HaR0qs9mj zUI!sH$2znhu-q>#&dDhF2X0-D{fQ7lS=klh$!Rm6!JAR3!uu=)*aTas>%?N$fEg@l zGGH-<%Bx4mjRyt1R9R`NtOMctZM%wfE?VtA7x&1>xRu)wZ`qE{9+?QH@k-j<7-3M8eGJiebLPH{|;x%1cbi4}Ux$CofN#_Ot=1xtP)?z3n-d(^0Cl zHe2g6>n_S-z`2|bA6i}_r6WM8(%oU* z3(xztpoNPo2bHFYn>7`F3x1aUpi7^T_P6_iKL6NH)F@wuunt=sTnDJx6nF##bR$7AEeGC9$! z<6GCGi7BZlZxBy*SPt&;$?Qx($M&?ib1O`rxU!S76W(|dI2tDJva1LCalv}p> z<^TQF7Ww4QHOV{fEtlQf3ygJ7Lv5}RDsJ7BC%5k_kVCtRrMxi52wq4oYwBb&DzS&a z%IWg`MuG(v!7b>#G%3IMQ?;_GB^gI|Vmu_Bome~TLPe+PGxH98L%F)qmPmQAwE?mz zl@+<9y)!Hm+Q(?B?eJJD!UBB(;U3U+838Y@h0go(So}u3PL4V~I#w6{EA=6!g4Vrt zO%;D$wh0Rb^PV35i#4^TBwOxNq7{L+4RgFIR|(J==^9EZRd~$(Tl3_>yGxD0HNBiT zACjpM8)Q-thX9XFyP@1Qf6PMaGou80^;E!EKd%&C-IUuJy@mi-2xF6Ta;__Co`swg z14=As0>3lHuuNKA2%6OQvcp`V*u)bhHb+7;?dKrjjFg~PIslIkhza_~_F`En@KT{) zQ6$j*jA!V|p!Nqscz`7fk4K0r7*AV4%o>+&vEl^6Rv1(mKF$S!(45q2J$MsL2Z{X| zHw-85VFa&wyYvL@{JzrgU$hfBo=_xC1z?7CKDo2Z`wi$i08x%-(WDYY%r$0|UkOe6 zm$65i+JFgz5Qk8MP~^S1mPCC`_2eg6UVjtL4G%Ed0?RhmSlXTEra+`4q~&+o48_J$ zR#Jht0~+ra#N@V0iv~6deZKw*!ad*yOc1UlZ~4SWR$s}C{l)F+pe8b zQodEPmEfES_nG5>;XrY_HtV=1Ttrmsu*N211x3hem}cCoA$aY3a9@NZ5VX5C4e5A{ z%lTd_>?UQQak=B9C&u74L57#H7^<}`Q5{ye z`=`@!&b19NPMz&OJ5#K4s!IE2b?fu>Kuo9R#8js;RoPOdelluQT6K<@u$PqJo9R|#Q!hh+mY8^-edoyEmJ^a@?-Y8s6_%DP+ zCY*|{u^6%B7kR~B5<>%Bk}K2`A`R!|&=IhtUm+6AThq#}OoAum){_0THxEJG^xcDv+zJ#x?9GCilnoM)FU%^s=IIX$X;UU=SvAc^HDQ~-u@^ciigiJTfuu*Lf0^veFzw6K89i zyzAad+1QvT<;5k^(UoNc#PB_9F}5qqB1Rd4vIkiRa}>p=C5N%L3V`D7_Pt7j`;^~u z)k`S*9pdqCm2G=|LK<7{k(Rm!`JeyuOLFPLu$B>1&YvHar=RPVr+?Iu=!aZ+`#7lr!;Y`-nYPW2ybIa%cc&Gg4 zziu%b5ty2WxCls3@04_PO~~*tVM$of=A=;P)7=O24{HB=|hyizS4J;{ZFkUw=5 zdaf>t5a3vyuLz6ug-b^-R`qD}v9@r6y_yX>%jK~)ysN^M4?*2o*=|F$!2Fo-ZmWcO zPDfeF?bcSPpu{0oWM@yY`hMv5_NpGN_ukgl>((q`aPZHg;&R=OP_<1Zfy+# zNBtbff_p&!l6MF~Ze_T#FSN-Fm^%>gcuA1A#_zW_H59fGIav2!4WDFRi}0SX24?(e zJ$Pq9`(U9*J!?hdL)=c7_sNpEL_NrtnMW|ztP^Vi6e!eV?x#eL*GIDbETarSK+a#@ z3nnv1=Nd}HaKsX^M0wyYMsAD~@PenOB94ChMUaK4OASQb7Iz=SpcC{(bx zTMBI(eA1vyV|Zj*{>{g#)abHO~}*s%ozkC1NHYKbG{saN^8qOQFJf^}1&{fxKj_yjTk>W5?&Lmjp?&HK;Xfh2P}HE{*|Ig&yJTu=P=bLmi3C%?o>=T z!8(XXVR~@_VMUG7CRd|?yjIA{UP_R5$2!*WRtJ1QV?9v0T_X>I#C*|6o; zWXrx!N%Mx*L~W_4Eca$ss3_0y+Odf%ykU@G5Mc!#7G8cK`6TiQtm!EmHnd1-kuPI$ zOHk@+Yt4E2h1N5oXk|UXLj#(2WHc(HW5@$6SwK4S{Q2T9C=!>iLh9-p^cnH|&RoVO z1LDrFkb*?`r9$O9F)p-?rYIO#?%G}~+qV`jMky-YFAa4ErKR!E zd?_y7C%%Hc63gB#7kgSw=^ol87kdxLoc5EgL`h$cB2m-`RxZW3&g{^#{#G?}C8 zq*wpunRStH|3CHq1~VQ^*|tH-%92XMwFG_2nvFO7f=GK8VEQ4yPcDn6aF> z5R&gbHEZ}J=kZsMjwSAHAuB$pJXK)6#I(%ClF?O`0#*f5m1!rDyFc19$sn>NY9m$pJmU>SXpryCWCxiSI4aGqBmH*KR>i$wJZj=492 z_3nO4>kl${s#F$c$(FXHr;ihO2nfq~mbg5`ob5Hw>k0V7F0<)upKYdwUu zX}=gU!Y<;|0-on;JXIJ+c!S`LQc{?0#v38dPHS5;-YUv1#>I)%c&eaG!IKBVv$RNw zQJ=N;oIGpA?52J3PN=K#==@cpQP;ntC#H2hiyLcm>LZj73KZ(V!vm&_wUAI`cD+l% zQm9yS39ppyzKAju)4G5}kTA-{p|G^>{!dc9;in|8XqR~Xt>$lj*={fOk3-ll!)(Rb|9zMqo=y9#7_ zf{>B35>sN7HFaz}DntF2RVCgac$V}k14}zpRr{3qOIpehy6p##_nXfsKRF~QE5}!xc%Iu`HjA+uFp4PhP9IWKmJ|Zr|0C* zZRMtJ+bgC(nd2SXy%L}8OCeyHPk2Pq*Cj>U^nI`NRKdb$wVo{wW6ia1Ej`8Zu*Zu57 zd&sP#wD;xikZC7`6evU(@3a?VFMXUd#rC#&NbPic{v5v3?qFgrf zR_7?6xeo%7t1Uby>$|B-@4XUF74}QX-XythVlThBn31BwO5Iml%yUy1ugh8QR)f;w z2Hh{W&evrZjujWyCC*w$I+*|Ko+|6Ok#M!1DmGYapf}iKSkpP*&z_@&J;+|`7oxFk zPnFQ*%hG%43n^uw>l@}iKYDpoCY9zOgfaQR;FS=5o&lf@RvRSm~2MkWiE{2?r)_ zN>3H?so<$XzZK-KoZhlw8yP~MFlOP0^OcT-u7)m!#$-%}m3AjQv(M``#~CN^g?wf$ z=6c38G}%WUsg-@(i%cmhC{}(unTzd4_EbShneFN}G90@!*7&4BX>%|eFPGV@HrcXu zyVTYe#kpZ)CU$NokKy=0@BNG;VQBh&#w3!?q)VX^} z*BgxeJTg0D8N&JU@Hp{E^QK$GldJC)b$;XoA)R(2>{5NE{@4GVG|3i7|>F>&!OXu}U!qd&@^~$ei zA-`bFvO@ej_XR$~XErsqD37~O_U*Y%4jsHh>gwuD_^(Wf>eoG0)*iIyx~IyGhy@lK zC)fbcfF3(NX^6824;4sBffBR{A=>53qjL7_fCQ$4;?7p$!Ucg~S(Q^DY{|iJ`$M0V zyuuw)zxBUJ)rMcyV}4y&z4D=l%A~c<3i-qNc&s=Dpl<|hK|QYIwjdBNW@p7KahF%- zvOKzg;=YL6G+}{sK`SjaC7xX)W0T42s&vyf0%P4ool1Z=2Nr)`HioORZqiE`Q^~@H zzi@w}!~wK98@dyrSk{tdwIeB#;a=$_E!?Jo?V$p(erR8j+;Ol(Hn-&)#*8@w!C@z} zTpF3%*=9H)ZkRU+{GWPmOdfw`RN60vbR5S`ejJ!JJ51MVU?*hfnXx=SaV8*7K09U# ziVphDPV~MOF!d;ddg63Ie)z(;spsU`fMGnShxb_vaG#PAx14DY&ewDN6qX#x_C`^_ zZG$P;r1s#@-Xb};r%-ln%{R(5);rcz=lpbndhN0p=ug%(*5Q9^e-d?%Cm!>?FtwDN~jUR_pgZQX~6z70I3*x({tH zl>6=|Gjw17VA$;AgF_LMe*nQO=Ro5h+*d5yHy6m>okb}^$JK#%u-=0(Hss>C*l86! zA)x=DQI-Q}J$MD^Ug#7IylN^&q@rZZ2=i}d5CV6(?YI!|E~&5e8NogM&foGSZ?a5$2M_yjed?AF`TNOo>t+IW`Ub*$w zTV>m}ZSuea4;Ue4 zY~5t74;x#^De09mr5_i=z4zWLU-`;c|Rx6 zu4Ra+&zI6z&awm!9Xe#%d();(^2twra=u^gzWZ+T_m%^<%<}hPQ*QT{I0k?Nx@cO#RF2m<-h1}eiPd118*yln$jGz zI8$)9z8*+l8nGmq(M=hnKNJ2ZXnEdDPldIFWF~4Q2c~2>w7Dh^M23ZSQCuBew???e z523ez>By7`>tdIek4(ss6G;JRI$n8w%2;>MrY4LF8)O2tg(4rgzj(p&$n8Zbp=DNr zeD|E(u_I63ulHG~>}|_6Oq{b|4bxcXQ|1bdyjz0deB&)bh#ah#P_B^deQ7NA+}3Yw zz$iMgnnUSTZ`u)OaS+R(7behQrfDr z7pP_8uW z_yZFb47~TDGTFa5S8{ZDOdy#*O!g4U`^$&|l>VYpvzNR;={)Cifvc zV{CMGh2_;(tmLk{_LNBf(5%@XZE!tn8v+aj>F1S+APzKh$T@Z(#_fVd(A8LKvDb1f z_X74`@coyA^3`Xi%sjqP!Ly;bBzz{qD+EbHqn2fGV=cLfENkXvBXy`;Gb~mO&y4pb zp<%j}!5p6?G-^_@lD$aynRTq=YLV?)_c&R{I#vQ}i?mjCXe6x5$Hv0O@)+xOfX6KR zJ(kdfH-e6woQlfiL`3RpylWr`PhO7#WpFrRXa|%z6cj2w{b6JMyc}ATJrp2RhR!&4 zYSQdS6H248C*91TEfKyWb0C>NVWgpJIgSF2<97Hrep{%$5t1S-udVh>rScBY z<*y!_ki%Mzot~1Xo*R*R7aojg84Gue>6U zKKiKq?9cwJeBc8gkh5pc%D#R3tm&|VDTP9VkYDh>;jl~jB#v3XF*l*h2z5L*p*&r5 z)_6sK;N7)Ke=m>r9v$wJa3~3hscWo4!Ljwiq`|MD-(sZ*yDXIePjKCQH6Soy)|e7STvsJz+A z_`=1J`C(~4_+rK{3PO~K@bQG*BDc^hN5@S;p@RHi0&nt>kSRSQQ^uQNE%EIi4x06i zXJE}k{<2y{JE6&F_nkX;nxyM|rtr+a_G`Z;ue|z-SyShcR!#bPaiu~fdtRYpC(?%n zEGvyISehELq_W(q2t}>)-Q2EhsaJm2E;}|Kk^{T%O)2|#-7TA2c1d$>o79vs?!CHp zwdk0vk;qK3K7(7b;$fK$JSo#-Pl;QONLk?pX{_m&ilU2Bly^xdREN%iaUG{qW)4&E zo><4thjpb2SegzqfLQG4wuEMZ$*9yB5mH zQxORSCL}&{$t)xkzc(2p69o)bD$B+SPQBisf3C*+VWl8$F@h+FQ|hg&&NT`O%3X(w zjknW6rLk^h!qjwBmgQu;uU&50TWAy+&a!cX&m`hz&P)dKWhzMQdCPj+1_{^~$Kt<} zM+K0062|V{J4$5Vt^(Py#V^}7=NUx=M2^W35?%e^8cWoJf`*U>w;wE$y*u+|`<6UY z4`HtG%(*JhB?k~T5_;?4zCzizyTH`5W2@hUSD>D&c^4;OT&RaOqpt0neOgz(2~CHh zh%vrxvtRB!RHVP<$?ok1rf(r$Xp3}@iIswoQBy|g6_>uAploe)%kTYWYQj`N|Aj)S zf_P9>;g+9!Z@JW!S|O@P+=}9RrKn7J8PSg@l@R=Qc3X3eb)H1yyfe9CGU0M($c!`A z&AyIFX=}D($_9c;Fb;>5zO#pdsF;Jp9E3)AxIE2D{TB766h&i~%sIc*qYP*~zM{ezOu2B)zv4h=`m zUdDJM2Nbz;D8r-K(%;`NU0q#g{L z!j-LheZah9?Lw$A9gIsTN}OiPBab#-o7ulsz`azt*r;@5JWAZ&ws33gnP&$inVTA1@FT>@okfD{Smpx@EkN_Fr)sE*ev@iF7 zHnF`ZZ&pC-lH&q-18vRU&hFs6_XzE6e$(;5U;1Pz117w>Nt%v87k-t!e{yoxcs64! zwsV{1%|vK9>a;w~vkaX`y^npnU%vm$uqm&fTG-(5t$>=^8hQHZr;P^&2m}J+^ZDe( z7hhDm&npE53wxPo0`v0Z*(sw8osG>&ZZ14>Oze>9@R6KDSSr77Mtpg>raw=eolY^z zS_mjqLcwYCm(tVOZoX5TC|BO;ZTFNLnl=>n>e}E@9@<(TP(n1;Ul|_Vp8b@=hhH-u z0$>07*X8q{|GX)9r_e6XJoAhc7N)k#g^rLhuw*>hrGMy+G1_5$#sHah9nXEs_{}Qt zLHvuE&RQOfLM1obtR?db6+K2%p-_RBrY#BMzM*M0W7)Ay#ueEVCU)wXz2PMtbsc+Yj*e7JFxD%XpaSwX%1Lt$f00fu{~<#+yFoB7<+ zGp3tXOcyDXC^?dyQrwcA<2JcR_`G4uPnl~n0mVvH%deTwcOEE~);hNl60;_^UwY%b zRanSCet}y$9SOwP5L{WhK}|+vYDyPqT@0snQwW4af)SU@#V+Ytvy$hHC?S>HkOxOd zVx=3pZZb=T16tuYm<~jZq9N11#BbBe5U{DNHNp{yzZpY>6EeqX37w9Cky-gaU+BHE ze6d%~T(~mEH8EiHYkt%#E`kTqV30?GvAy)-go9 z%o(Ggw6RKKbOZVw;v0|?W6Q=oBgCE3dU+m0K$N4*w1{+D0kaxlISz2=ZEnEAB1@)~ zNTD9Q8xXqV?SO({Er4=>1mXzvArPkn5XF`vjX4T|v=%^dYUe(&>me>F_28X>0<5OW zW6q;LAp&cwJ?2^HW5(gt2u1NO0TYutkAq?P&%cqXP#GDE$oUJC(%VN^t)P7Q@fP{| zQ*AObksR+RMBej2iR9+Q4YS5`+2dllV65<-5Std^={E0)0?Fh`(l%cx;XaC?p8lw5 zo1m_Z?|Da=@vp7rRY_K+ES`%QL@LEJ^%li?=j4@%at?O9FwL&!1k@&QZb=){8TVh>K=WSRw3FoqQ zij_?F;h1&&{KcUB?PJ}B?=W5`ap+K&@fg7i+@EJfRbbDDzGjV&>pA3S0GB#L^0jYU z`P`O|)Mvs|lYIidhx>16^vS`!MY3aSfzrq1g0sAnQLIoh0cFbhjzG%3#GZwn4x|)9 zoz0NVdja(I_Lv7TN3>pFa7r)UfpZkX{Q~vRruglpp-_-HYq1OzX zGBze)IRw$e;aHhv6>^{6Wdf9o2DQO*XHp3m1&iiQ}D@F33pt35j8Kbe(~W5Pq6e3Nj4Rf+jsVf*OL_Z{?n5qGB9Q>GMGE@L6L37}qt_qg5jmogiSN>ly9iWRI?UOg3%nAWjU zcwKR6YxEihWFb8N>ZG*m*uZtb?Kfw zps*9N(*{iqSjubLhT_`KgtH<{l^D;3EFE_A&tm<$81Ph~Us(eP(?@7C#vk?M=aB>s zYY;0rHe;Q+dNqmaQL5BxJuuOXw~*Gu=d3Ik8H?btJ>_gboUAlaJpxS#KbX_WX{#QX z9|XJ9!<>fzo6_Hc@HEzqiR8@9DL2?XarGwd8mTW$WI5Wqw-?yaiii zV&J<*A@SVH^{-1hIs%69q-@z*B+ouW!o0W%4Yp62R?ycMx*}0M zm{z9QPB8BTR-IKfKH0uo+q?xqhLybj*wIlLPFR5LK2UDXo6va@jl^Uu!2pw}e&?=Y z@#&a?5%=kMy65&{Gp0~H`Sbib|1ARr+w~oSbb5N)5bG2^qhvuzvQQx`fb$wGg;2C` z9e+s>NU}kov9Fq$j5y?@SqFUFsY+Wj1 zvo48hnbY6>xj9nr)qNpxzmbSXPV4=idof2YXub2#k>UAHw`WQFr7YRdXt~@kA6Bc` zYa?L1vEQ%`+H(fMi-}>c>kBzp5R|cR5>Ah{_j<~7E?1epTE{xp5++f7R-b-aPgK8- z8v}Nt`U+7RFU`IYn!#R68Ji@Yck(yTDG0<6jI!>o9$6+)Jz;VYm|I2Z_W93vh6Lrw z=SL)}v<*qjNi=DgwdImS>00*$Zb%X#TXlC8#FiO8KE2Dc-hCVK@Tj1zGJ*Om zA@iIB^qB*R5Mc0)Hw#=!&*vzQTw3gr&8_*$clgX0MBvUiq^+y8pEqvEliF&ZQCwkE z37zcDA+5O;Hg_>FW?5S42lx*oaMpVw-w22CR-Myv?lyEKNxkuGB~%-RkqmK4PPSj^ z`Z9Ara3d$GpP3EI@YsdKH=u2$wA?K_i}abZmDjJ3$lM0waRL1rp6r)zeB&GP;~&3d z&c=HikPsYTI0SzB1Mf6BZF6$m(s|(-dGbf+WO%~LZRjlY5o?19Ypne@|C{z3v=_1i z3Z6+Q%J|!U(aPEBR~|VK)pKXG@K?)3a8d?_+m*h3#*|AvrzIGVE?7>SeZib};>-({ zl12L*Pbb!lf_%KL<8ttbL}XM- zD%>fBb)ZK1<7zEsW!W+?bWSc@I4mcQKO>!89VS7#6E0mCPV1U=u;9lxHD%IV;i|fFqETx7t?-XO(S%6uD*AU zj7}8jS~;V0&B}q*RPB)uzqeihuRu`0_UpLV*t%8QOKId_&{{z2RkO^@Be(4*&I4LC(I-^3mH;d1Pm-}=C6J?3tXb; z=er*Kt3{P6AQHGFohN_Y2rU24mj|T1E210poU!mk>2$5Zg4LM_b2c&%lwECJ`S^$G z62FQP3Nbl+itQ!Gc;VpcO%4@kn?0=|Db7!BW*0gF@|mv;%Ty4nd#|)K`OM;Y1y(r< zCj;8{*}5V4uAER)!MHAh*;43Fz4>q=Nitx8Cy6=0GRG*B6xQ*D+d34{MS522&C|tO z369QQi|`?)Fhn8q`@&`0Lj8?Ftv_ajlnViG#529K5=~R&EC)p%?Z1i~-9#3?wr^-w z`lhe^9bp9oc#&@4MiCZBC3Z+)k22s&EIlY7YRF@OFdM~5eXSB%+HaEq1phEyb8_Z< zQ2P2K#_|baG{W4~;Br^kC_PYClosbm>jt0Jql7-fS?`=lW=^to6b!5l5H5JMfF7-X zF>CBPB}fS824hE(bAVR}<8X6Zo)W=IRA@c`aQkLh(Lfi)ZL;LODU0~{AE;FtN2BUJiJ*WghmiAGh%;>n8nPooBnP)qCV%n^1 zHPyM&rfsnrK!9Qe2f=gt=&*eGGuslsAXJ!@{(+E=0xYd`PHAmZ!8|$Io;;_#BqHy* zHyOY8xtAy9AAT@ttR$HW4ObcRZn-#iN{MV8e?cXdcQ(4@H$K_qcz#;RQnVJ9Y?Qkn z`77(9Rif*}Zz=(JTt4@uUis_Cdd;!I;#~RY$C}M&JX4-|$|C5_(|%Z~F< zxH@Mvat?zTOwMU%bL4WD%Pfi#DT&gvWCdG(|9gHhH^M zsLaK~kJi(SkLbujH!I-E%PGZ5O=Wo%3-pij=ahu$f^Y;ODHqELP5F!<@O**S3WQ%M zDu`7biN8&5Pk@#D^iFB4epFnHe|VY|EW`FA1yFYuCy#L>G5V?ZW06Aohh>pnYcOu< z30sWo$OVP55OeFyJfGWUrg~O_FL(OI2-luoMOW?JLp9aMAqc5$(iCzw@ttgUp^b-fp3S zjp8_@6TolShQ0ya0f5eO=9Ga(Sm)M&euF+&7>nmktuIx%&GZ{Tx0i3$K?YMj8C{={ zXa|rbv1kwZd@vp&+%(1^6y*HDdmA4gr@p>E(POdCjvYHB5(5AatD84((xF3#sHrJq zSA{nkLaCLodT3)y%g4*gLbZ|$6?AA=>!p-$>zdk}^b4avp5d$!o@kLm} z`_O<8C^k#}6WA<>$C&=2Loqy6)G8@;-TtA77)*hDo+_JxNYp^{5hG3bk~BJ-%3H?g zp%kr6P>J$!6TbZC)yl-YS|ye{kz#U%=L1$rz*dUM5feJv0&>A14(4L4tWn^4vI>FU z8x*+Vk%+ucuiGF>*Ujz_4GQ66Y= zeH8s@J)SBM#1Pg1M^#lIsb-qE>Bou*5(P3BYw=XUN;9k`guq)@&G*3y((q`MI=hsY z1@0R$kP&vu$+G3xM2s$9gC{^rV&$&K`v(d4aW5!tQ-U6QFcYE)s~17yBvV+`1!arx zJ>E!G=N?(n0b@B5dF$0>RDK{ z(lp;&ly3{f0oos)qrCbcHSKs<9k@m$;{giHz9mHEGcV1^HnYVfgbCU<#^j3^)OI}) za{mK$;>iN6#8U;y==bhZD`(JO1EHimD}Z;8_A)gQmgigvTH0Jff`g0=aTw^eHfi&0VL#&n@<1q~JnlV1}sL1kyQnoH! z@yS>U*#P5=!(PoYMZLVs5=tm0#8bsMMnfaeH!^Y7(e9vcU_8V3lBY@un+45N#XM)E zYInAxq6|iARX>1siqBYyi{CV?-D4$l4pw6c(L)OsJ}TtWqUNDIq4&^bgW)fI%vjPf~0(%!%CCQlVNKYvpbA`w`{Xo>u=iA0jBtLze< z2_Ey%tK_$c^2Ue$j|E`x>?W3Rq2FWsQh+QBSs%JFBdF6c%5dzk?`C@_l;wy}+|3UqPM_5UhG&+H_b=dG`+m;iVE2 zo!QGeGe`(|uiOUk7y2XgHJlQQAfRX9zL#rHn*p>%jClaYS-s&O$n{jgc%#T81a z6c#tcxUbYxZH~wOhkvNJY49Pm6~DNqJ;0Ng(b$HmnNDyo)evPUC)} z8pq;eM(2}+xi9yaD7TGKUEaXAF1l#Xt}svBN)bdoVDiI?eN1|}P+k@J>UedH0z%H< zNR;bb8G2{<{UT8ugcqC%N~rP#VTEcPo(t#;NURM&5CLhC`&_t=CPd-ydOTGCC?F6< zbFWiX2_<*2z_k`n6#xPXR*&U-PlW(71!J{#?`r{8FCkVlNE>@BO#k8286o5PEqKeR zuEp zA8J}4zQ6kSeGAFy0ln7=uv$+Q4TU^bw3SC7-0*u(Pk_2RRZbV2=h4R->CFrC(w>hU za$Wc^Y`fh<&fEoqMOP(qv6c>6=m9C!byeewGv`L#Rd8(AKnb15{yrUM{SD#tEt_Q+w zVP4e$nR5LeEBVLmyjaDq#X>$$6?inx&SOzToGMx7+`SWC6KYjGWRGWGni8YFTer9e z+x7JULIuf@m%`Ocb9DCADf#?v@>Hp2y|sOpllFCZxGk}6U@(%E+Zv48FTFlZJ6j#p z+U%rxUqtE!?GN+(d9E+W*}zVg^9tL*Ge7hV1?4?r!6@EOYm-BC8HCWCn2Hd{703l3 zTxxl2hWPg6b1A;Iftu^f>Byc;&c&_msWMBQ-9P5%G|}vwiS<+i>z^^!kJl#S!uEnT ztpRfunw-qelLP~I4HnK;?jUbPowT9$mPzuuLtF8$#H9{tW;Dzl0HVJJJFLFVF zc*b*KVJ39McCLSIp=Ts)puStGJ!7#`F=XM&`U#4v%=khcLvPo&BlJOh2f;BaQ6n<# zQ(yZC%?JWd51hu4ZX>xkdaz7nuW^?D3qdU+jpto}j760o;pS$X{JWXzYEyLT81y_W zCNR_a%X8dbm#&}P+-E-Wp8E7RzSo-Hr6WgA~p2+CfDMKCAG(1AJ^@q}1GB|$xIO{-}c7Oi-d2SP7I(_=| z!aP&*R9QPpo+@cH zC#bp7K%e|b-NG^ZSkQjsQh=;{%zN%CqlfM;U-%7)#Rn!b&pt9{rK(Dhe=7G!3k&KX zr!bLYCB0fZ`WKF7DqDf*`1AE4lPoi>C@Ofq2$@ z9m#XSO1qicKb}wA?$fs|o<4jZSZRWAgg6iC*}>PuDyX$U>x*HGGnAkQ@2*Jy!a~&) zlHkJ&NqNm_D}aL02AM!XsvzEQYds5BUM1Xs41Vr)AH{gwM4fJirwT}w@kuBw{Ql=d z^a<`ict;?M)LejhK+Op@TP5w-{doGwwZUX|)6B@X`I-Ux;nS0{4P$gmn_I?N0I#jL zCli+I&bw=~L`UQHfnR1~|l0PlKwYJ09ULO-%OR^zEs zc;XT-P97tmFryt}WgHYI+0Qm|F>NG&cSi8px_AfkcFTyHzEhZp4L2lQ}w%7*U z49^Dn7$ghtKuD;5`I=w!3ds3-=<6YuP=PFoc^~~=Una&QvakerH+ibqSZ9iJg=wB6 z7y?0VT)XL)_6Io~wi&0xEI~LB^0GIRUo{$9Cy z858xZ?-OXR3!$`mbD0No8Ou|Pt6cg5avnvZHg5MAFOcU$EsBB{#^iK4%g|Wh6yS4M zBn;f4-DRv}A_oQ{u~g7}=n%O*^|X8MY1)7APSywOX@2w;xvW+xP7A-Igo(m_AI(jU z(CNEBLS>bAQp&iWnrb>(N8xwR*F&z6@#zYRMtq_lOP-H_m30Pgccd2J%!=-$q7C4Y z3k_*#r}({4DL53a0;}~@!962mUg$*(T)Z; z_fc+tCI`0>*FteS+DW`+GEL>kn>SCE63+=RmK921w zmrr&`I4rb6onbt{qFCH^TPqeNnrL*~$m4>EcD5^966}x|^Oq{ScetskRxKt)F*zO* zB32I}QUU>~YmiuO7eXN78tS{v?j?t-f!~jd%+@Aycn*-=eUz-O6BLNl($Iv7u657Q z&HfR(aOGus>iK7>qkTX3M{oKHL=6oM3*-rad`YlhG&VLa%ro1~QzagcFPbCKXF+gm zHqniH*(#nY?;cWRouexZlG77_(Ipe@*Ti^f>hy0qrL4|F_9VMZ}x?SRH@?Kk-J9&CfwIA1qdFLxryp~ z2O|YZ71V+L{0P$q5&&iC{=K$Ff%gT)3ipe8$Mqq!WAcTe8LR2n3xwi=@Gs>fPL6`Tt~>W2 zLK5LRNFVr!Gbp{U}j5D(nA$sDG zOcKhe8J-uouHm*EW?>U07K>8K1aB7g+?Y)7I5@=bU)32B-#zyx3rO5xVd&osQU!IX zkt!Z*l0NuoHID}=o-?@acy5sSfq#?2FKzFkpH3gScK9Y=pxK!T`p%D(w~43RCLSRg zsRE;R=e2q64@l@|qWd1GWuY$9R;H#R3#7}j!7AG z4(xQ0%TdMer&g4i5=tm0pg6l+lT_)6P?Y6x%sW7dR4L(hVI`!BA8nGyP(2_=VB6}5 zl~u}Ss~6>p2HZMCNyrkKOo@I9nF8{>$ff)lgbETAi=4;uY9ZtjDhL$@4Yuv53fLsEh9Ype*VFQ0LI`@jhViywM$ycL1+=Y(s7x)N=-S zZ}}UMv{No>p%lMu{tsc95A0zbquELAEl%;mfWZ~|BJ`-yaYd@Qo!f_02?Qhb=0)Z8 ztp_|-%Do6zy{MBei7Zlu{|NcSGMQG*2wzu72ZL=2i@Yor7^+#`wkxAL0GSS6A~tJ4 z`V!vDt?nQl*^3ZKs&1n(hvfT!J*B0kg^x$5ym=ZMyu#-+L!JVIsO3T_u>a#_wv z$gu(Lcm9BhugCJ9Gs5E)&Yq&fJL;*u(M5+l%(SP~MJ}6zcDH!wP)9i{eXL96$r-b^ z(LpEnms4AVmyh)nksB&XxGq9F`nt~E5+}@H>=K7EK;GDRw*?I7e9 zY@3jM_^r?(?t_riO}17_SU*S>=K9MB3vm%Z}(4844I zf?j=njP+m#J^JX+Q+4Zy$X#(iedTLkp~?9u1-UO^k1tu=6GcFTy(kf#u`(5se{<6 z%OhrT3ae+7Q5B(V;1-M(RT0)Zu;K?z3|>nR7GOj~n_Ca50z#pU1w;@QxDMJIu7kRT zAOyh!ZB380kSadDPD3p`RIL0t&c9(56ALbUuBn;0{6!v&01ILG4gCpi8%hrpc=U1Y z+^Yo+5t52O4D<)M-BDDDp{!{YX6 zvqZ>D*{juYTP}Nyw<`~wa#v7f zJ)lIYlyJMS9H|1sKMdIUupF_1Rp}XIkGD$#yQX(XpFo)8fUIy&iZM`|!(ouay}__9 zhCvoDApd2Kfn3aeiMMIvz5W=;(b!(-7|6jQPjKJV7vM6v%$iCoorIaT4AW-Z#8bv_)|+!Xiu;Y#xx^ zAje^G1j2MFpkDLWtsZEz@Ib+8eaM3d=Z0-_b1IZ}W4)8c#-rS}lo47ZRnXSl4m)30 zU2m(CD%WoIrN3pvTc(JO6@#l(NEP(IboHX&2&s~WiQ6mc4*HqaXEdO0Z}tR5M+T9B z{)fH<89N?JvRnsUl26TtUApF@Bo7~VpD5??MAfZEssJ@LDm2pk>^KE|lT=yVz~_ka zxmh;%R#7PEr>553RM)(ZtgM?*Do*n=uh8%OVHfWUU6IEN3i3NtVW+U@>xl^)pz4Ox zw0rMfy4CeIP0U5IEDB}ZzVA6wPP>|1w6oDk(O@~bEKYLUT;#O6xIPhn*v8dsmr`zb zQ-#w*^%Z5bv#F9QTpsbp+1q9%huKWiKGylTBJ+_d2EH;vf zQTDgF>Ci3@U&Bc?6_s?W2VuprII}pU%E`kbm8r*bpGO7bot6F^up^;^XKQNzwaD%G~S>@tcUfw88Vog zWxT<=K|cfV7i5da<6%9zToTpeujKEX%jlEuL{cSpe#G-&+(CUTMXI1~K&)uFJeLB_ zgLa4WR#g?&t+x`X^3InURxxiaiS&8&3KtSb$9cera*0LJ`O_t$6~vd1>Hfy4`^NJ; zch6V*CzOkc#W80Sr9C+rWSd z;5Vl|Tfor+#%wK7B1%((BP-_UQozKryWJ^C+oStej% zFgyQCF`&OgD0YZF8$kO@FGxTvc8u%jv&900F&O1lds7~9xVBuUcvU7z3vo_dClJE9 zl`@QWtgR>yMOcXEXAOp-++d&ek4b2^qPX$3+~qdAUr!?6V#q zSv>&a>~_ryEseH?wgEsv8yQn$AI74(8jHN!e1LKXB?Cn>3Kf@7Ss98uLTqoCObBO~ zUFVCj`Wma}ISwQ=a;h~qDq=ogySVG<7&X@^!V3cORuPg*D4~QBHWLFwAt4};ZveSG zZ}qCMi6H(oK$ZaU0wO{W%)OAO6jm`_>vo-#2(=f`53p^=b~HMqAK{v8X@ z!eQ2T#v|gzjl~97ZLF>4#xeK}GSSFrBE}1o@DkP=V(~{$sGUy4FrdPFIq5nOObrG@!j8T=S`;UOI8uOAp>v#qyR- zEudmq`pCgDI(@91?mAgPCy#i=4x;I}>J{LBh2KRkpwj@5U2zR9?3dkc6L}fHqMKaV zcHSSN*WT`;m(E?|HoCkW<#u8zdpM#gED5bTS5d9VU57peZzJ@bTwq*4*y_>osMsj5 zcn_s-C_=BjHB09&&C^R~;T4`*@nW>*)()28-Q;k3=*)djP*rt3H8gj~-&~-*ban+* z&QOC2jrGQbIXcVNe(q%z#u$L{xvadB&fN1b-EsFrw0GZrzPC<#@s&3UmaeWI+O>Nh z9Y6CvYTEhn^qCgp1h?;#T=sTUQaIL5k@!w2Cd&b;DnCk%)yEf#({-2(<^wbv*hA;8 zG)d_j*+WC)hbS6vO`mZwu!uSoiqhO{P{ttS{aC8(-R+h>g>v*zJJr`OAIWAl*uTf6 zu2pGeof<@sO~%DSx>-ILO;&1X+b`t7!w)~aVEo5l?fac~-boczwN%~ECchN|#%=wz zL8gPaMR@96Z7$I%S$mcoLi;=1?Sgl9qWU5}84}g^4g@JQAEC$ZE~ig^w1Gw^ zA@pH|GD3bKX9`@_z>ccV=xE9~ps~Vg+j~F!2efnd{pmC3$L#3$Xrli!Vp#gqzaJBU z6~e|N_ubx=u)Y9Xud$jPM8;yH2PSTW_rOZ=yeM*OgAo|UY&`lIY3j5neIJY zh{0u{q%TTu-B1G?$O8cF>iJh8j2P*T<7zNh*L7rF*B40AfB)JzIZP?~(8CpyRA0kC zJU>h4ZboQNEz!q6n29+FPoMwxr7^PcF^}KtrH=N@y*>Nt9KCXtUqBlAMD@x*y3!S% zMQ#)ug#JO5#0~DNFxv0!a4rxGHg12{x&ji`2=5(=2o#m|B&vtNi+6kSs7Km42s&H` z3F!L``9?mc&S`J4u6^Db`l z=sy>)1b9CK)l^&8l@K06KJEb?G($IM=)e7^-C}IlFgV6_KW65>!u^TcmBW^z`idyE z)n`w%KY3w_{{AO^a=6S?Ut^VUW#|VR4R|MAy6TseGyONF=|^8YD%&q!3yXq+@gd3e ztMY2`d$hRe=YHj@WV2^H!d8pxuRI}t|K%U{(sWqm+1b0xDbKvwSSoq_vdW_l+IUtR zLS<#|eJ!m6h8YO;;DUD5pzo@-pG+C)+1Fd-^L7JPRUPOE(7v77D-bX)ym>uD!MLia z-R+rhlIy`N_Zh@g1|W<7_OB>K^4yK1G&WN!3JS2B|U+81&NR99I=o-HM+FJUuLC{exUp@P`^kY7}oWvuLv^SGFlxloJo4~Rj$(IIl0 z2I#7*vO{DJ6{2HmDk|Ql9Xp&Ni$O0!4vlbF<-KTZunW0?u^YP2zz{-1sZc^V2Kpc5 z-OifVsM^Z z6ed(M!0$^fyn?3&07EpwVFG1*UOk`!VqmWgnjg}>k(p$;GqqRhc~ z$H(4#vYdA9Q1AZD3$rxki;0}LgP-}p-ps1y=U$znU^F2Fgv*+J4*}keW88dikli&P zu{4eW>T0k6Ci^%LT%+S*);FS5QDLUzhauy$KHv|N)oSK;XQ5Z$oZDyuzx5hV=m-GTpRBq6pE4E&T_uRNU!m=y{zM)4GfQ3 zX<{l{*MVonJ$D#*dr;(G)Xj(PtD=2-R4#*SU4DAv9XZ~@CDs?PE6wutr#T3J)>mMGnsj zBp?6PpK0PcR`QoGSV`CWPRnN)m4U&Y%XHzj?}%qgE*wrbJ^22ALhiCkN+m;-3jPKC zk1zI9|9D93d>YU%pc6fG+)E#MqEWU@ME)`FW2KX))b)U0`uR^%*NyAxZ;P>e&tCew zFMc`wjp)W3zeqoLX`G)cbFq#VC!IO0LdPKl*;l?-EuUd5udG~MW9Y}r;f_P))Xw8K0B@kre144j`}=v^El#5PU;dPV-n=%;@16V6 zIFBib32JIIaUCRuh|_>~{u`fYlKvM-w$p6%eL@%U$fd!OUXsxwjc*9{{fi8d? ztym1)P;2M@q86lM47k#1rJjEE4y{&Q!^s1)DMe>aVSY+)V6^f$dTM_rw@GdLf1>tw zgb&XE&oDeZK#_2OW@bkz6peEKt>-QY`<_p{R7{pCN*Y$D+ks@zh=zQL>OoMPI(3Ts zfa;@LJyAXG*Y8(-9iHDPXrH-dc6OHM6V=Z^Fag*X!0*uQCMG5p<+jO(si`R%8ygeS zP8)afVJju7-~6S#n}wzO->QMh2A$l*1J9KkemT9zWsuIl;E57d-YDub{=#zwiLKIw z2V1zZ{rJ1T%M;nst1SF8ugNp?4`)^)=>_TA1w1oWAj4RUm8bdwgFD>!Hj7XJoGdrz zBUAtjS642fQY>KL2B88#FoC;buEz?Jk#+Zn=!LU0>8qSPNNu@ zuXF}vEWvdyUiPyfuN2r^LS?N0frv2%*9nIao*_nWU-45{H(c?R0`wL?AC%*0Bud@A zAv*WAUld{_gTwLb0YVBv(1KTv-Rqz~`pfI*q2h^5OyUwsSPL*VnoY>hq!tPkvkjL}La_n)0CGG$ zMIgVxSbfLwaxpsJb*e&)q{wrDurnG&#?Y4jFJKkzJZIOrxtJI`_jO=_BP%+5E%8>^ zUnb)=WIjYBfDt^INC=4ny$>Fzdv?0ycO2ue8|cUZj~s*5#U1S~F_6b&aWN3@Y<2Q6 z2rcWB@KFez4a3`sBVLgw;OPP&V=}Use z5^Oi}GwQboSl;vTdknK)HWx|I6hFf#*DLklj@qIvdh5U+zfmWM!p*^9F7Cc4_ zCUQ7!d}g$Pw6T|uS<8@$_66fTY#PvEFL%z%A~KK1CbIOkw2cMt7r5sR3w`tnLsoh3 zg9u3mL!H_O#L^3I&e1o1Fe>HMw`LYdrD;AlbSM~aXZSq?#ipW2uAy-(eo9K2^~Gpp zO35EL`Xl`Q)OM5`eE}h-An)V8D!jz~GDdfvjAoUl`jq^Ra^ygaTAPqR1u_r3?^AT= zaRaw^s}$6O5N=%mD1|()K-ziux@BBnTB+bZRmbN*!L_t{(13A5@7ab0cZh<4{s~VM z^h>;V*lVy2eO-SJco1Om9Lm&mg!R4bJ_O_=RDj&=I0weAdLAc`hZF_jrXkzIlR490 z^FM!ca}&Myz3&yn>U-Yv9x>`a`skzLC2{7=88KSx;dGe!*^CSItF^bHVTm@6_6q|) z>`x%5K@x+2)NC{OjsiUq-(P-xmfP#Nlpj5FT@22}#EY-Zu+PO{JF&04oQ>DBN`Ed&ux68=;sdlWD`dT~HRNEE`2n-nfwSrJxAk?a= zYN??SUMP3c$z%6ZTk9TbZSA1Sn&VX6@Cc9Z?IKIA2H0Oa=A97I81EY)xKI$z4Bk5U zi|_E-0daz`W*}a=y1MAqS6`*GXV21Wuf0ZZz4aDdzI<6o66^yKq_eYA%7qIT=%trl zqRGjOx7v2bJ2R)s>e~K_z}-U_Ri0a^zsE=Ke^0GUuKhzHZcOkZN#{;k_zOXo1sk5z z;0Xri8gdE>$d}>4tJJaYe(vOpndn$#oF@A|E1$pr>@d0&eomFG4ZLHl_R*BCvGEuU4oAd*jQGz|=PV>@57l;I0hv?GZ#Pz%qIw*zwD!b^#{G=tU_oA7R0!*V%5uL z0r!u&0d#C9{hemwF_NVYFyKjs6ja&0ac8@Wl z&UL}Sf_os^x4SrA1ZzRQ94i=~X6IQkOOI76DIkjUSR0|Td|O<5Yh`6Ks6wKkZ#Gq# zXlFXlSv+B&m(OipyDKI@WZc;ip~}W=`2rqD=R1QGORA2ia;mH!@aob+0IFCTZegc1q?O5DJ}2u)8+7RaU>=#)NfB_csCB`clph`Ja zO4uyq%c%k)0fsn)(}MiGZ#QDNBRW7#6FL3>J?-#(@#r&Ci879i$8l z@z9U3KO#6FhsWr6M2>;Z1l>5oy0Oh_7I_-;EDXMQZvBdTJ>aFHm#bGpsH_y2r!Zfw z6nGZsWti7s$cAj>;QNBNjgpsb@?M)899hqWkZ2m9f9e-eYLOMz3driYdG%oLo12fx z0zk;B)s+bMg}E8IdX&Kv-uGx%u**ckAcH^_n5B)(rr#@|U#Y)R;QAm3VJAV@H-vf{ zxz)bX4;&3f`6J^S(-6yfK>;xe=+6kJ0MKnB{?WS2ZTKrnHFQe>jW zMwP<_80_z*uYTn#bmYhpy6?XGc0 zI4smuXA`|T8Z*+B8|r#kJ-<{Ah zd`6oM@i-Udfp6N6HXEhMnIO$hsdrPXoGKCH9N%w}%G?GnAg<$be`pg}=&g-yAnr~b zD&zK&$*F?6t#4?M-+}-CAN~QIIB|l$`OR7KE&5INj+e^gr10bMxxyCykO?B2jhN2oq^ih zR$g+Eo2VYoV=)CN*&j@KG5HEjqg_<|-{oJ)k|?N`d`bTeHK( zy%Tb(=}kkK^&X29PiC zcEP!|Tu%9b@L*ddTy*v<`%b{pbHy6L11Aqa&h)@(>({X#*~?QMw- zc_(YZYHnopH*L2WsEvgKC?A-#RswjKU{cW+y~}Fuec(6!zPW%aG72Urv_%N2C{SKh zf<^@-KF5R#OtZj_*vT5OFMu&huaH0((2jwk1c6PvUakxD%CP!6zMasB2q~BjFQpoynKvsZ4jJbXHP6r)5 zkhbW#9Y&5jD+3DEfGTPDV5M>uiuPDE1qtR@EFZaJT0Gp^xQNHzw)tQc)`s?uEz?XAFEbU^w=mu zrG%}C%UzYC9G6f+F;QJzEeakPR~O==gc3FrnExP)%V(YnHPU3>7bAnwB)`MBEHhj& zrnv&=fE)-t13D)biGWzQremrE!wK;shFu9!8E_JWiUOeb!WfQRqcPTptu}QGwrjF; zf`uRC2*oig$H`J!<#B;s=f-WEw|zDSJCy zuIocX{15gt*(=;g$lDtq{#-AB={~*qKa3X|(%1jf@P_lTSV=+ferazJn0J-@cwMnjGwu?RrStr5YcDP&(T|N&r5_J%P?!NnOng6#twxFj93m-YG?~1V@ZC9NXtJe@C7RF=) z4-j3~=jpyXD7C52e`T=;Lwz|Ul0f!K(o%V3}_G&eg!eSPPt zp>aRCTq*_~yi~@zRcM%JUY?>Wy-_ic!??M3*X>)0yk>0hcmiPuCBHz06$Q!kZCmVH6%q4(%eP$ zWq<|Ta3cGf06bM@=S-|bSfor%TX@or(A8U^g#vGsNJ51v>K~4fi-qSoe&(lMnxpaA zIK{ZlLW$}hjgixBq0#9C{rLH5zMeW}Xe>&0r-gi>6#e9tIl9@OpbJ->3)ciz?y0iD z4Pyf^J{c25b8bE%t6T3lUM30&1OkL!f+C95CzwN_K%s4{$5UnAmylI8cc1pkbwmiR zwuq7nVIMLYw&{WEuGUip=Zf<=@4u^D?gQi?NDe#)6jP9Ecbq5_H*JKpf-nfrGzjWA z4+KVUnMuyQR^U+FH|`DBEAv_@Wj52$KDLg?sNnD*~-NEkA_(~)tt3J1b0{$hUMi9lBUUBC96 z)LTv6E*3nOU+p(~^N%SS8W8vK?>;|I29rvX2W4JUa&ITl{?KlV0ko}LPnNAvpfCX# z`t8Of_3^me#qXoLKSCpuY98NifTv2r5TU`bd3hGC-0BO`On~JQZnNm!m}^0%>kGy` z{KJ^A(lG!^7Ul=I=pzik!FC(Hda;t`{3coHWV0r@?;yT>$y23-wF8PjRsy13dficK zt)HPup1&bzG-GUCjeYq@6$OA*=>QgxL4L>kfu}iu^EcEv zxDMs(k^r%S`of|fjOCECa~ruv9^kpO2oI3YbM<`aL)z+n0H2|k!OH{hb6H>)t>mDB z`%M$K^?ZPB=|*p0k*A8@gCHN^F@z9i8qjvoZy-Nw_FTwmdXE*<6`tE-^@zQ~#?3-` zk;%^mpntI3vOer;v{PflVo#M+lI2VPB>mZ+|0Q)^yC%kaEWE+$_3rL&36+HqL-AOI z9)ItHWHcjhsFB`!?aMSiiy(LzIJizu9`=e(z0sa3827NS7R6}fw#jW7bq-HM5M+=& zswxnY%1V8GVe&eyR8eLnQ_4isQ>s3T<*8Cp9%1<%5p&07};PVP-SkASRCB_mu{Dgp<_9S}|!yV0*;GeY;m;&jXxm_snmOiY?YomEs@ zZ5OSv;8xtFxH}YgcL-M83WXMz;10z#xI+sBhvHh?o#O6L-2LSH&l%&~=4NLk`^{dN zYtCmL%B6vS{Za))i<|8V>D=-EHm?jMBg=}MIaINd?WZ))p(opPu1WhsUp;#%x`T(+ z#m1ma?0J=^68(8vKOvm;czP@6uuKcNln0d5y&|tHl&8#l^qlwBbb44;*ROyNvZQ)h zAVEy}=Lw`OO|~nMTNzY}W5iOMWwrX`1t$-pL-u>^bt3Hz#lY!LQ7uf@he1rVXiOr8 zw{GqJK@fQX<8jL%k`QW8%34x(7N9;X6BsThb<d zPGq9EnBf+_lf>-j+#vLqJ`_A9%H3j8%dp%Qc{r+$+*UcrFvtWhZHCuMrpp;$R7yXr z)z31Wi*|pf@4I5fgKl#`zQxU`W)*+#Zxfg`Txtpdp{PkC)QY9Z10rYL+5q;`mU5N9 zQjkq=cRt+~z2648&&6F5obn2sMwBR1VKR~3=`o;L`piuqm}zuJxYN}W*kiP)2GFDP zdr-}BWsNp~<-0kBHp8n-N0Bd<)vr2c20mV)vZ{$+Dewe1iM-by*vv2pz~2BydTf1; zPSO81!heG6Grk-o^PU_yXFqF1J!1{wAur1zuf2HMUU1*u<{mhU4FrFU9z%QF%=6cg z3V`i;Kj^^Yg1qMcBVW!#S@IMPYJun%qdqO`vXWdlGfVJtXC-k9_2Q@$D!n$3!)RH@ z;m<~zh33(D@sK>^hPvGv$ksQ#Ux8Dm)$@ghvJB3WEMeQr&5l{B0j#^+(W?kHiQWY^ zuZLM(DyBBg6%t}hN#5?TE8zRqTlmfsuFF5ikl!3k!93zz5l(RRU$H*Pst5cS7@+xB zBKIIbw6Rqg+i$8@{oJn*E_0X=+hCc{PJwb%Fv+058j2)xhqM(WOAW#tD%bzP%S)2# zg)n%75h{b(*8oHGDv@sspt#SHEv>);!B^m3h-9jSf+`dvRVsJAh8886U8PN=a%2Tk zfUul%dr8ct!iVh%d22=o36`?=?q%5sLrrjxB<>L#WSF}+nkE7;ILg&cCguqP4Nm^; zp4e=BIteG>g&C!wOCz*^pA53R6<{Fj1-S=2c1D6Tmnkcr?*iegqaeWidAXTwTg*k1 zRSTexQoD`y846&{*Qf11$2PIhM~D&9?EAajBeW%iMsQL4ZGxLy>v2>90{v$yidfkS6q+qT_~C5T^V1~ZT5%sEb%TjHzS24ozV2+Fh!K5X%WE0fC_^BHti z@Z#u);#VuVQukUOdPGbn(Whe#56a4)KgOz{YsrFT^~QE9d6U~#e`^c{hgpZXprelE zU+^klBUY@GhYcMrlw#ri*1@|WKdehSk32{6^RgR}>F~QSQ`Q=+Vw|6&CBRQ(k+rn^ zkqs*>W3lx)Fl{jDIbLsOg1#gLiQ%6`JQ*v-Sb|AOD@UmNi$%UB=$TH_4l(dhij|I z-LKY;>vlUxmG@Ag!&11Ln8t!XFNLfSpU^f0-m*-QY$7 z{e8ALrG{KTY#G;@w%AKpFppGe1%A>B@r37eZa%PV$lGKLWGD& zVv%7rkuxIz=*dI&a4KqprA2GhR)Y`4t!l=6BKtUQmr<0`;R)2xpzeA5m zJQ|tIDSFBqKjL)z?TE0c@@HlT59UPLm8UGsv?ztcZ6OV31iES(#Nj72ZG6Xj-9BZhz>~${<@r#k{rv6bC;;N}tKEaT zXD6C_kuBym9jk61_14gS#T-((qG;k6OT>c1B_8HWIBeOqiX7YXOIC5M;b9HqEnuy6;Q}}(-n$MHmEvl@PQ#H|$u zfZS8%yc}T7^d+8qqr5`VGHjz0H5ue{|HtXLx@m&i*eSwy1dd#8=&s^E+nRP54#r5tf|qy%*>{`9!;WL=8$L!#}7G zy0N3e1Ua=Vg+GdxTF%J%`oDqA=t7my-g8M)-7FJD_0%Ti2yavmD~8fg)G0Bl^YRoq zr0Nyk&?`!-EsalZE@LL%UrPq|ICQmW1i~m5DF^Z4df2HKkgO^@XfL{OQ3s-8x$;3pdFVrO$Plq9)byFPuza zAOm?m*3VzCPhJjc)VqjMT^aW@g5F7F{0Yo`2ertNJY2>T+zx@+cT{U$#lg#@^V zusWOs#5@nR)UEnI!dzJm#*rU6${bAQrGma$5L@I-1Gy! zEAnFk4+s7oa7##?h1u@ef?77DQRt73#IMlpKplZkgG#8n!4fs$`I*%cRN)d;NS&5^ z8T(6tJ7M{=e;kx*FJNJ5+x{(?mqc+V(+&(mR7EwaHFlkt8I>7JODA;bNe)&ze^aD5T+vzq0k|(=+_3gqP44H%PF;CE_*Fh zCNMUXZmc@P?##MC8;)dIUyS5H{~2kiV(}an8njn0goz%p~(mPAa$to)RmYhJ{rx z;f+7ctpt*k0$w>Bw>lxQbT9+-6}-K7Qd2{gG4A?&Q8Kqp zh$5_dwMhq;7ugY)D7C--%ZXQzKZ@v>fLv3<2f@w=Yg3FAno7hZiosOwvPjwGCO=fd5^CSj4uZ0(qi*Qivdw;dbXwMu# zqGuApEd)_DXcTth5pP%6r%>j%hU3mH)+AGWvMhN%clxpFUnJjv-(F}0&FW*O>Ro0X z{(kY#*Iv+Fc@$-N#XBcO6S<`zY~oodgNi{ zvXggz*+*;?MFH@E=p<_9T(Y6BSI!D-{N#h$Oqd=54;GY4}e*4 z@3p|;2;b);Me=E{3YH*!vGSQv9)n`JyYM}kywN;C}08ijg z(1_pdU$E5Y)Ft5Xv)P#RaLQkHf{*kk=S{^R+S5!urD1Klwvbd2ov6^55~WZ? zL}?N1su^u-=`*7ow=!*Mrx0P@^aTYfxdHtc|L6BbCJL7BaabCR7(;zzMYJr9W6rrv zabLdTAuENe4TOfdLaUg(`c8z`Lw7I&Wiq91^J-k*=t<9ad(D=i0GcpS9qw}Mxw}g3 z^Yr{Jl5*7_Q7W3{{hY{OS=bYIkhq|tQNx-D=9=f1OC{yqe3;f&>6_SteL@_Qq7JD| zJNw3KuleF~*eIeN!%DpLQhWP^2>9fI)USBf+R8_VBlVs%ax%%A*?Y!j7=bJauZTx9bhtGXf#V7t%RgRa#`YS`R_5uFQi=jFQ#bA#H1S4qLa6tgcOOj6@P2s?dliLj3D)AXoEd^3ksI+{Np& zyMCU!Gqt^8MZUg!!-+Q~=yf7Gx}HbY|A}a;Cr!CzB^mj4&r`jrclwHsW`6A%?gFg( zA*+}M-+r!}+snF#g^^)mouqO>ATd82Q2ac~`oj%jq0A@An+Vb-I2YDs4rJVMkC3oH z_jyQHe!!C-%JNcS%t&HQkhf#my&kJN*ykK;y6>C*Kk4Q)$-nb1ko`bgBpH?xz` zh>0u|)GWKhGvRfP4VF>+((LH9{lcXs18OOWxW&_QQ(J9Q(=I2Y{|@Ub_`kz?lz2V^ zHk=hvpe`9<7S-XmBGY9sKAXc1-ZTh|WbO|EezeZ74)FQ0Y?w1QV_Tx+7`04_3mmvY zvpBS*3KEFw%`^kVGT?cJem*JuU4p-%1K&DNnm_sS%IU67PZ(-RB-qegw}MD|W%4(; zM?ec*9XyVxEBuEM%LRaor`s?G{CspFhQ-I<45|YbBjsY0N9B*@^8$&E<}_)6dShL> zyi@`G{iM`oY$_1p6*7x-Bqx#f4>d_d(B02lGdlt&h?A-d`&cn6hOZw{2F5?6CNvnF zuUz?gojq`i)Ez4fnMGTJ@&`|BI}LU^Cp*=@G(==hC^6#Cv1kJXS@A|oOXHmg%~=(M zhu<1U!C6Ci1^jcn^%Q3>+0yH^>-CWR3DM6YI}F2!fkJ)coC?Y%c4BoI2~>eyf;-1X zz5oq`3uXPD#F>jy=@XXElgw!u`F69)GV4}3D_;^1zD&0$-WMXMVSY5eWC^{BxyJ7aXzhgy>w*p5^zpsv%7J(OYkdUn_#5U06EzUV!s<{wixlZ zZC)Oa@|4eQqri9gI^6c$>B1nq%#w3KzRlrz-kx2&7YsM=B78jiYWd+1VILB_W()Sq0nIoG7r(_K_F%kY~HjDf8pku zePE6qlRDUFwYf}6%HucTSq!K#$o#M7zDklMAeTAa#|-Tc56yZtmI*}{+wR?5^1=!DzCIH!7(E~;sU)gO znsZ$-m)YE0dFoGb_VojA*f`s(8rJKQO#F?ElON z)R8OV#}Hb6?T1x)&h<#crc&@f{7pJ^qKQivN^juajr+lBdYK#k^n@`x6a!_7PfIot zW(n6M1|S0BG0P@Zub$CB^dj(h^fbanbl*J+q$Xw`&;U7oXG`RQNn4ml9W=yf_LCJW z4%Pp|jE8K9^D7Gc8ClD_^a=PKIh3fK2o?4=lr{n6NMv}^hbp4No3`k?Fm1`C1qck( z{-Gb_q<<&`Ez*W3?b`BkCR=B?s@X-oIQKA`y;mJln&_BppwIZG&GEC6TJnv`f$S=dRtjlH!OmJ_ff}8Be*@5 zcJ;C}exzN;s@6$VPe8*@np7~GVo7&)iaO6cy^eTdL{N^w08zQAe16@PJs||wRbX?! zcGiwx%lN0x%`~(Bfxm;gqC?tZTsFZYFU4UrvTL~C6@LA&0u3%b2~k}Xm%C`OlA#~| zcvzgqdrd_6V29BNVH5{Ui*MAu(kP2Bv5d0h#`Mx{RFrQqDuMBza@cii*uNWu$;|Yq zPue(MW(7At(E>1K9@5k0)L2z3^4a;k{EBjGv1=Ys+)1S-hTRxNFd8TvMk%6c2`1Sn zA~JlBL`c1XZEV2)L3|m5$wsf#YvdnRVU1sHq`r zQ5cx_8$}sOpyChwq0>zCD)WY0_=^2>)N0g)1}!M=fc`^W_R7TSHn*tsoWPLxk4c4s z1Wg5e86-(RxGDLm5{+L6mTn!wRE=3bq11xs+9Gk~^^vy6{?kGbBr;~7yEC9IX3)FG ziVm=g@&-qzMb}0LO&1?qwIwq*3BD{;&*IIOSj%bLyjvu|F|HjG1Jum={>j#&;NrsH^J#_u z&v$#-7X3H5M#~2d##d2RH`pJlkKH-=7G#4Xh`)uQOW;+Z4-5pjs41)}s7P5cH(P_K zSaLKwTu*K1>Z3|172fi}-lEtz@KQvf{t224@hOpsl&+JE8xg4XKifGmowMd~zR)DT zcWWpd<393Bz-%>pqWZ!TbRHC5tp*afsN(AL9pX0Axan767a<)}Znf~LH|*U_BC)*? zP6=agJ&%e{v*M$Eqnk1<34M_;Z1!cND$kPm{0D;s1l=&!d0Z5aX9`(23M~sK#kT_%@2m-vj1oPLu`k2|3uvs2(+nRG zk7_kxys&84@^2T%>3~u2L~l<>v*#TW57n>F_tzp{^Dh$}NY1>XgC)hog2k3Q&Oc$? zZKU{>Lr%&X_ZW46Wf!Ity?J$S*d>G;nFR%k&7VlEH0QiIQ!(EGtFEOnYUGtv_5ICe z-B^h8&!D4Q1EBy{wHqiDul8+H#Dv4rk$>}NUUBuiQw;k(?c?V!Pg9o6R?~L*SR1$9 zwfuG7>l_1LLr;eR=paX<2OcF_9xthaS&S>Az_;cPfpL`q^xz87jfTIo16p3vL0e1M zF7|?pV{#Cyj-sjH7C{HS7V{AaqM$?laV`=HQ606Cxbl0ReV-q`uKuVIzE*q@&5kn7 zlw+fg-n_boWsn)U>E=3vW@C1T4Oqy9+H5_?df{ltwZSQrc{v;DmmBuj(Kh+<6+xmc z3#*^0a5k;{!Qh`Ru1;!}t$KufV{F``!MYAwf7R_XQ>sD~yOBY`J)CxQ5!YQ1wgguO z&P+h<4|wWEYvCr*Pm~@09;sq43Ty^mtEh-_uTSF|8uTrGy2?-9I0uL*0_9kMmq3 zK7HM-K|y=o;8APAm%}53@$u?*%Jz3I2c(JqgD`pQT%CAdA>PbrUCK=%|4W;9z=BSM z@1TCc2bu^>@}%$3pGu}5xG>a}N?TprQ#}FHX$f-Nuq#|I3wIxN_;=Oj6&GCXhC?_B z3L=Mxg3BrChZ$MyI+u|9KcbjR&^d^CS|L+=M1-ld4kIl@6u6p3KtWp!iwXC21Qq|} z>J;&zEn;=X3iw1tXJ4pk$CCe6a14jE8%P0yG>$BTP^wDt*Kd=VSvfS+KMzYk%Wd>| z^=^Gqzf%}+NC0y`RCe^UTT%J<<|FqbChNbOr2|ky`W)9hT7v$b}>qSEXA1D`BHOiRk#jGc&R`%*kLsV|I5l8YnIEK&|vM7)m) z@5k_n7#{L-I<7?FqU#Sl7z!!u@GbHbb*fdB_7xOxy8GYq{lrkKJx11+b&I zj;iSE(m?*R+T?VWp1ht4#P>BqCkY-HpZ9E=BKPIXk+-9S3ttt!oMj_Aa)_O4$PBev zw{#rFkZ`jAh_wp8MUF`H_xfkO-fOHA@=Y3E!QuzTH!nS9h{!uuUgE~pmMG<$jX^Q0 z3%~C(gXO9&juAtj_wo|~)1e|5DIPp)T*4zG%S=*IJJ}(@W1i~hm39=G(Ych7KQa8R zV^vPEwIuQIji08aQbq@fr1VLjWyxN|V)boxAtFi*Le=7CXqfeFHt-3-|6;dm{G(1_ zEUhkTGV_VOA&4wRMNd(24lnd|Ch(vY3c0a~cyrk8!g-2pg1>P3!%wsraJ!>w8X=!+LSHgh2%pc;pjv?0LOWnbeeE|Agj+jWDfPEcfZ9d2%hQ<>lz-S1Jj zmp6mI=0Hjvq9WrTmc+!8BjTQ^HH`2$ST*e<{!kWn55{U+Hat>)A3aZMau&ZQ=Xr(p zmT!L4`nme`m+5opu^|*=(|Of#3=nkX+m%(-NwS#!dQ5T3tN<}{HcEJwr2Q;c2Fzyt z<<-Le%}1>yWdG&Xiu+;6JgZO`nyf!_t19~c>V3d`v67dUAi1bFP|UQ|E%H~%eB0Nr zIUlgx4o^sG;S4bbtPX!_^Bm`F=DZIu0MBw2>T>Ae;u8Y=!@qsinZrh#iqC^KqkY}F z*U;0Gj=-X%b)<{$-*Att^3XO9l%*q)aRw3<5EY`y;R*K#7bByZzPLoY?OtTR3QwCCjQ~ux4W}jD#cDEyHmY3`0R``<;c^4#C z_-04%Bjj}L z?w~MID~?nDHh*EKhZ^CLdI%L{LVwwnHvE`=|Dv9NdFra1Lydrmuyd?b-`r)=@d3NZ zfOgJbAb}a?Do#Rwy2iu;a1e6x8xeW)!k-bLJ))JQIm-cx4Dn&z(=;HVnkneBg&7V+ zxQhZs9H4e7zm<=FXpwmD_X%P^L-3pvbZR>hyKixdXQ2b8YQ;2?s)XY;=p=v&;Vyt) zk5c8n>kfgJUXDHq9!)_o)M#Y!msu)4^9bv)~;rsX?C#J=u)|G&tn7MWYD?5h0orq8xc2wONji15)&QuKzC zQ3~LQN#M*+Qq|}QO~agGcqE2WA5Mie!O&49P2(lGHbY9hkO4VMw<}cDF}F+Kl<%L0 z1y~B$$tF-;z~lvij)6GS>o*)H{R2bnEyW|!HV_&1jp<`r)0(7KMD?j$(Fj?O&lqLg zi?=>Wl)IG^f>-iU(hwCDSp{X8_roJ4A#X+={$OCn%L^KCi*stiMMp2>nyK~R{EBqu z{TKzUqguMbz|>N7oNUe1O>0jkBI1{g$7~SI{nVN0NVGmjh}7NNjKCWQ*YUmu&41G< z)`o#1{TlP@!sPgkzD+$DZ}8AB7V1kfb9Ffyf>cXR%heRgWkA1kEg6jf4M58 zmqUBXl7*@XEudZ+2ACh3ShBl}gF;m}Z!7?>cG$6MS~ipQ07dX0bFg~<7svfK?r{t@ z#z_Oi@6?V4f-R%*v;S^%s$Q6c7SDe5`T!S8pq?EnAQajGI%_#7t_%TYpvcPb4+b0F z#0r|mkemSZwPWW->2$sn#iJ!U{d+)BqA%o~yCr!2SK_Z7#}rBvaW~!dDv%%;PnytY^;4mRO{>8|9puxSO3%XISd)3|#A*y`ojje> z|L!5<*DtBbWBF%$G*T9LnI=g6NhiAJ@`oF;{&_^@tpx~JfNwX&PC>$=P;vCKNnj>Y zm)xf=6OTe1qPUow4ipmex+*^OQZD%KgtO2?PdMhhqQLfCdNcM3`M`Nb3!^Ml7{8?b z#Q@~Y0A5POU<=_ZhY7EYG=FDfAS`c7JXL_e43!0Q8WEi{loWkrr50moq^{zmpMs#O zEZgPx&|+%sCHkPDq0{VWJ`L1gKPuvTLcp2MLBP{4Ht_roMp*feM)wF{UU*W ziF^*2K`?36&CTvOL%=`}Gf)gYKyPPQ7cE9jP|nVGSdgyRl_I9QW?||6g3Ur#fl+GN zEZ3V5;r&+?4USPW>1E2C_2I1vb?S?*RH?0{gmZ2CMF;n#?{}w59>2}An8c4{TvL>O zUwlZ+Bq1*&mgYiEBe^;@PGJH2MhW3FEYG(RAo$&sS<9b&sOSXH53uw`SKF*J?C#$Z zjS_|h;eYOQ=)>KtRYt(ud&Uq?33}?A(3BII2^>O*Br)U!big@g2I4-f|0sR9M~O1y zfm|2o$7Jk~n{2Zdk!Lcs$rHRdxxccIY@ru(l(kyoT~ED9(wnQ34Yhz#@g|xyw5z41 z>`E)w-Kz%nCGMB@624nP)3XNN@gAVm6 zvw$?bMJqWRF|K_Fky;C?l6jf;n}f_2@hpRbyBhY>pO1ohFG9kEg`>v)s6FHINV`id z?|74vh{lxCq?Z#(!+1rosYUFo={s-jd6Rr2e*T{cwhJ)v%95z9ER4FEKrun<1;aNg9Usn?#1pU03!pxR;s904V*#`STCB@rReq5Ud%frCjmc@7(9B zEhydp9P54KX5H5@Eg+-wag6A`GKRgbWL$Rep83k6ND&_!-*%KL?jjpxvM6w>3(xnr zcOY1V1?4gvbQwn6dIADa%iGf)7Ya_RYcjYrw@dM65iKIdJ7`{xS&?UCYG9YBT*e2k$_# zpf%N#Ynw?r1NP*2;^LK9xdGc6*L%>R7){HJ{VaX~968PG)JyX+fQq9O?@Ftw6yK4IKNaS(QQcF6rS30XxHRlKomk2$f%6j_H4GIfawJZ%v z>mo6uz5_-mQ?|yl<;PjvOza+W-Vjf87 zC&rMaSVOx8#H$LR-sgV4_cb_`)z5WaFz3iDZoflcTe=S5o_lE&luh!`eyh*fP+K5U zmpD0uHif{1&|bd=^ZZi6!3 zA+eIeMr$Z)O(LJ|o|nJ6vfNSR^{1z+mQzIp3C_-X8Yyt>-wL5#5a*t<231lL7ZjSo zUQfF`m(&Aiw`u`(ck(ZD4B!#P{`SHT+>YCEU5T1qR}o&ujQrTLiuwyWyJJjsVhlKE z&Q#{YD@7hFHycmk%&)xCLp%)oANZ5i7)=b_Q$|*whpZhpYv*XTxDv*6SomGpys|5I z-5V5Zi3}ORwx1c*3|U&pzwb(Ixh__yaWx-Je!xuCW?mn<*2frsLbR?h#mJ6xv8z~N z82CUWdULS;gIhpcvdNo62@Z+^q(yY~6ZD@_h5}@`IVQ(clQ#s^A{Q5fee3wY6(bY` z3c5O&ba?(axDe?cv)w$93EtEHsG?WpS*PY6{bhfUX`*YNlE^hpO+Ev?qd-lJb$4wMB{SA!oOwKWqB%$kOc z`$8Mx)twI=ym8F-x;yM;_sFMl=6jvU3kS;zZY3d(UV+aq6i=7&>%|i+G`vE1`ivp) z{@#!OXggk((^E_zcHh<3TaijD&QR)z9cs@+Wi5I5>x4bAe>RiLlF9zKX4^qhYJL30B(c^t|J0?|smoeoUKYaq4xPTP-@&_4 zb@B5qg|r6!r%X03mbSPz`Bp<#WOcJbI7mto&iS66&tsCJZ%tXdWm007?Xp;@r0+#) zH>Ag7M@T4CvN!qdp}9VH(fqEatj?F89E#1wgOmqC_O|&P{+H2i4;SW7TUY@K_iLV% zIbyCh-j1D3m*)zY*d3jQIu1V(JLv<-wDlZHPbAk7f`U96XOdJxZCx7WKhRY~9MD4s z#gJQ&3sHAbe=si!+O(M19AJyBQRNckG{IR}lZ$66O+gVkxIB`XIa>EItK^)!)p+_u z087!BQO=iMCk$HFYhUr>wcfWt<{)&;S6n8Pnop=#Sj+om($?+cGLb+)7%uthTP$$W zy>bhjW`f6!b|8n$3UU#-=!U-%li-~b;GZJ*TnDdb9k$qrbxGiSOwkKmDUR{4n zFxpHt-;ipPA)lBC4wMuQGnT@4`)P)3BEG6L#^nFSAL$OS$&{v{smvd-TNx{wu;DF@ z^y*|f;tgOb-GC%g;y*2XOdj2O^C&u{#<>t1A3u6s1pt+#k4pYBo0zj?VSv2byf5s` zdA%~Xq+uWBtxN;H=B89c3wCn_by|cdB^Wsbh87|$nG;3g6NUD8B z1Kk2Z;W%4=SpmllIES~UiNtRgXC!WxD@##w_*ya9Y*(G4p_z*og}ojV{MM)mC?FUg z4(+=FGzyoww9?4w#4hdd{+PecsW^PZ_bSAX?K5SmEp%j|!kNzfm#ReJc`RGNR1j(* zMWbVZ67ZJ@(HP#<=s#C``SgWRI&BQCDG%5eQ@1^fg)PJ-{e^uG|x+U^Un87aMr z!_P!@BnPol*-}J>jev&c_|p6HhOqvr&2xLpH{Z$XQ+IT+#?rQsaSX~QVXSQ zCHTxtS;vAjNkW5O_B{1We(gKbO)|`Ml?S&pkJWeHBZT-+VH3W#XtoQx9ju@hqn<;E zBl&idm={qLUrQL|_ed4+^FQ^Wp6Qs@6)@;*m)TM4E_?hdzKT-f)`~Lmespj3?}$F9 zGpczxu6`u}>+oqAWTZ*C+LV?1B+$1|_M*{|{bS%+5RchUXmU}+4=u%zEoUUbymDnC z#&~Y-7#y~+&wpGpfiN~{y5_{Hk&S_D_mh}G4A=Fzcvq?y?nS`;%Hk(PaQ&C4lldbz zZJo6VfEFErkg~X!bCk!qhf=dqTYcP$cM@}Za|vF9z@kAOqY6}7`NwmGnU$HjyUbZ< zp%xMGCqnFo`nc6Adj0y)htTfTXXDMVb$Q%!-B$(uf$@4ZBJSVq(DRr)qyjNg#z|2N zutNW<@Z*6L|A44@0a+FKmVe}iM1HR@;I^82SV+c9&Ciq#O2@qF>kF;;w}6b_eJq1X zeoJh^r}0jGV%8p!hI0mWdY8GJ>|;>Z$B_w2m8j>Xwm$a|c2ccJQMt3eyske}=pWWY zr`m4!L`TGEr&=Py1lg7sf6m6xkIXJ1;5KHf`ehQD27c1IksEXZBHT4EW<_?rY-X0E zRS&J-0qS>)h;Z_W%rfj%2P08q=MH*&r)#euT~RjcRiw=ZIBqNGoE|7NDq!lMqh;-T z;d9e)?jPa);vn?KkLS*#NmmUZb5#40=MV(o6P-vJ$mg3@Tm4j{-s17c% zHdW^goAGw53uX=py@0c?$X}uYm|{uCg@!~`0_q9f!q_23un3(E)Ie=o(O_g69)vKD z&rRp%WS_5v-iE`CA|(Jxyb#T;XrzL`8a+x-#t1<1nMeq=2GGSUjjLGYuJJPI8i z?&pVU+SrmNt0KI&^3ZWPhX)SPeH)Lf7cDS8g;fzJkFadD$;$_D%Q!GMcT^XS?M2Vf za0L>ZWdCRWq(LDjGs&N{62VSX5KHs#*(tAd|eyy^*tyA?e#$Y z{p4MlaH2z&hK2@BPM65((wL{&|JHB=+||9e5Rle+bxJt24Ww?-)Jv%4mG*LYs0Q^w zmvYvu_82HANJV1H1_paMDL*2=S=QL!Q*B z5CNCQ(BwI528t*cYnt)qac^b)LB!>dN?alM?2|*X$Er9Ujtg4fh>{C*=+6mw<=E@2 zHtAsgPEhAgyjWOTsebds*nNoSb=oJ%0zTj}Kd(7et&t8!TaR;CFap!B|L}^47uAnZ6eK z6}|7l$MyUCd1!Jyn7H}-vIy1b=NKF36JB$p5dM20-nIb@Ay@0hj#@s;c$12mXqL1i zJ(3z>a3K;6H6!0*b$WN!KdPve1=&rcC7?X~@nMDK(Zdi*VM zoo0b7V_BqDV%nM{F~&{t?*c7fx3li=r1!62f5L zy0@KJ4N)kXB9{%xD*`}hPz3v9FnG$_>}@)VBE9YRsU1bHNXdRHm=fyHCwg^!vZQ4N zV=fIA3$Ta8{ObgnbmnmCk6V4!i0sjedzq{$WSBKsU@qU1JMg;v#fX57(-JKX!-^xx z{muH&c&9%N7CnYjEccVMln88sJPb>N_{$bnv?k%oHLMqx8JWBqJ(R|rhFlFViWB)s zwl_)xb~6VzmfqHXUu0aRlPMJS2Mq|^?q!|}4K?eI7!uMmZc=XXxAGHHG{O%*Tk%{9 ze#DD?c<_Dor5vJ3DmG8W-HHv{&LS;Pkl8bVE!d_!DNfwlVwD0+1*i{5@rt^!y<&vI zpYc4ebu(?*Z;%#sz271Gy_ZRHlOTH8^A|Ld>@Fq~!WJx2pYJCzJmj{iVnwsbTI)D7 zmuJw}^aG(dP;vPV%T8-$POB80SjHvNQ=)~*LB11|PZ*0BbQIYI^){x-BK%Y^4y(Mg%wNZ^#w6qbao1vNW? znEkXB_taVOCnDmGl!Yl%DSpT?MQWFWo*)M11`Ztjdi{mJEM+JXYx{sk8c~r%T@Xmr zbsrr{WiPr3!t#|sZo2P!e~lioj2D%=U-xlb59V~eUv-_V3mwtz{d)~u%3;uaZ7ra< zY!p2dhK1hne?56trnLd)dB47FnkV4g@8d>{G7_n2ikR<5M!gT`Ga1MD}CsU*08-MQEKaC;O441GITw-ev@_z06{<<*TDVZiXZcVdW6dRdS7%; zYJ;6i^wNk7^2}Oxp}q?_*pUsbTxPqo|21ZL=}&0)TR;k)p8i>Fk_Ksj!dssLSOsA+ zN%g9PzcrSObWf4GZO!P>M&2c^34irnZW$Uv+nHc-G$|;Pc-wtWw>LYK(Wg4p@&=7k zk#b-*gjr%oA<9XDejf$7n)~-c+(Z+DEfdO725qDBc&Xxadt?P^U)~Ko=Ay?aOCl@Z9J=% zt@%i@UNJq#0LLHev$@5l&l&Uvcn`;wpT;x6XM%i$KkYl1{!*fWAiIRJ1o`(srY6H7 z0i4Mz;8MqV^RD(Z0|d#O5cx~8`KV7tu|NeJdwJyBFitLWz^h(>B8TXEHW5y(6zPC6 zQN{h)nsRS%Z_@6Qyt+8UGhAlLh#QsRxipwhK#)MT0wyx}2LaVR_8GB+PbhlCJ(?8a zqn}ww{k{RnrXH+qT=`k`{C<3DY_7(4BI4KI*O#*xE6(Df)5B!&8FLAu%X{gwl(EP9 zjdtZiqf_;TEi!_t+u^2~%T-4h9FJQEgMgvnMpM{IX&kYw1B5!lFwxtRW{sEh^U{cW z^spqN+Y4OacoDto_QY6!vpVgAL1Bu7^p}*hg75gL23rL=!icP~FP3lvc-VX}$RAgg z8CgyB5VH9Cy)%-UE^|K=s@QLUu-I-rTHj^pFwi5)0vHuhcKq#Zg;YE@o=uc4>phIU zbN#RL-sL;n{_+1j&y~kKE!lXu%_}iRI#0g4**Sl~@q2%CuBF_1UdK$sX5p7-86U^I z5)ITqyME}ktR9x$nj*?GUEBC0ss>>-{l??{O4c)Va1H$PkXY8X2Q6!}R=t_>dlxVj z{tPYKLY%^KTx+GM+n7?AC>X({38nNSMP9B{lJ_~yG2p;$L@1yrx|Cj7xf_?txj|Nx?gMd$7wvY zFLwPpmN~MGA^L(ILu_z&+3Nk+mDNGpI3*KRf!Tx(L+2jQG-I58Bw<2F(#zW*LlIhV z4F#PAlpYd1kHd^FYbsIeRa1ildN&tt_@(&IsZZkl6s_F2tc4Gz;4$RB|7h&!+a8Y6 zs6bwB;^N_UW}c0Z0ZMH!Hp;w?E($)%PEPp$5~csa=xgR{zzSdi_E!l48J!b1BvD>C z7)udk*qEg(RmcrSyQIy=6VANevaQW%$SzvbUJlDgO>xoZk@xKbR5Z!Lux!b7_|VMI zO9Jjsxr#g&J^GRJHwlpk`xe9@JdPn%VfZgCgWaQA$!)b$s#(|n_>*@zWXQKfsEmMX zW%$pWn>(OG`DHEzBes_Q8CU8F=tUVt(QPZ5qN#m5rXsFB3)f*(jKZS9TW{sSJ}#=b zK_fB84FQ~tePG1A4TXAF`qp!`HKlia6D4(sh+9Rri5C-e&E>*T${!_jte{(s^$vgo zxWo_~e}<1a0-3hxv((m+K~-W?KhZU*VzY_hM0`ONv#Gw3^W0pDr`5DB=4Uu)Mjxmr zCI!Iu>kyw!y@GvYkl-Z1t-+veo|san()ONh@#8J}6xg4ZfCc-{v~o1aSr|5?{VySy zP`m0|8*dq$8JW~?EWee{Oq>ot?{Q%2wOYQO>Q8CA%A5A7Cgu?~7uKE}-Ag~qf3OnX zR5&9Sw*J2m@0M0a^DB=c*+eC#XdKB0TCUR$WCcWiFQ~G6(zT3W&fdr{oZ#-@^wVNX z=2GxH9{5;StR{(viTW{Y9nXsG}zTlcq+8 z!Y6m>SeSCk0VVza?%?g!F%KnRwI~;YGIA6Z4^_HlVX!l*wbLh78N?@yZ7aKOqo(p@ ziF2R)BuvjwSE&TLg{_DmUC8?=2146l)_>p|OVB3a6l@&vYO$IVNcLC-Yl^WJVpe?haik(D~LUj?RQ!s5cM?vVkSwkr5oot)D(E%9$Uz@M<-csX-pO94*PfGWw zHX+ofa}PD(d+sYW#9kWRfsq)}eUT`IjFPO0F38yv7`Q;g6Q1!Clk<%RJ(@xvKjIQ? zaALw5?<*0MS}RV$a$rBlR=%2|(PLLY2T`B4P-lg?{@6na#+gs6F&I(>R?E{G{gJMU z-mCvsXU!*}a0qWc;_~Af{qc1qa`}`_0u7<@A(-#6BtQ*?y#A%%hh6eXj^& z4(cRY4(diChl>Y0eYiAPNDDg4Ggs3eD)fxc64uPn@0MVm>&Vpg=hIC zmtS`USkr@F;=KC=i`pq0cd`?bozP>36X>W0Ih26$dc6SeveW-dFiWmd-8j&7k|I+7 z4@c+V7U|oD;cRc1T$?AmHrvM5X1CckcC%-*?b>YHn>K8=o9u6X-+$0?^uF^x&wZcQ zd4+&3sd&}=m6WP)bGI}x{kLz7@>~yD$Nk`gbO=dFL6`sj{o@i6Qp$ZC4aKD*Zowmt z#q1LO`sIZlSL2ziq5>;F0ZKgX*p^h(=$NEp?&12e$d}ZT={+1vB)ya`hWIFbm%q+3{;;#2^3HHQa@^gYBgi*wV9tws! zmG1rzW|-#vH3E3E+$9y!4dcnGn#OAZZdYG6HTu7F_DrK@j(j+v1SeW5oW;uerjkG6 zskMa1#SL-}yXD~_)OVsPxrrm}4Jq$ppZ>Li3YIMYiY{CN)w+mwMHfU_$D}NVFfJar z*U8xNS?w<+$|g;zD_G$Ycp%$93eAMa0LI?iW0kJ~@)S4rR0E zKHjBeGirI#%V1ioSe3C$h}ulwr|L*LOS_T54#!jlS-jfi@ev}gBzaYhrgUY}>nk|> zalNfrmuqR+8hA13OB#e=gt3DrJR1r*RXQ>P+^{gOe6(0o3(TI2WdbF8i$BppIh1;3G8 z`D5M?AG{s`rAHFU^J;|T6m;aj%(B3*vv}Ach+q%b!qEF0c7bmsJBi2=G;VYN@cpIp zd<|)oWYBtC8}@Gr*i)(27Sd|v3ez`x2SY;MeDdD93beLywy0CmrC+S6v0s(0H5@pyZ?eVO9o!`X2rFh_|QKq$xDv!1Y0G{h()#|opzT%VKt z#L2ucyDo+pw=Nf3{qkGhUjtD|v3vCVD>7GtGsj?*9S~R#qh8#=D0^5tIlo^i#P!7` zc7G4*?!mBN8p628UR0Vl(vF^UGpCHpqb?(gsDuM)=Sd*YKNSm@x3j|I(oJF0scoXHT|ChtUo`4M=&U$9mc^#pUAEi} zQh%_lWcV{0XU=T_uCdUq{<`7(AV76uSIpmne-Y$s?b(p-!Tsg9l)Sc3VjZ*pnp*3o z;mmHI9WDn=zx2v2D4)Ct|KyXoWz-9D4$Sb?S}dd|iHJ=*uV!wx^8)!Kl9}{U#iL zV(dmPN2jbghT2H!iQ$H2u>RRA2@Ve%7eZl&@gx~!VRU9vZ~8`^lIKr(ojFW5zS*h6 zM|ZKwSe(Gf((W$&@l!_w12qi}9`%DX%WG;%>g(&#DYfKv1Vk&UxHmQGO|}qz_aEmy zwt8PIA2Ett6i||#MH9a(2>r45t@DKW?~Q!0Y?gSe6<0wEH#P+h!}xlj88LT8iC7<) zk?uJ^ONzdhzocr9Qvm!QXhh)q8SpXiM{2_f2$Qy;b;h8EU_X%sJ;~5gzDIReB2L5X zO8UoYr6iIv(+o(mXeUd+!?5-HZNCMTiAU7>F-|RgLb3BIy6PSh&F85`Oqs%ICZMSM zJeK!k5evvBOi}gE1I}$(;9low(z(`8=CQWt)g^#xMjNp|@NM_!+ky}ES~yvyPtV&K zQ!$gJwt0#vvN{1ud%!z1TMmUMic?6bkdYBRrsV!ge_zLMg{}=%i{s;uL8~+72 zu)s-pDHLXZSvBC;pu>^Nxm@%ny{EOQ@b#PT4>ag{ClY!(JJgZpO5nGnPHhUQ0BUw= zX;=DWuWybdnVf|vJY-qcsd|skd@QI8Q^|c>syU_^Obz1JP zj3`)LVoO>bnTxQ|YBKB)jP(cQT}0oSn@?e=3QcN=Kauhy6?O-kj_%?_s;4hgdJEUp zp-D#kQHUz^4LnQ4Z{P4uQyF==l5NhkI1h=!dea|Cu8<_Dyphdu8bhD{?bo$%A>-79);F7B!o~77JK-0L-qY? zBMpA7DEW#aZSzh>6J)z`6sGqnJ9l*p8kLwaIuf-?{sbh9aVTvKrJ1klpZD|Hqu4io z>HpG%?*5Puf;k>zAaD{$T{K|gv$?iBZ8NOnfT{nPA7pX|8)FgCW~4U|LZ^LMw-pS^ zg>vb1YqT=GNKNQ-8AJ(~Kf#vYndZ@oCl;%MoHTu|9Vj)Sj%vwl4|J0m!XO1xktdam z2lPe-&!X!T-Ysl#wu30Ryl*GEP-b%fZM+yw`PHQcD#up-yRelQQ^|rB6BvlNAjk%R zP8-H827*P*$ma?(L?N6DRMfhidH_EO{t|yo6|2^tP|x>;l4M{IyB)P&za-xNNjrrW zi83a7adLd_Ik8#xfE;ryMx>~*c{K{Yap8 zv6|2rWP7!iNK&$UnH+CV*{kVf1`&hqr5iUZKA&jC?t*^)JpLpXvWrAM!8y9**sI+lX7J9!4@WEalqb#l^XL0KLm zUCt&sEDz6vC1rj8C+!`O;Sp~!bO>U0=5&${+CD-e=2Z8a6SCJNE!raQ&(xQ%o~&AP z2WW9hZQuNABlmt$Y2^i?JL~B)G-8F7qyz`-eu@=Gp8(G{R6$NR|iELb}6m@|jKj zq(%A}uUlgUG1AKA#nmkz6rjv&4L@|^H2b_lol$RyT}Gt~ks(U$+T-qyz~uF5T5tRW zV5ZZ@pszI|a|+W$jn)nIjs#=Y$`CGr8i_kic+5FvxJbh?nKYQoX<)O8heFrk~;i575Ex#Vo%sX+`Dg z!IGHa(i(73NW`*0q+l4cEw5)`lz*hXWy7x8~>Dltt!w!2MO+N1-bWYKNb%W<%oWbdeK zgSwY;eXimLo)6u-<}Dr8evL-mn9~T7y#1VgUYOC@^Cs9rmTrPf9tdHxC~yT;sedJN zE-p}`m}1SuO}J&Y0SmC5dd62HUcomjkL}vga%eZfq7XRxOuWVz&G}0ehsZr<_~2GV z-IshPMQvBTHnRFvQdf#Nx$E~tYw-){8yifQ=sIP{k_MF@?g%|1&1@Ox9aV0J^3qln zwHe2SG>i_m9ATH%4I`I)Sf%^d$mbqPe&M(wM+#l1z)EOycgUpOuv0|B+|~qerh7qQ`9<1XWR$LLS@K0! z7#DDWVv!;()c>m~-9t-JO92~rML*mHFA+u3kk&?8EY6{9%x<32BTlO_JWNkSmTYx; zg7Jr90&EqRBIgTVz>XM?tpsjs*7mNOoQaz^o}qcl!tB7@7-+8!ttBYcIdb8!^*62Q+Fw5CHc3z)t$8Wg-d<#RgOadL*0LX;dck-{Dy%HM9%6H?#Jmjb*$L7 zNL@bpisvUpIp_{VV4{{A_3M!MmQK{;TAJiw8(iHEW(H*?y^zDRXY z;yo|fVqKnt5IAa6p-&$v$^W3l8c#^pzGwyFV1rSw$a3F@Q<`G@W68bU;{px)ahno9 z0!U~aqO_dF9~5AvQ`DvGT?%rZG3EGEEMrZH?mC1 z9CanVHs}|^u0(ue{3FPp#Eir46Vfh7PqgnC z+k(yh>2=Q%{v^3a03yc5uq*706-B#P2^t!j>?rFV*U8ygN~eL2ER+yU3k9n}xm^Hs ze#k=;-W3K|lK~reI{d4mH?||a`lMWalJ3V9qDoS72b0@odOssGrC-3dOarb8(V%s6 z1M|Q=otN;5i4<&5@W&uFCMp&J{!(25GCLo76`y2TAe$oTIfk}0(`PQc+O{F|R9^FPnN-iP9%Z z2DcEdMzunY+_z!I!kzOFZ>YGBg10;x7sOG!(fV6L*pata!@{#N*Q43I)+zM&B0r$e zSU(oso*9Fkrheg{>SvYK zGguTY2x=|70!kvAb^c42D~Z($X)Wy(!}MzGAN0nTcP);Y)!V#C6q-xZfLQXD{N=Y31>`>)Rfk@v~L|bEbNox-9U%M-m&J;%Im0>rc zSKenqLbQr2)i#fTkq6^nU;2fw`S3>wX(sWIu#SeU5gGePTBweA%O2=^V6jx#Hg=y( zZsF=frM$f8DBKf1EQLgMD6n|T<~uOG%G<`|HaNWg(yzct0`M!kAS=f95v^?FeB*qn zlyD(!{L6TrAF~db@CmkM4f@t$Q6XZhpPymPdC%gdQdUg`JEg}Q`!BsSHiho(9o=SY z-xNQ!QDedjY5|XZHW{9(9yHTQx`A&sK+*ur-UmpTpUsB5)vwa=p655>y=w0H3sMZ^ z8wBHx@T$khbd>fF2dO1UIw#%YJ7e}2e?;=kyz*`0+cBd@Zt%++*jKo*nP)!t{hD0e ze+~NSeK`;eeL{kQC9e9tY^(ddGS@nJ=Km2Lp(ZGl4P;r-ZX!vlWVh&WK7r{D42ry_M^fj-t{Gipc(JYBf0MrbvxBNEnK7TYvo z!momtw{BJdB!k@wx8AZH4cT+s3~rHEf+XdJNl-}P0$m9*`t{(~;>mD8SvC9w}2=u%DbdeG~}#szJ{^wzF_FzzyI{cqE~ zc16fe0|ceBUmPCCV8YJkS!gVU4aZDR{y`16R?8F)S*KvNCloIidRcnGWk6|%2XY;#QPK>4Mi~H)U zKP`SNWXrXmUT_59ABqQW@A_G(_6I^!c!_n3iy=DKj(ii+V!QA^OGL>?bJn0xXO>s^ z4~enf9Jzn~{?#>v#qF6!1t!nC!WhqkLCqgIGt$(jq6!4rjhA!qdn$ASx!$1QV9;`o z2-p;rl+0+X)o+8RYoKU!wQU_L@=KomGY`r+_&5|@T~jSsC>2?q!&udq?H&Fp-MG%< zq5ubMCkw=`nz;O<%W8A0YG^9|1YnC8TQ$WQuT(-FuwaJ9{Lwfbxk$k>wSo%s=- z0sRmS;(-1)h_2<0U(`-CKIo7EeAN4hrcQ$ssb&#waDj(PiN%2e2bVM+s#9L>G0P?b zd!a&=@T;F|**0tq>y}_IH5enZPQY4*LfCi#F25i=TZ6Jf`@_zsH>YT2nf9q`{Rn+_ z&@Rl<+wYPbeeTApw7fw;^xY|I=U7UAHXp@%#9UB2<)+83$KoICSqPYm-Tjt40o+N*+VyzMpz z=#i-l1_V#qZMsMNcy^51hLXM;Z_h@}0hTQ2xm{<(?{|cS^+>#k8}*5cA9bMP;jgyn zg?~e#jcXW&(66*%=B91+RX=h9PUHegM-_@(D7?E2ubFy1{T%FVOLL!|jDGC~e_K|u zHV1w_Cw{})zv||&Dbsf4$H_Bl%SX}$%zjlsp-U3W$T~J?DMfL6@nV`jR|qcv(&k+b z2p2Z3>?d4nvTJ9+ykha7j0RYzgQ*)%C6T?pR&*#@BhMZbHxI%a~T${EjY zMum;sv$V8Tz?=`+UMu;PG zrynK(TiL6$VLuCs^*sg^-AE^=cam|lixCEegxL0BW$Yj$4+lgOUR;`FnB?Q%L5Q>v zcjRzr8VM>bw(Az2HQjtEJuSvOh}>=?g|`QKkK+bTG|$#l0(@zV6#f21qg0z%Z!k ze&2p$EUS08kp+#FV|OpxYHEC^X<1QphGKo8VVfwK%UAoA=*Gaee(5UJdyeS$-tu_LE=v5Vk9v(99i2VOPtb`AL0n z(U$lSUSRm}*PQLWg13b8T%l(xfk37zjq=Mh1=K_!Mb9llA4oh9BmL*0E^nPFbad<~ z=+Ff==B$jf5KGnL*BVv{YW@TpogR}{Kp~bGfU`+!L%}3!4NXvWi+yj;Do#p^o+3ew zqUK7MiZ+20=cR@qN>hy$s|Xq8eY-Y(#A{uHD@UI~Gw8JlB}WDC7In0Uky6`%4mUr^ z-dIxBq0zR{Vsv?y@VcvQgO*I&8iHk%`8HZL$^rhWkWHe0G^J_szr6A?klbnr;)DF8 zDYyqHdu}ECA8R$w(612`T(p8`C8~D}XIn%sNY;;wnk_*$(kd0!t#jTWA77ucrY4Zb z#X19g4x>yQ$+pLL?3v(ss|&@;sRy2S()Oj@RNL=mJHm!s>NMB|V=H79Rfho~&w8k; zh(}+CXf>g3RS=h%&*0iTg8fD@{`+H~9o!8{YyIyk-Om29+w44q)_-JfzS1_ev?!!8 z#g9llY7&SU6BwFZCml8d?&~F+4gU8HaOek`R@zy zaXq5#Q8y=OuiPubZkp4)!BbW6n_Og2r1(4~iZTNI@Ge1=BT)LSi?ZD%b|mH4fa}!p zfaj-_iARnMM45<}1V2Pn9^yOkbu)C}@OWpR?)W6Ova>dMB#eXXa?-RBu@8n2$1vfF zOllg>t2$+TiCzzRElpD`bPy~dg{)wzptW_dKB*0fy6!|a>C-|XeX4%!mo#gTJ0Xvr zzcSYsZ?_JE1koxepoKe?21jT5cYBS~=)~~Hv#wMl=l7?B08jaXd6=*)KZ8$sl$Rag z7HtTH>9mc4opd9y-W`5$XaY^);9+V-(h5{Hk?koew*C;U+d%9ar2?icAkFKaSzPCpAm3n)R9hrPS{QS-8sx2C0;gb~93zm&*!lFA@I9SCs-nT`$nbRoitn+5CiJ)*H5 z|88vIkBOMY%ZdXl(P$0R{qTk;A|M8Bmkbgv4w9X=uLhnUCKjrs#A^InuW}YT_@)E- zXv5D|p`BUm)Kg?nV7-e_yrUjxx%LQzMqtkC%oq#q{PAC*WELpwdt4yGqp z7W6X|Dz-dvC+lq~wGuicso<{OL#kj0{ziT&qi?xx+cq&yvZa*7cf(E~w;%(}68H2K zT3OOcZ~Wfh7bzI=MU-^8Apq%5F(AkRB17{M`qtO6 zbS8f_D<*UjDDxtn&A9b7#m>&%v>384eL(HqMR*q2;CFLrqyl8m{Tdg_n zo15|qq;K(g{hX?6kEdx=JBqh?#)p3Qc}_55ct{GuvUD5y9n0lZ?j|9TU5alYF4LIH z-6nR~kFFI)#6qZon5Wv#R}TLzSn@nbA(E(U0;C5n>L(o9)7M(}KQbcs^T%D0HTsVz z2HnS>`0>orV$2v|&uz551^*kmj)a9OwOshi(Zg7`lpk7kr!|m;8 z8s-YhC2ZLL8Mk23gp2mW?%NGQb@+3XOH;Dl;EB;?uv|}iX1vCwaoU=KdiPi7%=MnN zWMQHrrc+pU-Uk6vk4HWh0vS8scRH~V85MrMHC z4C#4upJ+KB-emaiE9TAHpydLQfqkNqTo~Ll_2dh4>4QV1pfq)OM?oS^&jOzCA|;HL z!WgTEi79eE?>bTQA!0`%L;lxVB$X0a+W4P*%(}GT%6^r^R!?}s+`7l=Ed9hZX5xw# z?dJfZ|1NO7lNJp#uR8eyHNXun-Fm}g9Fd2Noe)oHG_fv;<#)6ZFdZ8!f0!4OC&;HC zEh?<>mX4Qh5Et&2GXG~oG{z;YKY*&!#6QNgwab0 zklHB76eLWJ0;!;5k!%;g6lLpjG5QC!K^b%P_Xn1-uSXm8$5^qgFeRpF#8wN0ZKSr6 zJX8`5R1_disIF|t8uXFtXn5hz9Mw4q?C;WZbA_+U#%Wb$Zu4v{@SteR?_TS8U|t+_ zH7258Gf!K}mxzzAoX09p*GI=LU)&YFn!~s3n=Z0|a}4cEH4~0`gqI>R@Bi@g>>04e?!b`x^V~UlgfV%iBTyeiGTG^itJu5-ZLQHmF( zXL(9??y2K!=H@@np9i_^T=X0m@j56@E@HR9G*gxrI6O4}yA^=o+AzG3#VJhr??e@* zA{nw3q+vFt%aD2|@~z<L+~hvG%UP4FC`uCZ*{S(@RL)Dj$L?^7JWpeXvEjLV1AaKq z^lh7B${p?a51_-V$1OMI;Z9g-{X6^9TkWQ#wzf{)pgQ@BL?Nx8jFSro113u-H)cV+tzG>*`}AZtWFgn3704K#yZ8y;LlorjQ;d~<_mKV?e;j3 z3=iAu?~L<+B859QLxhBmxx9B@nc@o%ijhHChoNFv=kAv*bllv0UhgvfHiZfNNbDtJ zs5)JS$rw|O-a5W|qcT;vh(q6VDKrsY4vtqr-%l>HQ|&igh?|7U~%pfpEC}rAqn>Na)==Fnfcioi|^n`+Oc}f`mxiK zG_a;f+rYqDzEhuGUJslfKJeofWT6m|-p`N)RsK^^Kx$)_sHlR|C#{&GW6*Y>PCl^x2`?6fh7;q@et3ze9zPJhltHur6A&6 z5en2A_5o(^xCXWho{6IP9w27!=jz#QdG2(~akwmq{PpcJdEhu7GRYy5BqNumKPntQ zL8z#*FZGupPqH7P)mn=B0JjLaV2YY$f7VKH1Z;#7<$dMmHNQ3fYc)%E2Sr%@j3(%a zc3Y0gRY|T5r5L;VN){KymKx94Z`H$3;USb)&45|ne|h`N+{08;Q(dp>8y!v7QJJCq z?*ab3iO+1+qmPG5YoU6hnK+;n5(nBk*ql74)oS*5nF{m-Y?WFiSxDOl%4dfx56HTP!!qCBoe}jW9Bw8f&Sf*7!^YOWB)3z)YqXGtq*H1c zai+M(VzyplpLy1)f!C~RQ@LoI$}^WT`OR>(o@$q{A{SG%Lh`c-yFR66Js{!na9(Dj z!Te;Z@8p0X0mBE9&>`s8f)!Z%y}2zvCxA8nXNC)+uX3pucAiO>Cjy|Lu3$&>kER!J zbfkY-B^8h8d>&?kr>Z)-#%2r+YSlo z&?+wRaF=Z&!Sc8B+6gI=!kha-n>jmv0yQx=S9ZP`-Q_2B3)3r{xA(v|qiAKvc|woV zlZs<2;d?&rb3vBPp6iE?#2=Oo`;+2zdJ~TU9OkH_l3^huFdBdw6M9ImVIDe_B1yy% zJ%O=aBJhjbgT-=ux_g~ej&^%VY56iy|$)cGOQPQn5&3;G%eZuxI$ zE2F&5+Jk=YIc8KkujJvWq$Z1}NJoe1HKt{(?DoZbUGe89SpMI*luv)2(!(L}%JjIa zItONc$k6W-UkKNFpGSSFLP6C~|NFTb$g9!zwP_yum;17O9)!Ruu8)<)bI)u!xBUNc z$II8@z#|E$*YU;@=$S^)NXe0_q`)~0Iy0~xP%j!k@^YgjKv}g?YO+X_8JCa5%hFTG zYXj8=~rkr#h1Skn`#(5A4*S3$>pXU@>cv%` z6$!qWxxK0;;H|&DIWZ;x9SubkcR8E<^uH&0^Foh_39*R$3q0%eWBu>`ZG{`E`Q6U0 zP{E*Muj9vk346QuDUJd8H6(skmn{dXTsA7C%YDmA0Omfc!nO%kOO~8DWwQPC+yKwt zSOwA#vjfVpV33h_Z7b~kW-{$x^*2dC3S|_2u6GvBJe1dd%LN%jX)u!%pMMbSKtT@E}UX8N@{{S5^DH)S*fC7W-;a6^vFHW`nby9_N9^6dY?rr*@5v>GJ`{lwa6+S=cVr3k1XC}bjCqGastLW2c^~TvF-S) z9C??Vs{%9jp2E58j(XC>!vd?a^y)O9HohhTxxwBvkSJr=#}~t}E29bM{L52YTteRQ z=kkN#1`^}Kxzjd?wn&gAc`r{_vBFx%XPrI~m>Fs>4na7KFPKeq?aJjl{drwGWI@&c zekcgpF&c9hp^PT`<#%h#|A$(f!>k^-grTIcoqJZ1Nhni7MFF}c5(iJ3amg)>gBwet z@QU$(7EsS)Ht091?^|E8324+U{ENoTVGWMH;~vMvlY$?r32mI^`8Tt? zc>8)yvVsfjmt-X3`wWuvdFp2x+L5bZY5`}Nr}A6g)OSZ8-~g`sX7A+}X}qk{c+^@!5N`!jYx3R^Hln)+;SrU} zRSa3=eE5X0ONU}os=3{Ize`TK@cXvnKcNQ~d5A5=n56p!BNR{`%sYK^b5}Xj#^;}9 zF?L4p%qZS{YBQVb>JfKTe)wxCm%J6xq#z;y+!=i4QQ$knwDIv%h4O0z<)xzn^bG+L z!&X}^+H7$&yaVK(adF!7IDt5N!G?OQiZsifFSA3m>h1#F28b@JGos{L)Y~(pViGC* zN3r*Js4^fULwZeC&e6FJO;@AbZCN~s9q^lOSm5>)(4x@DoI0ThGSsK)G9%(#zfY)z z=!Mtcu|rTsg4xE8C>bC_w?mOOGQ zLJ&!rGEv(e;Vu2##|2WyX#Q8~WfkDI|8KV$#Mbl-KsEyo9w zbfyYa?^2+3q;=x~(TDPNEz>_XUaT)=YMCmdpg=C-) zQvgGzbcLo~S=Ze^g^D!cH;AL{<@Qi%t2_D#QRa&0Uy z?nA|h5EP(7m}90@HI3ao_#ZvrYu*gSky}1lH&j9pBtTLf=1w4@j#x;Z_iMsWJZ|D` zS$d_bII&zE*>(_2sysum6+=8w#ih-|cC?)-W~ z2&!%e9%0}$G2gNx7k~Qv^(Juz^M%)=n`M!yI$ervZ@Yf6wkuJ?G5PFm?SN(vJ5*lS zmP>Mvbr;Wl<9tbC@{a&O)qp%425Q>Wmn;ZCmN8*>lzvQEgH5m_o$3Lm99OQjS1W1y)htW5Dc?YHM`3ZnJ)!ZTGV^{EcYeq<$rqR}09URgH zQT;aU-lOVce9@#*M>3+ZG>$(x*|8~kz^K7>EcOV_AGe8q}9#k=(&?IN_8t__Px)dv&$P=c25|kfJZ@_4Sy53>RyO{-{()$7K z-(8B1ZO86SwY<_0+yP;0Gmcs?A|UqMgQ~|i44L=lZHL72mwU{*ux8DY%{zL2-xX8B zwn=XAbd>o&FOCFSBwyvG`FN@4I{$9_x}#q1&@L1BPj7DE#SN_5I*aN`ZlZ5|bm`W423=F+cPM3-c6h zMeXjx`mlXt;@ZA()cw_qu-_>C+WqDB^L9QviL#m}>zMGB>>L$|nDr%Y6WD!R(1y}H z>;?6`KU$#@QH$f_;6QyHGa`yq=jYoxq}M{H3`j=_&VBV8X+`;MJJ%VnLMMMZqJkhzb zvu#!gE@()Cq4ca4HJVVVg7~^2*17k(Xi)K&YbJWxipJZ9KP1I-$0*vrHVEPR!)=Wq z#x3G1Bn*vWPehT2lL*ktlfwzAPln}zqk4Kr+~h&i(E8?h5c{yPtg8K!6!INn)ep`3 zZ`BL>0<=ZrvB7N1?&1gHjWUgg|4+gd0*c1#Lm~WeW)W#@A!_j-0hMKk$N$<3nGRy9 zwB8RK-ysEncUnICpsz=fbU6v{5dBqxG2#yix4V+S{M+jXYR@&ffSl{}vcI@o6n3EC zLmW3-YOfwQdqYUrbXe2?zqII2xX6f0pk6ygnA!yopp*+YR2AAq4s`5HtQ1T1-EviS zrb|#s#M?nc6derRvO#JA*l@Uq)Tq57oQ%gDnY}e!JdOte>tJ3^> zj9P%i^^~gtwP}HCp5Yc{s53tDf>>6NCVyS(8nFnmIJ(jly*fO?KT)j81yJzK`Wl7i z76_(I0mOk>k5(Fi_WHw~sNCf_3s}bxT<(F>6E5tO|Ye(ZRl_a_ERIH`&;52UKOTU zUag!c0>Jw%K^4t?Nec1Sk%PmM$ z!=jg~s8m}~<8mB!-lHD(K(;Ec(qt+AAZ7mkb=&8c&^bI-N{Y#@|dzu${Byeo|CC-kyH5H_$? z`ra3j{r6G<<)$Me^HZKI9!TTqpK?W&e#oj@%6|um39X%u(`twFQs%olPZVQn=}}f8 zWLPt9Z5We+&@~TOMy}^g1$qI0S=@}b%)xKCqbW^*R9tB z@ie0a5C2n)Fr#m}2InDtB0ZL(PxR;95S(}!w;6V$x^q_eX!opdMCa-{Q`5fLiz(Ge z>&s1{rWmOiE?e zt>}2#{TZt3YWddm*g&biUzLNN%X%We&Oz;l zM5Mk_j-$j6IB1zbFF_5?oSz`qw2EFWMv!i0OIO{ZS6B^1b*@E%0QaHW-yuKF;hQ7F zdWudWj0{LUcqlWn*N7uUlTQfWZJPDQ|L$=Uk#*1)TU|juW)Dp6n1Za!y*6@T#c7xU z@iiN-I9={fH{KI%j7E9oZH}}0TbW$KH||7$H=xqY{RE0a3d6e~-@QMB#I8um_O%uM z_~>9Xs)ZYvn?b_Nar|v-qcOx6UFruzVpfs4jdBj+T};wto2x>7u)x$%^m!4$4tyTNbfxye6Z;KJUx%}*3`v3=DF^S_;$Ye&ipn<{-y>&cYma= z7eL>5e;6k?+#wvDppy%|?NE2Qd3-}FmhHzFI2vMf-C++lKZY9q=T0D;n&Q`kM=zTd zpLEHK8%8Jv_5ggjn`tGh3a>N5Bsx9c(b6%rED%un6}|l0>tx;+gru@yYw!-winsEs zTMEz&+sC(T3&Bl0orTB2a$&TkJK{-$rhnBK3ClJ)_WSo!s%C5Pz!tmtJ@+0^;0h*m zf1%2P_x%@({U8AP&Y&m|E_u=3a51t|ybjar`WZ)}1}NB(m`g*6;4LU27@Ye ztwfGKcOsR;0P##Q(%m<+?J2%x_Jc&ze7>+KvdXeD90$~9^8%mR7S&Lo$xy4kV-r^M zGH@miznf|5j4o^<)%rar}UkZjs|6Pfmknyls!k4{_-T70Z$G%g` zbInFdkZC7v;l!scA^)fEzOiQ9`~{24kJQLr)p)rH(nS^^zg1<5OPgWO$jB<_)1~g4 zyd}IXeAv{JHjK~2Q+HoqoW|au8wW>68hTagHrw-3tAARkmqC7jl@M#HV8!I&Q1hoZ zEw!5dr?k7ft7%{`73J7WqH}ONCnPgHe#rV}ozad+wb%GnU166&TU@gr4DxDcvUvQt zESsgkb#Qo}pTs9q7(kX>Uoe&XUehe&m22uX(HnsPVbg!#ip!HabX2b}NF$yVh7U6G zVD(qmNKY}tN|+qewK;Xv{ZDcNtG}hUA@Wk^f=7g64j9;Y@&SiZtz_FXMmNFU>n$c}=7K z1Cy@E6X+P^j#Z8uf}Oqxbj$cIA0|*4*|ulGDO4|@0mm_}q@B)sb3>pw(4GqcVY3J| zwI}KQ7qocr{>@}CG`edFz>$)%&JW6r#vE=GMMr-@wPRy8Ap9_?8o}$R*Q?CLW1bX*qZIhTkq^ZRd@3uChr&!X_oj zBjOyTTLC|R7zoZ-PQXB*(?g6fT=mUOzFZ(go#ahJ=I?ZOi5z)?y?PocLqJ|hQ!?V6 zI7#+$k}v*?S@`0oN^$Ey%7=-a&F;5QY7j)~_ufqH*70!{=%A*5F=+T>=oE~zm#=UC#&7<*rM=!eilPi3anheU0S>0 zKpK*AAvs(9GX~L~$a40z)n6_{kXOT5LBZG~bm#C~sE}UZ^ZHW`BWURal zt4cMV=(O7Wa5E@>o4U)7=OqhC;78bl!uAS5^17wgMXH(1?}x4cPB{XW;v?Aj^ucJU z_*6rM-!UnlsW+DUGx7^k11jt&kOf_qpnQq4Uf;oVakWgmbNT*2%E^6Ya)Z{L!r<@4 zyj;$t6t#$F?yIev->mX;KU8hCeMyb8>q|vA3Hk+)+YvisV_t!&Gfw&{z}C9QlK;}>{6h1=y996m9`lhf&>r+zysv~S)}_VT0hgVXAeA!#YP zsZ9dUE(hDHdTtj1i1m{sr}?*e`2pxu9B7 z^L^5B&zRxTt?x=1Ka7OR zIfRUqt!ha?GYZf}DE;f}uD3v~)S3SXxMsL!h&vcD24pxBvR_5v)U|Z*kT{=zLH<7&@Ydj|biM0q50em>$n2FP(Rau|3U2Jzhp*5#Q8)!9C9Xf_5Z5?H_B1nY8Wu=wp{itV_zW+%eZe@&08D*BA`tO@{1`uP{~L54bb%SS4s&@3+`)7s zGd@3yruA<-+;C0Zox{Tbj=G&r;FbE*kP*M^y_-XXMa?%ZidUTe-q;wKqFgE;afRg2 zHI#lr>BoQ4PuWCcyBsLaFyfj>I2(lCOf?%wqt^i2*%}I0IEnF7xLu?(Zlv?@9tdDd zM1&sw9>j~lkNaXABjzC0NQZngz zOScUI$-w-PP#~){ar-Q$p&@PaJ?_sn6_0nx6F&`AsyC_IafVS2UJl0xx$g%w?MmYQ zLq1*QpVWtq#s_QI`6~}gsF}PpuM_)Kl2HY>ksXk-`T}}?qT}zm8_AMtDmYU~ z`Yfpp9Sw!)q^M{Ju*;&nK|Dted0mw!7Zog*_Sy#mJ*|Ww-Ug0JjtO_}gg}b_0nT-lZrq3y=O5>s;;_n#HSrBNaZ-ifvIIy?jT2ub6Koj)v0a{i!U?2raq)6g zPM(RGI=GKtyAd;l3ip0S^DK_cM2nkL`TQdlvVTvd`D`&ZQ7Lx@YV{dRn6*`8>XuB5 z4a$i#12Qt{$ndm3L>uv%Y;0tn^?^7EL+yhl?b@$Pv`=_drk#=c>JgpK5@X-R8{=~9 zOuxS0Gg4X_GQ`UD&PfxmGdtwAGFV$e#f{v`wOYuNDhX^DQl;bOq)wW7Qf0-sYfm#1 zHe7*(0A+Xj9EA*%YO^lV?O@kC5K$p)`NYb`t8FUoP6=sqf?`^KrGP-|Opw;37O+U` z>z_4)v<1(|xwdfrIi~0vCGd5 zc3su!q7)#wfAvWeBu-xbJ$ZISetaywlI_Bkpe{C@@r6a%nMXG>*|MCMm zUQJ6?Rh5oY2|2K-=C<6o<>UCbg``Ty&7j^lyEb16t8zDuO|Ew}>s*(4%>bzqiA3bN!&juXay(C}J5lEG*9Vo9B4)(c_Dy-ct2u9r6 zjXeOH@oVY3B1R)KHP)0auYi!UQ3I8CLs3maqo`7 zY)r9htFIhlMOAi>>AP1Tr_N}dQ>;}WRj^dC zaF4>-5i0aSZFg-W+C2e>Xn_o~o9fb$DxG(B$en>!^LcJ=PS<(kTK7rm@9C5~w=T)} z*r3csk~ftthO&w}Y1^`20-+LpwzGy@A>A41mv=rKH16ZjhxmLxIeum&2U5iicPlN# z`VlIrSiD@Ti9D&2zy{DbuHS?I#ACxX<;HxrDBZUyn0O0N#S$pb4B!I(?Q zp9vegCsVq+Q$omq9$gHw$T2~}v^{TkPnqMm7qLP{f=a5hNwBE`69wK16W2|HY{429ti(N`Ast90N zU+XvSBk1d9CzlGQOC{@1eJxO0>XW*fpi$Ollb+OtMK;JtsKhM>5=d@O7KrI^`Fes- z0W1jLKE@8d_<_5GLpv_Y=N`EtUwZ6ydGYY8PI~y&Btj(}?smCXjI3URPuJoExOYpY z!?ukum-1XHUqXomUN^l1Co*E|TB>I-SclRr}?04_D2nrw^7(TV+66 zDiXw_8_zvhk#c>7xqh)cxu8H7R#^Cv{F<2F-6@}`_P|CM9 zhowdTvKt;{&!?480d99mYmE;-9yKm_Zrq$Qgi0*x?6$XPQF#t`OFR!N2imnD%5Pj< z-s zrW_Cq`Q-Co*(|m7i&y$?5-Na=tn>w}Z=31^Qd=D`@;pjyHs(}U`3$je?$V^`Lp~J* z2quoz21;EuGM?*=2{zk}R^P)@1pY6DWCzcpS*k2a zsKl$ynE$!^o!z{)CEj^|P~N+e7_%)-o(*gJEo`r6A7^*(-Lq6li-pBZvQ(iwQ~Ggm zI5Acd=obYW!1~9Isek~%kaEC%4uzoIk;u+K0+rrPc=Y|K(YcZOqevQc`DX^qjVlS5 znhyByPPYkxK+MedAoZHHC@6SD#F#lqsZR$LF7}ma_6X zEsI~r@;SME`?gUoqR{;C!l(>QI?B#$ELGMP3&)as4UF5kxdCf!sWKM5B~gi}oX1%1 zH8Kn6AMncc4xh2gc<>lhV`_GG)gjL0@07 zz6S;K)*+cJRV-n#oVY5PELHd&e$QH!jPrm;X z+#2dHd&Z2%3l#2Hx3DJ9ge5IiUXP_ccmC3}oIb1XN7;lN*z1$}lsHesiecjzsIBr! zak29`7fTgWwwLFOO!bB5oi-R7cdTcM!U;EE)>4IQtV^+6K->~sa@lrIh1>nti;t8q zYN=web?a6M1f2eQ;mlid`n{i+&$*zXb(cK;*}oqDCUW!Ix8>x8II9_liO;flGv*BX zja}!iFQJkS3+4LN0(#E8rHX^QN~&Bs{w?GFD^IGd5O?hfX2OOm&;l@_Gm#>=TVzA5 z5ZH{#)vXXrS6dW!D8a3;VE_941!j`A0;U^S#JGtbo5u!@O;$oW$dm`+0rCNXHWgTJ zWX`kjcWA55+tc$(OzMWxjU6KpF(^n;sHK8yu3UEnc-s~`Rp4O<89q=^Vhj#N%;akW zzoE>6gsHFfsqo>%2OuwI>rBQd?b=!b=64au?)1(Y_g2JN;Q4LYM1b4^>FJ-9fq`jb zT8w|yO>MyxqG@AdEl3rMnOSziI93CBd`fW_A3e&-V8Ai)Peyj{jcvLgqrM9NZq1A|1DQ=U;if-w5`jvz~ePVeIJ3hEM_Q=nISU zyY99cm|i#u3=J2`wa!2iv4R2{Qsr*A|N8QiDUPNs+!b-*&68s?IFi1NS%Bg%8+4=u zT4#=6=NMptV_gwYhW6%=nbXpdSnCbS!%kgWp46c9*3Ayrao)PUTnSKMxZBEtHcJkq zpST7>1z+TpBR6E9!A+_>eSc|2WiS2DZVX{#iZhQc{GC_c9W?&9L7r5}<8C2)QYFzJ zGm$Fefqx+F?VDt7W?TllF34AZ?LRWdGvTlQ##iOnfBhR$RJ~bdr#fWl#((D`RUC48 zIi$+BzR_gj9)LRo?Q-SjR+*ihHFN68qd%6Bp&oNC71edEvghD)I*xc`-?nQ~S=woo z=im9^?F~SxWItAIbg%}y9)Di_U299K6jk-+wnGomK~7br0w#h}Xt(E0eHpSjaV5MZRWkJ($Pz40=y$Kb6*U$qsbmS(D@Tqd+<>i= zQ~?kxw0k=6{^EuWy!2F!6c;7yFxHDy`G^1AePia(7##uS629? zStousv0~!|utSUBYUAV1!U-iod6`cIQJ+y*xqr{*!4d|6g5L!;5ARWHQ*s^~D4IM3 z0<;S>6lJ9)C>VT6c~FAk|CD(UYY@nb*@)9#?CgMuK}d#-NhMYw03ZTrXM)~7_E4GL z*J*c@F$874baleGsIfcOd-OWm74l_fX3k8`2vS#XOqw<=3Ol3})+>&wtfLGH>u>Mf zS)})Ne5)d(UA-|Scl7yEE)+l1ZKGo?NtHbESP8}_7LIimKA*GmE*)@pu=u(3_f5^0 z`PXwpHl)h3VyeUo_=7h`WOOq7d5|#+8OSay7ef-E0^+~vkOztU*|e3LSg9zF%JXq0 z!FrP_iz3H|{%Ipruo@wd>RMrK2o;chCO4_F7;piC+yk!ONFOUA6?sx6kGqBJNR{OG zWHC}@+qUfzotu&AiBWm(+0UBenefuDd`14_|K#sVQAvd%ReCS~*KtzC8Mm_~RgmRJ z#&n`qH0ZkKOV8HME7TxW`bO`UO`A5E@5kQwbGdQ(r1_iFzt|w8 z%CZKx4GR>S^Oh=WOsZ5i3~2Mk*Q5c*nwU+679X8=$OSjHY+{Wwt82oDxpvQv5*?dG z&U}n}CdYb-yhnaajZwnJvf0_p&($iEQ83@Wv+z33&%5bT zjE_gyeDHbK?I2?=U5Ob5eP%*s;qNaz^2r3U8+r{kMrJdY8$Cncj8W`b zs}i!|I@|`OUku2mtPSQ=#Odo*xj349J?$P;c?djs$RR6IapYLk#4AZX$7U&r#B}Gb zbxdhLD3q4wIccgZkkV4WA!sa+V=Zt`U&?!={e^2zoko`vKbZztpa8C`sc~F>rQ*Hg zbJE`CSi9gJ?BZo7_RCu1SDvZUwM6poEQeIVlfdM}So~Wu=r@cHsiew(^Xg$m zs+#KjQdOCmaLa_Hd!z%NeRr>2D>=FDE}`N^wzXIsc~T{TJgIUou6)Wk`km$Q&kpj`au%oVJ#PzeK1_EhaO<-Q3mXt>a?5P>eql+5cUSZJzAwixh{T=Hr3zu3w zeNM3W)I8IgXIj4_u;SyirOC-dY!cjlp-k!5`mlqjtvO_TQKD4C-zUl+c2wIu7LMZ0 zu_U2=@84gd_lnN9A+E#DUm7<%Qm7aAfjD{aV2RlkGBFvGX&t2Ns=el#i&rL0dqJwW z0oeedf*>`nc_54`%L`5WT(~@Llu-EZy%$J`JgJh$M#Rg%EYSBk{v{2X8e%5Uxf@*n z@-JE3#N@HVx)@GbIR4r9v5Z@o5B%Bp3uOD2m>k^aoLfz?ER|HLC~*Y)7ryd8o3 zbmpjBKmRYyXTSpR)`(;ss6H1gAXI?<%yI}73*xFwOcqFci!SKm%JU6Fs^r*&c|v7% zu@MLrkSA60_#|R!Qf1+LvJ|Oe@xpUY%kJH~<>=9)#xFhK`;8knq^+$@_U%6)zw$>}6#~`!1Bp2!8R^@W zzKu&x)~6`ykTn>enah#ekbzj|S>P&)IC)&>UWaD_3TRwAErx8}cx8>8yV1f7Ip1O# z7#+h)L_$N)E`B?oA{U`Iut?pknGTuqAV=_gEsDcDv#lMfq zHaL$(u(Eex4Y1(~logodi$aA)>Cc1=82I^)@P?3I6e`ej9z!tTTO5)EAnmJmd!)pW&{a{mC?~Tos0_2`!qMl&X^e|kG^XxmL7Sa%$UlO zCm1Z0iK#i6(%-WiN{Ie4)C1wOK>Q5We)_f)gidTi85nbQ;ygmts2(ac5Gzc}RfuXXMO1LrT{wo44rft#q* zv}=2^rHUm~02VF-gY1&R9N!!=_~<+?{5<-;ipwb=6{Za5xxQ=uMPIO)MLWX4xr0ztawRzmImdnIUqf}Hl0kJ2? z2V`by)VS5Gs&0_dvMOocvPZ|0fcf0A`JhOzE15v8JMYJvR~M zHb!k|xT<2;e_(RVD|532^9sw=Mory}6nazT2nv(AZ5hAuK)~3{xQ{y~);-8||JYWO-m-qwUztvQ(PX zwK;Mf?MT8^uZ=-MpWzyNj&T9ycRJzmO@?-GhWK!!6G( z2Ko(aW{4CL<Zu6A;Rm@xIVg;G-Dk@`9(1p*N%EsaT8SxlN62{K#d7KVN$od&866&w z{=ROhs%en=rZ(xkeo_4XfSf+@rVQxu`|f{A&)<>OE&I(qz=x+_(Rn3#{j!{wF2~EI zw#vUj^)|WGVj--z9Nu@FCx!g+-uNDXru8L!@7WF=K%?Y zNj5tKHxiiC8)^ea@neBNPf#semzD;%hPMh$}UZW7=$P*eDga9 zH{@}IScIaeVcSu}At=phSvlv1HT8xVLRfGnt_<}2txoR$BoV@ zW0qN8LwixLIkWSb`ty4TOZ>IFMj%Rw;%mwI=wqKo`D zGTJYF{Wnco4`d`%=E;LZ3oW;;oCTgU*I{kKqWP{OLq%9H-|qG&rJmk^`FrM^N8UdL z$?wzyE1a1bUs^(CXxJ;^phKvPjz{Ih>8Q?ei66yM)!9wvk!v0FWk^MWdFGaehVfIK zNY1@n*XSI1@oFM{d{N}=d3?mH{LvlIx)Fb@Ko^e*Lgn(cs9u+72d<&)oP+dQX@a2I zD1-{w)Edqz@t#jDcrvDC!&Wh? zTP(bI;gOYt_UP92e^1Zsf<*hdzfVj=#it8zyhM3wBUZ zM0Sgy1S-A9cG5#)q`Cq_z}vnlY<9Sy)Gzd^aN+fsI3om!*ST6Jy3oAR3q=?003p%d z5;A>xcw|l&CNZh1@EUUB~IH8gSfyF=COy$4Pjx38ohaKmDem-Pza$ka4WmW zgTK(H9<7jZ6+B2BtE(wA#00_RxjuCuM__sC(Q>^$X7aG(q@mWU$7jrMrRL$D)b-H^ z%Vc5-A|@(cZHL+_k8xLpU<=97-V$8!?$S=QD+{v$?JHd8^Lvct3vB?I($<{pLJgvY z-EouyqKNOnm`!RMY~AGSZos}ox}V{5`vfOE}_QF-W4O#G|--ZG}!_s9(_*oF|O-0y@;P(gRwYQu_Y9{R4J+3lHOiq7HT&@Cn;$fcS#hrM&!ef=FIoK@qEn7)P?8&!G{sKdOa|IE*C)RT)dpT6OVe86wk?) zcHRMYVtVA%*;KbS$(7%^ZQ2AdMb@}*Ii}Yq&*z}LEFw=n?2%9?O~Wk{8-Y++FIdZ< zy!)>_)(h#~e=YuwB)k7AlP4c>tW#3me?9u(A!%-ImYX+k8d7CsWW;>uFW(<~;z{{W z|MTBB*E;UM{*n3oXFu;YE{ORJcS)KvxB_D?O$t>1%_f~koO$%#bN{t*$ETc;p(edaJnx?!PI5zq`!8auxPcDEu0`B|>hDFcQJGD<;6-hx{d=4~VUdmduhZ}4 zPLedV?2;!w_uJ+(dS>hXi&#du)#qJY%)%`#vK-ooBkb01-FsNNqP)`=u8zyBj>R?A zUfFEif7QqXPyAawdoR~LcPzd-&12&r%NKaP;3ic12WND`a}@t9OmBBj8NaQVMWgLCg8ZEJ+c)I|-~qv)WFSVwyOKB=hi8bK2w6eTCWnF@Bt&gW5q!MaTu z7@9G8tObY#zhidYjzmYAT&T@ppQsjj)T^Dx^j#AO@IFC_75ES?v;-e{u{V znD{LAGrs{Sj}@e`ykX~TOHt0gBEWW*%8;_iJuoEPy~sO%{wPbvka`ZLBAu0#Kksq}ciFu34<4sR+*m#hwL( z-BXWF&ZkEn7?%eQjF|-a0YPMgV7_&fSY6I%OQ--8f~hXQ+=R+C*J3tTSVAQnipu?3 zCYyLKICtfGvP-GjnpwGjzg}a~==|r0wO*D`!9oQ>1yUw)?U+)k%5zYLUpfw<+aAx4^oYjd1tvE|uNeOXRT!D+G6( z6FMicF{7f?YtG?0;(`6Rr1lyTjyf85QPXRvd$4VsRrQiDPX4w&2n9V!)|pN93E88m z-k)^NAJ-SK>B$l*ps69TIi$WesMi+7Q`pD`fIRMdwQI7dcWnSfzOr&997m=+Y$$b~ zgHQvE2=3z~3-kc);}zwJI&g3IIg9eL!ldKwJnrKp3v>_e<9HLX$n-l9gzn?%WcyD$ z3JPZR{a)(bb-zU`dy`PZp?9JWqjSnB`O+LqlkROo1+2WCKTU8(!#p-NHke`)MT47A zVe!o*!!Fi_x}X`L235d8`Qu)g-wR+6M0m5x1HMmAN6p|nHH-gkN2!m(k6jh1Lk&A} z0ZN^&o*ARGDGA3kMa{zG^haYdIXP!0e|&ug0|}p>2pR-dCt!R<| z4`tcZrW3LzOA-+5ojm5Ar7Cbn=H%p=QL`}d=-Ul}V)IycTnHxweK&c^=v+~=n*ysB z@=*5H=Adk8M=9jwDJdzGa~H-Ph2AulWm9tG*pTsiTU1nNCXRFpILAk*-_#M(h2VDx z6C|uw5aKqs1yv|6)ZYx4okmoad(~9=3@L(;!^8)nLfI@JQxMiHv4T}cLw!J+8v`bO z3w;toB`>_B0grvL+-drblwUWLZ!AkrgNa9WO4jzh zS3;-&NDi=TM~cNxS!CWyB{Q6NAT@@{mFwoPY~PZw^x@poj~3`LTwX@Zv$MqHN|L*6 zR)wonfqEkfy-B24e--iarWo&F(c5g4%b)ZN5-U6d* zV6L8;nvueSs2ti?YUBjsf&x4+tU746th$Q5(78DI+eU{irMuKN-J{4<{KcxYo_Ri{ zxP50%-uYl?K6Q0ZNK?&K+1d7v4ECRriHRX&RkAc}!@E;9$mQA$$n_`hX?$ubx+1Kf z<{*#dVTm#2JKs;FLC0cojS(|DNr2fEG98r%_m|2;2TEnGH#_4B!VSLsw;g)33lZDA^GKz0XcVR z+&oSc{``hf{xk-pti)No7=?~raOUGtdHtP1c}MeM292=T(&$)fu(N}N6$^lbpsmk* zJSMLn(aGt($ZYIC6-Y>090Vyf*$FD7v8ofU*zubh1 z1v{F!Pn`6pd44Hzr=ymzN#y#}#j&$)rZeZ7g5wFboemFp8`K1B&Y@J3uV zG7e`)s3gYC)f9CXBUVuEa~y)7ba)^~wL?Y8FCk&e8)w!a%F(d^# zG`iFHWJLM~6W2}8WZ@oiRluN@W?;M5kYzO{7qQ+T5Oi^I!Ua-8Ln2PWdV%=?Zv#QU z$IRi(IWseJ5)38QhygYs>U_uiivFRXz^i`=Qt!BWwmMkilCBDD+b-F@$rmPn+ZdRQ zZjxxh9x3!Y?)V&N2|YoXiSE>Md$nzoUF^+98%&-8UwiyW9G-yY*7|Srs*_k zCh7aF;qLi+9C`0YGLjVg%RaZnb6plz;THD>J~b6x7SgYX^Vk?zVhx%a+;=wR`|86{ zLa?J2AY2oS9fb?AFUBTg67YG9asy=x=UGtSi?B*0c8i9Bg>vG|h*9di`R<^cIX9*g zdQ2MY9Y4cZTv(ta#Dy4t5e#dwwy1KHB#iTaLR)=mU4AicxYK&# zZv18*>w=21m^^+sCim@*=zE#0z~$W|StZOvhoUAxy*stHIvt~?+Ig=5{;&DGsSR^_ zTpbd3%CQCv_!Cxq;BFBsMZTC+2BT6F7O75?d<6?Tyv>vDdJmOhvF5S;tFod<=eMv-OnT*Zcf|Z2gbIrOU%WjaFTdVr+;-v$WN>Ioo_;hYdw0g< z;NBUtVS%#ZTJpwCCsrAN9C-E3eq*tT#SGS%5M36O5h9GlXX>5mLe8cgTd~X(Id#@~ENb_@r)N#P1^PAh zvl}WFbhKPRR+|<@@`cIYl2KW)Nj9}SFKtbqU67g^p42(FIez8Zp{nWk2$J&pzip0h-TCYBBMzbkTjkIr|Ft<62tp_%P+a}n=J<|% zzZ*Z|fIRyj`mfBnqLMhF5HCik?Ca+E?t_2VIS@Y)(>&Yu{%7V~dDV{j_O!%zKT z{D6a)r&Q`&ojmQ^Xj2#bkDE3n59=Fb=aORW!=8XtH#+UJXaBF8@wG_hK@vI@zYkpp zbxb5;#yX$%-(~dc_LfIwOWTWgweO_^@n?u1YZD$}##JsP*>mF)19Ix@Yx2RVS4`^c zxgv$(sCbL?UDq@ji)hj@A#LKEle!0P&fkNS*{!6z?U#vFxW&DJPemnjM&Td)!5{qN z_~&)UK-UlDqbmb4IzBhAs7JxeV)|2$EY_QB#yEE={zb8=6*3_HWrbkp$G}j;xUjp^S_p1UZTZ#(i9KAo!G*`sNh}_Y$!Fh|D>P6qNH2 zAq>P`F9Dki4M{>>*+n}q$i;!8qbTIniNO){a81QMxXvLu7Vhvxk->yX%n{liVUmQP ziB$(K$&wM%a&W#tX7tsG=>%l+pooO%;CE87R2~#5sbIG-<(rFXn?xL!XFOwe3t^4p z_CcD*%0R3eJKxjK+-``l`r@4f)*5FXS&SEV1^GGm6M>6YJlf~5Hkn(Xz;(Oj8yfbQ z*eF{z5!b>Tnuk5NeGC0pCcjmz{6bp*%u$h8h*etN5_w=>v5d|=FQsMsv`iJ!-EmtcMhawZGC9qTdt}?L z7o9Z(^-QOKtvBcbA2V6DY#W-U=E zA9E9JPB|b}cn*wD%p3egDQDw>F=jD7F^3`(@a&jlOg(izgZSVXn%|g@vN#IL_4mrkFOAM2m18G|jl42D6V~5}$y1L6wJu)M?}kQ(C9KzNX$wnbg|?ea-Fgx6R} z#kl|KAMi?0MGc?MwKfQJZ*Q-T)8i)Q&cMKcIkpni)XhqvH~WPN>tp5wWC`MKvdN*O z1ckHD96NhqOv~=vk2xMM389b^e-rYaAlNoOD0-ySb@`IWs!i=hi3^v?_RF`UIv?LB zFMaWw^5P3$mj~{D%B0DO0xe^i1Oqi%?p->UmdI;w^~lLHQ*!=NY()v#ySz;01D%g6 zihQzbYl#F(o-=Fzn;mE5{=pCB=AB+CQu%EEt}^k49@qCZ zD1E)x!GARfg7Jr~r2K#TxJMaEP z##Khx)gF?n>P9Ildr-%dSvhs$Wx0N<(>&J)_LXVpJt)CYmC8}W^2Qr~A!Ab!+1?V8 z+S)n^l{}<&0*&piGW*|+;asjh0%@tQJJY5%B}rpE2^?9*S7&ph)R(sA>Q3=Xb6 zk;=LOBA(64smbx6;^;KSCsejhh`vccmqxoFhcYj%1T-b{V0!s8(ay`pD%@h@L)Ucr zTv-o9RhD3_RZ-@btt~~;*!ER({?mj!sj?A~degg7g=d!}{pL^Xv6@R^ke88PnCSeby5d=z65mqQ(({3o6Q0^on(Ls1u zh*MIef|HX6MUeBGnPBsT<9UchvQ!@GL;My3vSF1%La9$X=YzY-VE*|xRHkGl0aVPXqoFj`z|4YmsOCwie1!Y@0Vg?k%1t2=$OGC5r!WhKt$jB}U9jb#LN+_s6Js6Nv_wrrY{`*wR|YkN$# zZlZ1up+b2NA1X6eFBh*u&`hWO8Wcp?@YO{Xel=eN32(B zs{-0*9ineGGA39~Zr@yNTy`N73=Gc-0dZ0I@w=(X?~6)l>73p#qKjcCQIXz$ua4!k z<*c?L@nQTb7ew?um^Rlm)X$iAjW%<`k}8ippzXK_p~41`m4fHf(>r6xEK8(x-I+2A zC$qUm`-ClDAQ)8nqez0Gkp3-}P&jN7{kf18v|@JF*TuBuNj_gM{r>5rStRlJ5&8J|5UufP7f+`Kg` zy?qyCYIb&>R5^EXN{${qs?UEy?hM?VCsigR_sd&vy(QOg3~G5lmWi2}c~a%_HIKaW z&O7=W<8r6JW1du*o;xVV-a9TAF5cGqcc`2@K2NH2+zOiejgHMockh*XQe{T=Yn~6~ z-1+Nzu3Lu2hUZC@+dbv-=9_QI#8jcmY3EEocwldt%oXg@JZI&@56{Y&<{8vHmQ?BP ztC1r|ju>6ko&GD@p`!Do$_FPd$p;^Np#5u5`bPTaNtJ<-R#UdVer*HI6C;nx{g5iB z&)$$@$ByY3I3;%myXHxiv8kP=P5b*srK|V6$}@BGq{_JqJ*G{gu|m1ob6vJHhYhJR zK69UGw+om0wEx_Y-l6g24i!(+vr$77n(qq6($o#g?;U3oi}TK;Pab*dv4^Cly3+JH zT>O=kXq|LGo|u@Bt5>f|XJ@C3j0|d@>C^JB&byxp%r|a}Xm_%N3g9|)i|N3-kNl}k zZQ?5hOe)m%mHq4_pN|B;Q8qr2P=kStl*IW-~xmbl;Y*fsXDk{&jzC-Vu zCspnO@}x={v|C2+8BY;t_=n<1UI8XJ^uS6Dy3>c1Q1L z9xj#gxK-Gk_kIZ$wd!0DluKuRsn=oc$Ija1R8`#|+jbu|*Rflz$agU#sWLc>BG;>P zB?*uC2dp>PJdg>@ z{VOF_7`wPWl~_T6hg-L5mHRk1Iu@0pkWc4bF)pTv-9^bLqobTFG^EPbO$2eLU(HHS z|FoR?Xw;MwGGzOfB158F?a+l*0Aem?;+nC5+P*n#HZGjM%)BSExeYgL#9Jwlt(&7N ze|qKCof++GSes%ExMU~^KD}DR+BX z=e_!lK%RIEsRH>@Q#EU@VO~xLORC(r+fit)6`_JlFXTSRu;JlZW1YjZqx~4fE32xc zzOhl-Hf@$ITenGLQY5r&wNj(0zM)aiHA{0#tG*A_Qc_xK^3Tq)lijga z!HR|Z^6cn4B>F+NveIgS-_MgOd8{XLAytYi9+W`1O{OQi^bJa00|df4AB8u|?2Jyn zl3{yq23TT+_im-cN}fil&^T-6v_~HZ$(DAn&WFe^voaac zdDk~BJ2(4uz6qG)&5c-+Oh~kFO2_C(Ql6r4M8>9_JfWh9R8*?GpmQ4Q-(0|^MK)T{ zFL70k+(-XnUZ@0D*oIJ>BmXOEW!jkJ?PTQ0b$rmMm%MMf8&97XK$+pc7 zsZw8GA3vjV#jRWVJ~{GqC=}BA%<4Nhr*ch$JpJf{=J@1Puhx4`+rZKDWSjQwK^{vc zRifTUrM$dcY2L4LWVIA{o26Rkd-7D2Z&tZ#p9Di&wBf3y zsJKz8RDKABDy6A$r~cMnnTfQC*Hzf-HfQ)h^&>gpZRrsXa#-z771wb}>krLwY8&y`DMMVsu{_JBm9Z4!x9 z>9zHSSg5YqF16Lo(olauCTHrj9jZ;aOG+xV?={Pw9f$S$Hoaek-mBKswXD2V8frJ` zbKI|a+N981YVs5pml_vu+cqE2a&6Ufm0A{lt6HY?bEUR#QPD0L8f{SdqTC!0hr==# zZI}AmT~brINBrJ$Z9in{Q6pd9>T->d+Ue-m$l30WSX6{Oh5pZZ-s#dK4?U#vYGTJV zV><0j8&C$w6~DHBP1SytjW=tboX~fwVm{64_n4Mzy(@Jd-&*JWXq znRO9Uq~Ak+2$ez!q$G}UF06@sC3<~0e!Vv?;~DaH+SxeH@6tBx1Ii@NJ8(UKWLsOpQs4Z7_V+|MflmWGckbLtmeAG_myUl+{_K@Ya$6U%9XAPl z9g|(#iWji4pBiL%60f~2vUex`ZQ}=A_=TR^q4O2Wr_}(1S$D6qQ_`B#5-^n=o_Bg3 z1qMD%u~e{D8hwK^DyYRw9tI``D*Wo&1wO&ZdD(IW6ASrL{qtrElr{{I+2&7eeh4P+ zv63>ZZXI%eRc#$IS=3~M^?nYiSdBW|E4X%J%Iw|+SPx-EWT1z-duEIR60p!{h{vV4 zr?9*(kjGsF3e~rdp&*Y+OOvC>O-HCOPF%P=tBc5>?AtXFKbpYAWP#l149c$U&N;3t zDVmeonuWo@E?x=A)=dREwN`=5RIf_`a|-)i^TAnCBbf3G6eU zU;fMgua0R2GCehJzE4h!NmJ`K{W~fZ)va>qv0pLAZ{NNxHK89$dHAOJ4qp3UT)O%r zW<*DUz$=e39Wnq#6?L^_H|wadH!5MDV~yf|iK;4{!2VTb1-h_9n1$fb6Nx6$MH&{T zC{^ZUcy!iS3k(f2XD1ddH0e~tBa?F;T|}mTNqOG1wH?P%zSB1ti>x1g=6{aU7o73S zX*aIJ>H#H-+x;cSE?pZpc^^DjW)?Hto-yzjZ}yu-B=R6-<(jtUGI{geLV5P_sQ#wN z&-EJmLlGnm1W$+{@MUtVdq$3(2uN9p$TN>c<>lA=O{*Q;S8B@iv)548c;vHBMdi}f zn4CCWD33f4(SGeQq)I5{*EaRYSl6SIpme07gN%zQvNti*>aD)0V{4v3+MfK#Uh+zx1}vN`XrucR2Qvloi=vw|V5T zdbl0AEN5rlmeOvY6i3tdbu8Pj0l8SX!+V_YIGMlL|U zCZ>vePGG#pG9XoMhsJjdg6wUF5g3YRBY@R?_rXs^FgK^PhQ2 z{?_mQmK->6Abv*TmJboxvSo`Q0Mg;?$8X5L`?G%-|CT#==9_AR@+&ViNW}l2Xk`*s zNyx4o#z~&hmVv`D%xTPi!$HCOplsU(Ddk%0d_abf& zI4CLW@n}>Vxmvh_`xbJ7{mIJaO&VQ%6lQ0xog4taPyM;aQguM-g-=;`9n8*OEdv4G zQx!O=pzZGT%org!wGQM@RfeVmZGf8(cYeyiWW)QpR2`VSn9S1Ep{{1>HZY4k9T(jB z0cEERm#PB-HzWiLz0GZokTyMyFg~4i9k3c9t`Oz5&mGbOOS){H!*Z~IREh792cHO1 z#bWiFE{`<;@6na(lksm3G7&1Bw=ye*mjjgVsdL795i8W&TF>rn_sN5Mi_8v5H>vX0 zPyd+|mzK*wUzb!?H%KU4Ed9M*GT7fO590c(#knq(RKW`1-~3g--0E{;X0)657|xgr zsltv->VxG;i9Z@AQXDilhKv%bsXky_IOc?ucaAx#r$3@|{-jZ;O-?%XosD`#*BCMu zDKPEe2G4!9iItAqQznQxJ5C8o%-D~W3i1ZK^SF+CF|W?d_@sZJOm=LYl>Wgnou8ck z$Ti3f1VMl9i7Hd>pZuawN{V8#Q?EU9&QUgU?Y>jxsWQUbIH(fp>mRL#i~^B@-nU5F@QkL2bJNdHWcaLMitg4C=dAsCA1O zQU%u^KYAtcetz+@QC)P#zhr=Yj*ts{w(~wjN=s{-aq+blK&f>5)=lYh?bVqm1hICAuF&i7`t0;>AJNTub(u{Wn zGPr=m$OS7URxI*_$|_@(itnuHa2J$Js+b+%L9h9lExK0Py|YBV_sSiaP$A&AzT7Nl z&yAYR17Jqi_(K!3CJ#HmnQN_k>XYY3WM~wZUuEX|Ttp|(6#{vWa@+Zc*j^}0k^hJZ zid7-=g_TEJ8g;%%(LWe0*@np%tX7Z7hE&ackf=6eY|q&)T#Ip2gKspwQHAg8F%TDE4Z(srNyx> z>FDT~Co3#$8>HT^tgK8nZQ3Nm!^3jz+O_ym2ivw`=}}~Uhu^cn9qgVxd$do?%10l4 z6hG>K`cNmKPi|b7-D0>Q2xbkR<8UL3IE|?J`fU`r^f;k$KTVtM> z0$wx}I0#7Ag-9y6-_6@orZ2c;00X{5a^Q}_uVu*OcbkD3zkY6o8z4UeHcA(E1#=Hu z2KSYa84R?PB~_VZ>%icF0x4Y`7@Rw`4wQ4bbwHs3p^~l+2$Q@gUKJXxLMj#Pa=zU? zV@#;i)qy~=)DO32>FPik@lng))cllzXXw_cM7lcgoKW!cThsv(20;8llq^*T+K2qyhx{gXOuVe*rw=Uk9F~g(?!R33 zr#uj4fb!gP?!Qv8u<7&IV4$D#u2`%Wp#tddspACi>vCLyF{VJaGY2>Uvh^Ku%>$`m z{A50Xq#qfWmP31s&D=KQ*&`mWPP&SdM}H*aqeBvzosrSu0lC$2S;watL#~Vr4@v8m z{pLCrJ8t)1-1EZ=lj7HUc(iH|xBZ&X8$kAMs`E;9C@Mj3%xqF1==!4%Rmc;E%VkS@ zSY;&KV(8ds?v^FeT+H}KVEj!jLD{#n*aSbHiFjmcQpYx(8F4Gd??<8uhck@7%nhsQ z3XEM%Tti>$k6Y?+-`X1g{Iln}klq9LS7YM=eSQ;CQsNNLc8uhADGRYcP&Quc(Bs-k zdi#fsqNP~JamH7keb*iRO&vZ528VT#HKS!9wu@gbT`iES*9(lhyN;U(g){W_mHX=K!^&sgO1pV4_quPZI_$@xnj zZI8nFYf@8lqfdW>8ZtL9HzuFQRbFj%OrCnwc}iHQIPUr!m>5PGbTPO%Bmd>y zf90`Wu)K)xC`idtg+aoOJdxKX{xI((D6^#Uc-0`m@#osOe_=~k1I+T7a(XI zPXSB1KFWZVx&i|mi%_8u%WI1bfmJR(G0Rvx;bL-fQs;~s9b5HtLG_IAr+-QX>AVZyzG++oxhMLkca5^#H5?IlCkZ#Xd5P9u;k@AVk!4u z5FXYQR4RDiuxhw*@f%$`%Y6X6zeGX zvE*>i`I|RyHkKF=29ORm4@!E72ISkWt}gSe?Kxt{K;UpcND%k^u!!KdAv7RGY#s=P zhK2?i92_)6h&xYfYpeM^Vt~*NHV^qBC#W00Tjb;SA!6Kl_#Fr?2p{+TC@1A31`2Hg>6Xp&=GoF7 zxR4{!CV=+hoVAeQ8h1MZT(#BI)Wp9n#LKV#i})u%zSNXEm_K^^opl-W9ArvuNkGE- zm$_(Di&q{xSR#k-uavfyBJH0lf9tvB{+Y-tRdH4XDAziVBJG3E^G zyfwjb9a|V*+-G)Nj4&+Idy9sB^ z%ZPKA9Fk=Jp7?<@z^wzD2s>_x30RLm&6NPc1jRT$@Od#1RyZ~n#pk;imY1EjpeUS} zJlsI0$5jck4KLeV%o!aRL{TWAq;?NZ{2rD{?Aiq6!3R9~xz}8LbV0bnj1PrQ>cZi+ zaaWNL@bM$BW1|Vui@$i=)cihXg7h(W^Rtjgk#FHEzz@B)Z%Q3le7luO7S!Q-=aiWo zfV&QSRx!XFrw$0VB_+EVG8i!-anYwIpVGZ zuw|h9DDmh^Za6z_6VH)49NHO@+H&W*?p~*T7OO*tK1T=`i}nVeY;MwVN!$BY&+NP< z3C|(54wo*D%8|Ev<>xPV$$Q88<-++96%uERnQCA$v-EhAeX2+mklgfnY%nnP+dc=G zVhKtM1kbe~R4mes6S)v8j0cR%R>5z~!1bQ&^rdd;<`Td-&UwHXh$5YNFI=`?ynbh4 zeE#$sGCeh6NEH&`FK)m}%4(8Gm7bfwkb%K*bC28Ix?t;xNJPgn-fzmlSln3dk)|>+ z!RApUAKF(c&plBsTiZkC8V8B8=Je`haWNzZt~&4Ajjv^&nGa^Bw2k8A%1qR`3G?`> z5-WO+`g4x<;4{j-)ZJm+6Bk^#(`spQTzzqjeu-9F!tbU_ zMd6q(iYXIugA(bXLy2n`_}Ph9uGhJ*ai`WMHUT(tS1?E)pA)~{v#l92#o2IkSnp|p zOh~G#bj~$5#!sYxcLTrOJUiqst03LJbCKdFBF#eh`>$p~TL#*cI??W@PoGXAA#9x>PG}>_VC!q^L;!m7 z*fMZE&lig!+Q?l7eurlRxde&C{U`(HDId@Khd=zGX+NG9mP(w3nk8FwX;%I^I7dlMN4*Icdlb1 zj6#J$WdH6GU1aJ&q6_~>Bq}G*jv8eXyED`646f2e|K6=3*}bDk2Wqc$^~U7HnL)YO zg%ZQ5G%PW~kp=EtP_lp$UsSd=`{m%?5-BV7s~{DVlOIpW=__M08RrWS{F)mQCg~^~ zZgo3CJHdAwOGOSJES37YklD%A*)=0aJ{*z0(L|%SGzHCl0E7quaRIVSwbtPw9oTWX zK^<;u9p3wJP_FeP6yEHjHKzA*K!~sq0p)?H>}(IneY;8oYaU3$lOIpY*{c)AtqMR9 z)YOnzth4Z7q5%*H?NuHV7`LW6XxjbCjVU>Lc1(s`o_N|^v1(WVUF&dMf^eidIA`jx zNf%;1t>>-oIXQZ2SULw(s5Vz&<>WUDBa2QG7&-oo0(0g$?%D1_m9=oe}xCW5&3+0jYJsZ5nk2kU6cD zA}>B$HLpN>^Vpc2xHu`}@xEy5FfcG9uf5tWJ$DjrSyJ)*i;c2vdrACT9EmPzz%%?* zxc_p)c@&>&@Z9a#l8UAVXE(mez=j~m1RbVV75pA!qXhxJaeHTh0=?sA=JG5T%qxtC zZlDy;#uZpPPzNjsu|UH@kaw23hTB=`;ZHe?dA!UTTVYODK3#c_w8SF;l3W2i$vtY`Hy9AfWX`IkDz%^`RktRR}=Kd zy!)>_))VR6e---+~+Nj`$45cUillT+-rO#SfB(-7fH)IqG_nf~Pu;9{) zt<5OY(*Xhj<$gM#WQT}Y43How%`H%*qg3aw1?M3JARr(MuoSVNTv$qg)N(+8KxlA3 zNDB+{a6brzD_5>0x$9c&epsoX*yr~thXr}C1c3m6Y=M}tpv>*N;zYF(B~@EehUYTyOEt`3ei9x;S8h#nsJ!vv_`E{jtr)?FJV1fBqoF{)^8CVG16ZN_#m@)lNeQep7~p}U zjB*q{b)krS^#!d%%C2&D`uz0GL9K&x9oV|bQQl2V%$fHPl>6u8nFmV^F_sFR!!J)w z%v+sUcR;j>jlBS&vbVKRUVL_8XC#0ybr_#@^1Bta5M#Lg0QFjjZ+^LMp3JbI4&VJ* zzjO{d4*{iCOOw;zh{t2CT&TnIkCn~W&yCmL9g%m=P0zoEwhr_mtF%tkVPRinXa09z z8vGue`T(OYynteQAdtrdCKl;cbjmI4WFD}4Omj;U;dN-QEF?d4XI+^&!b0=>TgGk zWdSa|K5bYn((PV?-B^6D;msr8k?;TLe~Ev~5-C+hzP4U&s*C-`3IyE0FDyH^mu1w6 ztPCr=DRC2ze>f^O?n>X-jET7dY0KPc*FDR}3M;*Vx)bidZg$}@XwJw8gpYXUfhuWf z+A0lO{tGEAT%jAKdjxs+U+aw=UVkKeLGbs$X*tA zAyFt48^)E2CP&FpV9d%o-D4?x?RvC=Smp)S^;WP>d2Eh{T zSLbddgv0VOr?L7697PIscyMocUa^;o7A?bv7bYYgBT|YnwbunWJ6KWnBO|m`dE|3X zr4Kqs9k2!&9CsSUnA&SQAky3O?gIdgGxz79p&hSY(;@+b;%m(^0~k*6O`uiT>!DA-0OojTA*cwbRk4(mMt zRx)3BE`1#!38u9#b@n>f(tq%&4|?OS%c#TW9&;>QQb8Rm^!oGHrVO#ebE6Fq(1u4G z_cPRCSBqB;A1aOKN=9>oU+XX_V{x6Rtpm@{_C@OO%`d0#iWO6p0-!tarAmNHPra^Sr9<CIXRHh*Cdi*9?fK3Mb zb`_g3k}(SF8hD0DT_Z7XSY=*LuE2C`Bk^3h-o{wrUd)Ny#{!bXo?i^eB@iSPI=9oV zRdH)1o~^w%bun^`k!5`5`EwrS3;8O_{d$exoX5pjNs;yq&C9}yE=D(5`Cb`R=L z(CU>aC6fsiHgb5RwXIDyZ`tNtuz^rnS!Jwda0dnviVLvSb_HgMCHf!ZN8bHc9_xj4 z?!O4mdtg_InbWex@iT1jaV9^rcGEs>6Js6YGM`!JxX&@3F%D*eS)b^b!?qM-4k&$D7qf|yxdM3y??G-kY%wr~(zhUD zxCeQ34`enV!$?eTS zDP?^&;m9EVxZ)PM16hxD;5chlHeV2@Wnj>W<3`ybV>pl8mZ?0sz`FnX%8Q@TwRYH8 zV_4k0c~hT>{zWx1g%MUz15GfPc=3TfZIeX!(eEYR; z%g^+`&caT)KYV}u%*H|9Qe{1{jF!e)WpEe;Yy3b8#^Y9f%ePWVU#Kp#D_*5AB#jiX zW0_#Nvk@`7b&X;>5S6bzpJJtwlJ$G949Lfw4pYrwg@OY@1R(|`(*xVmTd7!Fyf!U= z{+eUPiNM27SOk8{ez#Y|@L8G)cC`E-|Nf3l%{ikGF2JZB0rCO6hJWRAm1&jv z7JvGqez|tXQGikhNQqt*%n;TfWgg!jN^7NJ@!`i4@}qZ0&1VEjcJLtVSz@SN7xlln zNF4}j{4c)WKX2{AE_Q@vYbjF|n3Lansn)b@Cj6W4_sPuxN5W?3a3J6@RuK5NGr z4n`gDSklw$#5*yh%;Dm+mNpi@cxOb8o_E@ezJ%2elL5~$QHRVg6mH7C^YdX-hgW}c zQ_G*liY1PxpRJRI|XSSRng$r4ouMgK->he=s7QL-8+hVCnYkW0mo536z%x$42MJ^TZ5GkD$81q0*7Atye zfh#cW#@1qmyKv0-c8>!B&27=Lx=5~LHi!??8L`CaoUke!jslBV;t5^vaOUrZre@i^ z#c?&UQE{`gLvCEx6|%xutZ1KVYYChFuu{+$JLB%pK;BX%kM+XpS*mo-yZ=fBmX#>! zP<9Z@%MBDCSZ^+c^cE|HXw6yN<1Fa_t|S$=OmRU1gkm zCOifp2Vgzy2Kt0_?!k2nzCYD)7tE;=UI#Sd?;9TeWsr|25|$( zPn;MwU)cLW9vYHS%VpNHm3}j~)K;UTSeY)$TB`h`KlnTH;Gz9V7Ag0-rOHNB{(l;P z?7rSumZge5h?D z|JXH9ZFNl7nIbz>?5(R=x)0kcSdYB%?x0yuVy%MJ3aG2`nN0?(hZQ{E_3s)=sr=5q-x1j(@~?*e zmAp9pV*HGQ?Z3HQMqYKS65sEAUs|Fq=JQ5E-cn_~u*}ZBRbPH4W|YP@0I54cwmf`j zbqN)~E_hNbMqnl}J9|-()YlSA#Zf*nr=sKs>|EWoHDq>m8l<`P)tl4O9gn#I8NyCs zlwJTmNn4%I1fI(T6l|w2JHi-5j@fBEnNaAJYu5XArS~!F{EA18ogOm*f&t7q$%5ee z_w6cLRJnHP`n2?oIKOFk-Wvby3O2>GXdSFy*>o5lo|BK`)-ni}esFf&Rfjo4Xjl+bc;C*Vv{oV(=dVo8Tg#x(;vPER7!Xu`_a+?-t1~O?dFB`6 z%3Y@p4jBPV9ZEg2b8BWogPlspKTfz1Bfonm6m__NU$OQ(=X^4pa-aHmT;g+@sRQ|S zzBIs^XV>Onk^(pt2-f0_yPOLnYE!m#BlW z0C3&QCKk0HVmTKd3#_GzMYa|z?1183Nllc|lCz`ZESw7@9P&y)e+Iv~2*?mvDEL>l z<0vyIn{_W~2^GfYFMhTrE2S2=e!E1Ub*23By;?bavD{duV5Pz$0k{_s=~B9D#wH5n zN{3I5eHf4nSAF{3Bju$|VD)4qzm&A+miDkwN<^k2%d=P+%N)F(-O<*ng!zU00Oly> z`)n*$a!2m>L;lH>xLvyA%T22R7KJE}I&V&xwydnKmaW^i>-|^h2i6FsWo0rwHD&yc z6Vrxw6}i!paw`FIe?kWI$VB;E-cluxb-`kmDrc`gB$qqNJ(aC>XUJmb!W8S^V%WX|KKp33?Acr*h1$K+-Gg`t+Zwn>NRKD(Q(fw8c$|(zrB3_FH$LB}{jk`i_Ij0h z^#1l9Aa$+d26H_!gxBZ9a>J_w8_Xb7_zl)m5GsCOp-fFiWMX_uZt zS*lRqOev4MgLKcrrnSOyEL9c~DnVUqdF4x=tCsSz>^6i#q?|n;l-G|G$p;?>rR$DQ z-(Rf%ow~Z~j&98T-JR??{*u4rmdJ_IG5PT0m<$cajE*xH^klSR;n!G?Fis2(&#FAC z=WUpSv9Ur7hX=$WhOt* z;p1yshuTCP&R$B8Dye{w*wU;*b11C&Yvi3%RpvQHqFRS)=Q-d9|Kd&OnWlnLSyIK; z0VQB(PsMy4*fsQli&RMkbvUrQST5cuO{&ADrZE+Sowh%z`7NoE3hJ=EEg)WhNS}jK z2l`ThPVBXn&aPA@drPXMf-YWP?vN_SPHP?Bt(6b84m|^t9Fi?hI63M>%Qkt(e^j<)F{GaF;S_Q@{exwJyBMhgvL#lQ0*d>v$`)a5njT#|6J(!V@3eJgg+FO- zTTLL$8`n{DQA4Oe_P+E&ZN{CMZj4U&@a(0d_+MvJ~ERVv7+bghJ;MSN+wreYeTH8?sH$*x_2M6DJ0my zpkwV=Tv8&t_UzN=v3hd|_wxIE;?s`9^Vg2HYHd+oQ6a-agW7MVjjPe1jxEMT%LhmoatsmFwSO8J%+EQh>7OS3h5;GI)uZ z(@4c(uWV^A(zS_CKDs=X6RAQx3%l_PprpRvD{6`{Qn1_qg(t>^%xR1@i3Sa(UoDxgHPC zr%=!%)R+BpCBSX;lkSo~ONggJc zLM@|l>8i2>qCjfQ)1+`gg=#VbT>Q%K*JsOisDl|Hkn#iR4oqzW&{fxHj6 z=*9vI3oSNoV&QDQ>+ds<8kr?aC8{M=BC`?s{AZuu(4-1;c52Gw-a@)(NLnd!B~{W9 zD%&@QZ=20LnD0xYeLfW)SyJBFUe5PPYl5li_XfI?*AP*`seRU=YySc z+<#nNntDn8_)q^>{`lAb*jTW9YvNn-+mpX-erF@%Q$ea=`b+?9ggzFQHsSgsHL-(| z2^Zxx?pDx0=zMBk#ARUxt4dsZVWpA{Y0}e&u*v6^Z5+i?q)K^7licio#MEJ8s?g+zOxU?;AS+VE@AZp#pOs6U ztuj7UWb#sns`6=Ru63*#mLgTkN_NTln+IihqQ(ehQ3;s7w`WVgxn?O+r8HC|cSfJm zXHhTHvrZdA>g;S!)L|)7r7&<<&UI|p$)eOuW;~0k@~Qbc-07QLlvF7%YLt&VA2xL$ ze>9d{hipidf$8VuW^aRD6IS8YYwECPOP@|^PTMaNfo4OhfYl&YRE8GftK90ImX9usnFW4h zy)M8tf2QAEEwt$GG?zPWQ@-@M8bdBDhOr5sym7oq-aet@c-$f-mjp5$UkW$7y>jHZ zW2RqUvv}+k0{lZ(5B1}=FiT=Z1#bRkB36(Gxjr4S0^xJ&EUuqsq_l)MHjB3-G3S2r zD!bi0a_*v&y6=cIHM(Ub=N`w7d*s-O#C4=neGN!%;Ewetuj=_riPYWWk*0=h<*)Sz z1R_czg0X}BhaS*=zp_3LiBhb>X;pc-$}J`4b2t>zL@@cVKKmjm*1y3(K;@RGE|@gM z^X3W`z!jBM(%;vs{lN~UWyIZ7Gc2jHv%N^FtCHPa_YKU**^6U_5Gl}c`@o(| z_n1+6(<8e#7nwL@4yYV4IwNxN+PJv~vQKf^=grgZgnAtM7;mU-vn#{h_rveJND z@0`-#Mb?O#Ig>VpsNxt(LEZ=6Gh~&eU`dtoveFGjsvw)CraV5mSn2c5g;YsLs62R} zbYZ;Z40!deQaSQou?&wS;&!>qoXg+TluEW(a>WoVvk4293zvznt7AoN!g|HItAm!t zpw!g{WXC2Q`&0()h|AS$2Y%gMf*i1dtc!th5EtaE)v(^_8+2k*17|$P3TW1}GxHY2 zN_nZzcr#+0#(ng)jtS{ixq&n@JtUEtk7cy~r*g~#O!N;z5P8uK5xcVU=877=el$_55M_8FNf(3p=*|l)> z#-#ZSIkQ;a1z7G1GLE;7=?i`){$&x|>=OCK+YSk{G*(!s33kiQyMxo#Ar#8ZU!+C2xK2t-OHE=h$`!O@ zFjQgkr*FqBQ0SC_c3e&wVg)7hby&`G0G`4slYhDG81+=omti?|n4AgC_l3pUv7#~{ zg*rjxf~MwVmXt9CLd89{;I_yePvvd`a)d?5}DLS_ccPN{Ff9 z2J`aGt|=3Ppy#7&N*rgZ1i9ka)?!5i-d<$wD(#d7qN z-w@N8uzz>4Jo|W+R0Lzj+LL#l=VIH1X9kJFc!8B8$01T|d=$nLN3rcZW1a^J7Vd$( z2JoRy;KP}j0u|gnMp@xLp9-GS;Lx1>@MU(aid0uRzLZIW!ybA2DAq$<>C_8C5}TJScrNL# zNhKfF4(Teg{Aa>?V7?v$$#o(nz;7gehm9EQc<$<%mgA>KjE;wPdi%X0vth?BCX97s zIHcd=dG+wPo@Wl3o}Mvll~7T@5K>HM$S1g$+_Sw%9y(ZR;_jg^>>qN8~A=;Qk<%;&X-9sic`td^P0 z4ajBIy;p8bn!k8_fKXvRN*xbbuhIUv*~YRFgN0wd-!CUGjOhA|jdwoTv$JeIL3Y~> zlGUXX@;9z*lYjm0RB4AJSSNq1rh|SlS~Rf zHaGeUVNoM;%Aper0}5T`@Q)zSNyl6uL8vyDKh2#4VejQ`Qu4S|KptMkcxD~3VoCLd9g&FBZdnB>4|xT zuUD0)&G*G(Xt@CygM5K-NdF}v3ta1*GUSRIwm(}!B^wM32j$OS*)BJ3m!u^_+zF&R zo|;mx%N39*FTWL(@BBElD6xWNRMx~wZ+c>7G)}B=-D1Rwg=2Y1V+_SoS$T!j)Yiq%=8nqpa;d5)7wwp2l8;Zmwyg2m;$r6kdF7o0 z^74`WN$HLEcj&vb^t+cQR8|=jdD+EYQRa2Pa?6*JXVKdvpLBn#s|gq@73Ku2Q&_Vg zQ(&kyqapkwUV^+~+L8!r$B7Uis7SiTuz1zd3pN^{63O zQelY|>VCa*!VtY{58ASHi#60&qJg@q9p5r5;r5hR=`_eQpi_mQcGP>>M8?r z<=TWHx-Va!kPki@mhZiG$B-*MgEKmoChkYOO-)CV(x$;;`NoZQ`S$T$a^u{8Ap_k% zkm*TXux(J>T~cM0(5nk_EK<@DDJb~L{4uF77P)_uPd;;~NWSn$iG1_3mGT=eRLO6C z!AXDZ3$^mi=d0xlk5f`znTLAN2-Xd9zY5AH9Pt?i+- z2{$6?u^}6D1^A@Z=hF)&Tqfb|yDO!vEIU^!Pd`&<{J{e=0cT05KycVV`T)h_S^zTT z`pqe$DC#SkYYzNl0M=H$MXLV0qJPrmSQv3&j6GWm_?E95s{C^zYwpR16sKT{?z zK3pbG?kkdgt$t~(ER>Rf$B-@V;S_}_mMjn~N#siYHIY!s-g#>)QZT4vWI<*8?9wO< z?o7%b4u>U{10fPCXh_OWqQ56$3E|8aYEQ~<>fl*g$X*N(D+Iw`%7s=sFqgAvCU8D( zA#x#9=&Rj55RDVY;(`VFO_c$#vOu|y4_U|+j&pr!xFBmnrK7u4e(?G>{f*pRec1#S zJH8TJzgZ~%`g4SHEr1IgENsu9D&W*~%q*vP7 zcgW6N2a;0z=7+@_{H(dox&ll^o={n33 z+sZSM4M3_`<*`k9l2EV8|6(+Rrw*i58oXH%Zol<@o6W`IEnl$v^v(sJ!uRRE83v z%%rBmFEeB4bv)ABzn&XKX}4v(`!-vKtdJ=f5kREyT-|^`DG7L`UdP1yb_A$zXRxUVnX1e*Rj&{P?wA zdHG1MAy{61w@+SsuV0Ry9hMJNesL#`y?tuXr1w6&B4^M1nVk9HAIQy%|5!!`j_4Sl zm5Ziz!`+Xma&`GJRah{hY_tn*iy~jlEbRAh3CQ95O60l6%H_fRrLt{v*z8PY$78up zs+f1;-_1z{dW?mg`>HTu)A3luGYK=8 ztR^mBcm8hOs{&1X?)%y9mLwq=gG-QiA0?HR+UX<9aE*DW|tHc`gJgi%6NQhX<=b3` zGtVWaN=5mm1?|{eJDO8Wm2hctJJNnT+nksxD0WAtW5(})wF>W8tMuq1b$r}u<8*lb zg+|%7-LX<(!p((HaW8VYj-B?a3CI*&bTOXso>)LCm-?f!uiY>A?=F%j9w?E=A1IX_ zn?usp6qLGZpRoYIRT;4lNPOm4eYICw8-03hQ11Tzcj z$U9DdLCNa&ZU0FJuPF<*CT+7_TS7XY6v+Kg`~zuhY@AQMy}dFw^^thyZkRmGdyBzBZ8+l>dCLL$>FMSy0F86};B+d){n220qnKi-Omm+`OJKHG7 z&NP^QpGyMS9J9xl3!9%t=wyNwn(2l?ztRSg~Zjfe$a2; zMyVpQNktCg*4^sz$d0Y_D|0#tZkg)B6^~45opAXTO5p~%PG7MN1xP^ZPO#mIib`o{ zY%&YTTmYd039{ONpuyMuY+Odk7G8a*)6-Kjp|T0j-i!syimgJdHDvh2@8@Hxq_mdMe^~*F`1Z|TXswp=8JPzY&;Zins_Ll`Fkvk zsp23hri#wn2X<$OsWLia#_g|uu2vpCRGCzlL@HS{;fm|F_C>~W>Vz5wd62mQ8H4(; zi38G+zpS6|?H|(MhWvQ^hKSZOS8$^?(yoC9!UF5R+MbKY~H5{yk8JURa*cdZo#rlEzICaVyuB_;Qy6()FaTC~65Gkc0pB&g4mPZei$ukdE z%7gnWWUJ00O*;28kCc`ArBr3{qOjMjkI}J1Mz=PF zi4&u8>GFippN~z?N$=o{ymNd=E?ga#^P2d}JTj^0re~uvr0v_Go$#YLs8Ks8x z)3zKywCvjvlrKJ8A>aB&gS_-~jcjZ1OVAhZfr=>=hEOhb+;(=et|cHd#xSL?}0fY*;)jKUec)izrPQ|vJ2PGUXHYpXUz4*+j6DrSTXTfDH z_Rl<)fycQMt&3)L6ft-QMFS|)*XvB#rN$Tyx3YJ)VGiLLR`#oAI z+zQ@2^4KWArCw37<1v6u@w^AM`tFsM`sC?Hoeiy-aOQley!uwHAt>Da+xGFrzPpqA zocnXO$xWEpzcyKG756cF+*+`Zh`;jPAB!A$uSC}~Wg>GSDGvo?V0g|1a$kSY7B*!M z#w>K$#I$m+kBa<-a$s{ve)Gjz`P;wQs_VNt+1y^L^F3?8+Iz z{*Q0(mQ4*|>AN*6moHA}bI>N#-=_=^+_(h0cy(OfdT&r(JJN4rXLYNbM0_h^w7mBI zfOK`8mD^YTP{xN(#DC%L;hwWpLGT-N1!FU0N-!!9>CufFix6N@k_OYJp#Ho<%Hg zsiMeise+YYLoUKsF3ze z#S)0`SYV=9388`&-D)X&rA}XI-10l-uf?4^cXF~+sjPoafZPjb#rRSBZZz3aMStt&?Zqrryi(u(8#seq%cBRoP%X;*nWx$9anteV22!Sg~>PR0`AQ;WIK( zTeII-U_i7mM&L#S>t$SaJoaF@T)g7+sdkl%D$BiQ;|p;``0efPTB=};(m%); z?t*pFU>Khu(qA(ZKR8{7j zCs%|+L7n576Vvylbf8Sb!$UeZPnkYLH^-$*_Va{u9q+d#@Ic;DC6D!jwNz;hh9n@) zobSZznwG+8#=Sz5EG8$$P(sBNnTsZwp z`S|27q`UJY^Y_E|ekzwQeIQfu>xpyp<5vpwJ($&gpP0uXRH`aM@}rm8@R3+o-sz3X zFWxNFGWzDz9UV)nbX{B;4;9FG`IA?%h*+3LbqP^l%eu_Dc4;{8Vy`aYe*Q-Kdk*XG zwK&VRRmUr@$K>oeEHl#oHud4Ro$~42ud=go73ms=E?p6M>!>pirCLIMbUGrZ-k+A9 zE**ykJSJVaHY=|m8Ch0(=e;qN(V{B5IU7Q;R5|jO1u}ZQOa`xqWT+z`Q$<5bmMXI& zKDqK{nGD?snQO!!knznWQzGVZmIJ6pL%5Srt>>vclYHjGCBj|4-`Is!dTRi)3YZNfTtu%2QA zMi{+Q{JD)!@E$rA%2;#}X!)ATAS~OsgghS6IY?y>(xA$J6BAJ*%OGP|xdu0tS97#f zp^Wa7$3mpG(R!p$Gdj{*syM))J1KdtJI#rt40}jdg0<+RyIe z>8?pVm->CF&rAJH{Y*mUbbq(U+$j?A>boD3>8YU3sf98%GpqBWbM4&$zq|Brvqo@S zmc;GfUG>}R>cGSIDU{&ek#Al=KAKu;k$a)FiW9Kg^uSQEtbFjr7AhN*)MLF z&?u{Kb)8V6@oQhu^YQdmO-(Ap-|7-Mdw%8P^J;(?Gwd837<6_X5S%{Og&i?ZmJ^VEIjAUG z=pJS<;NQBguHJm^i~Fz6&k=dt%b*XlIftF~>2TknCycd9Q>(Mt$AQO?$&1N_$=4@? zxS)XeQx?|cmtBHbD?JF6H{W5WZcN%*rcJtkKMG@!ciu;)WUP(pSnQ13&5d)ich{V` z=D~xE_fd1r`zP7ZdyR5R}+lQ2K5MWPBhfjdek3Z4S-L2*?F&~E$1O+B_)vSp_(woW>-NI|qhW=0#O^J=B^-3jX&(J8~-0l&TQ z_nCj$Z00spAdJPKt;O=Ue!W=^AF9;xIQ<%LA=3XwE?^ACMc6k#UoQu?mP%>RYu1n! zjKAf&w#3ae#0&1hh>?Z$EHPJZ^-M|k^?xdpW9Q>J)*tr-sWLKxS?JWf;)0#9+iN}Y z)#t0$iA({>!k_u3|Fk#x7x+1*}X8{OD;f2Lnu3XB9R8;q>B64 zg)7c6pO;c4mvg-ki}{R20lWG$q2u6!sZX$0Oml3597g)Vb8mo$MKn1>l z^IqY4G!r_z%jDFBx_PC)B|ui1(%oyhSS&B+SZsj5`bAiVN7IXuSPeJo_=ddZ*96iL zD=05eP~c__utO;w@Xu>87xkDR_Utr8F0?rqQ?Xt_xknkXej)Y=Bm-nWN|coV1*26m zy7Bm7>cb+_`F^)S{1{;4g;dwnnuTAs;96XBtrrMhAIL(P=0;I*v01=c<*eJ{WO1bL zUwPzlH-UVIt07W4V5yP}rynyf6)ZBW4fJ&xcN*DXu^1{RPCNJ5yK7RaDkHLgk54wY zd*soFMCZhqoIDeij++xQr0aDM3eAe&H>L9hECNpYE?slsC1^_Bi#iB+FbRBt!kBa`k+zT)$Ky6JvVp zt`RK!uJhZh#jbZwi8}~=Q)NK@#!C(I{L^(>_H4`b$oTNd_*LtVm8~$>0qhiT@2JK)t9q`G`J3*7iCyLCq=~IQtPjV}%JF0Cw#M8YP&+kIJ1C@7yV!*a=h$tkbNPeAA8AQE%xKw6HKho>MkpMSZ8 z#Pm$T{5_U~s1(oVUoJT{Ig_ZzaxfPwn$N#nYZ;4;M5u6o3*4k_tBJ{PeWm8Ek}0WZ zuJ_5WzE~v(Hu)r=Wwhw&o!RijN=ZqZ+<)Nj=_0I6!r{846bf#U{rmn-+I0WH|4bfw z@IO>RrcP$&YE0_u>q|5eUpCsH~xE_1L~!? zw87*b9rq>WXIz_|nK9>vXAa2qk>8U?pZb0I@{51Zq_2PFzm#X5_%$gp`Kx7OrXneS ze}BJmYd8}rl8MM>xjy`RQnTqlna@x9^{@W}DJ!ejj!QkNWoURR=^m6}X136r>l*tN zne+ynMTaL)wP%)ZDa7>$yJWy||{pI)ynM<^R==N$I#XC9yf&PR+`j zM+b~NfWPh%zw_R*(IXQEMndx1`|UawI94fc>l9!==X%U0_qnwI_q7WT($Hvu{Ke0T zb<9scKB0v02MVOj?*x$rZeoQ)q}qP(6fV5%7#qgq%7v zqT@E314PEgqjKcEAss_iepEqxVzNN{@j}rzU97rmH=O&TSOY(N#be^Bq!KGOuf6VW z0}{#3H>G9e=2_(ePpW{s4k#;$`wz+zKA&I58b|1*Ur^_zk=zdMIAVF^aW_F9wkaJh zop%%k&fi2owpMA2p{;#;8d4@1nFtjKZyS`}uj4qDD()C6qhnLDeanRG+Ln2}V9Qrl z=Deej;(#%VH9l^=6YJ#M#;QigVD0Wgi`>-cF&2xs`@$UrH6oUkWu+w2V20-12F<1E~=)4dLNT~bpX%R{=hv}vP(d4X}g z*jN*I3c zklgO5k}KzGq^GOc5G;2ClT$I{Ld$|6^bhSUlizx&N#~>0(go4hPJ1sGTiU|%D=*Z^ zzRe{jwo58l2bL5S8uxR=;zXV}d0|BQx?h&Lxx2H&&C}i8eb-hMmydr-{_N+MO>nP{ zo0De2zH3|Y{33fug{{8$?nUjtQXP!S3r|%_n@(`+gXE?$-jr z*~x%Qi;f6^^eX;@+voh0nrZ$5`YAyW>Em!7#Sm1Pc5 z^SxIFd_U>+gweLA@~0&a0}BA6txKo0NiGM_J8nUe3mF=9TaqR>+=L9b(~PdnOr z7l&u$8=rNyKTYdT|I>eeCv6=-k?%qCm-15&iWG4Q8q@u{TRsVGq zlRQg{Z+!N=xexf4f6*)58Mv=dVMxp5*yX#Q<>9@2>QrU`0KCabL_t)yO+CO{?~TZt zXVVilg`Sv%z56AK38(8>R+df5OHW-gpNT8;Z+<*D|Bi2NWoOmG`Y_0EL_($17nR-Z zetGWk%nIO*fD>mYh%fz-GE+OB0ILkjPLr(dL0Wp0^?g07thGh$c#)*dS!UHRLd9D zd01t56ZJCmiqQp9b-MMGaJ8n?+?i|*Cqyl|Yl-s!jv`}}7X5)>D&#N@+|JZaCZ6hHoXOv~w!&ps7DkPfakBlg-) zUPTe_5GuI+dit^WNf+81o{{2UyUs7Y^XuGnKoM6~T4v%rMUyP%ogZaB?!I$JPJDPq z*JGLQ!yJ8RvlCx$!mEA21TXYReU(oNqF$LEc1>D=Ss9(3k{O*>!vWmUg{AANwu6=h zc=frBM91|WQ5|b_9;^+>+;laogDFbf5aOG8`vfaL&MOw51Ez_LLXn9J@!+L&7=c^gny}iiD784UQGBu&^N@cNe zb$+vJO2VOle0({1@h7}H7Yx2 z@8u$QIBl^Kyz~B$oV`3M1LHF$wv`*WUqtNR+FqpdrC0WBDVEPX_g_j;+4_&G8!k{i z%#-#xnV5`7|B!PGi_Mx)RKEWCTC)&eA0$6D^DT>h!Oqq#twF&P*X_Pp6U1KM8>4(? z$16&hT)>XVAOFG;7E4_l`F`=X$jLJz=Pse7b(90qXrYXa*2wT+vy6|`=wP*YTUmw3 zO29&$fdN2ZV4=YvX^&+CTLuOj?#DgIpKbZLhP?bGKfg~|AZHLtIZnX)mb%fjf$AYb ziUarQbq=#^i2#di0@W7d5TJyW21b}fZ`+f6=505_?VZJ_#+;6BYC zn6HDo?a~FRX90)n6b2)%#o8z6-DJuDAwt_(qz0;g`{cNB*Fx}N7F82d+TmjXsV?6& zPb`JQi4~4h2ZzvDEKogV@D(}%b*Te&vB)M+J-;3F@7Daj1;YWCDm09nRu^&{+ilnH!>hMjT;BW=xDce-u%FPUTZLC)7Qo)QJ5DP zf80f(Lh}~^j!hFbIQ`-K%Z*>|boj}U?Z$eDxy>zLXOlp#$Crb}@^a4h84}~7{X8)2 zmA0l?DJw~t_q9#xY65cZ@;En;N!Mlo+K={RBML;jZCl_7$;3x-0^6f7r)b?h%sC+$ z81zW@9gof>ex2|AGBWC&PxW;X9ghno971lI(_?;_o({TzG^ zxVZMD4OH*-1*Cn;Ub%Gsl#C8Lawtd*RF4w7s6ge>80*afsjRLyYbpqp$n1={-Uh0N z;2_ximiEF0o(_gbqjIB@O#{S}Aa=@}zMDR|e67F)X+M8i<<>5*jx`WKQ5^%FH&P_u@%=Zl!R7(K~_asqfVrj%AGb9g3J-OfwFZ6vgy9=LCdGx-yj)@06mVO4+-6 zm+aWSO}1>_oHqHqK51)hmDZMKX>4qWr^fluP5PPqPe1v%oWF2M=Qv!gCFW?7ou~I4 zxK9d#A$?YrI!{+?s**x)g%tS8#ILf|dS`Gk18oG zuF`v#FSv(SzZYx$oO@KJxkqu*J)*HPsZ!alsmyVHg}IF2hJSI zra@gZRkG9EBhyo};tvM2uNRnjM3cJyt*zGex}IYl90;Lvzy+zw9XhX+l@_Y3>QPyw zEbBn^cMIv-m6XTEN4n=mS}oi#f$EROzd37gWcG?8zxcg{^5U~KI`+j+reJWSM!Ngj z%{XKex)~Cm(KDqUvxz#`zv&W4_c!%?y6^7Ki=DHdv;Aw+V&x{;x<(0TKN*n0{;-UV zpm&Svxa<(ttBq7bC8YAjZ+)rJklt$x+Q(_5<)Wo2D794q>Fb-7@u^7CI)Sw#eG>Tz zmtbsqY^WHLirQ!5SF9g4oTW-lRq`TE+sY6sFTGGJl^K*3tB>R+G2fQaN=HwO%8@hU zG8td9c(R9EVV02PFYhL4lOZzU@`UIwc$MLaziizg4o>&$)nn zHoyBm*}~?tpF!&PRG^TD1hBC8Kmos48LT27AUGKvdHh=bB}hMmqy7DK@Ozzmux7&7 zYAU#g^EX2o;`sp!k5t$)fOO?>=O?%xWS{NRcJR)&4AjBwsMEjpQf^hK3%P8|kgg73 zu`;CAA(gELpFwG8h3_`2nE(iM8Z`CUhmmkycgkdFLtlPMONNRom=uS`d7%EVNs zxn{Kp75Y27>@A3&^7*IAHYD}U?v{+$#T*TlcwdsuAT z+9-%bB6922t@t-tS4$NO#ym)Iw`(PU4tFUll_RHG<#K0*Swy=@m2?D4Cenp5iFQbL zj%4$#1dHY8T{k^_=PJaE1gDT&+?h$`okDnfq4?h}}zA2B)#EF%~ELCo+;E#|D z3C%G(7M?saVs?Q76zI5J1B?S$D*%GCb5Hw>P#j`?P+8^^e4{U>cuRHbmFZf0ovrC= zEAv(Y`X>sXTiwJIo0ImOBL(#i@@unV=*B>vAK2}g_uZF{e+B7OzV5>m7!ram_>Blo-<13LR}VMNHII> zlW=%c$ID5FD4u_N9;k#+6G8^$oZ9GI8`@{}l1ix@7nFnsaXd?ir zg0)I2+UlN{^3qn>u^p@Y%($pG+rDi}{2NH~!|_A!9DPrI^0S{iU*ce1w)omtzGxJA z8yXqf_4L_~<-*0w@ox+9>%aO{*|U3B{97EEn<@$86NB=@U;Mw~-x5FuVRHv_L^xC+ z+cp(xUv<`SkS51Y3~T#}_F>2U7w$$mM}Pm|!x6JV7D$k-~Q%*w_z+*-2Ebt zPZyT6MtJ2He=2|SXa8@rVT`_m6&Gl(3>)jgPo8Kn$Yw^Fp{TVFweYu|(`@7iZ)I{4*C+ckL7YffvRqeP0LTnOu@~;G` zgi3u?K)(4xy&0p{AIq;#=j|zZ?cILq8e~&*{GbA_R$*N)Zf*^mwd6AoRLMh6{xfa6 zRTc`Cz=kGO821~(_a>oYarDH9ym@*;jJ2%-LZ!JrJB6twPo8@`L7<#C;{>MPx5F<@ zwRKs!_X4XiiQ0kCeJ{Re3!BdlBKGrg;l5ukumhN_PqwhX=la-X4&+^K zeqieX_)MED7xsCs*1=9HAT`877^R6uhba6o+CI~beIC3RbCMPCUuAJ0Zbg8UvFahhqz-XU*bp5#5 zZC_OplArwCiThzm6$lk#s1SSV{3VA}*{kbK8$$&QkIWj^M*w$US8oKRuplDURal_} z<=Ty~%4Xv_?oXQWm#GCM^Wi~9gCAVtBpmPDkpq+=B#}GhY2Fl4dkca_{P^{@1EVxfyJ9?0n(BxngQ=A zcw@lgggF&UmD(!5af^nW$c|{vGshy!uwj;F?^Ia^*@HmJ7PZyQ^0$8H+sh_ZxGvW? zt?BweI&htpH?5};3-`Iy7^|GKo*>-kmbzcMJYY5Nw^W|hzF($1V72bI7O-VR2eBA_ z_|rd;Kl+nDl=haO&I?hw(>o)@0k4$n9QD!*HAab@4xL?fa;4L;QbCR+rLG@ z;TmagY?9KVrQLf0_rSFp;9hp1SPoXZJj+2g<+tT@r;UV_JcD#t>HWyR+GSb~@LbcC zdp({zf|J`--0a+dG}TWpP!28^C?#iRow^nKqVm{*BH6LUQCMxP-kcqn8)_@Pa{0#8 zd@P&k>DauBpu2@AG{r^tD`Fj@`Q1X%^bVHsV=hjkFNypFi?A3Nnkl`>#CK3%LL4jdn<7G$36!r?u~k z_zMf<(4G=Getb;FHMjdOk2JS#Gh|BpmOXN-Be84WqhqbFI59?7>w4Me-7Kw}ACa~# z`=p^|hm=<}nZKl9QIYfyoRaEFU7Kpx$F&s!*30!Zw}cA7LZffMr!r%quEBAyL2z(~ zC_u@~oCvT?92_Qyw?}qu_ZXt)dZ$MY?ej@(wb$&9g)rZ-wOGdzuXNtxoQ_Eqh0@(K zEk#A%_!#Ygce0{1c|6a>{TD&vxpqL0mloraD}LcJK-=KbYfF3lz!KBQtFJSbIYdfT zc}(+r%m$76+V}-=)Rf<+b@oYhbwXzN?*H>w^2;~hlJ`G2uIYqH+qQ1ew#VgZ$`A83 zg~$&pN`;wITyaVwXuSLTO46M>y>jlt#duAU!JM&g z&u*!$tI4LBq@(kuy!y*Gq`j@xC^ctir{vlCcl>3pLGHjR zlIP32FsL#k7PrPKR?oXp6fTtq4?eeS_g~kqUze_~E)$r4If*_&J29VIB|eE`Cr+F& zawke(g8y@zYxw-pM;}Q`ON){3?4}*^aGdk?_4P*aPvRVZPoF+*HU}Y_ve^OIo%?lk zbjan)m!+-EiS5HiDe~}qKltDS^SN5(6nj7NkpIk?Gg4DiW7^4!My#!Cez1lqE7rx z1;5GjaKH0>w`(BxF`H~2cbVOvLAvAi^HSfJ``P}bY{<@ab#*4u7wJE&`7EKvHL2h@ z*YHk4xR#YwNLfj<1bi(rGhHIHGq?g}j$YV~nQ*I{SW@x%+FKys`g)78zPtONy_`17 z1!hBCxnFMGo|dUuXPwSnAXShxD$0C1A9Q_g3ZzP1O>T;~)kNM>W$m%nmMT|nuroiVi(+S&Aub$H z$n%;bCpXmMYR;P!)6E1^_r;{lAC)~jiskU3h05pe{A{00%{Z2Cj2R>=EZf~^YXvM= z7-t}(mXZhD<5?;=XBP?lwJFp0M-Pt5BbriyBJTS?>yhzUj|^*@0BfxR#u&5iOea~U z;L7Ug@nJ)*JpVLtu4qfqv29weT*pEuDy_{ysjCi{1z&os{s_0q;^C@-U4+JcPsfBr zP*7G@$*w*4tjP{zMls+7^rhc!YHOErG_Gri>o+=NHm=+#Dt30`X9KQ(_w6_JlgC)9 zKzugE$+rYDKmWX?N*;F$SgL$9`?i#H`NTKnjDfiB`VU@ekU#oY1LD`Y#j#Xz`Xj;S zAyp1P{$i5*FDzApwF$Sh+x0!z)VNKi3tlpc(p2>HU6S{X|8w&hqJ&`dyx#kEM`UO? zF;85)5|pv=LV5a8$MWLHdk$Ig=tB^%6K1{yqk7GyD{Kaslg~dV(l_9dH{UIg!w09O zwZ$*TP7LX|E%M-ja{2ii9%I4r)Wawn1Mg(#_x#GxB4lGr^_k$nBzb(YqUiy+8+`ljWZ8=z^ z0a8va(NsCZSm7*Ew_p4EugKoLaZ44&V!z*c^OpS6|LdR2b5B2E<~T4N?Ubpx^rQ{* zDeI|p*i;je+A4=Y;Z`0GUN{#1dbqejo_yxNS~K@wyd#Uj*3*J{9nt}E;ONn#vVHq@ zLniPY9T5Ey(&yT>Yx3x$j~YcU{S?`iyzjsNzL8(|@856MvD}M1$mx&(yLa!NCrHS{ zIfw~JfhV7I^jOrL`%<TNk=H`TjF6D+$fmE<{0_5QwWkB~uoh&%l+uLi_9=1*vwhZVFY@GmkkiCx|KQ2{O zRkCMKd{?xBJhUm~&VBdYXEsy;TZUuDj+yV2&s`UL%$9j2fH;Ccvf!TFdof_C@-P4G z|70vxu60a_udqPsN`vy`;c^q}A{{A*+lhMSr>)&uTGD&kV>+^t{UWPQ2wzuoia!qT!n_G)r4! zGU>Z9klg0kfZ+8f&JWATl(R7k4-&Yj+u9yBvDv=(M6I;$`a|*gv)@#|6%-Y_ zHwES3zV!&CobvL_|FgPis`Kk)KB*7i`HnIGCCy@!;pOYj->sX(1mF$@w=Ec$Y(ja$ z;1Bc80Fw)N`I$(WB)J!pJQHE+Z{$-xebN#WFgrDPZ&D}H#b76Y``*~e+?sAevhZG| z`%Myp7}vXj<=MnUg-lJ==zVH*94Zp8PgkHh0(116-43Brs6u{wmB<%Av-G60+6$qz zLW7Q_6JxV-yWeTQnHhHcJ3H3b8>J;};`45j8#it&NbF!rcbsRR3jy~@13SN1$k9I8 zCgwJ`kh+?dDnr8&vuH-?k1T>qsr|c3j2j`w1a`l0o<7Fz9s=y5 z%Awt3VysnM2!#se;?)UON-`F4MjNbv?7K_STNq1=V31wf1?JtxEe@n0)frgCC@ zJoM|_a$skP%oIE(13g!@KPUP!f$BGH*(2Ald}M;oTVSc;ElP|^Rr(%mYK(}#@V5Bm zWAVm5N=mo8PDt;dLwaM`QBo{&Ro9xg?}!Wzd8L2QD_uQ)nVc$+_7)Kv(xa+E<}7`SW&xzE=h2FIFt$69Kt=tx%7N?AsNQ z+8U3}Plbj=XY&G90d6o4<94ZB$8_FtYpDVu1Hod`nR9W=kVmy1@qH~HUvU0{mL_Dh z_?Kk>OO>f#>??)v~DQZ%|#fPwQ2vvV=YW zeRSnz<i=ds9eb_Yw94Avar!9xe6stT)@#UVR3_TLZ?D;aT3lRY^0&2Ym)pGwMY9`N z&W6LR6=V9oIC75N^}VGjAkRHnE1O!wvbml35=G{7YHDhz7H{yuWm~GCTxZiCe^H93 zCXO$a+}EQoVveUS5Em%_kxL;xSPQd`@*|^awThKWLRWNyCIQ09OHgi zmaqn9Ll3`A9l1C8tyKrt@eH^(Bm=(>X~8k%eeOs5kdOA^9{dhv;xpGEpFo^Y5ANYE z1J>J+B-EFDl$*LyUMw?MhjVY_V)R|qkH6FjqKG5@GM_-w)RBvCd}s{Vvz zkK1cVHjmBkzL!P1L0dk-gj2%TOU#(56niW(x?tp`nQM596{sW;W&_PgGX;jZA?Hu(F!ZYClXZo*&Nu@1v6!_=SC11@rC9qz zWjQWEtZ!8Z43rGi4D6VT!HzQUx)TFd>W+B8Ai%`Lpw2+=9t1eXxjgdtq{0eK2xbV6 zZtyNJIc9pFxE{fc_k?Q^qPQOdBj>mV;bpOjH65vfN$u+@`g=04-o+tzSAiCuKBFQsd{ftaN?dfYnspC)>Av!wBVz zC7!kYZ2OdZ$J3_?EQo&o^PeZR&r*r^2y(!U)g)EAds)1R^bX7#CC)R!Ms1F;rAOe~eUGRWIYyH%)#3snSp# z(79?%3Opn6G&-Md_Y4~)goVcwk;vSPuEB9-gu5!IEDd#0xo=O*yd#Y1kmS+mluS$& z%FL{D9m(&H>9r#&gUuR6MsbnfxZ{fH_>OxqT(r*3aZisN*c+3k2CYNTXWTgA8@-}} z^=JC`v?%PjSBmOf%X*k#_wK}W`ov*Rk`+jApR*AF!f59(+UdXt(;x%{1jehczH06VnL-{*s=W8!d*+^y4g7|iRQc|AziaZ)?^z?UHey{w*$G#{PSY-yRKYrhIzenuCfdl7DsQ~;hG`@E0Obb!CgTESutZquGtD(oF4}}LEtgb5 zo|8!VW@H>bt=N$$P=% z$os@+o4D4#PrPTmACM^sRNRyA9JlWj0xA=FCZr=(0Kdh(KtaJ|&ZG)sO8=lUzTo!j z@q=M$U1nhV4LkR0!At;gU5sD6J}tA_jQR+Su)uEk^}wzje@*J^4#&SO4*C_()b6%o zd|eKyLZ7wC5`wFh5a#LM^hsxtx%%yB36)&H0)T~3Dpr$J=^J$1ZJ^A@jTiHA|4>AR z#$r-lQfS_9TtHwE0c?yFg3|{zZQEQlAMXQn_ZQ2NQ@Wsz3*4l;C2*&L1s#h#>cj#! z-56xSHPnHWZgG-&%>6wYE0FE&6Y)DGK--?bJg)cl$h1+kIl!+z3US)iO{zd#b@w=J zUsd6k@kw0bcvWuFh1-n@Lw1$NmFek8mDL@^)>uSb6{M0XpsucdeqLD$^aU~H#s-nLIRZ$B^}3nf!3Ew7OqokvW5U`dq(68-t*U-rr+9XERi9T$O&5m^5P z12L(so=r+c;fT40_lhwc>&%JCh>pXNr0Z&`AX9MF7&RLdg8I|Dw|jK`8kM~}RR)gf zJMI~m=bs51tC$%Ty9b75MI(%ng< z3Tp?mE>}5$aT@u{7rBW%9uN2V_%Qi!?XoQa5KFhoG5@I7)Hx z#1Qv2Lhnf8uFKpFtzgwURrfZ#aiku{Oy-2}wRlP66c zeiw3rzpRV+ead0Wz&ab!gLZ;wv6~k;NBcpla9`Yu0b~@;TT%t<57s#3L-~!~%#td^ zFyXg(4*~BXb%Mme?HGBe6Mv}__jcEb>nQ_u0=7$P#F??g z3HJlEIr)hvvzo9n9Hfo~?T`(ra^k}yMm}d_8I~&hcNa-nY5H}|iL<3DPdRI+)I@uc z+@DjEJ?94ffwJ1f7@3;varbpLAAd>qUiLFccieu?^qv07Gqlg_Zlj<;Wpgj@YFOr? zBQiEIW!6W4XZ9OkXp)f5)AtT2>(b>71+n-nFl+Q)l`EVzK%tbC_~pQ!hoz`&Wv&%- z#fFNh;)%}57auE?=h6gxU0uXGZuOzGTq}`vPQs1_@Dl`U%G~z z0RtCcbviL;Modne_UPnaBb!txVv@5j_1(lqD1#dttvoBiC#f#04JO;W0iFp$9TPV1 zAPF#8vlvQ!W(aSKDY5YDYVVN=h28-Ph7xfkvcdJ6Q%3Ls+iGI+t6yB1#a}i((HGFV z25P0in^;^#rtiqCrf6h5eq@yqFW66BACgm7XU!ss-Hz=oPArDCLcm`pyLSF{^EX={ zbRk$@GGhmt2xdE-B_Dk)mh?D!mG} zDPqyy-e_z`QcYob$%XgN1XIruY6{ti~5=n_mG3}DeU2?h0%{c*B zc?&^1u7=CGk74RE)&GZ~ds3 zra}oCoJoq#YHSshk1qFxQDYZj8T!@cJ+2@%2LRUiSH6B-w9D3*DJaJR}&2!?QQtJ&mZFgA+yoUn{Eoz4mMKJ2HT6Y776$8m6dpM3JkIm;2` z0qc=J4KYSr5exPDOgw-9XjWq`79q6O!sa4`5 zb%PnlcWJbr?R-Xb{4O6(0*Fve>a0qKX`Jx7QeGwB8q|2XC*ZP3zt9 zpJ^@b&xHN7>4yJ{s_HWjd>NiPOA~|7$l$8LVrFO}7^iPOK1}0bBciE66c){fS1>pf zl|3wT1+IoRtlKmvoJ<%sVn(QU{qg_|iY*~Y>04@d400Vara0#ZP-f?;*Mg?n})AIWtxI$g+ zdLx`zFaAFD+z|DM>)$smN?~T{Gn1%-<>AqYv=FMUtdPa)$;lYOrE2FYLquJ-rc!H2 zR9Ke_W6=uAIRe26jhnswA#q=gUYP4QZlcbv8w-7T_le{4KTufA@$r@?n|Y$is2@w=iNe`2IV^&=(&rCIywfNtrqE3ig$Y^aBSouA5mpq zQZHFiC{$D_UKSlvwnV#se47-ri^>ap6N@3L%$Bv$#%umsl%rG2uJeg15DhX>Oi=~G zz|A+`oF=LO2m^QBb(gHm>Vg64z7S5Vq6&a8aMMjUr3n!Du0!m&@4oxwvYsC5NZYq> zPZL!D(!2A{JJUoJ7okiWf-vEDyjgdb3z`vy1E?C3H3ay zr~;7Qt+(EqCaNGk z?=Q@&Wxd{jc@>nXq6ge7HLq{0r-$FP5=#)Q!irU3(YHmw{(4YpDlm`ZLlDEUmjdT| zU#01(OZ4gA?oRneyGd>19aP_XKl#nF%GhWx{qsM3ltMG2oG-s&;=Xx&;=0w)y0x{m zsy$GEz~WpB8x?h)&;0F4YU%W_r~*;t?5PR5>8b$z?uT437|1ImKFDY& zFvJu*UkH`89rV`s|5R>k1)|Et;4TUdJ?px-^7S7NP|t`_QAGou?mncftcfDw%@mIr zZdmXlXL1KG%BAx1V@el1M<~dt53DMLWdgt1OwS%n!SP|wM6RNWvQoj|^c%!0qfjdq zD|lZHkA`Vm&#@DH?akH@^OUC*hqv6ZnaYtOy3JA~c8K+l{N9I1a8@e&pjj=&b zUszP0oJAF%H$aUI9n{{oUQ}osMFoAecpt;ha;ix$dSIa-oC`2BM}^r6(n2q=`GAW@ zn5{1acvhA8gGvIvJ8ofj4V*ylA6y@Zj!vM$gKL{Fk;u4sF3!^B-eWX1Jt_)gS7bbT z*ba?EDB!Ok42%x{^{3BG%R+l+yPpE$JFP$&qN6G<1-$pZ!}y(HVES-;wX7H|HBjM) zYXX4xoT{v-pjTj=;`C+A@3?A$?%ZhzQb4Sc(}PEYwEy5Z4TZ`mV!8mEPgDVLX@!9Z z0m@9OBMR;n8rRa%UJ@>_Xa(gQ!8OBs55mgmSVVlkW~r@x6>Z*{y>%SMDw!6)Tcg4$ zDxl`K&+dw%F#W;c zdPD42F5cZ0@|kIE@lky(MD^V6y>ZRbMU`tS?xqfZYOiC4aRVi)Ts13xKV)|Jv1;Gp{6P?{r*Q*i!z9P`T4os!}RL$aXHqCA*#6e zz0K{lkvE&VK1g1VF(yMUqDt|y=a8}`+Wq4%#&I#;PeQ!&7f)2dJ>9csPf3U>D6c{k zK>cR_{{1N~r(g;4?svaiHfn$OyWf>AuN2o^cbya(P*#TkfwBTXdhdA0J7gVr_wL;Id3Fm|{ zRaAO#`-O9YsPgMy|9Z}S8bF@!zyE&uY&`PFBXU{{V10wmYbdMdBC4!utfY0TeRTU< z>@D%1-Q7T!dX4(C{_X;LSx-$>Q1u5)5tN8x4R!*HN&}$&f?$+g-Lqc7Gk|*yRNPXa zu6mSi+J1pN74AMqjqUHDrd1D{OQ~Eux1S#Qm){rlhB9$YabLte!o8{x_s;91tFLOJ zP3zIl;;y*zg|D2YiD;D8i05;$M3s^mQ)Q$#NPqb!?p9vL#%9FJ$`}WsynI$FbqM(F z!RIJ`gm=E{o8P z?`o>A+af^wfhf0!Neh`r7T!Y=Uu?yH1K9f;l z!EXqa9~78%kT<>3k`EOXhLG01=2}|Uy_Jrg*dw1A3@VF;`lxtblw|~ZzPB}d$?r$O z-Aq8>73GO)@2u<$(Y?Bo&h|7@|JYXP_G>8ukq_@R^~~uN6&0*;^KCN|_R#fP$7Omz z#L6k^Bd5+yQ&beT5r7&)1;15&Ock{Z)crwFJ)O{yUR%wAN-Aa2-Hxaqif1?`uQx8o zs*dbMVcf@=8SyNLou!~+reSwg@!SL_C&h1glm>@}L>QKx28P9NdK~Y-Fod1N+;gFV zk)Am($aO5If&MErF>biILE|c(3k+JBk6SW4XK#4%# z+rum@7otaP?@wBowTa6RCM?TCi5{As9j6xZi+{#_Z?3nFhhk#)!!wzhiPQOByTgRl3B>lPNSrFY6(Y?#@eZ;-X}II;8NyhGaK~CM&bLCurJw73LAu9A5+C_r!e*^77i&}qTM|{QnN|X678^6o}{KG8&~rfQzaZW+{R;^ zg7qDKTHB@lPRgpOsqL+4mdd!t_$ETQQ1|oFrAzX=h{oFaI&7gXfqDa;5w`=LH#D$A z)Wb1QPgUyxtSwL;K=~Zct6GP;F!n=v9OZJPqtb&gfNOyCkax8Yo@-^LkMqa1Q0pKt zz*+|Bp)(oE1BeG0upaZchNz>ceQ+$S!@WfP1o>3)u)=^SgyZ9!aGkLZ=df+tHn}bG zjk>%_4|zu3QU8E<3Ozlib3%HsaB;du=%l8ukvb=A3o9C=hqNHNseP~x>EYRc1&e-- z+zjeE;@of_Goi**fy=$RfQPnh2vAd_y@lWld(+*es%PE`u9X7w)}VwAYrs0(H+@@x z;~?M~s-VOdoTt95rYflYR2q7ExR1IkP8F}VD`mpbN*bH2ruOD>aem3`oiCL&Td8~7 ze-%^bPFnSioisVoOT+!g_e@fCm5=Ib^XU{}f8E!u4v6P; zf@&K)vUAn7Teq#uF;zx}!sLrb>65?do|Ve^^TRYfg^#6i`Q@`O=ZzUGx39T}ZoKCU z#)>THJN0>*8r^Fy6-G>al)v@Z5cP~04F;$THa8lL13vF&Q9-<3&NKOgmoHwD4C5v! zY@yI)1#wPd3qSz|AM$L;#Zm>ml1Ii2QN@k1RCLD1Bcd>iO1tr?c<8s1gQDik#K1E& zc;SB)X0@WdwtxQYD7|ssIDb^M*K`>LK4q!m6Cd_%t3A}!VYovptNt)GG#es53fn07 zqH?7QXA8wbA1_y|g~np#7rz_yIp?``}}P>F#%G6jBjvR9!?paK`3xk%@a{N21o zfI(44*?-1p$N>;k>U{~i;o4eJIa))noxH_ZvBW`T7Vf}Qg+Z@mIK^dJ{^SSFiQgA` z=ZR(G5Tb$^r$>I;N7Jz~8Z+JYIa#V;5arhnO^CGM60U-3t1Co$#y8z4GdYP^^W4xJ zDeYfrI%hA;$ll)cGtXO6XEI}Zws7fqwx~lSi&)s)aQjPnsmXq_z zfW*Yy+;T2fDq#PsuTWULFYvrU+=TGCX+0Xaa=-UZmMRNLWmyf~8h8(R%a)#{+j8OM z(BpCd`K-v{G0C*)yp}5S97nfQdGs-DuXgA$%7c~zp}SfDNgnrQnf_8 ze{7o+i+arT)bKr<3C-kXsiLR%&O2MBOHzf^Qbm5}1ULpd3+Waqxmc=T-(t3Bpi>RT zi9n|&l))kLDPRqPI@0scKQFgYc|aW2pGUXZSo z6tLcadoTzSaId8-=K(|~{61cL?KOE^z4H{a<5AUMT^f-x6wYZid%))X-)c3`7Rs>OLplh#br|sJddB#)E<9~nq63zM()VZp1 z<+}f>2*>Dcx4GA|`s~>uaYHenyBUEWmz>}x$~if`_dSnNWle7WlKap8y>tiW2ETq~ zoOT~JdKjT0u)U>|rYBpdM&wDEnKAiO%t8pWa3ou<&x%>J6-EjRz>Yw>P#K%3^V+khTOggGSx{$#C@u5S9WFZ!nDpV+t z4^&F=yK@UvZcs@pi=CnJ$*-k6OLm}V?l1OEi)Y4IZV-jGD$gw4e|I~*dGSG6m|rfS z@`oOQxb6sg1;uXJE?&)l?A;ecAzqZlEEo72Kj@+9$Se(;12j8|Dw8qUgBkn79UCkP zFd#kLJ#Fm9_!~|)&fRBs(F)0V(t9OL(=+ju!Rps^ucNghWDCA)gR&Gd1---F$01Eiw7W;PNo}Ez z2SoI&cy>}mmGT7bJ}{rCVx*_1`WthiiV-_o)+$AnRjX3lmD~_jP!`UmQ$#KxU3B`x zaZp#aiXAA=!37z{8`1Ls4-P0R!o3y7Ls4KGq=T|N#0b4T3+dsx$CxtK^G14b?}aoW zz9=A~Ai#|mI>6~x1K0=G_rQSzDd{24s7IVRb4H2>7^_5qydjS`Cx|Gz;DYoZs^D6{ zb(aF=6I>&l6SmQor%n(TESR z2?7?zZ~;zfDp3Vige^6Gdf!70;y$KZs*H?z=<#2sy0(^OJsYg?YFVGEpz0HtBH-E~ zU>?^-E$j1YTLhIRz&R?xL@tkDKz8C+AUVZUv;#xycL7f8E-khH`1QtxYIveP&yOO`p{4mbrz?zBOpa@;7?8EfT6irPV!BY{DLW&BdkNwqzrHS3SW(q#l+>p%;DwzBa z;(qp!qC=`$bcU_+z#%nD)Pfu@uY(vns@+j1!=T6r5aRPpG-uGz4tG&@0cGVv0vh+> zq6z`?`Z_c&OX0~T57-{=uz(&90R-!?pLHKtd7v@hx(|d6?1ObEJL>CD7Qs4nW<(>m zz7BD4p=C`E+o}Aa4z8~QSO;*v`Z@?O5LM9VuE*=w2;~)h9kzuK1oU_WY>zb2(5}ZL zPgn<0)tU#C)9lVk5BfdIH|XLI(97^D=y=RdOinIVC#NdpdFrBqTGr!0rtJ`v@L?4{ z5Fj|IfcuZ@Yn@^po;7Tbebuq>EaCp)8O1%owa2r9Yk{dXn)RQ{h0a?#JtZlYlZ~%Um2xSr<})8%?{%vHgBw{+7>B=eh^6TV9+$ z`1=$K7y1y)(l>uPOc#e@R268XtGB$%jAz^cFJrtw8OBX?OBFm{@ZFjTePF#@2t@{I zGm5`TS330_myB3Mhl6 z%GB4)C1WmP$yK0i%oL}+jIOZQ)EyX?&J-FF0p4`7mY*%I>gWf!i!aZ*Q**c<%4H=N>cGXs>~lH1YuJ z7FcK~AaWocb#GXL=pBz?C4)TRn0k7+w&%~Em;2%Px+M(+5abQ%;W#*+LhS>T1qZ-2 zf>j6h!}Y;+QowC4*5RD&t`X8h9M&n2Ukp%>JXo(et`GLXHpqjWrHUKi*m$<|^R(k} zSgQQnm#7J2U{reO!|%0s*L37$CB1qeb&P7eXEoP2eTty!8JMa7p+rrU#fomZqSmXR z(zJ>=cqc=Q!Toj%CFqn2Ti0Kr?oPY*YmrY&RxyT3=f=;NOS$vdw||R<`cDwXW)zoK zS_!IoX|aN3bN;Towopr}{TS!D(APIXXZmCG(0%V(cuN)aKrKc9U9BE!Zz=qR5sk*h zi*3@V+|30HOyrT%GEsSxq1-E%TRZQt%~Q6aZT+XsBj<~8{@tC6r>HRuQ~FFz$LV5k zSXRpHPy;!`#Z|X$BV+FLT~Q68D0o1OE~mz}8^pWMC?L2Q+BWD3TNk_Y4(}b?esU9jpT~!fI(I)b1*O zPywib;Ci7_qAD_~5(2DocI(09w0)zn>hWfW`~{2E=n)D_vq9O2F)M|Ywq~C!fWrz6 zAsy#*^TGaYQu@Gp!{;lLjicx(rtZfjW#N$n4NXnd+}t87qVth@^^;3>cLmQ_K7tA? zZUD{+0uBTf%;zhplp<`gvM?;RpaSY^J=D_VoePci`FL%}?r7Vus-tb2Yw0aFG|1n} z@Mr|%$I`@jhX}PI)X30xrIJpa^~rGlLIw5r#|Z6=DsFhBT5dNsRx=lefb9_UxWR!c zny_rw(=#i#L)t2C1Zj%xFx9tBrsSM<^sNPD!2_Akd=^N1p}-@P_Y9-0>ld|5Cb4S*Z~0q;)4}5 zXglR0leM}MAFLo>PU($|jATsD?woLqoX!bp*_{(`$^-K3lm{gel^Q5-Ra7{aiZP~& zs@E&@y1v4?3^Hw}2PJ$U;66bBLC~#NaIdTZ9qO#sD@Y5!CzNeb*Map4I`d&WH!0?C zHy=)%TSEiGcAcw4{*Xs4o9*5I-u6CZ8#>qSB#*b;uvigcZeCfhz-q;`UOD*21=*Hg zC@sxZ)YWFRh1un)m|@Yo@wYX4$ib2Rdg=s=|p84!ge z1o5e8Uwx;sfy+QpXajLvA5>0^PLk+W$&thkui% zLdk(KGvV{qP;2K~&86iFOyAe8U285G_rzK;(3kb~Dojq>{~*y@8i-BOKoknx5KUm^ zApVMqjwsiO6{?3Q3gS#=>S~N@Usor}z2=1;A0MMB)0IaqK>TQGZV~sx`S&P~Fn3#$ z_s8x|!RoBCGPi;070UG&&Z(x_s65oyF25H)3oFH?ST4VS-81h*wRnc>>%4QJwkB6` zF#Tw7fo%sm=1fmVWaWR`7Q+pW(OCz_EWC&4V$*ZEc79kVm`pobrHc!Jr;U{S&f0o?JLrs0S!f zKlFL1t#NS-78X@h!9{d~Xe=&%OtWNIrI_MLh1U>Q#8e3>2$-*H*lg}u7|nT^6{WsB z+M2yo>C$yz7-sp<-QlB~Hhbr+FHjjnuWcQD%n-lWZdF_1?m`9z;buX68p=cgNq!=X zX=QcNgxhTzRy|y>wF-JWG}SEXCvDkK3WdIf0OPA*Y@K($^PO}#_>ruHm8~1zZq6-# zQ1OS$HT68G3V{lGoI;NeI*2MxR0a&UGjMr$u?If6W3*Ph2U{A%yDl+H$4^g*avsU` z7?&j#cc0nRlG@Uvt`_bN3~Lp*$Wiy@)XC$v4FmIm9(?VqI;a-o?c^hNio<(-KB}&% zA)iPqAI_aQEeEMLo;jjM=_W|L_gxy3vD9E;r8wjzsJQ!jaS8iO!Ht$36TvXemQ{#y zV}fd{A-0+;Bq%%P=R>}f$SAB7{T`Ol^h|>G9~`Itp$Juo_b(cd{Qfd(sPa%_wU=tW z=t#N{50k?&v}nw_mlKPqsuuN9f3Fe@U0lewPM%pOs-` zaId-65L95*fNvOj#_Jg0wbb&|LVz(k-~wvfwr$kZ)MUmQAP%m*U@fk@wE}7%tK~n^ zxb3#vq{}VcwHAQ8ts8E*LGGu6juuYop>q%N05@6I^pF;;*)yf54+0M`2tM{hdN_BT zn{U2Z?xVZ+0@x1ga2;A(Tg_Ml40ez6%5;sa>ERlwbFz-3jP2p(4AV@)+kzqwL8dqruP-C$qKa<4q68KtvRDNbeHrW3wix3E(}iF$e&<%w##gb> z-0=}}E`R)iTJa4Obr1wiP{Dkv$O5aCa=LtRP~5-5tyNI(Sq#eh`ub9z;sxa5oBz(0 zaY+USL&m_Scu3I*D1Z6lVJ#C=6(^UCUXQi)>*r%(&S?-{sapue!`An#Q_ny2WVDfs-QrPaaG{93iS1d>EO|zEHX7WdZj3UMk+j&tGfc? zy;yEorUmqZv%Amiq7{r?1cUkqC*w3At{uwAst4Zsjhm>mE9t{KSCG!sWROC#5*ial zZE@dm&*$!a@)^Lm06u>}{(cK7kHNy`jo0_fd8C7T-?_?9)m0wx>=a<3DIS{{@f|It zF;%Sa7%T2kY(XX0r{}8KTB@UbMZwggsWDaF|E^iuzjp&2KayI;iD4WR`CB!XL*az9 z8l0I%hZ)s)w|K5m#p}W~YU|F5m$<#V9$#%Qc`Aoo9#h50JOq_V@y@Lf-zcU6D_;+=)>%9)GzP$U|VjeuxicYjP3hkdkY_b#hj^&Vw8J){9&>%Z4 zzFqp5Dtiw6qq#OS!=u`mDw|WsRB>Xqtd#-{pOS8Em76HsS2XJ4TQ=XAD#wo>m+n}t z4fYIE2x!a5dQ6pXeu-LY{8V3AMjw2)eVfPgufWZt(P2h^Z&}}A^DP6rIN-FeKGg$$ zUwTmEtEd3c3IX$|AL8Ax7%bLtZ{B{A8te7(a}BENc1YJ>g)%*Pg`WQ5N5%O;0Gp** z2w_qX!@M~)m&Jb>xBdEc)Y6)NJzr7VcssSO`GmQ&Ff8#FXX7CZPR)wSoMELRN;2ZC z42zVqG9yr#D99j))0JV?{>PdR)eXskr!wRGgQ>4s97T;`n9>3w%G=&@UIxsAyKfd1 zE`RdmTj8ll)!H{EK^AcyTTRFfD7zR_-D=NTgS)XsNPj`D@2V8wYNKxZP zL10lmsYl17G%#!kD(!7(a4MJYx>P~MU7Sm6g@Xb5&tICM)90pTkORt3!@slpM{O|2 zXK1YV$m^!=4=g_NaRa76<+Qf0o?6>iQK$G_V$7B5+FJ3P)W`s_5*95D4UJSU0-ho4 zQwYb78e%BU0S&_~&3M(P zzvMO{y4*KIhmQy8&0`bh7I34HpuWCJnwY2)!9N$Krvfw?OfE;ll{7PrhFa{a-amM+ z&KDrSxEo|$-6lTYFfpDyPiq+JSx++)ZjMlI+Jh0A$c!jAsFI|Fp(P0w8mN^fr6%l%SjQ8YHWC@EZ z#=|fDZbL{>MHKqPbk=lVlaP&rWt5l|K~$c?k<9)sbD_F%K2Zhv%=|-bs6`=_ zVVIT9Z#{HGTB+#NRF~7X4N12Q7{FPf8X-O9v#y9Llha7g6jRhYQ%*@#$kThAyNSPQ zLw+v6wAU-H0asU+52|Nr4LS}yPrZ? zu75Duh=|{^KTttFzfsUevT*qYaiF8k>OQLUfAwgzIeTG-M#iEvJQAV4{*Vk1jbJ4K zQORv#1(rX!jxe*wfbME68<4LXFgxJRtEQ$_y7sE7t`_$#Al+}2SGZHfICb)bbo&MH zT-DV=Br2n-stVcrJ8w$=v6+K~mBPqdP$}{=g7O?hRl5)lr+@!uLU!BC%J+!M?5l5# zndL-`lah_-h;4OYB@^yn5c892rEYBF)00&!LYOf@`yjbac3Ldc}t^Q zw=g(dL@gS#4qN4jO-h!i!jEHf44_39ehdRxa0Mqbxcza+N+>i-mwQ9=hJisNZ8Y4% zB6^`*3^9zGpgI;$h#!K(XQH_=mLhNfeID4Yb6T&+6sO|#Wdzh6F;&8f5?7SK0&ztN zEUNQfDWK|5svcErf>TwZ?2ta5T6Nv^=3HUKqf?^(VTdVSU05;273CVt5LpbDU{k?q zbMK|c5)@VN12TU^B1FWuNw-LmRw<-erHC(~_+81Df$>6^rO65R8V5bTHu2Z#;WzR* zAI;J)G{Z2AJ?p!Cb8i_mJ}U4&16Wt zbcMjgFmBV;vGS}`6mUBMU)HLiZ!Pre%c<*<+vuPH%1%FkNUYv(*KDn!x7<)q*I!*{ zx&SMey}Bb&!;HLG6f5QPmqMaKm!Pv3rey;t%B3iuLSTWIga%RwD{j-);*(+u2Ec}^ zEM+kQOO;b6+!I!c1qRn2=r`Q>Any=S@I2tzTGhHZgHb91(~Wrte<=5X!C6?zk6Z+m zidj$Uy_%XoRGI1RE8My@af!o$q(;aU~9s8lUI9x<6+P%wclal2)g&)h|7-qCP z$4I5O-y(FVgJd|+#eoPt@$12P!wdUI%{@dND;}p{Feoio(CEuBO9ex$D3fl&?Wn1S zIB#sH2WyByjoUaKI;|4>-CvZA+;`5JYcO7izVBS3LTtYCp0ri9wnG;q_aRu|H)k>*|T)DEuL>28vWB!T7#VM34_g)ogRw=kI7|ah49cQbA9u@$qpQ9UY~SkrC-W0?Uh0;KX2> zuvSrpd{yALF6;BPRnCpSqDYnoM3n=FCgi(F4z4cZYHKR!>MhmM;$n0h-jqe#epte5<-xi5&) zqTRW3mPCQ;$H{yQo3(jhpF(gdPSL3N_U3Sq$#9G&LQySXIXwi$c2>|s9+oQ%vs8$n zF+eagV_#mZtv0MfG6mo?51f|givyXqL$Hb~DEA`3z41bW#6nEE`1xFX{WK}A}yh@iw4%tvhAnM;8s zB&rxc6#SKQ=I;iosq*=6xTz5Vjew#8i(cGu@e+WT0wEG2i#JtZY^`mK6fto2k|*MjQg#a4((TBep8-cU3`+Y>cFsg}0?j z|M+%uuK1vg(%;`t7cN|&%aySc!aA|Ni_F;-A+gL^DkbU<7f7>?4&ID9o5Zma<6b#}tC8x-s9hOrTl zX9Tz|>t1cRbHsUV+gvSObK!g;CQSt07tE@wDpK5l8Sd1K>tCwE%7FL{99QG0h=76c zlWxB}R9BOm2$BiEznt1ya&K5gWjxXQs;bKNo@Eo@{;u@EyEEHh zNBXfp~2yL3ddS#Ec`Z#hLb+y^Z(`` z4>lK2i*nc^4~l&pn-sJto3(k6ITf@Q!3|h`WKJ9Q{|vL#QJyg-CPg9K0VQDQ^LBAg z^G?gax(qVK>G66TL=`pldJRuOs_vr7#l-@3x#P!=)0=O;DeH1QJw37>ck$vyxqRTj z0ouEFFC9L7SazV(DQ5n9HBqHPTB^8noU!2pRAGuLuu?HBReYwXqJk-=m;vGn?#)tU ziHIuZk4*j*Xulu0tCS*hfY{B~+6XE@ji-W6p;pA6(tQfV1qiuiW#zKL z8_diYg>09G=~!@7gU#yBO6kH3gYQpHi&vM3uCMiqb2UUIlwFH~bOTmyxB-JWVHH-6 zA2}?`$fZDEZx5Y5dBR+RSY9qg6vOQo(WzHDDx1Cb)tS_SCK)}XIfhPj`FkZsSyCu)wU07WQcS_r5LDzlHa1H~5B=EOx;P|axR7=*l| zjEY=Wh!?I$TuNNBNmFR@dWv^GIQFV`pPV)|c+-Rxj9qg0kf^|ojmhQ3;`p(nbna}@ z)gC)w;=Zb}e6?;~ypi-fEJ%~l!5ZR0KK63fzyMWkd zJQPZPkJbCs3L4Cso15i&{rjCe4i`_0cIWciq+&TnVaKsaL5nIZZD2{?vY0=)C3NIi zLI#Fe%D_SxZ2_oaUm0+&XLPow4pwg$zznz`I(7e8Ic^(xpqX z!yM{P2oO~Cd8@#p#1*WEJ1~eV=xk@D(7ah0F$b)VMux=S)a#cIy%(RLa(S*Icnnbm zuD>uZtyaXc9;ACPtcR##j{UgQDB)b=h8j0j{!K2X0M}WDm|_SihGmK&oM1X9sMv(p zUjDjB!6wlhFsxJxOJhd0E-(zkpv{2wMr~p*kJhR0bbbKm|;>G7%gm^pZS=aoTRa_FH;RWNcN z3~1faZj41@C#+!bdI&4$&YUi~KxYN+zV^KIq8vv>kuInNpZY7gIwbf@IKBKy>62&7!y;uXoj`5 z9+aq}gcUW_1r~@aN?3^B#dJy>OB@jWjTgAx^0%pa1POZ`ox;H{XYsCZxv%M=7dFp**kEK^c~vEFb8 zmY^dCe@;CY511+CM|c_o-e<^Q7L1J-))>k#%*sSHGQw&-5-IFG1khU?)*f)BI47ux z0JC^Zr>BFoZ_hW(t=%UYwl6ef3$6hKCWdi~kzkWK=RO#y6g`o2!9)cV`kmqx)`B!F zUXC3*R@4S@SgWW)yfpw!{k~ahst?I!D;QHnyhv&Z#_wDFz$bz@zrrgK3q?(}Ap$|jfbjeJp>aBMZkkSr^LypBF>$^X)NT$Y zUtgbnMK2%hgcS%rSXT7*T&6c(-!I*Q6`OD1P$oIoaX88#!xzW)ck-~~Qxc`1NKM^GdtS9w=cXTSL8OQinqhnDSAj0HgA&tf} zzdzRoBOKr6;%QOtTw0ssSdLNHact5yqufbbOCj@O8ushdUYYjH4ECI!o}p)7{JQwo ze}ke?9-N+8dicG@Z(t@8r&ywbM#rsn4C8mwwJO~OSS|s~H}A9ztjoYI4q)uGT(Q=7 zoIqI&<6r`-pkftO^q>nYN?cI_%lY%?=hCzzn|x(rbi7v79V;jipO&EzE}Z!{nU}e9 z7Uwi4tVnSM!V0EIVMVzI!?`Y1N>EfWe=PE^ApLicg186bB;tmc5{XgF3{pgy6IsM` z&Wa@=mPIgoUO)HCzZaFd{Ci$cjlN>e< zJ4I7ak>eYf!itzb@ahlf^2ImIJ=|kv;!SfdPsF!kJQ%Yb0Gna*VPvAwoO2%tAFwV# zVPA|4 zLo9~CTUAv-8@sD%;7CNe zG;3<~Nx?vg9L012rmzYtxb6WzDsrMqU>-gk3emA6hv&o=?cN+CC{P zDln)o2Jpwg@vd5^fZ|`;MI#oEi|_QxtxG^yDp*ii#?MD?xPKwEPsI`=nQ?q`F80h& zUw@eT2g7tlg!7kX=FOmvRb`Wlmfndg}4d)4-L}=3ed)9DK%{%b$T^w)!iCd<$aBmHx5fx&Ff7gDBjq ziiZ+SG6fx{dxe54T!6ucZ!z%u{jzWmRN>tkHm$Wk_NlW*MQldALtu$u6%Y&y6hj<^ zV0_0-4YYo3fYx^U>6)!I(sE&1>Zf)QFpsN%LD-wj zf!K>j@_OsSN>ybAwYT}@Aoe~lDm%&T;1Uet%HBOM(cyz{6eO@fNP$Jlt9xIeBZuFl zk&&dUFNi4^W2Uy+LmjL9B2UJ*Eh(tjKksf(Db9a=cVQK5hH(p}jX_w>L_?*Awsck6 z2EQ*~5z_tNnfN4>G;3P|)YW9?TR)j`2r3X$28SYasW(Jd1|!tdCzgj7!R?-QJqy3I zNWqedCH=yVVUxBQRd~8u3YizPB)`3KAsU;J7Ar5l@-`D{{F1N{IT(`5xyo z;D+wFtgk2mL(S`P`2^s!tgtQvyEq6Is4KaFs`n^Dp^$X_B}D`guTQP>PCJptk`ajKkZQSprjC%y9YRx%!ftxNgOrzjw4Jd><#Vec&%Bm2JLOBM$FILZW zq_5{epRcWs(W++qUTmk%87AczPo<_Rz0q$9f{A$7fHj?!B3+`MD`Dy%PRI&fSBGD& z3xyLjHSNxCeIZL<5HZ$t1*AJL2pI^l)>*%{k{TO|EvTdev0~ktN~#w5fu&GOlP|?; zMHg292D48JEC=b-i4)RQ*g*dkDYig>frSgU!x$--E?%H>XV1#P=U;v0WjgZan>08u zK=Bk&W>y@>uuj3T+gg1xFR)VDu&&x23l(7hlaYwWSybvWY``pkO5pZSir41rhpOq# zW0f>E9;a1p&V%RzpQnsI_|8t-kRR?}1ntvMvV8EJ9aNL%S}--^5LDpq3uB;Gi}!YC zyN_0j?~%_}q!YAD7I9|0Hd_ETDQHoJrEil%bJ1o^4p{ciyl6}MdXxg@+sj>sM$XXB ze)V7I!sY$c(|a;w2u_aC-o1O}_}WvX6TD#B-J*jEwckpGRW@ z-jQWA6HSP^(JYOO*q8HnY>$igq9J6cx{DrEoOK=0m!0CQ@%p^eGSHWu>QIHC>R%Wm zQ_b52Rew?fiVC`rVhs>e)HE86rdW5+2ac636H}FPIx}@5XBS{o!Haa{^)HBer>NT^ z;Qq>cY~1I$$`Y+1j7Gq@$3FS|XAOG)1^i`6 zK?Rm6DPoEtq$C9uh$-cim@TK-vI=oSJ#^;u%k=@?o1I>=H8u{FO%bzOpN!_Paplybm_uDbI<%4yYiSh zmp@a}ahjaT;{(Dl4$Op&0;b!bK#W4BUb(Q&TSGSJ1#}215O0bBELHSMf*y8k?Kihd z<-%p7SLU?o`U_)uI3bdu+Ug4V{=s{v!c!r|T#WU!)PWGbs?A58tNb#wGag zy-G(89ir2xPSB-`7pbqeM-D!pDx`o}@|4e#-&-zSyTLjIWqE+SbRs`<$1MK!35N^o zkiamxlYFjWdDlN^JcEfu1+DF>lk-->k)`vTTHhH9DGFs%xd)74vRXv@YL zx@vO`?Yyp@YHKnHzb;(_Eg8&?2S@1H-9M(D%a74)?3b4CJWWr}XQ^t*7ZxqY$PY_G zK#OuK-E)`r(>EUdSNgXfex1Je*uT->mB%R&d79!PL?gZCR;AAid;W#~M7?8lon03$ z+@w)s?IexS*tTukZrrG`(Ku~v+x89{+qRR&PJ{36^PY3QG4f+)jE#G(i8a^6b**mt z(U~5d_AP-CcNwr5?xxDC1xd4NV=WOUyKebg!7dOK2CnhO`E+izi_5IP={eJ)Px2H@ zD^E*WY!{aQCBy2pLxq$Pr?e*yA4VNT)bz)yvI+*v&khjUhFI7VR^5M`Xx*T}lUIsK zz}7wdX5(;5Fxb2~#6*sctn*b%dO$;m%VS8B!s%J?6wgR+Lsp0QHTWWk?o4H8oU3gn zo2ZS8G(cS@7P7~h&6>WLfAtYEg1R6j(NS-)1#SQ{I$+;~mdZ5r_?NN0SqlE$Jz=3_ z=hI-`Pp2g*wvRO`;o|UkYM(PYjRaF@`w%R7K2|Yj7MCcs7mN>!6vOAL>;I@va(lBsO)r1{l>^BqmXHP;NT~5#st8RpAev- z5Z8R~ccQ$Tb9=zK3tDdHaU^4NYIsPmAu2+@oR=YlP3@A68zGx*zsWAN(hyf_p4fnA zGJh^M82ozRJG-`Y6dVyd)`iM;_num9FI<)^=Y6e%EwIl7Zmf$bls2lWj%{;&RazQ! zAzd=p#2!is)e-}wJKzYe!?9a~Ps7i4j^7?gxx9;#z5wisR=I()!H!wPe3GP};9)F( z^ExIiRL|?fmSGIe6-MTe=Ucq*|252e{gG8%x|N=% z+d`3bWZY#^e?!r0^AY0AQcuj09E>eX)_UI7qK; zG>G|x2puKVgWv|bGl#RHJWd3D1kJjvLdC*ToP4}N<`-#%080d76Z`sD zeKdXHBN0LO>s#BCDye|Drh?yw-UvoUHJl~Gk732)HrB?cH6fE|!F3dTdo!TPR0md4e!3Qq+ee03D{CY{uT;0-MO-j)6TGgc$1J zeXAQa+CeA0trUe! z_-RItin%#jV2GcUXc>$>U4l@a$gZDQw~cz?35Sm=s1fe2=bX@3%dkb8%#RHQnX8d> zeL}sDgKz|yoPe4~FWAKzbbe{%OMTpJ?$(hEr<8KG(@gB=5%0NhDGE#I-VJfg`w%QA z{v{%-bJ$G~3KVs!jK2nk+fl6v9%8BA(GZ#{LuKUbvnD6?A`21{>NtwHBeohY)7B~t z?n@QlinvapYA*gh#H3QQH%syQQX{<>H6o}_k7mS>)!wqH^}YL4eroA=ORE|A`x+hM zNro(c_Lz*APks@pV+47J%UfK%Tehx4UG-#1sX+ChIea&R0raV-k9L3uJ434pnST453`J!!1e+Q+MoL*cB!!_SMOdf$_ipHriB1*H!+OiZJjCgP%+JB{%a=mp z%v1dg1r@4KbTs@y%x&)6dlAw%p^fS@c0Jx2)cdF^IfOF8{gm($0=2eK?1DTCqJn-q zH@CY)elZ3f`)F2b0?DJ$UV3a?UrKu7| z?!#spfnubD>cpxG{S=0 zlU#SNHi56@!9|*uW%SN`+xL6r;J=T5CjxsMN#hcB5^tvR%&G>>E!M|wEd52fU8yI^ zO%3N9XAg0FzTUZ&GfJYIcCQNw!}%O5qp7`w9sRo0gc_$#HvkWX zs#R*#0cwHh+j<7(!B=#)n&^NTqDJ<=B?iB9^D=QeuHS@&0tykJK5G>ibtHs(B8D1L zTsYg*XLGn{jzav!cCm#F)mHmMG~&l2n*MDI&#h=1VyC%B0gN}rEZ z4|t|b#tzw&qVe$yUh!%69?Sn?k`O};S$M6vylchHI8-KVy9Kjwb45F4g}FMc>=;+^ zfoNHOl}VyL97vW5^({!mj| zoX`*|Q;SX;IiPT4YrlH*iI(4C>Pj?rri$_{*!ObsVP<==Q(;nV)LW zXu80L39am-V;R+;kCQu!#gk`na{d0jDA@CA*A%CSt+cc>*W&7zt%E}|l2)~+Q#&+F4iRDW z2ntLfvRSTsAWMB>hDN>N~Ee*cVwF zo{!GGGG392I*h~>=S(o}KXU4PO@!|zA2sF6QoABQlLtva=G zM9+q{h@)d;X2xzC_zb#TU|~){!OsH{WmT1lR|eUN-l}3AD=Nu#FkpdVSWez8GM|1q zF77J$lr;CCte0)C!&Q8kTf zO~Pm$$7COjl*{19B3OQU)Ntc(gx_?~Y{#9C4DGOlCNf=ftdVCr#7DttgJTXOAB1dazSsms|j@w_@{O2|0t!mLD? zqk{*!YtzAYh)HfZAeO|Fge$}(B@sDxpx`o!S@q9=d}$Sn!9HuP6OV_zLT<#}2IBm52ECd~@-xV$;U*wsNZU^NP2 z^y)J<+{@`Oa)ll^lg`>6TKc%@5<|HDN}WX9^A2nhr=An2yv5LS8lC1MnYJqxhMt)q zO?UwQusmr{KUS!g`?1{-ZI7nZC_1^3TtmqTld}Chg0nmvQ)04G z5)SFRPV<%skOzlPTy0ED!qBG=e=7s=GCpiGpc?3!J{KP`7E`lgC;46Ly}AnhfG$L=*bH-l8Tb}mFgT0#BCNf z)|rDklgg)m4k{fNj=dq4#`7~J=Cjuz36>}Z2EMv{4GR^=As{Ro9+v(b8`IQycQ*&M zXhh1!#;$CqPoS=Ww?I3>juSYNtg5uy8ZEO~b>0priN3S^kCLz_>am2TLJZ)kv!Fa^^Y*9_l%2=f z);nC&%3eG;)OMO}U$TH|tsZQZ#_wh&76DP0=M1m6FT5*!E`th!jU1nee5ebEQ%ED~ zlzM;`GYS|85TRm!1xZPQs8YC6H%6W-funVW^TjMHTGaHuv76YJP-V5}_1ed}k03~} zlMzxGWR8&VA~M+j3^T&`Am*hMlB*YhV^Ph8$~+zI^#0){X@dckAhXg^6~Pf+<7fwJ zWb1{TS_{)w`xa|m&ad(%;BVEfkya%@dQf}jL}qZ%35^pkSi6jW8jBoj*1;$72`wV% z=Hf%wXO}%yd;zoq(Lstm92HbHh_!1F4Hc#1181wt#^{ZuiwTQ_&#UpW5gQxbNadT; z%ACG9Z`0z8JnzXq=7r!I!mDpi05cas@vmvMNxZu|bv8aWDa_YaE>DJDnNI9^3qdif z>8GNMrs5=fUn}cRA7njO(%8NkDyj9lUJwl_8L(nFDWIJDBc6`#Y?(UUC@6IsEuQsi`{B zF@s{Jqr00<9!dwd@a`;gggHP$&OlC5=I_*%?E5zMvvm)-TxaCChnKIx96X4s37oz( z6+kqIc0I+Wt_fwOx`=3}r|*B#=>CvooC0)u7|tgS3|diW8~}WSCDqi$tKZ#^o-2<^ zDFsf7fa)V{XgYj#v&ddwjgl~L6?UKuH=UY^ny|6XEN(86{#P8P&Om!GuAzrdRMFBM zcDo_zlmHFY$@+FOxxF$vQ`IQX>XaL^Z<`8cOzUP`;i1s%YKD_Dc&z=k~{LlMioJX1-!G|KT zDb(7-FG8L)BYTfx@LgSc@bst*5OkdyZW<$3;qZg&4}s|yhdXh)5~4d`e|@9OnUx)k zP0PGeX)V2^*(9X->#UysTy*dUT$dPpMOWCS*E9`ltIFKkTGXe}EUeYo6dU-yH`}Ns zr2=gQ@|Dn(#!UwS+j}-_1X)#4-7yNVOc;$x#NX=!>hu^hi-9p|iKw>7)w?j;i9ll+ z6gb+_cNOIY8Vr(rw7*-mR=9X>45HwhvwbyPQ^P}Lh&#g5I>J9Ybx1;n-<={WPUN5b zUw=x@#Tr$jrKRSU8vPuQkSuIrVPX4nXjxQbM);DLsG_92K>H0zLsge{x6pql#3kip7W^THgI3PP+O!BB2Zw4%b!c8agyXx9ie3*uyfp3!y&yXc2U(#3=+Rs^ z4-amMmwx?_U)6=~kH01oe(&MFX?Jw?NY!RKc^&EkD_%x=&kU~V^5qyVn-g&QUDPsm z^7T8$?069TY3eeq#)&GY*+ui?sxD^(aQgMqm?_o>k5oKsx{p@oIH8X512BC$A6D&&-8ShLW-UecUKTrps%=fQN}!Gx4Lkhmvr=c~E9p-oc$~|A#~vS2-Zo z3d;nV=%u_i5ofw_9!@M}u+<h@LyO^YKehj+D=vT+KTYwpNi&)?kb7X^EGhdzYi4%A4C?&L zb{)dvtCL?!@2|PKcvBsYUzOtnuP(5IWR|fqy_Iy#a>8NPo%@E)`O}|_TzEvB!a@)U zT5wNBj)E>i=j%v#j_wHgsiymIE%hy<>k+!CC%$gENz6Mq3D0+_b)pe(7+pRemr|$U z5XiT|U_b;Sz}QJ<))ZAK=u}Fbf?8n8tBXg5)cxM1Dq25e<7$_7Cqri-p{(3A;5@yiBZtHCcelvp!u%^KX`g`<^Wfs%SBMKH zig<$~4G3r-IoAyMyE1<}q$LBxf!c_GIyJ{Sm4J{4+>VE2ub>%5ALABP6^2`%`Ub7N z6>(wAl!rp^6FEoi1k1js9QS^QqpG4NEWyTz9Di3aO-UgRgBHq?mdL)tQmA3Z{0(@v zpW`FUYC?Q5Fg@DWPaW6kp*KG+p{=d?>P)B0Gz48;VX1JP8N9r}A+Af834g!-Eoz>g z$0N!qow9Rz8EYi9EuO`8D3sOQ5I-Z}jfUYoYq;rBPvRdJm%El#U6qynl6+hCs$06y z9M6O2HiM-5eP&=j{iv*xfQ{MQo_HuB$(7*TRMt5cDd7Z>g}{SQPb$zD3m!mDk7FU- z2hly2##}U-pLgm2S%D!Jjc}F>elNGe&`P{A#3x1&H0EVE^)({7jLKKuE_f|Y zRW?`TX7VmhA#qj}W^z^+uU@Rl@P4_&HxGsw)MtuSHRo%u_d9^QSv(bQt_V zKwqgnTtvubdJc_W291xS)l)O7-k(p?;)JsOpgMY{Dz*sbDtJ$F?GO;=^}O1)iy~?@ z0%fX*x;oleA5;k(3DI{AnqN{PKt(wBrz7%t`@9iOC^hoAFVc-{WzmQzgx^5~H6O!X zsF!7vO9bMR<=i1{a?p{8TI(EMUR&FT`8oGO@!zHOvrZjU{x;KVTZQNI5Gzai(!24> zD_-tn%34>LOIu3%`l1)Um&TrltDEASYnL1=-`RU#8$50*8+>1RuESYE6?`>6cxeMi zhraZrF9)rC$Gt+^Y15CRfz$IMFNgM6!j@gmucK+rv!%1mQ#W4Ur*iYx50aKi=%apv z0a_`K{U8KsrZJNb2-W8df&^UL!lpe>^fT2fdcs7$)rxbU;;?8Hb|TP)DjXL)8Z+Tj z7fOFtmgEKTOnSTS9~>OCz8pgg{>D5^9cIU&(_zv;ItlxRL{X`!qgyxy$Qojn9j8J| zY0w$3_)4vg9Q88Hp+FI;D`k?d4is~>!{@>#C2Cqj%5HL~73_ABH}8URMI9j?1<#$O z{J1>`jf0RpjZhsm9O2OI z`T}5*kY2GIjZ|!_?|&#Sn-R5~ zn4EeO#khS=7ha~tIyI7q;#ql}0nOv0jf|06O$vqizKnsMx4OK7-kx}qk1wyJad9Gs zzLhSX5e_8XuwgR~U%)RF6c?uQt{5aWI4Lr^qPVCCAO2cM!qNe^$wtVOYgDo?V#U8W z3I13C`+vbH!t|&5bdQfas-yL^9{X6@IdPO@j`ZD?jGxN*x0OJ;|L$I7ndx%wiJqsg zdbi`4xrcW2yLu z^trU|eO>lAx~xv5M8FeO;;a!)aw>BFVQ^wV?ze&Ouq}{(*JGi+zOF>H^891~fKX4Q zG=xQf{1||$!xQ37r(VGoPJ4ECrh=;cwD>W`E_(C`*VZ;l1TcpfGW{TSjuD765(?gV z420a7u7=R!$9(`Aj>*_Pp?lsx$=`u9ESN!=j)(3LJ3<^oy`tNe5{{wT)&TvOPwV--8jV@9xCy>^6^Kfsb}Rpea7gdhMG8p_J`={>8yQ6 z205z_!u!3`jA^pc3yp?Mhik?4^{Np>WjU2YYDx>@7{M&;pua~~Oau>q-`)+Ou_sG)`!JcB`U`4MXt#lvHPC8taBP z(8m+HI7FMia&4ym&o3`X2IZvy#Vm!XYQw1MYQrJ^sOa`J`+g>I$lj6qzY<5ohmyx3 z;N8!w1h^-oM{WW;#duYBLp)LF_%6cY<77*p(8FeT=j#Zo71jO2AZmM&e!77-LXquo zV4+RI(KXeSp5}tavRei6ZEA+4k8$Zp7icR684@NILO>+&+nS7sv)x})dYSbk^$_NM zp~Wrs?b>l1Vugy^>{r`)l$YEt4h6!?xqd_YT~Epob#(=JrCI0dsF{#a`zJQWUP5KJBSts1qbLeC1uYSZJK3)9c`wwffPdpP;fyL(}i zE&*Hk^oOPN2fomB$5xS51?F*vI=BZW=f_kvmQ`Md^@=>G5->lm5hgE|C1+>*9mPkP z>{&1rrj8?7+1Nn2S#Osez3}djB-xmnMvZ~bQRu=ICc*Jk0Xg@z45nqUKKe{JY|dNA zGFw7I#oYLkpJ>}!@~%r@6DdJ8;7psE@NHx2Zmk~X^_*J5-OILk4dxy$8f-7iuVQ?b z#91kz&G~{;#_ALiCF*LbiIzNt1fVmVUdN~Y;qmaOc=AtS?J!qnPwY1?k@9pE1eL;QX*jw)$K~)OVNhn`X0cA}?F@3?Z`9g$s z(-QyVtl-rePPDj_8|AIvd$PmKefg#dLwEy&K|!MpcJIaYOm`(@sxH2OxBEFK)UTY< zQt639c)5c1wze_yI4eSKr{8+$hXlN$`>KYl$$vcVmgL#c$1Wb1nYg&5fN6-IA$G-o z{oVC`$U$uKJl^yRh4;Uli;KM8Zg>F*xnh$YTyoe9k=N-IB^A2*)LuteF}#!HkuTFZqLvtnVkLvX_EMeC$&BP0 zVnagbpM9<+V`mw&+vO-dr*p*SHcs+SXs~}X$ZD7{U(u&!7TT>7eW@)5oLiz43y{T@Gg7(C5@+ah^1T~%adWrdHKA_ohz3|9QM*qy2U?*I5i`?j8b@;qHX zPsaAF3Z}--B#(7>W7qs!QaLQ^&|a_HW|0=li9C4p#6REwb0OpZ91CBvdNlgIr!BU# z;sAoD$!@7ecmn&Qix98ZeMLrIOz1A@`w9M^323e4`R^sLeF#0?C8tTW(XPU6R)3|P zrIkG!i-GyI!fElY<9mcCSkoPzUoOkx3aGkm<;QPc@BSyc=bX)2H~;{{C&ldi;;ct9 z9w!F5ATl&%B}CcT+N2^gl5S0AS@}1S;6&04gCyy5PpcFIUV=NLioa$NX`l0vYEl%vLXOI3P4yx~&i~GWt#}!GlkZ&%X)y_>e zqI!^#uGfCHemjlw9^U$!j(vmgn$PE9x{D)O2D^bb=QXz%Qv=tA_NYo1x3pHE{o!O| z(d2gR94Dmreg{4?6QabUG0IWL z$@Ms+yv1p}=w@#DVDGJ*&06JqAUqCEgw*KtJOM;mWoZtt8{4$L!{4OV@7r2x%Fy`k z+hn(USrG7&=q|aGVr2QsWoX!9+U5Q)|75CxEZw`mh(OKi_p48DP=CmzVT@ zQ4VQR5ecVZnv~ebd9#`pEpBRRB1Rz7S6jZD^DCz12a0xb?tJWXb59V?rS8NIHCnZ4 z1?7-jRY5cfryJJjGPPF;ic_nbb&5%|zMVEoX?NI)N)RE%jU~`)(8agDqsyvB z8wg82)-(#QLB=PB7#7Or;VkG~B7gf7Q)O|r*A(0?-0e%*ksrT0+eBwD%Be{Up2v4t z=XJe0HK*u)%9D9Zl>@1dlz``TQ%d5J63w6vI1b3mw9x0V=xx5-MAFZr<^oo>saA3T$y?vR`OO^utLXqr)Z2Cw954(;=piK625&;?j6 z7ZzB&(reeNv~n6%*}9Cjz^lTDi9*m5UTq21lIExsTjFRaT>45la}w4A&E7jnS|Z=^ zd3zG}s9W1hIK&u-0viUV&&8g2Ify@=$dVV3@YkF0*p{oe&q$h6;RxI0%m-=NJDK_F=%#0>Wq=8}aaI_so9aT6+3+O}?Wx#)Syk6Xrhcpz3~`kNC06s>LfVtZ znuBv@mYMR2nU{7{zMF%AWG0Wo^cESs2>jZg>S zT+?%1M4!vouTn+YwoC&f09OXxX#=X%PfbLb*qi}fWmW&4bLD2|KK1M}NsGKDp7fY* zDN{#67DO4pOZT78l)V;MQ5`w6OkyB7>gYR(A9+b zc@JR(NHpc?YndWZ7%FsZ_N!-tg~_m{tGxPowH>A{aRn8z3Vu6gakcI{T&?y6P zSC*L(F`F-lm$Nu2W+lVx7D}CP6;ARzZR%&qU_Ll?^cfhK6w+Jn@L)Y#YmKjJKj+bD zw$J<{-{^T~t<5yZr?+Takz#@@aIPPVd`Xj{BE5wnUl{i!aje`KwfVQv67~j6U>qd*q_*2>)ieC3iIjk(o$+XTF@xr zfk}}|M(w1Oy_NClZKks<8NnRc)O5j=i*2nLx8Fh9;JS2`TDNQ;`Zr&NfMJw&8|vzY z@w;SN>`#EF?ekXAlAhY{gyX+ERX(nx*0o$pJ5*k4 zRu;!hoLc>b>BFx8_gl8Sp&RyZ|0+?-b&=@ZcX?4s=zPi-;Bi&ZT)6x^uJSsRgdgX9 z(2w@~Hfzd;FVj`99X9%8f@7iWIC^j3`Ix185C;*wf59&x_3D%}{e?C6r9#%EcJ4t5 zxFBFlgb{jK1m6>;P<<{>B%>@oT8%}TDeYm2_`2hgD<>~s0A*oi0*-ABz3_f_7*D9P z)WYP#?$zmsuTW-EfTvS2f<#6m*X(MuXXg7R)EPh3Q|Q;G2M;t4`X2W+4c-0h*iu# zF-LJ`R^_?Zim57$*VRd46C2_{QWQTJkYJ1BU^k&7@v7sNz+JXrAd?^+=raFcfS%-k zQwL+QUDN({T~)A7TWb>V)$Urx(Ol!@6eZM(2EDlSnCr~bO3pKXNK((^k%XwyFumbm zu^(hJC638YjJ!RPIM=o=5=Q&Me$Xg9@5KGvox1Hq<@ZCZ7=`H`*1_ZANyM4-!9eZ? zXwU<0&-x<9B;s`I8+967;dfjBbdrq?mpr>Gstgh|w``Ay6j-ZfjpvYj6Dh3iP<>qD zhn9-FF8gZPDOF9Fnd|Hm`g4ZS*X(kYpPL}xzbg zIX)FYCfvqm0w>U4P}vySd5_XQR+u<0f=TEs9$m^ph@XQ&`JlX+=UtcFN7Yw~%mP3l;js3n zPWpM!zwT(R{?@xUElV)^)eZB&Vii?7!^)||U%}vf&G4(K6m2`9mtfH^nC2sUU5~>X zv$~kJo-9?m-uPH>fo?jxjYc|i5_qiNc1EUOfULF9ba_Q@j2wwAI7U&9E2fkMD9~nd z@;s;wy!8wNRB>0!IIoYI??zRPKUasBe|kYe6V0eMtR-j+;54V&5DwKrut`q6BPF=|KNP2Fjy`*Wwmg@Iqw8dx zNwkJcA@DD}F9dK21sRha1vy;QW}{baO2PBVqPjo5o&*2@5oAJ;>%=ruv|KT~J*p~2 z@$L}U{Gw-xMzA_*_WlmxhMOvDBm2|WyQInZMN3xVbx0-jJb0Y5*DScrYz&R=ORa=Z z$$U1nC}}stPmXBJTWA9?m!AEr`g{0Yl8SsX^KUGkmm3ys_UX)9hQel!;+^mAf?yBt zh>>z{%!vK_!sX7p%DIKOR^l;C8|kp<+lzb6}gFt1GC|+JVzlMH)jLo%wlF@bTh6M_3?LhGY=RsSOL-k^vU$T1(EV zmI(=!-4~_b!s2j+m$+=r&Ff>OE55Bw882F^f2UPW&T@J^=#h9hQ~9Bjw@a+ z689A_rWnjtwJc~+vX10f*_r7(fxAzUq2k+SY+~yK0-mEWJkQb1?5gI(gD^cFRll!h zXK(8*L%(k3605U6QY&Q|#@00darft0SxA+Yt2I&%(MGHTsmElm($c8)9jF|mVh~kN znFZ7AFl)E8YIi7-)U^yxNhKJ#n@9PAy%H!$_tj>QW&6I1J6r7s_L@=W zi6t_=JWM74{Aq@(at|B#zJLn?0MQBz!MFU*R;{&8cu3cRH|T8^43_<~8WqmEDK-mg zwIdn2GA+(_C)VjlFOSO3R=x)@CnMW8ieCiiPHJ>?-yX#X5|hVO?9N_-#wf>l>gc(> zSC!?R2$%T0Sc-`kuzbVV#Ml*^AodhIEod^*5Dz%U-=L!C8_yb-V_ya?ROHpM@*?1z z`OEh=zwq<>U`C4<)@(toji|wlZ7fF)=3&1xBP-(x(}n=$%}GNz{Ne;t0QQ! zw^`KU55)O9IYDtC29h()tGapEd~|TqCrqvTX$om_^XGwz%bC08=O9hS+**>%Ml`mn zL3MGQ(Y6y|T3X>Ho58^V3+~uOM{8D-eMP}IUY&y0BpA}5< z*b&MMy>iQJFC*V58MFV1DRjh#H+|ow78(T57{bFTX2)aEV&pr_Tsh~vbTZ1QCNV?x zqA8=MW)*&A<3BauG1aEF7qJQY(G*U!o2J014qfNoW6=WNXZnf9#UxF^ASG7`vT)Md zaA`nz!DUTcJ#mCCnHr0(j44tWAj5LmBPO>P950+H5b01{J)!;Dhbw5Ox10aG((9}E zORE*LI5y+c?2%f=j(OzGUt6o=0!F_ptAC0T_@AOk628&`4ZvmtNie6HUD4j19L`ox z&Yg#!ln>JMx~;8^C22|_>Ei<+vrA^YT|q+tVKTZ|tAXWBhZ7eV8jP+@RI$|RMDqIY zMsZW?S}LC_&Z>5k@o2;lI~oiBXy-W5OX3`@Yiis=1I*N;amrfQJ=1he+r7 zedZgrWTdM}6-Y$3nJqny_2K#$yKC`42c?mNg8mQg3I7~0hjUQ$XD~itXQVpcrBG0K z$I_m*iuedp*435WZnIP0KA9eY#2fPzhjm+kXR~=w4{~C#N3*1LMO1e|b9UeyAdeay zDCy<~hZ_Ym=pj!JJFBvBp%ub;N@}4t17|29b%EBek24OX`M{-vy#btVjcc#VmTbsF zPFZ%;?L^M?VuO1mDBrg$eDYcCkfCLe?g>5-NwB(n|tNfF-dO!Fz+2w4<%t zA+I+^!xMVN#1K65f;6cZ@MKU{d?r<^@Ri!21bxI=L0db_n{nC{lYAAyk-m;3HP+Ti zP4`aWDz}V9JW<-(_G=ADoiD900u)BGgxwp7Auk_I$~OG8R-MrF>qff&>8m)j8pKt9eCQ)E56> zUGzTje$egVKek2+v-0g7nUl-#gb`(9isLaD@fMN-M)`1G=QbR%fxBVTQ4+O=jErB?iV`w=(ED1Tkg-A^WP9WlGPlh_slnL+L9UW7&iRdX`!*yQ~Herl+90*8gHk- zFM1YvOZ~Qn=CGCP*UbMcNaQ~YT8UWSyED6|?ZQc{`(;GN|9%Z8PTC5BPezxIPQ2~b zmuNLFWyACTgU~Qq$kL@YncwZrd)_HhJs4PzS?x^d!B9G@H#FAbUJ>W5hQ+A**8t!q z{QBKMHc>8bWNL~@-n_(8$W|LDI!+w=7OfB-*xFlZHDN`zo>fb&E06EAW%9aZjj+sJ z=<4d0DzskL;sgAU?);xt>HwIO_O+?W3}dXg87qTM7ADzhBKVms{_5ej!uXazVECmY z_Qtq0jP_w2oQ8WEcrYXK(=dxHR~9pkhx*VbfPIFhu+9F59)oyNa7i9U>}M0PkU^X= z2kPs+c*O|F01{;8{-A$(%Aqf1FAEN@So%J9^9ShlT3g_s4!Ks`0g(UgPovFZ+-5d- z_(8>X_F_Da?K} z{oqd5#SJ+}QE_WH7mW0?HnV{p8SQU$ToNR?M^b<}6aytNJGAZ+I@9+tje_QA{hme* zXJ!=zGfAsH%>B6PM1q2BFdam`cE4_pqc(Tk&+Hd({=3fKn7-QgZQ&dRRm4vkw z5U5r^zdLuYEn0ARHB{cL5QXvAsD{28b4LzL-hM!nfznH#GgGOJHp8)KRaI9fKjk!h zJ<&Y&x$w#cKrQA&NB~~O&?TqaBjt$xgPXW5#2LEp1iaa|i

~1yG<5%;wZ^H2&>Z zK(`DgnpSbnqMNyS;paZ4F{iEEAB1@m6AI2&9+xq09YH!eSbp7tz($4|vlv@xv0^*h z*v~dKWoN?LrncpiQy`4-k7YWo8m{WdIjtrG>kLEJoRawH7SPrL8B0c~knwXgM9J2X zJoz>~J^eTUmXIkq#RSM&0@H42Uu|s*-XDqH$#jdE##jz29ehsf&`ADeFIH-dgIa$B z*dt6)>9%VP%NewovZiURDY_V0O^r={_f}f>*d%{_KnDs3F@Uz7eGvg7t0VzHQmM^d zuV=UWjDFnmdY^G|^Jq1zhMq*UZ5^Q*GB@Af9@7684grc`J~ag|41gg3AHseV@q66< zk=)S_Pp5X?aiicI{%^rJ%>m_Qz3KOjugo?K2T5h*(R*KH*Om;S>^A>AEZ)m20PndL z38(FP|J$VqWYgkF`vFe*4R-rKY6SD`zd1JLJT$pN^jaKN6?c;r=D`aG@UJQ->P8YAjRnw;X|A6Wn`bsUz)LbV|y?26?-F%~_(oD5Trap$?N z+Z3Af!l`LYm(3p|8BGfQrM0%R;Ow0E|?5L{evH5pHGl7pK)%gGIRxgkV|Ma7;!C_Ots#Qg1N5;;M{vV+> zA2I(w!O@}Sll3+DT@Z2`YHLfEx5w?)G&Z=Y$m<8SChRR6^2-Y_uK6c^PaV&i8F9Ax zOS95(XT3sRb(}g|eAENG!9i)QK0l`->fD|Itj7^@2VRf=qZWRfJju?;!Fc-e`XXuX z|Je&bfZ~ZECP3=5?IVUcJ*&l4x6v(K(LYN9D6$UbKJj=x7i3&und3bkYMKnU0SpAC ziTsQLiU7Yup%AgrKmvuV@O7)_U)KiLRd%Ph&Ca*UhE6YfyOovz$izf8es*zrI|4Oz zecDC9cbEZ>0#hqVP>n-y=!B+8T(suC8(lYxU+-R1(hK}%1(lYXv9futww&YsLApay zz<)k2#L~hd4f)TitT`L)XtqGMW|H_S&w`SjPg^29*W)$K&CYcc9kx(^Jftc{{ z`LBn7abbIVx;^+#14~r~3QPT;;)0+7ET%F#EL2To0v<8T$t-&7kJ6Tw#rT~2&!_Re zeL&wkp#FR@1Rn9BuzyS2$|7`DSFG;ZqJbvuEs5LYF84rd8=C^AtE#z zb&t|)s*ITnfB*j$2j~#>hX81BIx3SP6{>QR{rU()=YQ%e_L-0{?^mwyN{4Iu=iRX= zDuhfyuZZ5<&uR35DDV5@bn5Qj4aTGDYO3)YAGo==h<9vC>gq*)RUa@OdWrXqV`{<)2#rQw?D684}V} z|IceyE={G2LB-Rl!Awoj3s1mW_es_?qqL{W;c4@d>P*?VD!C; zoZ;_w5))*+9WecW-)H|nO=OajhKR(iUbJCg9@~N3-UDCwF!H}W?y?C8*bkr+@VP7L zn0aq~Bw{i}1pJ4zGXue&_ciCqY0b`SP}@J8^p=16{J%dsdO)j_@I4uoi!YZyarsF&BmVq+KMK|a zqKZOsb@fD-*#V|Vq!GxG#6*m?sW@6x&C7M5*ZF_DVVs1#X3|4PP0VCA>pnd@YdWE< zV+waKNd_}B^4sri@}2uk>!`5I`Dlv7dE%({1PZ2LW>)2+`uLA@u&L|qX}pac~ zUUTJ{6n-LMTXx>nHC6^gcQUK-~`Tr;#|5+dDqfK__Q}`E&nCHtutOoZP z^8gk3Gtc776`Shmu`#(3M}YoN^5e&kO?T};QDfN{bJaM)91uY>)#=%pz6ZVRSR6Fc zhnh8|oMuW~N|u0#PDrqHqE;Yb@n8%AfRHf7lnWL8k5pO5nrdoREdU0o*p+9&JKwE* zgUJ*YmomW|@jBwA#OEiWSngrAp8*ys=JJ6gEZFq@W%7LufXBbX_PfHqt#SiL;^N_% z=Z~FMcQN4kPiX<1%CRZBEI>u?yih}@?^Oj=U8yxKD~lr;$KqCi{s>qA4;OlbsE70r_pDkCu3BH|?y-l6;mPnGF!n$?ydvMcEYy>p9E`VM= z1=R1gaYLxR4O??vgQp8c8n~f!xsBqtl%cD&c1~~_+~`J!8zt~|6+0?{=1+~Q_l*xr zEoC1P_dI{Pr1f_KGnT+vT*bV4KFRFwC*7`MT(Km1PL+Zy#0UOU3oZ^ z?HV`3j4eyDn?W1LmXxe95v8aJ#W-1$R3glvCNm=v4MU3smYHDYqBn|ev zyWZ}KXaVVVSpW)pAt`rs_4LfzW3tB_*(h!N$iG!hMiY$&k5 z&dRO{BXv1Kb0*mEJYVvB&;iK=y(0Ua4U6N}EP`8MQI?SoVM#Y^3#6Mwvc;AWHr3in zu)Sf`Gxtgw^%!5;E!NVPVZUpoNUl4dgB6$>#eQ_pKRax2q=7j|nV2P~gM5@Nk7;*O ztN9pil0dr{!ojUD;D0KK6SMUPe4W3B?_kpqDM8oZy=;)xC}+%0Yf)E^fk%zmqH=}g zx;=MXwUiZ5%DN})m)=+3vsD=v!soIu*m8YXshHhnnK9h*I{0mis2#qeVPPfvpT2y zE){t&e3$M()7FW``SN^TOU`mV9GFi`KdHj9Vp8!|Oi|br5u8@RxB7z{h9fAU5f_Pv zKZE1;Fe0ByH7$D>{dr9mRUEl@*TvY24rwkIi{fO}7UHHJ)P?CV2QEERO}zIhKxu!e zO^W{awFceCKoEd_fQiuMAQ7Y-`9;KnI0M6wz$f)5QYx{p#c2rB41nK0M~>budU7wp~_<7UB~ z;BrfI%(M(rE=7T~`Y1uM7N;*k{|>WyW)EW~3XFk6tM~p}zn~iB`Dza&8()(|_w#2e4jekv()$FheUr=U7m#|&z_P0r&;h0w z;Rq3Mt+&B>N9(=U5DEJd-d#K^NkW~o4+lH`x0%6FS4tq=ULce8!u#fr%f&KMP3FdG_#yaKwK0psl({5|1xOf41^+@i{~Do+ z5ADj&ESO(N1GRG`d!^Es{U6=QA zabg35Yj;A~e4_anXyt!N~ebiD4c z-gYtd%KfKbq(@U>wlihv+4y>k=t?su4R_6lkW&|+TDKXq;JN^;E?uE|uFlwPg`A9KNtygSMP)lM;A6a2aEr`c(WTHKn9!H=0AYZyg@k zS5a}<=B0P<-OKjd9Ly}U^Gd$Xi+m61&$W9=;Y?1ZeDeo zW=T?d?9lSG1B1laQD?t3StG_t;osXrWqLC0j*0fjb3|eaOLvyNRjH-+nMqjfKNr_b z7%KzOKYQDJY}l2VvVx~j-}A`(U`I{E-2)K(`f>z3^y9vv!fr|h5<_62|8ZA;R zEqyFvkY?Uw!Faq;=->cp@JfSpXn#?r4rA4-CGxI>5IJ4uK-|gHdE{jTIL1Dbv-W1p zA+u4hY&v~4E46+xz254pRmUsHG60pTO7Klr9pb6f%pt%bsTPFc;J3rGJ|~VDl6KpG zoO#;EL#KEJA0En>Yn#oT+Bx!bFfL+uc-sT?L39di^T{%+`C3CX7eBR=8%IKkuq7e|oyR@aD~}^BQ#&D`G^ za>IVPrgW53Ub$m!9CfjIrh%W{lm>|QQ3O1_+nu%T?TWx7cunAQk5ktCEx%6 literal 0 HcmV?d00001 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Airvolute-DCS2/DCS2.Pilot_TopSide.png b/libraries/AP_HAL_ChibiOS/hwdef/Airvolute-DCS2/DCS2.Pilot_TopSide.png new file mode 100644 index 0000000000000000000000000000000000000000..b8623b56a7233e0dfe15482d28392c01cdc4ed2f GIT binary patch literal 611365 zcmeFYQ*!t&d>uRK*va4Locr>hbMM1_KQ(q$ zjWui6%NldfRkik7kpLwbWCQ{PFfcIW@3NArU|=w&U|^8=a4`RncaZ4CzZIBtRWup-5C0x4eubU?F zdtycI_I3QW3FMrR|IX;mbh_RcbVxhyv_PYs=2n`@ZHYO^>%U`}&sB*JBT_OAFUXwxhA{~#5Tn)w?0|DYgVSz!JDqW|3Tzkc{H zZv6lA1Ml9AhX%;(|JJq2%;S9jJdDVY&*+ogaMG1ljrht+I)2wPtYH(jm(A;^#qOsa zhE~nwCiB^axw(YTXp6-%#b)PYrH|FKo5xN2#i^;7f8f{W$I|L*`InARp6{c!T&e17 z9jg1bk+9x>XKY5t4a?_nZ^D2rCF$4m=;>Uc#B1FMr12Ze*DcH9NG#!lP*&fEyy5G@ zFM6^(zgNrG&!=8xAt9kx5+>5#d->jyFCF5)3I#;gmX`BR35?nKFPZuC{#+!2$%gO4 zh9xz+tx1!I3s1Fv+kG4_8>>Cio4;)rpDfFNKdoYp8 zfQ1lxFGP^eVwh&!BC5@sJ0mECB)Sd2p|9%C|5(pgVZ~eWKh(PH==XUx0{*v1;kv5} zdeun01s7fOI~YU%&@>H%9+@weQM>~`9DIIm`>bjxU~F7xeDM+XRgU8U`8Y3Qp^b%S zVn9`=smcmra!|od>~?}aYX40XMTbPdb_H`aZ8@X8+x;K$X9)@FYH@L~Ob)GH2L}!G z`Ph1B$k8vN#e@h~Vp<9%##b#ZtduXzlppy+yE+X5LW8YO0Ukm_{yPjVu-y`l!_R+FPbOYO%EoS~d}mwsB{~EA`P&s1i4>$-W3r!^aD+ASex@v+so`A)>3>#V+__cpD}bByrMRw!diUdV<%5tmE zg;-RejQ6$ZmLYBEaMe>X#VOZClakD$8?b5S-{&$HyKbelf1*|AaFhMLH_I#dc&kWT z0xwOh6g+X9Z5R36=%rxYIv)&M07t@B9n;cjD#d#}ZZ}7+p*H6GUJT)0CY15mppgfy zJmi?o`7xhh=}}Y-N@OWy%k{P;pSI?#C-adOB~VOD292}e)j<0+v}bEu>QDM&`_#Qx zx^VG5_#%84VIGBHF zPWtkm?hPM~twDbm_8Nn^ZM2kaZEat7O!zkjTozY2Uh7^P+YSoqd>0v7TkSz|e!Yfv z*$tk9ybn(?XT4{W9JAghd%*H%K|YJ?o$XhHSQ{})&%4^DrG@5_uU{-*m;RPd*AHHn zqjB%UZ?SFLmK{LN{WA++Xv@`BKy8~4lfTI0#)3&g+9YvNPoOfudzBc=W}}2uTS(Yt zBI9K|-E!~NaDJJ=esNAKiTZevvo~iYK8@zUeW6U42ic{wvW5;cRG$UVS-@RCUT1mIz z{(d?oSh}c|q7bhlZDVMtm)-HTbC<#iCKBa#EW+TGaN<2u;b`MYrfqpytm zA)zV8WMRa&7T4kEsr6Cr!*rG^+hjbR7P;ouu|lImLdS0;&_K|Ts5Gt?g_@Pu)3_+@ z#ZUP5z681~{$ysbMoex)a1#q?tIsK#ujGwYqM^lTN`hUVO)nW(jHV+F+%CRbtieKU zRngRhMMkMzeahkx{;EEamwqsmrtidWYLa2TPa4H6csPHnXl<1TS&%1Z(-teJ&IAy$sjVq=zkyZn5|>B_gZ@!)&#-=HS8Wo^n`nZ;-RoMepl} z!h>%vBXa(EdK#@=Yxd*iX6ZE#tY^ef-C1un>#Sm>pfpY}r^qrnHX8uXZnKOI2{BbH zYWxNFu&Gjn8eT)MtsRlRrli#i^UGG%MCxm7T0aDZQrNwRMS>}3spw+_+JPYFwB1POI_zgtMH~R77Xv> zTUI7v7@IMFPqfhRL30{T!rmO0O@gq4wFP07NVIY1kx2biUt!Uge7w+CBw7d%oK6t2Bl39?YPA<7QMYV7` zVrOEWKJi}VuKK8`)3YtI;N-buz?+&23j}^>7FU*G?2L(w@<)zQgx2j{Mq)jB;2)kX=(|LqRsKbR2voSrdYb7L8^la) zPp1F8C44-|7EDP|8JdHNIUzLzzmx-7m)5+;bOR@3Wo8JvR ziZl(f<2`SF=v1WFN}slC9-Y9lOsT4Q2l(`RwbdH^2b+$hX|OEHVj%@AR#!Ifg;vvk zvMV7@Ho5HGpL6!|)?C-bz9L6!X6wzQr)AUPFt{P^K8;qiSBjE5f9(7v7%2kSraZLx z67iS-weCXg#2m|hO_=Fl)r841ved|r+_J_u2z$21mBu}h7ysfE{&)|Xw3ISX9lBJ=vdUl)`DePmXt8lz3_$*Ir6BPD&bQ zR)G7Qm%qEeO@x-?W5=>^N?_*U0etpEp|7etXHp#{;y>}{+I3idFgfYcnPQpAWnT9_ zuVTe*WTvRD$GUJn%ys-mcIpJ+tHIqq9E&WisL>VuY>aDc-&pBP@3NZ~()!1e_dOz^ zhqL6@y4!=FaX1SyzV6QTsW1XgwQUo0reR?$3xqTVtNzR4em&eScExF;Gm6<|F%4-s zBNb@&AKyg|?y^t8&IXa|VpO6s z%0US7t48$!`1rB&1FAaoKmUDOLBA`#h;m-y^>}Gp-I-N3jel>wvM$>exUd+Sif&jK zK$cm!|IB3Ve%N7WqRvUFo`K#$?!UKD6{fVH%g)}yiY=8IV?h(_3;_LbsqS5+5oT>y zHs#MPttxhG-zIMM4J zYCbU_u6tXDrZ8bX5{e2#$H2kBxChH@l-ssGXJ?RgHNa{6uw^vE<7@BrtsD+oe`(ut zJJ8Gy>0(Kvt~K)2`!V{}=<@to2Q!vwaqXa!lf!-2%Ln>g^s21fyvxP4>^Yw)>}d=I8A=8`c10=-dx#E zb!v`Qp14aKb*20Cj)*W;T+>R}}TxYcdsvmmhp;A6p@sp=z8m+%^WDD6xB7T|M_dI!5+eXlYhrF2a|GB&yK-Vd()N@P0RCkvn!;aLW?Y4 z7$5hY9(ck!iBP+wnlrpk1T}5qj9hy?LIQcQ;@`L2rEj;;p0u~&H+{K0t&1bb0v5Bj zy~R>1V0IS3sj0DKm(vfBp30EXNdHjEb4BQ4ih`Mxm_RgrFetSY#W3xPZ%cZUNAqr% zi)BU*5r5#?eMh&bxSWEM)IDk40b}6$cN(Dt84pvQVx#CCR-{=;>Ozfo3n~s48fLQN z>mPB+9zh}foi0;cW~q}2S%u%-y4*OZkK{{R?rNAVtyVh9dUrdp@|=7%@S;~;-9PAk z|26|YX_Uf&x&1Gf9ZAw`Jo!b_!G32p?u%0p1_m@Q-E{oUFqf8hQ{@OKlNaGP*zpQnyEnoKJcA+3wKQLex=KBzR7wuLwT}oN zR^=jtx@4sA2WV_FuT{o9aB$R|%uo~>!56{@(5^A&@`BC05P?W>(F87-!I&7S?9712#F zDxouMsHTFYH>=PrcoV40D*Oz5jQe!l*X6tJQ|wDw`6k^XOGi3IwWb!Pq_y=c@;VQ9 zf&uy;#ZKcP5U`akp3$GymrYoC1+o`y7S6c$Le`eg654D;|>dUEqAz)dXz1uy)$ zRIGUmoqI)2Xr$^1nbAuI)2_WYp?alg*q5`*N6ROMSNc?XSFABz`*>xPoP^fM%C?L0 zDW(!hLniXcn(k=^nsx=HVg+Ylypx1K(j{YDG3pxA21UK9TcaWdP*W;9#La#1HDHSH zmXq!_ED%(ELfOwx>iGnl!*09W!*IYhKRXIVR4^P2FROHhen@?-ITYHXwcC;!AdH=d z_}cwoH9PMw);oM$CF$ARacxZgTnmvxr)PmDMv6BJ=?V^1KWkeKDfJ2x20v4Xqo1rj z0LFTfw2b~51*~3h{V^acO8|eEvd{EMQ~b5k6>*NN(#+K<*=fA&&XBAT>Y0nXzbQ$f z>yjzoyqQbR_IrDg5u5E{m?D|Fle~(bZe+>9_%|B%hi$TBoeUDHz|hk)4uhrEK_LO- zo=ZaX-reS*8yzsl#NuMK$R2OrKefPS%H{}(zy=^KvSLhA&BX+nNg@@(|Af6G2@vcmdQxwwFkyGm%f zW&}y+cM7vpYDryado_X=b5ZyvZ|CF`%3pqIe6ih>_je#K_eg1KQ%=(9>)GP3Xg};8 zm^oC@tIfqz^bb?mZSR6)Zu_3(-zoVHzVjJ}-CoTiLjW{A_r#`uI4Zy%{*c zP>KLG*>V;M!d1`HLht$vwHoo9J(HTU0yYP~j}r)A)}%5?>MzJ9O90Z89k6ieh~OYjKv$PtR1}B$(EE>!O+QPC;!1+%uwzUJ1fj);b zOD;($TU(Nu)oKVRY7|$2!aRzzWhWP*tlOUTscBOACYF3mp&yXG%!$WP`dviWxeBl? ztw(311Rh9JsGt=Jm^VwgvhAh$GqP3=#Zl0zf}1@E#CXdD6LC;j`^Z=-)l*n4F{qNk z6VMnOU~H7Dj9{#kAANwl1rV;U5NppNjhZmEAbazQV$v=cdOg|wmm8T{Fu^nPDY`qx zIL+5flWPvYJ}+p8KG>AF+|%ODE-Ef+(8cj2)Vt<^3$(Vjf_e3Es*k=6k|NA=ZY!8s zgMQjzx#G%ON}&O`8{o%|-&WuZ!5^Z)oN~CLsY)cwZ(LBdxu9JHoq4ns`!++3bwMZ}>nW9W5 zOc?PTQ~^YT4|r?4-QkUMMFos(P_bzlw0f`+;sKzQ2am~_fv`C_x)?;20s1jY1R%!Qdc{Y@Ie>Y3 z#(a#1-i<&rl538?jH?7Jt+k=dD@<0VZF74we;$b%Peyc5)n^gmktuC zr|ns_C&^9+F7K}i4wlLpr-QEu%TB1Ic z^Vi~ejr-4^ylKC6ur=MmuOI!Gcw{1visVKDIV;3`|F+;_$ty=``cLxU7k*EZYiqQj zZhZ+*p#E9$t!ea`BPq`9cHt5~4jX9hLB+J~VgTY|0ddjviy0{Aqk7K?rCu%P;fHim zp7R8VGNu|O_lvf-$?~3RFSA4;Uc9e4sbMWIPj~dEn+-H|cGq~4)H3;*v1(*w zJCrxwJf?OequqNSH4nlQhNN*N2c7A~6P)q}8t1-RYTi>`NUqZ+kXNhK6sPJbS*PO< zQ+1wtPIWaut)`>f4B}1pz3MFDCm%K^N;GdBuE=@_O_Q?#N|z7bdM=A2XvD$*t4BAX z`mvI6J2*a&hxvErdlB4mT#856&Yzv?M`hEMdr2l!l;dVO&8&smHk&FV3R5C7M~Khq zg;PR9X`8eiYfP>345pl6=6(hC%juz!vAt!>r{S1Y6^h8hn5;Y}?`qum{7!(23eZLLzx;5SetQ2zQ(sT zvNX(A90#m`z`saM=?K_t8G@U*V{;$wza!)AtB6vTl^luI)GVh?;B0o#3aClVmZ)g+ zW`@Cx)3FYgDLYru)cxpO9!&!B38BQt8$4ObV6ygLq@pv>C}+(admALvSRq~X>*7@{ z%Wc4tDpQD3m_s?RFj+9n4)H@BGW0S2T4v3-z@#CfrI;O53r)pXqO=c3AL9T|OVrt= zgjJ;G@Fij4R!!=yzF~~ZMrVrlkrNOm-TcW~_oV$?xW$9{X%P`5R-V%iA*INhgR!YZ zxAsF6Euf%Xz&Qd1$!xpyFaY)H-huhdM$W}%;S`H+*ocG!9~WoHNG}EY3@oH4%0q7} zoi`4;fsD6b{73MIL1jxAD{wy`->#=JazVQlE2#GRZo+AlaUnof&3U;zkUuQUx&S1T zSRpY~I89-N5v%?!E%gZ{-Jv0b7e_g=5qos#gIT6|JrE7-c!%bFSzIdxR85PzWvGQv z9=X-A06uV&$yY<!C^(p9F_OTOLQ}2gpl`ebz^Q1h2T0_Mr^pMl(88*$j3G{- zJzxa+4#oS*;e!Q!EjURJQ7vGP0t^A}s}Ii=#mf@#D!qxdYtw5`*8@2fxU}X=k(H+@ zSU6#GZbOTzDv?g39JyIa5$=6dp^tzP(SBHR${k-g=y_&aG*{ADFuCzVxauLITcK-A zQcGG!2OAeXXR0GCO9_>rCuoG(2wqZg4WwrPD%pV!%g!CijblFUgQ?OIRad$h0{#Ih zjt8urUD{JK8qRg2;Zm#tlRhmA{|4t*S*f^YcuOeUUMMsvmUUZ_)X2c8KFTu?-0-Up$!fwQ*kd>3j_2;^)c2` za)XKm(xf&1tC(Y`kTjcLn*GFU8IAW=C_?_mxThaX0orwmv`u7~U(xHrC?(F8a1wR! z{HAnpKW1;peV%Z<)7<@?-ZgwQ`M{-pxK-A9lb<6U&3826-R)1VbNkJ<`n6kaJ`nbv zd`?;v5HAdUdxQ@9Q^+Uw;j^^8vW`^4m;RdTA1ixIeQfF2qKb-H?0%Si*@B@X+XgE8nS z^U~#q0{u>hC(+kud40S)o3|n*6V1af@=ZQu5Bxz_W|r`Ia)rGo3BKxDe*1hbk-RsI zdPR9{`r7lqI}Y5-RsS*#LgiGRW~g5jd_o7?&AVxmXp-Yu?`DVd*Fjtn1FaQZugQDP zRnSE?-creW@Jk_Jw&)E#X2v#4Xkp>Fnle)=P)%&=3lx9dM1Km65CK-6Kc4dnNNGmU z_dWsUV&8ssgCbx%0l!24bh|_bHP8oDL_qqYUbYQ?=RZj&9F-?1t!pSb0R9-!4tpJ< zH>vb~JR>$f71T)4ng16js$BJMBWg;lrsLZT-v9lwpSp>w9OX2s@c#TF^3{-XPmaG5 zTBD{3;+|^ckH^U5BohDfq@?DFa?&=KkVV8_zJ7$=x)sP6R9eRd3{xH9QDE5q6s%Un zx`~{Tp*w_x8)c62rhk7_&tw|}R)*xOIw}SbAV62bbLh*};|W#SFV_IR-8f{oiP%=J zuB=c@lz21-{dzoA&`TKwUdj-Un{`o;wja-}uao!i4eu*MW1%(-{o7g#*s@k*i`3!( zs`6PgS0AcHRg6h^Qbl|Zn>b+mog=@>#2-jZyur^s!d4UZn-Zg!@zv>&x<~7q4mHcl z0dqA!g6>H}_BRt6{jrG{UyS_C?>zQ)W%(X$o%88*d z^}U6=flikg3&0P^zTd<;2#`OW7M7(EJNXN>8#9^K`u+93mofY@ozLhG71!$s7dI!S zmXS`;ZB!OoP$Z^aVSniFieO;!upsjPJ3ur&;!LWq{#VeQYju4wgv`qipLt(!X+9~D zxrem?+@ZVP-8{MZZ$KZ0xL9~wf3&8_!t&s!(6nlOpct0{2~x!jvQ!Bgc93RqfLeA< zUeRD{OH>>#j3LUrr{i47Nrds^H-6r?C(dzjTo~<)k2q7!u;NC?egc+>X(&L@W3Fy6 zyFVB)zt*MbDFm)rMr!%sJ7T2_);vGo~ZS9EZgk^+?QL~VX-v5rA;b+hsk;(owVAG z9JC_lh_M_y9T4PV_qW`3w6w!H%CqDSP1=q*?QW?Q%E=dSBPn2 zO>P(;T-y&~eopyF`E>q+ znKtys&%6Pv-rjH%Qr$^=j+9cLiA3!0|GmfFql|Fn<+SWlOogWaD!4^HDvn4u<>BFX zwl3UxjMr+rOYXv905AF0q$0g5)pcs&{%Jfwx04IuhfporD)9cs^Y z1_y(lHK(aa(fekz+6c9iuyb*Ra&fTFHQ5Us2wJmUtk7Thl01lH&r%Agl)vdGV# zhx4H?)t69Hr9_ry%{G}W#M{X8Dmnqd>r~FE1)289_hS2K&IJ2=#U&xJU1V#5=3I~3 z2vi9FeYT-Wn7Gsc!QGd`y(B5kA9`*UvI2}1T)iHve`DrxM>#|@_dY^gtLQ10pnbvt z!aDkBAc_XV!2P`nxQ$MYh{h=?pNL{KB27o@QAMSNmt>K*a!x@nu32{J$>;|zDmqW? zRL8VJ;fAw@C9de$HbeAssb=hQ4Hq$?J8R-}K@*0`vs+3KYNSL=zV9A!J)v^uogC2! z6hq7x*htT|qJh`J4hmnQ)dOAPe2_%FwEyW?P|h-PDN+x^i8HS9S)*4@0W+bWU8Z6ovIeO zM4`y6Zi-*LL+Q*pnX%=(*6v(&qMRXQ$V6g^-*jKQ1!LcZU0#nDy+MxUG`AZp9jbQK zaoGMTIGNGyEnkPv(dm;zQI^JrYeNNQmnQKH1TTZhPgdOcBzL zPx|dtSxC0?aTOGH81`eN>wdfQ^sSC%GLUHnBQsk$8e(~Cj5g?s@gZVl?@sxCtY2}T zj`>Uuk<^Z%=k0AWH5do8 zZyEPJN&*hdn2w(mk4#D`9Kmmr4HCVn#(sk&NgRR9ylj+%0iwT#q6aWW2_uE(R$juu zJ{1s-$N|U68jL=mGnEuvfX1>X?1*IK05ePi6$vmha)`@}`peei*sVOH7b?)@jnXpF z5&odYI*8Krmkg_Yf5j~EsoEuZg-Agjh>#*YMwmh*@EZnb;BWjX!;6wlm&pKP#u+_IrSa?J zQuKU7){k5$6YK3lArqdmlY)%yy4=D^nSgV>=tdp5-3}J}RXyy$NM|gn& zSdf#@%Hv38?q#)EJQ1O2?fopNCpaCvTp(_>8Z7~nOj&w6Zho-5653)GP()jK?#^no z@(`rI%_!MCBoJcOK63DU>VK&xS}MAEAG57t_veKP#pG{f&(+mA03$dSTX)w!Ae?>7 z6VN&I?Ssw*F)ZLk{|oVe5^~fGsc4vuNke)UR>-xO=#&2myPMJpsgF#|t9V9;pY$rk1 z(^i@_=B_PMM|@GcKN5&;WG?)Si@sMiAzPR~`c}ulv=|J5@~Ij=N`8UqX^H8o(Cl5; z+f8=fq7yF`=#EtL-jglPURR+jcC#Z+haja)C0Y>S71JwCc5rzW!qC6v*NKqHQ0(A) zfC+@*aro|uY-S!lr+Vq>vr`K`(568ZLhB) zTc{tn*$01v(oYqyYC{?8uEcycz)@~<{DZJKZdYIPXbxFzD1bfQ$XKQMdQUie7_7Iu z)XSJW>Bjphn)~^+C5%pnpMzzmw77^kXZ0x~`1(1?gVfmb|D-_aTweJODQq?|>|M8;dM21FhwD5yN{?_l%sXSK_Lr+a-j)>2@ zLZJu*GBeO!KTZ3!EFV+FcZsK2>+T1YWyQdXhQimgE3Y)T^#)UNL zQdtb$JZ^1$woPqJL)?%azNw>MsONZMXZ;ziO>wzVQbKogG&b9%7>kgTawlGEwupD^ z2q;tk7Mr~to;kyiLj;v)nE7-bs&V~8AnQ~u{}U2{+jeF47b;IlcH_T7pVLF0ypl|* zX)0vBZi}mACsI0Eli&9pr~iacuJHIQz~y$4en*YK1&jOf&EhAo!X*5q9NZtaO$3NX zZ2HK10tk6DTB#H=VvgKp1_TE9jBeu_WmQ|Ph?qf&T97`7e6 zPH>e?8r;*{W~iW_z+A!8PzFs^f*5G06uNx4kX=gI0KfT60@UA`S(bowy}rAVo-QJyei2>Xgs@ z8<(bT{YAfLhE#lLQ=w5XG#bx-t~Ja1-~W0 zPgD#x(3~|u+jql;;38Zcio-u)wm_DYBUpO400oF7wLB$gw%<|tUGEqjWYHEHj2)}q zI92wO24Mn;)`2yc_*4%+auF8SWY1S#77=wyDI6MpFN#KJiN2@3&CZFQZo8qMYhfv7 z%p8hilz5>7Za{vEAx{8mdlG#b8~+M?7I{FU%{>SW2j?5+Vi6+_2m35-U8QGYfW*PS zUG&-AEa(CIwu}tzfWIq>=feW==Frf16X1^h5KiGEs5BSC*qR|M;e z5>Cgu5?#E*A4Kcz(9iz02uSC{*lo;>hr7b00Ou-{XG$!^wotE1We!kr$+7d}7P zkLi(DZ~$dY5&X=lHeNn4zJKlh;L99#o}}2B%>6bp;}3ZTFp67(K@;WS?>PFnG|Y%P z!>yQ zLhrb!_84lFkRbGx$Rb`M!vH*XGKf*qO{D)`*@KE)&HlzNn8^zadFLe9l58+78EX}! zB3jInO-j85KSJ2jY%tT-IuZfP7Gwxv$&ntx^)yc!k)C3m`V?%p1Q=)Le*X~)wf^30 z-c&RlK?OK&adl>W-fmJ;^B7#9Npu_MhIxWX7XWbYXHG@M32*iHIicAKr?7FD7_w7s zwBexV%c5#_yc?(=X#W9%s5+>_p%K&C3Q+g^&_H{ z==0b%+N=V(Vn(~gzFbZBT#Q!cVN`hJI+-MhB?1JPt9Mllo6TK7-6Ax%s-UsK-FiHa zRm1*4)~St>M1)LDgSU=nVdjb7Xw9(OF4u)hR_GsAn_~B_y5f0z9~516h_{aKE4fTk zqnF|D&*}9u(=pT+ZI)`7HP`6AR)aTZ!7>NhZ+1|U`PaX&GKo8iweARNt3FiJ}HB3VZVTn3X9TvV~mdRgFj@;X~;Kkm+r z^0&!MItvX{I-6_}uavam!T$LCT;nwqflhv7U5BTYnkpx`!rHg6z3{lCb7t9NJrMFW z5d_y9HNNR$!|7|o^tF%SnrcvyhN;z4Tuib+c)S`X&0dr4pgT{={wI_shru^&ETdsV z9>r^lmcVvqVS&^sceOA;RB42hTA7+Q3?rSJnpsUun%%^ntD72inCOC{_BZpy#pTe* z{FMjc%%JQ>_z&FqG)23O?nzxVLH1@&0n3xdN5u`s8SlS6CRBL@p;VI{bd#iYmUa`2 zI5Ty|7Mdqz)!p4czJN+S+3e9FRWr(00|a*C)LsbG@ayur0*L!=)dE!k6i1P;9Txib zbkKJD*R>dA!2trV7Ep-K=Cm+RL=er23B>*M#ErNLUE#p@$Jmdhh2JuHYAklLbfBq| zWYr9WIqlGZQQoT6^Cd=;KUo(W0ck?Lt}HvI$WR}K?~*(<)+_v&U;|#X%(oTa7ObK4 z5P(wDg+qM`7H|((XeMG6sN{vOMuRP=AysJ9Rs$l6=n$bWA;G+)1Agsm?fJk}qE2j&|_Z!${hNK?o8zw_4_s!Leiy z1t7ZOBkoJ|Mf*rN2CTmoCl@iM)z{a`zY>R&J(Thsl>%Y(j0+jb-(?1i%rYgCh4>ST z?)Hdi9SZbBX$VuPF(M~t=u-q$3z#O52i9IfL(~bt;oJ(@U@ZFnyb<}G-4G?<5U{p+ z!Lf`U+`&O_QIMikN{!xy1gx+`Av2R3T?UPy%wl+kLJXX*q!?F_@`icra$hX4>h)Wa zO60_QkK7e9GR9)ul5A`?XTIY-f0J};fSJu16X1WQCEa33k>;S7y+d?NRBmHkG&3kh z_#N>`PDawbNbVPXe>0`>SipCJ_7Wx)d(;R8;kWg*+|Z^zr4Yd%ZkvNjMHlcRb}|v; zDG%cRevB}Nd{?S6r*5dQPj<&KSDo&y3g=7A`r)wzFgP!O&6eM7|Y zf#HpzK_pkiH@2cX4ooR>&xpggSo;zFTwgMn@@ zZjQYxwTyqa!+~0Tx^t`A`yt{FhJO={Gg>CIT7T-MUew&MS43I6Dq9yaO8F~-biB#T zflf3irtg(2^iYt*ew7g_n6WD`z$+<{7{|x%@QsSPX&I9F>)|!cIJ)}=D>mR>i;&6Hur2~}e*R{2)F3bZ?ORlG{Kg~_^MAYg?x z9M$S-HF~z0;!DA_JK;r?cF4+qutB!%?EOEJhMOmJTHn-#FW(Vkao7}v{}p^SxZPPK zo)CatigcaWT%oFZ)24q>kD(>McCc4gH}mJ>y#)F-`)wtpu}RQ;Vdu7?C6iKXjfnC> z#o~lGJ@2@^HQi?_*QQxFs#*lGQVx4hiS4{~3c1{70bYK7V@b&3tg#kV9wp(O{1?7|?)fdzQf1DF>EJ?mv}qK{*|rH;`de5dfl zcgX5TU(o6);@ei$>8Vojw0@Ed%+<>h5_7->w<5tD_$@(dHAbi%Zs67b6g$S^*iNj~ z<4tUamX{C<$70_9=oc#RDGUf?#d-=b^$tCQi;Q^g40|IEMWw{|d!7TG=~(-xY|HP=P-D zc7{EHa4OmW4bFE3iGu`y*yD$ShM7hCMfv3bf|AG15#a}aa?jdiXyB$Eum2ET==B2Hm|y3%sMTLB0=`me?B1F*>K>3ft^ zYGZ^7)VvO921N_ydngysb_)`vUel&P%A#JQni2L(Q82y%>WqnD&zk{gw#{lY z)PaP|v;=c*75!vq^{N>VIk2mi6|)xmQZ30*cwL&QWY}y)z60GuYIasARv@I(pF={$ zN*gT+Vjr-WiyJ&Re}o-peYb_zQTB5s-W|juZne>fGm$^QD^J3LkWLLd2rzB+rGFFC zE1{t~4tT-ZitN~~uSCQN??^Q3S`Zo$2Y))Or-dW;0DBo4Ez#~-l5qxM z`h@w@X7L<*+4p-MyX~s!lW9OS-1c7dnh6W94&vj>$&!>UHRmhaCX7?l80M*K5xN}% zFUT(gd%yd}a(XzraRn^0!~#+Oqii(-J#)Ng&*62iB4+a3Z6Pj}?}_JBA-Qc7VWOC9 ziUrof$4YJ_b+YMEZ*iR&-M#bFl`2@`O@KWW-M0Y9XV78ktY(l-p?Dr$*MvVXPfd_* zfac4ME+3!2A!#U^C>MQvdcoDL1anX$nPD)b<)n0kpC&G?nu&t$UViF&IB=4poKh}x zkD30fIfl)|kBJ()zfq5P#N;F2qd@*1v*mlJHST$%s6SCMyNom@mSS0{Aoz#b81e+J z@hN5sa4Iy~QWrev*-fj0A&SwodPR2r7CkOocVw+_DYqmk5MmO~gQ&j8#1aVp^=i@_ zV`*zkE&?Tn!|4M4_3v5vV#jB?UY{YWU{V>WATcJWxVkya^N+BIXBUvcAQ7nG-m0No zElN`2&8lyp!E&KBVsudjH_8&}uAn^vXEmXGwZ{)igQmca4!J1J_s983Eaw+6{3_z; zE?`SkpXFi35^4?qQ#xT>%nr6RT5riv9XKXSeivYaW;)j|%=2(hjPcOrXUA{f#$}pj z1}bcl`9k;o;CnV%#!(M^ZyGKqc`M$k?b@x#`RlPM3}1wKq~i7SagcSymaPoRN`F=FA$ z;(GSI(w-0Zm9-2Pw`b@oMLJ8$s2+@x?`<{keIwvc7cATAdwBHF#M1pmA(0W+_H+R! zXUrVnfG5WcS9kMn|E~%TdJs&Glqfj6X(#VJw8t?Y?VH5E{rP3@&JRw8JSx2jv9TEQ zxUZF`7pb1^+qIxE!ZS_Hax<}?P)|`@76lcX?Oe11qllCE1cdQ&=SV~0K9^erNvq=U z0qo-1e_r-|zz*Z*w8D4zc_&q3qR#fG-E6)m;`WfqFl+Yr{ec zn5+AOdg%>%`(=b8be0r`J9z+7q`h&gJiS*6g;e1Nd+0g=JAfd##6vUYl6Ob#R714{ zQZvyYUcQG$tDeA~ae`ptFB4&K<7bsSDKSZ#J4cYqjZgh2(t8Vp;G#3`z^#6NXPdp| zot$^*TfhPW0&iPE3MP)^Tf{NS9BM#nHae~T%~n;>#N@<{@sAxl}m|~zg{ntPKuN~&2-VWUhjaIv7!G=91t(9dzWw3!lc~9=Y8=M zeKm-Z-*kTs33WU9(_fY`aO9Wv^dPJ((ivHLMj7}#fW|L7kv#JZuL@J%)Uc4!+&tBz znvV0!n{e~fe20}mb%*#h?=MxbmPY&fx9%;1Pq+S9zD4l-ZRM%l57wS~aZr{nkH#Ba z?OnazRbGVA;iu!~{)&$`!mft3dgaHfiGxpgEx&(j=pQTRc%}N?@8xSYn8n}^uM)0C zp4!|l&|F`4NJl?tM!RMj6|FYaP0u&$h3Ggxl#PH6+2S>8@SUG>A9r2?A9M_L6MM}R zXzi!*IH++DaR1iTpj1?u?mnh+nUdX)cCeB4MjiUaO!+9k>*{WpF)AFb#NZRDTaRQw z4i6sq1h2$oP8f2Osb|Nz>KvuTpZ9XAE8nNC?y2HKQf)y#y&f8Nh9IuQtT&m5_W)6D zjd}w7ZL#X`i+yEkIyTj!S)#7xYUB#HhPk9n35BquhbE2-pOF+yLK`3*B5_aSa{W5q z>K~CO&0VkR^F-7B2Ah{#dT`V4NK9A3QB z`$fsLD=A=_atkBa5K5=9*uaAB5YvlQ6ZnKn+hcx7#RcMG%4J1s?y0`~sEDY0?&Z9&%uVG>JOb{Lzkqn>C!@1 zgERY6&?T^Ww+~)FHa=W>i0GMw^S$V%$AM0~e3m(qziPT#=D4A0kP>EmOhl-K1Y zG~2UI+NvlZ#6@aGDW3*32d$3?eA|T!z>?sHU zQ6T(Jb=JJ*j|xxHaHZQLJENXwiEg!tX0GV z(k^gUW?K9{PhFr;Pinh(^Mrd^vmgE10DQR|yc6dm&&MkmxP__3+Q47nSbSuWYRjPasNdPI*LYk!0m2D9|sx2H>yWBX>L-<)m4d zbp)YjieCrVEFI7pW~`%ES29Kd^!@A3mO3!h8WjB0>MNrd!JFKWT!xjmn(({Y%PMM! z&5M#U!RbV#6^2Y!FQt%opGvh?j&q*s(pOR%Am`APLfni_qQ*diyIN_=* zC_>R3d@f`V6r4493MR_@nu(hbfBU&)uwF$1TQp+O(vDp|R>)u~K4a+r0UAN&z98I& z;s~?mA+UuOx+w&+Ky>mTEH`heAf$$19oOP{Vht+~lbogHqOA1Qb9qDDP$V#wfqKy|>X)?6YH^Ea=BJGV0r^~E zEdlGWtsDJP`G(_I8w$bvn2$EB^UG(CV+c@?;W!jM-J-tqHD#&Wm!_SATj}7fAEW#4 zd6agpUq@TJ+o{XnOzoZ~8M?*xmaaCsdFvLs@9szG&}|>5n|D7*x9xdYUVr-*4}JXh zAbsq%07aJbEzJsP^Q7f9gPm=3+btiHVN>6>m9z>&FcYMm+aIN^Tkfa9f%|EF?<4Yh zW59Z9pqxUc6nGam4)~>lrAgF#D6o_zD&A+5AL>5dA*Bp61Mea%V(<>d;y&88?Jnx; z-9|m#-Q;(>DIh{T;-HD~6pf7}X?`w436W(Si-xn}S#P5KH-D6N?)->sr_iBNVXe{> zc<4i~h*2nojO#jHGY3{N48t(1!Q^~-i-&5MnB7Q;BwYK{pYwH7YUGc7V7XEsrA9Fq zM-S**^<^>KMhgv6Or5!WK#Vgg>syo`Pi83+Yog0z#fur&V=P)bxjd*@++bsmpYAwN z+AY%B#=L9~-`Y%ry@8eWW3aft#iXVx|G-u2#O*F8TMrIwhf}Vv(4|?gFgOf|m((sKxK5`|m8Y z#I={g+C^Jid*6;G>IizJ>qo3jySSu}=fv-NTE&1HP8pL!lenN^MM1Xtvh>)4Ip2UQ z;IuUeBYr~^1HOk4*@vLs%)`}_YTb>Tn5>}sEEOuE)Yt?bq+chm}zY` zqnlYBFxv(SKRh3}Nh?&yz>1_C5VS%d8w$Ck@YV<>0OJ_e`B3XulmeD-5cqB$49Kv4 zonH!p0p5+CE|0WA**M^%K@p7B2huH+?gB}HykS4mMu1>np^hPcg==;|SgnE)C~{yq z0i_b^HGV4)2g;zg+aoP9j21Dn&iCisMKP6u=LTiUpeXn4n*!2xAOh+N6kIqC>z2Xw zIVDTsF|{87N-`Wnz_w9|;1Q4X@BEEE`pALm+#B`u?xmmm{5HCISCHD8oYWG^uUlrQ zG#`JkI)Ou|X$yVnv%5tc>ty)E1Nre-DP-h(TPDC759Qb1>XFwK9>bb9P`cv%G9D`o z>pI=^$wNW3;ghfA=@(7k>V?>1TfW*XWMjH`A>fT{5(<(Z%0`zB@&|RrKH zOX_76!!XSC%i0i3S5G6Y@){L)I$eJ3P%V`zHA-Tr8kub4z84ui&y|*Uaox@Tok&`b zQPzq=Mw_6Dykw<&vU?A=$s^Y{+Wi>8#KYV6HBoB-&pIpn@UTQ*IW_gS9*2zh*T^RvzLd`XQh%^ibS+AG}aBfZKs=BTaDj<@+quc^6&lTn?lsp>LssK zZY#?yeHpGM&GQJ18WcD z4f%pEUaZFe%K|7EX66!dVRJjc0tG&k;j&0s-P9NJ`l2afw2ufBNs}`P%k)u(XpGH( zaK5X*aGlqIUWd`TI}4 zH9=SB<)&u6V|Z^XqKV4+l=%mt96p7W}f3_LF`YSKgb+ z(tP@~+*WJG96$e{RBp_Uog^peV}>dc2&YCVnx2qCbgUTzYn}_kw@_G=M=CO0MU>(S z{i4b6NpiT8bZ}3bTr=k6`MacbQ+Pr2Lz7ycuZS`U;&40}rn&SPIqvz?eIn0G-O{xh zp25uM$)ZVWl@!d?sVg)*d$mq$#^e|hV`%{4;hpa&x!F&lkdFevMkw8K<@NHL3v}ZA62+35OYU{OC{O*MqN?Jp>>{~l%w%rOn1KOn zx3kD!@tQI9AuiX9>5<#UHDjz8nf<=LRbLh-HyhTB=`XQnjDwQt1)6BcnlVkZXjn65 z$BxaSZfbcl>t06U!!#E*t{GFGK4^Guz2%xQX8D*Gd8pr-F}Vch$9L&l+L|$&H*0Ig zXcT8;YT+gEO(^w!&A+BTrDX>_C5r^@<)g$|`XMN`A=?DqO-}l`&#CgVmqMjPV=0=O zi%~q56d^(BbV|w#0|7U+wuQ*&_mIz5kI50{`5zvQ)BpVQVTxu`)Z68z!GRDxaqlL& z`=LM6&!`WsuYBbzzou{BFwBfTMaNEGrf?)9{bnvsh3Oyt9pejDf(k!S6SGb_ec4Oz zUkZp$rjKTqJrs_)MG$}E;&0qT3t=}+FSuxGE-Pm#_{Db^9U1%J-2C&+uI}yh&sg0e4*x9L3_+c}AX~c!O&)+%L)x+laT;=ZyCY3cX|!@u-TeRc>k7 z&;b`#xehVbn1IW)pvXJwgtnl&Q-%(4f9twMJ`0Wod@kv(s;5(1SHuYFZM(Q1ls)RM z@qSRxd&M<~Dz@zJff-b(8SHqiDR+H=793$qs~K$?IFYe$K(vIJH-h3{@f)S+&{ z>Z2*}fc}dy0~SLFtFfT}efR#H_(oJcbB19U#*}&qm|uDA>$JGExUxQIljw`yy0?`s zkMz@tBj2Uy@)Rx3jTePYn|FwB<3{S}=%f>GKWjK9`YHOh*S$y)(p)6I z+(MK|(z#P_=FTyMWOkWczO3l?Iq9a&O%zLnXnL-bUU}w!Q#vtceoZ_q%Hty<&t0NC zPV42Nj_dgr`EZ7kkgExKcF?X(TAt^Z*3mn!f0yQ_E>bK!W4JDNeJT;Afeo9ev$IRY{i=*> zB`j!v=a=UwA$qh}KeS%&3WSFki-V4kj~=?Kg*=|>6^d4jjV;srr>E%X(NP*1o};Gw7xi~ON>d*4aF#uNQ?eEkxPtkF($R7 zOi_o!qWr`;u9afbE|{Fc`nOr~h@rGvn>i0LmWYQn#fQ)5m1C1qgyTbE>{FXu!i;n> zK&iMkn>`c?%20}>=vjTMn7Mh#ILr&I)G+|1P&TU-Vry%2Nz3VUCN9e3vi_@nWHVmT z9_F4yM@PGOcGm9$ltQtjHkl8|x*#xp-geOC9m!}5WzxC(hmx!q{bT|1kSwVLDMv0Y zBeCV2$0WDgP3`UGidrS7iHK*C$(k*bkc;0urADErW|649yp%Z0a0v3g8Mr+^yEB6!ZA^= zvlI+fJ89JV{xM1a=(|gzO-RXQ3tC&ev~yD{4Q~02enx$$_g7%ekq*b{i$8%`!e}^b zHXb%k9iPt9vu_f;eab;ovl+^yQj``UnZ)e=vCPZ_QCOUn^ zOXsda<7e+R$&sJ2!fZB+4%hx|xyDWU^{a+5_g)PUu*2tGDd4sS0%|DG8m)+7>I0NS zRxZmr+s$2;K?wtQQ4nG)ltl^@Im&Gmw#$J!0;?Y=byQH-!%C;{*rp8u8PLG4yg-Kf zj{AU;roYFx64W{{g~wpQRBBc|>T+kBM=BV%ZwjsiT&v>RIv6NAR+*xfDakb~N+>^| z5P@ZivWii^p(JSpNb|(8msirm--X$Un$yJli3Ry#J+qqO{G}KTj~82*O-xKkMa%;a zJRp@Vv$L~w>eMN@uee6V-wlnX&qHmcK z2sY6R&-|tAhrnvqF0tq`UAd@DW-w##EqBX!5pF)9O`2Gt%q_qB=93f&TMO9^-Tl}~ z+}O4Y+RC?I`L_N`qcAH2gWF}iZ@l~i+P2I7+BFlyXK8ZmqW;T(p1^hy*O6C#DC4$Q z&f-GxzeD_YrTmI0wyNY^t~q&bmXm^k|dGL&^P}&M$f&NSP4o< ze?5S*DBTpBAAIUZaeD3r^Yx0~dp{|UVNv_K(6HjHE#mL}Fh=jZTcKhG4ePQc|KffAocx8+$lc7&MWE9R6NMB1~aq8>u#OU?oak)5rDwUwL2hLqV<9>_;-lfoY92v;ri|IVb#F5TMTG^h@WA>iRbg@O z)q*l81uO!T5PB($1=v{;bG=YbA!A&S9&30gB@AXO;kt7}QMxiBIx%B$QD3!=jI>@c zTxSK=T7l97iW?P-Gk^+@St>eIeXnDkXRaZu@GQ|mTaIL97@5%OZ8i(bxR@5=2{CAa zQrQUqbHttg5G}n zZK;GAA0Mat@4uf895^7|n6 zC5#@Rh!H2q;Bkw;B8Yu(`G;}vjOgbsF4i^F0u+lLpon?? zr4)I@Q2fwAEiQO-_}&i_loZ|aTlc%@(Cu!TpU=|EuiH_`sK_l)hs&H+FO0%=6>{K5 zEvhnPw-WVJ$W)9mUshois4B^N<*iJ@We$Vlx==`d z1o^)jjh>oCq87UgD07y{VJNl{02JGI-d4D1e{D=oMd|q$uhP`S9C@8_@;H;^cBVwT zsw-ij-1a!70tPN0p@i{xJ<`RV$Lp2bF43+o%tvWza*5LE(v$z~l#)c8wsUKUHuMEV zei|oKx}lXZLGkT4d|RvjtB?w$b^2*=dG!6~7NpP^N|&_w8l{tol>qlM+F$+HinRfLSt7 z`DI1S^+hR#j9f&0y=IxB6f9Uj=+f1gRGg><(xIfmS}V8?;FwXdVn$S-^;B0>ov%Z^ zXRZOO^xQBg8Jmd7@amBnxzCk4Mk7N{(edNQ$r;>4bIT5znu`~Oa~Fo_d*A+3dgq;Y z=)#2yVh~fwY>s?f*>RcX(W6IcA?l~4c#tM$qAOwC5dP|G|4p9v!3Q5mH)VE!LbDN} z8t{!>T9~G{-g=Av;1B*l-ovqD$D~5$Pyh5!>4g_wpznV7yEHU(ftD9%^{dtcAvei+XI?8uudd#{!Y+`m_C<7=o5I3x2s==zf zj=b_DojCfERLGbsr;Jxx#Udy;q}8`23NJ63D0vzOlrbtRJ2nQ$A1Iv3UE&_f@Z1ZR z>B^M_a%44Op;W|3YZ%Pj)|4=sH4G-2YJZgiMhj5Nh`%n)QYM~+1xx*e_&r@7>g)89 z$EA&-t8tlr_MDcV#~+0&ZmrKgGLn&sn7i-v(9Z2{+Pujnx1o@koWl7i({kmi&M9-A z@w76h+NUtm{D{q(XSid-{T({!p`PwSnS>SxJdQp5kXFCWp2Gw(WBe*qidh_`!ZqZY zW}{5vWezLKD`9|kf{L!}>2*U-%_32Y-6oVct3)LEify7To9m~HIeTt~-a9!;9;t*$ zh@dQCw29eJY%5C`sfdvZ7+n$L(-bjK$hgH{xA>dRIB0e*F4`$8`Jla$GM;wumKJLD zm!BYBEjP3>X0XRc_upBr!q^iEL7DKqAJ5S8a+0uskW{p!p>R<_vx?FF=0Zvx7hf+} z%D^;LDrQ7molLnXnfB1ka)8c{miA$34f3D62W;&a^oh!>)uM71DYmg!OqM_qWd&X~ z2=T$PT+>9W@KZCQ3|SF#-B75I!E=RTB^t{}r3x%l0F;?ivq`C(!TL37CJ~OqwHUPT zct=1v>lk%j!%(kRjrE^dC9dIf8oCmvt0T+g&%Qx^Izl~d=jq_VcG|r&OU_W7vcX&k zbfoC!?PqDvhF59d=9A=1yu7k_KfufrWkGi81HTOMMDfjC6lq=_UZRlmWeU08rrUO% zqfdXLnLhVKfVS@z@6#3sHTR^+(Uc%Z2)?UNlRNo51)Xn^C;ghp@3f2qVPvd$W*%Je zZ54yqMg+uN2}$t{4KL3V#isQ=){I>~M~>v8yar({;`iR7Z!whscV*{?+Vo!x!!Xwu zwJT(*yZ+GKk4gmuEGvrLXBpzGFnTBl00ix@fH0-XTZUUM#EXFZ*8`OmD5l`n6{vft zj{KYJ=$5G%XD5Z50p){m^}_WJLFlG^{JmM{j_IU;CE7+AwVA)~Be@K?8p zF(_fQfVD`q^++LS!Z^BK?A;k8zrH3S*0Y7>ex>&cq#~xEnA%%&km=8`*(Ae;dw1n}v(xPpIQd^Ak z43;n+sepmySuV`yMB6!K^a#J`ez5#j7sr}L_Jngo9Ez}%noPgZa|R>{y+kfJ+zh3$M*dw<(zMk5&PlY583fzvZ_4t&Zs*J$*k;)c)c({$vRj zR32}LcI>=|cHQ(4-E{NksdxQdG&la7Os{fs_ke|#-#Z(nXi_FA7am8Yu9@=1WJx%p zSq7N_K|R*+KwcrtSBolR&6{);i|N~CZ7<;OTJsC|o1v6{c%IEoF1a8-p5xSPO5P8) zv5pFqF6g+TtS=91${E}rp1ohx*QuGLj05MO?pP`1@ciWZFROv7|5d&NOar+F&jkx( zF6fqg$*hA;U5d-_!Q}{D8K0D4bb6L%!lG`AK^wWW5D*>ufdMaNoLQQfU!)@^#^~IY zF*-kzq{+n$T^LQukaalewKqMY{yRlm;-KYa7qzsA&WgTFkugmKq&G1;Ly2sd7DO8q z7w?wWF9r}zu*S?#G9$i2BK^_ndAd3=B?Iz$>QYRGOA|?PPOcE4ENSGsh4xl^zpV$K zVq8nxMOn3m=IQv!DSH3iGc-IrN*_6Npk!!oZ>96+&(oRrkJ0dzOJWd}r6%`#GS0QI zfIrqg@q2gcznDsJyIi8L&`gsvmqq>5ch(VJz@K55MpMiBPp`c87kLZ#r^L5@QGD~q zuEfbB+DEU)d@V!eI_tJW57DtBKbG5tWX0z&x5Qpq%&sE0#+a-q(-hgLu&g0gI6oT^Nqii0FG@xEumDh%*)0BASqnKuA4M(Tza;u97ltD; z&lyofexFBtk5vC5S1wRK?A~`+^xG0r!EyTJ5&cL$PAuLpJ~fzpb9Ew0Lsud+H>ph? zX$s}OL4_p_MViN>9iKES4*?e0#{&KlQ7ff-Rnp?WX_#h(2w^4ELx&lTjWMC1a2l1XdWzdu{u#Qpp4Ed05{000M#klOsaGEx6a+g)eoIR(>ZE$WO#s&OQ z7CxV~<|fn71^jbvoI5+)Mg24XUH~kbFBkCFMKJH3(w+|#PvsER+q4`&GG@JiKk8~B z$U`cL|eAqCE85!9I^>Y#AakWsVT7`14P>?{>pX~iWdCVT#~83F8!|) z+xV-ut!PtWB_l2oZH&FrvMLWK+ZPw(x{RmLnXj?&f*LD5;#ciIAt zOK}79);kL{J)0!-LGjU$XW$>vVkkw7)_Q14ms}8E)V#kqFGD+a+)1DM^#4l_KKS#r zZQEhdk=-d8=3erLHc}!wPSK_FNTEtZ_eSImFV4selt-e`6CJR+3e^y)ECl;3mr%w) z2#@?_#D^OT_d`Giv$WZTB#NzJtZikC^SV^V0JxWfLPeSuiUth%hf>Bb?g>g5+?!%V zbmEl)2Y*p+c+Vzh#4{1spj*izv(p2^HG}OMR`O}6e?oS{^0$rS5WQ;%PC|;6GE*)hsbw^GKnh` z@SK++=(|8o-cxks*c|h3zacI#SLp7(aG-#JX^!&nrN z-?}|S8`f7co7+6?6z!#ted4$2!H54(+Og{{>g(S{ZSCu+skw_nOLnAX;2SteGbvvDc-uQz7O7}UpnwDun)QwyTa zo6vu0%9xECTy)<(KH9d$T{2iHVnCrXrmL&8vQ$&Xn7G!?Wwk2So-#(ip%V9H@0QD) zWxL#9t(TG>Za{~4bv|;taUJ&R@cFxG&uzaU+Rbj+Zf@LqH|;&}dAj-bFNycUPqFBP zsH;)=Oq2pf+lE3$+t%7tkEp*n1&n58sQ#iMa!T0-EEvmD=9H!YJh2HtPa;%SsN8G zV00o$;Yj|#14;?CX41}W;(K6NQlz;lP5tY%*(r|nI!Z=G=QY(Qw~Zkd?xpFeuDmce z(?!{&c5WuIjv@=z9p6Gl%$1QCO-#i_N4P@$d}`|5D4WWafg%N}_R{^GX^h*N>I ztX!7G(++y$gE)QT`FZ;GixVs1ThC9(eKXPGN&xGgV;2+RyvddD!#9@c`>%)TTQ4rq z`0}-_IB>JYi}u&f%{SddM~>dGU08-;ZgAuTy&Ax5%}RjP!?s+8Rj4&VFF=#!uOs@#@J7`Ibe!zd+;Q)*$1!x@pbXcwYUxWdnkkE>;% z&nsuMgK)tbtGG)Qj9ZGG+cnMUQ_sewYpRo{l63Y$TCSU-EJU#X&7)Z4KTGTT_5N6K zRM!?mUgVr;J=mqE$0hIi*ztr^M&X{#0^D`MEArkwrQNINKqgcuq=F3AgfR~)tYNNE zR#)nc{=5F@H>CeDqr@QtWzMn}iH>$+&P5r~=JnPJ#7fw?|5wGoxmHi%^EcD2hkt<{ z|H4=4;649Dt_cIBCESo&};M5;KgJZzLn zb4!4F+Us-wh1{?s+4d&!K+2STc^q_ZC?*~@%%u>tMcL3?mRsMup5hhcVksQ_39JpMQR?!%;bzwE1AcOc4{JB<<+R(%=8PzeWH0Uww=I z%|HJW+SY$RojRT@8NTul|1ILf-^1?7>Op^Rmv{$S>DUQwXc>n2a1jc+XyZVD zT3b9)NHjfDx<8@>;K5L{R1iQYUN2xx0UBJuROFoK;bof+MNKUOL(C$$IVtk&ttLq9=uJM-f0wwOp$$j!IjBkRZZT?b6^ttn*C4;)DEKPxFRgntYLJE82vn14&r5o zHx*3ojl$P_jr54;it z^T{$Q4kGDkhB@P*|aaQ?Abn@dedga+9 z`W&^=)psBH{Jr`wbG*K0+PU}h^sy)YkUDyH5tJ`dAp->rtYLJ^80G5Gp)0uaWg^;r zpgoP1GG?+_F0f{V$Dg3z+TyEP?6eryCG`-}qH{ODh{c59ug;|h?O|w&8TjASlrqX< z#^uV2k8DPKT+>o1lS!xO=l|aSqyq;Z*JCYD&){eEt?Gd(YP0C9D^#Z!rP7dQv|$ln zAE1K@yrMp6rg1P~zcC8Lj)h7o&@mpHNJzzunGyyJuJ_4z7UyDynC41NQ_Pg2(wTv) zj(RUtV5(;gl_A{gMG9t_Sy721MqyOQJpPb_zW7NO9o!S7?Hjz*->J3hFw?CCzxY-e z!_C_RbkpYCpcTpzC{V$p4|K`3oeKQdpA8}B^UwUH zj2qAL1+i^~F^0jAufR>hcRBC4L7f-YbcZ9%jf6~QRe38 z`N_)`eiY}k97f?`b08yK_*I9NzRMk?_O654t{T{|=|Q^fBfqRGVKhaIhDb+F?3hj=yfPV-29rW;nUa5dl!N?;I`ROxH_=^=Wb-|b$El1Y` zku>fP3YiD)^;w3;AM;aBmniE-X4P06m4rI+@IyX2u)nm@*qll;Rq6TVD2~T0##L3o zAe2a=#32JV&axMg!2CqjuRuG}*Fowt&!zVn$R36^zz0 zIZGLYEdAYo_{X$$du1PSSjV*W+@t@h4k!mYTXM>noQbkVBR-pwhDE%#Q3?x`b6bnn z@hk59UOzxF0>S9^%>k(>*}Boca$ofZ@uU34CX>>N#%L8YFj9eEy+U`dd$E%8Xj@`$F`|NB;&rdZ|-Mcj_kHd!#(`P^XS^4{Ce&%Q7F`QS9YpsyMw|h15 zdvDRVn0nCP*G-{db6M+{GZ!56@*DOV5v%167=~dQK`jDTjP?3@d{QA(4&_b^)(_Th z%1kJeJ!K7pxGi0Y8Gzq)F^nd^jYWVz@#(*<3GziK6}McY5|LH_Tyd%LsE?a6jgGE9 zDNIM)D04}jgg$UhhImmXuwbc;{7j(?-g^BhdhhrvxqMd$Vl2E>lrI!WP<{miP36m? z=y|3nzp#=)P*yTpfDl_*%lypG|2}Qqen^k4GCKPo(YLCnOP|RM zjB9f!3afG5XjsJc1Z0&!S>KnVk(yQ$@a00L78V2q*M2l4d@QPqMc~UZGc_jHi_z8_vF;0H$w`rDS_aI3Eu4U823(Utae@#j z;ifE+NavM@9R@e;SSjlj>hNuW5(aMD5ciD5GpvmKOhMsw$K8)f6_x$8idWbI&7@%*uUp^X1~ky^4SJPz3fFLs<$h zuys+z;9l+BAJIGSCh3?6*9*qyVHFBNIiNhg_rn-H_af>7$|Wneu@A?vhK?mBaTZdP z2OHODsFQOS6z^GW^wdja#A3GzHqNvknV|HEaP6(mX!fV%x>vQ()_I4%RT&;ni1y$9 zOB4+Cnv8#pZKy#3qg%wN5RD|nF>yDx%VzbsjwP9mCqtU@CC@rWDq^6R(Udb-JjhHj zvv>bPw0qw}dQ6qm)L#1xTBHA2bb_sD*svZEuVI;ivRuJmW!X}0&;jAUW-$_^fpvcA z-xdKZE{T_23@((SVsW`L!K=dQ(ym8)qug*+q9m$?4pC=R{;|#rX69eG9Fu<`G{rF} zOS%l!E7fAAh=COWI(An^<7KU48fB?-%|Njih7S|h;eErs*X=uf^!Pn3Md3@IXs0`N z`K4t`HHsL;mEjo8&egwjpG*|LUvC^;D65D8ON)zi@ZdojA0MaD(NS6yzxVCiCzUW? z{_>Z_fUmOId>;mdjMr1YnYT=i-tJCnZ4S}Uyj*hO`G(s`q9&O2X*%zG*!ZAK@%p%qqSMafKb3iZl#P#*egTD^DiYu-zrTW zQH(0gFJ$GS{t&`rybc8o_Sth)hV-?NCu}z(cd8a_QFxKrg?7%#F}IMB>%m~{oN^40 zq~*EgFy6aWSX&@NS*eJ5`p4S(IH(Iyy1e{)VnqRieNbM#{8~a&$Y_`42NP<$cU+)? zM)96&fu4gB87Xn702^o8k4#|iWaH$6R(+y*Ewt63*oH#prhWgX{!8Q?3Ye^DEA_Th zTdUoufXS`fp3?s&6V=IK8VxIBEQrLRRKcSCn!-g>y5y8FDrkxtu}>b?6*Jka*&s!^4#MmyqoM-}2s7Z9St($Yx7OqV;w`z9S-TD3YL*0rsDOHL7fp zXH%t@p2*A`Cc8yff?6lA6ete`%EKzZS4CgyqKH$4qDeMI7iL$=7v&8L8MC-y)pYSn zF5cm>T%RpR?n-Q-P8gLtd1YcqWN|4ezgSl`C$scoDHw>pht&#nI;CrmU1 zDO5~pf0M~1rINJ?5ZlFj=fdnxQFN7b$FNvE1nPI(?xu$y@~(utKjP6B^-oGg47RbZ zOh_(=X#e?W=W4-L)0aCv7i^J#qIp^sNBSWmS0+zB9hQGl4<7lLkM6$HL-X@l86LP- z?0d*3*A;?d4hosZQT)7$_go7MxhRpD5{C+~ai;yq1Qnf}*Iu+X<>Z^yQfqtK-npB) zdT!Gd*t#pS73DSDkr@;)qG3wQ_A?jau}0R(>iG~zGpi$=hPyH4eoRx!tSDThA_fW= zT{*L|Pdk3g!B10L`+7a5>hT7wJGFLb3REuP#1)lawf2w}94&5XwX%7GU(T{dfWUw2 z#sDe*%3~98YHQUR7${Yw30nb(%V=c;g$+8O=sZJsI5U?N0|AoC8l^meBBL6RKct7e zKv{upP_31X8MsHRXQV7kkPh6B;V%XQbMr~LFeCB;D;Naae}Au6JH9C_WvBR?pt47QW5_cLn$BtN8h@XvZPudyx+6$cKw$%5RO9`)7$N%b-lj4$!k`?q5{f|a#kQv z!WjE0c0j)2@~hsUtl_#%Lp~{Ovw&>2@=maF+g1)+GIx_~p*#>S51p02i%+qe=iHT0 zctP<67iC!ICK@UD=<26hmIsdKWu$0_DVT@p6@A!R@K(6KK_y_O_u%HoR|JYVC5&Mk zGrVi;L**-^%9ooWp$}a)Z_IzM*7rMQ2uHFjikP-GhvBK%dp`M8dcKZI${1`=*mff1 zzz<_E2Z}1lEv^sB-;W)za60Nkd#k8ZBC3IPE^2FmD?A7FbZPYr>&l>hpl;Nc{ChC| z()Kh4^Ey(9o(uhtRfb9&D!|5>_9GKibaFA`QkScS>vbw!FUE`wn;s+08m7P%Su!OR z*Gds%3`!{zkFzr7`a*ofVdCm?Imx9IGBPMDnVj-Pvyg#OMg;Nq&inqZ9?7)@`K^}9 zyNK3^{)FgE)cz9N0iF9z8v-(59Tx}_rQ)F3Ed!J=_zi^wgnsy|6drRH3Y0d3nKKkH za2eDh1{6?Em|4p}K`>>*MBa!}ejtAfiz&H~J!Z22SnrfG<+p<}A%+qoEuzC3FlvE* zlmQeiu;zhs1jn><6EZKjC(T8hhi2xqa>AN2C||p%^=Rs$hyi$ZV-pFP#}7Stv{vC- zv6k}EATD2gmzL%x^j|rq$1YK9ae`uEuu=_pN1!}j*W;y!4hHFOJk*jGY6T1U-*fw2 zba1ODFWfEy+9CwBaZqM&=-1pZo_ps%(RaV`HG2E4Bh=T|MPK@B^;xGLAyf7Weo1iWD+Mvp5;11i@f{wr%XEk+B=Fkzp9-Lqj$0%7UW5(BdmS z-h<-djGGoVEvLOzw<}Z&6O2i-32oUc|{)s zkPp53BM%6k=n+bk6);#XKb0WHsNDz|1A$`-D~5I@|CnNpC5 zmgn+gcDQXr+=y4@-73G>@AqhVh9b-q!^JN=^L6@wfOr)GUHE+Lfq# z&x^cbjh^5At^a#ve;)d-lGVTHSgDiigWDYx|CXtwHLz*>Ppl|oGAUiaD3vf;NJ(L1 z?Gsv7o`0Q-OetcFAPFrr{`r`a%YYVaVl8l2J5_{Qz#1vhFm)`&5Jw6JE({9@%VIs}rKAr9aMY<@AR zD=D;ekZv{c8qvzeDf5psPzJr-o)tyZayU)1^C`JFKP+LO92p&tuPlP8<8b*IqxZ@5=84{pSDZ)we1Kv+SI1H~qa| zxSQHC-_-YN;QjvgEBUh)jp<*RXjyR~=yJxz;5te_ert(h>HNyk>dnwS2U^G*XqCSm z4kraXIrnPE&c$hZNwmWTSA(My@fFvOXk$?hX#e51qE?{TLVJ&Ac6m5wd869)nh{a7 zhCZwRV2r@c1}3UB67;>s#>eUV&mEz|w`FPbV15Jk@*57hfd6McnN#w?GUnI`2R;7r z3^nOSOK@}cJHPP)wYJu-@LUaQ`DQWKazs- z!#6ckTeFXzerl4s`!>_VpZubJRwX#(I2U~L>Hkhk%X8Er@{DqR>IV}vKbNFK_kNmo z?%JcBQ~_GF;$N4W{`l+vO6K{{u4d7<^3!*}GbVO>=#iiJGIe#8p7~s&TGRO}r|6|4 ze=YiDKJgq&C;*G%$ln1s+mOrn+)nzbM|-HJTN`^;0~YV!w&$PfzZ%2yKlpi?n>nK^ zWiqmljy_EqawW07b>~L%2db0bfT1ffdh(TNiX_tH6|e95etYEsH&dfyS^C0fa^n%j zE3YS|WynuHQG861%{XasYNy<85}mB|>q}eZO)ox2X&YAel@gD%Q*=oiGj(-!$WV&$ z`S0sn8pES$dgZmGbi>utt<_7&Exz^FaoVxnMF;lh+QjeuFixS6L!Mj6;?!30JhgKN z2G&t?v$eH+GQB9u<0bu9{m7)6XmNT#|3$QI+a@`w+=@tim=?mv^?Q2L*z0v3^*|APwcNtXhRhr@>U;sE85mM%4TR zQVD|K5p@~L5-4H-1fxn31JIx;u#NWssK4cal1G92QIR?R)NJ?h-Q$ zbM2|5PwWyynZfk|>RrE``UiJWTj#m}2SND0s)JvjK%qe29c#Pn+;@-Z`IQ8(H>bFO ztK-Fo3UdL>o-zQ=_%N6HdL2HhG40c-R)ojF-WHDD4_K8?Mf>mC$OVJO6G-&&$D|Hfbd zpP5p@4mi!`sTEU6K2`^0Nc&?&nZpIxIJ=?~UGTAWcEYdM!A9-Gv+YNJ!MnT1v_ zxuCf#(}MALx+afNjf6*@7P#RXFPjn}EtN8kER-@3LW>Wh7{jAe2BnPK=*Gi+Xn2ucfBw(tN3Sdvh0)2xO1L@}rw@jr z6cz7kBI7U(W-VvZW z{saB^2EigW7x25Mt9T#7FwFJHw%v#It@;81Kdd!s#$*t=bN?gyR*e+I?GLul#%;Ig zzpBG(Y;yC#M=21hzxAX)&`h`A{b~JIec5~a!_?WGn-O0Prsd%X(jE7HPELrhi(N%y z$+K{<=!E*tfM0-ycK=7!dMn&!Swn{ zLIZ)N(09fCt1!Q)DLsw*hKjsFl+R#sIp92FxK5W!0u$Z_y8mAGFFD#4?Wdp2PU_E2k>I4dxwBDPkM}wrm zx(o_*n3QX>;qjR0m{pbz?z@x%11`#-+!-E=tte%D1|P*Jmvci=>8{KOT>LJ40eH5l*dy zm}oC=WTLT@?Eu%LilXDu+7)C>Z9o~*)!s_2%^@*Z%E zp|!%{w03(_3qF6RzEyv`{?aakswLP|n=2B9*&_%v=Ud{`i+YuXS-q)S+yw$Z#9M9+ z9W&~pkO4&}WXbE*@`EI5o$!-Rh3ht(+ltnX?FH5_2pJi?zS=t^;Yemhe&NPM%Dghe zkD@}946Juaw_I?$RT!`z3$+{fRpP-A&qf7>%83fad$hf)4Hl~}EC<}XSs7s8-ka>p zEUq^;4LYgKV5eenV)(^->RNPgJn#mRtBX&*_xFvCZLRrn!Ecd2P`e1&;o&g zOOz{IYT3)PvWfu^_QMheKGGI*|7lZIhdli}fEsf5|KZ5v&@ zm|LtqnRU=o%Djz8iT51VVW{I~iWs;o1U;cF4Yp+RLapE}+_A2|C|+52nEkqTCO?V{2$ zhH~J(9{8x&c7Sr?M&=)ehQBY5lUId`VFf?WVGbfdWQXY9m1M;q$M}wWS^61K9Ydxyqb7`j2VZ zuz-KHHwY_=(J|5Sa5zN=Ml`NsuWGXe!bB$|=RiAt?9lv}dtxfIRKC!|s(63fuY zSb3!ulrT`hAa4rfMXlq4ZR7_EsA@1OVh{)7-Mqmk|H3N9t_w8?n$ZD-l@eTu;kSxY z0VRwAWgHHt#j{LFh{ z|2{1)F4Aqc?xi~pZK2oS$zMArmCn-iOj26D!GiDhTk;26N)e;1WmbCu|37_tk;e3e zfkB5iO<(#{4{f>q_sA36Oo>>S{>$(EF8$SCenUUQoR?mCiCk{K_(Zzs+_`h)Uj9S! z(Fd}f{G-2~U0L)WZ63gYQLQ1fS_}9?|G%}1XrsOsSShw`39hW~_4d1qd6tXwsgF_C z(XRhujI722{s8IB%*@bII7-jGew-e8AVcl?@&|7mbFAk9r67J`p}@Cf1;nFc^ug8FvuWbZwniE6RSw#R&_GDe36}>>LQvPkg*K zE2-wT-L&)OU((SGzT@fQ=e4&J$&{51*?zwv`98k&m8vg_?~ zQ7~xHA2Tgn$BO&0wzk{};c!;8L7Kb+mLtYvioyl_`}@l*;J@^&})q#z&}5>iTV5m{1uoyr`)qCdb%`=5C!sy^I$Pk$l`Qv0sr;uOE2J` zDzSinu?w(#G>a5-^h8t{0kdCKL1VgNvxrv!#j)T#VI z=nq8~1c+NVYE~(Bsn(q>+?zouq!cmecw+6FA<<~UA_z(tQ@&`iy0 z9bG%j%xU!k@uAF+H(3XC_h-s&8GuVUH2gRZiWofGp{sFe?Sg$6kSe!lR^S>aix_6L zfMv|{&p%J6PMs<_h{pRqDeCyT9xvT@XIoiC%(Vb**}5L}NkqyLW3H zS^WLt7r!X~e(6hJl7HRakW|E6YoPp6ZFN?ZKiUTDQ=q**bfC3tP>L9E`~H@^V_4vr zxwg2linSo13oeeG$n^&f+^nq+1NQF9N=1!T@T|>=Qw+l}E1>U>egZ;Ei`HmC=}?Q} zp{;p=T0(Gxn)^OVM8A7(t~U3m13jnpt$ZLjsYMav_r}TVI;sE4XMTRZrt%o*xj^aE zto|zp#vzlF)w{03J$vX4{Z~H7Z!LT~IFe8FuMBTn!dlsVHjJvfwNY5r7Q-Rqd4W^c=o%n;V#aJfA- zD`Ju&uH~pU9!A-@Jx=Q~!~qp_Ca2Q$^s@;%dp;-MfpX^iPbKKhw^K4a_fkR%#!F)o zxlIbwLpV|pkcSD8hg=Gkq-Q+W{Cp@_uuja8x089{<<}EZ0RvD5-+L-f@0_qF3#*2w zejF>xgITB>1;v4%&%TtD;SEvlDm*L7e^^&kK@s!aAI8NqsbfA0ICBoq9QRsK7v9o? z*nau-7k-~a)L(3 zmPF@ES;9Ef%iw3S(#h79921X{*^uNA8wQ@QXAB_aU^7(~i z$?QSs4l9^KAUwx9GZ6f%e8LI^mK1hS)+LDN@<>c>W1s@Tem#5~s`vrYFj~Q&p+e^o zN+h*T4S;gQjvFsc=vtX&jJgKk{&1gA&Oq6b)^!k=*$(qUSP6kEqFn4+?WkGgnj$79 z?@=jYuy8fpy;TCP8(8O+`Bv63>w5DodNd0jZO~L`)q;HB9@8TGDxT2^(E%#q3m8^I z{UQy9X#|CqF^3Q57S6>$8cG>6%NW%E<|Y^I+7_g_#VmO}E(!&-_Y!UZv5r!Yc>j!w zm_}H}h@l@na-V|&uKe#zf3KT<^p4i{K;ayZXKB}Z7k%{hX6m`=KS|3N@QuIxI{o2) z|8I2r?YGm;ojd8mg$s1@Ye ze>fx8{{wJU_VODJ@eVrZ&}~`qEivz{{OYf~KtVrS#xM-CwoukFu#B0TA0teH10TJ$ zoi_COX>zt*&Hyc@U?6NkN6R8T^THUNxP(cCjup!o%xGVZR6pS$=!g5NdHUwlFMW@=Oy_YYqELZ51B4n^p-x5nw%xy3xom@S(JX<^CUvoZtU0-tA={_4pInhk5?DQOw= z#SNmr*(}CcmByVrzqKh!uZldsb8cZJ&#;WywPPL4%-8UJ7jgAr;|X7uV?^w(egS=rykI}NLtq)w`Il1E*6N^#AJU#NgxlYLN_!vfI_#Eh z(kri{k4Mr)m(e;R-!dj>VHuM<-^?;bOHZrINYBjDL3A;tf(8ncyFcP7vc`xAx?j7Z`cei_`93FqvC;FYm`K;A428tM1o7}qJ zEiH1)c<*#dTJOL*=FsiN_fq>VXqGV>ak+m@d%6S|bqZVU{-( z3{VEaas_{l3+IV5=1PIouCJ3)4TgSF5k^JK)zO&D7lewi zE`k*d@}}~KPMuP~*tOO%SH$?`-)a;w0F9y1ItI!s2%aG%RRO=-T3m8%7^H>tp>SD_ zq@^;fug5FuR#x1vW+Btp?aA|HS%?~>G9OM-x}blxP;15@OifMcdqtygu^Ps{s;H4Fx3zy9mLUXweMQb3q6zu>YJB2g#Jigst? zfL|(NFt`nhZ_xfd%~FvzIbHn>QD$wTgq4H+-BS5tbWH}O%sq#*6bg!g<536ARX-V< zVHjrBF)Cg$dExSKRE8hDs990E zrKxZ*o{PJ?eb)3EyTRi&ACmdmyoQLho z!n$rvA!RIIiTK&xg7PrG&N}4s5%7yV7eos@?x^AXDuT!}>hgT=SIYs6|=XYgvrRhOHW@%&59TRL26uA970iGRKx(3 zp$dh-`T#uqptw*!X>wXS^Zt*zX<)sR*7rN50t5p2xdlz$P#G$9E#5*##WL~01OsrZ715iodG zx*+-+wF2vyp)-G=|Eiwx(f8$~h;GJCP-Tqx z08OQ6V%l18Y_F-*KI-e%wNNIT5ie<4bQ03iHCYBO%A`^z=fVtsM=n)weg!4W<@bME z|5XBHzRV4r(|!B_2-h1)EUsxE6=vB}i?~Bs0R;?%?NBU0(6?zYAdjQ0!SJZ&rm7N@ z5=6Pef}#hO6i5TYPm}?Ki%0{1p}bIv83_B!0Sgo;TcDtTf&d^c#Erc7No9yro~Mpg zq6E`rNHT7}X!y+B1QjY`V)2Zw4APWbxM$=Mao}9s8!U`KFi<`(jZnlWlyU@dq3kj9 zA9ZGaF(vbAT(}?44;@H!(8nfVdYq7DvPt9x!faU7lq=s#>ko6|uoTYF*kqdKmdt0& z)RQM3|0w;3fB&2GZ+`oC=x_e)-;&|q{iolhfAP=$F@5Q$ev;O8x@oX8S5NVpM?}4b zWkyrbL4Gf0?q}t@jM;#w*G85j8H&uu$e$7KfFaa_{`NNN@TK!YyC)?E!!bF-$%;rc zD&1Yc0_KGmUXbA%-}nYS`|Pvy^wUq%SHAKUX&DrWL`5e^^v>(Zd#8eQVaRVQd~nt; zz5!X<{lB&M`-8Jfn#nwTJ#x*lR3Sp1heI!gn_U_S)BghV;pwm@R!t^l9tC z`BVRv;<18GMIE?0bVL&%ih#a%ChMY`Z`r6HtqqK&lMsf8l4=f>mIJ8LE?MIG!H^ig zXk;mpBovd9MWkzLh%XP&3a+=OujL^h1ghA$wH1?Vw$;aoz41iWSTLX&(Wp#y2 zPAQX9$V`q@U%Ad6`$zhg&74`Bg4qdEx^e=9LX8zlCKBcihq?=+G6>26Wyt~IyAnR) z1%hiYEZPqtS*1V$0pUL4gL^6n?BVJQ$_XswfBupdpk#pJ2I=8kC}!Y-3jc`$b_ZoFqfo+d7OP_kEgTDOPo|RB5O)cH@*eAar;_A%{ z+Xgjvk7#4C{uIJ5^{x{Or%;cqx;g? z|Dyk@A197}Qwk5`BE;ejI(+9gvA6a@hTG%$aBdt7_ub~DRgA6FO`}pftz)P}=zhHb z7j004s5>_cm11?h**+tsjx`#%FRR5OrZNmAVc3+x0vo54q0E(4B~bANs|w_9%F+<> z#_DBj`S&<<=D*U?{QLT^$~brGN2IL_qgladiWgWF=9Dn-I&#Z_&D7OhyM-b0ei8EI zF;>RdM<1I`FDB{2B~@_N16CXQ~w4 z^pXF=#66jfoSB?*`a(qd$OEt*Fs{wf2;zy-f_i1~07VSkl|j*8tmeXL*Smr5A5W)0SYDOAM3lE@6iiTLHD7y)L9 z7lOJW-L^GQ5u-r-Sp5IO<(O>Dkv9c?pBoZ&KpZawWvmojumYOX6^&{}iWT#V^~pDL zeE}<~wpJ(gbd`VqYNffYUoKQ%NT8{c(&Q7LZ|%KRKrs&4>9Lc`bmDZF&RmSqduPIO z9TmI}H*F8<111eMSb^C)79~}o9vI^*j2C%ProYR}nu~`kr~jCK^uzDa+i$-mzJ-1C z`Ja5OWcc9Bd3xbTKcJ_-`*pf{c}T`lEB$>*+PXPL+qaYsIH#{yQv{)XMO)g{?xwyj zr|hhujfUb}^G#kmu}JN%PQ`7oJ z71>31O@-CMnC5Dy&C~)Ol;L5ipEjPK&C{xV#f9578-%;D_{9aV^$=) zhRlvVO~+1MqPe9E9e-z*9=J;_)`btVwE)-phz2ZVfaSmz7nM=ljkQAj{`v@oSGf;8X2c`kZLJ=eKdfa5zIw(!u>Vy8bh33n)AA+{OP5V_`8Zm78s?{o+0K z()9GS2vb^^(!%`0BEg^b$dw~BzM$1nyjOm|i=yJanqNrD`j2<7Q?x-lw+5yAECt@x z@yP`FoEaME^Nac{t`o02!qNAuU-(W=C=ij~wl__&6aP>fPpO%V(QIf%!zQV9*ve&YScJFJwiil93~=wEH@cG0>v zXHn<~IcP4NA%|#`lcH?VrsJNyK9~IFKkC8jJxOjz{T5r~K$QVIgbGaI?7zNAA%ko)+@##5Q3dd>7#w?vWt1a9Q zX676;JZ2q!;cxw{ct?xfgfa}ntOZ_q?dziNkh55A@;PZkzhCy(RR{*Oem|^17nhTU z-)Zp;PUf9!444=>^7CvASW_=xxQB&BvpgfMl=OZuC5{7Fybg*n5-g)jn8`UJL{c;@#(8kd6-{c_AkP~`o}=RUN)YE6e;f0>DDrGPW(*KW&4{|8^1PwP zFO?p!Ix#yRs65YzJe!?^FgKqPbwk{fKCu(7ze`(umhar79$*ZO{x$Lo3-moZ>M=u_ zC>9-+ZgyJQZxQvVjQ^}M{NIS71q2wnl%k`@Gvb*!==NK+dX&RS@kp24 z@_Ieg++2Fx5={(={#$;3e`Yo-@{pl`-yzBg6KSji^48fQ#sPg=ol~Tf0ZJvbw1dHb z45bLi&+1zmi(<@jbr|anLgtX4CdvnY{o=8yV-E43U*xxtM5II9pH^-yElr|KtUa=1 zvT;!!m-Sy-{l!`-h!+BAV;%~_@Cf8;4%)r5@Og;wU&c#`Xl?=a_V(72{c|i*{S5T3auZnh$qKoUci}i;=3cphX}^> z3&Yg3_IKMBm+A8W@o=}kg>Qn3T3cK6U*_PM;Mqv>vuKm5F1qHRJ=Xdgnw)gs_GTLs z{mb7g)?7zh8VL52Ke%4sTbg&@{wAG1@r;!9VmT}sM199vMd^&F%MK6Sb@yi4u_O0v zt0R~H@BL_+mSS;gYWC31O>H!|#OS%u8-+25zhE8oz6 z*`@U3I(0Te-+C$MLI&%xG}7K6D~P z+g#8*H~Hu3wO5~`mSqiRL1eQzeV5t>OZ6I-gdh4&PvvZDSz)LKUk(0 z-=5Q+mpFYxzjs9eX%8(8EP(#%8!4%108qr-aa&Hv|AVKrh3n-a{{>_-E?S({)@ulb zL|OIs$!#lUmY);vT7G~3?D;gk^RBsk$&5WWxoGe1d?iFY(m}DMUb)@b*={2E&u3!c z`}&r~#AKRYc-ej)*7rN(}>DQe_F&}3|<_9Pl z*V-MhW5*VK%bdl?af&8}<@QrQhF2ZAX@jh&n_kN`g%&4w>sz9Y@Of!)a6tcM1Qz$& z*6i|2Vq96eEi*@t;5r4eH^>Rq#QTpO>ZV)w#F0i|Omg{cz+Yj_nFlb({WomII>0kX4d~oU%-LZKQlq;BUI7xH!F`A!?iot(Ie!66zM+Bd* zg&zIlw<*+8tm%US28x*4FwfoZ{n z2>LPOS5{JKlM94EuI;aF(_v!so*10 zDb(Qh%nIDk){XV+e6J>Ri&^q|-4ybhKZ{DhKsgd~5+($B-L*IQ=$NO;O)bIN^M*Bn zrshamd$opYk8d?FDq}u*cMEM3gH9`6d25kge6P3zi_QeB(eAjlnY+?`= z2ilD|z4t+wx;k8G}i?YNLEgq1PXv6{-5;bCpC20_ly@HoA9 z_A=dbI4i!5_Urhs{>lp!^s_RCVVJc^p)#frSXd0M*ZL%w^Z{iITpj}m+wncDgq|+V z8Xx^_T#s)lfNRtBeGr^$E|Jln!I%zoiElk-`@AA9?S6&|`WN=lV=Cx= zU{?4By__MyQTJRK#eEvEuE#6A0|2a9T0MsN#ipz){nmLl&y5KtC!)_3(yeX^`*EeP zr;GvRb2l=k_0_?ijm`9l2Wy=zT}*S^Zffhiqhh7ZfBCluY2Uu}6vT|Hs<6KQKmX1I z4bN$1j{a_Ur|5&(ewg{d^^fSrNeUNE$1!cu`W)(v%9SzC8k8|wEU*YsY1<(bD!$2D zl`$Y3w%^Ax%LAxI83Uk@vHK9M@=&OZ*}U0W83SU8tF#c!DPtf@NS4+yuiz2Y8WW(+ zs6`ng-BF2pVF&X(jTvUCq7#XZ``AQ6G>lH!fyOK!bk^Hj-Q@SVr0Jzm zAlFEc7U}~^2MQGBstldBYFw3JMmz2$A_fRBuUATrN(MbBD=4XyYcrG?T=<~86le$` zs8s_Vg;K;|-JH3Fq!idHmq)n9%ncY^l%alLpoDccnnId&5IW?AK!}P#7oHpL6P-IK z9`WqWK3I)FxhlipVSFknU6rA3m2*|L^4?!Z$hspsUT`&sXCo)g)xdH@3{*v2(HPcF z(sxz~%5-iqBj0(rAi(12wU838NK(9asQazWb_QVA4s-xf_f#7JtC1apKI$k@$2!Fz z=;XzOY;%m@{ejg+PnSo&uTlUJPZL}NL`0p&dRln*@%)WINwH3hX*%4qG}tsNI`wf{ zw?$l=UZ6lzxMXN2<;ix5QCCi1t?n9_4wrX2<2`(h5(CB^*u%2 z3Xiuo@0G`xd{)y<+5G&x{3d{SGDV{kGt@7};KQR1dgX|dPM>v{hOr5vE&9aN`|kZY z(WYHr)|Bd=8HTy>DRfg-2>QycEn1&M_M64`Nquu6Gg#tQQbagn~bMtob*Z_%#tNH^bbPX*U$I3EGu-!_rw z`T4kP&y*qt$Uczh3@k5;v5mOKmjBoK{bALRFvoPZpsR=J{M&M z*Woy0F`SZa_fUW8Ng_5yi*v_mV&n%DUOXrI`U~Pc^XNevhhu$&SY(uDr(UD+tKXrE zAN*$;7-%Ptw;p|?{QEz4a*57f4X;=lVN$N@pRZ6s@uK?%g^Q+i$-l5v*DjlNQlb(! zW$_`(Qhq&=X+xkc1J=$g9n2_pQ)V_nGk0yFn=)XQmQ}FA=%x&1QPNFWCf`jNFiXoS zSW%UmvQ*AZ8QKf8^vnXz)hHfhCS$FX@20F>-^yVeo5D?5GNUO$v^rs)W??9m2M`bE z1paVS*3weS+C$V)qnk2I%+tEQFx-Q_38fZfoEWbsQW=x~L;<&DOADuH za^#2dZz49SA0#^S{%iE~_kWjM9xt`DHc?McD{bH2Lw6kPr>$FBMW4s|eX>XKJz#>z z_n)1nj5{OxG)~z^VK-$qFA(Hu z6oqw-H9EGdVHE?U1&E38O@U6p)=kjwAQ3a$VC_-}20Y5O85A+|i<%+^mOdDqOiY_w zxv2aCSj8Zo?oKaFOo``XP#__F>{mcZV03$j=Y{)Jrr?c4%d>W`qZ0`!G{wDYmO$1W z{Y@MEd3nAbKqmzCFqv|Q`^*={R|AwCVbRp1W6~U|Ek5K8ij#N(gE(Vnr#cWHlpE3| zhUh%4RiJphJe+%<@!ONlP;!y+QeIDAkOVfH`jgj{+C1jl~Y+EM9`{oh%e8(*< zvV()N#Cv<{T$rZC``q592`h}i%_5W^*+_yMm?G2`k~3B&#rfqhzW1P3%a~G%7`&V4 zxB#?ah3_Ezyj~e8R>S}+%b5P2{nXvDm0CjPg9pERn7W(a&$EmvL@BP#fRYhHo`A3N zGHGr4tiHtA-phxwJ8{ z1Z$9BoeFu4p`SQC9hDOposKjGg1PYpCbGfhbs*r8f?tR3)1Hv>#b1PbNzrx zUw`qvNgCH(q^wxQl)|DY&YsWE@e`PIN7U2ppt}wizFVcs5SB4Zl~~3s87*TpCZ{v> z{7d!}dB`VRl zv7}}h^XA(r(VsVd`>gYWJivvX)iYTvu#DNTq4c^X)|N3hQvX}O7n56p3_~q>0PC2a z{^WYm=crLeb+N#W#s*o&)Gp<_4uGs_YB@_Uy)mcnF;Mh= zVn^{yYrc1_;Gh>?UszGZfKoHH>kSt0E7h+-XIafYf)b{`*DKvjL1}T}QdE50Vsh3# zKqtSi$7B{q13K==V+$2Am~n13a}G)sHIRcM zMq%8Bf=b1Y^P#AL;sz%2P+H-7JSTMajMp^^q^C?IVHu=mS``Yy3qd(vZ=mj=TikN6TL+3@Ck1%v4VycKKh1c68 z>T(lB69Ln3?n*noeQHoY+Z-#u*-!|gqX~r!+E3>C0?HUDB$QG@Y{|a~@%q6{8Qhgw zg~PYudm;v!&xyKm{e3PNhWQYI@2r^x1FStN!(L+tmtKAmD3dN4o3*w2#RxP*?gD=$ zut0@UC6i8R*BFv&ZPk=Fh2LWI<)Ktbr;>S!7yvI6I6W&@sLO%eG&T7sBd)RM+Ui=e zmOd_qysS#LDoCWN{8(S4yd&U@%M($0_kHuV3~vP9I0hj;#wuEQVA5h)aH>i1VG_&w zez^8^(8#E^c1%9%LX(S4F!s;v;uT{DC>BZuBW2IFn_K+-R5Z*T1o-eS+MRvryQp25b|#t49Ho^FlnEjNzlbh+KdRC)6(2{;eI_)^-L*XV5x*g ztH)qfQg7hqO+9CnZ=oWll%Nv|3M}dmQ2vX{uyn{s!6{~?@W3Df^$*r8TQ>RWzB}9KqlepQ z-%TO;?u<<)@&qIh>_cf{L@8v@#v$O{YYw^PJ9hNM5}kN|NyZP^1>QAvo-qK#4doD& z*-(rEvvUhW*%@*+L0sh&F@?Zw=n*3rc zYVX6{xZZ~yu5If181jP6hG(sU1ggr9`9;e2^}9tL%)*YXPMV+B zu0sBP@(HiB;K}8~7&K(p&?J;%aw45tC3?Ttjef*Fg`i3 z-z}|O3d5n>+@jyAt*s*$?tjE9ErjfY0w@eda{CYLcZoES4-v#OC=6~#O7@}g9IVO; z6sAxKn>RW|S&KR#?p^zv3#bRma_5fQ-E_ZI9@H&Wg}S)v2-X;ednt2U81utpjymPc zr6oFl*}lcr3T4u1Jf$;$B`aP(xBle6 zT3QPfYg&qStYE%(^?^mix1O6PC3lD532T9@Htl6BaWI=3!g~l0VPO%CYR>?jXsG}g z5FKez8)ITW%C?+xXRV=xd+jY+or4e-3K^_@&?tqBvVMZ=H`H;viWmhHFi>cq&Y-+u z$_-&M@~_O7VegydRh0+E>SO_=K_k%@Kr3x8zl3{^^_*cWahGD7!Rx1EX z5ctG}0)d96$(zSuogZ zSTN3E?cIg_7q7kRwY_WO^*VyVU_b;Vgg{6rkMiU^)7{fKhsrtr_q(rd*Q-~rs;jE2 z!;I>a?sV0w8_vD&#&hmDr;`6Qn+jiPF)yO7paTK(6zCG*f-@C?jM!v0)faMzDPy%D z3>6rL`GbCPqixO8M-~J!FjZDY8D*4lH3Iwj*|`wk+vktM_W(sB@1mBTre&z4k;)B6L-Llt+{y=9jtvI49VvLP>Q%*VPTAp$LYx*hiQ5?L2K9O=%M?JY|mR_ z4y77t2nxLYZjgpXwHbn#Jdzdw^_-xM^z3sHZo&-ZKX|W!3vJSnnXCvbD)B0VtTFOv z7ZC-#I&QUteSvWMg*T^Z&QX8>a)EM|9t#uj`rA&L_DFn<<-j#3jM3>+4#L3P=ZkN$ z-6L#1opfh0S0+csJcb9Elbia}10T+f7J|^o0OKEm z86lhjBdooxV*a)YZd5I&cF$rVnGOo^dVtxAz6U0(7tGrw5Xi{2VsP*hejp&2$=CFc z^e&`B8-y!h>VioLA37pn(uHpwFmX{wVWtfA!aIk|M4^Va?f|%ZZKld+$c?9*s{5~-m;#!gz@1J_KB_nLxXytPQ!pL|L zH*OS==4AMZNwrZnflL`!F9LzU{5a)MJ5}evOGn^jIQiu&#IKRn!n1GJ2MUv;qn#iXJ3NC6xBfsq^K)q@P}T!_Gb}OJ$cF zFCB5vv?sM+Zf;P!AS>FWz&aJ9Ve%DjOn{q*%2 zf*;tN$fK;KMScXl_Kt%t4|^#T&E)4S6&9Gmu0EJ6H}KF@tLKZaIG>8!xWSl)E{=rh z#Upe4dsZM_#@SZ=u&e%b>G9*2W@$93q6xG%D;<@qR$|G38{!Hxzc~S6fDq0A5MT(O zEqHg3yslK+76Xat8X~ClQZ z2HLpRGH+`aOv}j`iFt|gz{o_spw(2YKqkd>PQ7KQ;+9dyav&DhU-7ecD~-B8XwD{(ku-$R9~KwNSXl_o7(mjDkpM@~3juplyAot5-v=n8j51a+aQUO5&Nv@%_G)4KaDn0kGRuh6ktGN6inM4fPbt~3vZZH2 zM$fX4RzM+$S`AeJeWiRRIWM2B!VIPC$LFZk|z^9fjBV z`In)ILUi*%9X)uro*uj>6&`s|&ovU363~WuS)mOhYEf8C7Jxj{w2YOdC?ksB)t)01 z3bi~EG&&xmC!Yy(!4$MV9=Z?02lkVIda_iI0bM3nP{tP!Kgk2kgaL279p$twHB_}> zx>&!L6IDXwYLBY}vI^u;mt0YBrWX7`V0<=6&%Zv$_a3SM7(wU0SfH$>M}7qK5BcfJ zu%A4kEWC#$s>edJ^;L13@7GlOH!b!RQwz%&_1BOWL*~;}R9HTmqR;NNO9o z@C|L3E{t0kNTYPf4=ot^Br6>EgZU~)E`dy2%fe>Igy2mA=oX=jGL{z5YQdtLZ-B`` z0NQ^JXOwHmKv-N`EiIwr(_t>~H=DCBshAtC3DcjP3iMhHh~N@gw)=7p`nbGgV2f*0dRYzcj6C3>7C<5k3FT$8X$;iYKYSM z?l2{m{tQ`08D*4FQeeNmIDw3OKVBNx9YMBN$}AtxoGx}&P|@OdI6_>TRzm9cU@*#l z3#z6;IevdsVwM$w($~BYtZeC-kkPX&q!n05Q8Xcul(4o&Kkq*VzEzH1aM4@Ggi7qP zRJf#g@rZ-Y4SM)3Zcq=OOI4M5+(4O!Xq()1had*NI3NURZ-p-?$+5o(rMpO(Ne3AF z(0qUf1osV-MH@z56M0xHgw>ZLZ$~BP{K^870Z#s*ol%2xp~~-aV6IvyDAVJ<(aWzv z8z#!z{God#e=*8;VQp~xVFPcIQX}nsT(yw3 zpX_5csm7F`T^r4G%fZ^@lLe5`QtC~&)D8O6R~&TWO3IcUv>LiP zgn6=su=KARnl51A7Xmo*2P1xP*iWs^5+fhZ=#(4pQc@2s5WPW5{eymP>IWu*21bGu zErDtp=m+BudBG$b1QaL(!a?}?nVwtREqO2&;THiAZH@fV-%(z%kc2T>s;$;@fzOP6 zVLI`?P%rpmnwSnr{gJgTCS(YCltLUiU;<4pK!Ta4vB~Uq8sXCcCYlCELtG0B0v3nUy541nVdZ7S=W0sAH z>#wU!W9q+s+|B1IjKOOS7@ru=g$QCW_9v#ow0CDEJEUpJ;f_%xs-@0WNeF{H|J{fG zifY=nl2(^$Gq1-@Vdo%SxzbPWnXl5*ug_8}ks1@-9XC-!?fT@mOw7*CQYbJ>v+j2( z62~D?nuq1cXI?4>`>y*`@>3adMA*s90NWNz2)uW<+s!X@h;XTYlm^G9Y1?K$JH%?) zxJ{YzQKHfoV`Ep+68+X!-zA&v>U16>1W{#_QO324-~Pk$ zG&SVeE-YFit|QOv7XH<0wNPtoGyj|obKaLI7Eiw{Ha(NzzG3nOOk^p2yM+C96!f<6 z&vkXRR9~N)=Qr(oHu))qvGF(^d1qldpsB(IBr5RCZKQZi+6$vCY_{wU4WltP*}bnP zze)Jsllk+F@SfBh=*Ocr^4PnQ-`JU|yNk`U+2_nac$D0MQ^{{c&%emdcu5EO3jy2y z4?isC_w+P=S0_b7RmpEe8#k^?e!_*SeMc5#lyN~AJA^hiuz8A&i87WBa$!u3A;vY> za={nXaub(8r7lJf-dRVLGEKz4{rVWSwaAzXEUt&80V?%zGU{@_dk7BP5h=cv#jhwJ zKH?%xE?^pUh9!E9+5}Y^a>qwkwI}0CV@|4DK7tqkLaXt~5Stf_w0XUiGg-7c$q$Sa zf#~vu7Sfrl)X~vF9qk=-;o=2yJDn7Z1n7Z#ZzqfP>7s-&UjHo3y537ZNzKD@2!TwH z)u+ysyDjoTg_Rv{G#gm^L`koQiPZECl}LcWq-Tfalux_&3(RISt9z*!1nL+W8DV`a zoF*OW!_yV-&Iv?p47*BFs&B7R3M{Bdy0Ax8 z3S@5BT1AHsC>iyu?VU(??&Ue^8TF+LV%T}Olz<>)a2WY(sC$hze?d$VTo^OAIAM&_ znMe}|ErjkaIFL`DlL{5aOsNQCfSH*%4e<6*2N?djocu3F7z6Wg=Pt%LA21&@HfS>) z*fT&F<6VR>=H%%ppQG~u1R;BNsketx7_(u++Tg7?TUDUl^mPV;}* zTZHRm=9zLrwbe2oma1{5=c4rF3$ru}70D!u7sLoG?W^YuugQgPAmawqTCN$xHb>(@ zs;M?`(^p7~Lq#?$mina@#sEtxkinrtXve^Dzmw&+8U!*E(_wx%Li;X6M{|SJ?gC38 zjM=!>Od;0Hk(iDwrWmnxf(N%3zCPIIh8^+}tgnJm3^P-5CVM`B(=wQv;{Gj?jIc_Z zmi1vh>%$O87S^BeUNPyTEz4LM$b~VDtWW&%N1FKOZ20@{&v1bZP|xCj@`H_OW+5SL zkmDOqvbj1S9bD>+F?!^#I;yM5zA5?kGqW_|k>Xby;`H$C)zp$h%jSnav(w<5)Yl-0 zdGO{cE_6&s>frR_m+f?ELZZ>4i_<*^Dro~77uoRATTVJLAdM-xFa|Y-A@s-m=F{h&exodmDWi-sRxOmm7+@iROrZc1 ztE=6T{FcI%!IYP7?D;L`5-?j*OMDLG6=~5}o>FpQ$ir;H4Mi`Sn7N#$MVT_cQgT0g0DU4Cn zHIG+Q{M!REQ_BT1Ktr{W9=f%Wni`gCZUPFc)r+ssQO}5v+`$wN5rPS_$!zeO$@@ZLeM z02sZw1S=IRF8YPj9V75MQ679lD4F2`Xcxq>J0UEIvAI=C6-J`I!2lPYfKGm^j+Kk| z1X_9CtaAyw!nuHVIXWKVHn7oeM1TO&w(#9qu>6$f1#G{2dS#%{*2&sOp!q|MGjwr5*jwH*!%dk-~3lEj;#SV?Y2>+RZlwBKZ^|`Go9?6SFi)8l^hNSn+q|=rwh|`#$K|THzdE6 zQ7XVZnb+%0eoLWuXo701iT3W&vAvyv`iJ!7_ADGe|Es^u=Kke8Jd{yJ8D->;=bryI z1p*$vpArEVig1|;7mBbZK`4Xu-plsW@_5Ri+@WIci|2ZsmYs!-{EQ(Fc1L(V4c1eo zwTYs^%3K(EMOrkLr<7b+c?vQiqiNa5E3lwKqqF$v!|;8IeJ%R+9NVMf(oqxZ`(lrq z!m?Fd6)?H~{E<1fHxJC8Etf+OGd6*9EzZQL`okZ{z;J@??-Ps$@F7&%CZVNppn-oh z8V&rCk`j0a0)g-VJO8Sm|DmOWOEvIS13*gzWs87!BYsmN7O_w?ER}6GS8#3ZYydsJ zP;c^E3O#)>s;^tzTo(@1v-(MAsme-Q#u-75cp}8wV<`D89dcS=u4{NSKHm;7A(o5I zMBK>eNL@Cnsi|h`MfUj7n2SQu$>g^b&Rt;b&)$g$x!PY1kx(_oW2t@%0a-49251Y( z0Sy^6A^a72y)daK`UBb{&gogmmr=-{x`?UM>8QF|2#CZgmyRHNCwMoj2QoUYMPBKb+!GazTtK z#diY_6BkQy$qoA{@GdrY*HG8GN0Tv1gKJh8qtzNI61G#Vsh5VQV6$Ay8P#BN2E%NS zn$ww_;J@;3lB0oTrpj6&Y7TRUUJaMULS?ysT{x<>u6i7 zAV!X2sLLN{dkn%{OnKNA#>NMWIs_tMoZ~w-N(%{Oilu%zgfYNU3S=NmfIlRW_eu(6 zpjm=~jF(z%K@Xn^h3vz_~jPzwoz%evdVQ9$5wgjwx znh~1y#CiPN@B9rinp;%kkBQ2cG+fIDHxOqgr8GC)bQ2pZ2AZ6lOOj6$=Ps!VwcUQC3k=K~ATWwNsqeOTc2g!rHBk)qU~hm65{u z_&9HC>@h^}`hzq&IY+I{3AR^)&jg}vn-W=r#{*4Csjq$EGoLOCW6CI_j8%*N3r|wL zHA1a*ruh(Ndw*{*#xDXvAhUI?mF~H*fx4P2$dJ&a#T6mS_P9RT+HEuGXmh)TIvOfy zW2c4gI@HMWv89Ec9v?d^OMCi~3S)r0wuN~`S~QlYlw4SO3Nj(1Y1zmtu%JStv-mjY zh1nSndqkZ6eW4g#9`Lh$L5$j(Oe%eR*(%S0GxT#W+v((GH@O3;i%%A|FIQ@Oml`n3 z_4d&?KeM$qOZ5iB`;|9fDk{MPgaP$+k|X~#<&^B(npvAAVyXXxOk$OViUa zdhbN4e1x$H@Q`pW$$U432x9=HFb0CBw~xlSnYKa%4oZ|l81wu~5pFsTCdeRYc=6Q; zO-?1-fwdDpqn)}s)#v5Hg)#07VazM9M`>^<)%Lvo$FsNpJY=l3NN{n&nD>rH>HNhQ z?{nyTFrU_YC7mV+YtRn41TvYzn9Afgb*vs?jI1&9WLf4JEe96P0enZjUd#EC0C%G> z9;AuM05w$W+3$H;pUNAB*Xr%#PI}|GgT@>|iY58I;Avnkt&o{b1u}&(dfMDwTXJDc z33pMe53TEdnN9w!bn{LNRkB9hzS%|_*I77IXlyc+!N3I*))m&!+2Jrf{o*XWbHbIC z$(sg@^Ng{c`A{{Q3Ic4Lzj4e*-+X$4`e52h*4J9u#u_GHN{@W0D-H`Wl)?BG=5Jtz z3Y!m@DZ}@UwhA&CbEhwqa?k_DB+{V_0SHEx0=zy`AwEgr77NxsNM<3pfUuxR#e7~q z5Ly_+V?kaIOeSF9<0d-t#>CjlHk0pHaBUaX4qztNRIzu?`q4CN_k19|v+Qwa?b46j8)q3@|6v))@G_)XwI;hB_nHfRqCQ6gYV=6|nDy zBVPdJ%hw(;4=*JuD=Vq3t&P_y7)&?07!03Iek!9BK>Na13^vO0V0TI5(`1U$^ei;8 z)WgVFjDGyQmPRKuR8t+LI}Zohf$Zv5(?e3)e*zan=luRSX;Tvn|?%Nyb;NINKu_ZxXQ*Y_!XMZ5d_8(Dx_E*B?4)L~B z0-C*EADA=A2Qs)^nS2Ex9FCF48|D{TlyG~(?3|K$VGS1y+#Z;=&Me61XM2l~S{htt zQ}@*xKwSgsbfX-#G%(|gvQlYMaont~YVA{cpiC8_v!TG~0QQM63k=?a0DQ5W>h;if zpPi)B=fDe+w|5bR6anm4-#PB4?>#$3m&ZKhhnaySaH%PmDdSQA8Zqx3k8>f!o}CiA z(C3F>Bu2Pr^x!=@y5|lZ8QJGI-ifh275al{n-a7UOYX48xF81Q-F`S-Q)&NR9X;}p zfrr{^4ZV9jmbYW~+(@s3m`f#y=gSWWVjyTiJIo8d7%6x^yd54kP>%xo3`^vNg}w4mObHYC~Dkg76>{&4d_ z9eZzRvnave&b0wWW9Heec}B~D!g7Fc8zxM-$yAmMT73NzLHgkfQ}o)~Gi=Q*)e9-C zR+svG^v%b|>78>W2WK z2(%Z#z|BWP2FTW~>d=m77M-?Vi1}Ms~tXnoM!COB8N7I;0u36Uq^dD zGX~>eG3~NgV6H(Q3I)S7I}xEX=PuF7lPBm(Z!f*`_FHuF_%S+r>ICbTZa4*7NLQ|0;m@EM(>HvQf0iR3&6rqJGE){$NG8M}2*NEL zvG$007;B1=)nilV;t#Y!Ge!W~F%T4h9^AG`&$4;^>eXIC{mUq$jB6OC z8^}_37uo9Xo)0~}Y|WmY;6H;YA7cBits7dYe%+r@P0RghaYdM!8K(Z>)GctMUQ4^T zR&o=gDWuOQxFzcJLt~ij3zFtNOO6GzEKQkCXOK)421>+Zq+@j#@N!0t^c|N+{z7$Vc*QG^)B?Y$;$g|e?ow;YU{8JGjF(<{ z*Fn8wUh;)fXJYinj@Al(>2j%Y<{X5G5W1w!Y7o#M+;y9dodG2CWHmJ!x-tOsSQ;)A znFrU5Y2+Uz%^3Jd$=+6KX39p!*gkJMLHFOKXLXj+LLf9aoZ#9aD35htE`&IL5$8*2 z@T9j*;hHf$$xjkI9%%na<&{!1My@%pgiSAh~7IEzmr zbMen7PP0D3=A8TQPPLy@XQEv@B)ZTh27Q9Y*^;=XL(BVx8m?C%H`-_anwb16uVy6? zq`}BHC533n0Qpdk4K2z8YOD2RX9o;yig7b$DK|O1J~=dG;D8ew!eW38WT`b|KnobL zaJ0W}O{O!?s{s%M^bZB;GFt$~CIU1&7n#2W=5oi_vk(vHXL9pps56}Z*RcKpz)`;l z5XJxyf}w9W)EU@>9jB?e7&$%Kyo!?NANfa$^l2TV7w3wKE&zL5U%{(!l%s_V=EmuYc`pl!!*?hu?pU;*l_Y z^Bdpb&nKs5*nASC3%x-$??-s}!4p5DZ+!jhk*^6v*9H5i3_|Ls?l)m}RZ&T3c zku-@o-)|^^-*A~nSywB| zOQT6}x|Ko|o6W>%%Phyl=*E639Asy6q$$no$O8oygy;n(!F~~b1F9>*$d(f0X7{u! zOfR2s(RZGiq~~6lrJ)fYh37R@iYQ0{+!nul#Ya#7Y?{9Fqe*(>jGgAZ>6%gCRdlsi zaDmK9LoP=E(>s5Nwh|#f7;^dkVA&W2d#SkWi^BJxj8ISC%AaGE$RXn?4vO}KCX}*$ z`Lm^jtSlhIB%TTu@)uJm*fg-rP&BgQYc}K=EeDFsL6HRO28114OGd`m^oQc~?nMv% z;Ad0x_)o^D_X_-erduabNB(q;jtA+rw;lAYC&%gKqjs8b1<5DVZUkR*O}i<>Wl1KA zXon)OQah<-1q3o1_x?3)-~ScbyYm1&bWLKq`_15L0pa7(tWMG|Bz6>gU2R2qiJXDx8w0paa{buEdi#Z1v)*-fd7V)Jl6$dW_q!qwM9|E5BYbtnH+sPJ# z1+-p}UX%;Rl2?ZO)HfKU{^1~d*CCpkg~@`I-w0?iiyLaiNJtXvCb#sMLcj?Jr9 z-j{^-SuVdlD}m9`QQEd`8(qA3G5JJ-%VnqO*&x^KLl77m8lqjhc2R$SfAWb0ug6X^ zv!RUm=gys@>#x6_>~?$diG+Y}g3WL61(P2C6=;%m3kq`_8xIjz97yavn z7hd4>@7c45*F_-64&XRAiul5O9Q?EF*s+7wuV0@g2#H1PT!6V;fFNdIV1U!U5OAv# z&hfK_Y)})(z|4ok6`|=l_!kK;Drmwd$Tja2 zZx|cPG|dM<5Cb$fW-=NFhD~(2&&>LYhHJwhluY?i^!$R21+F;Ml(zin)G?WG?NCer(B?k?o_=kPzW(F{eeao3dgs_I4Gg*2{HPSpWG^5Zh5x89ox9|v7hkv2 z*MBfZPrWonZ(ne5b7X-?x)26@&6WluTVr$0A4RrBkRn!6dG>V)?>1OVlzMtSYyl2(r^*Jlak}-!dg^G_lhvHQaq$F* z0wFEyTz-OuB$ywI$QZOrKnPP`yV}f{WT)33gq8_x%f>jftQ5dz2!j`b5|>-D`;I{b zL5X0D!vt17$Q28Nl50i0Zj^EiqV=6czv2pd?G>FpmS}f zw27XX3v-h|#RBy}-OyGL{Gc9SMncUF!ZGBJ_mvGIy&T}-_7C}!-!g#-7wXgS7lORk zv(2N6^^57*?3!d~Gr6D#PVvVkvopxxJPTSUgQGzR`ij)2 z^tuG~4)|$cILL1q?cXE)hQpUu19e6pD?dzk++0hz6zBHF*``=S?af-6m=0$!snNdh zfwFzGh5N(6EhZeIpv}_9%E7q60))eu)IO3h48jO#&EOgGn4F2^d>{D$^@Bt5x>`Lq zEw$W0eXa}z_@)J8=jQ#@e8Y-95Kpj;Gi$@q@euV52DqTBv(3cYW+eb^rGb$kg+mFt za7x-$Lnr{e^Ugc`FYr6R{wvfs^cqdfj!=yC1K`xV()fn(0O9e+ALrkJPyf3QlRI#c zh9~;wG}9#%mEMvV*U_g9l(4i1l#!n^&9HZQ(H$TuP53D!XXH_ zrY6Sex4!VpbmG`Q(QHsR-!6bwW1$M|2GVHMh00Jfx0>TL>wcHhk8vmFQ~rwy z7(h)>BkOLv6Kz3oVum>C0vo zI|w`=qfSdEgNCeZe_Uxb@H1+f`MczWs4&}yMA*4M6peA;H0scBAq<2x}b%0FAJ7HVPVi(HuV zzQo#Enp*^*d2;e>JV`_Lb1i6sZy5+_c5F?blVBb!=xyPj>*{J2G>J9sdN%nf z{g!kdqa5H{Jo__gfBWHwGW$+ER!LraSMnQCcXuZ{CuPqs7#?9~+LW)$?>`ylCeilq z%}kT)Hzg;|@9LsxIJM7SzkY4~T|2C{&+;fMX zo6=K*duB)S69nx>>g;UGDR^=EUgz(o^iUL9z!rY-yZs__C?Xl=Qe4u9=5ETpKzc?7 zHjnDT&oZ)k)GV1YgC#wq%=9MGf_LxoMhTW~BC$A|SHY)OpHIPWt*moKT{>e-^I%w<|@F9aik9;5;!o&lHezC~qLk4XMI`KUl zkRI)fn^ppNC%8$T4X8KLKnn+TTOOY=Qh91VW6+*(8g66n5>Dm4ehnMTk{wIDXWTS` zcG4^xqrL#!K$|r@f8^cBHo&kkiZWoQ7JUPoakPsZVE&!&!Tj)tmK0HqWAOindv9U{1n2!~7w9mu%d)k(-qYh2Tp}+H4)%zlWwA!{qU& zHeZutQh&bn)?0ZzlgY$QZ2`Nl+e+T>9NQo`_;+A>9CKqz*aIet5Uyn{Q-{cG5)I81v9(cHrCC9j10v<-u{* z?}O|;r~2gdjFHVrskz4I*JTY~_{^u-++VzQY8hpeQN~i@?YG~ipa1;l^uPlT(23*6 zX<}lM+S-h4VNFJ0fd7|WTk7fYXD*Y=<)%Z24$)(eJw{z!T{JMzPj#2`L{_V3iKHhOZOQAzc7HuoB1y0*n5(G!*|wK?5tm85tbC{GbRk5 zF-ajvL!Fj-uEe>JEXdBjN;(kEoRj)0ghT7sWv`#oXG~R9W%8Rkf{{}Cj8TmL%;_L2 z3W%BmMdq@I!ZDZP42->lnayt)KbQwOpEwC<1xDGkKt!5LXV_di?Ud$H5%Asajj;JP zM!_iS^K9;wYZC&{!l|u-A7>-CIwa?3sw1;vlFt~nOJaGKea0*yV8X0p({Iq017D?$ z*Z(!Oc0WocLxL<7aUP6@ID3K83xdxEfu>qL9oS~3JFd6Vx~>Y^y3tC9_STS=&9k@_ zt_oQ{KxYIq3%845ima^#PQ|iqfL9ZwN`SdNG~%aF(y^SMZO(@Wy>$MRoi3f8quz5) z8t!pQ-_N_Kf568zG{6MU7m`-T;!TzTh@}=2`9UiMjB^Nh;Ijpc#X?P%fmWCr1Mpsj zmdrvx`A7$$05nm+s0P5qM;}=XP!FZaGWhWT@N6MQc%cl|)rQo(tYMQVv_{xwij8GV z{HQB40X7aW4& zTw9ac7@|x-E_6YjLc6K-o7Pgi8Spry*N_Am*Ms z@~1((6J=0?@K-Z1oGh;|P6I=6mOv8D^z=&4L>L>-lF=d|X`Se#GG*n-0|YU04W3d1 z$~@=?J$Ls`H0^*2YK$)Q zc=-lYzR86T4wFfe2rksoRy!ad@%bdCek2m7kpV9`=fV`%T1jiFA&tSx7PUA{xt$*iOLRts5d2CjLK@2z;WSE)>v0oevIq^FS9LNf#J9Pg@7lVvdH1G7E= zO!wq#vJC!Nz%+*$AZ|L1mAzO~Wdg`cZn6wC;#nXl38JzAeO5TH2Oylfn#`2>12OhI zMtgTw@!S0X=490S+$A6Xe#7ocz5&B?NalO`{jA+1ye<&3Kx+y&=;Ly+y$X;Aw5%jy zBP8h3q9O-;#Q+fW$ie;7u>K6;$x;Zw=EskMo}~cV8}9@4m}Y-r?hSyp4otv7Lkl;* zn(7VwFtbv?tv02ZGMEsohedsYe6COc~+>v$L~w;=~F58D`4n ze3xi+vX6fUgqbo3JRl^2*2inFy~clonKFaLPW>b2`FB8=DT8nYS~2U^t)qYZ$A9F% z!A#laZS{2g+$;P$Ak35@Z)o?_*VoURPJ@}UTW;M-Z=d`b{|*QDzPU3#QN5-7R`LuvOW2Qu*``2k3_{ zyHw4TEf&+WIDBbn(*|f%CLiX)0!zKM;#M|~>Qi+2@@0DBi6{8)Hyo^@?sXM>-#Tm0@2nyR7$_E* zS#InNTyC}>@kaQ0K>&MDNyApMYLI2w&y5As6q9LjSiX{SVRcZU4jFCBPG%7WE}BLu z1Dq>x_Q7Ad=8PP;uxmEqvZZuECns|LylA3JhM>2VTAOzAJ(wIq3k1lfeIY*s#1qn4 zEMM5YKWAm+P7?`LQDwzGvRWmroLpKU0!lhET3YNo`M*RC-<$0GpXswpj!3AI%=+C_ zQ&YpgFGR;e^-_a7aFRliiR3qRKs!g5SWnH(&HVd9bfmR~Y)_eMcj*sZqChy^m#Pvz z=UUQfYN@@woqsQgjyw^LPLPMSNiM)l8OnynXg+^$-+E_WpGw3fq6*}^^VeF&Z2 zMm3E$b8VTOxBi%RANVZYxPKSjv=`bh7TUet%oZL4*OWmpvQBXGP7BwT!3_t&{DFN? zKrpq@X%<|3S2^GeUI=3RY{Py2_$-Z$1j*@ziH|t>eSQl0Jrs{c$zZgQwYHh6n!2c| zxs_rG3)#m5G%@Jm{x|X!R7gUE(rCy4h^dT?GPo1{A~a+m7=kYl1kOxPW?qPf49ZU= zCmW&3kj*}Ap#V(~!l12SGZ8`_KuluU!0WPt0KJPDFEF)`VD0+$F(+rx&N-r7xP^M} z*-=UG19jwGCk>5B!lFPZ#C57E@r6lct|wzejpW(V>|e3Y@= znlb)>hko##zoDN!_nd0*Me>n!EDQ`?VOkOMI6@x7nM1^v@1b8lqNQ_}U@AcBUl6ht zlBW{EaLN{Q84JU1xAXBM*M<=Ygu>+X_-V&x$roI)LA#8m9m^=Aj4}$v*|TTqlb`$~ zzp#<7<}BhtqXvH2l)$-4sUedO#JUG&2`*g?kNUYVMp`=)d@qfFJt!_m;p{QO&VV?- z6^z_G6NUvNlnl#PQZB3xD%2sPZQ030fdv*?M3Qt!8Q?q(egMW3ZhWf+$ z5Ok^1mi32a0|Xsj`zFrd*JunG0nBX?vO&I=(;`g)Ar}N~0k_0tUx*Gll;vd9jr2T7 zb|G2F@fsk6DTa=WGV=(zAm|8sTa?MW^8f(<^hrcPROV@bAWYu=YC+VM2U%IlHj;;2 z5bq@xu@cOJ<=Y-=<>U(d{p5Tv5*+pw}l}__~J(SB63)K;Yk#p z5qN*#BURdT{9?42KP4WU6kyH~eA%TE#4IQB>wWKIKrqv~?w9Aym^F4jN+y$y-^vHT z`11#~Y%{9k0vR}N6AW2wIH5TLjhJfzV5SNIQ@|UckvV(-RCQ7~Y9;rym*18bro9$|U?}Gj$iM_lAyB>*l(CRN zMmS&>5E?oOjh;;iT57CM(tylaC`2G5pBC5}xFEP)**x^XQE!h zED_YViviZwdNvLrAn5J)(eX1*I(5#&4}{n>AJ~K2&l(yU32^DR)vTj!8!g<=OsRdX z2tl4`cR7U63k%Ou0eyRdjUSj#TQ10b0YSrPO{bY_S%^iplz>nirW5-HLtK073J*b= zb+EZ9%MCRpo__ji&fE~r>;)Oq!TT-Hw8T`Wj;<^8<7vKu9D^odD?iYVk{nAX_V( zb}O|@TTo0IGsa`^)Ne%2nL{^20+7d#9HXmldT*6qwT1ak=j*}lO*T739; zk_)Hp&N$c3>mQcl46r!_c@`?bj>Vni4;@W@DG!|CTf?{WlTu?400UYzg0XqZ?@mT3D*2#qc2n(UY(8)qqM$pD~ zl0LDWtd{y@%%z3V(89_EEvaDAcatWvH%UibGG=BSOBoEhIu$zBWTj)Npx0HiveVxQ z+9MIXaY^2bvK>U-v|0<9&<3(#)UIDLIshdN#Q-T6|8^FUOKAv5qGTE6hrDPnX$4Dy zvYE0X05fI*PajPTe3N1kFEw^ON~CM0nZf@@L&KNoyf_CJAwoo%u zhIT@^vyM3LLv>ZqSc!1Q_Y0XRLtlbZFdX<`b^-4lbce!l@-Nw`tge!rBf>NoZtKCf zNpqut+LL_DTf4O(;1&H|*qnE!l;w0QsF2pdXS#)JGh*Ji-P#O4_Y)lgnn zyD9DVgfLSUV}F1DbN`Dr?7WHfwNzi9o}MD-*ah-2%Qaz$t!fKk9voo_hWi%?70MKK9TT=*Ghjk_4_5vp(L=HCS_o_L)Ly(9j2=%v@6r@=X?&WCS!kUntdFHmEL zbjwHJ(&@KZMFZqoAN>t#UbCHl7wEfioU~Ct%}l*VXU{xM zCkCW3wG?K`P}4o#TDt#^2I+wcoNVrR{8b)i-`q8Bxsm}08($pwv+?Xp^-IIADj+k3G z(n-jQMC=f2=eFdxGSqPT^lA2v;>mqRW_aUd51Vh|wEMdB{!%FZd%roh z&kOpnw~Da!lg-y`!>ZTosinn6I-`#2+4-iS!NlflVrQ)MGe+K6a9z!F;Vl7{ucU>r zdML?+jJ6davxq`VLT6!_6cjsWVz0_+#z*R!Ri zW!_BLN&)`88X6j?x_V_z;DV0I%F2vOfy)ihVK$qot*!8LPbv4d@SBSD31-TQMKScm z;{G%dpB62F}k)foSEsVU1E1ag~GE=7e(wDyU<>cow@`P4vB%`^7>Ra!nhK`5H zQn`UF))uO;bWzCpa~hqEQZx=nRuVH8H}k=8F7<8us@4s%$bL0%pJ;Sp}%8Q6gg3|=f?23EGb z4781&wYOHIr67CvM7?EHTW!>>9o&Lb+$nCsi(7%>P^7p^a4qgm3GNQX-L1u)VnK?v zxLa|zljnWU`MzHnWAB}jUwdWUYt4C0=V3^zbQiUA;)%-fht;LK=*xb#TCep&)EM(m z^;{MEr_qi`HT1f?7fvQV`->Leddv+|0dddOs6rmX9Xl4LV;0))6 zBGMTFjlL1s{Ms9)ccI_fTJ0xN?3OTm&`E6ZtpLb&bvpI3Q3kzIx6~cPJfInmFbq5= z#0NA$BT%+c^l*r)%ITW#p|#~zi$tod_%1V%)e8!b;qk8=hp}lpoOnvIbid~XW|q#W zby-B*FP~Gr_g*>uj})up^>jo(pIU>6%S&q$t;!geh0$j_Vu;45Qn$n(6W5C?v(lRH zC6o;j9y%!(w&C3?_Q|~mXkVSw6#od#_O>?zwSKqQ!}5Lbatc`y_D3__V_fb;^9#O` zd0G$FRa9;BK8b4Ziuh$&b$xzX^%;)@KYfjquTl&|Y5iq8OES5W(KI(dsGjAl;I9A? z1UN*r;=|T&_eP(Xh)uRJ_xhm%At$*eO8nYKOfb0_bE{Eh`1luicT2WU-4YPHkKZ=j z!w;qE@{PRaWW;@3;*7ioXwHIRfO}sTlaOp?I~y#hom1vPzoo;>rd!XY z%>vc8xnTokoKp>0)iKZq&|w4^v#_u%y$%nym>*?dTbLc|pfA-e&Ze#jw$=`{FL3Uu z-?K^hO_cF{Jpo##OaZqZtoYA&4*&TimiWb%D({c9E?|yK)nP{%^p85i9Jt-#CHIYAH6G;yFyaO>vLa*mC zlnmGx;t$YRdFN_kq#G?NSIg~U&mJ{?O%ySrxfz~P~Gsa@W4JPC#*Vt)GG@~ zr?Aqp&`N%T4}#74}2? zxLYnWX9?Qus;H#9=CIae0h3o*Z`qgV#g(SlV%haRK^I6JHI_~jFEY%MDX{o;;2tl3p(BGsaNv=gaLfcW7m>=$12zCvH5O4+Lu@q-@Lm4c$0Hc$ue%*tmuy@kyND3v2%=*n(T3O9l{GYqK37-oy8-;^ERT zU4CS)?pBA!*}g8mX7i@lI*JSpYOmllN~N^ENCHIVIs0c*%9Wo@Nv%#({%Qc*s;~CX zx?W=D+esDN4ca>~tqY*8%Y_SAcd!#=!wtf2AkjvqCPq(Q-L;H#Fz}N{Gj`x5fM3RE{N$q686-w)LN>gFrh|>o0xf2MAvN4lW3-R|)tL>gv|uq_|GAw#w;+p!9Z3r9o9x!r z-6u6&~`|k0X>tGjm=n@*^62Yw)@XxX3iUxWZ@eCICV^l~-gksTOy_1(e~{kGxitLsN~bDNj32)Xe7OAxc9x&7x#3DE$xuVmqLoDb&R-UaE-{DXcJwOx+t1+R_x9!Q+oTaVpQQd^O>>ok zR3)m=lc!%rwN8FUDA^mG{8OmsH#zp|9e-?iKRA2%-Teygo+V~3;zrN5Je7CR z=62$=XTtfux+rSCVIIznfy-Qk<5-FkNs>6?hn%zp=mfyvAm8MSPuA|Il)Xbpghkkj zUcXGFocKKne|j2U%73Hh-_aC5Ys+$f-a$9@or072n&CV(ulctD+Cvtb zmbBW~M%p@BMd|cn68ydAjgooDjQ>T9F&l=t0&4D*tXt7~QNuD*IIVrZi+rhT?>VzJ zt62%$9!rMpM&_i_{n)>RW=Zrvl<&cYm@{wPtg^z{TNY+dju>`v$PQsf8Px@d*+5fU z42Qu<2UEJ~S(t*=4^+OIFtPzaAcg3FW~eRT=&&ZFKpWIwf+8Xph6%;1qDMxa0CSk3 z=s=nI0o%lkS1C1wsH|u>)S4_o-xMnHbB@hA1SJn#l!;GJR4Y1wIFZViFbq^@4Wb(f z5}qd0sSIs18dG2%Nw53elf0dorA|QwK20EKcupz^iJ<_NvF99iJNktfLH0dyr0jw$ zsEIJnhGY^41~zb~o%jRqU;%Avtv~W2E3~I~MKf0u=p+LPpj|h4hImMefmy=Ah3gg9-H+4^%*bBFv630sAr+VO z<)2JqcHyAYgnDz^$Q>>TK6Qeu9Pimzx~+2TAIC{9*jHjKW^QK2u5P_eC;pE5Ha9px zDwU5eYJMoXKYsT&A~w(eplC-XTRt_b$Y6G10e9i>h~eHnl886_0lA{dDua}jXFHpZ z$SW)Fb=lh#vM#7Fxgcp3@6gxJ~EpQ?&jveVMz zy-}>thYX@0CDjmote5<-*>kcK*t0P<+?PfkOWcEO9F;(%I{L_kS_r}AakfjsU7G4R}yqm^=!;%)mB=Mj-9_pwLuM0Dn{=h2ND68?OZXm6Y zd#J@4!Ex|PXAUQ&_kEMS3iJP(lz*ccQx7hr&F@WVE`Qvg?oz?$NisnSGO>Kx!-Pe8 z!8K}G3$gI8kd_B-05O4g4Egn<;@QG&)lKz$#(HPJsfmV_lp?@sNb##fJs8fCKwh)< zGqroc`Q(V2u>umJOOs(X(zwKq+1>>^j{s9G+^6X8)a-YH^(J9S|6c)MI?%^;B~k~= zAFy*IhiL37CA@CCiO0{5W&~$dE+$K6ua*_zDezccPO~D>K!P{m7#im54cxn_!nr!a zNUF4mn^NG31<{Fy*^+9LzSw!MFe7-s(-&H42O+Qgv>!)!Eqf2CD4c4cQW<8#)J`XU zA`O}{p);4k;QL*#%=E{ve*%yAzWsMV3w#Li>mr$DE_aruVB}Fp^QP6?`MO(S^yE{Z zn^VZb0-jb=3+guv6EUq!9mZ=UZ*ow?%;9Fns;!EeB7%~BuwdRN9-4@0T54<%GTbH# zV1ny;&+ZOq?V4IZ_NR~|t)@Sjp?W@2yQ)sW!>2IRr+A`;0>xJP7BR~|q9 zmYMR}jrPNz(Dx7G9|hlWS*vEg`?Sj`Sik4aINodB#H=-ZZ;@cI1`Em=8~p_+BJ5B2 z&>@0L3FZG38ia-e`2yA$8<*%kgYWFzaeIa30P>En9E}POjt7PQ^8*wj`^i$Hx@mg_ zLd6n8u1O$bgF{Q&Lg6Uqehy{PZ!$jMo8n6yzXYDHnKF}FtliD7-U&o70(CFUia}M) zkZhTOkP<@N?A9G*l{MM_Si`KsfN(6WF7JjKEPP6Z)#&l9{*@zh6ks+(ot=!_gdDn% z3&{+b{7^_rBw0rqXu!u2V(X_-_(1oXU<*35N^ba^aQP+PX(5)uoSia*p$~tIPa)Y!hHg5FV=qZ-I z7Qd!brX9W<6bb82B~?|IZ4U;Ayd#ilBcA3KdQro^?58IJ_^;(ho0ni6CfT`K!s znGA1U7$lYM6Vt`@)dBFo{+*ses*(wW(SeOY^0$|BNt;umV>rNrYms1{XSv0d%>Sso zY~{jgihdQv2d(XkQg=$jXUR!0_UdVGTp9*k*y{w0$>4oC7{XLgaUXvSX!?JOoJ zFD5-4c|jtB#FZR9@&*F{4@`@vA@wG+yV-xfOtUolFsVm|bibn^3MbS(r%ftVGhjd} z!$Z@=FL^_a&B)FEu>>o74jBfpEL&~X6!%}!BprndR+r9vrZ=;|EJDde+GOkRJ0yFN zo!<;;RuqC7ttRk#`L2+?yORHElH@!{`NBc+f9P#@f;Md7l}v+eD9>fUW+ETY{X@_% z$dFJCCW6kQYK(g7{>sg3NB_}-d8a!CD@%gp_3mAcsgxf6Y2*KAad9v-|Gr8#NnmQJ zYQCKZRcjJd$zH*n*DET~zgq#Dr$?*YAy-UQmc*|cDz>~s<8GW33&?komA8h@?21u@ z7pZlj@UZn^(V}rPes{lnRrnFml-XJ@@>~m2{;>4Zj7yK5Yh}rC$NR5ac~*9T;384M zu|U?rt8^*>wrqJ^;$O{@A`*d|OFOVDIu>(us{=B^=ULPWo{xt`unpv~()_9!^}bTj zx|)D3{=B+ObFIwu`2EId%g*JH4Vd=h9YynOAq64&59xV>lENc&%vj+qUM`A#m0}lg zMR@|Ej)W-dHcV7DJ9YD}xnk~<^|bHUyH5#P`2~(1#Cmh(MGn;zXF@tMq4=g*rl)uV z%J$5<33DzucoIgk_yXJs<09NhL-}Ns&%R@Rx+!yjE5pCVq(xt8ddaDp^Y_Bzkl;^| zZ#**glQA?JZH9x4?zKN7f7p;S0uWb0qi}-?Y!YtJz$MHGVQiu=0sk10;Xk12nbJCf z30APT{10Jyk3?WNV#d=+*)(x*WCYnTPsY<{eF^=o>)qZ?D@gdznaPE^adQ{W=;TD7 zQd-KZS)d8*JW;KvreBmeoju2fNCr5uL!PgyPb1iq}8o;5b+343u?v~7N_J6Eewt>)fH=8u5x;UE%c z_>xcnyUlPx?*FJ=FvMRDRS)~auiQ)OJjD!z?&vPZIbI}rtVR~t-P0!RF1;?D|IH`w z49NbPAHhXart2pnDgYjiT= z1v%B%O$g(5Y1CmYFEwh62)ZFiXC@5K8B6!%Fc9TA`(2OB1UBGGf}JZYt_kzi)tR;M za(kk#lqvqC6Im@(;h?;Zw{XI_`3p{@>}up!Df3uWAmOu?kQ7xDJ<4%mJrl*i6b$s> zr=*_ll2dHm#4insa(_ClfULC2Jf-%f_BYaHZ8PV+iU!1V{MArexT01at9=D2GqDk7 z(r+%NKtyaEzc6i}an!vrAqiDU;GWBf-uEW~1*@_7^ZtaqP9OPk08k91l6#B8r>R)F zngHXGhp&llZ%%lV{W%Cc37u?q$qnb3E#0Ga-})THdqM#HZC_C9!ShyAHK%Zvdy`Nh zrTQWbs*{;tV?i?qPzVF<_3ZY%gFKp+CCYs0e~#E?U0*|2V@0Sy!1%n2nI-!$7(?5^ z%7(wX<$RrmHP*e7k(x`T%;fEZAu)oUr&H5~bi~eE7=_aCfWfiV$RqlXt2CiJ?3LpZ z&%ZlpFdAYMG)`GtZ+-HY$?nJRdPgLf>P$cl8<6U|vWUl&pu&inQ(uoy7^Gea{&X~1 zUq_-6mD|?TWKe4B_8^}&M&&slLR|ilAwwK@;z9frCGv79eqt0v!@TqI{lwsR;W|`~ zRdX&H;s8Hha^bTw9J;=0RVaez{EUi6P?g0g>d!ejl?QL%*2UxUinR~M$iypR9{-wz zfds(5YXbGJ?|7Zvcdlf?cUBmlmzc!LdO{w3`F`szk4pn5{!Jok$i%bOk0B>&MAm2e zs&*?SKJG302VHJr-x_&&nvfUbc~3;?mxw2fVbnQZhzEkOS3jH=+XL_>QE4JLnj;Lo z1ep*Cf(x3Y$>|eDK_K2ngxuTkQ%c|u<7JFJpjsp_A~N@vDHI0TfWUjBNL)c#AY@BZ z6-|sw{?LVZP(E_081ca}Kp6wu4r5T#ATZ%QJL6PFYIAjavWK=@26+nAQW zTCZQPj&qZU>{7eekqk-$&Dg#(!2fc~Bub_6Rb)Rpc{P3GBH+3)bc*5XqTwDy!L)S; zj66K$F?!^R(a?7?bCZXtG+YNh)u8#jWMp5TY!oTaB6^^2iF*!?JvG$~4_*cSi;C&K znTG|oE{yw|4C!{me_6_q=s3&0OI!eNTyO;#`HT!5BX3qmVT()8sqok0>rtNVdak;s zlq4@wNohbacUU16JdF==lPEZjy33uBJysM|`|>C+Bh#&Jl3Zb8=_v4jgWo3F(_1}A zDk79wMPd~IVK4*WBm&<%G*XJonF@R?+nV1qBmb(3N?F*u?k~wPv3)*`>veUjXC1TX zJ`1^pFv$74zvje@yp67Yvu@FlUfB7E&$_evv^=`C_gBjo!w(TnfDoS8axw zHxMS39uI#n!crtrX9|zmEh@gbDRZNyNS&Oa-0Iofm7)_aep-KdWjg(9V)fO`oJ$u4 zbrIfv5|I#Z*yN?WQVE(WxllG-R#DOr(b5$je|m=i^L1v~aNFc3>fR+Xqb#omv>LrX zc+5R?%f=a&NVHLGv!Laq$b2vr6AgG>!5{w5TDeHw8K^v|HL~3OJnQ!%U?G(T(&6$Y z=tq{1#RbQ>SQD@HiM=X^qDBzx6v@EBbdW>2vd*y^JnrF)6uq;wzbWEuZtWV+hXkjT zB5EDzf^3dEp^d@U`hGgVUcBo+{3B1yuAy9dTXT5*kMglFSSv^0HrlT!>vlo%E|)vg z8O8@wVEg^*(GkY=0O&_)TAo0nab>ey{Y@Rlg#)a4pQcFMl%QtQ5zZBohbW^J#?@gn zi9tU~OF=&k65laAnVoGj=qHX{KQk^&>-NBn@jC2aJS(CrdvUj9>OEZ=h#XkJ)DB3# zvqi9WM*hA7OTX<|9B}efgeO|2?e}4M!xkmXPY&c#%ex1M=-Gef<$IolQj%itMyb8$ zCB0`lhpv3ZC8csODYg(dA&3FLmmm#IhwOpE{T&p)KMO*+V3$ zw3a#vOd{EuTKOKDn^7Y~G)-^jsx=fbTZeb%W@*V?>bZ5qDT48RF<0GubN0gAV)5Vw z&KB#q+-OENKC!(0n?et$@8l*ZmdP|^!U5?bm(smT&6%1BP1uA*b7qugTdbRMD`TND z)4qPt0-Jv%v?*GdvEA|}K+oU|<4?pRTU3A-0S8KCSK^G?98&1qQ%G&_@R4m+f_naE;GiGpX!;rdx8=E#zodpv&)w9pq!BEaGHB9Zc#u5_+Ru`ACu zEv|XET7^Uv4H9R|dD=I)8cP*|CfplDtOne-sv{ShYUqam5!%?#imRRZ4mjST1;NP$ zYXLUOHsw54s8jW(K@58ik+u(>JO2NY(iicY5kO9;$O^)C`lz5_jeU`7;IGO_IF0P{ zBKU&3qUlg0nvGnuU5SJR1Kg5nKM_H3=2A(&@ZklgmqTjZN+m!0YNuH!RY0xAw*q+7 z->(-ab2~8#{sn6UMaC~+H|;lBlis%hPsTBlw17IEp+gNS+byzk`}?vpxYnBMQYM6Ua24gvW?WB%?jVEX&~xk$|e8f3;Sq4wSJ*(lo6<_bT_~fA-A2 zAAq+`=|urNkM$bIU3)szr2TQ64zIVgA(RJ~g@q#j@ayXba~%GIB~iDhJ?Ejjs(hKu zrexvUa>4XAw7L{d|A!3s>-+;7!9}VO69Z0+tvAV!rP);>tVrNaR#Or`j2hs^1>hlx zR7W+U<^>Fp23}C~u$NII<7CnCxZzIuMcm?ni77*MB{TMUT$?QW{qO}Yx~6o;tH^7{cIswrOjI&%a83ny(#;<`}fM^d@W{^H!q6mo96Ld`!~yAdBs-z)pI}v? zq@v>k(m-`xi--#xrMs&2(Mj6-Ipl4aEX|zmgSFcn*wiHq{~jWlKOAqK=#?6RImQF>koli z+hkb*JS42)F9Lx%3;&+uyjOdUqo7%Ual5`~0)# z7KD|K{W9Qi6yjszjcS59$SXQ^`?ubwfM5{7&>Gt>n*UKms^@D^YBKCXa6$yjQXYY? zRe?naG4(z{Pv@1mg8mwwo9T^O5(PTx7s!rGr(k09`(~nib@?$J*{GL1RLhh^%&L|; zHYE)-Su3>0(ZM8(EUHTuAEZNlsT4l*G=LP(-pyRV5yiQi74gY0$pkiyk?YB{{{9d!bm)i>Ul0wHW$rtQD$B5;NQPJ z0iFU^RNt!^a7zCs$od*E8raar592kcQczHILgva;udGL@b^&VPh9|LD>cb}|C!MQ) zpiMO@lLnUDcIHOAMUKj?+eAz1e3&cm;t%qcKR_%$KApUHJ{~n-w)wr`S^eP`6AC zF16BKUmz|oWavZsH8Snx)zrdUQU!U^$(97UIy=2n#b*@#t!2kV88bVh;rJR*vbO+5 z(V^HU=R%kHs;OT>lT4%HMCF#uiL)*Cc}L>s4+C`}zxu4~c6eh7hKeIwclXDTcnoLi z3H<&>L1A8(X7^QXvYyOM?0zEjFq@Bz(>_c%Nqz;W1+{iRS;|v?Tl)zOD|0M-VO)B` zb~zrF)Xa4&7)-}*mwYim9MDW!=z58J> zdq>sw$McBE$_M1>0iQ6ItRgs+7^H10v%C;C}&gY;!|6AjB zD@gCnPshS(zgy0v^;ul3$b+qhvzc+uSB<_bE`T3i*F|f@DHSLn`{41Etiwae!Qr;y zYYUv!7));i`vQ&lphQh5`0QX_SIAOo<25i;aXHfK4FEUl6pU0F=UsM zi%c7vzN4_fO=ir#|7G0Q?CDlYy2MS0?F+CjwjT&oBzswlQ6W9LEA~^Xmr=(X{S-oc@kJyQ zw1fL_U@HdZ9aWPL=K|q3Sx@Kf2z*ye=YTmE zG+~$OJJ2Pg0f=HaRw%iQl4ddlv8;wUKYRTX<{ca^Gl2Ps5%LT5vBk@?hL6c<_eXnX zcJ6n1O(ziU0wWxI=oLxh({ng2LSNSgj^Nm3Gh&;ZC2_Y9byl-~wFmQpZ8iDl`)t#&NhoF#<0uN6` z_JS==BpIp+2d45>&m^Y3UyI_g&|`@~3}ym``RlZCcb4C;J*$12OURqxTXmg|H0JRu zBoG!*37qLwBnM< zO=TBvY1IMx2VJ(AT@Dzjim<*HM`bvVLuY3FLV8k04P<&R4#A!&?f3;RU0G5R9!U6t zZjJ`Qg^-xFTdskY4PRD()&gfIw)+2q~WRLQJm)`sfHb1h9L zv>b9D?C|ztZ)1A69 z4(!=P^pHNM>#<>e>qnAyz5hxTO>)WO4NODa`td~Jo^=FI$?v24fkO>f%# zle)2g0T2SBMh_uQ&{^g=A#tnAA5;j1Y=$W*wD$QN=#xQi*WV` zIKMU{X723RW?7DF-DZnewK`MYA!)DC#_l; zvszY=Rm6-(XH%ngQewRZl;&T%czFlj7BuC+(w?^e`u!Gu zCyFiX^k=-?_TX2WXW)0>4hGXC}eK=i)4Rr2ktzI{q80Vg0}AAqcA;ID!T>{lt7GD#Js68$k@= zzZoDl4u+&uLl57HO(CvM8o*0f0qJIX$0lF;KzFwFB|{~maXP~em9^Vi=Y9P;(L{Te z9{z8>EUg?-MU)Ig{b#)PhUwS-x``kjNjUkqgy0^LF)V~ur9I<9fHa_O!}&fk2r(q% zGeRT>DB&XsY6&t{Tyk=9CoqNHaWWO}16vHY$qGiGB4)Gr3W~QhxP`zHh>d;a3BMTw zBKd-9qB34SNdaUVZ6LR)v=_2<1X*E1&HB7xZ3(z`O4K9gAJgJBj+g~C2(CAX2xo;% z+YnOSfa8Js{B*AwCObSJA|d?V7;>Hez7CdxISIM>O#4AD(V3yB;OwDTU$+eBS9l4oWe!I5-RAY`%4!J_mRWe+EqkYtNVS{d>~g{oaD{yS%8Pl1jo8%w zP8@kh+r~5KP&~d~ae&}pPg7?iqn*h&uTxaS5|d_C7HYx&zC75UNW$;_ugo)Qwg@hf zq$-!|iu6fGUNwXP&JR9T10U{(`*K}pR3X1>lIecIiBfm3F|2%3;&sX2=nHRK>QrO>T49aThnz* z;G;ins&5Cnj}MA+OqAmUM{#k}mya~B7e!|?p4~Ufq@)LBWqFUd zqBj%M+(!n$YQpc?*x!2^y`B8BRC11Yl|F#z`XmNLbeQOz=>bCV6vEojN1$mj&YUED&W;9rdUM6lkDbWHs+KPQ(&Yi7^0w!?TXT_7xH4bY%GQ701lVux|vX8%yg zex9xOXG<^yubeTj>V`*Tz^ObRZ~1ckHz6&o#nFQQDq)nd-&-$9>L=H0{osjvNfPs& zef|+?g`lURMW(eC>73lOL1GOR2VQEUv^rnJ#3(0Ao(g+uTyo(3m3>5KNe@n|1lYWa zw_!Np7lKK*(z&R~BiDLRBWwU;l=6}b)r6jPe^D(f)z}>{-sC+VUefNTR~j`bJt`%& z{a0PkY9$}FruL;>R;6#WBbV8)u1N>hiv0h@gdbH05jRFDFM7yY=d-Ie3Ft0HZTM1p z?e)vHu#WbMdKfDG5NwJee#sFKerN!9(0xC|86f!30l}le#nxCKf}LD6!`2D!p88Pd zKbz+!Iz`mU_O2r;t!}ioFWVLbi7WI0u#lILfxc4=HK@WPqVF;ifbkx)?~mB*+SZokYP8+)ITM76yKzCNTDi8SUvg8`chkMhGeC z_WbWW>U74db7Q-2b8D0Dn!6_@R+W8@9H)R-Us9fD=AWwhhYx=^(m9-fW=U^<>IJ1C z@OC3s0?}4F_&u}KK(hZV-q}_HHMJ_Xvj}bBrlw78;j=v2O|d0o{$!7_;hv*xiHKnh zm1C376vg*PqVe+7*GY6+VUPv-ctq8vI%01Mu3&Ccz|(G8@R21@^$(Uuau^U77oAZQ z%_N#WK3s__zWT?lOW4@i6?&aB1hHhz4VKA0_unO|F(K;B0>BJr4O7VUr8QBn#A z!-9tn2OTDa7C0nCed|zKvmbsQIC81U73C=rl*O;X){o1cP5hGL0WNVYOPz~LCdFyL z5Dj}8Lb7)b9B1YX1+*``Ci#TE-P5^0y(;`eU?5HoGiqUbI~K_FGXB#z{HbkSO`dE; zR}807(-u5!#nWM6pZn>SZ^pXyYxV)uk#)6w?$=e@0lxbxa>caIU))QX;(KlXoLdK8 zb&Zxd{yMJ7x$UnJqt)i#4!jzvGSUIE*rkbua8&V}TazkCmOn>O!9aiS$^@}zb zyNJE`cA?EQ@h(Z@Et(lqdGc{7<4#>J#yy7YG@Kuh+n!n8Inx6}NB6TkUn99Bj9KSi zBTKn^dqtE52WAYQ@EP!6^k>|rp*w!&{I$+E!Kz>bAUZC}I8&;25^cC+e{8B0FM7+_ z?U@!9Q|%GC7@z0=B3-81qePRo?hr|3ddj{ULIlT)$^cp*t`-D)Hn-_4IyX@$&HDxO zwts|I2K+rrUuPL|2)uSmDeCNt3V?jYR61AqQR*2bFSYpYPpO}M)5)+RPO@iljcxho`{czxNrA^&yaN0~F3;})QK25v%cI!5 zEF-jA-&bb@aEzDNC8}~fnwcMy^z;j+zjGFz?rfu5e((1B@~c&1xt!?s_*Xy!P6E{t zaD(&cn-H~0z{i)5xv86n);+@u{NUY@<*X#1#ZT5;()vVMbrnq{dD6Z}S7y?pcKY~; zVtU$NC~~_1n?@nFc0fPlFi~)KZ#UrS(@r?IsQs&-T}1Bb-h{h7ujE;r&EaKrgb_L4 zjCfv?ntx<0i>_eC&&hW}A?Ke|-je9{8=KCvG;RN1y~jkVsS3Hq!%@HVA;{Z=aUYMs zwbt8BAThuK_JdF>Y0v}yvFM)LLuW3=!-+BsbAWmRH^0!m3-g`nH4$V}j@N zY<&F-!4HYPQH5(-9-cc{@8MzZMy18X>WBX{H`^WUan{YDn8iZ5W8-Y+LL&hX;=wIl z3d@eC$Vk*fUHU@p1e&}cfkz9j$V9bnM7gP$WI>dI4l)yr#2FVb=H26l!@qhvgtf(W zs!YEku3)7vg(Q0)U(c4%e6TPusu6Ni8Q?yI|T4y`vX{i=J`_q;zb~PS3d(d$eCwg7g z(;P$DQI|L}GO7FFNYr`2$JX>K&PBlCHp*dBk84zFTQ(NO-_gsusVY^=0cmW}k7u1% zSk??<0xM?*z{zZ;OZg4Vy)BIsdT-+HxSVu(=K7sc;@>Bh?t@Je zXt3_LdspPm!)}0n`sY)QfA50SQTot{Go;GluVWEyX0rp-lFNbt=o7Mjgv6OxWtn{X zK#0B9nhS=~JU!TKMWwFWE$gq*+w&$aL^dV9z@sWaFxUej8IOVG;>%hbd}Q9FBXjhFsK8R!}psC>*zl0Ko!(+8_}54C51_EelElFFBMEun;R9aheTHa zFZb^u)ER?A0H6g3ecthR5fIk&Ihp{r1wfXmy>5u~A9X_>SR+TVT~Z{(`<;FXh1A+V zY?1^>|6vN=w}o|s7X~%!=#TT4()lA!3M+2Aj0YNa`VhnC(p!}aSR*+@cp1Y8zkGnu zm>TZ0C3sZxkz?h*>&-~SSj#K$J?~~)4?HnuBDqs>9(GCZ?lGk#Q-Vc42AKUF8_9p> z1Z$FED@3(w`BHfWE`vvihny55jB20J;f`WO)cDu%R}_qlEpbFJ48k&URH#C2Nx3tG z8&J-@irgDU#^-wNVIW)}j*a28l6+{xu5` zR+vQw&G!{*_HN3OC-r)beMMy>99Kui0&f*WlVK{tk)PKCf&=EwnW=yE4morM*c{Ph zplfNlRMsRruCel&Z#=)4zy0e`m)=LPaOmV@A5@A2yS9d0>v86G@v7t%%r{_D1%w6c z@&s07!Q4x!5sYNsS&ChBJLmE?txm$9dS0{NBqmp}t%|uc*CnO#G1+1xeI8}OQ>-Py z3^8+<*2j1Q>X_}T;2UpwD)XC4UJa(Cjl)K`EUxoHz@LqC#Sl**I|&@busG6~AfIY4 zs2G9U@tkbwLwH~cY$p_U3-5RyViT9$)(!{UQ#Y3uJ?(a6zqz3(bCLVzz3E!t{EBF; zB1s1qICT13Av@Jks6O}cDSq~VE!#Rtpi6{9+j_w&%I)Q5@rtYk6ddNt!lLAUU;4rp z?+Lc&P|)Ld+Jti2P#iuOumSr1Qu$w?ketbd1vmI`LqUe58M%uG_m}x%axD&-F91`E z)@1h!Tp@2qd!xBs?6>i|3WwE5t!-7o6=urJ?@dGzquKNA_qpp&L`N&vF_jk-ub2dA zaWmoL1MdxJUVIlg+fHAqZJz;#a${7bN1ty;~%HueL#p6WSQ{$ zp&;Y(($6^?KASAANGyu2fc}8zZK|t#D5S!PH)%C>R*&EXJt&@e2b%`>5tY|`MVQ5A zn5!=k1)2}7qwW;+y9f2KBf(*9N%L5ZFQ|~_Qz{Lo;h0^8x^Ya+Nf3u-pU`5~JFOFv zW*%(k2b=MkBc8vST~KH57aS56HH-<~20%0|6<2?Z_`nU*4kPaw%u5Go1XKVRXc2Au zt+Pqpgs2QivP%TpQf>(|tea%Lh8#f0*744h>1hmfx|4eU#mp9$vivTU;)zf;bl<1Q zSHeGMhAU+}zzYBCzO^$=KbfH~HnB3_zi5CvC=`D?NQ%I~C1%d?4y8?s&%D=t`1E5j zz8EcH0`?;TuVf18yC{r8TEyI6Eu;bxGbp%nwKU;(@y`h=nN+s~UbUqSLDr+#HYpE< zeu*krJ8(a6Q?6;Kc2I?7OH7w5ZT;l=-1PqTkAa_bBpHzAKcCG{{f>?gcQW zFn?ftp*+xoc%p2SE5;(`IK;y|3!xC6<9#b{w_=Pc>jm1>-WB4ZzUUY7cZIw`v)a1? zO~_B}T`dH;W(?|qcL5quwy3k1f0W_rXTQpS2cXrGkA@8Vyam{N37>XzY#xPw8O)!E zCz+wfTqdnC5SHW%l!g5j@_}%Me`fmyT-viTny`LD>qcn7U@y_yY%Zvbk|WifRgm+? zCBgESxDZw!McJXCb=8nw0z#IoF4;3)jAo3Ox73j9x1|E+X9&wNZ!6b<<$|d9YSN6s z+N|8iEH_qzW(@j=(2T(vzntKjF=2&fOi3WE_bZOP$XF$`<^c9qDa{zR*Dq_vl(8Cs zjW%vVVSRzK=k5(v)U~OG>RaH55e_HW59~(`o7^lGBiX8K6tp(cpZ9js-(R$nr^3WH z{P4X1hvHrBX0}K!{~}$+`xhRMgM8l18>BcG2mEewJN4ubr#o|tMxt5M_&jd%Ilbf$ zwI`oS@CUrAX(G`Gd+sK`%TM0WhU8N)QQ4t7d9a3)`Qfq5+phowx|$jbC7RggfsHpf z7=yFwY@xj&bw~#j9pBaBAta))v~r;#gF}3w0HYk*3lPLWz#`xaMCs_2km?eQcwm+z z4H(-3Xp^@t2Irmk%Yh9PnE6O^`|Yo3NgP#c4JVMX_;TXmU1SB|!2|>|ffqY=b2d#i?Pwl&x5Bw?=$0uc1=I6pwOG#aV1H8sCY&xTn)mS&ew z9%Em?8;Eh|{eau;V0j>)R1iWKc>qHg0qtBYa4=UpoP!~Y=V}ZD9HjA^8bcclX8a~^ zR{(MGT*)8@L>i^A0LYdfzGur12W*SivB7239PAb*TE5tQRj84w5KP>miX za?zKoZSfpIiCk@42+$_k>WleQ8I;IJLxyXyG@AG`T)3&JHc&@v1^X^&m*z2CAcRwX zxtX(k0O3k|i-|hgD)<=@^ES#tsH-vX^WxerGyiR&%RNhuoK-7+J}(x_U*bYoeH3K} zXqC~c__}f^0U;ublGkU+GR_L@lSFtwL0)Hh8?01#KVwz3MM;ZCW+JRG@*-oE(7K9{ zx$7*Wj0FIJOj`>(oS3v!Y1Pq&byixpv5MAitE0}1HPqH!Ma`Wys%o@QE!&*O;S^gJ zCW}o=a7(eavx3&GF;jP!g&ok!U9gPhMepTzC=p2Apcn8sCdd>|`Rb9QulGHQ`zMp% zQt-Lw$QYYVeoM#5$R&z-Mv~uB@Ozx33r+FEF+8V28)b4jOj9#bfNvB0g|-2FohSib zh6Y~ZO$Hj9#DP6dE!G6xcfgtvK6tp2c5g6JENT7>PTFt2&ZHU_q28+D}9rarZjtia5%){vsaP<`@~tIsESD!*D#q4nHo(~Bc~`4N}0M6 z2)V~ePeImY($fs}vA!A1?6)D;IO$^UjQAr1Cn@TiPJT-v=$;}?NHPtz7~nl3Ksb>P z5D(_8E?&HtW=ba%7Fu-a?*MVW@r`fr_z<+@gTMKkzv1OTFtHF255g4)Rp5sqAAk;| zfe!_kL@PCfAV%(^t+hE$_uK)qdqk5nc6#Z}lQb|o$r*dffP)7Zdl1H;e$ZZl`7ro* zfEF7}o8bl_0&a?lfcUt+T=*jV@Bk>M7(}8m8l15607v~6v!B(; zNiKJo&Rz1cx`k+n%}1v%z`1seGxjh?4YBrsZzf^c5rPSpY1tN>ilv+q*D`4 zWJ5k><%&~C9mKOj@)LC_G{1%VkXo8tLJ76_YCyRVuH+I%;1Udi_@1v&G*_H#H>Z(z zHe_p~LV&R^>MVpY^17-8HRNlu4CgjzwIV3jR@OrNUuevXP6R2y=G#Jm@*tFf;00&I z&NeCFGXy|<&&!ctUszJ)Bw_jKTLmqm!0MwYHx%^Z>#C?ii3nM;`iP8|By&|@9+rnP z%2*0q`~7Tr$8ApJMan9oca@>c2`{54U~`WfP}p>1gAG$i5U{N6wo-eCg_>H-ESRXK zMo*Pi4K>#5Xlf(m`#(yDZn&QQ?koR?KJ)2M^6@ z&Xk*)@Y1~xe~PF1t3UsrybPqf@9ul((T{(gygnaK)81mBjcYA*)BYOTz1_wStzLGp z9v#PFIL;Z5Y5)%q&a45bPj1_6%?KOTn#t~rap4ZobH&e{*sH}w5M~q$707^IC7_J} z736%h7X*-I>(;IO7Hz%&)BKJ*?kK1nfp93n-_gwn57M9g_y5M<55fm-yOlq`(w}aY z3V7tBpQl@HI?UfE`U3vmcGHbK{#$P!OU6p!v!DMG-FEAp^c$c143GcOM;@lTZaYj5 zJ@RRK;lU!Qzh8mI|kpsj{Aw6;d_BeP*$lxxYH?-`<(-a5s`yoWRSas>zxz}SOu3j!4g zToB;ETsR6xfba&6tx-S31+x%P=2r}cryO))aEfci==E``t8q|WZIITqS8&rgZf}In zU-nXOzmNMn0Hd$AT4I`_e}Dmrxou=TloG@w0TZZ&0Bwrk54h)7Q`6ZmIbgr2^gAd7GPp#C`7>9L3ullIE(sMX zkjWp#w^_-MlZ54`4<)XGR*_-#QIs1h^sbsJ2tpP~Oo_5l$C6~aATWQ*Lm6ch3S}Q! z?fr;RnEX^IkWPeEfV@aqMf9#xl!Y;66b)?hVG9@z8C#oi^U1(A^jd1DGjMfvuCm^0 z;*PJu7=cMLXu~Yz^uLTUmIGkoi(BkUCasYMxrr{fC(3UKI-Jr$9Snc?tN?>jFlxO% z$-jX~GtB?00XNLS+=clr!0VMX0FY+awo2{;!5`F;)oP?YJ1VKY*~ravK`1ik$j&5d zsPCY|H-3b+?EDA?wD+ch<{k=!C1>S*1Cmz8#&tK)-s>NwnCbrXxO6K8qxC$F94K1| zapds$;xs-L;aWN4Q(=B<9oji^fSLWo6Hn0DvuE?xUO+r(JpBCUKQAZ^%%Q#f^2_|4 zECw)_g?9vjkQ{na*QP-KLHu9&m0w9dkzinbM-4Em1v6IA{1HIk$<}XRvI})W-;|rz z(viAHc=SzZD&VhNFqJL7=>Lc-`X!L9zWL(WXP>1TZ@iI@54k2vjWNzm;VB`6BoM6h z^zl23_jhB#HqG>ydO27LtftPvk+1+0byRmtMZ z-MJwiOs8S23xIZcd_bN?yelxw1dJ>V>OGGF_oLwTWfQ~*I9(C8_6BLkHXk)LM%cU& zq_!b_t*7n|Gc|GF1}VU_qt^>Z-{}lP>^Dp@-%twyexzWs2O$!1b3YW> zf?xs*%@{CI7klti3Ohu8YQhfjTP{X=HcggX$i-yOCa6(MlaFvG7d^_~#CNqc+47M; zFGNt2jkzxWuKcYS;fb84Y-OqCm+d$C_gudzA%0V~Q7+^YSFKFZS8~yVK8<*oM=+0y zv8FZ-ML<0CwS0sz#R!XXjf-4$$p@&Xs52nyjCy6OcQ#=R=FBy0j>KOjgg^!wD!IZM zT%?;fTZVUC7RamwRza&Mu=*&<4bZEgc~wlz;Fd48cbs_ z^yTmc6LiPnI=bnG8g7bDnE3)@7dPL*$d)sXfp7e9hMs*{-OLl1>0rV`Xds6#7$=7} zPQE~#{QfY_+N1LaXR}GmZ+=TqXL7c;Zlb+=?xD{0cT>W2%Y29#57VW|hp2xx!W~* zy>-+LT0dag%gu4Ub;3{HKxTYsD0Fpo@%}0AYZv>1#xucp8OI0>Hqpm`n^B=&-B)N$LR;({s+4I&ck%? zt*xZhr0V%U|M<7*)mL8N@&D@o{vG}LZ~q>T|GjVj6Mg8CjI6A z_%C!Li*J(oD?6}n3qAkrWAwFu{WqTP|M>I&O+Wg{&*+Cg_%40(Yky6glKGiO2qtwyd*IV~yhSLFTJg1$dqd31Xn-=5k96 zMw2l?o$VpI_s$rbyW*_Rdg#cp^YqHQXJ}}An&p!@PL%=_@m(#*e^-7MP$ zr?{1mP>gmAnA#A+AgHw?o~vmHf^m!Al)@Ms@I-zHa)|s8lm}PjgXe0(9g#*&qhO)@ z)R^O-T`=2~5WguQnAK{(WqS^Y-_+U`&$HE6Ee+}@@>3!ged4!V`DLRIv?w9+Q_`MK zeh5m4=gQyEH?yV5l^^e?7SA%FjwYEin zRih7MThOIMw)*A^kyi9O%qhw_M;U^_OpWDSf|x>qxwb5jkz-}(TLrD6!0MxDVSr{C z-HNX(j}j8J>grZnV2x9TGOm4G?eBeYbc;c~O6r_9DXWO)s|3ZLSj)%@i{BbAEx==* zoQb4`sf>{FXOSzwetS0Ly4_z!87l$7{09>ox8UV?=~#eXKOLot3O#M#Y~z9v0E}zI z2P0c(#t4{fI%;Z5IUttCG%#wg;sQ z(IlwR6jQAQ+7<8Q`s=Sx^BDsmjhxXghwvHm_SJw)Xlr5dtCLSsXl(AJrmpSDZz(i3w^Duk7K*E+$p`QwRfr%)0D_20 zo0ghbGu?ZKh;hbmmiXa%F@@JUS z#Z7jlnX!BT#xNY(BPf}6kd-&3~yfW_vg{7s}$GQ)G_ z2PV15PYIDmDJ;q-KQ)K!c(zb}N)SAL*Xj$-nYr%~o7 zfcJ!WNGpUKV$3Q3dcEHHzYyBg*Jo<>ssWc`)aU~QeagOxxZ<}$`sPAF8>61`Is@|h zi8{-}_(Zx-vTTAFm~~Y8kjWRzFOXRU$hlR_e;-*&tW2r70E$*0RSQEw^Qxpo~MaG*yCmjWl3(uU3VSVzK{c&C1)>!p^)I_`>HFU4HKuC*)aFtVm3?8R?~q(q=H5U&(ZTw ze1(T|M}I;`U;94){4*A=TsoF!D(1}57t-Rs{@mC2=NF#(TN)WS$LhQAf&(p>DRwB= z>xk-VaGP2Z(u_}rC=yN3XMgp>^wQ6tp`X39)ZWt9u)V~7u+A1wsLX=-ZX06{ z8;tCkN_@aME{GW(&7Tn&Ve>pLlOT+aPw?@k z7T~K00ZdW3IUxvR)EK;Flu<^0fItIt48~DSO%4BxIRydbP`}Gr|Qkym+Q~ z8A}2A`%u2Cs}+l{2hxeKN{}}>tBmfFVfpHm$?+)TeG99_#tsBF(y?9vTln!v3pAj8=5$4AW)2SGsVG5= z97fjkO%0N^48r;~&;s#N|Hvf0d!~n8J9?hpJKIZVdxofQc!H+poaFSdc_aN> zx*+(2VRE>AG&$#{0rsvg4^7dTzA-x8J4(GH)7&RaEFP!L>xm0s4j)W#!4QDk)uZF- zf)WT~O65yVDTslYp=?0_Lgm(G6A$K!Oa`btfDsHPskpfgK@1qe${Y1%lu<_hkZYgd zLIg~1;;+zY+pj0~%js)Yf%6|}27 zT6qYfN<>(Rv%A_LXO_!D8A}7Twie-9KxyhE2IMMhle|e61nd9kUTlanRr~mDH^cR2eBK_X)ev3YM|8LX&?VIW5 z?G-%iSy#B~ei>yfCvc+@PR5ltD|I>zI}~ea#vbL2Luh>n+bca?~|s3O^<%9W>|3ZiWH^DF}~Rnv7(3#%W?EPHvx;+FMN2P-o<~`b`zJS+pH& zT(dz9*2+57GzO!Ytx%a74*(eZIzy(J6lgKTs5qu5%yt2|p_&iiI|z&*xyi9yK>kRR zFOVy5=I7&QcWDc|4T+_tN0e#63-`NN|>3vNP6!- zQj>wjQG{mWH>g(klVr>k=4J*+8oNDMRx6QF$t0VlN2 zwrsTU=Rh%n7$s_w+A@zm80SKgwOt9Sw8glF%#6cLBa?GwLSqI33XC_5JN$+*h;a*H#-T%plBusQV4nd& z4C;&d1sb-fD}pf7hWaXl+dGrDAf^!DQcyO54EA>dhzCu=rNQztKyo50DJw%GN?k>* zlf>$zDnF>uzG|yeV!}jrCC>J0gq)$S7RtzkT01GjwTNrIe)-P_c}Khok)vKqSmm-X zri={KHMUSi&BDyN58VG@GMFV(Kzf6j>Y6su_8WeS4j-)L0XOH%C}Xuk_{@N&%Z?p8 zl20X^JnN=cj?B`fUN6B+p8%KxaNG`u|4Ih7wL(Lc3J2c;q8ylzk^|af7L$hG$OiKe zrgl2pE2yU0z`vU-vT4O+BH;JZ-0WoXTM9~lB#39W*vLLRk$fT{64#JFmVHTpRUv5V z05ETEGJrV};S2#hhXCoPKm7)Gvi`>FuVsWQ1H+^>XWDi@a^z`la!f7F*>e|3XUk-C z9(m(O$uzHLgj1)^kk(o_a}+mm@s40uUJjjB&1e?U&Ye5y#EBCb{Xoy+tNFJPeMfv2 zkhBOh<8R))nfuN`-;tN0Wjg}3_qjZ(tDG!asz_SU{GRk&CW&mJaE(g8n%X}1cO%w12iz~PkxiIkRT=+Bd%RD zHW8w+$q>N@Tqq=!18td()&%$A0&N)xXYdyS8a#s_1%jH6R>VsMm>Gk>1rGSTJA-t~ z!8m>VkpzA4zBp~$VP1u#KbL8w$}pW4ES8( zYKK~#vW52x-Z%Bmd+g^O@hU`)x-CPsbzl7A7r&hRTt-|x?^W-YG8=WY|N6sp-R^xn&CXrBDa;PeEiKK|+*m`~wrn7ac98YsY4Rq|!%_C0 zHm~1JH{EhOPjllupq=Y3Qm)`p)e~`>eDXgG?{{@XwOFVG?ltzvd_6-R&QLhn-1N43su$B@^^%`>*(yDrur({vS~e48wY4=*3N}hz}k*o zJYJ0Dd&BsF%z9e4wv$?G9OQCLl0PctUt{Z_z55Qbe$v6?*VNYX{)6}%H*`~5eUzND{p5>C z@#||kY1htu)Yh?v=ewr6n`~feSxvNM<2veW(UQ;EORk_4-%?RWdv+dR{eJ_`chlz0 zWV2OLYfA%dT-Qk*%_a)CE|D`CKdleAp%Fk_lS?qsvA%&hW7EgkSTT~r6{Fgk6ob8g zIK=u+jJ08e`o}`N9h)1BbnrSW_Xh+(D{RgY<7q{hb3~|jB*glwfeRf!M zLpWQP2RloDWhBVk9nAQxYb&VAqUG~twlw`LzMr)t=t2DYDyg3R!$H;f11!ELEYS?y zdP6m>YnN^fds#b-PJ}bk42}j_+w&;A&5TL^Q^~H(fidLu#aO?FhDwZX*i%Jwc9z}) zr`B3-I`qtW_$p!ZT8*@hE+mM7FQ8y@Snu&1h_dpBN7FU*)C4g?P?Qc? zL*)T3#5S{e+oq%Lbq{mqt&*uJ572H)M4fCNK1!2w(p(vdIH{>|H)oj21Au)6)?;z2 z{bL{dSl-%nWt34yZb0CIF@`e*gcBlQykU>8aE!kifw>1l zU6^14twPfd0d-W)KS$pEHnlZtmqZXFfVG0J=T<#ybLkn{9_K{tjR36qn9~tw=}_3b zzof`Y%F5BWidsj3)k|4^P@#WSSE;nboxhY|XMlRP7tFL)kPEn|f_VZEe^(mVpJ8ql z{JWKXTU%yio8W&^5sC0xx27cP(|Udo&rNG|>3{{%g6FR|K)Bm!5m_etP|skNO7u zY?B;j6ON9yZm`bZEMF}MM~H?-rQ5cj`{ggu&b`v%=Ji)!q3?h9+gx=XlQwQqx3;!& zlR02uG&VNU=YHe2*t0ese{^JoW|F=ZT6BNP{|=0V={wKQ@z1C?obzTwFhDdht|4TB z&RLFh+PF9PV+S@ns=YYdL&eP}( zI$G1s4i2^i^<9aR*Dbw++L|g>52*~8M2LiDX>!KFzjwBGlG!4a!JUOVMko}CQ!S&b zF-ey^4JPx(7C$xCn^>D^X>L|xKy|TvDw6r&7Ou;2gJmNqljms6Au$JAn>*?EzVH`htzXN(3pnQ{SsE9eIdz8WDlgDaUwnbC zOi2QbiV6$;@gM#JRW@zr-vwNb8PZ1VbpGslvQ$jbE3bZ=E>B2lz!a7R+w3Ql-Jn+S11Qi;ayrFV~U@M`En4gOt$5DPl=K z(AQMyS)Z0RvBTpb8W{`ngZjp9Gc`4uxIkrKI6!VsgpcvYIz8R6-avOAmilitJbA>+ z@(c4rJ+|$8)@bRzJ2JIq1aQ0mUw-W10uX^6ts45^y$#84nE)gFt52tdDB1Am|KB&+ zd+km$mFD+(Ddroeo=ZJs(?3sN`@wtUOKKSX@gM#p)wOO;bM}sTDC8Vu<8pxXiTCKS zCx1e-0jb>I`P`q-+Kv0kP?2uV%)!Ro%;W?`1FzB(KYorTJW~A6fBL`BmTiZ~XiaYq zCmYvu(^KSeoS+w8dW;6=(9?+?y64}~9k+cf!&i@YZkXJTS(+X@La)E^1G+RJ_2run z+(VB%^x1TuJ1i@YeUyS;2aOE8LC21MhfWPieNyTJQrirUusM&-6WpPEt5p9fw!T4o zOlZ?U*syJr#GDSWdHM1cNk|U}K@9qMjZJFL$>|82L(?@T1n|D0B?1jG#J|+%XMIkh zOAX5S7$X;Yd=$m40~H`X>IQnOtWE|t^m+%_JeJh3Py&KI;XVq&kUG{jNP{)&LNDr> z{80vxrpl(L=0?Q9A5wz6B49j@vA|z0fJv0Z>xooUIymmzJb&`?P|vXQ_KC_3=E|- zcf@mGi1izoT@%P(5Cf>!Q4M&P5S|0=4F>v!k3Y>nFNE>oqttuxf6>XFR6pFd`QNj{ zbNZNyMx*>f3f3X`T6*xo2a~^)kqgUt$SvdA0Q@mwuL*x<7<1@Df_Ve2QMq<$Ho(`+ zN;94E0nDxq3=D8hKJ24Gw{pz%4Zg?D2(M?%`K1)Z$kE+tVf*q_SZ`SQ0)Oyyj1KJFNOjePG0EZc3VaYXtdwvD zyrbdaVQOk>TJd!N8rXGpb$P8@O9{|{HMF52``LLp06K6P0T;ek5}*V7iskk@7mxeN z>3=c#Z5fgGR{UDuv*%YooXvZ#_z2c3ni~zYhV6?UzHKcXy7N297^Oj3GiC`euNgCW zb!x@{4!fOP4m-b{1``~;y}jIFCQRVmeDlpTJ3C8<4&TBBGr(drV*ow-skV;&HHFD& z4pNoXLw6l;(L;Cm>EJFG-FSVBE)LI;xiUhH)@k~+PsG`V!AXbqcu1=ck~8F^+A1I2 zxWi75-V@}%A1ah5*gF+!WCTslL+12BMelzDY{6aZQM>Ot~0cAy$V3wYKP~ zzCJ;f)lt&u1Jq!dqF?<;gbwX?(oKw3n>9>R>|klL`e^@VJN?3aj8<00O?zY1H|8J% z`@POQO`rNuhz{>{@%q)*Mrh3CAqy)5dz$t(1GTipskS~!ajl;^YG&v&AB)ib>+C$f zJK!aMB0#m3KDzHFC*6D4!++bhAwsf9|+KX*1oqN2vP5-ophEk)!Xd!@%#OB>pqFrmIgl!+1*rC z9j5EL9rTHZf;`PF``Gg-Cy|M@zXi7(i8|VK)ZUTc<;3Go`oKOrJ#ZVNmBqh)M~E(u zO0+hZC+YJaXZ2&x4>4Lbj3#@?PgOSdzPC-&BX_a3WWOEU9idCZb~3R#bam?Z22f2i z=GI$3Mw_>KvqN4xjl$3M$aVX?7yV4;cO zUe>=Nbfy11Ieb!@?b~joL$`dKf0m=dY$c7MlEwym$Y}7f&A=I&^Ga#JAkB5#T@IYp z<(e^j4}5^^vy<$Zo&T0iGsa*rQZy==T!I!&Hq97lKfoUh&fj=n(2#)eB@l=c{5gzH zglKvu%o*-Dv^O>w34DS&tClmMXC2XufSdDmwFbI05+RFO$F*s2W51?CLmIY`SH`a} zNxplanK5RMliihim-Vb1wKQ5*58RB0z+jfO>$F{+u@2PNwbH#0eu3p9-Fg==7+G6c z>uKo9WisjK=;Zk;^Fp1Ee*BB1)uju}aBCIu$3})oPcwAx;>CGQmq$PLpV>Rl+<==a z>uG9og5uFRy3})yyh)9V4?g<4Z2m}R0s|GcI&wIi6!s0#m4S2QOv)JVfAI6v+`2*f zB7@OVOd--QMOpL}bqj_$6f+ok0(j@C!0NxVYrc z;Ag)}f)}+ks)87Ry>hhYi9u-D z$bd~F1UtaYY=krGFy=6?VEkb|L>r;E;XURz-$;E^0Q(vNp#g*Xt7*o79=X%!T!NSy zQ-UhkPw653ne_g7^bBC0fL|-1ihbUG-7oUb0_V@4=L}CAM&&mpJ+5&!cfK*N83P1E zb8LRNF8NIYZZ+ZnxoOiTe#>!WWF)VE`C+9G;boL@H37GGYinz{2~7w-;XiHd+O?c% zlJD)}mDY^Gd;=eDYIA}-K+ho4ig#&xGDt?Y--@uw z7yC=>%a&F%Mj*Y;D-Kn1R+h$9)Y86Lhv6?Z})zx_mU6xBY1A%r~ zGbSDHcg+~(B?t5mp&7HBSa!{rEN7-noa4nQL$;LjTL zX36xP5^8aI@CS-dqgmV(Y&2F-O?@j5moJ_opU*r0UBH;sSg=;sCVy+=!DOzKzSpJV z%6)~@vG)f?>ey6_Cg-%0=1aYSk1;TJp%I|bB&fPd$DR5EU_PH4jndOc+^XU6*F5yq zA2~Qv8T;{8md<9?QqOcuHU2-dxKF>~rJuaxV@;*u@ddJ_`Pb)M^ut#@JPl+_Fk6%h zxP_W6=v9O$YVkzS88gil1ytgR5Qk=*q7S%T4%N5_(S$Zb5ENx|uv%P%U?@yl{r}J2 zdjLpsT<5`Wa^9TN<-L5kJK&HbkpYrm4j^e!6e-D)Wm~@``s7qs&2YlnMxo)^%nzhLrPOwbmE3oxBQX^tcYK2E0=QA$-EvFfbC%c^(Lk z4%Yq)-H-a459;&`$y#4{21ts0K@c$jCTfGDxte$C`_)9u^jw^q^@C});n67d4~E$| zDv=Q&z0fY+KeE6{6Ppd%iAnnCRFL3P2I&Q11Aq*LX*0mLAo*i~=Gvg_z#iI4&?36& zx_a8R%}qPEy6NWY8@R9z+Pe5wr9Z6Y0<<@k$VbEgbq)hP`0?hv;qDvjH2o!&f+I(c zkZvO5PxJ?dSYIt^`wC#bgWZ;+qoZX7?DE&4L&xO>SQgOg5Ap?U zcmpY;#)Y9LGGm*777^3YX6IU=0!?Rkt@k5fBlAk7V`5@LGYtqUnGTG5T4_L7$#g)YR{j37XV3B=Hc4F4D60!7 z`NoSFm3-s!=8tZsY#DH|n<<+dy+B9ad!7FDKmAXBJ|DjF#RuqH|MYjs>T1d{Q`Rn< zDeEu8Oc@uR4TmzqGp9LCJJ;K(tyN<0;oIS*Lu{dvG*Fu}MF;jtCVV#aSO~JI?>#X~ zt#u}P@V-Wx_ocWAB)AWG<^4JG)Y&+j2@H)u;3f&M8f;m4F8jT3&^*3Sy-O9$!ucZ+Uua#j|S=W_x<$cJL}jx?R4^dl<#mG zn~cy0eUVHzuw|o^C!uhPM#m$xzAjC>cVx{%9X=JHk@*CwYRO&T0#>VyEn@rVXOF&^F;fO~vp84m`Isgdhd6c4L3;Ap=Q3u> zfI@MwTe{voOV7XX_>#?(xjom?$27EWATT_A`Xu$AevjVv*+KZc|QoImfCT8=+UP$`QG5L(1EKzMYT1Hi5+eZ zvDQn!dg{@PnX($Ym2SNDURDuRB5eOz0o#%bJOo)_1#3-+$zZZbU2(&_!#EP2WD0aUZ z`G}Zu+MgB?lUD;q2At@FTqy)x$DF~yve9NW@x>|#7?=S=TY;7-v_D{Otk8U7d@@EI ztUuno!AZlTakAMhtdEBIzBnB^?Bj$g`g)iK0I-1uX43)La%u&wm2{v!sI@z>mWEakv|)fmBEi#w^eq?ir2`sD;=QNpIR2gMe^~+&yzVvUzT{`E$ zZo2VWHko(Ryw^zQ`v>`XlL2OAaBo&H4Yaj1aa){ZViWSTf$Z)^ayVVoWB+gLYPw`H zMoq*3=oi&FB`zy1y{%)PsJ zjx8?kME=CtAQ!*_Fku4}BV!tDN&3?LOvlX7L;l_q2$KhOlQa#mpMgW zy1TxhR^Tt6oym|fPE(3LaZ?Q!(&xidFVE7k;S_I20Gz-Nk41Q%DhU^few%-otTWQ&PkuZ zkxXUVmziBVGaOw+#sHf)euHXj7Ml$$2Ra!em4OZ&D~XGpj0pr6*t+A}@{xpM8Znp) z3m0kk-_S_)3iHrvGR8mCMn zW3sD%9V-L$M{9Jz4)_M?!kMSYH}w!*)%zrU>7L_s=QT%YQ|E_N=XjR}CST79?;L-G z-hbz>DK_^VN-q2Z*~0%rCSr&#jKt}}u=Y-LCD0G5i5LKDcbrlN0p&S3?uW@Ez+^V? zV|1;`I6}yUcPI%ZagQ

UYD3fOrR-+~Xa|l;o6I#K{Nca}Wd>fj`RgA@)oGJRiOm zpiQET187wp<#Uwx;}4FJ{t$Z}ehUHb=wyt)Lmejr#fxxB+^4=@dCuW9^R$Dkh$W=& zfL{o8905U~V6M>F4%1gwGPAhiegP0H2$4AQK21^C9ySE1^L|z~$?QDMtPsOR~?Z4Qizy2Z-Qp?h51C;L=5su z5HT=O7GrIsv%|*I1FaW)hmwdyJK^5}jZPNlx&w9GCsQJ6TnooJ?qzMJSM&~8f7*&ALss@>g&za+-PL|7b^o<>jwU2uz_GLAsLU5Z)QwB$|4-} zQebYJ4Cxr{-(5quUEe@AUt3SNTvyM(ZvuI$s5b&8V~mq9oQMIkT~p?K=2{*+{>)4A zFC9z8O71$;q2p4)Q!kXR5hH+c7;`v;V)NB^-+Y>D!XV)HxzmSvIQF6B_cI^-0TaD; z&_Qp#XP_e=8R*fc4RqqPd~sQ!=)l(k@+N2X(up^(v0PGMZKtk0Xne~>_jw}0h z1N;QT{A#JfZ1`>I=;$aIgs{9^fP|^5tK;#DrLC^6mO48-3WlWs5gHm6TU;mxe4i*2 z5JDh7@P4F2iwB9WO>W16B*iu9>pd6HCg1Uk7fS(w3Ixt5?TGe$@9m=hvE>D2k zdq$~!-RSZVF=aK~^4j^ui;M3&bj94$*EC$-RPTEa2?}KR? zS+hYSy_q#Oy9VKr5JPDgG0BjNQuPQEa~Zn6G>;3DlLydS%I^8o@gJ6r7Z4TQOW4D7xg8i9sD?rv0;R`0oAJ5h=Xe~T&dqYNx;`!ITT+>7eKa1m& zIA9>a{7$TF&N?Y2u(WZ@^@)aP>u1kJdywk7J!PC{6bSu zI*}lQ(ah=xCh@G!PUPnGa%;%oexZTYH@H|!s?M4uw`{6V;D!Sps+G&(m4gd3JQL^U z?*Og)f%`s|&C|zTny0A+seWu~GtuqWNhS~HS-pIl)g3i>yoZ6xz>whkd-xcXik^bsK;d4B8a#pPXjxkd-0K zlX+ZedgGn>Ogq`L!%dy6&0-9JFDI1M;p0+0Xkz{H_Ffm)uEF_%VSHbb6E`TcdRddC zG#I3^UoJCc+pnN2uKXN18+zn362iVIG9-iKHa|h{pX#UMtiC3aCT<$j$Hw}1S^l98 z_HJ@zd>lbD=Egl5yW+Fin}f4?G-IB4P9m}H`B;k1vH2YOAP~Xu?}I+?0?SYQ1@IR> zfY3&EZ+EkLW#Qj{|9$_8KK1cmAmw=vYpywr0%V{lh<{{tF+msjM0ma|8M!qV%&1?H}h)7 z968}&bHeOA7huzD`t*G()y50w-Ksz{NvoUAHJD2ZtnJik0UJJG9(6JDd`lHRaiw$V z@n;NqHDe&WhA>-g`l%2gXa_Oibh7zobF+L_8>dd4<{As7qEt;7A!x_FAY%{;;mDC= z@~`4hYoI{;1VIZhO^$nEs;i}?so>azZ#i>D(poGAwdM!%0BOjVm&!DEb#?IcA`1<< zkWXH)0T3p_2|EZik+%R$kD=Tkm_|OpXNVXuA#g&P#W;)nz`eqJ3{0Xq*+S9E(kUEG zDM80g@)31glszD6)TDV`!!^_g9BXOc z;F}i$Nq#Tt8TwU}xmNuWKz)E9TFS4*^(vAy(n6FyR}uUy3{NL{xec&>T*eWNiNolP!^i+Upnjaj*F9zP$Y4_JAq??phJ5hQ>&kgZ>D z9}DKaUm(HyCzLVBBE-AEzHfrnZRP#=M)bAl7XkD`7{^3jqWn5N)TUP1b1pV2c z{{?+`7&+)K{H9Ko6a?uODe4G6oTBGoQX@DjM!L@@xE|KX`Ew$ z&2==-7YTT0Y40r~AT4>q*tnUxS{qs4lAYH=pbY^u$nA1ARbW2k@ksp-`eC81kq>!{)})@i9nd;Lo!XUpO5>O0tg}@Aj71M#^%Tn zj&Xve6hQC@fLKxr2E*ap!4%~LLC@q&f|8?bkoJeEuBPxpQwR!S$_B!40VRP0Z5F(D zA!wkad>#v{9Fm7cMP0!Fj&wl#1jG`ulmYzPuPE;A>3P?lQ2SY2mk zi{=y?;Ml|$W@nZP)DKLa9ZvQPn}yOfPELqn_qiJQ#$YJ_Agv@~01yu&WBDfoY6vX? zfX6LCi)lHqZ8Mv!IhNkO;fn(0x1QxiAZ#Ern?UZ`>Z0xr8=LT?*ka$suZJQ=HW{*V zjSC3kApl05al4GvPz%z;Kqi(Q(3WX$wet2Nz<19tqsg*Lu+%=G94IwQ04$i`EI%LA zBmmlKsr3tWQu!|U`%(jKTuG)NJxc}J_fm-%w9%olDAzs^;rsww6lxGL(2!Ez*Egsg zpxuD?6-x)|C-O=wpuC`2QYsN7h;K~jqyPd7eLl+<_8b1ruu(w0>k{o2aR-LNtZl(x znT4Eo_->NYivAcrX8=5dJ%N*<0P+xR2__&x9Do=Bana5CB`0fJ8+r;aNVSohzU2ZI zNRyM3G%_;61poqXyesXDgEo(Y<%5IeA;wAcD**Zi^dsuAvswUIj!hwW59%ArK|Qvh z--4#A=)X{3(4KVY&~bSI8`(gLNFlEHT|5AoiJU2q1NYIWz#|i^z*YBux20Wf38Z6*EJY``SDx z>*h-Ym&W(%E5x;e#qzKf0d`)&BvE5sX+ou?0D_1d;U5FEK1zXzhegTQWQ3D2*zpSi zIdi-uPyoUyB_OCb27+XrnPVexlH9JWaIRcnV6V3%$()uZ zZer&_KHwXK*)UA@AiNg7A|Ol>!e%vUtZB019VwP}_6#F?kJg(YXvDLpX5w6USqJ|E z4C>v;5Nd`aX|nqlSU$}2d_dkU5+JdcIBW(^T0!_bI~gZ~FGLNj?g))9lnsD|A}6O5 zgbcnFf+;0%4LioowRTFk)Ut?HzUzLekc4qj?mvb<&uZpcG3BCEA_m_Bp>BJNEhj)w zE55Z*Ty?zV5d6c31SdCSLIykH%K_RdcG5@K{3;wt(9C>-Yt*40aP5~mnBsxvM4V>k zPBkS4HGh9Ih_DZv6W}asXRzTOqNt#ZXyOGp#bLX z^9pSS0PS8fQzrpsg8rirL^~;la)}uDo`J)85ceX0%uwe6G-V+8!gUDd5iquC1<_^; zr33e%4GY3q9WX8_>uxa!f*FJhc37f4piXtPnAtT+a|rz_NE0QX;eoWAJ|CpR$NV%n z5~Yt$1!-^?X1b*Ga-TD-{9UXKG&P#ow;6ezKzl;lLw8=8_J3ra1sl|(Qu zr3niD27Cy#CV>ngBa>2^So#o?L&)R< z@)m>_@*2K=pjoR!hmOk~Wpq3mw_@DrU}JM3A_nujmL?nb)i*X5r{~|Er8kdwc{p_J zO*($|ZTj%!dz55Dyv1W!6k?VX4Nmt{AaaEK;Un}>-vp2Q)2Alr_=O-joJn#zF!n4? zU}s?qFUx=mI`ZWLlC&sUtDnv_m{SU9X4V^A77WUwQX&Po2sO0KQun4o{?}}& zCh5bV(H;wou+S#T6gh}gV|1wjn3rWKweh zvZj)hZmW|nXaGW4m>vtTZo@M>%T|X*O1C%gNh^e3NFV9|1Xf5V&O=}>hz;R8K?$T4 z8a@yv;x`-j2)xv&qaOsiCn@=v2^nj54390rZXN3(;OdSVL

!e(o=YJs0n~!0I{1*qR#2 z#~R3&Vpu$?YJ-<2o7V{B^BIFWf$tsVRYU1BMhR>rfQD}=_{Kl^ zxAgIQ|A~Bb`2vCv9XeJD5LOkk%fHkB)B|Iwo_P%NG+A5g*$YZptHLv*(`(w6m-V}8sn3znk(y)8of_AIRqK03!LiXFUIf!V-COGKe%|Yg0vJPV*pMnu*DM0egTEZ7zn9_76csY za{*wNBmjhl4+Mk)(l=zu0T2)nh6dTU`&7gcfYghf&#w7@pVFB4SDq zl;b&=+?5NM1rvaP7sN;*Krk*56;WR1SojNJx*E_35ab2~>)3UVxcm2bcpC@sZD;y| z+z%1H0S?6R7x1$_;~cvNJI7l#I;c}77(vD~HJEu_SEAa4j6?=x?_CNR1K_#k5Hd?4 zW0d5&2mWg0_P~!mg?SLsUAM_66u=x@3+VGf z#)sIr?Q&W8c!qvhpju=MfH5VNvQdmptvlP~lL}zIzOq>9_mv3EWUYQ$*Jy4jusSK! zCSnY1u29W+VS#U3<${@-fhl=cqv52Y}qJH2C(B9#EKwd;M+wA7XhSONyKnrXC6%p z0SG1S4wEFLpN?gOacV6ZB@qK>$f&0N;I15u+qDg%*vn&Z0i~6lJ8$ z2Q{%PP%04v)03R&S^S6`z?QzUzNy<(HG%KJcL|`c41!Q#uSdE)Y<^G($ZL_GXjd?2 z2{MMa>B%VXWAQu2#y9M8137{I68WVx$5srb$N|t6OCe+OL5%MpPSkZ+NycE&{JGD4 zj=uZd@A6}iG23=qSlgRsN7kRJz=%^>742Bwm6@_2H`vucttg@AeC#&!93pD!PB^L5QYGg+&j)-{@2Dy&>8 zOCe&gwy6$E_^ykifbt@hv{EuGX~uwz!JMuT=7P`4zp9I5w3AZt7XBM)5dKB9kWPnb zKJ=P=R6bxfUTmsDe+kWZVV1wic~yptfd)n)GA5atqG;-vS?^?OJ~^Pn3w;E~z^lA_>0&3xLAwmWOix8Fz!92cCOExCR7^T1; z#0*Rg-F$65&(FgjEpXEpFayMQ`LnhS?U-XH1KeaFNIhJuaho!I0>~H$NwHAZ0@{OG zh*~NkBb7__$ru2AM=6BNa*;8W5-|WLWaacLNen<;r%NGX)OAmpCZ%Q-Aihf(Cm$J; zuiceH#E8DETy(R3Qt7h=#3eQmRu81L=%$07Panf*>Dw`9QN&hSA_8 zkMlnHXn7G&3{W_lHM0ZoGE$H+s5_jPXW)HM0qrh8kT-xdE@kVol8m|QuDddJpoL~k zmW%6DD4bh7?PanT;#i zfn}Pl6QIe0Yj(Ca0zk%CEh)O`I+&+Sv-9xnXyDp1i^v#&Jq~j+tfA1q;qhp0ypNN| z{*@+Upfv-a|6Dm_)4b-eC~0dWt!p^P6j3eeubGU$K9ypTZhjFWJnJi8N^E6fzGMipc_pAE zWSU*q@N)pjheGDT66s+U&dNvCLp)kfkwCY6L`5}HV(DX)N{cyn^`InUEEY>qjg(00 zRrYW0n!8dYcvEj$HIvi0E-g{^gyIkLd2*60VxOt zWk{E}z{sMq$%1gCkDb9{w=;e#i4Fm!y?bZ{DFPVdaBitY41nFzs|AaBJvnSw$wv~<4wZEuCg%k4C=vAei46c`jkq7 zPWe;C?lkoR&BcaJ@oJ2nOCe$a#KqW%K3(c#3KK}h0HRa$k2-YdC=ZW4_E^=z6Hh!r z2M->k`T2SI>1zWn*14g-!e%G65U!!#$_W>n6=PX;tbiFt^ik+<-#%oZr=BNz>s|Sx z8Z4S`&PBrmtk3kbzG%Tlp-J}6h@H|tD-X>U54GBAazdMnsLh?o3C%VO83VRVynJy* zs53RNbyRNu7Ywm-eVXX07oe#lpIi|veXLz}EK1tiNNb@~U=E`WtApix@9GmV0KQKI z6$)G`7gc=JVkjTZg2|BECuloHmqIiil(Eje-TC{N$2Qc7#<0WFzXa0i;D`SR3EJ(y1{0@gM*3pUA&;lnI~DN5_vJ zmycE-*aeovR$dO)sU%$#kF`=f+Q!bi$!H3*&PIDy9B2KU@ZW;LszG)R9F3Ccb-(EvVYqH>O#~91bNj_uzT>Yc(6Ve;njNg5{mxpWtb;7}J@1>pUiEsI}0@ zM2wYEn%^G@!)#50UpKJ-M4XmJE7jMS`SWIH;TJ%9hFS4EJgcpRExg!7adafi-WliT zcWiO-{2LyXd=((huB~ov!bYU8ZwNwEltuP=_=fIw8@tEA>Q9|Pst9?AjlQa%gi z*V6$f@+mGr+rY{d<>&QEWr`r;xa=nCXhB^BImPNQ1k9{5=6jFHfc%ltE3QpVM_JBf z)39fon?DZ$+7}>Vl<6xJ*#G=l;yqf|w4S9*o7OdBI>qwT!qbd&&9F2<7Hw3;LB3hp ziK*E*wKbY~or0eU+=uJD92k&>^Tx^<^Gi}3k5kkU zBQ5w6ocu%G&i74PA;RLoA#E2-T%6*(t)}@okv3Lb+%%(z zBkCKj;XK-@D7%&h3vKL?$^v120ora6&Gcyne5WX%)hTMhW2$>D3oIF5K=7aj02zZuwKeVSn z4&uDBpG8pi&C2r#QoRymfb^X)_8fex$WwJ3v>|C6(taKQ@(~)20tSPH)#WYn(elG& ztYhP{lZ`!N@);~zB%%}m(S*$e*zFBpR1i2?SOJOaYN+pra1ugDkXk!8bkjZee1Sgq z<*(D$?K`M<+jcr|&9!vx)mPA!S8Sus#sTUZo~H!M8_X@lJVgMD1GH6)$65iA5D&n8 zPKTL~n<#J0S3qd1ai))ztBGjy20S1?ATY(Zi%kbg?7QM7>fLgMe02Gu&`wYtmoMIZ z?sJ<7JD1Lf**$@P6h{QR-A3EC?c}>$ zAzZ<(+ttDcho55KGR}Xa>O<2+%lR|bJvg6j9|k&oj`b;4qTWqxj9}M}onZ5zgwz)` zHL&#%>%V}jcGl2?_qUOEwua5=YUy9xa*A%>JV96W*3-3YzJFkog|6Hvh3mFj7lmuL zc<9>AwK?JXt*%U*LUDQ69HX0h&at%B(!d=124j+cYdCCW<3HgM`ou(bxhlghu(j<)L`WJ+=+N#ynI<20aImK?-wCu7?AI-9^#Rv98w5%17)N2euNbH*^-S7 zYWYxl7AUZ!NUH+$fza@URS?LMU=AFctJPt_ALr{im}bRX0GmpRV{PO^PAb>|&R#daAGmgZExr6f zfDRvDpp9*2`t&``ykVR;6QJR-7`@*Yr8Z}Zc5lnZ0fuIhH0evx)^-!sI2SkieY-te zPy&I=(Gz|en~KwkkvLgRY3gk^b3Yi8y?LTn-=3#~ry|tsNYRc>PM+qSY(azT-+yEp zQaJkhCmLyvHBOk`0w9Qd`*egFY$@8m!$sGy?*Ooy{>fM7Y096XO-)4Wx}-b>ak8$< zPJj7}8S1Dr&}Z(-ectJT2#tBu)LoON`)+UI=Es0{KJ?RTM+4+Cr&(uUBagge8rN&< zt@QAVUaFyZ#vjeTUF^GA`v2Sa#>vj&>|k+jXWuID@H4Y?dMr+MmJgfTOkC>#z)tL) zY%vCmPsV9zR7zJklBRdhL@1tO6IExDZo0NEQ{G2T1nK4X{d`)qwF{(+lxF0eiRIa! z|7ePC-)pDqSl%2zE%_S(4t^BoWxS2Wx%rxUp3e}HJ@fJm9T`eet0PH!o|oR3 zqeFcOR(46+wb{X+k87x>|M2i6`B>H8z_JX4o+#IuxdeUt@mWfy4Ya-%q+xb2&xa3K zzRiUV{5`wbd#sl11oHGilt#Sl9ja%+XU)53VywJVv~3;AJF5|Lb}&kV^F-@wQuHa- zPQ>@T{l1UaUk5AG?dv2z3IM)qA(W=Sdvun*c&nQ>vvT|3n4b@p&?tECOq4(zZ0$7D zy&scox5DJm3vbNR>B%&;*%P#jRjP6zE^*I`@pImKi;My|>7buu8QX|WUottv=K?_6UF*-YyCaW<`cU&oz4{-cckZUg-8BS3%d)AFt zdieW+3quil`VB7y<3`%b%KP@4qcpVXK@*u0HFCUAtwwk29tQG%562Bx2@*Be}a55Bk#}E zZS@$dBU2#*ZE2SJ1OZGy4_}D$zWKloXQr<}zCHiuJdG}}?@`5prqu`MW8`3Qwu|;H zzv>(t0|w-c-AYrHz)G4aQ$lI745WuJ^Cf^qXM3AHqZw7qWSRPY;A@|}gWN6OAe%?B z?=2Aa&r)!KjaP^ND?R$+35p~Q(mZ8-ZX4$2@7Mw%AB6uj)MKToHIeUm3oL4M=uqO{{PETNFWTfh>$B&)F}h-B4K+1bxvAf}S}QpnM*8R!8*k@g zZ0^~>)-RH?dZ7g_aMixM=qq3RmsDS0&jmbd#Y|bbc=RdBB$;sF|KxLNwoWs!ykO(@ z=B$~r8}`+a)9j|lo+G+t%NTv}8a96J_%Rvm9sK%oAQFjWgqnb1;ukb@G#SaJGQJzEK1($q!*jjuz^x+peQ#LC~s&M!|DS}<*ghl z%dfRf#Hdl^TdQ1ks`0pb=Wa3^r8&Rb?dJV)K7fds@_r;ARS$T7y<@k0B$+8Igc;u% z@&*Uxqsjn&QkX1*X)u@w1E7(D%>spxGO=;PAhd<52mkCI`Ikh3DEo0Oq|9%~zp6KH zi-uY$7H*S|*u0zNMIrw=X@i&2repF^^#Fe{@Eaoljr>9zhSJ7C9&)gxY`J*mz*y^n zbkXvYn?>R8foBTH6|oU~@n)2@lNXtkD3Zh-`1k8RW7ae-Mlwc;3^8MyplIAz5gD_d zjWJ*QY`c6UY1;hdPbc{9^}DZyU_48p961%HU%ln!WXx}TxihEY|KyojF39-Y9SvL% zhl{v;@?3--d2ODPG2eWU#ZlleyLNUsMz`&EQcD5n^8)W43DOJiv+p*g>ALL>wy={1 zNMLXzNZ-RdQyq60^zwpWIAP1u8uYNYk1%98rt$})Yo=SM>ppV{WWdQ;2O?wX_B|lj1VA4A zHH5WnQF+_`tiT#Lb}B?qyzS>?%(uRryQuuZ6EieDpPC%cbfi^)nDKfH|558>pdU6dLqgN`oEzl zJCGs&i`5Z9#(ebwWqxZ9LodAPrT5OoIT>^FZV+Nw=XxKV3DM&RgPe@{`sZ45+R)$q zY>E?U*KL ztIIpW7NdX5+7RTZ>he~SG2ayB&7Q3!WA44yogrcXB^mQu4`#;=B^h(eo-6?h968~q zr``?oviqlB$;JWx@<-#mUR|$h-yqB$dEL+3>Mq`&X4{Gu)MU&*QS}Kwcw~|jY1eGY z?Gxaf{~^}Lp>KZh+=V-@{9c&VLj)vd(gEdIT0E*6iEn-pfRxZ6DU(nt}T~flz+Ly&-Br_Xl z(bnJ>k`4KsOpn0_9y^G#ziL=nTdk|HXlj`*AIi@&iHL!0BOA9AA_iLFN=@aJN0Dz` zx$09CG5%4UEgaVk?y0Uq56GwD&9_sh_sf0CP*<7B${4234$H;*z~J}AY=^D zJsH72v{68W6omCH`A7Aj_7{VV3WW$VGWdur)wli=oZrsY57{*_h`K@~2$_bYP(`Ty z#o+x&M?sibUKm-PEbcB#z>*@Z8nC{bVf7g#y%sPw*x0(w%*F=f9qPGqe26F0EabKY z6tTy}*4A}aKBlY{`< zR|X!QebGpV*)hVozHH}NRiI7E?Q(inGKB*N?Gj)ZW^DjwhX8*GX4{GZ0&oa~VA4d( ztVy*10k{$?nwRp+=6%xl2{T8PA|MYA6RO?Emn}*x)Noj;x6l??d%#DCaH-)^{3ac% zg*V<=y=j}$hYZLN$?r;bF$V$1_(X)0wLmc+GPob6_b@hqNIr3Tn)>_tG{gAB6d8=A z3wRoAAis0N?)6r>akrC)Mc3_;sW=Fzs^LRMXwU)kz6tWOphJg_EP}xxz4Pv)@{!c1 zV1oqAAkMKhfZb-|02|9oN{HhW$=La5>f2}ME$+RlP!w)~qi5LLH zjPiKxLM2^UYe4dHlDPcog+}}s8>it*R7u1*EJkW_S!i3Qi*DWDNFTqYg+6yr8-4YG zPI~Z@9rT6!+USe-x6^0tY@?g^H_)#29%}a3$Za!oVH^MxxM-)?jG#sGEDsiCVnJky z7(j|!3K7%NXrbB~$)x$}1%oQ6uCp@C3F_-B6wHR~#yRxeFri;4m@Glf=TsU}@hl4r zGDhp&%3!mFSUhze=L@;-f=PR&?@0gx>iKzdhKK=*rq23NRHM?zOlg*St z=D83^(J6fG=OGvmn4^W#UncX?huvE>MzrxP>I7{>HTy37x zG-K>^(>2*RmxN}Fh{KAmkY>ztug}x_eep$_5^F;}8g#6E2oq%he7a$?2uzcK7q5} zSHJpI+Of{EhBadZq_JpCBPWT=lU@kg(2kVw*jQU@veTw@PTJn<&RIJZLoA-+^Xl^h zK^kRad?1p@?1;t~-PEwQv}AIL7zqyeoGgKeQGN&fMXo&*sWU6s1QO9M7Nq$X1l>h_ zcUcdyej_`FtQH~*S?wH{!YZr@k|YC5$5LRC+YI{U3AUEQnn}QITSpE{cFh9K7?2S8 zV6se*$yQxW5Wqj1>$k9&c8=L`nvAB!vcO6Z4R%m0lAV{MJPMg811zo&s$MtLc~Pux z7z|OeIFHIlg>doCJ4M}9_I>aLR^zbHw)HOBw%J*5bDb8j?!!9hqcZ^tL=!v+xSU4r z7aQZmN+PF(iWHY_rtBiXS|eky8!R6tCndpYDewjlQ+KB{Su52{+1@QTkj>e{f5*ZX z=)lfN`pMG+oQ&DE<3WBt6be$kYlLcD{hW;H?c7cEO}qHDL}Y*t?3$pTJT*WGHp$t& zONtYTgsIjsM9no9=$Eg})5g{f)ZBgzzZMRT(hYlu=@-uo(QF_|jrJ7Xar0Iho!iT= zs}T!N(Dhdg(uuR)3>mX$`vYV$yCmj2Iz+oRp56~ zjM=m89x_|&`C>mF9-#f(&T}%Rg{_>{Z+?Ks@%emo#pZr`|9BrKV|FX^Cv<`KZyliT zKRH2lb~A0>`gwld@AuR0jptdX)z8V8of{93!?T%RL!2vmN9e~-4|9Rv)*WBr=R=_o zbvO0X_~bb{(ifqf8?GQ%?GAn|5gBB0hUiC64s(IuHaSi#8ly&c9|Z$v=%9j(F*t6g zaBQ(p1uVXHZ~Tbm*FuJj+1l1h^=%*H*JF_hx^i1T{rJfNKG)l^?UO7|-8@fCsSB(l zKgG$IZnhfhTrZi|2?b{9y4`2!XU`0B!Tz>QA0w+n68_>_yBbe$GN!}hpq@>i;^&d4 z*Y7?}k38Sc$(U^$ZzQ`bo2MJwPiDxNP1~ez4F-aA^^T9|SFc>)WX$#rSLftuZ}-Uz z8M9^kSNVDD_}kiblHUB_94BM8bZ(-WMybxlSv}pk{$vgrbIXmp>GaTceqD`3Y=~|@ za3P0`*|PNuWH4IUWIj%9wWsO)g;Si2>1}Iad3w7PF*!<`JI>P2Ul`{C{Y{(iBa5|x zwWl=MjAzN`J;uqHEiHA_*df(ZF=PPZ7tQI+h`0IyPqO+|}C-^R^0X-?X1iQl#%k90wiC zkTL7GeT|<-p6=argdTd1)jI_l^I@Mu=!K)A3=J zcZV}%Oz)1*u<~&7I=8Xq2)%Uh3@2l@cD0kcQMU7u7^U^iACe$rcJKZKMH00PrfzH%WmK9n<$)I$FEuG3{6fP$&fMD`Y-bH$kXjzZ_}f%PV%zbyXyc& z)4lwf&2WxprVi(jF;>qNtS`zXr3KbEA0|U;Du;||UH1jHKsNI_x3%MKdhF$4Hn}9$ zAFd~VQp!^cv9=gIlp$j_ZT}2~qYj>@J9`eYvK!)L%q>@T(R}O{9>4tCQhd#-^N!Vqp-)NE;Bc4= zc(HR*2(-|@pgn=0L7VUDklGN)8`v{fV(;#c(Un)ME?NEd`~QPtvC4#4xnvB?l(Bh& zOvVV)Wk7F_la3rVtq2+OqaXcet_&9ETWLg0L?Mino}ngUhR37a zvGdwSk$O|TYNd%r=RP)fl?1mSV-WHom1c88-#hYA^}fgd?X3}3y~nf=op)K z_sd761F~f98^$fwaWx^+pvViL*!T0FLqYXJG%8(BQi75t0?FaI&>Ot+N zrC8lC7(-uVx3Jr`zavXb2{?I1=vO-7d9 z_%w~pOj27z57}g4F$C?~*3Zz9GgG|MceG1_DLl(aK5DEPrDJ_zYN_iYr&|&hBhHSE zGj#aWBx~3fYOe3*0*_=`d)GLGW~~i=^7@nH3ncjf>T*f%N512Fy(d7Eb8)g-VAHdK zzaL>^*DUo7PEsJ8q_*ZO$YgQz?*W0bW5Xc5^AU)qda9|Hh>$=aKpjo9H1AJQB<3K8 zoIi`+V`lGB~ zptiiC^Dqrg%7X6ob_yl0V2k6$LOv;7VKSSd z+*b<(vJRV@%q$N8d{2!l#IA*To;sb`JWVBoWHp?lJ~laTa@UimE}K7_yC&$^*(vt? z6ty((<IdoAg-A{uyr<5?-oxq@U}xo{%pZ?qfo2zy8hIKfpFhaeg`IMq zin80((MN~RMagAJQB&(pJPw}KTsuKSV`IF$o9epB?vjM*$kVMoee~{$Frig+*BfZv zx^)@Buo~%9h#G4nG%^|Enn2h*V^`#l%@Sk_><}++yVb?=K++E4dFu4hv^T*f4Fgoy zu#;ayx*;@ek2yuxUs*$EM{{?l2;d#f^{hNueMg!xe^%#@(>70Y3n|S!73GaM z?2GxXtc8UITGw)xj+~bq>$kS==Y0j^>~^xy(7 zyROb&il-z&vMD{m(s6+%eC(a<+MdmJN|`ot(nAY)huO&5DtkZLs@rbJln+n0*_SDA zk1N|>qK+gJKAzvoILPak+I~85ewrU|UEfOn*cSdf7KJv*=}dWdc3;H_UF1P~eLrvC zMw6TMnd>NRkhG2PJiBF{yaB1~M4kdBgP;6Csq8#XTP6;k=d{kT_PsbxjeU^LT^MHh zMYOro!oETxPEqF?oG0kypww13wV0@Pa~+)?+QzS|VI(hgHhbyJpgq%8>+5PW1U0W$ zK0mSIX8pH`y-y=z&>Dab9W+yYY-Lb8XZM$RJw%O^} zwz228zV+{QmV=q9x~_Uv<}==n=w3Wfqs}Kl>Q6r3gE0YZANfAHL*WrnqL?2EJl) z{4SL}4{&~rV16{{Z^?SueL~etP;Ygnex6Dd?nmMsmt-Tqj&pq?a5Qhpe~f&=biLlj zo}{}$s9DP{v~(3_I z*F9QGgLp&>l3aebKU2sce4cMV?z3|r=S<>`GxYcbp118)G_I~@7e^QF#~Z$KhB=erLf@`}RjnC?%?*SP^=yWL|Tz&=yZ{p6H zbi23br_r4?@zTvV+t)EM`?&}-8*%2jm7ZVZwmq-*V^;!V_WW-QuO|x&o$rEv=H&lw zB6=tkKlD;c{e*kmpCw-Ngk=7?NWLzwJkC|0`H7Qqn)5zyXq-s(WaQz{#lYCv=J8#= z`Dx~CO8AU?f{Nbva3G3aTDw*BJwD3gd`>1&zJ+_jrq_wcYai1H?ckra53a?zY~rt; z^5Qc+JpKps`&lueVz-&v`UZ@TM-4BFE!&w}d-tc8j+4Jag!uq`{ma%rp_ea%SE?%| zO!K2{J;hQ)pNw5EXyenuJ$Fr)a#;g48)AMR1BU9GmanUyc&wY9uI*a#c1O0MEco5K_cU(N5Iw*0a~JEhxy6$S}@^j0-~{1GaQ>xs?rd(XU| zy<4zBBzs+luytOVsD{YYaMDlrpnVI9^Jc889u-S;p$3uk|Zor_5@&4q-_AEH) z1G9<#J2}-0%L=_-B(qbGm#NJFs(xR99`gl_k99UOc2h#g@PN?p;ChWO^Y|3sFSnh` zH(}{wX5xqcJ6U60s5|dy{*6ME!hd#p=`Mjo$ zm7~%|2PZ!Q#c$&opib3@g!(0YcI1y zA|Sm;^rPG;kr_vB@jQW(B012)ClMZ`QLVUc3Q zYL)dRFHO@zU51i-GbqVJc6BAmq%hudrbFykng%I-%YR%@fw!4v;nYuB&RGgvHTK%O3d;!ZgYK<{#{cJQ43SxC`Zi((IO}=8(wr)F+ zRES7c_NJ2=B zGi>Q9(f3kByJIu=7?>lZdvfNrvL4;|)U`&aEK1tSYt*i5&M8&Y z5hDV>^DVOw1JD%X`+q+=c7|EYek&`#`7TpL|BlxU^TNU0mc5=)V-z%8GI>Wbneo_E z=f(HzCH_h88T;K2oD_j_!9|6j8Ry#yfGINQ4$GR&4|zH$?j|II)^uZHA#Zx2yKbtI zt?RcHKJq?49f5rw@Dx6!R72T#4=m&H>hSQ-pujju@x=J%6)A$3(0q2%9RTd*^g(P} zU6D%FE=RNsN8z#v`H`rCoXZcIy2E2_=VR9+93tRN&S0g0+kGZ$W_l|iZ<^Q-_E&sbdHy*;^~d6dvp?ct^CZXq$@ZcG5zL8fMorP@T*;)1 zi?EMW_P|>_XV7=QxMoZ``ywO{%IX__q#rLA<$qJ#LY<{{qmx)K_O4pEIn8%T6i1GV zZ>xen|0ajx5BHxltj{4{ zpr*IO3~PN<*X!F?Nu!7Hp~t9dBhwAhoFuF1NH_MC@=+`e-=OkgIf#J8q1@jp;6!xc z&bXRM%jcchiuHRbajrf02>;gJ*_W$Eb+?^&n{fBzM@zl8d;7P8s&giCWihHAr}3nN zt-*KCPrG1TKgC15a7I%PuMbIIA`fQPh8Vonmc=DI^M}#&yG|u`ZP#&MYRs{eY*x_L zuaVTkioE{)7SZ%5@^UH*=1_F48BgJ=u<(e}q`Cs4(SJI&@u>0VjQ}hH7@JU7BNR}d ze41Qw?kW6M{fKtFqso%Wug9I}R#uM)MMiFQ;eY3h3eAtGjZseHe{*R<*ckbp)=8%3@6@ z6@$+mp%M)cW|Kr%U{k)lgCK1UY+gA#J3D#uy?Scpob-ED{E{X!VwBN=yr80vNG{fp zA8hojyg%vCI$p+?!B$I!Pvh<|3JVi-^kVaQjNx2g)omM=H#NAs`h&)T#%bQZ8jd3z z^$qGY{x$`?B^kVf$4w0Buqi~8LQmJQ!#^Rs&s!5z4+r_|mF)B4X%A~c0HVIG$QN>( zqmzdN*QBav;~Wju4|=BI!(H#$OQ9Lz|1q|vRSLdL|If!*5-W=a9pSGo^|wl}-^D>R z{o@$cGB2d5sGx$S4L!%~ro7$jZ7J^`g+T!D>z{`#`Ni695!1%P^xp^oUFaY3(!mrR z?}<3(Z=mjjWQW~BI7WXAFf9gDEGz_6WFzw?75`n=4xY$r7=dFE6wlcpBF1We9sm~P zs#-qBr8QJO9D=RDB#c96l0T0GWw=B;O?sR+&rg}rVD!)ek*c-=NXXXAWj=S{*2Uta zwF>~WxcFqh2M@KrtW)^hUaGC_ANLsbDDV;Q5@Xs=gt-^9=r%)zt$|rxaBCboAx-*lem;_4OMGx+ z;SWxblb#C4_RF=1)83}1Rds4`E=`5U);yOVJ=7Al(VtumIt1lSiSe#r?OPG~Kuj_E zrnoy^wC@2!Ne@i$n6e;T92hPuJ07Wp-t_c{h1R2K^E28BK~JGpaMTb`Paju)TItWY z5AWnJT4kAZplz}C0`0d5pvP&vnQUAXRerPz)pf);33)YHu)ooZp;OA`;f@i+yK#hE z;MzEySGMyJ!%G#08U)FC4d3jKGd^ACqo(-|X1jrUQMjKC6lK44U24_nx0X4xqcoum zxW3Eb(?XFcg)vcX>v0$q$d#`Z{NFo_$)gZ&9QLWo%R=adB*wxV=aDGSS1DRBgNN~= zO-=~rTbhm2{C;hRHZH=RzuHxi(WqTHkNof}XkZ$PYk5c{44JUFZwJ^Z{w*e9g=||} zrh*A*)v5+afTW@#om8NxJ0Y10VRE3@62jT{bIkhDPeBV}sI~zb{g?-94Bt^#NZ7;T zK(yXL4#6UGvl@}SptIr~vXfZ0vBB8+g{T`W4~p5{W{`8ua!l+OqoQ8#AT?}yI_}th z-U>_wGF_o=LdThQ;K1}Db=6wi$UM7I{Q;oo7q%PopTJ>(7=Dp6J*>*_WJRbdm}I45 ze8kyMfy*B}eR?@B0zqRVdutbxo2l%J+7@S^><4Fg0o{(C6n#~Uh%zbN3r^0|DJv}+ zINT;IN$Ekg`d5k{^qpz`G>~y5(8lFOu9iv|qQZ6WwY+Bg`jo=#(rC9NSYwoUGGry^ zOH7GP{t=cy%ed|>Bi8xcEsw1)t%MO&V;xGGUD|5zkqVXa$0n2C z0UazZ$FrbRM`S|Y?@($dvYKl2*pQ^;O0=Nz)r~f1JA9}Sa@Yv8P?4M7hsT`5`RpD2 z$1e&(Ye>(4q!`w_Q?fBFJEz>M^+|BP_2fXNXZ%HF-tAP(PdynVY(||?$U)uj36=C> zr03qz4h&H5+3C@aM$kS?;c1TQ%jA28ctcHXI8OrL!U(WWvGvxdS$lZ9V6!;^%ab%- zhtF!kS4JZo7SlQj!E#jP#l^VdDZ+^pqPeYwA*W~c7v?O#KvPDT*_KOYmkRhHg3HKt zi@_pFPNf@f$vWxC>HN2i_Kz$b5L4u=os7L4oNq-(BL^#V;X?a;108%gK(xcB*T#)? z(^5XWrAMDm{!y%rcblwJU6r?+S0l`b6kr~_NiLP~TtpL6cGTQ|Uj_&QQfE?>z}Q?n z_Ucj=9A_Cfm9Y=fhe~?Aqg3YJKhcLn73Lha;^kmpsc65UsANDLyxdWv%=fmT8~|C> z-O;ZeJVAQrK3Ue& zwATTf=6)o^g*{Q2Pb!}3!oquoNhDt+kbZhbQL)d_&kk&IGV0pe(KWW+#+~3%j)T=> ze7**HIyRa?p+%kGrrpTVKoE$OC8ablbKA4QT|i)vq7*$QUCvkrb{E1e#KlLJI|l9% zYJKBgZGbsaSZEx1i|JxvXQvm_u)2sktr&$eDy13z9ubVa65}>pRZ0% zXt?r2>LCq-toc0u?K`Kn_7Y9|?hwPkXW^sSM`p@Nj+rA@PkHS@9$j~3>NMImWJWpDu#(TSY(+kG%Pj|j>n_mMAk9ZIJuIBn z=;u9c;+J4hQ=jyQ@GKK2E0hUi9Hm%;lufR*04)V4)1e3)i$P(0x)$FgvBAo-#?-0+ zuN#s3R5DDk4oWmST{>uHZSen8L?@VjkoK~4r0~$keV9ciC!902ipMb)2$sp}MaJcu zRJ$s$^a;r&{lu4@gB+6$R0D8dX%x`Fku@qiWb!5<(H3N&euru{B`H}3r^3wqmhq3O z{cRcRrHp%)F*Fpy`FRwx>+zMO>qb(D(EEq}24n}R%dDl9D_RmVoWe9uqvM=M1!{fW|RsK*zwx^C9ScCk@io4vBjV8NGOlcWl0w zFxHqcv$C-&gvMF~rX>rQ)u11SeP)#?_(jjhKY_4<2{*XDn{GRqpb>m1)iYE5fguB_ z7e8YXaMy6;t1CEeWO!yIJ7!*=cKL;JzP>_>Mwl@30~Y4h z;&yUnjPJb^bngi3&MNHR`OepCRQa9N1j$L$Vdodu z?Bm>yV?lR?EY;+xwT=&I0sXzr53XD-%*6V|%=d*)Z=VZ#)POr!D{*YS!y||Vp+wM= z|NWX-YqGC*K7?-;-Q;@l*m`yYO+~rfF9BbMD%MDJB!c+esP7XZLIq$oo@FtpdU{neRxfAzks@K3-5!JVM7~Jsb)T~5PE2H$H-W}FnnzdUmahf z5Y=l3HaUPIBiyYrA183 zK=4(HsM*k$<(BTDuM~J#m85Q)f*W>h^-YJofc3xUI@~?>8VqYTR2kW^caDMj)=kPj zRq3wwPf85<*v!b>1XS%g`iZ+268shM#SGFe=bIoR+p0%{cU5R+9l|J|uMffj?7P!j zAO{jfGBwwoFd_$8FZ#}k$AGqU|vj&f^eZMAz7*c&8JVi zLrN5_#I+F1-jcThrJ?IExsa|XEyd``od~Z7r|^j4%ZZI&97gE%0Zw!RJ#ib2DSh50XOVR2J~uM&A1Uo|39 z$b@MV^0)92INk zJZ9vuh25|s#0Q8U#Xb--#Lu9OWz`!t`BP(2DO;7S->}+7ndf%l6k9MS{bl6 z`tJj_$qV+$> zv)ETMz#5I<*IXf@Wfs^EOW!e*!$y5OQ z(jq9jb8Wx}`0@_7iFN&xS+xWTm9^E5EmcaGLWNYOIFa9OM~9A(gk+Iw{5NS~yo$u& zPeJS7O9(-v(o|06W-Jmhv;#&KXre>&bp(g&%i!;Q=g+luOX7qVZTrPo-rdYy50b=F zGn0w`(2e&*e`7GaE)$)*vaJzfJ+8=bhDCo!);4%#1(cWvVn)=7F8pSwV1OK3=BbiE`9Rc77C58!&pr1LP$s>YJ|m z1-1osZK(uH_4tlti*>33n;AAj#?G8h62>DB^SGb!&h0#@I9C*arvuHJ5w)>6(aF>Y zC0f`3XJk$G$M|HZnl(%67$06WZOGCY_hs75kqDU$ZDjnn=anm0W~^Dy%|PsXFw%@} zw3!{z4}fUP0tA|<>-pO0VaGC5O!jRem)xSB{jQ)7q&ET_?;5e0smLPGxB&D#Rz>VO z2A104=uL|_nnVL4)y_mQ5@A#nVEVFMAqX19_R$O17Qu(2mY)L5<`mOn?t$DiJ%?Is z){2&&^uYl;s8i4jYSvszNE5^--dU2GL{T8gHuG5bHlBj*;b;DV&G9MQvwLlQJo)6vYV$D zEjP4(%X!DiP>mE-%WY_>3lTu|3Vtq(1*WjsfX7nVQxO*~qPJ4VzUW@$YY^AflMA)H zq@*1b(xX~r8<#voV9iDJIE{y;n00i3v_nsKl){TZ4L`{7OqXun0+z7s*kmzx0X)Zl~Q6#umf5}&CS z1KS6}^+XgksFN*S{=6e0OD$q}p8rZav$8X{&r@SC$b%JDlJ75piQ$W#!HSX1d*eEg z&vXSmAJXIb4(OHoSM?=s{YU~LM~8Om`WyM_NQpY1u9K21c8Ubfv5!}G- zH=p`sBvcYTdJ+TROWK+}(RJn$_T;yDONb$$cC*%6Yj7VQiqbGbX(lA(D3x3$cI z0R!B*3o|x0!jV-WwrtoG&(v$$(4pxIL~6K2ZCDo$)eZ2Y$#eUtDQ#4# zNsl|Q86u;*T4DCSqa}r9WEMpzc3JC_rF;_u`d(-uHSER@-e$dj&D}8|DM7uvke9i3 z=pEjBx;P>~pY-)6c0%K4*fw||b_<_|DRM7|p*g-N8o|*SJIS_i$VkI~53b0B*u*4@ zz3%!J0RRj(RBv|n9||-qTxq+X92CO6p)bP4y-pJz$li#sTi7#QH-h>bo6fcwTI`ht z23+*PO+Zut&>ddteU*|v2nbN6DYpt9iC! z=1WvCGCPU(w*Trk+c4;bHZ}~kWir5zLqT?tsKbN(%AUreYicraOB6NW=g8d-9@)%p z<69Pd{&D+I&{QI_jwXdfgPW)R?RSGU9c29)K5{N_8&bkLD5RaQo{z4M&)MH6F=9%< z?XkVJS7Cd#93X*VX;sGJxP<}^9KCOV!rEk-sACmgzb2}3CbvBp?(^8Fj)B;p$SocQ z8>fXa&C>lFw&Gn zHrOsb6Ui(%L8YVb<+OT^Vu(TQKLuM|dS{#D8DYL9MbHsN2WB(xW+w;}PO(8ymi4EZ z$sOuvYBE$f^C$K#ENAGVCp%sQ`1QkGMQVxVI@1`#qE>@!pAi}KM_Ao&al|>^lrSxE zIj*xpVc?0u3;L>XM4I?;UKduz40x0LfxX#ufaG0p;^Pkz*Ac8oxO52bcLy9EDHio<@HpM3UeRyz11Mq!et&1!Z2hzTA@A9Te)UjBzt4xeZGZ)3qhq6llw&{lx~9F~v3PwS*l zBb&Hk7){6C_}!98_?>d>(vy27|7c^{O)f6$=q<{{4l6Jxg)|089!QMfv-Yg}-m0^c z_P-U@CF(0t<$#G|Tyocuf?JsmgOu1Yt+07Y&V#34}9;g>_N8}4mNg_Ni!|~1MfnVW|46;52SY(@jVMiOgrM<*VPkMFEE7Y<>+Ngt4G?>Yf(F)ej zsk(#MFh-~|zZp0hOiN~=)ZM~D7IU9I?GfY&#saouU-_rOPVaW{0+%_2&-mZ`hW5hW zLmeD)62oo$N}Xh-Sn3=RO+yl+z{9`!G*G*JImH{Y`XbBn zL0*ptaUjq4VG0|drS-JpARv*A<+8MRSvMn=s@DQp)n|ZzYH~>POS_kV0byg6K8A)ZADaeC>t_h(L$?E(Y7l3!zfel;jq_<05zr7ErRA^uloKX-U&bC9EkL7w%Tj<-itLiA0vdd!Yqp>&yd= zwI?HT3SyoGuur%x{-lr38#6WgP%(Y^gLJ>dTpHHcPsR78J;cm!W#p3_FnP#+hE1^p zsLh`cxw}i@kRQHxE(Ycda>KC+VC><=_3Kaqa0MHY@;tbBpthLTh66d#5hqrFx=O>c z^;@692|_3{5;^|iB7`9Pq?YoM$WC)(3ZM_|7EyY$VNM!<`5UKkx9wN%L=T8HQLiF) z=epi_vCz0JAUijTIH6D8N1>_y*t*+Eu`Y>|BO4rdGC`+;D|TjFQqu$(DJf(J z9dOEu%kjjcbu3!23>JcPTuG_a3U`v~ zPZaeQdx2Sb@4HG^@jGOPKWl1+26EavMkDGZqdpo zpGGob6srTD$)}J?^hmRpZmm)Wg|aZmrAi}!G@6c!4A14TgBs)Ls+M{O{4ZP9zhzGU zrWR)#lS`phZ80w*EShbKSD(kRfO@mSHp$j7RS>xAJ)Uq#nhj(ZeykrIT+s;Ki0 z##eAdB5l@cRZODnN-DwWThdu6XFYn`m|$_auSfJD2@mpTA(cT(e{x}x^wt5ifMN=9 zsufX?cX`DG@3!uQ+4x3N*eVVkWa+wb)jR=iFo7(KYD&g+0$Pq%rqwFE%3pRR_hr$O zAFlaxvx^Ga%@>7Er6>yRxB%`3yVMNk&><$~GnVEl%f>ca;{bxQiHn@qGY9 zgVLUkKc&crd~xCEhAoofg)lpEbm#&37#L45@97!;jPwj?m zCf11%GY~$J5oZgTtYE%hLLj7^mE}W9ASa_b2NzRbEno0EvEzGD;=@mpL)FGYje7{_ zc0+xJhbJCjCP$4Xn`tzX;G=yO#yLJvA7W=bBp;O;2r2COWcTaFdQVjuPrWhH`zB84 zn6JZxO(&=lC9o&$kP5#C`va9d4$2Q0C{JKG~*ba^hz4<{EmT5iN#`77|Lb|0d_c2KAJW=w}p!{0PhxQhTMO`zA|n zw8|fW0dma9n~F!>dN(;bE^>i&6sKFAXC9DSsw$FBhQug+*R||EI7DOD&iDtjU$|=t zgq@zBy_dH7(^CH;x2!|-n!4aaYGqY>&C*tfEV@cI$S4axiZdCcB>*#Ol5`jYOvTjB zT-~4^oql}~lfoW7@t>i>IJ=WuR4Vl}$KA8GFjS4{Ni*{3n`&ySzuPS)2p zmC;+|Buw=C2?HAF(4wQRW87CWhg@>pGn2CTRqNJB_tv>vqadDSHH4ppx>uxkQplED zz^2b0N*jN2CRrj}D*Z_TK6__k zns?;*05FoUMowgc1P9}xngdzDUtuI*4}#}z=8uGdbbUQ?f;ie%5$zeb=qy_PGdQR$ z(eiD44**!bq(RYQ@yTELT}#6u&r67?!0(`DIW4s+4ou6vRAFpD{`RU#b9NpwV<|DZ zMYNop)Gzi_nV|wam4o*gbQWP#6zo847P;O}KLqQ&iQnJ%rEa9ucotIOX3_6k z(T9@ujNnmg?(DD<{lLR67WhyKsR8iSCC2K$My-4n8=gGx+$9r}m%&$L+O-VSj+}{r zq1}QmjW0BwtZRrqq9`6l{94j&x#A-Ef_wwR0*w6(T~3zY6oo#A(gjq1BnNBF2Ma2% zRJ*(%KwXFt=!P!-S0lq|DuGKnIfd@ekaM02Ag;b!eV=9G`%=>HM#mI`U-o8Ml%R@OPN;v&@lotWen$i^09ZaaGYMG zDjel^vLvu3&1$3C^}_@GkUWJr-hDFM8AV9zJ|o>Yzn>@(?jA1SKv1+Med7ehpIL6* z73DO5TkEnlI*Wg)E5wDswY`Zg4k+FHQ)d#M^eJvQ2ooPgMVeEAYPV95f(BIMN!XHM zue|}=!v<8XPJn^h0lxuuhPJm!e6IUooL}!PKeeMTFYRvKDU$n&t%kR?1h;vqL|S1o z*xDVeEPq@tKqRR+HbHkpzK7wfCIAe`0pxFlQET`v^!hfEmwhtTC$DgVm|Wm#(5I zA7$jh!n!1d;Y8l~6-b5r$_(7RuwjaoQyvg<3wf__*XyO%kT0Bdt^k?&K&YCA552lh zho#557vtsoUmU1ft67DlYV=H#DF9ii9&hKmdxGpA za@(wz<0}iJbC(mq%kMAoPb2zX`$r8jvmzGo|1nvA%1bhiKgl|5(16If1qHSs*|Q0@{~kX-cE zTmDKTJ*YFv#Y)zGHqCAS2*x15U*oDgbFJ;>mansjI(J2Y5~byRjgNJ;yHipPlK+iu zcEiu9z^!9&^LSN#um}I@z~4|kEq(MF#Lk0J{D?Iso<47~s{*p5AAtL&=~SBT1u80~2yR4PC=+rq3brs^W=d*!{2{q@eE81R z=qc)#ujW8&Xj6RGU#sUUZ|<4lEEapto()d6iwl<{bm#BF6&~(--&22qfUMhHX-!xa z#{QGbnlELZO7NRI3uSSLBNn%b|9nzfaMSEmUJJm5#~a!EztmXBsGbPt9IRt3tBpJy z&)>CmWMLsuf9P1eByX7?l>8@n)^FKFr>>J(n_4qnZABk(JNGZ$mr>i`W~?)2V8bKC zi^fA9Rj?9K$Z`y)hEO^~q-m`+cClh7v=n)gfieB{i8h|4wY{rudWdtE^K3@-<^69v^zqX8_HMx7m8v2Nh?267TT=mGR;>QUKI{)t5b^ zkppp0%_?=f7&QYB$b3>!ZWxEBsyK}?&R=5s@j=YwCwITl7I6Uz47ztr*Sg8%64!?8 zRo4UJKhG8HV;_sGj7QI|2Cyiu;|E_#wQVpViTI@!^rbW+)| zo^NLfbW9t&!IP}&d6a_fYOIH!bYhtQuCGRcZpGdsw*&5vu@<#o`$nv0;Y;?9T@NmL z>MPOz@jW2$kfsG)-&Kh@>5PJj>_6&pt(c&R4m=6o%Y5qNRW&9L1vN*p5|se5ZRl4! z!H`cE-ti!*XG_X&fUA5A^fe$=?gl&XZ7u><5d!vGLsLN4){mQ2MEo$-jY+im7`Jr# zXm8(ysF|BOs9;2Pue_6p*=mcKrO<>ZOGA(ADW(HbV;qA(v!f+Ha$*J~r-hN@i_|aS z1eQ^XsOP^+|AZB=U%4*ezm69$oUPQ>p=uX9w{#9LqKuG)C2S%gj%MtxI!mtkLbc8jXlgr~1h z@feOjTS{s?K=!|Nwbs>up{!qEb)XNizqq9!N};-72hK}sn&-^V)G1jaX$R~#vvJALX{KM>ActEili#$M zBGJ9766ItYx3bJhC4qWY6xgylR;`3ZMyO=}hIe)^rNn6E@om9v|G{C=WCc)q-1`A0 z?4q)UHQ{e^fdF3v_%cL?RrytxNy&L{D9>wuGQ@s8K21V(>J?CL6$#z&>&f1xm~C^` zh&437d`^l=^{cur7XbLWmlhXM3tV|Bk))$$Hc*hGmsZAVh1MsFTiMC5px(v%fqTC+ z?v9$Xyp+bX2Ihyr3>AI@PUVYQQ##QHmsAY6aC9cKUWPJ34E}QXbKzjWeMFWI*Sv`` z_pFxmMtbYM%CW-h%dk&eAkM0=U?YcNg1Bw=)WrD>3zqR4DC|2rr2A#)fYNxk4j^zh z3z3xM1K}UMv&@Z7yWZHAe9n`>(spotH!@squQiXQhCyYOhp3(tE+QBhUWZL#ly#ml zr2~8etH(aS#i~t@rq^>!Fczek3QIDHihcMJ_6mv?bn%h}MTS4zhPXAvjC!pTIG=%8 zex{*Z5$oo;DN5V6=QJ@GeqSc07tIl`+4WxHE*1LQS}ERjS^(mQk3=bztxES5|veUJ80JeSVVW`OzQGkgtsr z(LN*!%gf96vBpqLE3>l<`W4FX?XZ=?#zFgmu@$<~;j;yG?2||2(TNWi%^Ti^po~jZ zB3G49X(lVyCYelPUs@DI!Fi3e4-wf)}xbau&?@*@&bS7WzW! z>rqM62Bj0o9Z7-W9UgR>13gId?mhBDux4D|nb=7{u_}pk*u#3IKj_cOy1Jl(Egg5> z7Hy)MPTnB_w_q<|y`2uEY^L44u+dWl@v-3#7*v0%XsgFyzBrkyQc#*=s!Z5q&mb!a z8%?5RvhdthK8H?ACV=Rgl@fB_cbcoHOPh2Bjb7%{wuIoASsw&n#4z4l77Vw|s3Jw? zF(-1NGmBHKF8KDzIahAofnL+OJ*3OIC<;F^Shh7*Tz*y;tKl~O{i_mBX*_@5%OKy_ z#U*5@`8%DJ1XM3!L-F}8)>sySbD{$xu$$bOGNwj1+gv2%*5ZK9w&(Z@ji}PKzkW3Q zqLHIwq;_UKBpcSEFa{th6`u?KuQk`XQm{5nmGM|TAqq@*RL50-Da*oA{v+QzDzk-y_; zsjt*cDcgqO-DqiUFhK9zm>l`_+WmLU)wu2+RFDWGGg>b%nwc$pdeU6KKnwNBMQl;_ zp?^ZuTCL#dX@xkdhmKibIV&oT%(jkOSWrs{LQsBI_A@j7;z0FI&dyx;AqU_By1%3Z znvPg|wj_@58FRHftT_tc+OnrN>M#G>T1y-ekZ6e-*k6p#hF9MTVl7u;!hlA3}dU69rp(&q&af1`%V>;;HdB+{-cAy}EbeZc->#u-U1tD6? zA&P{gZ9i4#?e)rtf+6NvH(y>kRWQrWD~qOj-WDKgHI)%SWH3BIN0Uqv31W$d;XYIU z^m|$UZKBkOh4|wDxPR2k1=BZ9mdA#XVOcWc&YGM&@h$F)D`rbqN=4lDlO$>Mc6e5^ z!vhSHR%Qi_#=5p*N%T$Wm4!?!=?2j}R9s`0C8aJW>Mtaua8a{5@EzQC=GPK$ihMlK zj&4w5_5}8ckDvA%?o07eXlUKO8RZWaZV)>O!@HZ4Q=hN1%^~-c=Nl-v3bt6*CFPerds^5Mq6% zi}6}+QPTGEMe2HreLdcu^MD^tFfkok`j>AF%E|y={*D_IQ42n?w?3NTey z(=kC7e&(-5-dmHy^)Z|$c4qOPSe`g&POa}dYhV2;sw3RhJ1=(5|w+I}3 zT!v3~ATL(&4(P;6n9cVRT!{t|NGH(*!T@!XpEZag?XMNiD9-8p7(YY$_b4$aPD&;T z=$A+r&K;26DdR3|on-&R{ckHD!XO`EShp991UW*b-z=4Wk<+~X;vK|_ z4QZx;pMc-#5G^kUL7qFSJO?8L2UnFE4}GY@u+CuIXqw`zwG=ogMd^P!C!CLg=!{gX z!{Uj~D@!101T=}i-dn!(oRs-kSVW{YU)XpBs4mJ>cLO@QrFG9J7H~sQBg8Fy56M9W zPDxNt?6hUbb%iI*j)yfl{x2m4Q8UXj-%w#xUrS@C@A13eXufX7Xt1FntXQFYFW%hT zEuOHXkAHrT$witCD}BG6Giv10KB+!KKwxv~MQ81My*%2?NLJhj?fvqC>vPtH%UFC< zlc8%|Ku{;cuifo_rSL@j%;gRXE8fZFA$86eT$G&jA+IbVP9*mWcBEBE#pFOIWO5qbtH!A(Wbl`@KDhSf4jPeLD+> zeo#g8KL6?!i-p4bMevLO`mXA}vnIALOgXgCM2uNKF6KIWzA7mh4!j#Ygl4+y$4cGTk1ZKGU%M% z#;!j3-!?Dpma#`?txoy4P-+D)5q;QeYfV_qsIB>OTiL9U5rqXwgaDP;8+IC-H*0(F z%DkVPU3YWu31ey1& z6tCmKHJh#Z&CTJalH2_0e^SIb+zNMntu{mzufc7>OX>8qQ^01f_2UW@=i6woms*hY zqilRub*t>_{pELQ?jx4s-e*twk|2<4X1gG>vehUbQyxt$z%MhPSDtHa%i6%JIfbNi zU|2kww%e5p^8WV}oc+IpjLs|Y72L$tD)_JjJFK@q%X`F#;Nu$3^KObOG88nKlxfs* zVnZTfDjJTpoq$1W0AlouDpwU=oRNM-`V>+c8|!ArTM4*0Hsi#$!0}t<55zeQ-k*Tq z5{!6BeqI#}~gigs_PSnP;oxmv=+%VV>{{Cwr$(Cot*mi`LXxSx~QwFrxwQ?^Bp{mYZ)Vl zp@_%|M_STJa8Tm+&=NEue;GWELy(!OEW2rOF>_Z(H4X}j41d`L8`YAEc}m9jn$SxQ z0QDCb!VHrIuun{s=8+3VATtR%CxmR!2o4;uFmT*wrBM1-VL ze~?GkKUNo{JAPf+9AU>^H z2v9TbN1ICy`lMn{zM)VDYqCxW2R=3vhu`{#{KeJOkE$uya^WrxJ&ZR9>}pF{sef*I2ZoE*gNofdD!Ez_%= z!6G<7c4du4k}iARi56hTlh(nl+`{H$pe8b@VZnJmGb{oL#?U%0ClF)@k`^uo&=K34 z!bbM#X$5~q{V01WTTYd=Tj94d3!}ovJ0z7OOe~aS9Sq6t4RQX^qUIV7QSx6Z_7j3o#gPtJUy)5*rhpy^8}wva zd*+iSm*%i98G0F!`gxMP2R53dQJGMEFicA0E~Ln%+Q)7&EPW6ZtQ?M6Bo1d(#fl7S zVaZR)GkAuR}N9Jd+!@E188kWlNN^R*WqP%O>r(7&&9Gq0b; znuH|b+t~mRx};z6O@Sf?XKVkoJV=Y^ZmVOQJl6;Th1Y+TD6m_mA@1$~MI(L*^UsNY zucl~z=fr`W>(?E~B>MyWu0B2%78Q9*OMORJyB!4B3I4N$lc?$h zgO_$E*e=ti{8iFQ(#wm8U8d9n z?~T2oW8xq*;!nb1kRj`DpLVQ{}e1Wy|+#mqWKj7z}_ zn&I-W(7QwJ+X97WN(Iq}BK7R*yjz0Xeu5%k&U5%90P1$P>j#SP4!)zK?+O2mArd`2 zF`1v2)rZ!)?Vc>02hQy{G(AfAg5fX7kN$XX{fnJGixZU)_Wjr6m0p75>sbHcMAtZu ztV6wN>xeH$cxo?;9~D7TSbVRD&JBbUDVo&$*5~F%q7D%*U#lQ&d_`JJclRJ@8kIeWA^&P^WiF;AB2eB+zKdp(mP4wLw*xokdd4wGPeQT+Bgz(>K}o-icw_Trf%APp?zPv&&X z>ZXzMo8MJ|sC_rG+ql(tC`w+mHSXq4h&`5QK$W|ziXVo7+F5a^k|w0+Ev^(-ZLFEC z{*O*jNV{n6#U?$=H)&!w0Bj3XS5V&H`x&GfdUlNUW?ks%K|Ar@AxJpNCLtIsNSI}^ zymMVtxjOdl3*`_8vk_DVHvB0EkFI`foESHXB6QJb*)(iioYwl1Z@uA@_JaGgO!wXa z6}%JKGa(lp5DvV->|3I2NHhze6OGCowUin8s`G%+}5RRr!A7?bnl z?EU(JfTRE@&mtp)lpf-iFFZ9y7`m}gzs_$sjKSzLF-gh2F2&`L(FhA)8Cyq5AC@wBvR+`KR#&V$N zl~<7pIjD`=XJ}CvxMU<-*bP%>l#Ad4tkpo z6GyZahWB>n=TZ~tB@^AodyjZo`Sj#|3BfhVwGOF$W`@1F>FQ;k*3yt5IS58*e+Qqr z?~uvx-Qq3QeCj@n*_1T^uCMYIWqH(nPjt>Ap03TXX&%K&fbnuQT`xb|-rjzozve%k zN;165GBo{GUGx^^Xz>zdsr(XES|W__QO|GO@#8IO^lcb8+p{QpsHD(7-e>5*9UZa9 ze4;$8xaDc->^%w@;Un@jDjqT`63U|gW)UKn=i}~^Z(&o#?>ZDabMtj z7X3@sCKJgo;e%tyWK`5#H!I<)wOu17o?s@z^R^Nz9ahTKoA2!cYHXw=OyRC&V924qDP`1*Cu~Im0OLw1L#oYUL(AAXE*sud)c}8Xt zF!wOryXc0*;z$1Y*CB$Tek3Sn)Ey1|HfAX0?%40IQi z1pNaNEDHIKe~OROSl6bjVV(EJ4eMIlm0vVER=t~z{)&ye`|Pq-8b27)1Rak1$d<~T zuqEg6*yXj>U6LGz*NI;h4MYs#>G7#HW^MNiUo;+DGKkQK&_4{-BoUhDz}D>@9q}6- z>Q0C^z@W$TWkiU3Q4}tBBdY^fk>78KpaivqjN&jd-j=3o_4(u>%n$Hj0)Le?gnR0i zkU;DnU>=cf_OmgT5}hb@2FAWO8;xm8pS#afCWi34Z3N`LWr$GEh65A!gceU*NS3)5 z2}Yon6tvnU-w8vJDy0Z2QiFDtBMJVMeAZ$SDwn4Q#3v%OE07xjqTGTP@f>g6kjwn@ zV@vPe)iF;P23~;j4|aB2^VgVWvM&T)w=HgLsvr)hyT8}D))XfJ3ivNUT0%=um)rbzP(4MLh8mU+7JZ7u^_eStjl01Qx-z)GUbf33j31LJd8PS<# zAD~f3KcZXBK=CxwFY!(dj>)xwBM0fO&L9NTI35Pc?Qe{MT~N}H1C=3+QO+;^bp9b) z8Z7HvpjJOsE%{gbJm4_;=rxigH&&52ERKnm+@w(V&9LgX5?9$a9#?A)x` zJ}|lc2_^6yxKoqj;#OPEr>uSpobd`{`m`+eAP*pE2W<%f&ZYq+9;Cqcj4y))o zd;6%Jw2Be4q__%+pTJgt{YKNOlzK)GZ44f*iuEg-#i(Gt7&NZ})LmX$KnH}Bi-A3z zZhd!5)t1KaHVxP-VYt->r9>%$u#5yek^*5wGU|wP+zt?H+!p`YA^BEA0CUP19>S;4 zNG8wIHyWAguh;$WpsJO5q37-Pv@@$qv2uj78y*5LDq3r1q4II1K=MFzKn^1iB}LSr z5H29}ZaR~vBfCPrwmViAe)FOCw=ARcPt}T`_{{XD@8Fc+@4KEo3G!Unp zqA`&~fmo$A5X$wNLInvOEElTSz*4EaziJiE%*OuhK9w2LVplo3e?5tG@1h})QjEwc zvn{TuH;3iQvg3AtV-!GSF|E{AHkqiRV}5yg92~(U)X;ny3+pY*pi)6$T50WU)1<}i zcu*YTsG7Z?G^?}mR5UcBRR5E*oL|?L1Xawxa5Ul{HOdT;+Mu)@^rhr7Syc45p?$_a z0Jk*sC!G(DY%0(qu{qhj+NzH~BIZjXS50*cZYd|$F^FpY^*k%j7j|@wcV4H{W)l3t z-9y}beF*XHPnfrunbj|(XARJN6$6pjpyP7JcyJ>0a6+iBydxR?7F?oHGvP`Z60FbvNe_X@O z`nON)2Tf#{pI35mNuTGw&*3@1L|yMeA`<*=5qEc+BETiWWA(@78a=_xR@(l&*wbB3 zK2x91DZ6RK$Yog^)zX%~xx&79v{ZkGJS4BYGa3|t5-32SvnC3s z=yU6MTM%WhQ?RNeD`MuU*f}wSPN!G)*N!akMswWIPh2E4zXA{3&P5jO)k5gRHlmZY-> z035|Nvj^Pcmx&MKl%p~jFNZjSfyCgPP(Al>qVi#{L=2(mi|)pkg9C3Go{HUUGGt4| zNE2L1I7&@sM+s@fuA#^|()a~cRc?-8`%1`4B|c07 zK&DdZ>Wlmyz@65&m?%^s93?@65~Vy47@nG(e}xr_5LNNKNAds7ilk@dtZx2pv%q0M zQqAC}1Jwy*-AJcU90-JRGxpCmp~&{31Yr?(j7RKZ*$b!^oe3j-^uHw&;c;lIr$5_%K=u6F1w zh+e&?#8~l?VEmu=mRx?TFDNVyM#!V~Q$laUn+crT@sN=eOt7+!CKo5lu30c)2WtDY zONF7TpRL*t3uNZsq7i#G$nE4H<GO)4uLrWl;{7EDI0W^$w&vL{dRV z+93ZhUm4?|Bvc_rXHGVP0*=^;aSa*ZxrPT9A(Eq&p8}r!62wy0<3*2!s!`)A=iXJzcPRhW=$B2u*{jOOvg$U@SH1LD}Ub%E3KTh_DqolTLQ`tev4ZAtbN{4o*nphA>-}1z!`MATc5|tUbRn`!~dK(?_a$QL#qYc;P zdU6si;l6RmGG7~!bp~Ro%5FtpA$kKtA$>6n%#}^^l%s1!totzuf33MO)TrVj!1i3H z!Cf1^JG7>#fAo$*EMrMx)I@qdMsL(T0Hp|(31np9%#3y-Nk~N8z=d1-`&=UEVS;8J z4IxGSdt46HjaT6N3=WUKy(fzqw#Phk(MV^BzrWCeI?#bCC0vO_zqF?$W!$LPb`xOl z_MUHO&2AK zb^880+J*ay)Q@o#+7ehrfn}0|eHP0bwOa#h;I-6}r4#RQ#GRfbxfUT2L8;D~n8_OG z@E|DL+#1?++2r*|E0)W=f3U|S{MX$9Cw%M=!ay0}uZ5n8V`D(+Wv3!A-0)LZ!uskc zY%E>?-WvY@tiB(LCUq0^-47cAbJo?JO_Z5j&Y`GmS}kVn1s4Xo#8{vp5Ij!SeBwNPkc!10nW(*^1m(5VGg;}!#K>dhgABbXq9ETSB7$!LM1DJ;)g(eZ? zimPsEZxJa=_wk8GM-Y46b!Dp$+vb~lJjAe`4%Sqqb*6jHB`L+VP9hCL~>hr zh!tzk)pdoFDKWrf`Od)akLUt7Do@`kEbx0h!@FbF-?qL+LTlBFiBB^6k_J~1t5^6l*6 zz#k`}AHczNGjKmr5rn0WB$RO2dB_p2ZK`B`r&4oj|EqPB;v$I4f{tty0(Hc^1q$JG1(TR#B=r{ zQSfl(>0zd2c`Vp#Jyam}awWHnp8xj4?xS-PXlt$2A(ff{!>gqk;8{aOI8kFAZu!*; zrBRGIc#`PL`>UQB8#i&w%8D@~*8~*U$7N}NJ*>~14U6X#ztJM&L=~R|vA{kA4U3=d zc+aE3Nh3Tp<|XCR3ikcuLJP~z%zc)Bw_r~t^Uy&s{_#7t?^JVqW)$;Zb!xzqQVl#f z*Fg_ah}doBSOOaLgpGHY-pmQOhHMnpNP*Dz`zZj+AFTbqqKsAgvLL%;t# zvGXkZXhZ#FRVfQshQ^{d{t+-Z%B2oIGTbAr(Ba;X`Y$Y1zY@HmaFg zsBO2fq^g4R=Z9z#kZ@uBWO7261+f@KnD9frdC3VRV(i@c^~CIqMRnwK zW%IK&?@(rWp2!uLHu!;7;m)-JxRXLGB?h(C8 zDBLkGXp$*-m3acA!{+OD$T5!D_+bDR^%V^>x2lCzgOjtM9ePc<9~rWgT`}XP4sRji2vc(C ztm6wD<4mX>WTkmt<*K-=jS?s^1js}YalQj*Wq~p+5yRt!{yZi={PD%ZGDvWb=0kr# zV=o~z&V?IE8l5<|AJGUnxYaFe79G-fF`HJ(VqADkqe!1e;jpcjp%YaICtfWNE}k? zFwj(+6B^b?ff*AF*&^rSDbrFyI~0n7vE_mXMH2-c1U%VMr)9yW{mgh?nc!vhrd?Ry z-^&{{Ha(V2%LSjH<6gxD?J@!D$$9CM;%34uEJ2)_dB(>py5?tR?cJmU+`TX z38Dc#pss3mx{2s>m$oOF{;V?RB{7R6xhbU5W$RRN2awNrj);IRteS6uYzd+Asga+e z6b3EK_@(kjU}#y@jhLKkg{QGY$5`^TjHX42C&AM}`&U|Xe(>i4l0~>J_PNdFk>pQ& zVI8^MoC07Ok9-}yu0t6+_{^EH7!j+IjIn zVYzJ)NID3cwbpI~M~!Oo0@S3NUv7r*K-ltDf1%TpAR0)L{I~O+f|?i_&RivRPKJi4 z*r-6$u)?wIIfeS`mEJ5ECBvp(PA^gUxm}hNh9Lu4d)MZDD0_YTC{1j1v?~BQVx!?0 zYQruO_BOe^wNBg04x%K;nia4qfOs7<|4e{?xLfVVDck+-2bfu}B_*ebU;S8b+uH<% zsJ_6zszVx)IdA-4cX&T%zumLHHoq?lu0L!@Q8i#V@$=F`pknKxek2AU{ko^_JUCX3 z^Y{7t5I-JQsMcF_gGc5QWR{{OW?<)JNICJT?5Xy(A#1Ziiv~0yLS9l(QF(MtQB!MT zK{_F&D|9ze*E#{E9SNnmlKWY@o^g8r+%Wsu+%&gU$;P|kjXKqMuh@UY^y<%qAI!)4 zAv8w0%uJ{@bFJ`}?_$R*J4_FDdYPcd&Q3c6d5nH?;SrZ`k0~%CK?RHgF+C94SOgm4 zQOepuyEJ4Y{U3pFm<;qqk;|1`^7u`Jl{wiwULP#gEhkHUe%;*I~-iXer@#zLrP+% zc7aF{12p50kQqTNt<`*jNI#21x%wAhj2#}bMC8OBDkQ?|Z55gI=9bg8@-xe6c|;5s z|CRs}kB;+)Rv@tgsVcxGbhL@s!OI_>og~OF48iXVw%d?6vt?3*N`qMOA9M$KzbJeD}pMv&bN=b#h<2ydBua+C8 zwg#!Rh$YDFZJYq?bzX=A9efPWY3Ke?=F8ZQ_K5KjL;v5Czu451 zQ>F|E9fC9!$QAJiQF5Ype=6-V((G2|bFrT6s)(95Cj^M5ipjnV{*V{%e|TE?xp9Wc z5yF0fWgrfC^c2T?@ILb=P)#25L$Tq*rd7!CvNkrTNSIR~Ho8_W%*+fe(b{n>83}@7 z7EZLu^H3-z7W$S7W+sc%aHNHs@1)7}TVXuhb!q>f8yQ|Xo3DJ4pjl6V`>i7Vf~ahx zlD2W)5;=>fj*M>0$;=Rn)xK5L_Y#^q14)hcLOarNAM^!(h@z1X^H>NHKw!wF19din z@+YLrC7WNPO_L2?tqt}1xiZ3Uxy+9E4J*;SD;c4cUiVc=Xc9U~lgi-z9Ui;oe8*auV zo4(pI@|*x=QD2{mkbs&5s0(0|eZ(Ko&SDdf>q-~x4U%*cEl$^;`E-mk zKrre(LuDvrC>teSGEmv_H=J90RD)~%Z}tk7yB#+QkCnDT(asFnhAI|0T|B~qc@xF~ zD)J10vrWkg23AFe$n}L(;xIm;bMHcPN)dN+stoBR3q#dlncIxyz(_8FL`(g&2V?%g z)*uwj6hRx3mQ08?H$Qk?zg#<|o()l05B%(LHus+y!yOXb7>8P&vlbCnD=lGMP)8J2 z36)fLaU8c)=}^8wR_)*VR_CA9T)XbS04V?MPXU2~4EvTOSw%lOAfXob=5?;pxxueM z&48sSFPk2&IEEI;XX2?ksO;*c%`aNPj}$12C}h@Gv*<9C;+9o*cL@@q8&KZrY72?g^0qe<7S;=hY=M9t!$g zGEh{!nE@c+25d0@^te(eG7K`iiLH;Xc+b}q!K=qbAe)D3vWa(;12r&Ul5$b^tqno_ zPn+ZXn^JEr&nz0m@q}j!77Lo0MBv$c1bA2UU%szOJL~G*YmTxLB`32Q$87xy*=a@H zudkR{IFU-sX~k4ky2-hgIcUebDMu%e0EXx@eop>1AG=Vu$#87#J=F2AbC#!w0d}M) z)mY%7@IpJZXk9>1tC12;wPt5-38sM8&1ByN1l<#+WCQ&A&0?B?@mGU zmJ@~E(^Fb*Rm?W)d--%YnIE3;jh+qp>M(mOGC)u}G3+nhb$9lR>K5#1pKEOI)?Bk2 zV{5Whil|JfDiy}(AaM(XO~_A|RmPU{+0*-3d|7|gi36SPLD@6l0Es0IVE5Ua97+%Z zu9ubSZHH}MOX`~q=IvosD?j_$OcEsvGe*Xb1ZP8}U?4!yB26b#p}~TFNtg6(f4(d>j*8f9{M>LWNp_G`*hL$`&*4TEoxTs zpM)yI3NYmQwiX|B0aKCbbT#0KKfp7=0l%})5m_BBBW<i^Bcf>b2sZykOTrP@qE+r9_^(K;L-^+Mgl8I1pA0B$N+(Y)!$!^10ZZ*IhXWGW z&Ij(<$m)P_XGP!25FT4Q#(({kw24l31T|H#Epk%J1UUSa61kwmwAlUmz@#d$i!>3BUJlIYat) zJ9-VZv! zKw~-a>JhYw^VnN(1*T1XM1@&Vy+H>o)FOF%GIja zp~;99&C1&tFZ|G&8CT;I!0+~c9k;GFodfL$bco7Klk-gzNxV%-U#-Z#u!yqhm*Up) zD83ZN>QUNdm;H1FGk+83ds z5zKBIr#}GXg!xN!OCLfU5~dIB_8pl*1o2McAySD#Wd`KT!m7@ zR;>S>g|!}KtGop=(@jQ*TiFk1A3F@WiEA_4NK;v&nh`?vh2SVj#IqMM8U!COzLzrkxdPt|-|=6U1OTt<`;+!*z5bUR_sbLM z`%#~D^C9G1Ws-FYA|Toz&0lPIu$x2T-)EUIQ_XzE>LWVd${RPL#`TM2SAMi~$$Gp+ z1Vm^*S%~xJA0+i1KqIHnKZugnG{;w2dVX%yKOxO$=3;;C3I7RM7MA7J#&ejy!PL$j zeb()0(LooJ`Is8_o}@H3WdT-at--+rfr(?04@o zRrwXxF9|AQ(H{wo^%1&_@#6P-l9=;PrNh39XSmU_<{Uf5o`Flp$Q9#od;aiXH}v!I zVKuhdxss}gATJ3>cGBl)i=Dfs9S{pAPIIxYCX#occNbcf+u*1xU$erYC^4*Fw@Qkm zglSJ+oL?AModhM?vcOY{(&ZRZ2mD2tNR%X9=P8|;fDK_Bk)9#D(7q}qBVXQag*`oKV86ba-@sY`6ovs5$4 zFKrus1$d5UR0!bU{=Vr#9@rXX0bbG|=c@fY>*dm`)}h7EE&&6385Ir8kKe;l1zSr8 zz>jD)W3Q*fvJn{0huI2`$c$Ww#W6yOc{8uWLKV=}Wzw5$|4a$BAmjwR&TJ8HK98uV zxCBgIBMI+r_-InQ**}hU$6>tA*La^70y5QK&{5J{2)Hkjrp+7=t175Qg)Id={gJp` zJOW}eZ|;xfrjzupLe^553H*gmR~A@kzNry0--W1&eH<3r!*i{z1B+#n6Df7@QGG7_ zPA9p(crCJz0M?L!V;mFWVzf)@IG6i+V^$uv4$6t?m@#)tRAvwU2EkjqjxhsCQ%S|H zyn}D^Yk?h-@v3*h7uA@*!c&_-+{c_;$GZ+AhA4xCN_C{;f7JE98_pXWiaWJN-wLPS zOvbfF>ujpYw4(OH4;aI+oQxC{+!f9;{jbDr4ph08-M^kYwI9oF$`mQlW`Nqh4$|m5 zp0B*0v%T%OkF%ZGwqqqA2D<|cBt0y^KYn=uxD+Sa+i&Q{z=oRedvBFu$iQurifls_ zjOh01YN|?NKmKPphdX85^ktNud~_7jd)^C$qEvrW+*j`-MFZWd+P?@_4qvw9@;E5X zDcKsoR`E5?@FI)ct)=XAF^cKSwAgJ=#CwSZo)-0p57vEE{8eGEiXkbcWQth8OHS)5 z2L>Lj>O^SAZB#~6ySQsfJ@B?Y10qQ$TN62ud`uQ8~Fj*9AYAi=Rh}a)@K%->9NM1DWU; z?=&W%?vIzJs52qe;9sK7n@L_WDyrlcv1VoK^4-hbcCAQ)w{e!69g61K$TfgPmb9D*xO0uH*$^`i?=zobMaVkV0Y+)!t6ZRY+vIKIuL zD#4Nf-8P4lugOY=@V33VUyRg!-S3?gF_KXjveHds4McfR+KEddNo8TFv%z@SFw6pxmn7(H9PGso zzR;b>J=AhXBsJHS6^RpK0QQqgla`9RgTwkns^sxr(aJa1gv1yb zrZf~&FqAyO8I8_>H6#7^?2Se0M}3gX(*okjAjVgO-uErW$>H@UhL8%$@kwQluhPe_ z=Shr(M3@E$tPXLfc}rtu_UN7ayN)yqUOD}bsXjS#hK?H$-#yfvT=y-{ zFrThF;R8B?pID{Dk!4K95!7XW^Z)-q)@$@QQxuT3z)`0*v*1(dRl?W+soLis;2;8o zj>F06%oHSBIug4DBmy@T2_04!sruVwO|bVxd2!&arwzkUWT{)|$gPJNJ$SK^)c7zB z@C+j=7yE50!1bf33r8r>77g$dJt|69d-7Uect*ewu`|;mgT5T$d3qkGvQO<{qi*vGZH zerWO~YRbQAf@=oKVMCBiNd_R(J%_MgW&Aot#d|RSHpBQ_E8$R)sLyI!uTZ@vZUe-8 zuFMidmV{8~TNgyLvt?MSWF#~_dz^k1xIR#HHz)AF>+oEztCJ*Fy#95>9`vRAoT_%6 zFIK0xJaM853$u3$?{9E_<~*JD^W*q@B)HClytc{@YUh0*_`0NjOHy!C_MQiDmIsaU z)6U z)XzZ>37)6rn+Izu6383{m}JVf+<^0V`|u7??@JIFPXxaGWlYB*#=ge<6h6ZWZYWAn zJ&D5P6M;im45VAkw;}3$~e*0Bv^t?eS+> zjoVz`7g;|@T+EVfK)XUtarVzb28sH2vL6Uwz9Af6$HwKbjbH8j=Lwxa&%7SLeO_A}v zo0WylWTv^9b)>WBTpv(@+6Nb21cpZZt~+vKmV=sOr2r0hN#!8<82re&s~*eZGLvVg>1WwZHd<$e7^=@HHHJfyp>&mnn_-U4MD)GDf7I&Ncih`A5tKzu$<(JmLLKsFGJA`Hs#Wpz^=dyPh{#P zG5VKRMTjhU{mf6x+Xc{0uCZ?hAK%m=-!a~L?*!doc`dlLx33qH=mz6gZS0Gd0CYzf+kF#F>M}{H<`iJ*m;P%=rS-qNUR?aR=!+9o0UHhcHcPAqEXj`_2b-0AG#T2Bv7$*T|x zG({|cNy1r&bgtm%6t>gz0pR6VW+z|TY{&|t(4XW$h|NXY9}{NGXCt!%4Ox18v-H2T zX-`Dz;q^*m^=@&T1MIt5g;;tq(^}V0_dFqTKVt@rLQ_9({Dx`*qR#5ZF6-jQ4Uva1 zJSf>qIXUWhNWiu9CO2k9C>vjP(`s z&1cr^crM>d1`$s-f*?`IHKJW?%{Rx49ZDpM_L6bW&Q2F83hG@)XJ)U@x} zE2<@G-#OTW1rJ>k8R~_l35iPImMQoU`_unZq%&n(<$DZVA=YKP7A+73bBu&;sXJ`q zOJe+MToQ5EQpya*2f^0zt&abTbSO=z}_@ zNR?ad%8d(~5Z-|J(JqNBv)^N+P>D;ReZdu) z>LY687D0-r$m<(!bQ-j`-MaJ3>mY!_LdG2fToXSgM>%n}wk0T^>JUrHRnC3>s}nI{ zzSO2?R3dSkKy5om&Kcu!^B!rsmfI@ z$5hV3aA^atR7ue!NbaBX6cO+5F6&;xt3b&?5YkuZxGZiAb@JSN#Y+mu1jMUnpgMZJe~b4@cla#4=<6KBX5KN=kE*~c#L)SG(yBwhOGcvf z+E|p>OD!$7$YKVb>oMdb`WOYBe24{lC{wFjb+U7KwYau6C=&FayQ?+gZ_z-CcjVgF ze59I|fsfoO`JbHC8q=7+4H&81I%IYlC!^J~F-|Y#b>57KxQ+8%NZ;u%1kX1*S=>dtd^_-33%JAPdLG(-~X4!Xx`7^XoIT1vm$$)b698#mr9c9tq0*PKmVbj28rtQmFvfK;!pG zBGYDGUgM}TTO`x+j<6`v!}ENUzftB<%vZ-=Lzpn$LukTSw9353a1Q|zIr+6|^lOdQ zDR!!VG-CJ^D7Jh<&MwWoF5(rGh!+Lh-LKWJkM<7Q^>crh%Iq~iM6K4JlOz_Buhkk$ z^gibRK+$|IHOW?I0@9@}@Ru8{DxDdT9136XlT(|D-*XaF*-Stk#`MoW2Q$%c779;i zwm6qX?7rKS|L1f0F8zen3L9fbt_F^weQ`VdvF9kIG4%-+2u{}_nE?O2#TZ^2D+MJD z^Q#SqJoAaYd(lc|7abLmbcBnk$2(1_X-or~IdP4u!?A%Y+uO{y ze?B3^WS>8UwTlSmn%<~VB3N%r*w8nLR@R!vq*GMy78pIJ0R^}{L@|57Loutmf1mb+ zV)9L60(}bb8W(%&qR3HLa%1HuL%>!CIW0TgLTb0#xqXbWi4O{bPInPK_gnK(Eoe$oJxD9P)b50y4n zq&z0Q#Oc?)jT6L#X7SU8NGxLmlU`rGaS9+l?ES5xl74L0L#Xznc8@7gpbcGxJX#9S3BXfMQ=kLOonZeT=$|gfe9)GhVT*= zZ#pe++RQDSnztRG5slvfk=7Wrh)jF~J64j!K5~F<>_3)*XquK08@V|i2Oeho7|rAx zB!GNpGNv*oWSFWpBSe&99aRc|_=FCzI~HTb-H87!Ca0+u?oBq23;575qb>E(rNy8z zj~a!)R{g^y9*OdkESl+g`_mFe+$sXw*noC*)bsr8H7Tl26|rq7wevgpkJNqsQ0n_L z$Dj5q6{DCYYycFp_Rl}V9AK!?F`n3>r|@kFXDUXkX!!Sl#yk`iBQanWGsRBR*u?4S zn`q?8=8zJ1i53C4Xnv0*bSD`{y%y=e zk=0IJoSzrqaM*=An2vJ{(VC(+f7NIWVa^{5e7_1P`f1dPZghAiWcz)2wz-@tBj~m| zMIQxKny|Sm``U6a%r!fROvy{;b@XP!)Lo8j1;o>ZOB`r%WZO%~J;e zs(M@zXrNOnM)VNofg{{EGmRpdCIwF#kY!M{=Q3&AEY!O)z#~2#28Reyra|5Fn^LhM z!g~65G6g6`;C2{@q>^?z8SbV^7J4E#esH(3X?jPrC-pLqd$!k<5=xu*C~Jm@F|8r` zKY^Qq5mpx<2JSU2S&wc684-6+2kxp~nFbjln)8hwFC(byg%4;JgqnjA+=$gk#}>AQ z_$B*ql$@PEutOz26)OkS^&si>@5915p*zE`Rz`og?;^nWNl)|(u6K0woa8N5he)c7 zJro?L!E9#C2DxivtSW=R_UI&{%|yr4uS{oUj2U(2>=6m}21RO{Q7NFvAj^enXFSq= z$sKfCr#vD5LT2n!XjRw6|%7N64g?N`FyF^8za*T2EF;Ab7dOZj8} z;BJ>(o}Apz>T%hZf4#kNaq#gJZXWt3Pw#-%1V6es)B{$e5Y6ypBl=patLG;!9Ckk{G80CV7Cc#W*h%EUDi{7$ z4#JgQwjrGO+<8Ay1euBsqSec&7|>6DS$}u-s&<}d?@`4-+#eukPj`=mA^WRM{+>KX z$S1??99&dWeiZYZPrW_1LY`)MMC5YOyjLNt5H2EpJ-*#{>sDgj5T5nQ*4h}=pGHP< ze-2!BT{1T&6w28&5N7nj7r7xBA;Mc_^upDmFtoWdUB2_Q?B=~&vQb#s_(V3fo0P4+ zA(tH^5b*eg5h^ZQs#MGf8d>)z9DTclmX6bgcUWEukbcShS$2XpPFU^m@YXsPd@V8e z^c~3}SQDdrUgl}Hwp5v>SfHQ|`e!@sL6~zso+|ZAiZL2W9R!L6?6Lor64)UchEhL* z6krXDqL@6cmA8Uk!?&+7?y(}d>PU^@fCkIv?GD6ZQS7^wM>vKqR{aolx!sj%e--Y* zYPK;!Xtp@4zCfhiVYHqjj?9_Vtr~M7Fqu_an3F5bg|{h1FCU@uO`Y&T>^Nr*sSJj4Z7e zPhV!(5H-~~)0mOiS# z>yRbILgwHjDge8C__@#+OQLQFZ`asx<#kI#ht^NysJ+TE1FXX-8R}>z5e&do=t8F{hAy{vW?!%8-C$s1F4|%%t;^|Vg3fopiEJ2E-}8-)j5Wohu9pO_ z%o8WpVuiHv#3StW{76r<*!K3SMKJ(GB<4I{V6ykTujebm(%9q%STsLxn}zPbgi|ZA zjlps)s<4givY5oz*Bsq&O+fx;GLZ}Jdbo82b>vmJUAbeQ*$7h+AUOIF!~poL1vo)O zN*F(1QqsI-1bF6Ypce!mHv|eJu*4QtL``rb^yb<^XGrSPun!AFuc-)nyV|f1N z6-9czPeXkf#}t4MfmGy4GmR`bb~jmTBl>j*9ga$OzpUmIK;rwRUwPjkx4mb3TRvxZ zKFsvT&X7D`l{8Ox^=+%Lms$W%m+WRJ?S_EIs`${zoQgqvQWx=6x&qELS=IB}s&FQ= zPv^4#B}{39U^Uwn9@hu!w8tz`!FTCmX>~NM=i>fIF&}s;?JcxAd7$`Vp(G@#(vXWhz z>OG7;C)p90)=p+y{WaAws|C}*B_rBo<+viH;Jiw~nLaENH)@He-_<*Vz7GS%N7=yX zRs}{)unK&%D#F;o9E4aENPEN>aku3r%xaJXjQ^xjt>&L^aY{=ZHdaaqM$CAmI@tiD zaK{yA36xd_XJr*@4mMVIIzoHha*tnIISY6)2DyDgpITsnyvZcA zKk=0dac6S&o>O^sRhR#EXv4bSBXE1{7(Q0hB7qN)x`e!dy5!37>Th6dV-tYqCY!;R+wNx`eXX%ayKOv~C>j3RN`gG=Rk9xK&0E3M7eAv~)t@!3z z0Ls0*vU_>%P*-OmbKb6Sc;j|zHiAI0iZcl6>Mc1&HehCIR2WS3fCI#l#+Xq6D~Lsc z{Qhm~U)lG2bv)B>Sa|ukU1g(+)qre)t1e{)J`6((Jayn90RuRU;@S{m*yJJ6+LUXE zK^p`$HdweH&l*uMHt7*UhyjskQf%&8u0h6Rv6I!+Afhf5A^_$zBtFk3?W3cVMNLa zcUDCeRa8+$6;<4NU|g3I@>1pjK)#ZuQU~~BezKJJ%+AhID5M;&`?(KYCaWgg*J20w zOW<%~7&Ic0%I%E**a!X@b#1v*{i`qn0Uy2n+JB}4yXWY|cLL4)wpCR$CP)>+Qs@1*^&2!o%o-b_7h% z#>nqiLf^m$i*{09YZV?VXcx_mxdzO|4)B+NvO*rpKQs~+p#cFXNt^QC2_PQ4_HgvI ziOLDl*3Hhm{-uw!Qd2`dU$WnO{(Cp6S3Rg1Xst2PuYG#6`qx6t%*E*I-yfw} zHMAK#RZ2r%852oL#uH?6EUdF)fRQPga8Wemq)jX%(uj`!w{I{+aqh!m6xp-INp`hw zK6lwqk+{N>29KGxbSZfrpNNX^J=k4rV_qHDoi*44R|i5AiUuegn^vzN)R2i~(@q9W zaS+M|uv?7uz|lv^<~l@MwrmmC^6}+={1YAvN7TQF^WxxlDKEp}@Cc;?V0@8szOtyC z?3IF*Kfqs^UzL7Y4l2zV%)|`dH=v^CA2->57aldiFwQHv|^O8G$qNjh$v+b z@aI0`!|l}r{27lPsiV7(X6Jt8pn8D60(pSHe;Eh(|JG6t@K?I~94H6)kJC&j*Xs;( z6c{YFa$j7Ncd-679s?vgTWw_12{X52vyCJl6dxkW^rDb9$xt27+t*?6tdjL{jf7XJi$5y_jc0p4vknAAjaIXmigU>R*Kcp5GiiK?i$Yq3<6L&*}PgUq@{1Jy0R@KF zjy5}WwAzJ{=5k*^C_P%5ZQ{%aobQqi|FLq$nDv9o2od-Jz5s=dF@W;D)icHb%P-@# z8;Wuj3hJMGypgtcE9-0+GXCL*V-$*~gkj~EKhj2xTyE@k{=4UgX+|}29Ny-pXC7@9 zzu!DHL&wg|3lAC;_EMs3k5aat(8GNgACBYa@pN+KMjtx6Ao6+M>sr6 z?_T(k`j>)RZ;X+sjQlNzwP%dcqI4eQ8)FU}d5|1VH=R7D)Ne6k%(h*Jg=dTmJ64J@ zrr7)QjWO+;wh5V%hMQYqjQP6)#+YIpt{P($tgJDnw0>n>8e??lCs`CS#z?et-{Q!V zky4E@hj!)~@+FY|#bZ-67fy(CtdL&z@xYP{GHUtUyw>{7PjBLNoW9Wn`1|Ka=;nNc z-(jRHeO7LNY1+9h%4t%fKf%(noy(ISa;<8NajM3crR)BSp+pm66)O!KzN=NNEC%eL zg%Jk-%86PPRa8+$6;)KR{!s3DD{Bb}UPEYUF=!1jz#?m<6@%HFU3@xRExh3Jkj>E| z{)XFrF+&WHh+`g>5(oH0pyqdzUyGZm_)$%RGZCKfoGuflZW3{AyFA2l83@C4)uG>{p^y` zFTafPEFf%9^!bzA=cEM9%*BOK1;9Tzd>Z{W41dZwH%i*0hib)dq=E5VZgfnhh^A*^ znfFN`Yz+*9+K_h$StgaG`Dm%TOoz6=MtAIfGl%wXeVuOHc#)r2J`Yv~$k$rU+iGEP z9)!66LYNK$Hb=+y~m&Eghj6zzX_G$QE2Rlm^HE(VMx2tnr39LNu& z*P-CZ#Qgj`ojZ3<{i}4KQ6`hg zobX~WsK~#uGc_0tihqj{+}&W1!44a|vr1K}QkAMyr7Ep2!gvm2O#T?Z7$L3nV!?(E zZTQl1fp;$DJu=_G$XNf@sbcr12E#q5E^Jh@Qwkr*8#LGc~6{6qZ(4t zk7(bwezANZ0-pghcTNX)xr_4U!j%Bc;2?SRvu@_&k$r`Cq(gah;c9>)YMmhToWPQ@ zU49uwY=0(veP}d7@16J2+vj|Abui3hk&-9qv3vVN;@&*V+YtBhkVW+G^V~1L%VXH< zr)Fpj#us&HN^qi!y#XHAl=t=VyXDv;?4?qLwy+6lu= zn#YS|4kZ(DI(ykq;kZ_TW)NqD$PJemGthPbZ5y~XD8G)10remu##J6O0eKxBw$js7 z+rA~R;Q6%Mi>S4wm27;^Xf%<_?N#(d{I|iuH;syMdU85O zDV~y~LM%>vxk-J0Bfo!>_We=i{Z=wkObvj8_v0SOXf$WupEQSv|163*o_Apm27Vsg zS;O zv^mP~uF6I4^$<nCUF4IbNk+<&}(A-DhInHYt`R(k3Y zCyy`sYrq|wU37K$NeV@qSYBOJUtiC%YUB2cby}9@eK%=*@}in*{UR1i(iHdU;3>uy z)X&cDTH4g}3H6D}pc1p-4g) zIIvj3q7@5}=0=N9qUB?EtDU;HKSIGscGF8Cxb5>~PQ6P%IuRhR*UED62AwTZ}lJ$j=UP9cRLnb?1dCTT<4SUQWo_pn5J*F+lMN zIqdAP3xg5Do4H&{c(I|IVd1p^afV`FdfVg!@&pB(1Uww%`7i(sCYaAjrJCJrq+fWp zm0I{4`M{Y3U;g$@n&I(Ji!EKwj1uqGhAAtArPon0tnDymi@_l3$j1L}+jNLLO?S|q zJ$r<5G9RzJ@jRWm@H%bbGI~AtQDf^a+PimermnR(@y_4zeB+Y%eRC{Abvzg8>bR5K zbq8tp?%mvW7tR}Ae&g%n{YSRBSJ@ za?XtT#3N0#W4nInr&571W!Ka&Wtf}Y>M&(mVD6Z|c}YSm$9uScc&-9r%HC4Ll)>Q8 zyu>hNot)R@hbarFVak$R4~v8;Q+XxAl=1ivWWto`w6)T}^L?J5zVOmG%~l{xnKo~= zyoPCSwDY)Wqn@r@!`V;Ym=fbS;FeNpTJ9#2UAq^R=+921nke z8$&Ovf2~I-3_)AJaxEychZpsf%5*8ApS1aAZI zOq;KK$Y+-W?fa$IMLD!sUY82(yY#+S3ZX4)-?LJX?*|X`@}VVcn$RQddsZT^Fuq8_ zc!#{mzHYr>YK9k-voNSA=cZsG0fp2(N4<2{5ii}%bPp32sp71OaDpCxut8kkzuQfF zce+Hp|IzWR=ZY34Q=E?OI71H|c$*$NSe%aRyeiT#8^xlge=sBzl7$R0PzqpIrQ-6R z7CXUTKQT+kcu_kr9A?=u<``lCEUpl;OuiG!H0^FsZCI1_gQexUxxqqhP248dogoIO zQ2pRF>#?er3Fz9OCqY}nI5&J#F<8Rb3PTJQy=V_o`MMF}jjtRO0fJHmp|hrEW0{@O zO98xBE)GRhiqiLw%?Nt^v`@Vj&KhC>{_L1PNpD{83;NC*GxYVBCg^KF8P8lh-5<&r zVt@s6nkC79$q#0LzNNj*E({@sFv&a{n~c(|CWMpNb+7ip?Jaf+b3ctu0+UnxoW@&2 z3*6I&(}VnK4L496OGAuA@AV+PcXp2DJ^N1leg3jf{cF8p>2CuzT@N4EtkUg-Q6%9qN2D~mZEr!Ni$>8%Ss`oXcu9J+clBn&b6 zz*r(emT5L3;$QrI>C7u?>h*@w_*ZFEJ!6)E zay?_9IKfWRVxBSOV0wC*7y8OMG6-FU9j^EdNCnYSA$L+B{qXRx_`Os>f!W^Po|$YQ zyc@iIkVi=}pXCAyFBq!;@OE-?Qv6;jkk`)6PW3MmVNCEoZC;lG7|&{I6iYb5p)B=) zW&jg9xB^OfLA{QTkLToRx%>mRY}q0VfWXb0H^q0B3goq=rA4?c0w^zdh9W>gv?LNVGfDG1_)H?O3}T z3hyfC9ca599UVDscy4a4qWnYK+qrY6_`RI|26;rglYq=Xb`VafoU)_uf&m()#ghWtSe%K_wA+lFP|RSy4PFpzC{IrWPC$o2(*e>{H? zysQ*ZNAeqJZ)0O);`dU4dd9mX1_lO%43^qYqb(Ey#yZsVN&);_iUFyZXH0#aMJQVV zgcQ>%;h}u>^YpW})=Xw&nvTCcFLt%=+U}y^(FDOwzOh!>nf>lrAMM%UqD}2~8XixQ z)6Vzm5DqLvSFVM`ZZY{CiG3X=`sfF;eg0w_c+Xz)(+`dZNV5hJ$T!5?^22(h<~A-kZT|7(YR6$DqPNu$hIOY zN`%-!h%6XlFjs_k3&K8Nu`hS})*`eYH>7QO2ftT6W3qq|M(b54fzV4Rqc-Ne9;9cC z76_5jqk6o|&BIf%$h<_A+m2T3iZzKo?7GGy1dyVw_3T)HlI6d=hN9;s1H%;zEeQX$ zXM2t4zoB@-Vf~{2X4%=XRhg&3&<bvVdi?R&;(QC>Z1vA#WHlsa;njCB7!pQcdMBj&Ao@_*{|3;gU2 z+QoU>yyaKKGjh(YMKT$qq0t|3y^o8(;ThAyedM0K|Ag0bY1zoZEj&j8%{y zZU3R?A)}RJ9N>TJJ!35NxsPuazstn}&lnx=!F-hF8B=6Jk_Q~%|H4ZX759vhXsk2y zIFh?bYk=n{qQ3e6=&Ks*mHTMY@RUcJgG?Zlu>{84R+d+zX!lC_@EqEx7R5YcB(4vn zXl6zkzn*&3$UQi8C2?NAx_KRF63-%yL^sd7My|z0h(w^);~*@LXJv#?V>$#ouHwk&&_!UkR--27uzQ zoE;x1pVmkQg(j485@NE<&qzK9Womp@{03yc!RuH&KppKJ4V4S;{hKlm4k z&hg*Mq(+B~(a}sD;<;!v#CcW*LHr$w z_$ZN522wL$ci8KcJQp}*8@uRXKxt}H!aRU?g`Qmuc$aokJ~A?*{!-*K9Px9#`Z=H3 zyaD)TD3Ub**;JlNML1BdK>{e$hQTk$AAq`xt91v|Xxee1x zv{b+VAfau;kw}>4e3Sew#H6hk`~$+_`AmHSGT-1;eFH*qC`w&v6e|ZM$6Z<|kM0B4C@=?zjBFUos1J7{`_+gaQ|EsbWD;UvBF z&Kw=wTO*7+@TiF=3_LM5)9hS~-aqH(1&n3Ef^~s02GGxnfSxfX-w=a^I2K=spZ?5a zjV$9l7f2g;(PN;#8zH)SJ){^_s>YZNj0%@^qp?oYe)0iX7anJ^v`{L>PM*I(oofC8VT|!u z=$Xfl=&mu5=G29Lp;!lCjM=-phh=QxM$%L7O;X?JNJ)IiHO92*7-N=J=T&1&7Sb34 z=ow_thq@dFs;#y1n3)zE8YCYoV~m-lx6aSq8e@!FOks>UQ3+#A`F&3%jWIB;OF5Bn z^0;H?HH8-7Bl?Nl5M%IM$%bmv%A91_<_At}&*i$-=T`A*jc!yzIk!BoA@c z*$DSHw!DyKW*>i7tv6|msc&qhhQ>A;9_(F5#+b$PS2f101FR=wj8>s*FeJ%c`;PjT z0w_>0$OCAIP@(`H=f}mr0F+7PLQWS+6x z4~b`>pc+Q_PRK{S*q^ zpm-AAPFddJ-6$8lf+Q-HS8dw`td{FEK6PF2r@_-gJzWZa;2AeM{(ZH+)3m+kX~9!1 zDwU`FHjHw^C~%|yH1{P+-PuiP+PCMI#eMK}aOfpUB$;RFI?i8~cYriNb#-;AS1Om+ z9Aiv$f+ptAl9>nLeY>9HiB-L52iN;w=6jup)+f&C=Io(v}e}`#WSO0m&xlvDAL@vyINR|F=k}yb$b7-joV9t=Mc&P z$1prJ)Gd4;T;5T3gxA5sWn?tUWj4`WhdrDJ80*u7Lsf4KgsHDTBz7j>b;v6gVCcHB zSh;W|C>CRz+wHu7RN4g$C0I}_*BGN`h{57ya3mr^N*vf-BaBEe_BGYxjF}|8`qr%Q zn1NxX5H_YU1}MVZ4Tr*IMOGLJK8J^GEhXIEn{kn_6D>x z+IY^qupLy5F^Ym`U??ogi?eqyJi&NiXE{STVT=K9z)vU*U|`XM_RN?^j(WLowTQG* zX+1NmcrXF)otvlLvFxUfdhVm2ykGJ9>}<0O^jlF$iPK$Dh$xrXN?8u=?*{k7;D z2rbJPb7X4`&)sw9^Ag*-9o$xxHhJQmSA8bCh+{~3IdKMLAs`gw;G}YPO1Z|E{VWsZLFspK zj-xp5EbrVdiKQ50NxRDXlhs} z3wp*Fc*Z>P)X&qaFFwBxj4`F>t7?o{2Uw~xCV!W*R#{UCK#5XlCp46&+FiiTnoDFb zM)_~0Gc9C{35Oaut&Mn!zd(UnE}*D`0uc&W?XK=Sc3q~|-yann((YYZV~oReg=*|K z=(Te}+SayD<*(nhvI@yM<-0@osT%ZgzmSwZ2U+y&K{>aFW+rPtl~J zG{w7Q`>JHyhQb-jcFDip-NQ6A(o4PLoVSK1YHWW-T!%4cf7h$@xg)=g%rFrJMkjdklSjSx;EcUR;OYVhz8D3 zBzTs3C(_(jjkK-3jjoMkjeZi4J%mIw8Dl(ARxefnsB6><+DkNins#>CDQx1W5 zu8g#^)kyY+?AXy{|1KT77^P&|K-(KlWOwhNtNjZn`Hg)ypFd9X{=pWuEZbQ^lcNK~%hUi;85E0n#EMJP4$L+2I6MqynE zD@w>b+B6KZvf%Jmfaion{%fkn7@pIQD~gmpD6E-5_uo|~$_t=B?Y+VC2kyH-;3YzF z=|O9Z`K6Dv>MC3$p8xL61;&`)`bD|HY@yKN+^;W*gXpt$BA-IN%U!nszN_2kE!q|q zeLw)b8XM0}hOqm5ocr=tmXDp=++>)XA&SH(+R{X!NQ%x}@KMhuCv|PAA$RS5o|`#n zYWx_DPw+UzJa2Ec^Z2N~OvO@-F-VVaaCT?AFvv`fy+@%&@)uBIM{Qgf>V~m_96{#j^ zj41{vEIZq5JU`9yzZ8^Xj46hu26##f3FM`6}6@^ibF(x0_U4v(sYXGbPF~#;gV^X^eqdAQDydC>DMt zc!s{iW;RkSf1|mgXg++JWY-K4Yg2lGW)-zf@F zlXsZzJscyi*DDmHTK=Jakgv|>S(c}9k+)bhn>X;n>kg2`G@=&JwT?tHKxo0B_B9bAs_h8!JYH8we4NK}yDe9xqJI7-Sx07U8C;=q!TRAvTf%eec&UUq(q+-T)aPdKM37_l+maR$w4 z9^-n&cWRuxm{;@QazwNBP1*VePf_2O1T^PS=NCp&P@mFQAd}Q$l7|ijeP00}7=4g_~Ax04U|KScAe5hvC0@a#n;c!-5OE zf`So?@mG(}(y>#s)Y~5xJ05p!bMgW`O(SD*nwm?oTo}c>dMDHL>e*1qbfE-841hdh z*Z9nAT{++h`p9RT0mx6>^YK({B>+Tv>^p#^$(bmxrK9AZeV^v0j&t4(LJ@{gaN=$1 zr|}*q&&xnP?T!q29A)*3Nr*4gxgQTd2Lo zuKOG)o^RNY)s#olpj`|o7rf)Jxl&?kIwsnF6^jF#h@gy*MipLTZMBE%5eNLkpfU@& ziLVi6s&b(Rj6Wy?`dYUuyOw~LCOj>wP=Iz3kH*M1?-%P>m(wUV!9Q?UE&b}JJLyAD zwo+}4MbN|d)bq7Xaf z4}JDy9emB4bKk)E+PTHG9ibeO%AkCb zN>hnc(n*PU9T}3_sL6XTHP=4KjWv5_N-mO=q5vh*qdXbEmP4&A+&OI8BnV3BXCIj( zlleN+VCH&bVK?z>PcFxGiYKpd`O0fH zP?SP3%%7x(?wFuBf5+(<&3p&mHV@npqQ<%b=JYjQ#8@)-TKM;4cTb7y7IR-tnxlIH z)KojDex*Fvt#DWL3f@U-YikpH18?p=5D|G!ru!(C>ZAG^e_-$JTk`o?j^Iam)cwF#QUIhFBj=_l4b5DFBWfRz61Gr@W>Rm>poF`TAps* zoaV*lpvbq&)}Of!o<4EU3|B}m4{ukgr6IAPUnvEUIX%9CU|6_gZ;(2gZiw%vSngWu zvohDS$x4TJ4U2nr(^ckav$zhPK5!(!@8&ctBVPAhCJpLh&(^|j^NRt7s?LrE@ve@J z4m!9iMzyYM+#mK*qbIi=-+SODx79xGOM7{OWzY0Md$uO2&V5a^{r37{@jQ$HOGRUY zOP6ox_hNAqd7MG)@Z)o!x=E81Sqf-#|`>G!7@ZPAAC5-?{r>GLwh>J7Ew~>TX-d zKn_n2@tCI6cOQ>&@l2YXTTNWw+`c(Ydws9^{?d>lKezumGMeVOJ#brSkBHyN^je+p z;yeSTF7)ChLx~9Q7YQh2wFVh|DdnbO6R6m&RaO#q9+c z&ar#DP>86aU>UsqpkL@RxOZD1kw}R?4}B+;q&AzG$7XD{ON;(1p!UI~3R9fdfT`rt zlw|%;r&!Mv0zx&yJ5bWL9v9Cq9JG78oBMaW7z?C_0*p!MdlvxLiWXt<@_|p<4G{30 zG+=BpO z&r(0j7IwnJi|qTaP0}}B9HUp>nWjJfo9pyv|KmD+`MWpiYn=8%e~=P7ULB(|alSv6 zLtpvcsG#rsY@9+-r4PVZ^piKI#r3a#e>6AE565V5O5d|V0{sdO7$3fg^MVWW9dkW+ z9bxXH^$ZZkVvPdcZs)lX&*kz-yJ@x<;616AKA*IkVf60nQ7N7|0K8N5(l3W3!YmW; zAc0p2fO`(Rfi`zIXczaL^QzHKi()*%cpy<~zEOt)vZ?A3L(b2&1YjNvSwW~cY#I%P z6yxKLEiQuhk2FNWSd*V#l4A*>zVN)Zk6(3Y_%h4uoAHTgL4qfY1lBuN9=mI6oq`uD z4^2jk0Buw&H~HXd*F}9}8?V#cB3#+pKxySI9hG{IJ~sNuU&Rt(G?;l{%-yl7kMcT? zo0EmZtN26uN_u~=u=3s?%(dPc3`Sv$(jzF0qw&I>OrXejpy1R)ELOM)6)aDI>p-Bu zy=c7fcM9cAfqp#&LJO_lW^*=l+(Nz;?c6|wVwA98mlFw z`VYPI`J@dcg*mg{Gx=1iLLc?3mwq{fase=|N25s^pH#f4ME_&pwF&==dY62Zu(4<$ zbfVrnK{%I7VnM#S-_j#*4W}ugNnt&bpH|8Rj4}~nm6sEBlmwy{JnGk{c4KUMs9i63szDJs@U)-Jb;c)=^I^&DQlv1w^S5+SD|~;^9#d5Nlee_--F_=kn*lrnnFs{n+14{G>Rc>VLernZ$Lr* z6etf+$jDZVr-gV>tUQI%lv{U|#7r4wEp#0y%%8$a+&}??P_Za|#!V&y56E>^&Z1r)4@@X~n@Tf`8$R1_>v83wLmby|$yg-|$erh?O}Vr_phBl1#E zPI(F$I)QQwrzI=cZV~qHQg%gQN93jsI|ai@v13v~S!`w(lqe63E?R?3Arz{Agy@k5 z8D)oAS}aguSkWWglM6zLQVcONloCQlU=g^v!zPR}Fbr+!a)>zPRY~{qd(;9e??z<{EcztNCSfl`hO^ckT-Z3N>9c@2W;m6;!&_& z6mBq3>`6r{z7N22hf*m@BScIvEK=hfA^-|wY)G`byU1jz7v3~DC_KVxwO_&Y3^X@P z7CU+Co9K=^?x0`!m0zLfo_mfy@rh5+Q%^lbd-m)R|Kgh2>LQD^@ce%x0rd=JKF$!i zJ`ke*p|CI}D*d#i<)9Mps0=WdfP71W*9gL_9@y<+*-x^pC&WBr=T;Y4ZALn}-y=4b zghFxQO$iSI%r6k44C$p@N+6t3jT_;C(GR4>8D$Vfgw}@V*`_v!;Oo$6gvY|9*vx}> z?%L)S^R1aV#Zv|IAiTd&$ZO1ju&D;21u?%$^Z)QHjJ@zGOQ;)f1o$VsmobkMXZIP+ zqO2$n&hL?-%Y?EXKlAA}hcMtVp&sESBw2#+^nUK6!l5uBqTfR5X#(;;~BD2V>^~eCjQT|i0fbh@pT8cSBwu@T97t}v>UTlf$=%- z*Z-FE;4c^3dmQx02Y-|9ee5%|eeb>0(Y2e}H!mcwy3t_uup0bbIV`>cuA+*fK$p5w z-Re@YynGZ>wpCgoy86iFO)-z2^@w717cFCV`dX6ee3YXU-e}l}Jh)xzbz_%v{Z0le zfv{?5fnlVl%OQ3lD~EJvp^YgHV38&aC2jhLIb(s3!|laFRJ|qv#pLD=7)kOCA^P=@ z;_USgg)$yIK&gfpDC7X_V&2;ABpk#K`(ta&Cku!^}b#@{?^+xKC#gI#YFS;*2(wi`0?WujfClIU->e1cWtH{*ZTPS zyA%v6UV_*S4dsvGsc07MG7?cjBVo6`6;~NtRO7m}i zOaRXtOgL}UNG7vW_2r$v>&R2m^x;T@0^ZCEIDc@6`f7|mwp z1rGGaSsUgBXDLPD&5~EVP&h$2?EK!Nwbb3|Aa4yk<%}ZC9(dso#Dx+cUc(5T34;*c zugzmJnG&Q0>J0UTdc%0SwaZBl+*wZt_jtrRuptG;GzmPTDB#hK(i98?DH2xNc@XE` z$j=pO@VLAb+JJx@pl)EW@&{5}w<+N{QCsICuh%Kcy?aNEnBz!bBht`Fl*Yzm+)u}| zG`Wxv7BbB8vJ!xi8}CQoiEwX0&inXOoaM|w-dYcrp@t@><2)9?KxbrmgQp>_$Qd$C zH5R&SmuGpzGOkBY-Q7UXKG2jyde3FaOKqOgJRZ^BV7SFOOH0G*Hw~M(j2!O{X4^Ys6Qkn^T^&^Z716~}dWQ1aoaf(ML zL|=kU2GBn(wO@fp492-{1JgHz*d1(ZdfvEdJi;z<4Uo6Y(eL#!y&<(YrYw z5lUEiLqYL8!q-;rVDf^3QgOgo0dXbXxdPuKya=!K1;m+E zLn9G!z7T*gy$H(%0~^qH%}j5dve4_t&Gg!vrh;_rgpp?E5)@k?o0WkGWyfti!LmF& zTtkC{ZaVq4nZEPG6n*;#NkOl?VWjbK51l=4r_*O`bnb$Q=2^}vjoKO`J#t^eicoFs zLc@yQb6SGuYAKkRi;K2*V=%;RFSniRLkiF8!{tnn&BEaoe#mTj1*aD;F@tbhO!olC-J8MqQmw+SK6?;fQdrYm-CAxS=mV zQSJ}@ni%r%+<5WD7wPil%fi3{#1%bY2L5Q8LK@{cj5kPg;=~E+?CccRVroB&9sWrk z2d)i-sP{&YeEy^eQFZ*CSz$mzXd^u7!8rxx0Ex3%(O}_4VUTHe(EeQ>F@7M#Tb!jU zo;HY3PZ%4(L+GUEeKCqg0u&BMXmm0v?m-D!D&p}tee;{&6!h(Hf1Cd3kN!yT2zd3? zSLtv5=5NF^pp6VD^(Urd!Wf5eJ=?mS%>No;NQB3PG{``as}J4EU6a7s5Aj%>0>13o zaX@>EO~@A%>Q1MXnwx8c!RG4qAVs1nadr$0FST_}s;hI+=tPtP!pM@9H?$Ral!XGy zSt1fJ5DG6Z@!LS*U|2i{Wj)d;zF&$w`sM>d$t&kT;=gO3A`VhZBTc9zmbAL8~jOkr`_j~VO{ME;&JPSV78;*`=g)eoQ3f(w zh*kjgUgdm9)Fs+X?~SnNJ1<@hWIV{wk4b|}Pj`a$?v5==`}andJP$7iW;5~k;_OXxA z(W6Jj-&0dlViJ3+XnJ~@LZJ{vqnJGA&7iBOVm(5cOIERFQLUgVs;D$Dd}G(5x>+#; zEQT%S1f9S1n(iFnR?x)61m{)Bs63z_J4DZ33n@{+=|})VNc0_n`zG z-5;lpWxonCQWSHT2O(8|YU)+LED1k9ab9+SIrL^XdXk zI~2B1IBLCRWHdXO|1Lo$ql?>-QxLaGUeLKIkunOSChB|>k2iH56Mgf$gY++c?-YIT zlRs1GWkLV%|GY>){r+|OKmXvp%r!0j#_zmE-}uL?^zCo-(T6_us_rxL9sk?Een(wLYJZg25mUoDp%aG}pH(s#ptHy~#rrRa8;MTEb7?n5Mq|kT?fmZa#NX zJLd~iBr!nY#8qApV@I$4d|xMNDI#oB}5iBOemWs zRu9G7LAkJ67Rm=?>BxSsP^iQBu&)U#O{b+|TI zyfI%J7!KuZl)-#W>#>IV^LXs!3nb~(>3LyDm0mep+idjdXIklh|CMff8s}*2^$Pmj zbM5r;Cz|Q0`x?l`=>^+YhV|P=-FeWfURfC=Q%<^Y)kQyirGftL`8N9LTf6A> zcMjY#^3**}`?h~bP-E>=RO5JDkk|PHc^pS+c6y%Pe|Lhu_53yZt3N+O|MAby(qI0! z%k=))84<2fOR-o|$U**fN%B6t@bvD3N_|Hm(mtCH^kL}ZML(avlW<9p9mR6qu}rM; z=W}NuRV*7$r;~PU-^87ykD6MBDUyDlMrY5FFVaVD&p6f9PwLW*5ry>bfo%2=4~C_? z^(^Nv?o#3fP10i{;$d87n$-Fcg zm7UEG7b2XU#~LFLjKHWzLTHEqLwv3jm;d$q{-*0OcP`NXkj&F z(=6yO7`&|2^7$pnkk=;xkU9CC{PCs`Pmv#)#!x`!Kw3afGihjHJ|y62f(0Cq zOwUm;ewIQ7%2_TD&)nf~kju^UhxE__iYA9>F3?YN!G7@@*CL62n(b{`t|GTm4$#Z8GWzEWnQ2hoSlyerF^-hHMD1dOF5TU zrqR6l&K!N`C*yRj_Y5^y|AFFxZ_wG(U#4r$Vj0|}VXPqnun5SX4{c_14$eruKt4Qy;r4lwCEd}5?!uR1E zrGXKqVGuT6#l`#{_3!nVg_let&!Z(UpVb;nsN=Wg-`_t44H9_CX8jr=PFthHKO zy>$M}42=xuu5s53aQ@osCuit;FOJik>gia1-z@u}TZmhf1%u!3zr`irct|FK^waNt zgkF0;Kz;o|8t2Xv1Mlwb?t(j*zV?FhueF%RHrG@tWh9T=N!}U1bm?_az^({p}tUn+iphWZ2#tonmaPrZRY_jB#)U)U8x^jBZGi5Jk*_jzgW z&aCV1>5D=7?y))QaHZ+jKC8qS2B1UyOHPAH!2<_eVuB)Z;cA$^`PvM%In(s(zmQD> z{PowyXgZLjMthn*{h=1&hMo(pI-ckR*UL-q_{e5T)4h8f^dL`wB>IP=^rat7Q?nyQ zzwohEu{%nDU+~56Ow!HiINh<`Mo&DL-34}YB1V7ry(y}P|J52Pk4>YS+u_HP~|MeT= zo4}b=ot$_}TG! zdh23{?4}ewc+f?6A1S_LVVd*&KVFz5=(oD-h<@=CZR#DhzQ24^OwyjZ$CFdvr%ngx z#drMF>P*o;{cMMNRjKd4{_2>Rls|gZO^5e;)H?`q!!mN*M=hM@*FUSum74Lt{>m7I zc{1|g0cTF0FZYG%8?Vh%lRZVh^2yfB;h?~Of1U@5V2bYDZRh&t%&X|@57XCwHZSV# zb02HT9PkNz;ad|lF`uNP+pIbDJ#aHhU-|JYVGX#0tMunJ{LY2sG=Kl={H{P+eCN~8 zHs;9aKeD`Cy_ulB9Y*@-2OuK~re+fKx8Io}mpM(Jc&a|9zQ6bK44vtZ)4ulHG_&&w z`hQ=TA_u2=?$J8x(j4UaZ{}8_lI-Rr0LkHd3yDHlv*7L`lp}C_6g9l|K*p*D3~x( zgDpv)`)G3xzxD9q8?$t(H%?Y#njSu2&#CY8SAz8IH-lW?Nv`jfoJGKY{fBXyj}YCr z+eQ!Go$W_NeZTDIdPvf*{d{hkzhxdw1=DnNtA*=3+b7%@4AVdS%tu~pihe0C&tKs_ zVQ?lz2fIx4!N(fat3-n%QTp0Tb6j^R`pgG&>-!t1@3ABu?lRIdnl$5+G5X>UXSuC% z`+lm9S~d0k?H8x%!bpKt#2I4`Zrt; zh{>Lx=eOROrvcc3RRgybLrz=K1HS)XSgz+|M)95e`u=)n9`4+t^QnI`~KFCC+Xr%#gNd%i{4tV zG7iBQ^Rw3t6bdVHt0+56)ZE~uEuGo1V!6OvV8-X83%!HtmC}$*Dz#GMPSXB8QE}-0 z^h}&W+!mbb;&DQ+>J6%0V%#gdqltXL$MmP`Jn)r#PTk?sUxucE#fGf8ZMT zM{<;e&(KI% zD82xA={0H2VYr>qcSGreq4RC3Yoe={(scdCpa?gHP-8fB9^NrH#J{oGOq;f36^rbJoDgMSG^*9>^X>eu?(r?{qBTt>uk7Cz14jRYi4C!%FitLsy-iornvB5$$ za=n(1oR=-H;at11aHA0BcXhQ^n&WydQ9` z2Y`7=OH+0{TWdf*Z;nO8JO^zL9w6|N0Z?COF8IV;w4+ri1H7dGcmqqoi%OoMAg|Z) zT&P}EP!HXV2t$Mx=oeg0MGoK<3-7Vboyxm0-pl%dE(W3KHVTCNFne9hFRd{L`V{n! zkRiSG77PJej~E>OkGWDl@cuIweWLx=xU%zG;Gu(Fy8kYH&o}`6@V9?9L4hd3sTqWU zW+~9CX8}!nDh2Q~@oKz%U=S(P?v?_C-b2VZEpQ+^&ZPp-d|^2A)}U^TbaPzU*d@m; zcp2f~egN_guNbw-3&3bJr7`%Rew}usFm8YH$!2mobL&Hk7hjvA)7N+n#QjWu`6~tR z5WEETb~)&|C$nq1e88ah%^!`?WFXGvAdQz+`4Hdd`8WO}Mtbm(c5a{H1?>}_ux^dfw=gO`Su76)vH{tG=ONDa z!5ST7$#ai%(>;%UMSY?&$ZDdhSV1h_pj>KygaghB5|0^)RElPN0lG0fN#}cq>CN}A z(#f-ZOQsWNdIi08`YOHo-er32)Oq^Z@zeCuvG-_f(oZ;75Cr9lmewbf*r>|_zo0Uu zzx6y^n1frNr;@NnvRQgI)(KxLircZwI;gUte3UphTO(7r5>UCEVhoPPvg2_oWuOF4 z5^qk-X2$eN(6M(f(b>yGneUWJ5>{(U7;J$WUVzp(4TOCo+6g;$NJELWT2wtFW-Va- zwA#vG1pi2^afJOZC|k@K>ZlOwaLP=%5el<%1-KCSb480a^WVE}+<1wvav zX$*zdg{ywWIK%S$#)%oBT$Y;;JUmCJVtIfO8pcSiAqIc}6!!{keA60Y+M3}Jv+y~{ zGUiNe&34t`3BxMxEEMQ;FhaIjUk=p-1GL3jplvP@2zQntQwfCdXeA)$y(JRP%*h9g ztMGV%AqKonBouFUc!G~j#)TmU?cv5?h{h+PqEEzz9&F&j<|_2<@P5$(UNTw_8N4qL zN{S6X@C-}^A~gS2FZsWFirQZ~mP4NnUZg*58KMqzW%yqZQWR8i@Lw6FsTa>u;u~+| zE3rnhQ8mV_5q#h=qECEi3H0GC zedL3w5-6EN&*jlmk0of|o`9f3`$P2c52pn^{diLR4eH*!Ff7>Oz+km-z!K28Y_lpC zwO$RC!SW3<@?gy6ABJWSyUQvGnI~Po>121gC1~YITdBbAhvh+&TmETN7l)NNl+LV~ zcP{09%l~o~4mBohp~DAP~PFdZxEDv=vP6NKudEC z{okMe9eUv#U!lMI(pTtT{p){Azwz7ug1+&c@6ngO@L%W`KJ|?HWEQoxjr7g0{Wp5y z+usyv{^nq-o_)e%;<~ zke(S5PSvAG3p|tG*Wj@6e4|ZbCP35AAE(F*$Eo?mdpWfK+6DSe?+Dcym*<57+sB=| zJ@gFsC8bgiw<*z5^~6G6W7^Vcr)TcxG$qo$9yghFj4=b;U*qs{cnb`VhG}eq`vE3+ zQG=K04`6(OK56$3H{E@tR-6%pesOkA=_}v?FE=wuz#!Aypx;jXKRZi_%R^+C3y>+1 z$RURzMNXrRSJ4V0$+8eTeu)etQ)Ef%=f_cYo-~!FQhxZk^@Nd8B7;;4tW)4@H8HMf zNPqn<>ue2R4P^yb87)c`O9sM|tt=UG{ns-I9z|lU(iyjI29uTl=hZ1II-_9EGue=8rQVH#E;A7WE_)j zgtLL72+zv<*y${x-AU{ZWcd~jXL$qc-lpo zcfhtDr5+Fp4KgC%r`;_W2xfn4Wh9ZxmJ{U{hf4DzsI5g=TtQCceFk=s7A zd_X&vY4WKM^g49NsjM2-hRugE42L7-ImG1@mUe z4GyNqZxBL~VGRsJ3_@q;dvjCoP(nl1?%xhG^zB>%rkfdV(o%(nfrHpXy-OJ_u0zk zB&-z>N^ajympBt9l}d`ugFCjkM4x~;GS*1wFY^JuW4>B8%4hp6fRvMb$^ynMgfGN6 zS;eh`qRZrQO+yI5sX)K(ZW-24Rx8i-%5%~;Pt8y$p`?+3 zas~#Nv%O&&9ShUb57yJXKSl4K%N~vl<2TYknFC$|SFVMr|7KX6V}eZ`+BqH0HIM_> z$@k_(#|>aY97-6(85xMzf8>C2m>v|#Z=RebKj+cO*R}6@_`Z4?9E*vaJx|)m;p3#G*Q8CuVphwiSUIp)=gvp%|epG!<~agGDZ3E=z%Gp9j4 zJaVsc&H>z8aRx&qX%N?~86_GNcIJ%Xq<<*Nq=}JiHd8zEbjKzoPgkx*c;cZfLL%U) z`W=a*%v*HIKYeSC_HT8FGXzd>IWTbnV*Gu`#S{0}(GC9A!%zPqg?yK3YWQ39<2UBS zc{UR8Ai4XfmwAfaf?-h)P<)=fsGM&E1UV1jTYasW4)Q_>=!GJ1B*OeKh%+}N_VQ#1 zy#4X9dD`4!rajwTbmn3}#54sUQ#fk^X;2QdVN70+oq~)g!h!Q#vTrO5=(r&Vc$c~c zqgs!d7pyfj#os%1Hb@_QNRgX2-<}gjCLqlGL4EJs;>gG{_!s2K2kH*rmk{k@n~RQ} z4sgbk^Z@g!e>lSRr^pqagxn)dH`fDX5IA+(M>ByG=S#|nvcN{n+cTE}nKbP!Rxx1& z-aY51$@wI=ku>KIGFU764Y*FfbH*p?0q17`f_JLd&*lCIUE_Lo@;y!SDhMUdMv*sJ zcQ9V!TRwk+W?1yJ?}9^G2S*;ea4ri{@H=MCY!D82ed9fp~2D5u+Dpt}z%XWf9WH&_;xwwlW6&tE?=E82;f z<-=t+u-wXVBO+uM?GDhM86$yyFM@MzyjZ*?>HYJ*jNu(^14b0NyC4+K)oSv zTA)6&iZFd>7yKxP))0d+QfmM#7niQuc@C2;s~%(+HH1(*uv;0k+ITTs)FW{bEdR_H zZlh}PZ;vx$v?wk&8xN~c-nGP1{b8zXEIczt8JiTNg>oIhTzVx}f%fa8LhNkSfa$3w!zD{5G@}H=G z5k0_j42SDc+I7c2$nd*bg-80sE<+LjZ1{%OLjEq&&B@D%{B^} zl*9fDV_{pA^~~KMee%f`&Zn{tEd}3yX@V{c1bF?go*CoG_CL90D1PouK90XVODE3H zQ&hW?kAbsOu%7JU^>s&^L$q(46N9zYd;C1k-^99Z-!5KPFw>#$N%7(Z2AMvVR~U97 zztA`2pF<-d+X6zR9p3Jy9Yej;Hx#6IN7EGKu|W^+!&}H*XUi#nrJ$9QE!<{1>?vxv zdX>&jq^WNvC3v3?8w*N$*XGQed8ttP$vi`$=N@KhZlAK&&y0EF)T?yz*ma6W7M?}6 zUe1hJ2z?p6r6@B?knM$M#&pp=k9}2rqB1aj{_~&z1NCOZy2YNT$Wk> zJ;Bf7Ir%=B2C89v6J_O&W~k52wYm;HkLJ?}E}8zj;<5-i5Nx^1lEEO6~iUx=@~*oJ&$Dnj&Y7 zg>3fhVixzHG##IgX3}ZDBZ;RWB0n&2pnk(VUL$WPKknn(FxKFZ??{|^95m4I$R!$| zni6eCmH{MqYcPp=fHw!~ZpN?Fn|ub4zwu7w6TA(E`FZU^Cn)Hn$2Xg z+R5QG3Z+DdWlBDaenI3#*141s&a?J?H6E)l9*+Au$mBjulQR>1HBR%~zU6Zup8j*a z5HF}vC;SAL14gJI&jE2?+g4@ULpjG-#xeQUwpFw}JcG81wvRq>F2HRS{867leWM=m ztl4H}-tn_R6FFT=ZS4yy^X)i{Q&b8gm1{aNs=-$!*Ukp_aQCHGapoB z9&JXZ!S_)fywhqok=bHez#p_9$Qe9e=D1uaAHEG4z?SUPVZQcY0ArhWNm^i2MVnJ1u{150od5>ldp~ z-VMr9oH-(u?dWU8LGTQ$TeM1ethMAlY}i0deE5h3CaM-$&nr@?cGX>q~*$OoA{w`*$|c%xr*$`roDDf%g_r!v8bs8_I4N+1zU5 z`DhFE^R?l8x=6 z-IU&VFqXRb-BGRwD2lN`0%I{0sMzRY?S+4?9IvYsJFd$+ndpCuSsRb0IubAFzqV~&UUINCMlhKRHvyyKXsbKLjFVw}cpqY>2z z3;9Jfn?mhdwgr59cq&R?dnZiadM`wmr_yw7R-bxyH!diDrJ$9QS(c~4`4s*6cPHu8 z%@p+beZolGmI?1dYaJ1%-PDgni)K4RWvy@6? z`#p(r*J~?@v|O+-TH9RI)vat+rifND)xG;w6nXGI(t5$K2aIu zN^KRl3340wYBqNaK8O{scko#`Xs9!DXS?*l1rx*VTbyFREK31WLiRCvSuPgK8z!ch z$mg?jvGtDAVWiGB?9|dLNcI};cW-uz4#?xlPE-*4KNws%c$5O|!b91er0njpT6pm} z@d`x(*Jx}aCU#Tl!KfLaq^o~Ew0tWx>DNP@cj>aEpM%0ce&8X5MPvU^L>N2e&Uchs z3-GFEbJmR?3O*=d*AtLu99k#=#Q{7tmI@Cq%)p08yn!0qA0wNyg(tM-EvAHQ@&D`U zT6n^P#qP>4%A^MYltTC|+AWKwUK@lm9gA{D?HyFt`XHGt2*+U)-cfo4j|Uiv!Izqb zJH0Eqs8V~mX}5`$bJKTLpgF* z4&Y^mkZ+*&7X4jVX!lyBS)usPsJE?M+4niPug(XQK3+GJ|3(U`$_2;~#x+nruGn_C`OhG?1;v@uwxiIJh6Koo`6tPqCH&dwea5#E_;#} zyK_A5&5MmE0O|rp$RzF)hS&1wbwMw_d|4P1Bz^y- zadMkaXYS`yz3mvi_{uO{=Vvcn^$X7>toLeaY+Pdoy3!Y*i&y-@pj42iiqnKjQUM5H ze1*4^)>AXUYZSb%B#3siG?_xZU=xJ+&7YO2;pGwuM|0*ynO}>1LV9jgvC>Gh{9s3a zR-Qr#*-^!kF&m20JL5@uxqqeCrb}y|w*pX4;Dq9IO8lU3Fhp}RK5-pDmw-MS9@XeS znwmUJHNuDkBEVS$mvpw6(X2iI#M6-!uv z$dEJ`^z{_6QW+-{`qV-$w_CXJqka&UP7(|S64+&p-523lJ=M29KqhkyPhe9e8)EQH zX_UgwFaU}~0N<7F;{d|!K%s`%%X$a0Nuvth2gNYnjol-%ToT{|>S5l`3s+l*C<9#E zi$N-IvExd9rx4%HwWSqPLD{MH&`5Y7Ou_yFosySPNT@(nS=n%(K(0n$SL z@mrR0nIgO*K)FgW$e=t>MC%cFhqBeyWnIb3-8h19YLKIl?>x;<9j8QWMofP5<;2YL zRSpo60&=L8B`8v4dqrE2JJR$*X$WH~f7fMa*awf?bxK z!f2(fbA;lM??rzO88F!Pk-P4&$eZ@N639;|Vj_q4PI9=rb^9ai7Dc(yk6_$d4Cp(s zyAX1pPx*jHnIQD@ObCmkMaB@L0{k8wkLA#{{xDs=78d8lz`%@9t&;i&!#N5>ln?!N zF#_)}Hfc8yKw&w~@5VU$*ntPO#{PW(MMyKctPT^O82@- z@R9`d(Xld?`egfzs8M{=Pzn7-E2680!n1-ZZUf{_@>Xif2Ul*i=M>qfsr4XP?9D>)si4?b z^;;AMJGh^_fjT!*fv3P0uFC zVA(-NOQ#r63wdu81C;A{|KzNh8rz>Fv$b9vf|w5|q-4I`PP2$%541KRo^H&3%82m7H!D9hRG-(vVd!=i+R6@Hn zF1U&zCL$&*QemwH(&OMq00WpZQDHgYXY=y|B_*z>&F$p!?h(AxeoF%718}wiCgxH> zn14Ql7Kra^ci2T9mB&D!&^JA`UF2}qlhvU-R|sYnOBizCc_fYTg)lw^ zLrHW2X#qta`X)i+3Zd_j$T!4{@WKdV4isJ>EG{oy4Tv)dt`7vo0`vSOzxWR138a-F zjBzkdqfaYF*ik+2=jUyRldsez#wJ7`xa)|QM7Tm8#?jWy<~q)cmvA=B;}522|DGg8 zq6Xo;w2j9mY~;X>SmXs^8=4zfJ{ofS^3}&`^}^)?A!D2lgPVL3T0qUy4CSD&0#We_SyNEkZD!psW~! z5z^%1RllIC*8=p$NuKBM_=vDv@aRYR13VYfdyg>0sB1X@p^7%;ooS*SJIh&DR*?nf ziSR0Ihp@jkna+nvo!RHq!`Tn?Ow zvf|*uuf`!JxpK!@K4h2}DB!e8?0h4DTohq9l+}hE;3iS-a(RkA(d$tTs>7jVh2A3% z5QcF8gCZ1>m;gX&hDCsc959XPc~KA1;DBC&T&^2E zJdhB|4BkdijN;o+YD>=~7!kCJLOr+4d0$~AGZt4ps=)|KJuF=C9bi&(xS#|k*;u5S z4Iz==WZWmNj>|K(L~AyzK5OR zFa}_EKI91ol)>Sw(i7z@WQf7;a2UDd`%o?@mWOUe1ɀa112Q!Fa;0i`vb0ieXp zZHvppV!QYjGsvJ#Aq1YDj7a$W5t^Nuq`{l9O#J6^0NzdV0t_-G^Mvd}c4eOCR7HeV zCg3@trvSnGq;fkFO;eP1P>i}ocr_WrS{fjb9+PincV|qzAN3-Y6r#>YBQ!HTK{K;{ z5qb%ADbIn?1M;4X&*m5@AS>kp<$)0hhLf4Oq}VlBE>N$?S2`7;SkzAgBhh8m9p0Da zHIFZ#<~s1JR~N!a0r4CRT*Z)1PEsr~A>Owbl>XMT zz@WDh$T!4j>kuB46RIpfbZ@QjRJrT0S9q66BdZpWb*&d>G5EOMpzlODF=^n(w`G_@ zzaRZ-n!f&mk*244{Ix{s$bm2~ZWV7soR1dep#sJl@C)7@@aVzViSu@iWgi=K*pw5?-vB@e91_xpMfB_t3!zPqPiOa8hok@a+ostbQN;s<6 z5-1zOsu*ED0Yxh|%!zXxM#8)fQ;aJObvCM1&&a^vdg(zqh8WI&{vqd>|7o9DiL)PW z7vPX}%&%|sh3N8`dAf3Dj;@}Yr{2p!n&Nr~Cb>@hEHl-yNgt5;Di#8LPaU^+oMjwA z2P@=9Id1}Ubo3LT&Q_%_l=qc2rt(`^Mk~MdsXVM#Mf*lH!~hW0iYTCm0sYEwx0> zr7NJIe8EH;hlv}SYbj~5($I*0hX^BrJOcoV8yR8?ibd@%B>>7M3>tQ8isIp`l!_0C za>FfksQ}NA&TI&X-SP40grW@5*)bu!I{4dI_%zmA#BXVkf%2(I^{ByhD8&$(B{cUg zMWcSPs4E00qQ$$0BQ)=e@M17P1H-wC1{~<8H4ebakNUYj5E9|WuJwl~kw|5B>4P6j zfe2C4sTg7qdm0NW9DFCCU4Tj88xgJtw|$-h)5nBD8RxR(1CvSc1AwQKRJ`L``8)UU zUBIiJo0Cd}7Zq7d%B1lQd4drJI|Mu0?ZUG~D)`|lFM)3tGQ{9rxDMIJdwQ>jghCod zBpgCLxXAohBtfc_vBTUtM$2gz%zy4ij7+Q(}eG#66fvXr`(1ABnF~d$VczFzJaU=_p-L&|ar1y>w-Rlx`WQ&CodF>B7 zezDsRo+_AH27-#A{?J~J=$qgkyYi9@G746%F}NHip=90M>7-3<4(jH$i{7TKVkl&Y zncz9E1lB9-JX!NK-dwC=&2fG!!HsuWv_3n0TEg4Kj0?_3_Hd%Ao1yTn!r((oc_-C_fF z$5ms@N};rV=9UAyc(B7%t6&EzoqZ^cp^Szy|HeS5pchIhfbtBxTD0*tO9d3114AL< zi2-AQ45xySQTY%dS=zJbdqB}CLv3jlw_3o+1SOGyf)os=%ic{6MG<)B^GA6?IHq1D zvBN6gAcJS6;RKTaoN0pJ(zu`vrv=6DwSh484@c+*mmf-CX^_wY?7({gybHUCCwQ?F zi)9sXSTI7t3I4#?(0e^7-UrVmc&6ZBOBhn%H6!^Z!>E-CY0N-bAgA~{drkjc$oKGQ zROCsbt;H&KqvS)D5#thmBk%Z~Z{(4lF=oR&`Dfl1#Ggl>9k54z=D8O7_0O~~pbtKpJ#(oT z@Qz>pxz?PtE|yi0Q)eNCIfOL2LwSV$ZPtgd4a!dD{7nfME8rDa3L!iX7GMa~Bga&y z!BUpe?}g=`R^d|g|UsxpfR>9{c*KDtqt66^{~q2 zUCqxe>>^eH8%KVy(FvZO@StvKwh6;_L%o%{HaSG7FDT?M_d4kNFH%98n^)d-^%~K! zlge+Pqs^9~i76Ye%k1Je&f`3H$-(_&_P(TAkGzLxODAlOz?^1m+)S?=Gv(xOWK_+N zieo3zIrsDFyv9)!efZS0gU(%a3OaMaNk4tvNMjRO8IT4U7&tJu$|cOVlsQ+W3E$QK zW^r275Th2YMPrDnVrlUCc`Z8x(LO=S9mCpV%yDoKD zR%e~#uo$V%YM_68znQ-BF)RJ}vo_uQy!^4nWnm*5Vgw8Z?t50YFJDRH%c`p(HgMOw zP?JiNQl!mS-0SB(E6`A2Y56lc9udlET!R4ygzyB?@Bkx+a{fT+^$*3V zoY27VrWhn_6y|rq@KeYjCLz2=)Ox~uu#hbTtrY0Vl~jIX2Yfg*LxUr+jE6%$Q07g{ z2LMWUlpV4oy)C2>2Kmz}|4T8%Ag(l?5r!3;QM?;U&FMLXz!TI*?gCH)6rp}hLNT`@U>xb6`O&R?cjRPiGUF3T?ZUn@WX7YtPH|B}psh`f>%l@bbTPqeP2X)1ES9Z zu+tE2@4d4=a=YiKr`yMU{4CYhPE$+E9M#v)kk>myZT!1?lTZAv^-Oc$?9XYlGSpcW zYXuvxEf&Wrmv_UncViR~^E}LVVbH*wA7h$48?3pJueUpS4yyEHFhuK-MeW)qrWC`6 zG|0$MU*|5GxL-B#x=0BdmQI^^ehBaD+>l_PlzPu(Dlx>EN&t*O@1GMtbMkibyVu3^oOWP{#~BBVA1OhYyB|Mg;4vdB1DM0%>=k(E=o9WOmGa)v zRT)~$BL)!X@Th#PVrft|@TJLWNKzuj^9Q?&td1J~*C~uL&8?lsfzKWNbRwMP)=FYEg6`H(O z`ox2^ba#hQ80X5xhBw48%oZE>Kjj~_pa-q-rI3EJQh*K&=fSQxZi6PDr!KGJwuIV; zKmOnc>9>C4-_tLC>i?j-_CG_XPlf3GdqEoPjS0GbC6`)i_t7tZ`giDm;WVH6xqn3u z-uW0kcIQ6&z}+5t{HTi#Z7J8{TiT$4owx`yB1tODi=mWoJD9x7&}3oA zD#;6C1;#{woJcg&4*Grc^=FV^8#K) zFvNgAP-;SX4U!?tU^qeiI66$6P9)@UApqP%IWA3t`9roSz^K zF~~n;CmUK!JR(rc5QBxcGy=j913-}|4Ka{Ug#VGG_3n_suEdNXCSG|%jKoSAWWWzC zEfp}Jl?oWNq+t^EfnBNiCin~^2n>wUAcMB1C`@w8DB9svjQaXRq8??xy*J;uMdDC>9Bbf1}YjUsEcyG=-)VfC>x2I>GL(E_(WbdiAf>f|lon zXyXH3i_q7s71X$tdG>N}I~ZbsR4PgFNKpN&JglbiMGrVzD;QdVHSq1#jH||&DpYV^ z-nHd0?b!1WZQJ!Ajm&h>$@hbFxi3m%lPN*-v$=HOz(chE=(8ftrtUkaw(UbSmH4c9 z-L7pe+PTfWLJ`J_e1i#;le6j$djLu*V6h224(o?fQ-!Y z%dZl~K+h0^P2})UbJ-14>o!tA^>PAm9oN#yl=v+-oI@FlzqOPP7|HUV(bB%{PVsJ( z0g6=#+_PI*=J+1SW?uL$)RtC8@myD%m3DO77d$ITFU@97v$LmontW*Q;~id?!W5LF zxsK~Zb6=)68M4tkXo~DP$V%Il(=t1^-)OWLA+s{bD}QM$Srk=6%*tZh)@J&^lTT1077@x&5PribgL52= zMqZnhJuj9*Pys<$he)OjG#yUsQbc$4wlti*=%??$G+vbYhqz98?G{fU%x!k<94s=o zzc~?G@SZsz&g)ExekA|iwf^NP(Tf4=JFLI;2peGYVQusfFP3Q5;igySojLSQO*?(b z)J4g<8uHYvj4{K`YYK$U1nt{hBd(e1YbfS%({*w!$kQ=b2mRMrr+7YpU5v4_977BY zIC|^mwTu*uz})XF6}Qs(q6g?-)9DK75pL72)AaezfBp~D-&Iry=~SGqU;PIf7>kLR z=IF?w^uS@{I7?$K0bz1*ehP5Mp@*oYZ3o%xE*c&gqnjhcR9|0D)6>)BbULY}rG+{> zJIQ9ViGM%$tN)C=wMzVXpU+1j1Z8K`n2w2mXXlf2wl7qQT|y{pptOd!3-|?P5_ZEv zNmeQlwq)U9jagt9`eJ9*AP-O|!I%I~1L^Sr&k<>;CUyA-fXtdxZb6q@q=7$l)UL)zRv zUpe3&yPpwS$;i)vZ{S%;hAI_EFJt#ZNs8}E;M+J16N+MV^zvDFerTU71yV7IK^{D} z8WjTuXj_+q()=xW+~8h!yN$dxCYqRt3Ik0_9bk}VN4G+$21A*5P0v~=62I*J6eqNp@(a!qrpr~HAZfC3G#6=mpM&`wpwZb7CUWiw^Dn(nT99hya>-4 z3n0gB&J^8yz$Kp1(*1|rbSHmrTZfef$K%vHkewv7@*?-id%bjYmvX<}WuQ%s=1khn z%@!J-h*N^g2pNSOed=*9?bu|cy*+m7s5goHYQNXrYNZjL0LOXqF4KJM;TqcAg)}zW z)MVx|nD|*shPqoVV$zH>S~S>F^w41!9oS~4yY@OoY~l<3G3wxaJ$o<8YM~adQKXmO ztmiZjA5rdsjEMwIDpAEUZ5Xm9-EfV}{TR2YdasE#w<;bpQ?m)t)_S-+kx+scb15MU zNwuzF@PSMrbfc4H2a4&m+9N`y@J`4TW*?LMF0>=B%P7)C_*-}vfHc97iDu`_T%T#G zuY+Nk|IOQh1mzFpTwVuH(e4$)6U&v;NSoShETf#Bd5&^6c#Jf|>13ObdG~VL?`*LO znGbOL#JjY4$Fq3n)-F3ui!+^4)WOf!;4BaIeSkLaP`Y%q<@W1Mwj@2kvUgyso$lni zgREZ}ic@=&g+6?rn|ip;T537pjV2nM;>j!L5B2>Z*SD-YLp(uKJp9PE4i7LrV->sw zrI8n7^J2hwjs6)xee3mabf(Sg4(pNDI_^7-9_k;hXBkGHsZfJwl3MEh)HlL?2FnGWm4;vd z{k$~hJGejD+SN)!6ARyAGtbkxKF(V@n-*&-81G@ML@aA~?)CMDh35(kCVFUKdH98o zx6-~{?nMbo&A}=CF>HqW)PW&8x5XrF>WGQn?uYf1JiuIg9mu)okBf~C z0L~0_IaOov3IWQXf#I-d*J%IfAJ7+Iev983V|4|9wcF)hoQKH$=pvia2S*eG#(j4x zhL3*L5Ch{3e#2`O9yXCE(Y1b}&7D{asfkq}y-c^zcv4t^@J^(|zneRApEGecsLlH& zE)U*~?-#@LEH-8l?cSlh1Hih+W<@lB1oy9L9%D&_n8N%A{9hWClcq9+b!UEPtlP;D zgSI1q_JU0wfV_^)By!vazw+1gSnEI*0HncOL>``wHaNj^$eW|{^x+RYNiV(lQ=YT& z+yDzebs&ZzrmoRNEzEO^*(f~xZMI7BerJGUjiX%W5I@F@U(Q&Tjzpu~=t- zp17|;%$1Wa7e$)tXuhsKhhjT6)0w&sigEd6RE?zo??ygRLsPyuO>n&yqsjR=T^|Y4 z<^CXz&1A!YW1PUeRQAJI^MeP#OaN(PIW##RqpQ4jzjz}+z5K8Co{#%=oVi>Km=DXj z9yaslhd>wiRoT+s$688y-sh86-Vvtk=w1)Gwl$M;S37z4c2NEPTyl3c(1kH>J6wO- zxqc;q`azom?d*1wyWT-|&QHyr4yxO?Fi&x>n|gUJFWa^j(1B?ARH`8c1{{~IljSt` zozPvH%_}?Zmy2L9NartJ;Wb`N7-sSz4OMH!=#r1xdOJ0>I7Qcq@TGd^GM9|CSwztX z;+O=Kv4+PMugA(VUQ3-lpHQEu43@#UDmFTLdU|Njo;||w^0AM7O#E(ZYZLbl9Xcfb zEf*MnI^1d6*}|PS({FvEiF(?wC^efoAHVvc2KxAe9`f=uVr!$)G1^RNPLtv^ zh738)g?kdOHBH=hX$L=dw8uif`SC`f-~_hwwNF1@OHUkji2E&S_(+!}n?{lxxAZ0e z4fa&#xkvZg`JG-d?Xxj|@cTpexH9)WoFAZ`7cBCcBmj$BOmYDX268}Xb!NZufjeFF z^j*p>A40WF#|piM<~;o&pw%vU_Ot&!;C57p3}yOl6HckgkC zZ#=limU)*{_R2JpnsPTkFF+&n>e>5h=u=PD(kGesI0zL=atG)6zCCt&;;2j9_uADD zFrc`9^sr0Nk!`k&Ck@JZWSdny|4%>KNc(zh;*0~Jr_m^$KiF-hM-I7o;#62hfXS&` zW8daZJ9RMudgmG-Ox@xAH96i(cple4*e$LHtJNUF6y;M}v$9J(5=+zhE5V!z0Kz_X zX+j!p>vrU%g%L^%OyFOAi&xAl5NBKaJZQI0nq#Nb6K5ItUVfT`dkV)_#r^F)ik1L| z2H;X}kS=gpP&U2vdw04r@0KCew2B?=q|j?k(F6Nz^ync6*Q8mok*$v!ONwQR)9~{T9k6HG1;nSjfrRl1_wL=Td>aPeo>nvc(g*A4*?ZiA zoNAhU;M;PMApuVvJ$N}E4{^Wn;rrbp|7{IsQ8p|>Kgi$s+%vV}Tf5q`dEeG%R?5nR zv^jaNC-MAepZ1FTX_Zefj68AFA?|&E`-eh#&jC}k0g45SzfTJ+(ryff1^w)Vo8COT zi?8v5QKh-LIqox~G{TFP_s-2{o-G8ErHS6YynDerl8M3_B-Eio02?FF2O(V9N@Hlm z#(flz1KYy9*oQ}AO8l!Ogs{QC(=!(8Xmu1Z#8k0%P+I@7v2Y8@yrJ2=I)%e{jPv?1 ze}I7&o4+s@#3m(-X*l;0=RZ~&@NhxsG0=I<0r!Owt~zn5Z&*@#$6-Y<(`c0MMKBal>bzVX<`5#h3t z?V+kz9cYvlYaJ$&Nmy-22D}a`P(FfbtKh%m<7P@>%R~y4J4@vVGS>!UO2;BVKXu-aE3BJ3J@T zfIN!~-k6N<-RTx(0HE-dlQ*0h0^okByObf5cpmwfnu&|uSAg8z1_Oya(7zByhTIgG zuccV1PSCusf!=!GLEnGbEa;UJHVOxodpAaEGuJ^khCJeWFi=nLo_A%g|LiRr`RCmf zk7euo*$@6x`sLsL5;g7qiv{HD{5KS$yD1okSDLC_XFT@kr|8#z=gYcj++BY{L3)^y zlx?HH_U%XL=}-QxZW`~FKULG@%3EjWc6#RL|A%fGkoG&Vus6di&$9s^zvJF zaXlQYr?*ZsAJywWeAP;Re}lL;$N#=~%$B)#q0d9%KrX-XfqItS7jj1#yi5j0BB~s? za*Sie0C|zdqp=C4-$R={eO__T*~9PJxqZPF)Evk#Y7)ifKghdW(DdC1iADd&XjI5Q zuH$=!@(yE~7RWoEM>@29*>28V3<$3j+{-u6NyMX;yt-?oA29zV9edB2sk>L-wr8%t z#C7ElD0PSW7S~@^?p^Gw5!VBOg##>h?tSvZErPTL#gBimnSP$H-G67U>;j@s;d_ri znBBH}Xm5?U272h8Z2yC@r_%{xXi2A3*Qx?AP=dn#Ym`bBKes8B@KeZFf@UobHLez_ z^=zWLx~=4LxpD}*!|Zkk%?4Vire?Ev4rDgB=a9Vat?gOx4tT}NcW6;-O$mcF=*}HB zdSJhU?%8e6TmwntRi%IskXySQ;$Q6e^VXz=_i;DNDh%1UhrhMdwMpsI&5Op^u54bb zSPpK-y0`^p-q37b`NEBiD(AzEjzUgcz+@#EtJvA%Ids)U? zD`({bkvyP02aR!mR}5IYk55H2&zA$VYi!JFtheeC?n{U$9U712e1l9Rve4*R3Dh~w z)ZnsYXh)}m?mt*7sH5H{uGuuYB5Yndw6jLsf9l@GoU~eU=y;HniWgs1r9$*!r7p4pt=2B{l7UR*aazgiv6G*Z&HIU7 zI~Cy0)j(FGiR!&}ipGrM-sohC`i2sO08uWRh3e}Z;<_(Dbm>}*|ul@KL(P%)5&>{c5k;zphf7$_7%NlnyP%M(76MLdtggil}Qg&XI^kmQL%3qo5d z-{|d+(e%8Mrrv|yzE*L4W-d*a`U4`YjLBdjtJx~P0hY(2MzR`=oL2`$<0kR^xyv!S z+@BET3;9zj&y;Um=#6oijAZ6C&GimSFduMzbUaDdN7X~(O?FOc7T@ss)09k@xL%C3 zsohNheirohnJ`Vv5|;yEl}zMx*u?c&AJMt1QA%+6kS}eTfsr_ks}ll~krzzN6MVzZ z-@w1M%-06at9<^{=@9utMvC)zTU%pec{Pda6VoZWI)M1TW~#B{pm=8{&82H$^7BF% zNU`h%=WA(x&PMaIHj0GpJW#l3WWq`p`;2t#?Iev)qrRM!h&j3b9n?2q7Weu`EG#$7 zAHElhI%$lb!}W`OCYqedrkRJ|`qH#C^wx*TBnoXCVAI(qa;+Ozjz-87J+!Tuo2(h!}#G%CWB z0Xw!Iq5B{BxNe$c+DX@Xr@8(o>CC0!OvtgG?tS#gBcIVtL&h4qdU=v8W*ZCLMZ^4 z3?al6JlSA?80@bRavx=RL_X*IO5Wc)Pc$}VSMtvH#;0s7zi1C8mi=trBV4Y55#{>% zt411|%+33tn)i3l8*=hKIc*ntzjTfH$9acwGRb`-@{Z6a4YgL9o$_SrE>fiKre?uc z<@)HPDO-2({50G*#I0QBlu~!;6qiHk1D<-~)706upRBH(3kVZO|NO*)kXsMj`z&qQ zaffc27`L;a|0bR7jR<+iTB7h7EvpBk!9z~lUF5K~uncgW$FU-G-gxk1z!>ujA8Db3yIdl?9Kzw%Fzws! zqJz6#)ZM|day_yjyr9>n7`aLTcAd*GWsrOD9I_6h`K7A{@^}oia~qFEs@o#&p>NgF z%&dXN#tpP*XPU=j@z^5B&2K&++fc9q)i7l%jpB8&@o)>vTd7Z1un6UaDa(d+QNom= z-IbOpY|ugb1YwPYcNHUSq=2CX%Eq=9JKcLnz1VyNg*w8eVJ(P$3!4@4!vU288Kw+p zvETrEoV~KGN4=Q`8Kw+jz4B3+FlG5z$YX>k+qWxAooxnTkb!3p?%@m>gegPVwGTd_ zJhOWTuZ48_X}vIIT3}9u@R-DL4E+tsSu{!&TSuciMb&9e$@Y> ziee3FJ!Ublg98-|4vXP#p36S*U?c6{RU>Fyw~M@Po)7bQ)U!#6AaHXsN(t2vgnu5n zqk$TEP1M?Gqn%q^nY5CeJXahT<+*d7oC8XjvKsE=bUHy5FnWxsVU|SOSpnm&+-Lwa zvkdLrS~!9Qba9vZ0u*A|k}`$*0We0&_FU)XwJ!IEg`j7MS#M#=;)y8T7#*PCe1O-r zOWbv^2GG>xp!RmR7^fsbw)5*XgM}iz=7BzNHNun`{Lq3{QBfolLHgd(AE3S) zL9r_eXK(D@p10e64R9U{gMne?G{oQdC;x`_A9o3tC|NFlX*9+k{f8$r_ zlb`wwIcgeccxZ?wCwO+uXt(}*@$dD)D1GV2Qxx?#QX*E|BcdE6cs3Odhsk74k=+@i zeY_|sq|CsCqyM^t;*ru6KT81&Q=w3Z2kkW39S)xSl{e8S23b~%HAz;hn~a9a4=#%0 zP2s1FzhPK`Z$P1ka}dnd1P`m){2J1>4~u@il9ucDO(l$h``1A^%g zPa4g<_zlyRE)!2o&2;)5#bc_{fXqO4cI=7^CH2-VPtv0g{Q}iA@QPXk|LjegpSno{ zH*S#2@?-j+FPx{CsyN-Z`!4#$pa0*;)0Df?_sxz`aCVfg_w`YY?G^f;-+GrKNhQs; zE&J%#e)0b#Z}T?sx5WJHBqc&qbos)0sb-o4yp9v}chA2{lapOMIO@0c@=%RmS`sEiU@Z$F_*ydKeoUrZ0VeCezj> zwsX2){>-D|cQTcvc<_Dk8$g&ei@i(yPR1wcrI+8QW0w@85|o`f__l!LGPt#)$ z6`xeSal$|&Hx2ah55p@}y|^g!We30xOzF*wjUYXn6*<7+-S8OI12*MIWds(=a))M1 zlTDOsqXWtt%sT-n2cSqP9fj*+W8xN;w^E<3&^l*$G$Ir*0M1>MUY^?P02H`rOTf@b zSQtqFoc++$s9ayHaA?1!oGF$MtoPt~{n!JIqHn;k1H%xS_^WSDQ8RxZO2N){#}eg! zA>c9c!VeT<3=Ap7fN)>%K>7Hy>IDs6Ii?s|KJ=90mGYBU;K`zd7SjUh@$91yD51v| zN0!IPD~v7qxG|WfQ|}>c8qSg+`qmH9;@$A1DTb@ph~7V!rjI?V7;*A}@<@Xbz71m& zu(%OvrBI|i#fy5|L3=PdjGEG0TV98f55_70XLCYXrbTNryd;!y6yvLf$7Mva0H9FU zdZuCQmHh*h_R{!;HY)p(Q2 z?#&K7d1o!%aY*r|H(3{Ul4mdY=n)Ca3ZLWCHKYFB&?m4P>+Uupcd^I3=H{;8u zk+875dhCj6uhl#NorY$z_qp!!-f)zxO_&6R?-UDZ0wnGI3SnrB_N(mi8FUFJ|gOZT%X~*HEAqsthZ#0sQD=55!39shu@Vuhi+_a6dwI+ z5rNPw{p7WuQs0GPibt~j-g?0kkF?P*eo9&QAqvm&cV}rLpv-%;^}3!tV9*C%xfT#c z!ZsdTHg~${xktL_p2xnbK2aG|J!4h?i+aXL;HT!#TLGe=l|t< z#*E!8Jds@vgv@Y$8X8l=Gp6^7kK6VvojH4+CdbF=wO3!EYrVa6?2XsyT3;`6>cv6fBP%TelC&pG^^U&VjPWAQmVk|&e z0O6IP<{i6jn;Xo+V`n9RZ=vqAo-ubGe3<)z8ZsDjcUjF(jnMqeO^OEIr3=?)ay(-W z?7oxhpoxs8+;MAma)bhNlN9#7M;EV6WaPaZ&loK5P-h^ycv%k8DGS+c+p-hj6$0cD zM&4kA+j~-3Ks@`Q|Altl`LD^{{NV*e&PQo{=pDMyJG#I#=Hnmx-)YP4UnWQGePngt zO@W!WxK%3)&brRuqMDXZX6~JR|8*LkQrZMIU0?^S1a?PXyJ6rt2a$tC3(B~BdheWK zh-q$2(>B#^R2ruWKUMXNDIGY^3L#Vd+%Ca0kn}2mB24aPE{>Iz?X`(pSmrgv?#g(^ zXcaa3g~M4drR;*%!|Z&V$2Y6kQIGx|io68RsnOnHsF9u;7`GP-ZM+zyXUtL#@GsRf z2K{NiF$P{N@J1=kGe*K7j5t5~S(^JsgBbs{xNsTD4tVsyi&626Q4a7gE_l*2rm=qE zJ8>?}`O5~{+M|@?8{bomHy{{#)}%oOSVL{?R$_6_7}K&mW8`=ZBMml1;9tBG?GoQZ zh&$PTtW8u-P~!3IJQ>r*d_{dR&lseWhu=?gzjyIkupkYLMJUGggt-pX3gvpnEC$p& z>QR;n-&>A{%u+pLwsx@WG(JnSk;iH4-d`q9)6?W`crrsC)RYGczXA zwDWk;(Ec2!d5pSu{UUjrKai8Ad&jf%;Deu_@$o?#8R-*gBw%1cWEfB=%JV5M>(F?F zhMA@is!hEoOS&4KF_DDwO%RN46Wj)orx6}kgZwwHM^)ZSnUZT3@EE)XFjf}wj6rB^ zJ*+p+m_#x{H->J|^tf+bdd3_*)IiTX(MI*$Z$P#X4ll@kMy6gjz@WBTo-xat4OUSZ ztPy$bz3>Bi^QAwc^QZnDnG@fkXC9f&&|L?{$x%0wL#MBNmwxcg-=m8sf0wSE`M+rR z(jU@|v!AEePs|9qaM`E6`PRd7}2&A)c|2GD(!^?H!~qe);S4kN@yB`qnp|r-??$Em%jAHFVmO4`YrKH{&!|)g7oFD zy+D8a-~Ss;j*rr@*IuPiz(-&F`!9;?fnbooGp;_pF>(L>_h)2h=gyt#)xy9+VXXkN zzJ2@llJmY=7`}dnMurAxbo6EpjSXI8GhXkfb3%z>>$fL`TMq--;%n zU@uNdSPoVJ`Cd(!bB}SqUhE8+N+J?+QPe*v=EK;0nh#vh_i%}Z%@p;Gi+gg@rWSf> zs;J^t!&!SjwQT=0L7VpeNBZag^2_vxzyEc*`>qeHPS>=7P&LM^5SBdEUITOUf!Q>@ zelDa-7e;u2qLatbpn>m)b?MCipS|~hkL$YbgwOPb-YW@^AlQ2mRj6Jq%T0FdI4&tp zvQ9SZl+A9O-Tjj6rtG)LwzMz1=}sKiShgiAlC5G{l@cXV>;wp+_c8-a@89{~H+SaE z;LTtLm_ecNm+p^)SMR&^-1EQZoWYbi@LHo7JC8T9iF{B|k#cQSR<^oUIr-x9<;&FF z-7Ws@>FG%vRq)lPrqiqh)M##Qrfb)(iC9uO6Nw|_80 zETe1Uhd=zGaO?Ksi!UaQD0u3H*{pfn=zx;kitV8ZsDEbzcJ)aZ47#MUXDy&^>#*!u zFZiWj`vdy;$39N~=THBb{_yvISESGU_{Zs|e*V|!wKv}8X>GB&`+xe+|BF8HiBBc( z`NA*!E0KQYU;P^W;Q1f1;H14XYZ@fXuwPi4V%H%Q(XgJFo(oampq~at_?%l=Y(a62 z9c8!%Rum)S!8{exD}$CI5bpU3g?dh%9=$@Lh0(-cDfnCy6!oT)uDM`wY@@2S&y&6S zuEdf20Yc`Xdt-F(sT@hejahzchRv15QULLSwh!V3?OIw5foufX0v93pJuwxc2oL<& znTq41a5cky1;5cJmd1OrF4p*)Z`vYHeV7&zgP1RMwTR!5U)t4GmfZCXrJvny6m!AZ z^YdbE#*TZ;)7ZVenlRX;h>A>YO|-a`KRfLGR^nplWra;^{ejB?;WVWeKo&-E#8?Q)|!xk`>?QUKy$NK zV770Og$n?2I_4fGpU0Irl0wiqK*K{<#Bb!erOC1=HLBtp!4gyJnu_ve41jsS&gHH3 zKDC8eL!DXU8tb~NZ_7r+tTAhTo??I%cIS#;Q1hBPM$oOIHF*V-=mJxp~iy`J}Bjh{}nS>y4;qq+a z*J7ZpBW1S3OV`q^V?eaP8o-rs`RVmWY0jwxe@22k4Je@DQUeNSoOAOrxPZXFxCW#Q z6w<3@A)`h<#9uBv`~2JVnVA(O>-OAJZ3p;q&wd|K)e+lb`x&`gi}~_Y+s8 z1Fm|iE5bB1G?X(R#4{c|BDk#!Qi0Q&41dxK- zM9gwY6DYc0Jv~P+ygWm1o^=W9FT}q9Y7_A;RtgXci1V^kychs+WwheO03cr;Qo?o# zNJ0kBR;T3Uv4YsLvyYOePV7WAdEZ0w-S}#smV8 zXHPi4bn+zRW5{`Mn}a#G7-@bXMq}fgj{?&)xA{%njKDyxPQ?etH|f4iLFPMUN(bVA zlqz0KCf16OiAFrai^EU;+^^A3fA+KV8~^rK>HqxcpU`JM`3d^MFMeJecW1afi^r7B zP@nzTU!|Y?^k?a(KK&Eoo{xU;G5Swm{P*U7sM6kpzJuT=iunbqq4;dM`6U z4^|4~^FFQfD~+4BiS>v1i5@zA`q{)^o5&ZNJz>3}G-G8}K!JxztDxl2PVm)=lzBW` z9GBGuzEka1WfPky6|P>rO7Fh=E>B3O)0FG$2~aTa-o0Cp9$E_OY=G4dNR>C=d^2%G z0Z0HWTD26(l88BT=1k(q(tu^mkt0XerBc6?fYnjHZKqblrNUaeS(uudqPO3ETjU?# zvEHC2_h5A;ad|Adh!m98S7`6J2lpaLTp5q1k%A%+Y*1fyS_zgxF#q3P)v zKIh}bsV{M*f(j92+bk?{(9e$@JEoZq95^79SGdlA003)_bOpm|x!zdM00AS2m~f0n z#sb3ccU!Ynv}*)JhI=w3^pD*;9D;-!pF$sri#D*0`$(AQ4fKI@1GcrG(H)i{vls-7k{aC@+(A4x@#CU5d)cKaKu+o>gn@}u|ck{ zwzk>Dn2(qgX#d4RzVT0TS%hev!!bNtomPs}GvisGsr6oU%0%Y%xxPi~Tyao>PO*t1 zVY6;hWuQ)l17t?ufLA1tkoh6?PK!Aey9dCy+Be`^c7m1dQXY3P_O2!&e?Idf|oV>EVYSq6z*R$JG#4#J)KpBjX&_Q7z5Q^zCmyA>2KCJ)Yz} zGJet~w6MH(z4q9s`6lY^>7oDqKmI%Y?O*+0@h{T<{mZ{4&oX1~y_d1sv)3ci^+F{D z810ruYY~zqYg%oS{A}1Xhup+!0PW1>a%FY>V=*a{ufedklQ75_#3#Y-x_kg-G^|`| zYikonQrOe&5XuG_WK#_&v%9*w3L>WNzWZ)*pN9p}_YxwJNY=JvOz5J`W~JR!RW4TQ z*lh@ey>{aq>I?bLgv`5^LS?n!a5zL8-o8DLt;7l7dJvZ&Wz_Bmv%%+!ibW=N{BPT8 zqna8!|1KAbX%H<~c!9V)u&0cSCJR~ZZNglCOPfN-;QVU1Dg%lYI|c|Qh$(ehz3{>d z;uvt|iZ4lCNg@Wo4q+q^Em{dcJ_R9@AiGM1LQ4Y+dRREU*D*7vxTA$t1KRlgch*w( zHV1WeI_TKJ3ZZ~TQ$xZWf&KxvWC8vcLCB#n0icvG9K~zH8wcy)n+wT8j_C+>-aqUY zgdT`EDEWq9Q3cBwZ-gS;p2jAFBBquaW!$EgLO!!#xYX1iIU5v*fWSH(%MTb(suvGLB^ zXIQ?er>}qYD>T^ON6$R{6n*>2@AEo#MDaRuL^t zAv(OzOLkjq&H4(I%zyj0e@pMY^N!ewlP|vc&2I{qL7Df!H!Or%C{Hr+H-Gat;`&0~ zBkxhWzIv~ttSm~qclxNkHArpE+DaWPETp1)Jpp;Y@6IS4Ik0v@8g{9{3Zt^JQV=uw z0E;IOgCH%{mND7j^T(*F!YC|61JPD8*bbA<*i5ZlUoyrDTs2?;S>14)Dr)wT#nviZ z*Wj2h5M8EHx^NV8bAq%ak}e6q|NZX^%N7Y(9^tdpL=4tX!;|@w88d;>TgK#9@^P_{ z&r}er-4Cr&6|M_F`HVITcVk_hcCo={csxYTd7j_6&F|o25+LhAMpl#=sN7-aKEcQ4 zl{SE}3qh3&$9t%-lUN7eT!bt@DTcNK%c%)Y#N!A^3ye)u(;-3hWsZl9e7-C}-~r3E zn9+7kW?e+YtOT%Bg3jY-A;Xs2kSa_y(!y;Fb1 zf*!jLH&d|_1e+o#I*O+&StX=0yy3FGiA}5$U=bs&Vqm(xntdh4;}Za@6HJ~LFJ7eM z$B&C+5+;3Ilckp~o3P{kvBw@u996&*2}L7u{+7jGgKMFj{nV#El{lgR8}zb?zMud6 z=fypbKmK^)hyoaWtV~?q*Z_eCTt~V@I8d^jQcD$>Vt#CQ_UILT}q8V`#ZJFl~)Gdyw{f0wvGBp#T>PjQo zEI}F=3D6|}4Og~EXd}zRQnhw7VjX;QqRy8CkSwrK)%hp2%(r8xB)_b9&slVj-$;qM-gDjeG8*Y5i|< z9)4RSzv)AXD{=#5Cdg1&D{f*FDJ*XFO+2=J^x@{b)2X8@{~DKGk5~+P`shQM_cvut z51**NA&_0P+SbXyrz|jexCNTItx4gH&E#E;cp7&3$uo^LwtHF4p_6EE&G|#V`JL z;^~_x65_EC_4j;@1|~u@=L(C3209&l$QK+xWy8twsSL|s&N&MOOR%do#6EWi)!#8`ei^$Ue8i`x1a#8w)(5#qiGcSu1&taNmA zh&UhkyS&Unx88Du%5-nj_*^8p+uc1MC!Z%y7K=r=cxrEN7x7=9(6(AFbm#3SC^&zH z&Rtocib|6R%IEjRY2FzV1P&(ZhK2?j9v)7{fO+t~Q~aKbG&$>~a3Wp@^5vRU7KCtJ zgm;aNjU@%xd+xfGsx3V%K+luUSH(w)KRC+rYHj0o8ZnT|x%O^FWZSViLS!^4eFqAk zT$T-SuDhv;HS`IlLMRjxd9SO}3!&5RH`2VTH06qSq3&YwSd#RZ7*+n21SHVc*C+nn zyQiC6-a(4SlxrlWClG9(M69Fw`g*ae4P*@Z$$pgClDvL}P?BQ=fIi>d-A&Iw|GfCSyxc+Cw%d7pNf8(zGhj)vbH_0{eDKz+c|d=h zo0}8Aul4?jLSZM5Lwd1b#=oV6R*n=RCcWM>i5R$93Wc-FB6T$>IS`g2T$}>1E-dvo z6$&V&5nLYx%B(XijJ z0J05ZTYgFV+RQR6?3s%biwAULP)D^ji3jEZv{T$`Pw32PPpJSn~P(?+|<%aTROIh*b;WTLp&QW#3#rUyDEN5 zV9uT8J`o0c&X9cr<%*3UXuG8f@|`c#u8z^~WSk6n9Ih^rPhdgSza`N3<%T5O1DR9C zDuEkVN$z5UOhtL&a@NfRShY$y8C?y8xEdiI3o$24G_q`Z{7{v!{7z4>249@Kz6kXW z`Y6P8lv&=WH`E{C;Ia9xleL=9&`Q|!ce&RitV)!8=hv6eE-=o^Z$`iNa(l4yF|;#` zH<)W6!y|v?Jl`PSIIeD&xv;gRn@k29z4E#eBNcj-nwlDFY;2@+=gx^^wGAdRt7N_Q z<}PyBD(S@^y)NE`^)GZVSOdTO^2_3ysv0AYB}UOFZdS}MgoTULS zJC|R&3~jgDMR~4A#N$BHj+SXl7 z-Mee(;L$ev*Pr_Wb$4x}H{LoY+BVkJ@HT<9@#yHN_?D_#Bek?B7S0&;IXU)7QT7 zHTvhT{)M<^&#u(s6{xFs&^Q0-|D)I5dWZhUpZvMF5C4AaJKqt<%N!2cy(>L$?^Vdf zgch*4*n~Df?13y$V>>rPvp&5a8g$CvPNy?T2CDDdR!d~ni1{QIro5QLzZ3@%JV)c) z@8qHr$KlFJ0_PBNNS~Q zsgPN_+C)rxUO>cXDTpPuKa6 zT@Z@Ba5zMl;X{2gD83nSkvg{6gn~mpuZ-{6+HMo~Z+t9KNSnwCxF!QZi5Nl_i-8xw z${2-Xv1mMRB4#P%Ps9L9eM0%Q8SAAmAO_HlL4SeCmzFYvgu{X(^O{1_YiA;K_ClQJ z+{8oQW5CY;9orn#!0oxU*(wyz5^(v1v3k=&W)p=2W2IIqA(r|0l!c6vN626k(=3xF z)=hFFfH=RD;FBjnkmhR@17M?Lb#=9{I@rX`k3&c5lIiZdn(1R7+NzoM?Wv`Xt}1%q zZtZLC=i@uNt7-S1YWgva^GNa;58vBDANwF5LsFf;^R_1H-dRl@+pChPw$4U2d!kQd z;GTQ#NyarwUt4eL_X@!#8M9Ha;o5a7!>f_?NI1?5xZ+Hlo49!ZYqU+Il=sI@JV4fp zX7O8%#@0?U*z3jb7^MgFKX&Y1vQ;hib=%y!mCWT$;&(J|rQJJH);%2^J2mfVX>FsL z=5FyjO0aH8p`oFL>f3iG{z{>?u1*{myCP{*DFRH-g|jN7u#DVo|(trKK|4zUBOP`|y`*zduLyH6Rf9%5#(Qo|wU#Fk?+|P-7KJ@s<=wE-~ zSLomT;^$~T-*aTY(pNHph2Eik<%z#YSQN;j5BQ3LQsa(FL+`YBoft z&${UJJM;XF0Wuo({Ow9C4s5`{oQ&8Uu!ez^(9MNS8MII|H(BZE0mX+U#y+cAM-GQk z^f|Oc>{u>@h{3&DaPv5vKM|t<1f$xu;(Ei`3q)SU03$1U`iS0qM>~yQ*$$e1y(@J?+|O5KC_HgJj^a^D1(dOLRP5Ee3p zy7Jyc3Y%oiM#B18tLKT;%P+I_45)+%%nof!o17#I; zq&F;9E|{%lJR6uuXIQMr&>O8}Fxe7+rGR^)q}-Dkr^HcKLq_vr*K2rATyN2QPhDLr znXHQy<0i9>vu5XfEGA-LevI-uc<>;Vl@-q&9W0h$s=i(UVoF+Dr~&scMcT}@DyXWe z5_PwA>(<1P;^TuKew^O-{twWdcio+q-uJ#osimcb+wkIGHjg~=Fg^08JS8JV7C_2?d43t5oCZ1LbbR}4ZcssW&3vCtzbLIF=EF(= zD^$1JO*7NeG&O!BakRJy_yaUMGfjcu(t*qc(3BI+d6SUY#M(gB2$Mj}QLW=kV{pVL zT%r{Mw0T%$N)%(=ba1DGI@^`C^8UR$>DJqB<8`u)e*Ry5UbqwNWchgi-d$-f%DT7O zXy-O%t$cuGXxuY1J16eB>z;eX{kW&1qBO3|*EeK)$V@i};DU9G$69r|cHOf`R#_1W zE;jWIshhAo$s`Sd4}IuE1h>_jR$MECZed{|?<(3veuzdq^ukjgp&y=g)AfF@SlD8R z6&4*uQ4Vjg8oSY3MlP440EVAjm|xD%&r=|fr|_5s@WG2g0I=G_wEtiv=}T4%BSQ|F zo>Y`&P;|r3Ay-jA9pGCMsI9g0-^G6izCpy;u*PZ6zBu(>TjR*#48$RkLBpH3DlrfM>=Lf3 zG}75K%1-+uM~;ZVXn@P*qIchYSNvWsL~I9cJC(IwvXup?vtvK)*?yQ>TNhicgd<@= z1{r)$(%*mQGKCVcTpAlY=fi-(CJ@g9 z-5)OeVL}Gx3ci8r(L^t317Sb z>Rp=4E*G-x96DhmyQ7;foGHx$x)8|mrK;Y;<6KHfiiPxc7Ub3FANF%O5p}fL>B6~m zH*jkOC?k;fT{{hewCKBGCAYI&j9s_!!b9THrAst3Q-GEy1K8DuvHbYSAWhBrh0+`N zvp;@Kv{5ZwI{PZQ#{Yu8@oaChy#v4hpT9*_)r&32fNK}tB6H~P=&eiFX>>+=0eE9D zK*4a7j0Ou;R5ep$^>pG4(ac0-+j5>FVEn>K?S3tzzS?k3O zl9okGTeBsnT(y3o-KK7Sth4Wy*;!)Ua`CELxNQWY5hXUrfj#Ad4sJ)*<=iMrE=-86jd+eDpPh)x_y9MHg1--mLN$MHK72N)n~K*lt% z7=h!klmS5l;8}QPHlU6MSr!2*tvdSjhng3~B3TIRrK7j~dg3od_ChQ-%rCol@6OAD z6W9E#^=IiJ-9z-a?{R*HmxeF@5}!%6k#iRp=rv9}9nM7#{NrpZ;pV1r=gL0k{V;=N6WS0mP)3nN#Wj{lBecab3Qb zfcl2}Y5>i5+tw8E4ZxBR*4+}j+HCZZN3`W)E%Xie=zBk!CQnd_n+$7M35>fVV~W0^ z)?uWd|77}rl54uarn7H+Z-VB0=`u6o$rK_>!S$hZhlua*++r8~SRTjbD!9!A)a^1G z9ynf2Tef|cA|V6qEaM^Z-@v@k{g{{@-8Z?^C|;wtW?}cmJo!?={h$-Q5(k zHc(}Cy5+rR@+$qeKmScGGneQS8z0)WJ2(P;g>nwDHD#=)OrTw9p`iltCsQ&2P*+#S zb+|s{>rD6pPP%&I*~DK8DtNs6Jog2y%~@Z4VvPD{0`%x@HFRKax@QppZS>ifXGqUY z_UAsH`x%elQ%Buha`S7dJ|=lQc;%dnCY>QMFQA{IPAcsNy6=`IGT9%exj7g8{vZCC z=qvZ$d#{KEeE9HT`tp~*ES}M^!$QZ7R*F8g(Sb4WTAzpK^Efs0+=98}19xwsTkiR% z#1+NC8toU^#EP&%8#qXcTW`HpC{T|cJ(@VW`hXw|(@*3ByRu7Rfv_6i3K9m&OuS?7 z-o1&V#RY;_A3Ag>Sysh_TvWHVwwCN2P)u(ms28BcwDgeZAGkoh=f6Y^roUd4TCHEA z7R%qWFfc6wl}Sua4$#$izeWv4zAhuld(8T&#MKIL&-u5$qIpk~>2Jk7R{e0|Y6ZCG z0^d`s|A$5QG+X|TT5bP8HhnK&nHm5=8cGzi9~<>76o!@Hlrj}lQjlHGaJiKF z0|Bc>u>|Jv$zYO*0eY{#MZ-fwnkf`V;P6yimlztjqIo@1FlHj1K3(8fV|+3s6oEco z=vvH?G$IB;zAs+&h~1|Ua>Jo1s;ih-F%bh`&H=%dZ-UDNb;8C0JY%VZdcvjywQ*bf z_7jVU7{F28O1A0_{-k+I>5}5TQ9LkRC%J>F{iuc!;6w7eu>Pniy~P#Ra*L} z#y&tc!vuu_ZgEYiEKTf|1@W#b>kWSQ1fU)g@z;8X958dGO{@r79b;KVyZENY1`BQ9Y8NhqF(|B(Lj@BV>);S0Y?ufF*WAOubM-yX89#J;f$pIh;_Db3%Aj<-l zV+rTyLN5GR&KJqTHAsY^evFf zx%P@u*>JQC zva$)PteWC6WFna?wqXi}eaUz@dv+eBmbN`<&yy+O_mOk*6}o(VG_9`#J9iwT-8&D9 z>*U;^POzfH{0y8u|3jKzP%NiFaFo(ACR>b{%J(P{1L7CfUb8$WK&IVH`KE}*vG-td zY8+D~^ds!z#4h-*4u?XRB>E1Ji(FYfB1Vm3joHfwyfRD{-v!s=S$JkP@Nh23bHHlQ(eVS7qJGr~Mz>L2V~X9u zcn@oEtUExoR*S&(DWHw0H@?(yIqu$(eSMY*lz;D_k3w8WN_nT+ z8|n@92iSQ`KDJ+bK+zg$LEP6=n`nXS5^^Bi-(t)GKzic4@{td*c}>O<6W?EH68%6P zM}86W4#pU%Fs|$yvoy#vJHvk~_LGrIhgd+j+2M5G> zCC6L~|31!rLA}X90@lMWUxd2bZPbXEM;TRva_Qs#h9Wq+FY_77#qt?@I_*3MYRftk zvmu)0c~6a6?i;mr-Q@99@bh^N?cC4n`pQM~w9#y*v57$n1;_dQiGv#$7z5!R7cxLO z&n=isc6L-!Tj%46D~f~kR=bIfg$>fsvBL&X2X}(fbES&YLJ(z1T<(_6RB)FfA8^eh zQL1l+X`lp@nMlQk`W^TNd`q!`z;+T?j1>#0^Eg&u8weoOUVZgddg-N?R^+lN7renZ zed$|MnyG&@NG?y5&{JTd4HJI=oBF==1Ye^{fBN@h^oRdvg#PDWkJ4A4oED2+HK2Hv z&mEo&iRVr`qse1m$#Rd@wKDzVx2MzO50IR)ywq*=y$C2wHxe+GzzrW<%dOPC+)^;; zLs=6RZE8y}39W09^ql5-5jioV$_uUYOv+ z1&?|sYB2z1RIU__hD3_RLNq#ZRS@4YjgOC0LtQ8R)Z^7uTLCgexmN2rnfTEU{*tbo z{-S0Y>-i%xP`c%ugps23o$q{yo_OL3&Gh7xPtx`4*TuDU)|679l*kpVU-q!~8WGb! z6iAIP8*7+ZV{8^y5_uFwCb5DxS1ck1ebQPKA_mx4^$Pc5a94%|cVlaUj3Tq>uh6wC zFRggPkwnOMjRr3MJN~tF-7H5|0{P|Pv0Nl>KT9Qd#^0q1X&Q{g)84aG!mfQlaZ#1N zW&~kYU6mq=G{`wvQmQvPD;6^OY<|_s z6OPH_^0(G?+OQbTl9`^T-gAFISKt2KwDjGt{Tlt&|MM92UO$_-8i*>GRDh=X|g@3MB8Tt@QC?eoCARho_SFv^Lww zY?u+pk;)y>Q>?W5dCWKoMGB&H8 zW&#G9^y);K@aX8=jWAsp3e(l`2%R4c)9Gsga`HWD%m(!|%T*t;J5! z=nNUT?HG)ODWf~L&++`AwBZQ1Q*}PjZsq&3<-=y4O&;IcX3Faxyhr98zSVJ$(VRQ) zr5JzJz)rc>&MYiS(pNUD9XhwzlEfnr3dc3?k?EZa*~xVX*d2)=o`BmErQxvvRaKeD zksy7xci2R%sMUr~bl!VMZ<@Mq+SDA_jiOZ&D&gqV!d96JfKk1Teg!D6$ksCb2Ry9uT`c zi$%l~$0A0JjZ?2xm5Ox>65Nfg8B|4PF^*BW{_8Y3RvejscKDCTW?5Rk24L;7kk}Ew zEaX}BIhy;rfEFR6hR~m9rcERP{RZODOwRxO_rJL8gUOCJ;v^m)s{&X6~Wd@*&M+)QxbS7mrbP z)1c<{NJbiA`CQ&3JK<7k6E_VCuHL*ZS{~vdvR7~)(9O}scfLdKyzz~+^v_@YpY-Q{ z{u}hp+b<+;xJgi=;#6ZZfPV>4@&Nu?Sf{lJ^U>aG4vK_|A1DtBq1msE_F>K#zN$pHQpl{SjUieFav27HU&5TnY5 zd9s?7&H>j!*rDE57N!6AD@uHWcP|I&sn_Rd))}GMNgsXT)6I0`fD+W~fBfwX`JxE; z7$*0GoBsO0?-9p`#)9gnOpFsElrlB z(nF#`C_0oK6cEVavsw#yZ)dwz{0q3fso;{C7#Ofq(5I&|dyKy~M%5J+w6#rf?}mOd zJ>#S~cYyGyj<#m1C|AZG^wS$d6BJ>2qN==tI@*(c=ojhdh6;HZtG#{@0q9n z{3~0gO&9&}qVm2<{+^FMSS^CZ!Mf{DzdT9q zu=czm6sL)LLY*LhKgv%A_J_g&^G}UAN}v8vgUCCqI{xMfv~4{Zba6Vq-9-1DQhati z|B92|=v6EqZr^94yN@g5C0uI##W$wN8_|me(c!IndPJ4?mo6ppZc_3NG81Ok|KC?R z?|cscf&zrc4_`Hq+ZE^XkMbB3PpdoB!^p@ax97!mhkkv1U`(mIGAng#X%WYP!J#pl z^YFLp^iI>XEnU>))HAo=N2k8|%`^2nlun+)^2*2Tmz& zIkfv64{;jb-d6%Yl4|7-5+WwEPcDy$$;9f{ZK(tJ124V;g+0;xA5{Lv zZ(LhY0Dp^)KL4q9g1e|RB>tQaJxaUwe^{&wurUkkj*}-(=HU@P}f4Y9=UTZY}VVOSo9Vj`z&XPZsZ_WDeX+rH`H<;{P`cxpC!g~ z5y0OWh)@$hOD(ftw@%3aCi5TXvVzy>}>aVn86N-NFIa z`+aog$^!X9QSJ+Hv6xz4+-xXT0Do9vL1zZt9Q1M6*tK4u*JGn=ge*2ckKHa7iJYRJ z4<+;>W$4ci{%(yf4;|K&CrsVE&baSXdTgPAVIQ5nFfS}OiP!br?RL85Xu2=Xcldn& zpiewwE6Y4_ZIMa1F$+Xv+}^nC634diTKRoqWbGiAzF~De!QY022FAqrJ z#I>2%XL}AN3|PBpor9%~H1oCCAUK5hy`khga7{jWh3`?gP}90c{SK=m$N~w-nbbS- z&1mnK&*HL)|zpFJ!wG}>k|6NhK=aw)X-tDK3 zwkTbnaFeY(LfaeW=~Evvh~vlihiTgBCciF3m0X?=-5#R*Zd2~*Y>!YM-(z(|$Y6|# zi3ExVtpw$;^reg@;PJ(T5Gv!5WCCRw;Li+%cwDPd+&n?yik;wUKh$a>27qfP2p*Zh z^VCEPNZhf>bj7F|Q!_^L`1RD%7NF|dFf~>z(C2;(W#Xgb2e^Mn7RbqMqpC7YC-~S0 zABc%_hxdf&%AkwPjwlOm3-sBK=;+u!KONZI~!Bg+3p-+%b_?OFT+<-=-*|2L?xIWHus%e6Kr1A9|oxEGS_i`0AM(6k-7pU)fxx zqaB^f;s@n_zAq@Q>1a05EeRJ_s0+l%31yIY5>>n~g)e3R_rg^c`T$&E0a);0{;?V2 zbZ{5UiuHoz7@mrVwvFEp-dd5YGbmq2<`fBSOM{6zS`{S~1mrV`_&%9=FXQq!*Q@ws zudC409mf&I^JnLB1ow5@qL>0lL)drP+i| z#LoFO^FklJR-Hm(PF4B|6kQj2Ow5-0MnV*f>co9&{D-dpO#ij&Pw5N3FC^3BJ&)6` z1b&5nJ@V_xW1sPVhAy6annq_7mzE$r^6?2S0mbFhKhRUpbsde4@j_v1;zR<45HS*& z&1|tnO!|)Fn~sQ)$g{s~0@y69OrTF}Y$8Ttb?bIDV#eTJK$1OJZWSCehS$6zW{k$f zY%tZ5t>)w8a5#kG3~P|(#*8^&c#y(@8@&EbuVciP;H4i~cph`j>sd~PHEfjUJIHQP zmW}l*Qkdrpm(xgIuTlp1wqnJM+19S3`%g8|&JG*x?XvP3#*sC(H(ABJgcu$Yh`*s$ zda7f205Xook|y7+7fIkfR(H13AnrGxFST<@e%!klTY{UTd?w zh4QsziG864WNh(FJd^>VV2bBx90L$nrHtQG&hN4DdrW*CP6c^w0!1j+B!#-YEp^No z)D>bB4NpLpP>#u%E?D=p~AM)pq3HOs|CupZwbK;va-=`%n;yNg? z(I%?-+dy=n9Kw+pUA^uTYk#bzus*=r3FI2yGdUF$`OhSnXL${LvDYI~Oc$pKuEV}z zKRx&AtT;Bwf1~du)GPv6hlKgSD6bXHTwI{n&(0^GfiyM~q#)-9_aNRR`oztOmBx$- zM}1^5Ow-*bW3+9HpSEueP-nYuP1E@JC{4S^$sZc0s@hR<`d%QjP7E@)rk86b>#oJzmOM=l;KfNbwT zg6m73S_SzdQ=A2kBYU&=QS`G**F2m@==U&hn8m*v9U^87_gnNo^u1EWjM*e(N`N&X zV?Q5gHgXP*fkGmbQ6vx@YOY_8|Sr=gR1wlW}_geMTCZo+E$UO;h93 z^qap}L66?6=Rq}2JGKOAXx_yGt&5D&S^Aw{s}{%Kf1jR)W}IYn1jyzHiv?OXG6uU; z{lO50V-Xsf;A>1_s&96YYhjjdJrJQ^{H$FJ;E&vGpq`N_3UEHA$EWCbf4!O>yo1EK z);gXTy$j?EI;q;~qW}1BD#h{l-L0cB=PViQoR6{qd003Yo7R!7JV>?*CpqV)=%*jI z(Z?S%iR*7W7N?%E8S+IIXsmyT{@3r+i{tm*&V#ZpMDFMu&CN~IJtt!Hv!AqzbNAe) zrz^uVR93?RpPeW5Sr*pji5i-H6g4=>x0{z3&kc#89SON@4O1nCBsjoa@eE6vdF z{A!gr{?MIV4->N#Gka-re3E|YGgkW0gIvzHL}_n#n1)>QR8bui?z9HR^gLk4sbia) zJRv7Vyp!|?|DMa9uf6X!5FGO~^Pt))H zI^G?nd-*%c>~5Nmc&WT9KqhmDdWQ_;=7GL*n~U@6qUK5${rg`iqr3R}2X1F!)Hz49 z{so$ynWWGE1a{@<#koVf!_+@LOM#f1+%seJUw^YYdC%bkI*OQCV0L@C{VCQH2uNK19jX@vvj)sI%HWG|drCm>ZcY)l|QSYFiCS5!Ma{nzep$@dkn0Po! zqvHV}AICV5WsS|mvtl&Hv;2=2oqF8BIq))OQC9O~X`rP{=I!sGEy7Lc#*zo)hIlQ4S#QAU8lNz^duU zUZt)9?5G-;N-aXwfFgU|8Ki@|9palj-Wc_9yP24caGrQk?+($v-DRS_usG-&Q^=S| zFv9(zI!VS{8wip+pjcj%bDNr&;yiM>w{YE@zQlFK*W7zcCDm3K==3}DbcO47W}eGA z3mJpmLvo>ve`NrFEixwHi%|cNU$lcT=|y~?mIe#makz}mU-i+&D{dO&{LBZH=c&n< zx6Uol=nQ{rf{c-QhgH;$ZFcIPj0(bWN4uH2wpi(MkC!f7@g(z(wjkR@{}9@lj_T{e zJYMr6$;d*Us_viwzC5VZ-JM6v#Nryjx18mChPgeXzK^QzQIkl8K(=#9JYs>a)j#r0 z66=kK0noj$AwvE($9chO+`(gtMYI_t5am1D`{@$K6dtbt^jR!^GLw3dj&`wBQl6HM zBM0uF=9V3azlffF>d&aj@|P5HKTp=OgMugmpmbXa8MELfy3)h>;58iDUU!#5&;w#u zS_W~l6cHn#^py875d+9V*hHRK`vQX!8Wz9k#~8P{>#vGJIukb!5hJmBbt}mjjAPgs zGwV!G2(}M`MG`8IEi$jcy)r0&VqaVG-1*Byyc`ggHy~bM6@%C_(=*C*O`Kp&qXoQc zDKf?#IYnD`{aZoA04pYAboY|2@;36$J)1bI0P}J`%XS#&C#RKf0~zCRC<@NiB4kQM z#%$@jm3AEZ3ScxMvWD81B^)$ z>y3em<1wkdqJuUaNhfO+wKJ>l9e+ zAc4R^@+IV}Dyxy|940})G}W4^De;~#zo*P>APe`e06zz7wQQtAHsJa~$e1Ws!MTg` zVuyXMbn%*-%DC<#EJI8?p?8Uka>KX)Kyi!w%DOY~%g#t zMaXa&VdIz@7^5%`qKzNiQ!dH?-)!SDN85v?JdV{=nZ-H}YhA3b(Pyys!MaWjSe(g( zKH%oEb8;Jah(#Uyyna36Qqv^UHyq*Ej7g zHuCWtBGYB=hfhC0CHf@#yy%nM&%{`A6Ou6))2etb*$m*niTtoZIzUBPoJ__jCuI;q zwjm&e!$JNxB94o5K1H#C!Nr`oUf#13#1l&D+A4mwd}gBTpqLAVf@HU*-WT!1zdZ&* zDDG1E!vwu+N4Zd#XF@78D#~KX>j69m%5S9%l;Z|HTuC(w;Sr>rNmT}Tj^0p1I%6#l z&*?%uObspOR6daaJOc{uO4U06uTL+8iAW^0=pHS|$q__>ycT%{#5?$7)OiKmUKWbD zJd*k1^YWer4^O5G>4hbQvc|f^vp7je^J`ItiE|#GqC6A|(0F*!J*dWt@;EisVP}$Z z41+1sk=vT+JFj`^@1Ay3-z)-FDwA4yjg=gY<@AjodgvdXbyJL2oNzA)xT0qI+KUS! zJ$Ke8T$BNDyK`|gMz8mT>7QSA(<>Jg^I4SpQ?GmI8!yd^bC)Mr7>p$vmkO91vjMvd zo_~3kUVg(VNSoSfC7*})m9rol7w3>%EWk_j@IcdWv=c>DkGd)z5rc&eT)E-OGpjJf5u}KSaAp^Z}JtETAU-Hmk!j+zv%lqrx-k*8PE6xoi z`X%yleIhE(A-#GnEL@ZUBJVRgas6}e2I+5}o=?_G@0fDW({K6d%^RHe#64&W{-A{% zHMfz`ym%Y0tOG1c5x)gvU~>a6JXLk~%4zH*N4iUE+6>y3y3 zFy^cK50tRot(R!u);E*s;5H>L*n!=v6M*sB<(Fw{;wp`e_EB%odD_`_MI4Vuy)-}m z_u@EG&$V~Cq7)*g*cjunNsWAo7yy0YJx#;_1zfrbU~LP`<3k$=a$AiGC6t-Rdi*^( zv-~l1Iao^~Mv+fS(I;2GZb!$7&R$rYK%4*|O+czFbq&ZC^|`5;ba!MpCW#%~_sR;x zRL0}lWCW};&!0a}Z@u-_lIhHuGrV48`8P+gLvHnQn^(Ioa;TJ4kXvVFgGsB=jfy~| zmV&y26fztVDXP!komA0*qL!&pEa#q804!ppjM(5XQ5CPrZa+~?pZ$0nJ@#ND-E(^_ zJ#`z5l@m@tz0yJ)hwB+|9phE6vnc#%m)U$I;eZno8Z`!0C_BG{0l1H0lh|H-9im zPrp1ZEIu$6LzY)>MwZ_Qcz7<-dQPsi!1qW%UV+yISU3Y%PcDif1A@z+K3|~B;Z?r2 zT2YdRVZE(05Zq~FLmTeLIvR+@VI6J|%4}H3sK=A#0&czKx&YsROTm}Uj8$%%$V3hL1HKL9a&k)uW zVJPo){QZf847u|P=HK!i6VqX#1eZe3;7Bl8hESdY^4yKVfJn05K)|#%rTh&8$V(jy zQK*y2=?L`>ASO2WVuiH{6yhV}ak|oHCa>Q>^<1YQeDIwT$T#i_@Hea!s4MKS zsjh^HInnN&2C}n|KOfT5I|C6x1dXK3{!7A$gEw|L}6YaL->q<>c$# z^wen|)z(=>uy9Q5`2fm}riSd-+PIv&JSmG^L3X%nG6+kRVXiYQDDZc&i5Rs4ro3FK z&)S+W*NYM_2AB>Q1hIki?y!>uCU(k&I*j@uif<}DA2b09@PCZKH4uW+uS?oKMJKCJBaQ!NrC z(DtN2h22p3V3zv}#t{iDAk_UBiy$qMI2S)EKz_Dn+J$i#zIXk|X$g zWHwAE&hQ-Uy)2F+)zBZ2$)LEOTn@1L`tX6cNOzo!b2%hVFw{zcLWmduL=0TG0ojQd zlwC+}>C&YoQ*UoCMKfH=D&?Q5gL4-b zMC?{|>evekA%l39*~j`#EEBRiQdP1v3cbF>fQ&6IMCy3m)5voFkAI|#vh9@--oi6yiy6#vP*{otdWv9;jxyy!0jm^^F9{#P^-Q?x*v; zKB1g+@|uVet^7nyQE}Z=LhRC~h>+ z$V`-8decSzFbQ`q2ClOkqd_v-Omwl2^Ksor*fHVu;+&EC$3ygPkB@x(%qb^!wGXLwdHDM=c*YHSp>z!E^z_z6H;qgM#BTKf zFCydoop2{KFd3%)u@H?-d3e@d;A+LU7({}rAGm1>@;E#)9j2JUAYzkT==0J7e;1U; zaElb+JkI;$^x8SMC}+f$Kp5gEzZcdW{o`RJjszc1>&K#88J9wqFg*I%eaF? zr!RQL``{xL?h@dR$mQej59#Q&cNfTDQoh^ej#7l*G3$wocU<5ygu)qc$^5Qhjxl zg*3$-6NDrvr~yBh=j05Y1pzZPR6_{I1d81)5Z3T42zzRie=VSnY}Pm(*$=Z)SeqcW z4&JSthrovC;yYlv4oe;^95`D?2=RClw3Nbaf zt#G@*?s_OVhPf`V`yVFW1H%EK#6cTrsJGD8wv@nFOdNf;GmtvdZmZ z{112sdGQqyb%b`KH192?tEmt$Jnr<+diih5M75a01Y7VD*H>CxAAF zxn?~AyKrUwtTnJZ6JsHY&8CkDD>5~a1oC0qR+}jA!KtXIH(1x99!in!J5f%R{BJ%O z;Jgj-91WnoA#eEtZFn_nKnnJ7eb&GK=TawT^CzFKy8w3yHTR<+zg!(?DT)>eRO*I%cet8Y`^^>Z{bbcN>TCwc8M!?M8)7om&C=sA%B!C98crg;vV zp%DL$1ZT+Y9w$qGh?*`qsITV@njHKGa=F|>CX)%4+|!&F%xN=odVVf~VCy*P#ka~0 zb?6UhGnECpuF4msa#PmS(n?!8wvpH4A-mlno(&k{6J&}dOqmjZT&C@&O!hBD&R4H3 zmgS}_A7pu?+658XiCojmWc-sxNV~RA#?BDRW3FQVsjJZ;CXt$UTq{RtZ3f3zqGr-U7 z0UO$I9Bl!zdRdu;?={fbiwmN?KqLZz?{JvJIU_GRuUz*Ck0AJ#Y(SsFd(>m0M7~4} z0H@YgixP(@TPjKaTmzt-WV=|7n=+t|%Y8?uLzL&5B<{cJzc2TAL_mD5sYHK@2rEo= z!UkNdX>tANL?C$_b0+FH6By5A8wPM6^c8Ag43sXuCD0cXJ*dV*mjGmf^0MsX19UM> zEL&j=fV>9%(aiwJ1nQVErE*iITUb~qyjC`m6VZr=UU=#w^ux1mu_FgN9-z?Jy`wC- zcwbelaSbDQE;cU(gIqSzpis17z}ekZCKhHuAP^PDpd13=iU|uu019ZF!_H+WVD{}S z6T%oe2dqb&E@h%q@AAw91RvZ0;$V6frohU;h3D?r=Ac%d9PvEtsu&*gC*9ucV*v>y z8U{NE?GWr?>4De~80avewzVjWJ6tn96%_gP`yntYN<=6@)X#wciRU2325{nV6*=ts z#DE&&b0M*4#`Or2tycJ8v5Y|%q!Iuk1ILiJ6Nf6rV2kI#asg$Dff8kQXm5p3WJ4H4 zd&D9Yi=v&|9U@*ukh6lxz@UdxT(NRczXN&2U<|*ixDHAzlmo1M@Qo;s!~2xL-C*+Z zekiJO-~L@?LdXO#sJRv(h$)Q{@4)i`lzB~+k#=!EL0&;t!DlNJ`T)vfA3qECV$z12 zBJ700_sQ5QxCRr|z$k)MTdBJPWgKOp7nVs}zC4K|KM<7gZkQ;K^7mdJ@QUv`ez1~{ zL5Rb5!{Wxzf|6hK-(!3Zoe6?nZ+|#x{UZUTHiRsc3-SkL9VSe~>BtA_UD>!t?&3oL zQYfDB-F*Xo>e^-(Wj>JOxrhsbc5`FM%ynrHF@!+)EDMR-Ahe@>Ls){zHx_ni2e8C| zPhAiJyLY5^a21<~kwCjZy=Md30@?xECfOu6e)gWRd zR{s+>I99K~re+oS^sZZL#Jr1ma#%#exA?o47KG1w5E`YzB4S00h*4n?akBy<2Eg0{ z1y2Ldc{0XVky?EYy!Sc;=9s}@48&Md5b=H`D^?CFi zkOUH)TS`+Ni;#FlU%z4*4K%B~8_45mKQ)QCm{_Z;En5LtU&tNceY~#2e7>bkX>U+& z%5^u!inf;g#yUI)Xeu+&9Ve=|?WlHiEP=Pqy6ECH4~@Ii*DRQmA)|M1w{xCtESq72 zl0mFL?>SaY4T*2e7Z|@mAWZOk;5s> zO)L*dnFDPM@0DxZVgv7kbvMdVk#ACS0oHUa+^zuRv46-XWH`HBPkVNh36BrJb1%=3 zjpqui$*}(3yHlz2o*Q0~cg#(ScNJ|wMg$>*u@Li|1UAUEG%0n1yyYTd@vfcq* zi)<5!hpLWcr3S3YvH@hNX*I^HY!KN`uTQ5xx9(vpulW&kSZOOc7BC55yjE}UQ`&g? zeQ5i*F0&}$Zc!2_`9kS4i^mi7cnUdkYx`nL!Ho`(V%M&F2m}^%CtGYsyDv?#PONM7Z~{h}}5T zvr!69VYd%2p6bj(sKP=LCVC)u{6U>i@;5h{mlPK9T)hE;j*&XrL8K^gE|3opF>|gM zxyF=tK{<(cVIhFuIOm)3ao(X6SAtRra);5#dBsFNJs0QaAtB3`t_3O!n_A z6Us@Kw~XS3I#HH#ha=tr1$r>nKpwB+K1m9=P@ck~2Rqg==B5iyudkoNCJUUf7#uUMI2 z@I%l#EX+W}z$(S%HVAcI*xe%`6^$}jCklTV)|ajm+!RDTgeV zg!BQ7HjV`Z+=-xl=5i;7wvBJCEDv*gQY>$ljYJ+ndZB$o_^YT;c0ob80>#c=t{XKG zgW&C236W8P-Yw|%hA_hQ~(5AJC7+{&-yG*P)5d*C5C*A~Dy#m8H3FXr4T$smp zE7erjkv$>9fvCx)Tv{pCf{4MKhj|;DgW!e=id)QY!z^<^j$0kPmpcSDz#-5!*GnR~ zS2eCF(qf`pwQek3zoX)-VeR57;r+{~q zd<(-OMZ+nVpBn-w_H|hF(oGPSEU>cK3X((SHIMvCg{UcGY=x|iwpYh%evDIky-}>M zF&7s~!~l2?mc3?PAHl7*+O_s-18YOIYixYeYP&4MdOjaulO5!_Ij7w zL<-j%#BOnrC5Q!r>->p94ii5nRB6tv1t{BLbpqun>H_BJu+o51ALK{S6QbyXkBofW zYy}Y%67CE@{DkK`r1NlI$~hkfzK@>+K?m284Wv_d`hw3l1zuVg1wIc|QfhJV5GQLa`== z4Jcf8b~(r&j8jD4Nuh|HY^GU4kax5{>~sf-5!P>G!F`tV427!_OGY77_(k!U5Hc{J z!U96=A_mPDB{SVyzxvZ0a0GA zg%|~*jeHEI#5`Ff%!lzl>}G-zYsRS~ZwO}K2C`du5zXa&L*6kT z*43H>X(dfQL5?)pV{~+vojRIK$+V-*Om`eEC#ybA7yE+>iCANx+jd*1smhpktxQ3F z$3jAv2eLyd`S1>Du8aKHxeU?1K`24-kGd-3JmGI?X08SZHk5mHrJiakqr!As`ifr` z62lgV5D<3&`r!WEWh}tzxUOS@97RC?@yU=NSfKckyH9~)5HSGSB6cfe1Bg5H!{xXs zgH;R&6a? zE#aQbx{{VD(rOFO!}p_%(8u!u>QoXMu=K-t0>T$%4@*E;mY~hJ`P)$DAWBh2AVnP9 z=1^8Rk2a5Tnw|-XGQfC^c7)xia;(w9Qf|sJf&5_sB1vbAU-DYqi?T%95q(*-*Trod z*IBJrvf5j@4~8O8DC;kR7FQ8vapxx{d|)24T6umpu`J8;m~_d4%`&;<=;dO?L=3LaqFl^I z#6T__GOWazK?IwD*fw+@j23p(O#C7J83*9vhLzg?U(LU`=kP?hFf+ ze1LL+bqwb7AomrN!%`d9AdBPM0MzkPZptuT<_nC;SUbu4(a(zMvdn_4i^E!Gf|9#8BO4{D; z5a%Xgg~#7)=Vx`d+v(QB$~`*HEAGL2$}PNpGIM)Wy&rlTRP(7LRpR|1*6=Kuw^m-` zo;;X(f0z@>BEmOS@w?Q|LJILB&Y|%hD9X{M3ayv*49McLEnp4095-d92Ul*Y8!sEE zzuWd#(l%}*cO0pv9a|kNzZ~MRY9DoNyN4cq__K7&(f3hZc|9$R^i!GM!sEJy>^ciY zyxeb`I+1R>^WRce*Q0c3|83OY^D=o8auw7p_Z_Pi?RI;cJ()0uHCCCaquEA=IFCEN z6bZS7`^u4B72=$dtn}D@jcNCrx!;ZQx&kq;)K-bu7+(t6ajgNFay8tPZIUr1z`7)3 z*6OwVUI<3`ekd5RIKtx3%M&ojj#x~Yh#fo$VYd?EP+$=S*IAf61v^}B6Xhrf3VtBS z4a7}BSzr4e=uf%qt|Ze_t?fxjn6qhj}=qEH2CfQ3~kT1K{t9o#N>F=Ch(3ON7^ zEhxr7>KKf6s;uoIt8toQ5e)i4zFsGGsThoAan7P2=S6l%xXpqvE*EXcE4~>75hnA& zVYnwtO&Dm8IF1CR8p>V}dEAz84hmu%N4>PRSgDmKBeX8GHA%)`L0D}gdgz{7q1=)Q zRy+VKA9_bY=ESIm>+bf$?U+4?S z3y5Q*unvRLN-wO`urRCSzKk-2b&ymDqh7=!5aSECEhu#**#I=zBGg=^qgq~L$@Km^ ztLW~dWz?5ZA?7@IKOMqz6uxQ)i=*{PTgddkowte35j4N9kV*;fZ#G@5HyG z{y`jr97FrwwZkEl$tYvAmw_RLxPgTgj)9~>JD+obC{{>Lj1j2wDsz0?Ew)p#^0zG3^%bcz|*a8FL&j-Z^?wY#;a=kAUiQHV*q;h5-+lwK)NJOYCy({ znV8g3cNh9~VPp*Yvs6~(B4Q+zkuDdOzGAs3jEDgW&kNjqBJeGemUW*%={|8?BCj&Z ziP9Dr=0j{mQsmg6AT9=mePW!){Dt;kY!rovk=JJwPcGMFQogwLXq9jgy|vvg%6s^^TqdII3L;}T zA64mX68T#$83SN!E)^kTGa2X;k2cZ%ofWjNyIiCj{XTLBqjYqqgH9Z(p=z$*GHxq2 ze%~NA2y$I~;?ZVmsI?HR3F@lNG|F-uVtVZBbkH5gYsGOS2j^>WEFix7@dq2JrNJtW zH}m{7H0&4m?BqG+;d>frFTWe9rNKh|d@jZxdhac@)X49FE&(x2rg{B1>kiYlW*Z&b zUzL16?tvRp4;yo2bW~$9P=>SNTS&tE=O>)sbs< zoF;~^ir?}-l#xu`dv7DN#ZIwEfUaDADM`klUEFe@a?uzEm-5hSA;Hb#q*L*T1GIBn zyyy11~Gnn`F!eg&<>kzeWS&t4GFEmm6qD zo0ax&x6!s13+>-#r=44@)XBfQ_;_ulBA}py!eU~zpu}hiaf6PF#UGSzP{^WOFaftT z+QfkC^T&A-V8kAV?Z2Po5gg=Ty=?!~+C8?i{F z5RT_m^FRX91o?p9O1#sLhag-_zEZs2$R@7Z!z&?9Ga!cnFzn%Cj?APu&62I&t}t+-*cTuU#}p8 zAXG}oGKL^kZu1KwW_&6v{Qg4OgmMO1<1o+jvxtVrgURnlSz@;!7CIiE5^Dy>)c^tJ z7gn6fMHrt72{H!d=w(4yABhS@ zm=><|`ST)UP(RW-2JveIA;bAl{zl(kOvnJJe|3GXh>%Hqt6aFE&T$C4X(43TZA!pI zvsy7S5sV z$nTNBxPs$I_^n1uwT?difkqMUN+z^tWufM#{z)aTSUa^;E0#I1no(bmG%y;Z8FzXI zh1oFL4ZaU;6To*s(Td%`=>K=zQpIx*_Y+4QpY)4ka2tT@;EplORa#lyM3rSBQD?Av z!Z(1}0_=u3ee`|xba+261~?z;gm!!SVt|}nMi|p}Z86hz1YT#~57-LI$MOohNF<`bQ9SoX+w0gN)hJ=}5-7KslnU z`x3D@ZaZAX$CPrxJr}RK1+lWD-NtiDiUdQQ^bYz&9o>Ee>nG(NtV85Iup9t6BHxd7 zc~8Gr5GzObR*1P3@5i|-y&gfvG}oG`t3z?=jpL|;t9@QkXLt|lKt8XBk1J%1g%0hl zOdf~M=Q2NUlZ=7PU>0*Z`gze37pms*6(;lrw0C?PJ-0mthTmR z{C3WckzN;}ippB!eV88yW1kQFY_( zWUV-oOck}qXvfamskOC>u3tY#4b>*<>TKcbw^NYsX=r;S?Rq4=^)PMeI7uU;*U9hq zh_!rMi#_=rHyc)qjLAJxZ(>~o1kB034*KK+HT3YwO4_&GCOQ+6!v?Dgy|@Mm1P!jm zbssoYMfv0Y{cwTya zj?X#i%)9eK`HJ0a=m=O$!F3MY>J$Q84~0MCgV;dGU^`y>1~$ z0Z>{Z7K%KFd_pM2;s!vy;F@4CBA%rtHYBPmjAFs^`a3T1oHx(9Xpk4b7@(l+2I2Jb zn@(}=G@p|JG3&T30(ckd4P=lxc8vw-ATNqiWrezcK!JEJ_>RjxK7NN=5H0{Fva=W6 zq8ycTc!#2Js>o=^GPolE(hk093jq{zSfsl=zJc5xkW{K%v9@I${sTX+AWxJIUh_(y4c{vdgRO^GY>!w9!| z?CL~WwQ+w&yPD!Mg+dyWM6MVzYCtH)bCv@gHx0Q!hSGdwEJ)W_V1#=&Um#9BH~hjH z1ByzqxZu1NlZYtM-arPW+U8Zd_v)0orv|co`CT}KAYuBy3C^52Jq4ZTXU=iZ;>jhbJ`I=2!3!*|` z?W(3^K$)DqU>DyB(xu=s$%)bz7{*-ekOT<>0tB)|v5}RC$?~eai5SL~mfXSmA#XxA zfb{~#2+VbuzcE$d9qP?YK=HqRDdetW$WO?#Kaei#Z=yJeCOMs@`x@3gQ2wnnVa>UA zz`Kk6{!%=%$S6Yg&3 zwXibCp-iR{0dkkLl7YM<^&(55wyr6Wn#I31dpYgcb(q?=>_}XZ9aHXmX?k`$#f|&O zUVTSe+PUumI&tD*+Ogws;%Xvq!CY1lMsDTm` z7Bo1n2CjjkxVp-)NMON0D0lZku!Axa3sfXn1Ylu`gqy=$r6;ioSzj{V%=lq;nVN#ZFrgdss{rijFM@XiMj<6r_V`$rIVb3%vAr8M}6z zr0Ry_i>?huvv2vAt_aj^SOVW8ckml@ioz-qc8i4|#!-w9P*53-O5cn`7C3Q}SB;St zvyD2p-^#1XLln{-OiO`CEk#xRxVE~Lwrsm~(RK1#HBc{F05J^fBz#Y6Gu$>TCS;@{ zZW9|1P)?t_;8;=W>tAeX2rID6jS8y)^&F>#R8Pu=rLV{bDl$Uf z6hJzFd`J=y#recF$IP5j5K|}lpJJ@+)`vXT#a^Q06B7$bz0eqBq};Yo^h0{!3qQmMV#NOv5p5b3UCowU2NE19-7woqej3)NIN^IE5wWz5E8 zDlcmi$B|m*# z!mL3K#imNY7mjkDTcW{h05KM}cQ|NgR~hZwRZe%DtQBirtZ%VqgC+cyHkPxu*o7Ah zAFrX`y{xz{&KK`qWZ9i%edrQ$t##K5`4BQ&xeT^<*z-!KZmAYJ9l#&7h-5INyLStP z^@($f*TuvD1(CqyJ=f|J$7|NnHXc?2c!l7<+OB;a!SzN^y$Q~%g0i`a2 zi*_giQdzWkkXOD1kQNV_z)sIhGDZzp0YUha3w=Dt4%1&QA1J0}%nBe9g&RBscnu1d zZ@A~!;YaD@@yEn@H6oD+_4VjT*}5O}A2H~J~^*V2f%Nd{rHBjXh10=^MME4~YE`e6OF++ABg z_mh9bGdn)+}6zWZ+`yI5@*vfIyy>z-yHQ``ct|(mfmM% zze0V$U$Gj<|IBQd7l37=k4p@5d%iK~7mL9IyUY0dtX!^2x%AxdiSY&BjP}&I^&oxd z(SI$@W#ZbkYy6To>ABZlqEJjnx8L$OojCe%;%o}&AHBW3WEwj^&LnKyiqe6kPMhWsxx1fcmPfiBMhb>XT)~07w|L+hW0Bh*MW*P?Sq< zEWb^x74jltRL!s`L`+68;r>yc<1mLE+*={W1mN7o1z}~54L&#r%NcBZ!aNA%*E@=h z<<)VB#l|O|iqqi(I_ln@IH-ZIJ(2yZI=2wd*E)LYSrzf3%1#xFEqC0ass~#v=IE|Aq2jpojRs$Ni7ejpI;8t&&0>zxrkROWtDuvYo#4#1?99ZsvFE zDHNQhi+#`2T?Z@4VBSW3Lv=|PQT@X&^7>+$e&NU4=*!>PN(~JSTvsNFM!fWH&y#dw zcR9DWPC9p`LB#j~M#f*IdG`qY+{fDJ+dtSs6_pKK-&n_l>D<+SrXxGbXj?}Iz4mq; zH8m;TF(#+a(bU{E`rPBK^z;uq$!4!6yIpCs=dOH}cJsF$+}lAfzFsf#4a_=wXmI?U zM7`V`#EjG{09dc8-6yJ%Hb!uNw*2 z`-F&hbF%|F(rec}Vsi}UBM`y0}Lz>s6bw%%)^(!5+4FfheFE|`GC731T|0Sjq^nM zdr+qkW(7GHGl&Mggwk>Pp2wEe0A8Hn6-=FNlQ&Ofa5wEw@sDB!Unv zp|lAe>@{{WJaSsgF^u7JRTE zS}J}F-XYrw+DKuG(R3U=^dRSBv0@WDPC(2B+~;Xz2EJDfbjz_v6KB)mcDpGMh>&aM zjYTnIl=@cU^`OqNGfo28#xbNg|A+6MoWX81B`_z-Fc3mNNBoVLvQv%!MZ&jZAzNM5 zM7z3AB%YWK5K7VTG!2a0plBS6-aXXX(v>)yLX2NDH#bKi-xV63QWOVxwrm5)U#1%m z(KdOZE!#NS7V@vSepC|9!Qu%-8!YrT)A~>CycX!*9;5wxc%0ZvJdehcY0u6Wb#04M zTT7VgYJ)8NhNz`!ae`uBjRm)n+XgSJLwau4XirM=`9Z#<5{$TP+!goiRN5N)%5q}H zfc%gaXBa1PZ2*wSZv-iPoGCUD1LEPvV0I$LY>sm|MY-Qa#J`ml%G@Y}*J}aw0)hwD zAx2}I$L9RW&;2M)<5P%PW+c}F0#L`3<+G$k zjH;L*dqAFptb&aNa03K)#ON!K1L_kyv@xHcpMxk^+uh`a*D=Pjt36Oy>v%j&9Mr(2 zs|xAz(7ieyW7AV>i}GGr&s0|uz5gLTzDr5fl{)IV4og+suM<`T+`Of z*YLeKzPmg14Uj8j%or=z!^y){V!oDy3=q@rp}NNXiN7#@unfDfz;$e){rmR|%mUw6*It z+H>#$s%<(#=iWIho>|P8F}wG4(LE16PEE~qbb#xmdq+KWcX2*A?b>ck%O}>RS8pis zDFBR7ASBf5EqFap$L4`&hiq%ErBV2e=(7@-Z{_+-9v5*l5_22+^P-qB{EcFb%)mXE z&zFoDvqU!WJh|op*)i`73Hh|8G5b7;d|}=2;@eJg@p=Ua^FMK&o+9C>kXbQrqm4@I zb_sk@h#RbzWfSNtun9z3fn?&vS7*ii?(|0}$m?}%GO4S{o-Z}<4NJ$2QOZl4uUvVX zg)R)=E1!$L1@_-LfEJ#$3HoNfxVv#~I9lyuO;bB4Wl= zS5?vQxIIb8dVLdI2D5ZzPX+Z3RCAlR3DO6cn7K&xESEMlRPj2?A@U9Q1G6;m8Bf$p zZoS7w!E$28U`>%mW~L7Z>kiluiZ+jQjN1reRRf3_Gd;hJ#|(I`iO~4iF!lFcp=(#p z(&PlU4lv7W~*JN?O@{~bN^>~s9Q z%cSQ*dh?Cf>B^;x^yM#ql_sZVsJ6jKjnyXV?$D9P-%jT*T%kYadtQ9ud0zkTpckI| z0hhI%{_IcxgnsnOTh!QMPLkp`FA|$R=O6_13wQ7Pt>u~r91-*5Vdj~_bT6^DAQL0DBiV5 z5-gVR9mp^8z7k+}CCs}^fiTypECT}zi)Nn6V9M!ngG}MYo!doGo;S@%5o zqdGFj4Lm_YS!ZRTtAc_7pSU(04zqymVL^L}ykS2D6Yfq5A!7jaqqQJp#wHbE0t;A> zYzOz2b9*xiQW7L-SEoHWR-xQV5hDg=ldD}~oIxAMcp(T_;ZCqHLZ(>I`9m~5bcIF+ zE~TX#J?902)QezI-Y_#FB>;{MfpFA`CJ&9{a`QQHDcW9{Z0!@sMQH6b)2B+NOy-SfXfM}cC|8O1R++hBM z)fZfr0r)QD9mnC$ax-n5gdqZTrw0DUJcaoSV+;O;tHDf#OC~_hG&P3PQcH7$jvUa@ zfxS9GzR0w*EA_0^Bx8W|uhqiRSEx~JA_j`}zJBc;zaSZQY!9$35$44|++t$miIVEL z{2S^bf`st2!*POYaRU#rRuM9%>AZTKK%4wry32m?xj*dBBJ7 zME?VMswdZif#uK`?dY^7Wg|@@hM|lnsf76-^F21wK;B2ch6`ZqoX2@t;+PL1yNh`y zPZ_9m;Ed&oLdX~pEs}WA0tgi-aXYuBuBj*|n&!F$x!v8RjM*Sxwx~R&TCI>TpkN|F z&PZgEF~<*7a{Z*gKN#D#h>UT$TtXSu*48GJo=XAud_Da2BpDNr^Ll&snZ#KIu(T?i zjFEZOrI9iFyUR4&NdNpN$XN9lg^agS&~TClCYpHtUqvo&Em_OE$X4D-7Hc`Z`qB&H z`jwI~P}X6C3(BgYWhb?Eo}ejb8R;DNP}FjV$Oq|cWQuX+s{ol9F0)uX7V=kH^J1$P zD4ygR9b^sq%*v7ej$Bw1GA0um*@a>l_kxV^@mS$4?E|)ybj04P@{;6ig8NHJk5`$QaM zr1O_&X?*OhL^?yG36u__>z4EfF5dkdYa5U27!zT^IB_U!oX{%T{Ojl z+`AX9i0hy)ffo$SSz}{kJdOsbx$R~pW76l7O)_Q!qnKn2h?x72r8PF1#1{LHonI@jk@Dz$yuK zjK#*}Opw1JEWW3fg|JM866ylxbM_;u+b1d!cAmgd+I6 zO`K2x<%#c9+Ddv^;G0`{L6PenD+SsMgnq!JGm_1q)JsLBV#@6Ic|;qK!B)L`{s_*d zRc|4)-bjtjTe*zQ;yNUlI|f7Cc5n~aodgOcV*p8{pbX1afsjF-q|bE_d3$(q8jb0= zov|Rzi}K3ylu%SEA_l^?f!2pHl=ft&G?1q9K8X34OzG-Z9fZyXH zcS4TNhl~NxHZcZ4;6}nd5&jnJ-kjmKh&qI|55~jIv~kkBJ1XWbv^B+QHcl}y$iv6K zVjYS4hH?z`k8yaZ{)$)}Q20afjoo9ec{~%rySZ)htx!0svD#z|5aMsZ^Km!cwHVs- zeI|-c#GvdhU(BIpIKye3hrM@o0<-~Qm1Stbc3MljKcF0uu<+0R| zmN0X!+;fy9VL-OzQzo#QvGQU%liUFz1B)(@SxY0ocCnhcaM{j%Ge!^G8KVPx^t7`J zatzVs9@H@u+i~deX4lM+R9o=QE<5epZl@h>R%)x`bDXNIJSJds z7>^6+BA90|=0JX4TjW>Ir6yy5fgzNOLdL*V83-CRK)Rhd$8$N0#JMbEw8$8u0FMDa zvfA5(;&G*9OxJ>ehOYb`&l%}`X?d10sl4JGuE|BlI0O61UY7FHwlMD^A6P0zMP(&9 zSoQ;fQYm@5cR@`$2wq`FU6mf$)RtB)Bh~oDI=JFiL~d0hUj> z-EqUi^^i3z76Y#XEP{x+bj>Yfb*a#7ZcsLvBEM*3s0aBTA3qOk!lBWiaGM7b2k-In z;57r{CNaljGaNi)N_}(9aMi3983RBkfi*^^o4I^pX4&xQUM(_aAVJ1d@p{jp zB4e&|T?FaG{))A=jNvtKsmU0~(@-GKa2vroNu5yMXlH2u>kSGSqx{w+V-j6mJw~Ye z`$mAwJGv~aShNyiMoCgd4a`G0zu=G2@MMq%#sZ1tr!gM8)%V~RuI*^w&0~0qjDhv( zV~;&1+=gGid|6y8$(R7Y*JvuIZS8x~$e82DkBjz=c04}L>;0RKj9FaP601eVY@8PS z9)!cH&x44OSUj*6Jk%y`fV;B$j%7&QMFa#I#3|Xn)h^PGPKQWvLjYw+D^H5abK4vu z{shc{Qwk3yqbr$8pxA+siC8R%Jp*6yNISOK#lP@ZDbK+LQ%yA{JDvCs0t8^QAW)t{ z2;dkJIxNuIViWm=MF;}(;T!OM9b1%d!ZDP=*7n8c@U2qVOkwfYN&*4{1cInTD6M2+ z31kiwT!_N}lXD1zgChaqj}tR@oVz`)AD;{fVGqhpxR}ZYrM}EuN2n8}Jn$O{zVZ>* zL7sypk30wR5enC(fVzNH13q zmc{Ovw18l1HhUS(%_O3w<^gMIx-mP!?#zXgg^Au;`Ih)aiZf#@#O+$vvQA)4??)l)uS@= zKO5l1eQfa^X!DuZj=E6;g#&el_%INRlH&#U5yS>U9fJ7XOdBiJ^4y4VyuQ{X=6#SF zAPliVpl^^D7rfZOq7p#=#e9M}roP537V?>Za{uCG2VJ>lPo|4kZ1lrdjP&dadV2C1 zJ)M4AC+0?sbyCSt41gq(&(tCnAsb*E>b>Ek!O;LA9?cNX$s!gR-+u2&jye&m#^CBTCbI6W>;@4&V&rizf@cp zl*9f#K0!_uV%39ktgHxAeO>x^2%romr}I$?E@$K{El|Jr+^%c}kuVq(vLuqQ_|3$k zm@+JvHa7%m|8AdXHxg(!WsW%aC*^M~BBs4cPoI6fnLhY%6Ww>JZgILp{da9z`p_ed z^q~jqsiV$FQkUc8v1hr;!Q!F#_1r(C#EwBi;QnF&M9i}<#0fgX_dl3RV$g=gFh(|d znkL82C625NvqOK#YqIpsKQ}926_ZJ%tP~((5YIya+DKfigNqC0xut01B?o8O!UIKn zvrX*A$J82#C}ha!LO78^B5n(msQ}~x#Hf1n9T(3pF8ZY+N1a&rOem?Jy2cS#l#5IV9U*E#uR%l$qz@E$0zwUqie2PIK?f(SCQ zzyw7ub{seyCLYYpy!g}!#gT`FB|HJUUoxL1pOfnyTIbS{eje`804Sy~8C|&Ip$nJY zboPRq-hOvMSjFJkP-20gL16Az-gMDB7v_b<0(SmZmYc|7GiWNev>@`D_gw*~oZMj9t=7595MV)NiJZmE;BhId5QI!T64IAld9(uhX*%F*D8ctt8@b zABZ@R^>Qu(5i>Ak70TT0odL~MRT-iFK^?vF2KRp+P=O~aK^Iu`^WjGtdCXX%z2s=Vu-tz1{(2E)9zdUw zJH^))IWoNrAP_%-{3CT_SidX>X++FJI+isOCklj)g5>kgCH~q7C|;ec1lUwlte7)E zIuWA)8{Opkt28KX8(%G;Ot6s>nP0tQz2K(n z*F4mJ!<)2VT3h65pYmMhHQ9~>I9AAUiEQW6k1PE+EdCuF@riQ1ewEAgiktd--868+ z!{w@Yb3yD9Sjwz9#D-(62@8>TR}0Xm^baXAJL&{U4Ggcjk`{2>%#>RfckM7%f7vUQ^ecyfzrZj+G$A`I-o>O#s$FTJ?ZM65?d!0|+V2 zO%~BMM#h3-*AbozC1;_}LC{Doz+@AOaVSWjEXA`$fJu;&6Cpytd|oRi+g>T#7ux)2 z4)RD1nEsuo7yF%B8qLBK8vRD?s-l=^FjWb6b!Z1Wb{(ek@4PIIdwe0zf0)Ad z0LAr6ziu_xiXD$=TOea3@!?tsP%siv+ExZo&WP`n3A6$Dt-dh;C16a92OwwQ-ejJ? z6=WKYW2`9W`oZozVVRIH6>sGE2d3;M;&QW8iD#J%P5bDSo}f}12+uPvK9cD1cfmE739()`B3>zLE4Nd^9y{_<5|cri1DKbDw2y+ z zY>99G3)*i?xF%EM`T*LZ(w?F0f9!$9L=2P;r}jDM)X5zFxwMd_*iOIWq92}h3zuc+ zyV(7{{2DJdv@;Fz>xrl0bohWykSy5%YZwIZKXEjBn|bP4xFjXI=T!PNFTNZn#Eb#q zB9RXf19@3)m;llB`A@ZrjY64->l?{f^~==I(7NySPaE*m!p&x&=L3nOZkoulJ*C(m2X_xqov3_`HfTpLW_`Vp`)YftPx6r)PN&on_ zUlP~g+oX%4m7;skKH7iy7|+WAYHe#zmYX?xj%;C7r(|HA`Xg@ZLoEMFAU=r}5u+v) zRu4Mi?n|P%(V8SIR6$M6onj21n;oNn zdG0m-#?;&d-CeoGKznz>EuJ#QedzsnQCL??S9$|<>EbKYJ2E1UOWb$cmCr*Da40En3G?rwVNrI*Ct zhmPB6M^|y?u+n4s(i}GPUc2rUIzG%tTia~(fxEZRE%$sSaYb>EdquQ~BB1br0q)6` zOT-L}M(CwCJoL}so2G9(IU&*yUYeoa8{YiQ?-N-D`??y|F)ITchm{@>R2u4)o%qU5 zYzt2sF`>j=5DJ!gTW+P&tAHmMpl_fkwc@A7bNu3Mw2ZanKBe+@H-f2%GVgLxA zP<}xHg(MYP7;F~5CwJNe+?4GQ3ieFEZI>D#VsNb%cs^bdg<7_ZPXvWPQYs4>>`cdV zp*XCmGK%(d;fkBiU0h({BfxDkF4~@01o6VQltdo{n>yh_aA~Zyg^bN!UXXkpwyh^MI91IB`BviQ|S`?i^H`R6d+hkWA20Ra=1Lux;~!-av0AT z;OF9BSi!)Bmvl)7pub{X!&rhb1@D9ZbO3D};}QPNWqAQWF&2#~V;TrYq~S5_SW~QS z@LR@j6Mu6)a1Ow~GFBD<%UD>ypbg?1u=5S>)$mLx8E_5@Mp(T-IfwBS=OH6Jd~Y4y zcV{i_+TjpHKZs#m>rpK%Q&93VnNXM@HWI9G@l4G3`*xPCn1}%~i5Rmv#^tI-P8a@c zHK3%=*HQ*nGD!GcEJ#b3rHGi7TEeJ-jSFbQAYu^540XPDXX2y^u-;VLm4{HhEM(S0sxj4D zen9crKNgAR{+ODr-=YIsUZLA|y+}ve{(-iY{}uI~`>MFM*f2$}Qk~(e)aLj$ncRPo z%!e%uMOu2EVWEduCF4AwAVCqoeux-g?b>>=fq5CO#yZ>KhTP8MnN8>i;NlDxHL$GN z+GbxfB4(`s83`^{p`><>duZpjZPZX-FBH(5SbdbF$H}2FGc5tNHwJ7B%m&E&*!V1E zUtm31$Y5OnB4%uo$5?Lb7-Rh`_dy2>_k>c1hV}P7x7X6C+jh~RlmCW}ocu{Tb>HXc zzDIt69)0xZsJ3z!jSTQwBaw#sdHlZWqpyEwn*Q!9<09EAKS&i#KPK*JXindifq6G` zHpJQ?%z_m*KEUEd4NTKo-bOy~fe+Buty`(Ox;k&yW^0cE8s0j$P8;3^D@4JbK9yqm;MZwUk`#^4KO4$PBgDVy=aZ3NH^|kHPxphBP)wYn=>m`HHB7RraG$$6I zaoV{xM3eI|7Q}Z_YwJ#N4X(A=%Eh&1l?@bTK_e8Hr>43XEhILE!onn*XD1?p5RSwYtCB=9RT%7||5jAi(%j5M^4dU<`&x{zH7{0>Ds`&eZUEGm z+>wJeA$RSo&!O!hfvko51nlIIFc6g8Qz02ZQE95^9jBOW2QLI^Bl&Fy*tZN z?lHOhfUJgWg)-T{yG)RpD3cgB-zCb&|rWug`ATTDU(GD;c>$uHxQiYH~8PwJk`reh- zMWINybkzxB1^okciZ)Zn-=Mf%)3GeTvWMG59uLNPxYkvOn4wVv%fpaQV&WPJ#7?ZP z((^I&1t?cAAL|!c3_)kJugku&0J5s0!x(mz*HGM*#a!iPxd1!3OOfD`5Hd*N3h(r~ z#u#{|M^T;xf;t`>;6Fc=tUP6dEI|N&AQoGE4Xg=q9Rm1+_`||;0q;ZJ zVYLHUT+0n`600<J-9t{6xU6O`Yjmg zU2nyJEG_j~_zluBTfWe*(2qdEpdAB{x6od(CdTO%o=(61x;UN< zpa13GOwJ`2&%a2+V}s&1)&fVm%BZ<{H|Y&!Bm?+&c6QR_#NL>r%Bmo_q7f0qA8yJT9rfZG0It@2K98`L8lRY@s#-tsbSTDY zv=u0nGXXLNK~FcaegOBJW8(ojday$5>~y;0RN;U!D^72nofmUq=a&3jet>9!OoW(E zuy(=N(cAA6F10>VR-v3QG#VnCVad=!{SIs z)!e@gbk`kGs;Po|v^c%|hEt63ci&b`I=!C1CC&>dxbutA%db26-#9O#c;U3CobQb# zNJJf7?(vE^AP4sFf~OI&PNKXx1hJ{3)9=jlLMlS-{C!Zu0M?rQ|UWog$+S-Uv_~!$VFav{2Slsca6vG{v7SKlF(hhC?*r7^t zR2}3+t)GIPYjk6f`_8%a?}c?q;jYF9a*hL zdgcX1*}ttLM6k9%T?_k7-iE9MWq5-%! z1K9$S1!PMm;Mxo>&H%*P8qE>{4wf><52s?e0U%=9TWxf>+duM zjz0mVr1$ME6W^*pCw4$zzPfn5JnyO?pGO&=v0f+^Dyw}|QK^#UIa^2eS86H=VR3qW z$Sa6E3AqUdWbt}HpGx+GEC7WoAdjziH)Uum0Ls543gIF?5{m29bW?`%9~klTS|C7r z?(h5e-bW6HgP*PRpSrrb6}c$`p(`N?9zcB@bt2yfWV;8D=azF1kS!0(xu=jk6oOgT z4T{nEv@tIY#TAKi0`rG-#|wang>_l3ZiN1}+Ahng>re6g>!azh*LjV*Sms8Y7>rF= z<92UzP-O+nw!R1%jQZqUQN?o9gC}dn??}9!oY7B;-`l%(Bwbj3{j2{(-i3Lw@!*+f zo}mXGct8*@=qDgl&>nv6H~xdT7WnEv{wI3%Eyax(KK)aV@_OC;VV?iZqW$QMHrl%5 zpg1ovJ2^maoc=bwd*uz<-)X12Pu)c`&Tf|D{4B#&Q+Y!d_tA6@FauX#r>}qSPlRRP z`atO#>1w$t+azO3fb3)pV#eei9QJRs(SBaE=ZkOu%OuSvgbM(b355k33dHv}^&-#PXl-IgJW9NqyU~&PQugXk?NVU62UER>7 ze(op#h|8}s@mC5?r<3}6FH_w2B)xK3@pJwwzwnph-%McligRX=hWr1Xu8yUT!^Mut zlS#&OZaqjJdh}l>{z}K?%NHr?J4-)0^O7KAZolPmI&t*j#Mu~(&=kT zyqRod3;>~A?kw8G+5=<;%>1e~#?0 z;J&9=Rw91O*$Zy5gBZj|O1YH|C|1yCYFYxP9EmGf-ISH!J17+ zP4)O4qH`DB!sQjx$`JUn6~1RFlxZH9|*mJd&;@(Dsw2twU^&m;I^Cc-3`Fa zSH48kVidnV)X1D?Kzd%fW)fwMdVqT}K)PGI=Z-k{6Qv$O96b4bxCw+33D&eRC8kWG z*iA+|z5cdhfq`K2SOB9fghDzVR~DCvLdH}l$e5LXw;*F)T3s>*z<3FT^Kz|ZP_DrI zd|0?SR4b+p21U*>84Xm%>rX9Zn{+cKpQA>m3o@;1Bqpa8Tf~5f0W!&$8-s9}9j7QY zu*|TX$8e<&W5Y&!i;+fHCiSvRrUqm*SW`;aO|XR23%O#re3*8}6*=2(yhaT*Jl57K z{S5A-pMGwNu8y+o%eSwDjLC*AZORxgfw>1HeI|ShmE>JOo6b+>&KEH=KQE(dv2j5Q zs3W^QBrMo~CLWLS(gCa@HYyo|^#wM?%9s~WAY(0o-Q(HhnWCe>p>Qq8m>WYr9xsAq zi(BdNp}T}aSz;w*49E$ecaG*2SsQ_jiN?>bUK?Ek z>OKmrM?%JEt|GrL!efiJoGi&0VMVdsK}HicUP1oBhAqYNGG8+0^lPt*_J>$6Al=TK zIU_cC!$RfIp+odP{^ZZawSX2G6ElC7qTv8-*|w9a>srZCQ7z6(L;?%+qgS7zC%*d^ zf{eN2j*oJ?ujY3;XwSi8WUyAHk$rKVuiegZ`s*+K1`juihm5sB>11{_R*Q_;bW>IW z=GF!ym;-!Hy=oWwI%^zAsjKg8z#iT{-eucTTOxsxKfAmx}9oSix zciP1R`-~@^_8geifAszuKJUmo?dr6Vhvz#73*xxH&;;{wg8?qv(goq7AWH>e!2?or zwSh$-f?NU~uZt!oCunwJgo3_ta?TElG&egy0pBzkbSxZ2uTvjS#4gvA*u5}6J48PB zSn}H0nE{Ff=g6q{(Y)&lO)n^A2nFR*mU95cl0saKVb?d5D5Y>&w%!2u1(`0(;I?RD zGMM~MjK{)XF^|m%VvkrUrF2<#^w5J`&WlM02+VMS=U=!)BQqW$*xz#O(Ztzwz_)88 zY9QCl8#Loi7ecVu1X)&0VBV6bu4|&FjW;VP&JlW`SZ-t=v)rec9tv;sc@0 z<9)D3Ast+$fiySJgamEUntOE#e(en9|?$VoU*Hi*uOUQ6_jE@&gxUAb4Ogi-i})P7nVLMN%b~6YdX% zB6R+;N4&d^pDp7mWGg|8UwF3&zo>Z)>S-rWVxWsEl_%eI0Xe6dF{GKjBUYC`o=4K zM`gv*^Ko_*w>~7ah#1IzHPx6)^|atNi26bT)I$Rr-~*W0~h9w5~yNx?t^;YO|0} zB@qKars^LLQXjXOm)~~LnTu|^Ht46`!5O+S)IZEW2dRPeklL*o&SM>z34h zBHc}yFm}ZYP%^z`J z?%K9T$ZZlUaZ?6a(8%j75EOunZ2^lrkRW&u#z@4=z(NHjpHh2hTzt1f=nP{sw(WwK4 z?KJVSp!eNZ7ZQI-#OV|FrSGuJ2T$^I^09X6Y&KIvwe~~~<=VTK5D;={OQ3?FsytUv znMk2%S_{h<5%@jh`??!+^kW~;4rKn$c{e@%rqWj+e;?gpqWe#2_v>$cf3{%D7>Rr> zTku+0b`VfjY9WJ|B2Y+X#cFrF3_t)wdJ_yI_Ufsy?%9qg>N&D;h*QlX8O(*0K1@ovHm|_WEoRmV-||= zVgYNTJ}w`L=B6&X_2`FLSYJF=fowF>ReI^o7ldWZo}G8l{@o77}72JzHv=lI3ATWOSHpOKZ6kSkC>5&hqAjY(WOEa_) zSf4;Sk4-2N*l;4h19Nj#WsDB)El;}jgL^dG2e&N^oQFgE%7wxWxO~l<3TlfiryQ_oFviG6ylUG5ta?bt&eO(Og3l*_s@3ymKIxbO#}rD zuFVICc@4{$9cgaLR`%VmocD1#+*VeWFVJLCGra{pwglvYldza z)1^?_Cq4@bE5rpUCa}hp$RuLaz&aSR=2Ac&v6(Pae}?fC&rp}!V(7#;EMsrs9<|lW z@Myv^rZu}|j8YdV>&r}B=Q%@-d@W-#0TL1xILiB%9&bTTUhc6Hti@IWjPJX521NO8 z&#;784_MkV#>jQ7%&XW4veuR{uq;8Fl>ee!LByE&`F3tYuzFS6lvT91^#qx3K*w3z z2Fn*!^D4Gw4AxkPUyNjk>*^`lILTl-!`G~ATq!0nCSv0X+KU8; zjrHiVObZxehDLnCWo1p3;*MF4Npgc{9ghnS-&P~?rC7%Ngg7oOV?y3p`j7wdx9HVZ zbH|K%{<)_pZmJUPLCZ46-talmwn0EzEa`JUh*;;mi*5{@r+3aiCoE&`x#uzRMLI=a zsI65jchrbPJT&c`qqpAt$Hb9RV|8WqOstxlvibS>wf)kY5YdR2UVM5fG6qO5`UVyv z??0}v`AfCGXI_}1QC^r!{LD|ZCw}DyCV*#OoEHAa0SK-iexJ5dS&a}2nE(8OGx66( zKzvoZFb01plhhTLi--Y=N5&9+;=aXhkd{KeWX$1i8|`e*E+9b|hO(&?c=w8zUO1~P z_STAw5lXOxn=*;Q$QU!-f2u~aPp^cG0oH<$f$)HPpiD3Jj+2!l7LAKw*RnlA`8mno zb@E6hFE(`Kg0Z}=n# zBJ?Rd2c#7G({hmMrVQ?l4(~5?$6J2&RWK5d&6kwPhP5JLav>Pf(S^(DmND(EA)bd; zO2z=isgJ^m7+jxX1acBFtv1nrfkKEFK%0yKmjB(WNyY#xA!KkLQj2;@#^U?qeM zl;0_fDP`Qn1^@t-S$+Lx+TIzWy}OLbvc|Zqc8#Odg*G9xR%8sYl-os#&MiEyXk3c= znx081-#5vam6I`ehteh^ECU#6dxt~ld*B)#^$M8+V<_5Ev5C-?0{v*kZp!j&k^*S! ziVLRzMbY0w4wf}e2$BHEmyCgx2#5~+D^n(*oCcWzCA1oLyYhUOYeC3P>i5ZWqodEY-FL%Y=*UMoW{l``CMwloYiU;)oAVJ(k|cn9-sI#oA?^l95kNi<<$-sp zmEJfG!UP11*XvJO)&Mq}^1P|3Y5twEB7&C^SV|**Lqj9f(2&}gZ8EVO%J0MT=I7m1 zS(&aYa=J#yY&)O$YyALavr!2d%sE4&J|1gBVl9DchyDR=9&4Yv8Z(vgxc0Aptd+{j zOi3~Z#9>ooy{KD1*UNwVqd%tpf#Jkcwee^F>%VZrXr`(v2YvIazei^-zAcX9Q$fbG zHfJB>zW?Gho$vQjII7IO`#SCP*!_$36cVV9e|c$!rag+qA?l(uNXY_gjcjDhiM#(P zaYb>kNyd}_`I9j~s`$6HSm@+FRiLCCHS^_fjwTt_J8!MY&)rx8PFIlr`FoRzzlc8m zp=KdOEQPQ9U~WD2kvyM0w*fP0@j}B) zW{m|_F%b;7NKfW zc4j_}jJa*Mg-&sPwXhmw3>GNrm@xpzm`{JGL9~-hKsl@?W42Vp=+lp9=^Gc^%O+zA z#ppyZ>5?KJpl`q`BU70K!5aMpZ3+DbLVhVop!ERMNtswSbR6)$H0vp+6meN zVxbhW$Wask3Mm3*2>u0$f_{fSSj*2V6jReyp|D5&2tp*I4yD2d-=XI|*50a+4Inh+ zn2US`cs>*hCtmF#hJoB+jr-hgrT^m|_k{GT2N-(mgNvK zin3pspKEx$wsMi*cdAynFVy;W5a!RnJR_`yB_RW{0;I)Cfz2#Zxs7o%Q<)2B5iziy zQIj#~|B$)VinrwwGAKhRiQs}(0_{)|G7^~YQPvXq5;BsE0jUmaql+CnI+(D_1b;Fe&w;*9q9~k%4F74J5$UFLw>~m-jxyTrt2hk2M z154>PvO!u8p+AoEZ`9p^uG^@xLRs(ROU6u0Oo)xexgg0H>8?xyBo6um$O%}Gs4Yxz z4uGq##>Uio4etWsgKJ<3qmJDI3j!$7aWAY{)Z`B=5&%38aa|-CBcBJrrI?yL!Ev0& z^B{++^DmzVYZt_wkrq05Kk@+}297#bjeH*dh4qY@NCL(t`YEPAr@7H?t%0$AqY^TB z_t=DAZ0eHhP*}#nWg^xOCQhdg@;J@^#^Z=@m_A2d?eo%1!iAs&+QTio%eY;q=1#Z` zGw9*ME++1oO5B6bT#Agr#(Xsy1Iw6PWDMlA@9{lO{vND7Iuhe*aj^bmbYPQ=*}y1_ zi~*D?K)jfpTQihX8nuIk_}9Lj62LzFvDQUGelB33`udX-dL7=;YojF_ySpsUb2|HEWo>{+&0Avv4tcV zbN}7HD+XsE*R!UkrYIU3&VmdqW&n=Y0=%do22d@91sDhPGraKob zSmB;$e8R}`bpCAw?#n95BV>03$jlQBSH-;H(JY6S3C2!QmyRwyAOugB*9Dyxn@_;8c3ib-Mdw@X3>^Wvme z*^q)YpW1S7Ihf-yT*j9}-xU@aDyYv(G_t%^uCe(K^5{k&WF#45<+;_;jRM~o)y9)I<%IguyywXJQiW>{IDD;5Sv zd}-EbXb-u_7zwyut<;FMGclb$j%h+QwJCCCfYmV}^!?1W|FE20G zBx5G$6f!s$YI&WcRqv$+#`=v)$RN)cZ!*Uy09lawJ1wA%@+YLBkb7`#7k}%0ch-x) z2Znug@v2+=mcZsSC+AU;G4))(w!~(EBl|0;rAg@<-~ZvXn4j<+UQX^{tVm=`#s{uL zq?0igF@~3dj9EV`llL@~#;+C}lh8OMEn*}JAz}awL~2VIbTEzAWJf_4uRThcT?FY> z542(tm1Eb4*#y&cyGS}cPbOJXTxTV3pps_Y%`AX-(e;UAH1A6Z0D#5f$m>~=sF4>6 z^)xlVmHNhy)4=4x#1j(OVD-7$z@je`qw_2@Ib&(*)r)?5=Cn6S!~i^h(Ol3#FP`($ z^Kbk4x_DZWL=3PJ0Rd!hQ-ihwTtYq_!UctTzUX%qE-{{La78c;r5rJ~WZqf{;eKtVBh+Xw^Aqi6G z)iVns{ms`V=qulz55@Ee5P&79DFp+tki9OZ<*kc;py6d?5wGX_EPk+yg6 zLUx%%46wZu8(x$;KYSogk3AHpNA8Q#(L(_`buvtkJ`fYfkRHA_F4`-I*J6HCsZi?W ziYzxZGA(8DM}E1T;{Js`iUr@@x7CPr$B8O2UMuciQ-HPF^o*U(U9c5I!~h`ZM#n95 zy|03LZ)nfuYXP_$$|PdUX2d2cc5N5_yj3M)3bcrkz=i=>z-0%%yVzy9a$rt}0#Xf- z4N`dwXps_XNaa$6MMnpAmuC<$z~b+Q8?95f)QHUlh#!o1cv#k1DWnU_Y|yHsg)H}A zZWZe%74d;F0_BDJRs+{I)~A&2nZWlAkNJ~iKY(_Jxke48K2l=>WC6I4kx=SFk;k;4 zc25?kHMKpg1thfx%Lm@2P8$Uoc`ZTK4PX4?7k@kPdlN-MJQk*b-mlZZxUwq<0v{$GEGo0_iqKJ8 zgPE#Ti<%@dZt(}=bhTH}_(DKCxHp~o&j(OWN`+NNyGv*k>pe=Ml%`T&-?c-=tB zXeqJ_B`O$u3C!)7G;*P$yoH(?47~YZ>8BT(B9;wh8jPO@L? zuv$Rh#SZyQz?}eg$HP(rN`2(5wb?3!1NaJdEkuQ4ACvL6t#+{}g_0Qcss$)Bq)VLT z0%Hu6S;)^)z#gP%WsK)2ZkZA{Y+&GlMq(}mKJb*W-%M6vVzOftfSG{7!6ED z=;Dna-53i~_wGvWe-Y{#HIl)q6VC(Dg7$Loa1HnI2=z~yXdw`#OZ`C_nc=Z!K1SXM z&m-8O#Lo>ytEsHAmEw`&$MVYD%^Ha6X<#anOy_$2^wwoRT^4vNC0;R*FA;;f1Q{Uf9(9fY_2}17#-RQr zkp@6`2cd>~a=IckVW=d%5u-=803d#iIAO5Z8zJR*I@P+<_v8K?3MG=TC zjB_y6M;itqf;JVlcvr9m6w13-^}M(J+D=a!PS0%5 zEZx$D7!;*ltrW3TgtW1wsNGmah>DQ3!BB8D)XtL2=`rMV&v1HX+CS6%Y&}!;%AyLc z;Jr%#31mX&cfY*IFF$;l$V?ex6TZp^e*J(20USGMkS*o*zjr%Jr@^8n?$lM+l2Z4wI%pt+R zMwaQBw}1DKuFcEfv*ZEt2ic4MfvmFN7&4m3pb8x$U;YBA zZ!*1K@;huruFqnRh)(a^!?qndE>0@ueOu5Yk<)<13BzNl-&44T1<%1e;RZ6-E1Qt7 z?rV_7#hypx0=k+T*eK|tEFe^|w+Un*@|}CcTn;4*o{g3LoM%%*5uH$>a^HOqZ+lSZ zyo=Q%oVJK>wgt}&%Jf=~o~<-G8(3MZl9|Ph&HW$dXU8QJERl}RQ!+m{EoaU@t0WNc(WPMv*BLg6a&xw@u7n%YiFaS1x>vfks0so$ITmQ1QT>XOZ+_Z!g7 zEoc)P&1jFKyV(Vgw4=A}X>W8Cz&S*x*nUhuvh7M=NXo8EV<+Cq$xw+qJB=R?Rs40^EY2>l8YxQHcO-GXr)@c)!N5r zbSzQRVI6a13h)BCWaU@6)<5;TU12aAJWd zHjIBk7Fo>b9B=C&8>GlyJ=Z(jm?NbyvKxg9psT1D$%&{72@BU8W7lpwg z8M6z>kBkvR#5AW{9qKx5P37wKTaHjh0eJjU?whxN_{m&ifa^r8ldc_9nMBj|zLli& z9_)=AD*y`rpk5*du-euNui5zxS&s!&_?nNK*wACE^D(1DXDSn;{c?Y>Pok@=3fnLW zbwkxi3K_FHUnH}W!@lRc%kWUYDh1kK64wcqMYfVLz^9rXI2khch<@1j6LwYAx+VPA`lxI&?7=`!!kLPskI}?}%Mny{#DUuw= zq{V7}>$hfa+j8Ii>FcjQ`Oejbgw6p0XIw6zMK?a66#vA>Ijo$$VInKaz zjtt(JcF%{9f#AV7YdiKe9dD}8$Ht9Q07pOPu;D8aI>q73Qdxak)}vD@H`dLHaGXmx zj7#{g=CrIu$Fw~*WLlLW&Zm9Zql0G)1cFjzu0N-DEo>WEhl3v`r=0X%kQoq=^b_W_ zTRjmeEn^Q0N9aLnFjjD6u+Ip4Y`E*Y&}2+5smZ#JCJhn{dK^L!>7?eehCHibr)Sp9 zekPEv{DyHw-$0>%7z_Q1y_M+aDD%9lC1hwTzUSJk%iN zTK|DS%%q+n?P7GTR6e^I(sxRnm6RYJcgHczelrWIQu8c!-x#jxojcK+tP`8>(&;-E%ZsdBN-*bRW zgbW)aQ%`=N4hv1lVEX}b{%=RdL>4AxeJyH;kys4Dq&iPcy^M|YOGo!*7a8-Oc|M$r zgX2->y|i?;l&37v^pY`=#c5ezT{L7*OKX=oR$5wSO5fej4j>tmOcO_Y>@3QZ*F1DEX2cBV6hH98Y1eA-$(DoM*dD@{{Da^W3Y?9_EMufdU2~CiF!NP zU16dSMsY~$v24hgv#MXe_(YwYIaaZ48JnzCx#YCZUXU@6DjbK%fS9oNv-_@a+)I!^ zWBe^>{bNG~jv^j(Z6bOZxB~X~!rQ_(|;bIEQ}$&yN3u z&t9^KHZ^e4B5^9tR-C>zJr*4V$8WZnoLZG@Hdm~)n>W_91pDaMVMnq036ZeFHhelA|wBCd1Cb{jg9Us#U)=Ep04qdHh$P9+8yI<2!8C!)wE<_AYM4kiL2dT=&;Y1i%nSyc;F-Duw z2R?5=PAx{9evXrjISg4syU)z+EFuU(kzwZ;7tWmQ9)~zL>=MTa z28g6E&Ov>ZT>5UXY-3Aw45_pr<7=w38(02FUeAK|H1a^_)XuhY30G8`4XM|o!$wzT z4lF4S%Duky`KYU_*Y&;U<;h3m^7P{>&%>*7>O`r|yK!kg!lueg+O8}n*gB8Kb(^8kDcx9@~f>KU}PM5U@~FJ#Tu_5gb_#Nc zezKthcVa^4OqJa@I=9ExcV`ccAN+Vird&K&>ydJ!pCJ$Y3UbNs_;!W*T2LJVnFPE9 z0N`(qS*Horu5I_;aFZbA`Z(}rLDeBI zo~krtKrE)urF9f6DUo#*3SNj{461ob`G zdxi7Neb$R*Rl5iGiNzh#+=BT!z8;s0Co9Zv?R`oEF`1uVGvo+W>zyz7Tu4I3UY|C7 z>|ACt=9Bk-B-4|ln`L2c+C;D{M;7JOg%?uD7;szL=DymN)^S)>9*}m|9z$L-W>oFJ z8=t&suIs)J_kaXCd+C+K$QW&>+{hR={N<$^CB;Q%KLtoZ7Vx0wpf8o^cxY+}8rg@A z;p~01{q^<=ZZhVQj&mH^>A>DQIgv5P!t&^aYBR6+m$J?B>5VmsuB*Nma7cumk}>Yh z>M4*LZgPUZAzCQzdqL3H<8C4bK$zI$-pCR@+wUw9188e|oRXsFW_dj~5d-XTiX~zI z?_rO--xZLi%zo!4Vjz)bXJ@6oWnJa(y3|&)7%iwaD2tJtwz=E4BojnM=T?_ZfxMpg}%`I9l8 z3VP6F3@c|pzMYK7;yw0~kYN>Taj;3M!mB#29cMb@`RT`Mb%J9vvr08~swA)xF_Rw7 z#`9`e5*aZcDV0#TR?l7AG@_9MOmY|jC=w84ERpM z-YcUJxCt3nolZ`#87DP$j4|Xm`SjVuWzI5)Wd8zEA(4f8!*fztO+BzcIeDAcO5D{tz(@_0CwLUl>sDY;7WMyhN=Rw1((XVLYzG}h_7zUIhD(!7+E6w7Bf{fQVNpU$0LQ8}`v zZRPBH#y%5`N6yQUmh-A#O{iWR(KcL`N6r<=nG+>C_aZYB7f1jygp_5C4cXUEAuu^z zA`_FTb<937r%!qwa96Q)uE1G|&H#3gh#?{-x9A`29PArxr&phE(0M1U_Yazto;cWx zgC%B3jV9{jbXQmwR-TiKm;R1C^~BfZ{Mnaf==%Fo zRUAqw;i8a~ZInyb@$bml3;(G!x4bGx>#s|DlRocSTt-!<>X1)CO?g1R^?H+BQhoVM zw~qJXOVZx?H|4o!zb%hF`c)aeaYZVmH03^Jv7k&0qhp;@+vz_y_o=U#m$O}qQm^%P zUv-c~@N)`m9TtL+u_)2wkDbpz#>|Y%{l2T_Z$Eg+7-aPie?BP_vyL;L&(qrf*;fmP zIoOh>Y-~WrhLg6Q7Y`R15yuTLAsHs;boJ7HoFTJ6f8tENsGi7k}h}2ds=@@e+#oKrH7a0R+-v>>|a30;yUEJrp zzh^NCa}VPqr=rh=O;ldmD1nV?l{^(vSzalN3q>+By&?0e*A5QGbdFGaJwsVin`mv7 z@x}86q$tC_gpKvV9OP8`>pV3_zGc!r=7r!b`>=z#&eWTf1a@WFT?W5#nw#1~eZjGQ`T=;We{=L12Y;bKWKt zt~4thM(+3Mq*-ZJM_G8u7}9zK%VTo;J{yxedm*GNRpE2`jJrPprz2x9;07mHq3*E! zfOpvoLWVY2iML2VCqr2uQ=_KHkSaV!M{BwM8`rVEqKz6c;~PVVbJ$pPJ+6jhS)~-0 z)=EiW)Fl@`0xxE7)0}6 z>~J09$kbyfK@bx}5L(}fI(VdDA8xUMq9REGR}pN zK_1f&Sk%NyO43|ea2zKjzo(9o`Rr%07+E)cn&S|9MM8v9)W{p0$vgwb9bJQK;5ar4 zsJ1Qbh0#|?aKDhYE%J?e#2L@~PE0vt6vC*iyg|xCP1=7Kv`oq1@TxI9>HmCJR$eEo zkwNWSONKC^A6+<8DJA;eL?_t2XfX)$?eh5&G51FtNA8gZ>Xh_#8`3w349c&MJd7}M zHnA!TC%Ej1T<{vu?J z>i?Fu<&sYj_Q~!Ql{;&upD=dOs~P(&*a())s;n7MxfPX*7TBs`kGJA$O9`;gENZKpvlR^n8du^p^3-Rhd)0 zhxY3344biNQ4k^~gY0LY68baI`{-Wiq(%nmGZ10JyibJ8g6gpo^YNU@l1^o7u1Dv( z4Fy^tkPgV4dBgzbA5KO>SL%!yNZRTjzPHYiKinm&D(bicm}@rlV>LuWlh@s#FGi;rRyB_rS#5 zDJdyy(Xrq-S8sm$3yH`4yd_CbwV2ujYQs!Vd?p`#@Rq#)!OvuTc3$R|S2oMi>Wa>#>k_Iy zqGMx0W!816Dt$}F#^+4C^baq~a?%Vk(MCi-E$H(xC&f34B(k(5SFc`?yLaA|k3RaP z)?4a5R@A2GK2{-ZM_aZ2CS_^(YBz<7F)gv`DEh|x#f1^b+N0$Y+)p!PWP zPB!rSS##~v5)QUWSxK$ha~5E^c_28c1Gon9?!Ov1nQ)Cqh9r;Iekz6Ns{Pj z-oYPPzQ{ucbOQg#m_ssV-y>f#hKZ3){Moa?LHggKjLgoi2pffiX*HTC9c|^Cil!HD zzP}_lZ_Oq?IZDfmPuC?rZH4aDzUozVL|ZBYZt_jmyd&tkzd(l2o2a(p{y?si~8&X$mI z#;&vK-)q408w#WaeTBJ!zRcg81LzNg9&;}Jito5T?}%)V#Ua0HrR@kZytv>*40VLk z!L_;n@I+jeR|8U4U8MJRQhTA0l$U9Lk4{N+c~Hiu*7W$Qap0Lv#fuiqck9tf85xTj zr)$^Iay6PtWPFlUKO5TD98xmhzQ0oVkBF=&(B-Ajx{>`qPOB zH1tsB2j)rk`k9+g&1nuUosUXIMXEl;TtvS_zR)KjiXnvQ7reVk>83JuS`De<;uSrP zGe7m(g^B#h4!!+B9RsNyG#rY{(T)s@oOT^fo6rW9IKgHi{YC%avZ+f9^a_>REI?tO zHH%C{430@l+VGoPBVsIQS0XJT_*Yc_E7o~)L;HRxRAL+=^c(x!`GUE)t+{+NN+cVk zN{rlqe4&5tgpkppFDeS9ttDjU>1^@K_h)2Q=U&7r&LiXoV4)G$;kjOTti~+%vzVMe zE)`WRn`F$y$ZfOu%a;1aR%3shf8-e{F0Du*V~PS%vohF^jH%G^`@|#3eJY45ag#BN zv%@++7nx1z*Yx`Ker$lhri!;EV~XOpq$Dt5$c#*63_$Mq5i+EG{rK9vk()-xpLOOt zyQhvHA;Z}{11l2M7aP{OYHVso$M=BBq(Qmf(=Sn374{`BQjudzslM8JU_%yH=cJ}) zLRQyCWpHd>e)6js^Xw6A>!j>;p7&;NL~i#l%esD;n4Z$HbXV^5-c|WIqW6eyxkriK z+lU31pH@y~ScwyWffz zhh)rFP`A{(tyAicK3re3yzj{vz_UImLdGqlEbt95M=+)sTV7!IG$9vMUkPjB-%O>d zJS?SU-DVt+X~zvBzvkvVtBbNkebu~FtL<&?1L4oS1GbVe&hgJP(7_JLm;;J@$rwQFWmq7?PdANo6|Bm;Y88^uKM*a zHEk;6Nu=J-etQ4rl5q-VMCMo9N676#3q{1Rs&8U^T|#Kj353E`vJzP|BnlfYS}^dv zWXxJg%qa2}mBk^WNCAu#&Y7NaB4WrPY~dwiVnrLWR-D0NaiOK@q6+8TpMW!wF*o|v zsL}V_BxDj32k*3-gbY>7Dv@B(v>8t$V~#_CaYfV!;~8aOB`PvBvSO5gb+rW9oS3|; zCB+dlHrWe=afo8h?*VPaz6`ZByPK~Rq$6a!u+K!F!uaI5_?K0v5Cq7Vx%rqHcTO&E z99@hH_Rzt2%~YV`S{YXJ#W9Mv=Qn5>!iqRzQjaY?<|i>0(ARX*$nkoiTb zkdbtW}wa19Nqi^nC0G;>>frFV9NqWcI;=I0#fC1Dy0}`@gWa4ef#R38xhWc~3;c zveqm8o(LH~0Prz<1f zY2Se3G;-tYnPu(si4PA9Hm#jgFN_Bq=+xaakI_CACYQL|ahZvT0bI+H1nj?+%RK7_ zoAx6UI@&@K42ETO#fh-w8HqS08kW!2wt}?Hrl7miN7!q#QO~sw-@O7djQZROA%j{o zKO2>^S*ECd_sXop^%hcb0#vWV$e2QrF<#`S*X||ul8hl0S>I6Ywqy)W zXB+VXkOhz}?6Klka7tVI`H+ms9qzhBz9Qof3K;{eEwI;wjFm;q!IkI~D$AeLxvZrj zD7BTvGOoG_$B3SUtT(^azkmDdE%M?s_44>5H5tpP?n1wHx!Y7~jtDuR}8CfMO?P%)I{gY?pV!@;|4n z%t<3NI=&*7kU=rQY1)5(S?=6hGONefuz$m9{0V&f*P4wX;*Zq(%`U{`dS8|++cLl2 zCU_jKJBi~%6)GljR;ZyAZ-o%!I?)**!J8G{4N(l zW_|&}LWgZJ1Q311`3^@_EM6vM!5WGfhN-`moorv){pUv&e&S1o?uT$JvZ71wjG%X~v_zn_Dhr0ueCt3u>skHks#d z2xTH?b`GM^R!x*ecV|e)Gfosyqp(QZH&qUl>9cfqMvW1KT;v_yZA~Abe-Mp_>_a)#A@q%z}owKZ`W9ZQ{aP2^7%I>hd^eP4gM)_E9e>ZwNC0E zqSoI3c-Aw=|a|yXMH3FZWXuO|{fV(LC_@81X0v$y=3j4`vfLwM zT8#r1{PL&YliBHUvq+6=+fC~E+nuH?S270ho?b$RK1*FwH|*)hTtq=%wC%wwxOHfN zT(Q>xv?V&ycChF1EG$sS1ezB42IvRgXYc}&#jiU!=Q{UtuK6&MF~$3UjB&%KA@%{> zWK2x;;2xC`_>BAtzKaE|J8F72$ruaB7}Ac}=oe(0w?MoQMT6hKk_m@oO!n~BC-q02 z*VjbUzH~C^+`hZGugMs|v+p$_V`ULC$vJ5~|Bq$0XPsO$4R+%t3vJ$giL!p@$B<5G}vzz zCRpr*jCtbGDhUOhaYB}W_STS0sT?Kcv6Z!lNCMsKkc>H?*a;cKik#;9(iCObf&Y0B zGRM1|O&m$LvK_iQLh_s6Xf;A8Gm`gv|7OIj_Q@KVUr~*Zm<$dtt5URXj4}%E&59lB ziq(xMP+p)o^xa=pB_e7Bs6E#@av)@^5|$lw5=#8#hn)~HoQHtteRw|J50nIoQ^=T0 zkG~|<`D|3~Pp0-eCP+U*2BjPW$Tun@rL1jRY_3m) zFpe%9QA7p++6AJ5@oW@;XpsbptE5QO*wp@s!^;>8<$7eTSc*z2^;~CT|0v&S-@y?K zI&>1WD--tuJae{t$nc)jFXIXa7{GY}XanRJG6Z8L>!K5x@9_c^W4LL38e)cbO|%i; z@w~_#NKwY4am48F_&vs(U+SZDpkHK5$e=$_fFYczbu+5-3l0y) zge4J+OPi%ESgp^!Xx@!;kWJ(s4u(4P8OyaZ5h3QJ3_?L>tTyQQ?7d$U|1#$rFl)%^x(9dWWBX_jj zyyF!4NgoVo8#33M`9O~wIj!aM40H@+JN1Gr#P~zjAg8HA>NFcLKH0-$YC6?uT#ERo z^kQt_)Z|_Oxrp3hKJ){}i5^8CcJz$6lvf^?53Z!H{sXT(AJe%VCyV2t=3MJcON$I* zgm){}*P5SC)oDm`*L)30MaD$6pVLMUl8o`fr(qrdEE&T%7}s$>ruCby%xk^bTF#e@=^w7! z9NS)`BV&k);a@+nF+YWf7=Fj!hh$9tuw+bo^NiG1Ig5Gsdt{6SGITEq87rf(C0}`} z&N%2Tkn6}OaP{Wmwq(rB-X`fjebM~AFgGiMefP}YfcEI@J}v`#tWadklaK0r5p)*U z^Q^qXy`dE&4-c^w=wgRt%mKwt$QZD=9GBzmTT>dOo5UGVtmHXzPhkD<*i1e;no;#We}SWzB55P9MfuOV@`0TEv_(Lc_3xNY_6fsCe?y-x zE#X5%?-MgCU#a)T`lQ0gs&^cknF`N>(^{pc_Qwt5*kT1HktKe=_ZFN#^k-IwA`5W# zk`jpLtE|NNrSh=ii1z0)S&vSuBJ7arI46pVLJ};m(|XlWu|DUVM?cbjN7@>Q7-aa$ z3T;5DA#FeX4&&OdkQR{VVIIf^g(70;6FB{tL-`xW408;9hJSh2{a%biBk{aEKXQk< zfqgyc6ggR$~;wCLP!0aLsj?=#&{*aSy-2?E9L^&Y~kG7So46T(b zpD@3qMqgKiMV`3qtk`F~@*c=lWZ$;PFtLToH?~B_u#rC`O<^K`QgQ1}$XwrzlgC$d z-q=5V)lJ4=v!GLhqirEGhcPjgmByu~FJj0MY!0)CO2-@R>9uRpkujutW$Z%cUpiN9 z>=wo?(Kw7_>%_3Ib2xq4EWlEk0FYtUk<9(+AIJmuoI&5CF9IC(*ckS^#fbAgS7%P3 z+<#zt4n3icDnoW*(I-~RECGoP>M7)qEE)VXbI z3v?B0Gd5Ng%dw*&GhZ_|&qbPLdU{@FribO~M{h}Q|2?%)qbX&1bxr3N9rtz35{b-7 zY_&(qi*K824C`|Zj77I4W9FBewT)I}c=*2b-McC`Z+;>R%d4CBi0C~^wGS2*$E2zK zjOq-FGC$iZrE*i-LC@3s^s8=>Eg1vQJNgEeeL`sJ9~saJNixP+`~w~w8RNz7_KkF~WK6Eehm1j= z=pU()SR4{^>$&-mF_6O*6&2=t{be&h z=c@-j%s>x2Bx4RJc1p%9sbPU3Tj#4Nq(8qrRAQXGXHHhi{j4}*F z_bQ_7kV?p))E0_};rVcc;jm>82jWFiwvkkTTRTpg)n?gj;2%>XWO>bT_*06bWk$eT zoI3lsjE(e5N9Sqtuf>)$WkqV}Z8(lrTikVR!Ii5j&Z&Uj{R!BQj9H7#o5|5_lv*%B zLdbN~s?nrYX1RWyuB^pvT#G6cB^y#vy5ajfN^HYPu>{JCHzZg}4(nE_2#iUH{bTf4 zZ||Z6bYkpmR)a^1WIdqm5T7@bFN!{6owBiklfOucHWp3a|m;1^UC%pzM19>JC zEmkB$TxSFB>j(M(&k_u(+|-vNdS^rB2@VL(aUAEocfgP|D4FyXzQaLx;cTTGQ6(0= zZ+1>)n$|xX`y;#4m0Yk>A_ke=P+KPLEzUS~FA4xC>bwi&D*NTo$M$<+yz?5giG_PC z7$YW{+a5}L1;!Xe9d*w0+UEw7Gi#=eIL15h8yl7Ou*1k1Z98-yce|kzpaUTfF|?Q` zk$;ma>v92`%a2c_>QbcIYHEn9P8l}!ZXIRZ3z>#Y1RST}1j7(UHd@CIU63)2jK%@Y z9&A@X+v-GVYl+Iyc4u)BvJgTPrzR1uSs``UZi46-_QY|gVFOD`4$)M|JzOTIOSVK9 z6%{exESma2Ht)8hHXFFf7@X2Xp`g#0h|D1UX5B1?>K$~Vd6=h|1JKV##?c2tD&tG^ zUsA~xNn^bu>%r}N^c&Tu%AI{U7^g2hRj0NQDaVTC?8%_o0y;O1m#IuG)p@&kvjhUF zyJ|)8d}r0J!NG^474pW)13(`^PPhvxKhd`UPFdyy`yJ2i>^0=*F)Yfk@Bbix{3063 zjuC)WVx7n!9T@{wRh3($nY43nsGy(HvDG)cD%b8U%Yq)a;sGMYOLze{83RG_$&CfG zX?z8GOuSD@if);5?ba=c1XLE6sb1nLp^CUX|7?ZS)eM>6-Rt{Ie*D&yd~|(5M%2zj zBzvEo&kglK^Q@HE`k)LCeIqwd4lOoYV3INR_|C`}Z)8lazJk5L?)DXny(D9b)owo4J}W1W zj!JjikW`1q<#uma=L9EGCLc0};}q;H_L?~)V|E7oFK3R8sJ@tNhl51M0BZ;2OUR(} zK*9s;WbANjU$}wnF!DpcYp!pSzL66$I(AB7#o#!mv0R0gp7Im@{*1_=WpKk z5C3#T?&}ceUlVdGG<3!nty%{X`RGII& zpSoHxXSf~}B?#pSu!8II`D&9k4TaEgd=(p~i*fd;GVCT*M$Kl55FR)eO61AQHBwVk zY8>0-9_Ks+3+GYSDAoA@g|<*cOmkD2H0$%()yX()%Zf`RzMQ;PxT4Bz-e2F?B0V=h zN*uM0@8qNiR#e2Vtg$ai+!XHy{#>WDG$_lF1(RFZ!b`@iOI(&?&YmC?CLccniGzc3VqG5 zyjUkMJy|1<>i6z);Z%iud~-?GH=H_EJ5;{-Op(0))UsYHXnynfg-ZG23w81(y~Yz4 zt5n%vmZ{k}tzQ+`vyQ_Vf`a~6RF+Cu30nhu*r0LZXl1@Otiv8odTaRnlo@RLBJz#c8Z-4F(~nzPkmEo7R*`n z9mX(9J@rbPQU}JFY!vwYTQFAX(>RgPMR*UKkhBTW3GT7rM4D(D>bqqNoaxjna*leY z6dKNaNUFP-nTv6-Fm8D-_K%~@`I|N*x^2G_ON9b`l-1mPo zh=sqAZ8pLL8R!_C>;sd&tt=@)nk_drHcI4pm-9DcgK>q^i~Cb>ZbQt_9>_9Fa$6@L zKt3WbShat*w_LC3eGa0%qpIII#5mVA`>p9USqP9d(!AcmzRJj`yNJ=Of<>3EHA6;jBRR@l5OwwiH=63#dpB2Js2#YtKDVCtd9!mDxeL zc_*Z8J`%N*iq-5-uP9K_K9NE-=d}uK&qev{p@Wb-$Z{Wa^p5SyvpswHEdao z6zgx-<(bE8%y?&hMCWH-!-lZq-VZo&Eg3^yr<=$Ph89Ixw(&4MauO@^!aD>xjBdD z85~+MivelJi|4A%JGp;9G@*TzxtQnGV)guNLA}r(j6-a7`Uv_8^+p>J^@r@-2^m8~ z-)_u_Zt&b&$(Y0k1LuSD{LZuS{liJdlpb(0#*5wQJB21=s8?hGef?Z_SmktTN;32b zTdFEzGB8{uv5hMIJ+eM`G6uaC0>++qNXG08_+L6(r&GunvM7+I4m$x7fjM};!`cCi zbvx&0OUU38!Dh0yY&t@Q#Yc=CH?*lA=8VC>B-#L}cI1L-76;@=%&MwOhOf3!7+_fEjZ=XSzIA|CGy8)pF<`6B>u zUZTX};3`w&y-pQH6e+WcGNFi3pO0UxF?EV@NNOAght9(?t;PzDaKZ->#<>CGys$(J zhN2howLl6PLqrT4RFYQAO`tIFbKSr{9IiCif{+686HJbL zpWIu7LLYqZ>f$CD!vexfXF_tM(NRKdp>JUj@b`yT7i4H^UF+DXU%tbc5z)R5L5Pt} zKJ@OckjcYs4U7E%WD)g=A&zqKu!Av$a)z@I#|4f;yTXNbV;tjHru`TbIHtGTSQXGO zxvrOxp>A;?k{ZoR?9kUBA8<ZZcwg$%MExX04XIBc+^1)qh@YU2KgJOelC(|kGCLLd5;5Gjv#s2mi_;jO zxI@sfPY$3h$;Z#X{GNBEf3RAAzZd$YeO?OhNxyQOcQ{;~s1y3G9Sfu|V}-nRT=;== z#>S&EHH(uq5zVD@IR*^(+YK;=%*OQkj65qc7?O|u^6Yqa6HC@f#((p1JnS~;n>;g5 zNPT9DcGXK5N7J)TAgxHb znGWF)(KV@?`7cFid&mT5FDN3Eadx>2?T@n@$0i0YpD~WDk&Apq7Obt6tIp@|5bS7M zGZBHDN8h4Nc~_o0CnO(z6R~(erf0V5XOIZBwOjYa$p=06wr<*gv^_3gc(Gi%R2D*# zVdU{X=&%nG=!eK^OUNK2DCn0a;xX|%fd0++o6+Mx`Z=3ri?p`P>amENJ;mN=8`=k* zx@~R}xptHOLds*t=8ACu*Vl#QPH(YZKPD%-0&=gP6nN`$>0CsPwyjHB%bNC?xY`G$ zI!^@Uxc-KEqTf)MH~Q}{>pe@Pz9Jx<4aL${Um`~vOQo%@#FX>L%H_+?)yl==A&D(( zU(zvRzoW3&26+N0!28iR?X`CU$XmuHkr?!6WUIS)kqa5aJb!;^Rb?L85t24z{~&vF zI?g0?JiFJM7b~ld>~I4gC}Yk&fc&0;cEG0V?yT6fZzxu=;W+5K+?S`8a z;@PPKQkk7Po=m;w2KM7lfoyVY%yl#8+jk_Jgk2z#O2%0E<2?JpAY&YmipP>keE%?z zF|?igRS$k-%yuYDUn(>igDhqqqrCEDovHUsc;nrG)Yi3_zw;quEUcsYkc`_m$I*Qx3VTqMO5Hh_35i@?KXQFbtt4)^I z+I8+jRyjm4*>2orEgF>%KKZdsEv{!>7FJY84jt9GsIX+r%*v!pFRkf4Vls>Fk$6vV zNXBdhy44{Wb3joDG6s;Y3__->Wp4?Ys0yzizB8BCMD2^j^U$eLgjBW}0oi&aXapV6 zKL~o9KT}#?II>ZYaegtOqiUfb0~ARn2nGfUFa?Df=NYS)t%8Xl&ILr=jE%3RR9&Ho z7~myix=&n?p@AN0Xl#|`$l~T+FT9_Zj5*q@?^db8blDM}ZZf7`&xed*9i!yG#}KAp^EYAI{A;4Ve4}B!*x|s<15CWeX{rCFb5=i$FvhFO z62^}uUywN{VaO4?mkjb6`Mn+Jmt4~lGMq!5x``eBeHiK(nTtV&%;s`sjBQR^n3^$n>q-I zmbsLAw~nkrgSnBhOS>~hDZC$!IUDiAv-6Jh3Fcylkb+1rF|v49iq1>9mX;%B=GmBk z!}`ox@us~pfx6}Qah=m~L^U*>mLi!ok#DSIq+O47I(vOEXO2&#B?CeOzOMVT9~t%;Pj83X8E%8}M9-+H4!&B?QLmmNv_Ps@$deQa`9}H z>Tf}ronDps$cE8{>1)XSThdBGHQQwSjY`Q8!&=u@= z#{vz`KHe2JWDxh^U-Wv;=N`N(;5o1nxh9cAr@FNrb#7-)q3)3B_K|omZ&XA+;Qq`L zwK^A~*RUv%lx4OL9M$n)|Aw%%&U_2n$UZ;dIrlFalZ@=)`-d?yhPn9RCS$zFuWwm0 zhWa_p_*LD!S^KJAsnEG;UdJOfosNuggUA@J>&2h^s72oTuvTvNwn%B2v)2ZW&^}E}1=XSszn^M~n-HY}=Bx4Q`3Pr|%c~zYDl8}Lj`TmEnQ#jDg7M=sabJm@Du8c$3rtUNYwN$#Qw>@k;slcEl)G)bV~JV@gWrR9Rax z4xDs^%qy?{ucfHC!nX|d56SFQM5@Ds(mOn(Gh3~^_VRx%RdugQwCKe|dC8QX`<*hg z*sS*m$kkf|hK%XxI3+K>_#3|0j%}1l-_4s^FZxii8#>OD&wUU<`!kL(M(O=T^Arl` z5IE67I?fsYtiEIwC5F(024f7v%=RZ>BL*g>*Nn3lVgZ?r4Brl1#}YC)+IU}x9ZSSu z@FVXyZk5A>3d9c1UL5Wex5C7CI92R-6zY0P>lEiR4sq-7zuS)ywqfd->*WfYR?HfH z5GnNGY>1f7_Hqfk<_X9J+6!5T6B5~DuS=g`({bi=3jKrM(k~7|;aQn;i7H`_B-(>L z6&Q!Kg&CvzFXIyjx;x5*dC)APa8)Bt4V;6IUaU4GOk~9&9NU`9jN{fi;CBl=KasYU zkl|UKNSGq?t`JN71}B-7HRgBP#~jDxE)=evU#)RqPJ-s@g>zA)SU$65d@`!y`9A_J34E?vevs{M<w;H_o4lNo$L?bLfQXZR`3tjstyobk)cq zWafj!#B|h*^V7#Gw9TBTDZqRN!A*aJjHy@sx~4iTW#z4M?XwwaZD#MLCG8Z>Z$U#{ zk+#1hTd&=~h-Ke4=G&lNV@bxRR%LcBsQp~~ZU2-+B947iU%R&14-vgnvn6UzsXnHC zp{!)Z^n22GUb#9aBYg|<&;Iu(rAg<2e8Ifa-drwsdzZ`x_lzxlC^NPS1#Fk`iLFjT z<|oE^x`M27JBu@sG0d$*xE()Mp|Zfdgwgqt!9!{%!MI+W{>Qc6|7cci1l1wTS%m@jwsV99L=1fnAh*2s9ylap3JVB41ARXF z&LJ6-54P`bmW-ime(mK(dFruRv)`~^86I7c(V3|67o;O&xZZ-chl#LM{qczEg|><4w_qgzL~NSd`=~s>l13 z%8=?xyO5^r_2)${p9#yEV@?^0b}s1qRU_>8s?*G^TrTeTHcVM z(Wu!V6y*vbSnm=FDBxz*sDf+s4o0M>FQVr;4x#IJmW*=@VT&SW4Z>`Iu=Og~tg_w> zA_kO|l}mfq`OQ+_)G1R_Q*wW>FXedqF}~}NP(`W|f%C~IqgvX#E~K2pb?)4{X0GWz z-r8|Ss%x9ncu7a-?O$Mc;}|8Skp&YXPS#J~{|~aZ;_NHq#`wTBDVEf>DJ>zLSy%!^ zp)F-SRx0z6CRtpqN&H&J+~7@_8M>DEl*Ih(w9Jp*-0_5!9=mnj?Saw4s%cWH;YhPa zXujb5Gbh7lT;MQ2uGc+xxX<%q&(@Dq}X3vx1F^J)qAy(LzDjN`? z2k0MM2c?R>YOl?>MZQ1;u<~@Lb$n1jJ$?R z4yVZ5;jvYtES=DPM*VL`#JHU-v_ENsNTp`4$vg-_bEh|AoRK&KxZZBfkGlyRYCJdZ zN`EIk8T&v`N6fi^zR6fc-jZI*_GRjc<8DBmct`pMZA`!0_0pGH;TehQVUGg9dq6^Tc9fe%A$~H#5QnP!tgbAX zJyh-wuNZ@q_5h^Zp*^B&B_?VUqZ9H4gJODSU8eNASiD5Kjyll;qIN&>E&6Q8*&3(Do z&)%LgGVAr{>Ws|ZDY(W()l;m^zZ%`zpR<8q3;Gc;I4MtdSC~kVOr@i3>wZI-K&>&p zsk4<8>>=kpXq!!^Qx0Rm0(}i96ZL{)$PH{Wu(SlZ$o<(5XU&ik^lgr5Gx~zPBUV?P z?}|1#0095=Nkl&>x7%gdH+Prag;}tq@{YoSm`s3V@ye210dW9{la7EnM1G)M=I7^Chl!e0 zk=SU=w^18DalpWQLbej@8w>n??1h)93vwO{&9Gf9I1hWm0)i%8y-ZDxY8f$qb1iIE zrx1PVF7|k8ao@L)IMLl;^bbmBM{YVs_HfIc9LKrqwB4TL_Y)2yV|D>fWXvB*U&4Wd zVTw|BgcZCV#WPzFA=5v)D)rSmNVg#hQjq2CKD@Og@84KTeA*p2O0~1s04t$Ta9L4_ zP#jZ(g%vB*PjgeyJ}(fOxxgZBE{O?<0Bh zjW^`p-5&X~KmCEc@r$3!JHPs+u;jG5s#2=MH{{dXGqN5hjm~+At}bsWQ`6JNQ4}hj zmRoo4n8+AbP<`^zki7l&JDb=3_@gWGlOO+;y!Y;V(%RA_;qpcKYEh_7}RzZT|PM4o;rpBpBw5+<^Ir0igNUzfec{9H8P3SA;pFur@vA+I7RI$G5+N|_P$^t7<0RcQYj5c|NRvs zKOuB?8;m#f3DTCKKbVM<5+_>5jxS4!LhSQ??ue~jEm|Mjl@9H9COTN_cS8FdeUWiN zA7w6~@D7Xtx9s7)iDE)N*_FPu7c!faLG7-Xe&V14KmAe!0)Oi` zVBe5}M#fm^ZHa!Fnns5BKLe3JtNNR|+T7BqT+}tJ==&M^dah5K)e_ zmyW**2tX$?hE#W?oukd?7s~V;HeN2%_EkOh<**Fi$Jq~|8Zl%H^8%QfDKY&nRIYm3 zjFV{qnbe{>#BY50NY;xawgc~UTlF~nD$Kv>^x<6KN5o*G*muhn=$MQvKQO*ny^MT= zTndHQ7p&OyFNliB6`B4n6D?%Z24 z(U-h0vpga zFn~T|`-h2`(MO}*vyF`5TJ(3j2!I6(cF_Z4<>8Ht*&g&!`YK)X(kZo-Gt|Z1z9kve z`lqJTMaCd!tbW*~ItXdHz4-K2wV4Bg!Jyuo{q8ojee;WqfrMFDSTN^>LLt5GVPwos zU?XFY-PC7u!;FlKj?4JG)9&bqe(in`z&jN(LdK0iJRn8uj=XV4#(eqfe?!Jc2Auty z_3P3~9c;N^qeS(@Rx?Hl85#5BqaoGP972hA`SiN#2nCFc!5*QWy`cXfm(!KC#51^o z{ovIP_8QFphkM2xP$biorIIoEq$zU)ClM*CNLyB2f#Kusq#3T8;VYtUe)iG4j7%jJ zpxuN?AGW~;&(0>lyaP@E{w7Z^!T>_VD#8{hyPUfiSvLZYko;0r&`IxrFvSocnkE;c z7NNoFQVW!R1crlvZ?)}&hym4AZPL z{JR}cSgex5b;`=tBwTt|dWNDBP{GSa_FhBDVn2{E06{oCo9cvl_g90`)6*j_z4)U1 z!S}u=$Gf}b&;ImJ+;F< zMI-mw!-MDWLsLW0+#e@<-yrfW`8!CBDm5}mWo7}%K%YUrL7d*avt+K#`*EFLeGt|8 zetSKwttG1Czie|Z;(V}UGDbn0Y-YbElT%T7{}adPXMZ3fXK{uiKMA~mjA?4v(03pO7DNv1 z6w`M@Zl{tl^>vW%ahablmgQyIAJR9V{ZZ>=sL0IO$2wK-)%lTrkBp&>Ha3dn+<+ln}e$0xTEF}V;3zy3n4Ja#%P z7mtTbi7u_lk?LY;tt*i#eeGHF&cttdM)qsrJt*|E8@HCszm=7$Q>cwZ`{qM3Ar{bU z-SxoYCB`{GcJUee$&Jy871Lg{Bg9a)Bot$vdS|ZZU+T>b>K2FaZXwr*7=JRx+A;wn zj}I0ZW3ju>oDPosagajBB#!TtjIoOsXfwve=M|}BOohvbv9;X`O~#O-4D5uA;k?Sq zN>lg^iyaQhnEc@-V_F(!Wb`2+V*u|}C_=`KbYu)$1&odKn}6AnuCx-J%6yd_c8!ct z9d1v_m<_f2Ln?#IjBHL|Y!Z>FC8^$J%_x7~=ZTSP`j6TP;APf9bmTjl7Fm5=9^h4IMkNmPJ zlmL5c*fdcP2p0Sv;_*Qi47K%jl-9x*lrumb`F-y$?s@@`CA1AGwx}m$7-_XEXd}M! zlUuZ>C1Oa4xu(}=frJIuH5*lbj$!4ltv|++?aP4rA`Kklm+z1hKmX;le0pP1-v4-B zZrolnE88s*`yfD{VgC!{8RH8FGh>W@?+q;PZRyWkApVfE5Doyc!qo9GCtV&92=+Vl z9rToRfULkV_2H-U^3m0Kxz!WVwwclKye6cDMb>}#>4IFnz9`r4MC2F0nlWS>GA)xl zvj!5Y<2&28j*r2i!AaO#-ja3O+*{$p2*FD+G?f87WM^Pg)9g>cBJXGcD< zp}fA^{p_9n=~Ay%RyffwfM_T~!fTVldCZK=mEBXajqs#BRYxsmxWq; znbs3M2(pZFw=W_@b7l+DbD4-3*Q@7B#Q5R$7aQbjUuZIg#b<69;!}@d7xC}=wjR3O3gm*V>i=(&YTS(Xh# z;iRsMU6iTp6#|mpmsWTb;IFy!F;?i?}Rc`jL$kg1rD&HHM4o+^siV*ghA;lTr_m8d0)w|2`&S#5qUyWw3 zqie4KAp_f4UCGL4QWZD_L1$O8rUS+XzhmP;d!AW6lUOmG3ve1Bh^Z@9ZTYXmEM%m;X7Neqh)=iUy3*MT7hvXE1r6m1aD+aWMxXrtXYXb@hl857`^W}aGIN&rKzb&u3o(=i;GS)&6!ijO=QfK z8}Ask5L&IO#1ZuMjjd8sQ}1l7riiRK=^xgM;}S1&ZnV0xAv06X-=|KUl3)Dd7xKz0 zugKlIcg-;(W5%ZL%lNc&4M4v-C1XG75Dv0^h@kkSH2U?yeD3;Go`S~_dM>OiJX65}*#=RT51CG-dZ6wuhf%`BYPE4*Df(25Fxt95r zx+B_zF-?Ev8LKLtv|lV{WCLf24(g9FPTTC}vt|n;({+5ZQj0d`Uykjk!t>GoX6$Pn z($+Y|(T{8-&(H`dT%ELU7?He(-+X9wBlh9odZabt`j9P<%E&R&P%)0U7uRUiYZ867 z9gu_6VIV+%Ej7f0#oD^_cc?rj<2nYrIzn>!e3j~=0pnyR8iyz}R_WjE4eD4;)zyl0 z&MhtFSyOc>Cr#PjMaCTOUfptx--W|*6WOsH`uev<#dLSE-%hcSFN`Cc@^mu*H60AvAk=T7@v??94>0g!X8n+sl&*Jf_B`Vq1$m&h2q z=NRXC(M zH8Lis`nIze!;S4CW32vbQ;xCV)UWVc&LtwoM!on&#&A7;L-foc9N5LV)D`{`Tc6Zb zNeS}<89vITrD4{jDVs<{#-xjgI%wcMw~vrk@UQ{gcgg)$!jHz#E zF;`ibpO%=``S9$Lv9U50o`HS(v`Mr-7s+mH;NRIcuQG7W=+XG6iPT=)rO23;rl9J% zPJN*7j88<3E$J>xk#%FYnEt0S8J)|{|L8OM_;w2kbb-Byj0tFiZtZo4*b!puOY-v{ z{-*r=%Dl;&%YG;{;(49$aAvr%dzF7cn)LxbCMi`S%Z_1BI9$5O8U)6O$G}2JK*r<) zHrGX9)mIhEV<&?0*du-+w4RDde1w4e!P{Fmt^b|ZYZHHEhq;BA{O+Gl7^4|DsQ^;% zi38>QiQiIXCcpR01v4`<5{Wo@$-(0C9a&x-G=F<^?M;02j?*T;`J2CKl!@E7Z_D-T z*UhnSeC>64`NgN@fBC_`FrS&$T7z}w?@N!rWd8m1%A4lj$(e{wb{i54u1UPq=?`-= zak+Qf`TO+g(^6kwFZb`?H-*XZ|MFk|mvX)5S90s#74sWFnue{>RXfG*43P1ub)C%9 zulC&OU2zEbt!lJj^(M*(VDe|R{cZu}3FifqDNg4F?fXoyv?EFYV>uo8p2!P+kAoUR z(2jfh3@gD=pt1$;3XwxUv4+1FrZ1-IUV94ezZ=eue35BP;Z%me%CxWmhXW30^jS9% zLt7e>-ILe9kbrQBYd@piiB7N}>X4`e>KY}V@9Cc{N6I!Gccg*Az~y;y_V7ERviux- zI{|Ht0}+FSeeI}ABD#2{Q{8MP9Wu{}6W=&CbZlGT*kNxSqL}#oA$AVx5gB9qJt@m@ zIvH8iqOwR09b{3aK5xJCi=^>>w_U3lBC{i8^jMtX;ZRt9;!K^JAmX95c|rShRKD~| zgX%YN9hVrlL8+_WkoP{Clkv%z%HI0K8A;UF&&tvg@0B_SJo)I7oH|}%oJOR4vT09< zc-koz7K`LoPwHy^^Jm$AuxLv(3=uPYmkDgz-`CH1skQmduR`D#$s50#HuDgBEImxX zvDVukG=z*BufDJ$krl^jfBhx|R9udBB=rs2aB8Yr>g$T+i!T?+Pu@_SWHRxk3(r2` z5L#XwsV$M$o~TNE0y~pEcY2rP`#+yC`*PYyFvxM7H74q$(U~tGsxqZQ#@=(oM8voV z5epm>L#~a0y+GFg&X*gdqpe8?S8L*EDt`FZr>Y|_n`@Cy4jm;M*tw{_uFMdExnN{$ zMfIKJeIR1IX~b+>u+I?f4;t&s%;J-5fSkeR0yup;+ET}i^9OO+9)^Ln^oJNSKx$2z7ctNu`}6+N$>iF7aPsr0LSPb z|JkVYYrQd?iBe>NhZpFOc3i%ExmsR)y21SI#=rS~hqf2lQ5-!08w_HGl1LTY+_=upwFkoWpzY9i$JAatnK}OxNQ(p2LC&75i?~jk`YF*W(=i1`tuC zqvtcleJ}U*AXzAG@V)iD*tBr``|RaD`S8je`AlV5vfUpZ@{+k}WPC+sXHtGJ21upt zCp#@T51WU+UaE5aTtT*oTXz(8O<+3U?-jWF@kB~74EgW+G@Z7P$^~6NNM!{|tdp|YCu_Gn&;)QZK*Ph-{ zZh^A()1UrST3h{%Rxj=k+>zx-azC0(;M$iiU6Sv7=R1ib>4EcXdRFUGE=a7XIdOFV z!H(5wP7R2f<{UN=Mv>#5_tkJFg_75hw7>!Xpb9HgSOv9TiWkUN+Tc!a#H6E2CvRyV z(wNzm|I|0{w-X`;!=AnXp@vg{)S47){97fX4Udc^j#{U0Fnx{sC{XPckn{}8#u7>S8K0Qu3>;Ov=XWDyY-K_`7;ruyc) zbl-cw%dD+1H#p7!oYFW{k2E=Zfw+NFeqzcorq=CMRXtijj@!fG&s4 zZ*9JowiEK`Ghdf;mtT>i$1lmr^UrN5r_Mibe!CyAqV}>=v=3@oH7h?eyl}3tRh$E~ zrzZaT{33e|=@17H2gEsY03Q=WgOw${{marfu(jN|7m^9|KU-&*_3c13%=z=@je?gALg6ZzN~9>;iq!W0phy zV0ncUm4qc8aH4Q_j>5Kw9}$CtBvW+AZos9N8l`Brz$$WU+!KvJ1kS6^*UPhy*T`!x z)SFc>r0yXtNjhNAW2B>mQBNpg5HuDXgQ&56AR8b*SdqgDVa7E3obb2(j6(RJinGCV zWM7nCm8CdPa2i0S*t%l1N+zIS)7IAMj0221&zFdy&2c7DXluwu$O)oEDD1&yR~F*z z!O0a+1@qC1)$*7Y_AR2H*%Wjw&1HJ5T&CyZvY@sTdjOp54x6!H3G$~OtufI6<-t<3 zdG-^Rt4$d9RAS@gLV$6|7~$R!Rrg2NWo(j-xJ%4EF~ECzlSVUry}GK{v<2^C#|3pk zy->dpRq2R;Lu3!+1ADE|K157;37O80a;Z-cjXOm;Q;5CzxED@pQX1IR?Z=L89XqS5 zW!i^I3`xrPD-Ddw{N$UaKaWimtD(R3Sx+5jJh&!<2MMhN$OU%KFxQe zGjpRNEYetgS2os1Ok@x3W{vlU4P6~Ul^1OAPMVGl>2>WV0xBy4rXL{_ki8Iz&f*3= zkN%`p7c7IAC^b=dEG+Ko@F#bfcPY#Z13FKof_tXx$=d^&&8pC+AFDP0LTZpA>G4Nu z$g(QSIu3a+q80tXIJKayeTf(y3zmpMw}s4xydc)b3)J@E}$HIdK{mb3QX#e~P8Nj>Qa)?804;=nP zwv3I98FJweg$E=|wt%eZ?wFHfZL@N;c}SjnY)roU^${uCM~h@K!!3jSN_sGF?u3vz zt~Qe2fj=r;{zgmM@;hH`mZ#2C%F+5#Q#uNy+k4SgTcX#eIQKcCI>=tYJ@0s- z)#(ejpXgyn_THmI>>O!2T>36r2<-0F3x)&um=MbBWkB&;&4qH0BN4J>yJ#7Icq&Cd zk|Mxsz)-xa^0q^1M&J7ZX^aFQV*3006Q5F1UA7_KsLOD;QaUX-M;wp}v!c{#SK1e2JXjKuqS%m>#O|2m`w8iY7(b^0*l90V)myEl z@tL!^tVJ#)My_CN0;0fhWV1o>+(KN2Cs;8gMw!BK!rmmAfWd0VFb)))&p3swX}>)N%pFy6Hc9Ew>}$5Ki5Y&JM>4PTOo88?*t=KMOYfC&d;-3eG^TlPwWLTS77r z0hNhh;CEJ`$8n9~`O0(kQdd(Zm6c_3{&c0BJ`py@ab%J9hBkLr&&AB&MA~p2B9pim zj&_qvSg$uT7c;3LDl3bPbE#0EKDiq8g5p~d;$32fgds%?&r1D46577WZ>bO9j_`8o zz}a+}x`qs+?hJXw{sme;jFW?2kQa<~j5rGY4FZbeg(jhBA3s8d&(t?^h-WFpeZ9TP znHwNt){LXtP1vuju1j0XR-I#IrNZG3J^PEpTRx8gxRVSA(R2!nfuaL&c?HECxWJAcfb(4y)zX8GfaXp;;&K?rZ zIs6OJLE$&)icL>qL7OBa_mjwmkeQfVHFD*(7aHV=%QbTGT$Q}^T!WO924qp6kGi10 z0p2a2h!}`*FK~n|F0%KLqx^2SaHJ4mF31MFFJx$82^kAIc79`T&tM;MpFieafU!aP ze2Uu{y&cl+W0ehl>uW>u+rK_4|KN9)=JC4$8!_UCe7?)) z9FXq2T+VTS_I~F^y5pd(dR4yg+`PR0!h)7HxpX$Jb8+I!2M(TlyRtJNJM$%E%=if} zNK?&SQv&Pn%1Hlz*ev}$-;n?xot1Wtu4pYAS&9<~eNMVq?IC_VbH{Q~6#D8JOzFDZX2RPio ze;2U1fxjB1TQ>0bdWI9&)$wq^oa=i9R!6U~W2b`lNw>iyD;rtuQwHOI2018oz3sH8;!1$cWb4>gERi7mnSMYj;=l`;ffy%I`>f*Lf+g zsF#wmO7k}*RMl+qeV#sEBBPTtvW{`QvLVxxF>`%Zjy&_sv(j_-t{R4`64k;6{@txJ zvbZoR6Z1~$3Q}){wf&1^K}X!qm4qaAK7Mm0Vs;Ap{OlYXXU8QJ45S!~;* z!DUM4(p9zPvS+%Lh>;}<(V7#)SJO&IhoWkGJGtRyr ztR80^@h^^9{$7ou949Vth+PNm(b+~$rkzJZj``MMbeR;&|JLORzNA51CUSMTn3gH5nbKL|=!r zPso?SVTS-@qs77?V8|o-Fk^#sWnry9R)*t9M|WXvpdUk6@(e@((Z6vf($^W!f6k%(rY<&u8kw?ZC_z)cvB$(XiGbQCMse zO1t2E#i@qlm%8P5evZprL2tKn1AT)rgzU5{;aT`WpALsqCN30fpHGgDc$|$mH?&Wz zn)B$-k>#+??WvAa2*0A@d9w!*_gYyg)ptsri?(jy@AUcP2LAcai+&sUH#HIo;mC!m zs<@0#q>eE*=dZ2RdQbcY-0NdLNu9ew<;WNIij11bXxgY%jcxb75)T716EO}s?ImI? z7(a|9`Ynqa_!lAqSz|Zs_5=15V4s6?-Q}i#q(}DsgMRwnrwc~#cIX^Jzg%8kH}8im zyxFs8#(=dG_}2@!oxmLA$bcju8|+F?6^&9?TV`Y=X;aY`gTZ1WFX-zaToRL^-ceaw zo|5^QQ90IqN}nevcdox@J_l*?Cv`9V84HlkH5}++}*}$JZ(ACvt_6K_6(JBcAoy8Zt zcWncIv&bYdcQfxWANmzLE?8L30(J{Xu^F9b3sL45*YcW&(GLzc@IRnPyMh1d#0LHu zYJB$^AkB?}~vGQRN&|=-9%!4A@J9e&xoAVSsCFQAw{ zcCpIH41m+>Fw*h7Y-qe85|wVJvdEE)Cd7MP9Sa`2GrLkQ?X?-UZ@x9 zggT~A?gZQiSqZo<{S4yAEyuYBDHm~s=6gRoH;|Ud5;0ab5)H_;EfyAww`_z@s;_gW zBie7BamMDRUK~HRtYZvkx6?NUhsyL`sfJSe4gB5nNBX+Y1m6w(&#Z`hzZmD4QuQYy zX4nG-u$K&*(|hscV-YhJXd~d3KL-KyGa}zI^=taR{hs&S8WBVEOK$Qr8<74N;A{Pj zFVxDZ?xYjTAKCQ}Ht_$wAB@ZJq*jD1g4?HUoG46#4oXZMUKR_liKLKPr``x&~qOpFRH)#9QCo9bSfDF0W zvt;Tmo77_IfJ2^$4nIQETW0{7K}6r>i#5i1vZQuiY~5Kb=O+88gItIhoO4{8Ihne8 z@=<5iG7f8^oMQS1@6R4XckV73Vvn(637g#n>051EI_;RbzMb|@U6_KO0{wP(klk1; z=m!3J4*NrHZs4zTKcdgQfq#w8>+b2} z?5Rp4Kf%x6o>Ezr)FDdC9+N=8k>j~;;GYS01AmAJH_FTDJE|wm&g&djY{(SAd{$QG z%=g2?V^UvVZ~g`)C6Jp%I#%K`IXNY@waI9O^74cZzp!NFuO&O&*BcobH=F81!T|K@ z(o(07dhf+KoV&Qlo-t}mB#0VhPAKF&>)6<&c|S}1@N6td1%rdbrXDSV!BXRUg7o1T z-9!y2+8CGfr=3h5?|e9I#)unpD%Y6Wna|ii%^yh_a*%-z!ydD48<9CD-KPGvIuCyN z*<{;!F)pa0mjHK1?4@Y)yUt)Kl^ z)?6w5X!~3@@TdPl;QYhC9hUlP=b0co{>>lVmr=DpL3d}^kg+>~djozz{k5c-yWK#y zK*!iEAhWCt$_3~bsT=r*5*zsce&QE}!C_>~E+AuMjL#(I#?FR8ChXpo3yM8_%zPtb zNRhyPCM9MvdBHC9){3js3C|RRyG?Mh({&62C|V zL=cKyZN-#?!edgbb#dav8M*w#ekh-`R(T6>QG;5P3W^8~5XE!7y%V%Iql323*(X@wb>; zh;8l}#F(M(a3*Ix4_xLRYEaT20W8w$CK;%;Y)B%xyv?);YPoDPrD* zwql`Vw!l#YvCbR}A@IcI)buf{t84mQOe!i$&3EczIc?Ue6&JAWjMu8ADV7`^YXVESTThGBY!)g$@7L&G+^=j_TRj zIrAOYcAv+09G{z;*ZxK}l;n5zdiXGiO0mcJjs4EZqr`Cv_p$dPTE%@mdwh9$#Skd& z^X&CFhsCS*IM2m#2qy2nIEQO4Ek*R5*HXTttgc68Y<9r3&B)}MET{}gZu0KPO~8D% zo3{FX0P|-q5i&%^oNy7BUPM-6(x-X^NEaD%<6fh*cbzi*YIb^3h6e{!Z;a`@k1Q^h zs+wAv7#rPDWDKA$fhQj=%^VryeaRewe0AH|+yh@LX*-eE>5Aj)+&v((u#0j9`p{uy z%mKx=kuhMKTHn1!IUvow2alOgWDJJFswy0hU#vFHthkO)gg2=H{J_M>YSKs~DV*Fu zz}u(+3mkF?4wRr=_kwYQcS<*TvY*FNq)3el|K|exAu=Ya6XO5<-;8ZejBfl7|F2&q z{@RLbAHOGyGvm@;_aEga@86Y$h}LtULXNl9NPTr;rEcPqY$!;|s)m|5`Sk9XDkW=j z;^YhRjc@)l=La4{qpR}KyT6c7>6nZR{2Tef8_uMNa?i?w-9`2TW2Z!nMInYFt2W>N zc+PBeZeg6>UT5zvjC)qPU?^ay;=I6kbDT*|8Zi_qQZ(fXoB*sMi+3TdCzRb)|+=qJtu5VKaWs6LG{qqFIHOl*h%3l6P@58a>CnHFE z=yqaf0(~l$kP}VXZtm5~>_tI@6GRVtyfkQ^+lkT4SaL_iFp?l*(vdkPLgZGeL25R_ zZ;wjfz*f2X$oYs~JN3QukBo66dm}QN$Qa=FJ7<&sHR_z(UhBjIQN2Q&L%=;yU3V#KA16e^w^~uSy|D(qn9IPA#+1|__qnqN{ugE#12ff?7r1iV1b(V~{$OdM$w8~lPydi;*{}9Tw z_ilrC9#TEWEvLEvc9AYl`|o9hj2m0q|1dIU?@`Fen6?(RF?Akr>@3EE>JnPlHnlE( z1$SR-sCryVik(H3`9{X@Hv|O*dmg_Fg-8@g8T;?l)RZA4_-rFpILvzT3`we~eA6%jjfSnj2%%(zMm+ z0sEbd>1aPC-A8KVnJ14XjwG?H*Fq_&EWIv&_1>h+E;#S_%=wUXw-#u4GOlDx3UZeZ+`h+#Fd8@Ucg zowpKgwxPz)x-sP4#+@$_19H7l7GT0={4r_c)MS+go2ILdW0cFCt^)LPL~~D^?HDH* zGwiM5b;=%MXF%byb&TFJBez5Zq6eC#@!zk`Bjq_2lVM2Qj^ zkbGv|*DF^JDrn2?+JpDSu?sOvnFoWYDIoGJh!#_B)m;76wTp}A?zkThNthKvE(jgf507;yboxgngk z!^z{TTHl%LcfZ0*#5e?YZYd*nn}`AQUrVgx6zOg%kuSekCyg%RBQsL_2lK<9{bWM! z&pN4C(!m)IncpoJGKPAFSoabF$OP;~OGLQInD)+7($Lrd>)R@$cpMQMDXxd zRz6TKM5g$q1%p8GbExs$nFtwV$Ebd9-!B~*gB?WbF8U99X%Y=w?OJ6I{74qtF4l<- zc1pvy{eryX-AR`NZsa7fnAAsLej#sKNDs3Q9Oc6x^&wzE45LB{Yq^hci0*)NktRE#@k z@tYlg{LYQF5}n>_+f2*P?n<(!S8JwH=Kyr#D~uTn2WuH z3}b`2o$-`wT|maX^jLxgNrUUR7YwNh*4D}-Ui9=9GKRLLFHk@>kz^KJ=SbZR9iz^< z_%nIG$;3Rn|H&8@d8yr_bFUk;l~*o0b6QfT$&QTK+W!y9m;;Qg$r!Lr?eAXWq`xxh zQrK64&g@ps+&~Z^kPuG1Q$7m9w%FyKnGYGmBaLc%o;z77jrHW>%@@DolQd> zsSL>1U#T@h)xdMvHxpzGDUGU2XjQ**&d69srSoaPwHg&2dpqaW#l93?V` ze|Zj!`d~1i%0a5L8t@y^IvoPXOzONs-C-;&FUO6thjQf?je#Qwhjg|i3@8Krq^e2TPTqVm63NTdDMdoyNYM^+RPv?1^N zFv0dq>wKV2!)k0Xu5n7c!Mj`1h5n0-AUeu|@9D1-2`7;oq##=$im9p0kYpx>lFDb& z0B{T)#7nxEaiaYSBa1$ToQubt&zXQMVvZovz{(|eL`)_LNxH62uZPUPneg0`5nqG9 zaAXX~{0tx$GRE(>Uby#?IcT8&9t0xBf_a>A0MNgy%QmE~u~aIu)Nd>%r`Ke5N#_z* zv(@Na0c)}***Sm; z3#T0qA|d0Tr#EQ_exAt~p3^!tbL+9Gpby&jPX~vLamEaDf2ZsB%-7kFF>cJyN3|ct zO&wQMWbQwah4VR+F@Asq85$ZgY7Vfy}sn|Gqhw zu?q>pxd1YQbmyD{33BwPv*?rS_4V}`Vu$ZKJ3FPS%88c4hru)8Fy}eWo;_=h1EP5# zPB;gm=*W>H<~a8r92_*y0=m1qH}|>0FT!(hJ?iD;$&==|_nq3>+6(~&_^l*vCXsbQ>aWFlp{5LS{QS?;Vh;(lUACe7#Qg<+8fEJI{$C z!~|j$q4pyyYJ{#PB4b8V3nN}!*!Hxmj;#8~hQj6>@vKxxEb?)Til zI2dQQS77bgtTtrjVd`wXJs^pwN5~kIOq@zQQ+Y5TZ@o9GebJE@hu9gYQyfBGV%8Fc zM6fi~m!>#H`Hu8pw*Mk`aDtpX7B-uPFRx%^un}ua-hOvh{$%Tvo&hw>r%0F^p zS=%``xw9WYzu5^9!+A|QXJ$)S6aw^N_S)K+gJdgq8re*Q3iSsdb-a-&^bR8BvL$5d zv_F0JiAc*4$H{i;?Bizh{;9+U{sW66D*yBAbGZ;Qe()n>aD3zVP&3Eq!OVFxI;T-5 z4Jzv#-FSQZ!Ar>4IwdN~Jx69DWHQOQT)~{^w$IpSbb5M4?+ zI~+9djpE(EZVoX*Yi&oyka+-~NoD2s_Hd!d7$OKDCmDcy8b_XR4046@h+t`GNctH_8OF7UG;lvNL|#{!b90>Q`aL(-!>`11<3q^@hh$7 zy?$p5VJlb}W#yAsKUkkuw99*ZG;1I^NrEdh5kOB4jKHRij4Xw_a~hA(V%qy2G~Hj*O{rZMd5b%j?N>9~>F-QWcoF(l%|NCI5tt3_h?;RNfwm#3|l4D4_Q79q?Y+uv< zKo;QeCT#J}Yg~Sig18q}>|tC{#GTi98_{56;V`hEi3k8I#TmOvW!pH7hW9 zR{9;|)obu&3$B3zRb91xS|h-H3h78V$nc9C@&ZFKmsDh4IC4L;gJL&fjP1nch8CqN zqsp}KFLQBez?q}d!FHF}M!?L+tMPzDwXA9J0>Wx;Va<>+IPO_{!Q3@69+l5-Et-|S znaJluE3FA3rXV~y`|SlN9!{E)6I5)}i%;g`~j{ZyWNa@9E3AcdHx+|S}i#(e!t z>!!}wH;*x%8yN%A51L%b7~buptNxC==B9PCasNRB^N}ABLsUF_=y@Xu*!u!I#$r3! zyxXu5GK?9Ff8(^&MG+t_ zaXcrV-X1f0F>fBwCSb3K_6GKB)cLlySppo?Z|CQR&ADKDg~bJl4+<|KV_}?6uDZ)a z$m|7>VLyFy(hvkY*%t=+kNxP4Xktu4^lS$lbY9!TX~*0N8A$lscbB9}`vz@D|HSs& zt5j>LWK42g*y9g78Dkx+L!&FQk|3PXA8dqcoyxWrt%FhqlpMh3_q?VaXWC7Dy8Q^^!592;)AS<9=qYZwVnU z8Dlr;=Q-VE3?!0GIR?DX&3O+mHXJ|&J~AbOm;vP<3n&3f%wmjI|bv4#q8x; z{J=cto+FTbl=nU$k}h#@2e^2y$dsKRS2Bil%h>uB_{;qW8S2K8DQ-Q$M)M%2`Uf33 z=jSf(56PGVjJ(Jgkf9}Z+DH*qcIS0~EG#;M1l_elb+@pV#GJkb4E(CZiWv9C zk2vVb3F>wrS>Oz!EbG8n(XSzBQ06Q#lee>a7kX*7WDEu>g4p{E7!PJuyZ)bn?*95= zAY>4Tgy%!Xy#8#hD!`eI)z);IpnK{q7i>qy01_sBw{Qw)d25rBgHKIqvwcAd;^>L1R*S)EP&q=O>^owQoCNv3h`c2a(x zk*)avYqPnWoD9(`2$U8{LLK@nKNP_;1Bgsq3j7~(&G20jIG3H*# zm=~U|HS^Pw>I>8JAvw{xCRaY4H_qrx#sxBmdt##(6>A?@by6Dm!OEvxq7D3d$xNE) zn6oEWR0nqUcJd=+{K%N!`3==0b&Q~Y@qFE#A=5{*Cu4wrU(S_`0qLS+o_s9ns5&Sx z_30sEu3ViratW}=7Mau7P`YWIeq4`_L+c;4d0bF ze)vBozS)XbzV`R!NZSdcr&h-PTXXD(Kbeq^dP(_XK5l|`L8s)p?m1~c5Hc*H!0B|e zXVKJUo3?W{>CdRoSXvoO6bhSaC$B?F)=ek5e(zoU9!*U9q?U9Or54Cp<`5QLSP%iu z@BL7jxCZ*f%{z;m_6+rF369;y=belh99~Wk%~8`bbXM_MZ6eue;N8 zr*;hH$Upt*xXkH%&e-`pkTJ*bnReA@p4hpJ&xMR(K0Dr3kutBP zJ0F?jN5-_Zgf{iQ14los0n)S|gu^f`plz zTGPp6%|rxLtHBKk;|2~M9O-m4lpOvw$l`_&GvqW!dFxlBh?O{ewqS+Sk_v{1jx9(U z1P=Gec@^3&^wMm}7{byqOdz1Pdk**44+|kPrAk`T&PiVZ7@jyxwqOTs2O0C0j-%Zs zV_2>C{>P4>KXYP3`{@2AV+=u1FIXJ%y0qZ0(&eDW4=rB!L5)gaT3ywB`3@C&W z%r)DZArAM(xnKbagQCehSOTV^B%b2n#G%AEYA_Cm5|bh%TQCceZK$xirl)pWb~59 zE>@}jL{w+M$cSHkFsFtTa=w5vHxGC4|KmB+uV@>LO=K;R9uYm( z*jQ?0CD9P>KKmfy5Fe|i{~%W{oT)U=4d_o-uFjb;)!7y@GPS!a8zX#c+hz;KYwv(V z3K@qx#*SVNLL?VL#yCjyU-nmljOm^HEwdupi+F5FzW*2hPqj%_WXOyO$LUJ+672~w zW1QG}+r`D0A!9F`tu(2{Ro?n^iYRV~lcIJnTSb?gkFYn1>7Q z$PyN1K=51GC=ozP)^gGz6&SgaG2LCMi+r*nW01x8nvIU2=Rzu3A0d8j_SZz80=q@V zJoW0oOZ=iRDE=q^uF2wt3<8uTQt>bV zE}pG2g;id#_N=rE@*7nm%Jtn>b->Io#biMZ5eCb)-6XMtc2oTJKaR9P@vxyllyrgW}=*M=%p*u z^D!BnUK7&g%&GyHQuO>S$Fe935jN{)wM*iG3IU(0r9Fm69p$#Mo>h~qIx!!Ov4v59 zp_{3s3oYFZFhSVK#|sRRbSvMy$c2aj>3Sur0{!}V-q?liPb3BU?1J_y$8ZnmZ8p^S za165r?V~eltYN%ie4@y>fx%r}$+3XhKzpa)Ss3%QBQjts`SNXJj|dkFQ{HX-?lQw z>OqsLFQSJqACWq9Y|=^5g%gSM#wOO}`fVpY2Krhdog(?dKEdR)KCdUb#UdI-c50v3 zzQ=n*#E{kpCqJ@udX~taRC!xfxomXAoe?n>srAHOcvJekZZtKntBm)T!My`zTb|E? zv~2aYF>Q;)fqe{9pN5EW>I3H@ktGw_&uEVqp01OMP>K1wt+`xn2*=rpEF!8dosPWM zKqsW%j83eYaq@`DPv&(NOfj!l>N~Kw0%wEO?cJ+D(<8s}#3ByIL9im@Q&FRzLAKx& ziLE;u$6KA=-hnaCf)Kj^1ATz8flb0*D>IWz@`b1Sq&|FQOSyjS4e1|UHu?(pXm1P2 zb5GV8z2<0p$ms0stHWmV#oA;~T&^)Po^eN=v}oJ%J^Bat!n9p{m8 z{1T<9|DwYp<5>IxF-XcLyH5>v34Irt2&jA7Umw9N0HhvwqbzD&)34AY(09@Mz5S|D z?R>~)79HC1@s(NAuC@;MD^8xm(T+Y}q;rmAql4lM_Hm(so^HWCEzxC&j zbbP9PZTeqK*u0we>252Rjo|CD82^GCyYLUCvgsQsrRnIm)bw?_;iSa4#u(d zYeE>i?MSz5#qM*b2P+hiueta~kk#0pbn|r;L8K-2xAh%=G4la)D7F*#LNB$yXD`)b zone=L8#8(V;8;G3rOo1yX~%cO+=Bc&bF4<%kNsxi7llFLTjCJAitVOAI`hELstk=p zq)4rRmWqJM@oUH2g|k)i-EX(bw|}ig9=}xM8mMWmoX4Dt0AR(*>n}CQ-}<2waT5$?ehBZk4CI0P$lr>F(AJ&3|4)J8#joSA%)rIE%Lj~uEW%4 z3K8Q(9uZ~2G2}!nUMwr?VOd_?Fwqq3W5EI;`m1$(?j88;23(kFvbUXHv$h`p_=Yf+x57L`OcaNN_md78dF?z(na76l4-`IMuM8ttl zM1HpZH*BY%8dhXo;QA~mVGlf_ad22uKiDof5Flo-P_QwW57Fywo3bh%Vkc{GTAF7J zg`G$q{%!9(W&Q@~UnzMpB4W_fo_wrEo_@SmP93k1=bx&R)A}#Z=%mj3Z!wnK3rkD2 znixNP&t3&~HTsUBj}9RM0fSSsSoOt~m8fiJ+aTX)7s~2NP@>Do>F}0PUS6r=e``ct zI@lW9d959y5P*QOyIcTY7aYn>}Qg z^1J3Casze%8}Cz)qv`ZaWbo+tO2TJF8o;eOKy_7FihgU;vla%sI~EVqlME$re`6`5W+Ar+qc}R%AW4s*38GPSUKBWHYj;p17#rt?KV$YDf{b&)=)kk)}HopqKD$?|(d_O0^^8*jHvw#|jHuFiO&;3EP4K^;pu6;ViR2$!0ZR zCTylGQ-dcHyx(G!<&v^2d*oLc7-Q6TwyCVPV(WbomS%4aHAvYD#BqGO;5wzfsZ?IN zl(|3t^va@)&#ar3n+WKZa9qwDPliu>ac^i<24|8tVXvE$?W{2Oe@6(o_j}l9g>jZX zO&O6f*5KbSuuhb4$%cI8*(y1G_6b=ndd++n*B5&0Fa8Jfw--w*8?v+(LqQ{=^0 zzVQ#_NK=*hduC=v)>g+QSh6UU;Ph(=XavgWCQ9GyYih2tk9R^F&uN%rz63@TX^!`+po_e*rn??9-92oXZAV`w5$~ z;}{|xSygG=5HO&)q*6|tXqS$*dRdE=YF`Y=a#V}{yA~@^1ApDj@u9M12?dv>Dzu>Q z;C!wMFPLlW6s($J9K8F{yotI{v2FI0nT-}pJ~PlEb_V2(J8d3B3=uIzG~w9A;fleC zvz4B<8>HP%K}3upB(_0kdsOGsq>*cMu9kB7@KcdnJ&A(}{PwpoxC%kUcoC3X(vz&OyM}{kfmmgX za=%OGt4%Zq4pn69dsk+RD#I#wcgixidc&A^r`-alTTA4(%)Ss?pX1GUr{(QyIF59l zP#vDA7$Qg3)jmNFudXhYU%oeER`6qUKJ!GKAvtDdR!tvhs1M4o-k&koB9ao2W}3x% zcHxzy7n?s*@ZHyw8(D)ZcXyhmYS#ZwDf{ie(Qf7!WG;KnSi6V0DAT;dd;9g3 ze6aI0Wy$?*IEVg|Ynn30k>@O;B<)RId6C*dTVIeUEH=qsj5<-ykk_O<-wE&+;dI9N z%vd<3{k@{1#LWMn-CQtHDz83KE3bdyZ|gl~}Yx4A^O8Mkwt;)!1GZvk5 zZb?T|r4$v{%KTDzGd1MQY_F`YF3B^OE9K)GHBwborSGnKa(qqam}}D3SfOoHCBx&@ zdX96S`T0Jz2bbi@M=Ip%ty**3?j3V~2Fza)uckFMTJDCloYi~Z0(4wL>icN9CfLhS|Tn3QG9yPL8sdt_Hv z)G>KyAvHGib-5=(hE-7cId`_+muq4OvmzWqCR1Hj>-%;!XLjE7jznci`-M$YR$00s zzwxzZlY$3<=q+wvG|w+5XFui$CQK!L>oG8o4u6E=O`th5<(Hp#~L zLW#o>f#I2LiYQi{Vtn!L0sS9_3r>aI24f3Zfn4#*OY@zMLH?IrYLeOa|@}) z-eROk>g(1Mx~8LZkq&2c90NJ^x0lZE1`*=`-Iug#z}Bc=nleb6p^>e63j4%(_r_V# zxwWx=n`eCh&F4qNupbe9jC6U}DBAT*TQoOr$mB$?(c|cA5E`6E+L{WTAG4hocNMb@6DKbv8iEuCl%M=eDo>n#7)AfGsqI|M`3(&4-2Af&?VMY z9A8phGobZFL^_UIQgCq2%Ib!c>zsrwh+`Ey!VTsqcgivl)~d!Sivxv%bHO@~A;<X+0tg3GE#Y>OYuHL@gB~} z>gCakHFExRmDy{FSB~h|fEZZTe#jh+ZDH@94|ralVOgIQ@`#0ZkV-`9Fs>ndTI)-t z``9@dRr}@l|KR)b&buE-Z%>chyL(4|{G-2;AN}Q@%P)TMrasezdC%>lwHQaVBS1E} ze~(Vc5NM9Cjqp!kv7eC++#`UqLh}+Nsxs{`fo|;Y}&FBn33_RFKl~_0;NRH`&jMYA^G*!%H-qgH7fh+ z9Fk;XQ3l7Z$hl*y=C?ER6^5wcoXP2{+7^TI^;b*vJ~dKPQ?0T(sO`Qk1EcTBiMC~F zX{wab$>cdRb2oKf?U%2-P$IYcswG@et$H2v?}qe`{7R0sL<~7LFdQ}{66Y)~_N%RZ zSHApwvD_V~m0)>=_VJMUZeZkXX=_+A3sHOTS8SdWSss@0nVTw;XQZ)l(YLgU zh2?rrh1|Lq(utwmkT`>CkVaODbf7qccUAu-|93v1L!Z`(rCtZd@aVE=)flJpvKlZL z7dUn^3cdpBvN$=|#NQGtDE16Kw_@!@HiV4dBO(+Y1R=x3LtiLU;f3-_pTw|2NSl>& zc@r{Q!F!}7WL%GF$(VScP8F~K_9{*zEFHr??QTvIr3Mp8!v`NNT z>^d1!U@#fe=aI+uZzgjbFy!?{Ie}QoXQNWC$F(p@xgMkp?NewV8`w93aqQ%-j+xXb zj9)gG8y$<9{kS-W!wRJc8MmGB^soSiz7Z{3?!3x)BdCFQT=U9WiWC+`5o6JrA%c- zmSb=aL^5*UOT>J7ebGdQGKWN#ooA&Dh(y5YR#p~}`T3aH1fMyKJuq;HvWUt{B0LCK z9TpJH5?Nf6>z~fZ-}_Fhyzpq1oa_k74}LHtFFsZ+ZFR-cK&ob+QoKQ$RrWh{-XEQq zG3M5Vk%>g~GcIj`cv)SI8NC)~DdU!N(RGP@32I%j@M%Ts8u^M%1DOGt#aOmud^OW@5=QyDo#1>+)IevP>>IdNITh&x4N7^Ps~JHT20f_5p~ScVW>HtLaC_R}FD= z=WfK1JVdYKumIR55G^>G0g?Z#YzMUc`yb7kzQDU~tgaj97mgjux60z*Xt( zd0YC%$7Lb9l2Xb_qjI#fN^MlNJt934U;RWD7e>u9k;Zv?$+;K(k$QyO2x>n>r>Uwe zHO_I!sETmv-bMV&?;j)~<445sOl}Mh91Jq1yh`<9?VGt~0>H^tC>_)7Fr;4hde0d8 z8nzz}+4^vieBs3gGcFj*R%UZeK6iG640(C~{<2A7wxo71QE}CJ-F%xFQngga?S}S! z-jlw~`*1&GF@M+U*lnn7*7<2x{{0XBQtsToE%o(v^7EhlOwOD>Er0Zfe0`6xi)B1kmVy#@gRbzZ#V0~>tCTII~4j|IJUKW-d zQUgrSs@#dK$kUf zM2wB_s3}*SQO81y+U6I}Rhu-RC%aip7L*m{B$cg+1? zEydE=#{Qbsa`CKlP4?4fp*Sgf>@_21ArwB(!u93d0^|6gkuf@?RF;PISsmX=CPJpR zy4a+4W#Jm7s#0wXm62{803QGgi1?1hh5(thBQnP5B8Ozmfr1|ybMf?x(p3Mn5cv`a z6gZua3rsEuaRfG#(E2)#Y-i&@LNdL@ecVhk!eGD=P^yzdS(3z=hQz6m8+R+@F~BcxE;#%UVZ4l^M$_D_E_^0B|d~TTmFi z&%8g*Q;gL8LdYOI`98N&>RT%H9ZY%zRWwLPz~-I^JT~t{=<)9P6Egmdz*$Uw%l zwLLBiq5rL{mcE=)h9<+(82ZeYj5+zte=jR#Ur71=)XJk$9{W&k-JRV+#&nJq(b~O-gp4VdhNj~ZE806UhGslyWDG#=poAFmLdPOT6$%#Pjxmy}5$Xl~ z$VAKNbqJTWh9Rpe=ubF(@&%3woI@xWY|P$aQl2;jD+(y%m}ro5rz$p61TuDTvSpN| z2Nbj=&bT`5ckF`#iH1CT5Dr83^q81pqtv5vru&OhU3*qa%AC{*y8-%Hpr}kMp-Sh> zBXVb;RzAF5DgDD$YB-cgkkn}9Nr!hPFa|Jcy4uTSLf?ZZ8AzGPAtAHpKqj%WD-$7u ze&TgNJt#o7_(hJKIk}?aQ-ri#6H}=M5X4P$BjYzYSNoAMM;cSpHWd=tkTHDk{S6C{ zP8^GxcPlT)NK5^GDZ-+wnE5^@?1IQbK6;6mk3U;94h~kmUp!Z7$OH5UY!vNcMxP~( zFiv~)+GaIsS!93%l>WCL0O4(Mq(bDcfAfg^7k~eliTptJlV;~PzTP5FT*ARpm9|_u zTPa7I%VcCYBFhO<4Ke^-hVeEs7B!9q>INc!Rkw^su20=y+gZmhVE*Me(Y21AQEGJT z_dc3&oT-GmDBOgMZ5s#)61M?luO&qKc6WpKYW%clo>hyQ}mdt8-e%qnCK8sAy zU+G|6b1@M~L;KtGWPryA1&fWd*Mi^ijMr`~m`I6Q)n|C#>4liw>|5R}L*oN7I@xc^ z?9!a-q1us3QcGON`q8cu>FFPnPj3y&T5MSEYCHb&<2jj)#7z{D1&c^#=GKg?!!8{g zUzO{(7R~!&(|GMO{^hgV8M9Z&hKKB&OnEQrd# z4*cMLmc1ckdh;Y>=6%SRnEvj11~O(+o;Y9akTIohGUjR;GG;PC#yI2eVFL5!L?Ufo zy^e!QeZ8-~)+CQ#sx#59_{b>CZ)Dpc6&LBT7|qM;&KPIh(DyAE*S7C8>NRV_Me=K3 zYF1sKTIan|Gfz^`Be*815E;`DGWMFa)n(de%q8|M7{~jCj6sf)hM0S$FWMF=Q;^dD zvMe2$0}<2ciFRfTWB0oW8LrE`!FTqZky$$;V^p{!hj)vNDSS&DA_dKjXXV#k`@7Q8 zbTV;d??59ztJQ^W7!c-p-_o@^$X4NrI+i4w3iJ!Z!#vGjo_0;moEw=6cI>fbN;gA1rcc5 z-5*D2s|p(Td4QE$I6+4zoIQL{7~NoSXWG;sgRD@+Oh~G9l5!xD*d7N1;_}5Rvw{bM z3y^1$)qS~ub1~Z8@5d@Vjx!sc=>6u1vY z74-vg!hN_Wj_>BiGHI$WGtWUGM3>(>p}MKXjw2i?tXjs&R30jo(y|gcb==9JZWMA= z5-wk;GT(*6rDl&Z?u$IKE9(8Ozn=?rf}%yl3#)jkH|o!6w{m^Ips8Pe_n-hlwz1JF zkDU1pIob7^DuIr%v{zt`CUrqaM~AF!9FdQ2H_M;={G|NepPiK-y>nDXCNuBNWr6YW zwbvTt{Fw?99Ycz>L+m}!56~NMP$HKY2j~;bvlxrW5WAxNL8EtIYZ|CyovW%Jk|fa~ zW88bhSo99;(tJ@s^bTw#nTU$9sH%)hWo68~r!DKTfD8=f(Khx11p;%A-yShDYMA2C zfAVs*_A6)M5AzA>90BTJjmp#3<}x{cEVN0)Fpum9pj%qhmv6|ozSJbAy0epSUf`%8 zT`kw(S^%9Ec}`t14oMMYHuF_`fV!DmSX0|(Ys40H#2m!9{ovy{85&+O`-T4K7Za+} zi`2QCn}GfLSb>j&-V1aozfJvlHm(n02GH+WTm`Yx-5EA3dT|zz#_Ra8@aCLIA3(Mr z>kP?B)ff2A?zv&XZ&uSu~F6W}WvfXbGh zfdnsbKtO+V`XrD2>htyTH-EEzOZo1%$m(H!_7Gu1<`U_PNQ2Z+TP#Q0G7~WdT3zg= z#j1MJ908)!cM4>R?Q4+c?m2%=b^3J#k_%t@(wF4=_3LUIrWu5L2;|9bIC}RMTV->h z0eNRi;`1RKkTD04CXjt`zwwo3mH+AY`(OdYYcDn!Te?oi4RfV;&yeX^=QCrpIvkMS z`1MvZrbwuVDD#Rl#x(aO1!1~t9wIZ)V~}IX;%DaaR?f6-uDev z%J+ZTD*xX)lXVf7DXBSRZ{`D5SQjwJ(N83n2 zDYBSY!N)N+7-S_NvWAr*949oFF^!V~GKaJ&+}rQ^`?*jjIHc)gIGd=q$_nNiQzZ`^ zGjnCq)&4C*!UW6qmW1(wIT%u=wYAl(o@1fJ;8?Bv@a^OBKmW&b^3K&(?Jt>?Rr=a9 zkJZTQFV-ItG7k`bgbb^8Ef@=sl7%Laa{*B!(P--Z%gT^P$>&77V1E^FO554_WMm3@ z#IBL~d4f&*y{M{;NnK6qc7(H2$V>$;)Izm z&;gOPprtt}XEAIcyX|-T0qzAur;mk<6K1F28prfK6I{b4m`7Qq$=vg6uQ$nS&)3Tr zUv4yYGd8(u2o*QDPB>H~<5R10qi0d>^e*YV98eoDv^j^nVF?+lgS){!vL$4&IZmIf zlqVmpl?!L83^|hzyo<`fu=X1walPbCu3!%x(AG@qHdb;w>B#&5!2uCSln&85?W*&j z$1o_|^S+mmLBB~YEQWCw#Oy|KJDbx*#B{1X`{ie9jr=}X*j@lZ-&4HblkV*5om%;~f7T^eZ#%h&GoijdC|`QH zK{}4)K*$tOF6K+fAOvuV*pkd;SR%)chUKwGYK#NbOLj2n>=hvs4h1Bn_Ke#oU?V_Q z23jzA`JI?L&EwUD_N~FY8`V28%c$3 zKVW^mQ;xNNOXrIROTu`;q6kPCHZ`?#F^eQ_^ft*K{OGKFbgMb>%k;ou`>n4uNnKUZ zAtCdCfPP>J864s`$yv2;owx2NnFlex`+TBex;wWhM458wMAMpao1li;Ud(7k&9pi-+cR7eWQ=dLWj2pK9)Yi32Fx;xYb$$nM`~g<| zJ0u|WkmEz_BCN9%KT0~iCm(dG9$e~aa*TY^>^%NRwV7k*7h=Y~d0h2*KHL3vEU0s$ z&QElO&8k{->#mNlAxzQ%LS}e}gp3=c;b3t_p_+@uHh#~LE1YL0!X_@qJ5_(x=Nq`6 z2-Ww%reI^S3aM|2M3oo@AIYD_C2pM-9B0ifNy$)dN!{=VHt)P)8l%$YN1 zHdA&ztjOF7hdAh1ia7oa2#|{M4VC#sr@31_U2zsfuoxkfATDv*qua0-9$<6+#=0VD zYxP9a`dki)Mmg2(M8`qmFs@nHc!=yk>Q?rJv!E^d2A8)K?3#SxN66STl?Mrjd&U$H za5HzHOX=$l2X>AQ_>W^;k#!{ zbLSVg{64a@B=x~7zI(>B9DPdSQn%$CSsy%bd&ZDziv5+`c>eJkIon+>u|S8!icXnh zcF&lh!5$eK8PNA#-2Aui?q}xjg}G@%%B-(N&1a5-TsH8(eK#V%`gF-eVeo9bwz|21 zI?93WpsB2B`^e-_!A-;~R%9A>8!k zg9%4I?H7d0pO?z;xx}aa3Fi3n@^Xnr9hrfQV=f+>s+8-!O*+@brKwJ3VH%K^9f#um z;bkd`#Siz8c>rKuX3Vls#FWy2*{h4WiIjyHAEc5Zji0k3%-QdvP^)s&p{IB2rv0@w zF==hynvx8Zt5H3_P%6>2q%dcNVP!?Bw6_GLZ-99|RnWJ4NRC1x)1EQcZ-oq@;zo1R zx-``J8{rk94H=&zCw%f8t`AW|nzn)?_0cx59TCG}Qe84vA8FL*T_2SqS&>rxx*qz~L_xMyIO$fQjFRC7z?LwgKK>D#;eJhgKv)*7vZ4ky3#L6mNQKult6Bab#Kw#k& zW6ulZEQ=((y0#mn1tyI#`OL8kAQeb2=H2fMz0+?G85VbO4Ef;XXpb3r{gtO{5;cDYXvVv|6AJ$VBgRutRud)zQm-_`;$K(H|<4zxa(xUp}i|fjMIIa8_&q# z^cSVB`I{0ic|l^u&u^As9k-E6*5&9J_xrQXm9S8*jjSWnEUtdYrTYIVq!vuhK9_s%?)l#d7|{lpY_Fl8sw(>)xc1mz;Cy?1G#) zI%2;2_~R?)9QKTP>|&XmKRIoVhfD9s^*f_x9%0XzOJ|qlWap^)?)qm}WJ+Ztd&WF^ zAt)D5&q}vGLv6)fm5Kc(T_bzOTt2rXr;m-B@9y0GKqgdnv1iO<7en$$;+&@1ex0-L z$g;}5TsH8ho$YveP;Iy!NCk$!tU~9$3nwe2Bb!u#F5sAFE?U%gWnN@HvXK{%F|=hv zUG@tM7!Sv% zr%!MUodI93`x)J!zuJDz-0wu)IKanIta8rri8ywVg}t8p{9M4ZAMP1*fG{{XD8Ki6 zzqjeU-0xu0W+jDH4znr1?|7zSSLRYkk@BmLo8*sw)F}%~=>~@d+Yg)A6-Y;5MVN8*MqaE$l0;90!D*s*&~ zc#*uM^Vf^d)XBHM*1TE1_)4QWZoxaQMnf{U`np`X)gnE2Zf%ynzI&=jj!E&xOybu` zG&Y`kNrmAj*B9hdEjN3Xe9XT@t-gP~ zL;m!QGcrA&J{L1Yz+r^UgT?Sz)GU|)IQxiLz;WI?$bJ@1`Y8+zoK&m|W2Lg)3yU;U zIFt)nii=8Q)+ci0-05}S-&064^vvUlAG*-nFLLwFsv!>c10ZOKjPat=wO5Q6EHLtm znz4&J3J%1fM9Dlq6gMDo?hlLhpTvPZ2F`!R7CH{K8jZ#b z!N5F=bH~=T8;sMT(G{)xWf@U@&2J;xfuUuyVwdqs4Wt*^GE6rz8;=x7V-cg?0ea;_?I zGzsL5ExfP0SkTw{2lSoh*QH4H5S)Y99O(Ku)htY(99}Ut(b2Y$oIO>k^HQ-)Ogf|n zK#y?~Gk)M%u+N-m46dKrCm$4eF823ugLk!i6&y$e%C$`#S&uWyTUhx_TU$H#VSv7t zc^?)tWe=wxViPepgXy_7Q$M?bs-VvIo@lGT^LPG^yz|aG4}D~e8)c<&9d|5xb&4DA z?^3}rzH^Gxat_K$N$2bw2gx&&_sIS}$b{WFClJWKbK-LvpInu@eM@Fx6@_R%A{D)< zHun>le`{-UkIIC6U2vz7R9Ag1cuD}k$ZUQkv)j!wpRB9H$e~Ld6oyIScpFRp{ zl4(yKN`5q|m0U&{Bs_r1iYg9Dqkj1{zwvp%(W;rE+t zi~IcPxpMgrKkkx|iF8(0l8|Zj>>=achh#Ug6G8?-Q(mf*W(kw0GsIYB2dof6D7iz| z5k|b5-EU>*#aVI3HF;)MhUE*COGusV37PG27{K7h__27*GE$T=rU!;_{;q6(5BLoQqXpSe z$a4GcRs*@aOXS$mGT+}*FlO0vrNOnI48U=Jr+1ekD)T_EPwKUk-P%9y4)7SGQPPN-MrxjtWTRjw)dp+uV! zoq@UXnCh#!rdNg_N58Vw&mu2xgwjDKWDdP~JH(&-$)6Z9=AZ&1h6ow{^}_48$)$MV z{XV*0EI;~Hn_TNjzu6p4pfA1BDD_oEn}iJPYTA8G@{_S?u@gcj6e?9^D7nILX<3c+ za%W;86~wVl44iT`j(PC37D?3!E zq70;#rTH;A8vNH1i+m>cM>kBFnGML&A}jJp8iP}#C~GR#N?v+{ZhoaN3g76 z%kL?XxqiLJ@5<`p9rOFinS&$#>|P;&NytmY1mZI?Kig-@=;)}#0#&lSrtPl%b#`GT z>vH?Xr_$ed*Ia{ii%UyOva&)>^Yn&Efrp(x_T(n}7evQw5;7S6ZLE4PH>=>C;{oFk zX*p766dw0?5HYNnKX}Mr@hdb+iknPCOdxO&>k)^ML&$`~;VpA9`^mihX_whkCLK_q z4>$FHaA5w0WOb7+IFHaJh=3t2g_C>1`>unI4mK1tZwm_C)*ygfXzjfktw53kYb+sbj`9>fEiIN#^ zBIemAvbo02oCN8>yvf3cQPua~cxPIE^ovRP*)OM!F6}IQNIn~5jc6CrV0`tpCVBDc zdU-($X&y;|W+Paz`cvqY$=qE(@vfs{% zc2lB`PIOn8Iw7inYpuI;#bp3}o_af}=d+(om+Ct^D_kSDVu`8x+N54!7vOr{%bA2EB9`^DWm-#nZGF`L$~!;`$tdP3FuF@?UuE_etdOnhK5Xl zaR219dAZ#i(fMxKL?aLxL!UWZ-+lNNdY*(cJd#)yv{)RTr8oOy4hB^k08wfN69Jt(BDqnu3!Tjxoee#*P4f(@A zFOfUFyCn$o1AW}4%)<#8kH;lYyeyTqb5dNgA@6_WtRy;ff>n?aV<-X~+0@H}M4u{C z^h1CH&gQ=CZY`Ck&w0m!KDYkg>--_Q_7DDYT9($Gi4P|X4n5izXBjDNe(MW0QsG%` zV1cpW&ga?FyDY!Bwqn{H1quhxuEKV(&oP|6r`E-8A_!rOQbRl9)WK0?6%b?*{lu>L zJ6PC1jZJE@>WXhCJ{@cz^A;8sbSyja+&i})ZJw1^pGe&s$_?g8Z`l#Slz9K z1c%rT=o&b0aiV*54h$6LedaHm#4I2w6h8bkqWhT{`8}+pt(seXq93t!uctq##LV)_r zNW|!2OT@TA{~&7G&J*rABo`3<^2dKl^2&1!hJ0Aj->s`+#@;ud-dHeEGnX$^oAbyX z{GHeIdJX@%)YfYS`ryX(>+-Mur~m8bYSFHSV!8PE|4vSwa`q4O;(LGme^XoL?q)Sz z?COv+kNjtH^ypFNfCoSP(f?6mvGgP&d%%2lYe6oYtul54vIf~h?sg*SuY5Wu9ql^K z^!Z3p#@`T8eCMQnE0Xe1v0V9N&P2Jepak3Q!EL~sU;nWP6qUc0^U$eVOcWoOj48FgS!=?#M9BYOZRu#!B&o@f<(G0!@5B}YskIB#9n=x`e8dX`LvV*iq?14o6us~`nva2`e*_^R> zR&A|UU-{b-+h~?Yo_I-$N>krsBOa5;(wzJ^|NO7(ys&7-me;O#!+mY1zLHTj%oqKG z$u=ouTYJI1urrY%I9^j0k$P?!*5^Fa6_)3pbQbjf>cbfmB|NF)tfi`0zVg};YRX_w%~X~^)8~L8q%E8 zpwCq5Qk^*t`M09Q?;PHzPRD@v9PTlv^9OSiWVjc!>G0@^SwKswY8G0ww}ezi1>-N z(RsOle@NzLN965aIhzXZ7tjaUklx)FaZJWyF$sp2rLt~elZ<)kSyt!mFEZwCUu1KF zp?&Q0)T#nW`XDdZPlQR)3%VeVRNy9K;;PuODQ0&|`h2Pr(`#}|uj@u6LF^ooF^4D| z_E$rbnyjeE>-0OgK<>@W%^7mq56$%p@}*~3@#>GyZY|1tAI-~3EFja-{cDtbUO+?x z(Q?f3Ss}d*lMxUo><{7wnNYs@)!fEw|KO^8e636(%UkCyHy$(@(^$VQ-JNbn^!63E zvbrJHZiZFQNd4{WFR3BiH)}S~XEmTDQ1ZpLM2up$^_D`DF*f4L=~Mo{-JXoG$gO_; z$QaUwk=mtA4e-n7os>X03vc!;8i!F$Rq5s`S)5+~fA;s#+d2PdM@C9T01GZm`4aWF_!S>~1?7i5)E_WGVy*q50 z-N~_gI_Ds@)XK3`L8U6yJ>TbFkMyrnl~j_d6ngaQc}A7~=?UjK`M{pN@9{eA7iveu zm8Y7OYLyAzI5Q^G;kZ!}kBmC?pN=1{GATz<^ssJ`FJ69g)W{Ggj#e9E%z(-pKk?~p zQrYn@rFGjLbDdONyY!;`?tlI#NyeC?C;yS`-MiQMAO&;A7@)WQ!0sKg_t1~7*cgKm z>fA-YY*XHE|DFotxsLL)uC_$3T%R(EK#VK!-6+mck{{RSqu=-)kw+IU`;7vrUF8!# zC(>lK>tpp;{`JeNkBYaXQN~BkNjyd!rkH&4i5h9B^~#U`{qrVbaWffXK*3D1F{ZAe zMLM>3%DK}oneXp6V+=A@uhLP@S*p*|T3slQo~+S1nVJ8i22{J!h>^*tykOD<&SP*m zBA2gCnFw{FzuH^NbiFUtPwBr;HO744gFh`X&o(*w;G^cVboj@=_;F*50ni!x1)7wq z$6Rk?4A&q6F?B3){v$;oj0ZEYp8V_Ug#000=fsUbs3CwK&u^2>>e%_q!wbvfgO;p(vm>*Rrh*~wqu zetE>K$9|p97}3&!we#7Jw)yklNi%Q_Uzo)vf%QJF}dH17Bj|Ju%0s+ zWi0*81b$8=>tZ|t=OKc|ol$0^8)G&uSFnMBBIABD!~kl@R8}r5;<#GCfG*X#`>W)o zcUluiECdT+@6J*wQ`r(@E@?P2)i7BBAH5`O$}-Cst_FFyy}W`V(4?_js>No#5{(r} zII@s2SS#T5jk0mMAa%;8J~}HOd}>yilFg&_AD@cJ?Y^0$_Qv^ubPvoJLrH40h8Q>S zti})nZujdsGPHs5*n;y}tjV0-Yzt=#E5OEDd*x;CQ>O3!F~k6rLG1JFyXi16S}ET> zonH9|4tACs5v`o~aD_k!U2j8- z#e9$OYW1{$`ZE;%f9dtro@@2@f}sSZ6^0lbb0(G7V(bofR;Xa^6fd_ZQu%<-{Q4QW z(IeA(tVwSiHz`hRx*+P%@H^_zV5rdPVA85!h~eB#^(Aw^C29s`a&Tfm#`_Zn6c>Wy z{W3AIa8XW83`_UTb7`A@YBcdHg*iVMA8-miqhLwr+|y9!HSM0x zzplF>qx``TGd4bB8W93)Gt5<@bWsw$dtt()n?@0cA%=da)VYcw1`qzllq~szrIqu| z@y^e-xnT=Dqx{BTcfX;oA+wym*}>dvsCUMUNQJ(Mn7sJfs67AeLFw)dni^67r8Wv$ z6t&-ed02ks-(Qz+zwH=eFpQFxJTl|ddc?qLm4enea&a)9+$}xI3g4EB!sq4Axqq>s z-M#S7=k-%U`%n&u7FMQz(CW_>K1WI*0W{DVBYf#v~qI^c`tKEI; zEIJlfb5p6@x-%t2ECzHxMySasaOQ!Z#{;3VywC_}5PJxUi;fuY0=L(O8}9Hsev`Eq z>nh-+0&uR0F)34D`BliYn=;-)2vlygw>_-)ymVM6sc(p^3WZdF>r0n*F29(WnK24R zj7RBUQ}bA`3DAm)qf%BLk;eKWeNN{)XS|%(CKXH`JP4Kpm{2>{7@x)N2ScUxfLRO( z$IR($fkJ}0k`4&c2;N)R!ph+yrW*idB@ZjzY)`zqzkopoI+=-&nGBTbJ{OaQnuS6T zG`6X}Sgza%N=ac{0@2OG@ZQg0e?aMj(wO~gY{F@zRYK9Rns((zv7RS+oGHd%TOCRJ z`%KO5snlW#h6)#)(~b6){3(ngk%9&3#N61sE37vE2zG$)B3C*01aE~1g%SzH7s@3(GvSknA|6ZBLAcvXjVH#>W1@U^ z?eLj9=3K!*RQ7h1%bo60`R>cF$y;xomdh6}$cx|kj&$F-E#La)-^hgv?@A~-pI*Ac z>yfMHF3IS?Rq45NLF(#iWpeDEoO}Bl=Ka)+U&n3!A$;Xj7bR+BMC5i?P_Ew!8l^8@>^7Y)zzdh(Glm0$ z(?-dKaR$DTC?SBu+j4l))qwlx8;lqOwxyNH%_(}FO(VjGx{WiD5sB+x<_Y7!v(;6+iHNA?Pakp3jiabeMXic|Nw-Teh1 z7jEMXYdTkB&2^!HsTduLn8-O4st+HpG0}+~ZPYd^GR9k!tlTH#%yN*cP7)H#;pJyd#FM)U>zj0mh4clU@$#m<|nuO{8jVwReH;jB)?=DzhtQ%vfmFq>&@a3LWIeg)=8v z$E5lL@EYi^EZnpe9x>MuZUFiUom~vv6Kk5a>)sE!cbv!4fuHTzru+fSpTeYI4mf;? zyYV}oi}P|F_HqEta`PkE0va`<_XPjP{X!e}@2rycou5nmA~)DF#w-&=#0(7$CEnei z@Or(v;W(3Tt(nLEVV^YBg;XGOFG%P5Fi9*fJg`7u8UpDsPHP4F0-_Efqi7?!p>3U) zJ#7z0uCn2ltm#+a}_B4dL?GI;OiqOG^ zVmd5kjBy(iHnTCtjC*1{nQMe*lEx;rEm!D;X-Rh;+Lj?^3-=R>irQ3oIhJ^Lf130C;b^^#F&K(=Zp$WeXW^VjDUVXFpnw{H$sU-I2#S+wlV)cnK$zSph8SRtF<~VS zox2ksDh5mX{3FYwg2x_j7_Nw732P#IaA-zDxu(%X}~|5O#3;` zDnBiFb`+=V8=MvSs7B{_>hC~lDbMbt#o_z zM}>6G&KLt59{eK%Vd=dWlGop!)bG|_o?b4NGR9O@*NM+pxzHGsLk0bM8)E>+mz5Rh zT8|s!3h4_2I({gIQOr^oWGoz)fPQZbHahp3!V<=DxqqMZp7`B3;Swnm2Q%h&EHO4g7m+135 z$F8(t{pB^|#~fh(Lk9u<#2B)+ zmaC*kw}p;^v}mk3+EgO-J<4;UDlu&EIb#vh@hdFQd7=zc>UXSZYfJ#B%~)>%z0Wb- z|EW1K zTnGBYc-d#>dRxYr`vla9dG*y-6YuU{Fo98MyS--lY$a{EAdIrBuTpk*V6k>DXy;ro zJ9w0Zb@380Jgr2UaLcq<1G-6Q=Sqz++C%1jzA$f$L14kyj^>oSb zz#Y?OW7ASwTPqWz_vF^Kcji7H?7JiPdTtp3P>QM&N3R{2Z8m~4WXH-0zPV7aZ)MYgc^$Zn3U z70OGWQhJiDqHps8gAB%))YOj9(plY$`-ZEftzlBiO6Hk(3luOY9%Cx#O~>^2TZ{9) z#N}&c64UW@WAE;;@-VAgv!rw4yn$ePo~gMpYWAOefSNJm6X|&c(vxM5ib+Lszp!q+ z#U2TUXLMZ^>l$)D8w!wO6(}UEY;D(QHgTe%v7){oazQGXC-89a+Epsx+j@>D zqMS$>g`RqFRB3axUhee`8hNa-u~BZ_x}|*(HPPo~+6Qi93~(D`P@cPuD@Elo{jAWW zKr?bn+_S(K1N`vt{7o^&pm0XPLvsTq8cICopIaH84rYyT4*iXt&-C?LrGP;JjDlsc z`LJBTo1=hoE5g87a8~-pqSDh9GX2f7(>5yH#u%I}8g+h#f}S~J3qj9Y0?-H>T12(e?(pP%8vW@$_i~Lf=s<{8 zVJuLD($Fc;&x}(#r$4Tj&JfeourTs~@eNO-pie{^O-7B;038bByj){UCSy{zpg(xl z<)XUMyQX>s_9KjMjDxeUgpKpm(D1bB1Lik$7(*d_2k0y6oh^rtK(B@4fmMdHM>xQN zA!g=ISjP(knzQFP1{T%|-(kpPKjJt$Ua89|?v=*}?24?nmx*DI<&p$5~?v*Rb>|70jP-@nHmd|FPw@lAQ~)Q9BG&5Maobpwo%iX^7v zqSsjmW6V<6jFB-IVb}=V#(b1*hlM zzYdW*1$(4sH3rP?o?OB%(e0{tHve@jX@?AHPx{d zMC2sjAwnRYx3Sr2-T#u6OQCRq)ao^gi?gSB2$37j5Mx2a3x<~wS1FQ)dXW!3op__L zDa+CUqf2w6NB1G3CLF_zg*C_!fnz^spR$5}RC&!k+sjtKnB-#)o{^QIJ+dZe~Kc^pg@zNX*k_k3aA5aR&elmf?$!SY*in$H}$$<9#>8Z6t*XpDhn zKYnn#)VDn&k3RiL*?Z_wY1?sFDr#C~&%sls1tLM+BYJXdjA3ta&b6M#7{FLDN01GP z=t5ELR`{bphJK8UM$C7do5Im3r*TvvQUuwXnn(;g=US;O$-K1+NFEv5kf~9JYH)vtLtzxl6v20DTa8W5m~~8KAv{0#NHztYZ8^pmqtwFWK597BxPTc~t6VDu-)HMrOk<@r`( zjG-UaQjfsgrJpQqW$sh+i1FkZn3Ie(edspG@O`!RQMP32c6Z3k4-9h517v>Y0qcTw z%6c9cikP{JL59dC<}wjtjI$YQj?uYdodj6psbH;9lg+E&_3HU(qz8;7^luiVw-Bv4_`u#`6=Ig+s;K(d^`BSqV0(F{VH_LtmMbUT`@^ z7z@^{HKw>}VLGJSH{8cB2V83{j4^9R88$gCT)1HBVZ4{%^ZCpKOl@m{{^4@D(XG;0 z5*)%&TjP}-?WLl7o9MbWxg;0GTG7!>3K%x>J6k|}`uf8z4~Jxgf`0S2xBI&JyM_D# z1{p7)#ZX*aWeReywz1w(%(@wmXq3=)LfRK@uGxU&P#nRG!Gr;0l#I`cC%#aS+QQm^ zIpqk9AsJA{m4>2;&tQz-%kY&xoOt!#0JUQlizpoP`{c@<=ES>Xv^068uC`cwg|oUB zZ>{C~4R^X17CYVEkvoT^!os+0Z`boNby8X|=!hr0%{4Mb#h80pHk_Io2>2)q*xyhl z?CkKWAiq#))7_iBK!^ajQ4KK`9c|QlnQu=&n)o7tM^D=CJPX>4Q#*;B!uO1cxk@0kar zZNZ~H74u_88l>5|)K*IYW6VcB@)5ao=~Cj8r4dX-#Q>CDfcezgQZlF1wt%O%Q8a4} zN2$AfC1`GAl8Kh_7$Zfi@@^PmNWaMMQ99e>vjGt??0NT; z#`O<|6H3^aQGVL7#fdPLu923?$bbo?8e-^Aj=6lzFPEAAhh?L^EoyPZE51GRma+w8%lpxnK~Cl5YQV++6BT2DVwT7lLgLp0BNL@^c(2Rl&cNB(Af80Wuw{f* z7F#qrCXZN6nlg)gMaRH|+06^)D^pz$7&eHT!#p|n$gws;CO(}U8PnXlL)%Ve#JzLj z>R>ZP##o~we;196(V?Ml)?;n~#*cB);S(GNF+Nf}yH=S7JTqzc?o}rlP*w`oI?-@$ z@R_$XEahcUIdQmB+LVD`s=?%A++&TBvW1X!o`Lio2*7x2kX@XJ7}mkEZ+-QT`kn@i zEebv6H^wrQAcX!iPI$^pM-r(>5}qab#l~VlOG}PRQDJ@J-FpX%MaO`V@d`P-+wrb; z1G+=q1B`g_xM!<&%zcC#wgB$e#&+VbZfvuZFrbzOuy?9tf5j z-4L^UtZo$Xc4Xf|A;<8HOwAgF=)eF9!D+d9Culr%dsOI0*^{}2<>J*T`R0 zOMV?!C(RG{fkNL68yN$A{_JNzYiKS}F*pa7mMtC`L%o=pnaEtE%b-7Cl(9UArQHGj z%0|X8KBS_Wi;Rhd7YtcGB4aFwD8qw1*T`guu|PIsEw8*e$6G#}^HbFRGaqU+O3=Ul zo6S+c|KU?Lg2z1kJ6_>C+d5=2)FL%CHRc(S2i&de?nN0K>RK`~2BkMjb=D4wUeXpa z9?W^x4s*)FJ(tpXI2)r^LfMw@$e2_>d*GFEVj>cTF-8GRnnA|bdZaVNG@gs=OzGZ$ z;+uPi=O(IZxfucMoLZ_uZ*Y9${(NQBDJ#%ECQ87GEV+8ai7ersXOy&IB5{@R!Y8@a1} z6g8iL)MHaouKoB^Kd?<6I8>FkVT>5k`NCbTG%|+uF`@Us{9=4;qmOJqVBm6pM}tN) zPV`Z^&O<(9EG;k+Rwm{raIZU#V=fahljw@Hpk%<%a73@=kv%(oCY=|NR_M5>wT5iT z`t96RChe_0qsL%P@E!X#bmr)RN@D;~5yXrobC|uAIqKHDgf zF{=mj-O=;fHJeKNXzsEV<2oO>AHba6$dNHy#+WQXRLsST^XZu0OTc3`6k1)O)|DbM z1M@Iz3i>C*2^}WiLAJ&ige^u^)$61lA^i#|v&TVOQ4pZuDl46p;go0dPZdaOb7m(e1jn^7#PEzPc^V3fwZZDH z1HG~7Oh7={y8iK)oW2s2H!lX{+>MZ2x;-t|dLlABrTg7rG)n^Jj4{R{(M=yeRV|M{P$dU*~3$ZVqG2kz-YJ%1XxK$nL1rmfw(~ z*qc(A(*Eqvza+PMZ<*gNW{j~4cG6g(RAr6_bPghCq69VRv2-n4<*Qp^i1KUR7~{xq z>uHP`9-+Xv<9&~_*+a)`%=Ms2L>*v^XAaasFeMh=4pU_8c1Wcv$XsALbcAYB{x zPkJdL6H0VEP^hE-ATowJTBJXt@7WuPzTqCMk(s^Gir^^Wp^L!I6ARWUw1D*jt>T`D z)^aP;Q8Z(40@)g4QbE5k2Rj;K(pVc;8s?Q+6usK2b!;*87wa`?ENkerMVa2?!$+$V z?-t_f&8azK4EM&EEVp62f_^b~-Hr8P*Ty})$JFmhHD>p8_Am?=F81C4CxLXv7>;M1 z7{l8l^a^7f{7!}T6NVV^6i9To&=~lNby(P=>96hWKK)yu&H0Y>AJ+@fU+8fwJ%8fA*bNwx2%sS%>U-&}e z)!JZ2xpBOnCMG6y5{$~|$cPGWQ##320MPG9D?%>KwE)*aVZC0_F+-zea%|s7;@v#h zA0Wnf8)NR=4J#2r=y$vZQjIbBxH7R+y2c-ozM@>%J+dC4i(pTK6T83Q(pF$QJOzHKFj!IzrP%Cz@`5-EPfwAWv| zV8(8>NHxY(*VM}2|Ak+c?YoXi$L`0)KYK*RW*(5qnFCT({XU6!o$J#krguxZ$1zxQ zCl?aN7{G>4gLx!m*&QMCUP4r96!VIdV5B9%qla~gR}te!erdi(SYoXrz~ov%#`$6F z5hfW2Lb;D0t~7;^n;N}F=)#)>K@lM;6Fs{hQC9M>(&yCFnE3<7kKy5AQv-m;>nYvm zY0xU>1bh8j0mqAQcwvnIi{XiK>D)G?edO#77VK#-$>eFKZVb7}x3IZ!?YaucDUmAm zb2C5F_Uu9-?L-pa8;BU?1qxdfNG5X7Pwg|u z%hUq;JvkYZ&fPv!92xpvRY6*iQn`5tUfn5#%d=s8!MJ2$uU}QMP-sPH%(o#18joix z=|y-=<2qpNc%7AvqTy4^9Y+DHSiRRjEkWJaP%xtWgeIA1($Cx;wwbZ;UZ80xjrZ-T zFm**3Z^R&{{)5NRJA`w_38M-M;(fczB{YqJ%c+^b81?Gd!Jd&igEU9*LYJ>i8O1c7 zFN#XoKc=r`JAxjYfiW}B;V+KtX_ShV&&k72JZrwMZ`orSuR9Mv zDd#W0tk2BR5QB$*W-M=xA~$hOlwr(A9t9ri ztKS?pea^h0ZB*<(RB7%H*{4M3>8`e79g|t*1!GAq9-ooZ7se!*=-N!i82Xo}io3mG zBgY_rw(44fu9DIb|E9Lq5n0G#NP+=G6E?iso?O1+M0>AD*> z4xx-IktM8s_9qnfl@(s?(;^dr!n}3&7vPv=V+`NLjRBI+8Pg7>xzzT8KF;W~v5rXx z#h5#?9(XxBH}Xr%yWcoSe5=uf2Dh zPmXq0NMm)8(ogLp*L+)!F$Uv3`jq9iOkl4_T^nv#W0b{mj4>8O8Z2gv;TXo52paYT zGG2_1_$3sa*8Qr)7?PL|L_f{yLKxBSqEXg>*Q7}+D0GeshcN5~Bt9F{wOwosbLi8U z!_ZU{g{IF_Usqz*Fe$I1%5XtP;A5hh6!JT?mMS7Qu-ZrJ@5eF=0fU4vJHZ+C;aw2_T5&Pv`wM%=x7H}NX}nDF~$ zXlzWzr=}#P1hBYN8QGc|scvYH^6F~w`h4c|iC|Ft7-mu_Yo1V2vd}|vtw40lnad4{ zcW!u$0ue%^bXGSRQe7S3uYMxD-(Ra3X@y9eS2r(lg$HnRLo{Yte{<@g?r{&zEE0LCM8OPii=Cd zQ&c0vri>#D-ka`WHj~k>5v+2qD1|vq<_x>m9WV`NFcw#>FXsuv~85mCHFKr=O za*oHOK{|GRPzs7$&HhFmC8BC9wzn_jO$UY+_A~rfz6~*WXyY-+9%T0#l%~9=wi`x< zwZY2w0JmU`Qvtj;^1!1fYs}vV4p*6m(?M#E`1IgjlJ5uc3O$sgaCMaED1l~`zsKn2 z298#VA=A@f)FVp5nNyZmKq-lm6437`(n#$>TF^jHd4g$_R*s^YWBBDGN0W;W!@r(7 zb;|4?AmQYjgvOSg;;X1l+uSoBBgD<_0x7SkN&DOK%G$&)U0C^$Wdt%DeM3V@3{YU_ zf>no)v4H!Ht<=Ie{qx|;!LlO>Qe0KCPb{|{KT0VKGN`CBn+mhOke_xw?{F!FirO!jV+Y?gS zJb#fB2P@@>&NIH-rhSom{IPu%QpnA_03E{UK1atD$U=NZ%g(63G>UbvC}EB)(iopi zpbpjHZKd*|hil~f-q&Cn?`bV5`%*gad$>uJ69Vu-Wfg^t;9eM^-@Aotkn|WK$EUsj))p>dK69h53a33hrumqduea4l9rYVLt`*ZT1OMR52pw7C{x?QdIP#@Q?1h2 zJD5xE#=OGuWivUGE;b{#ptycL|3%7C&YV7TMsD4>Aw6AP(wk`Z^}X(H>AQPZ`g?k0 z;NCscdiDK{n>Ur%^(M}eKaj!%X3Dm;#>Ja;iC4)$aYS*lgmZvV(k_YQ{dd)HdpTL# z7#=5H<#P%PoIJunUkSzh)*28aw`Dw62APrJez|_-Oyb?EyR8ClgA58G zj53?Cp&+|`H@ozWC|0aO4WS$_K?>PnY@xxlvL0b7NrTXH&pAJy9SBIdHpl>$0$xuD zQiYybDe}b3Ysb^qF(|*6P*_l-w0tF=QrUy(Qj}=du3a;cukJlHT_aMBD48zh0Z5g~ zG5N+)ju*FjsHd}VZs7He0=jssi2tU?oo?0v<2c{)ZHNIFV%l038ZB;jl^CN;DwaFb zFfxs$G3@N!?I-|IqUy2}(v3k2XAAdAVaYB-4@p19XYfxJ)@~VA`d;FVNkL(;_$r#s zXY-07=Pw4I=7y-dOO;RbNO#Y?ryhJ)z6~)%kno(O^I-oXEe*meMi?9dcs?5)xi+x< zw0zh|9=|>dW3hKvxsd^gNZ=W9M8dn4NYm^we?Od)`2Z~@x+$*o7{MPN#zed5Z}8j( zq{_h~v`hPtG%G~u<3UNE0`}VN9Zqco?iC-}?Gr$uIr$8;?+ldSB<0~w_I z?Ml;A*EO_C=YbP)?7^o@!)c4g>vVYPRGm>8V<^GO@uOwJ$Tr17+u1wczq1?I?G;5c- zVcZJ_n%P;Wz6a5B`~?XTpEq!y7+#=5q)Q|nm{m-YW^C6E-`qa45^yZnfYw3JZs|P1 z&eYQElg5TJxpZyH$TNHooYZ}cO}g<}e9X{8U;CDsouNjIheDH0fje4KgJqo!*|Y&%hj6!dH3R^y!Q5(+2e4CxTD_zJLgO!obGMN zzUMAYXq%K9w*$`cH>Qj%VZps&oEjUCNLNol=b1;Eo6B|9c;ub46J}mpHC&C(cjWD^ z?tr|ZG>Y@`8yfd%qkNL*V`|&NMn-c(u`w_+?lk5g@7-WuA@UG@d9z?EP1zFo%2&Rk z8*eU|g=A2O5${;8VOo?N{)xY|nHgo&wM8g?r)_%Lq&JBuvplVB%I{aEU_dvR@+B21 zD+LAz?v49dOISk(`RaGHO-Whl!s}BY93q}|sxpuu+_``aOE<4|gE8Uzx&aZ2$-Na9 zBUr^%C<~g;VJsjVR)|YQuA^ht+7~kbd;I2V6z4D2Ff>Id2w#7tOluR$|@==<;26Ml*UXlArhZDbEC3S z$Jh1Qba+at3tmaQQ(@YbrYsdOWH7{p3)>BK#Z3jH^=K$+U_hA{tmVb}pR_luxv}x6 zQ5>O|+16I7f=Xc`%7=ocPS`&JJt+)P&M@|P2sxf?9{qgfa}XLdI6Nc41g%2h#{DC( z!GQ7%TnFVGjps57_H5|sva#_P-V*Nt?SuRk?#GZqBuqLQlnrWYYvt3Q{ce zxs&)bKR^*@kvgy0i<|5HQc-5tw~GcSo$4RlN>#R*aks~-bSIh4U`W{3vCv4850ENs zax%H#J>HN+$50F(rFc3lHQO-6-0oh;A2+yCuc08oSdLe5U2UDzHXfDIvO0-`x|JV@ znDjI72$pwaZSZ^OXiH;Uri0xwGu>xWf8Fc~ndpgmM;P`z6vWB&l+(i+XupAiYmwRC&@4)BaDb4G$vI3Kq2T*i+-e9^CIQK;4$k6b#(kzF! zV_d1BVb^g@smgpR2j008GWWoC&euTTacGh>^QDsQ$hS;MUnApVd_m@*QFp`A zEH|J#HZsQDUx0PVICl+&wvHA+&cP@L zjA10vcXoVJv0vw8S>2~(rr?+~@A#OM)jXQiD(W7SLr32)@0|Wt;s{Z?SteDDACpl0 zn6&Qv_=02VnxBw;hu$Z*?_5-xJY|mQ+*T&7O%AP32k!5BS8zd^vU69D$(c(va^ZTT z42!+D_%tZ{T)G@gXMurvlfYGIjx`v*pEpyLKuTW)7;_Zr)bY08=#i={HL zhr5Apgt51@oo8d;V6U~$%=b2$dO3hLZlx((XOK1o!$-bA3KCM3EP#%>^^Q&3l%m4C z+lHa$>eZ`x^_(p&&AdtF3+`vWbFU)tX)@TnOsy7OV<;T6ijK)4+(r2Cj$-3t!>p`; z33C=cf;mi!6$tG{lL@&t$UuZzo0JJt#>@f&lWl}dsuI{11>M3HRtlH^goIT!W%km3 zz6Q;DSrR3)7|kJ-4UCbJFvBPuIZz=dj#L`Kl+;cS9)&4JsTY;bT|W8XlXdd=L)G%k zW3{q#Td6tTFvDq-BH04ENGde0fw70^8)y|N(c%avF&3q!83WD? zTnL`&%JtH;h8PSx?uZ}gFhE&88}rN5*xTYCd0kIVx(&xb>E_+w{czMEt=EgMkI99r zX9;`O} zAo~Q$H1?jgMW#_q58Gexr|fGeYIbfbk)mRc=_|Z$QTDD>@j_}JoF)KXw%_>fuxad> z@bV~BE%4rLX(FX-fte5dhI$w%As;#6)D&=!D+PyfUcz950uyCb|IoC2=had3TyBMF zfww{miWkaXh2C;0C|amoC@zYoZRt>0Fq8JTv`oMQ+JRl4$sl6hw(orXi^gG#mMN0{ zlJ)^9s!-xHM=N}B*}WsC{18ff6uwS@_iVuLY$5O)w}Qs#LX;OC-V-^E_KMG?;6cH2 zXn%#S?J_eDsZ9XS1v+%y{+%CaOHzn!7Vrqv0m;-7k7!_{yXkvgqg-VT5HS&s;K&&_ z=@3z>`h4)vUNg2tFXbyrAw9C2N0|Wq#|eyeU95D5XL8d?)-465QG8>twZJgNeqi^H z)zb3ifPS_umq2cyA4q?Op~s`=N7;{otEIVQ?pZAjT@A*^Yjv&FNom!|1#Rcv$K~kJ zrxqAF$0zD#V%(SZn6@2{nqyKC9Sz9PH!jK0SIHChf}0NHY|j_)ZVd*5M){H2NDG#( z5q_Sou?b<6A*EWrj7Qv8I>n4_`9@a;V+=}N2y#(kCfg{LC6Ob(gpI*&dTb&vqgd@x zpyGY_&UwEIF9F>QoP5zJIrE9((U{yDj2X`aH`w^n8)U+Z3OXE@$}GEutu3rQJn@he z#8qfdw0xrL)=e24=o0_^>%cWn$P-%h?EhN`yM88YRVC2vsFl>;!Y1aybjSU zM7F$nCQ-kse?(q+bKDrxQ|p8PJoPYIlM0I>$ruEnBH zn9^3fua~a~r+-L)0XQe=O&C{~kJZVCpJ|YfzOTVV9)Z+x<+l_y zrmoNhy>Is3bC>+albQ50Hu{QZoF4gO>AU*x(zXk4{ulGRY+#jKs|7W4atUhXVE{yl zPu&4zsKNpaf>D!Ez}7M8xfe3OSq#)D0r#}8QI;P&Tqz%Ty1_IGm*)!H2L-vewU^4N zlQnaS!^a-3HS5bd=ny@yw#J6_0reOdBO8@OBn2~=wTa^ryzA|*fLyydW#&8)WM?l- z8r}!P%DpT^}~`Wwr1Y&Ps6PwxmXv&(4Hp^xh@2?&jgV@#@&5JBC8>d_FqrMD1D3 z^iPQA-l!A~Pe|#=SW;^U`(;m2NXiOUHgCKM{SSM~`1CU}F!qp?xBiUO?)bT+cJSd} zlpp!=Uy}!prBCZ<;q`iz#ud*sPeGaP7Y-jo%LeY_X`<&?4AiqJ)jrMCD)bpklTu6Nq!WX_^1hQO% zh#Ly@X2N2|jitV;tgJMtO!9$|kr5Soa_L>PJbdqm?nr(0LLvRqwSc_()~NJO#f`TH zH7T-24rae$Kohx_0fOzI3grm1jEODE$wsk9nYV1AM<-ro2d?Lzas+8Y@=24H3VuV8 zTEeI;V46tBkjax`dbC(#!Fhr9)RWK3=y0Eu`6}ex>6a3pqHvBXk(`#8lt{d!Bk}3R z0OR2I`;*oWuSvgGQWlcdj)2+lE$$eh-uZ2_G63tvKwED?Z(&>>+*=|?_AfL_{$GFI zxgw;s53GbAsc zb^2kaU0|?(GrcXiX1+C*t|~#sl>kc#V_WCKf$3x`NG7zdAMoJ zC!f45wN=(bdLG|+aa5>z)E6q+prgHobRdG{{KbWW_(LZaj`3Q7)MPhqEp8Yj+5}^f zE&PwcCe=uj3VwT_b9#YM1i&8+49%ESUT&a>Z*9)3%(aG#Y?L6>zad)34X?_NpZIY8 z3^9NR0gOfPs?hi+Pt}UA>ae_f_M&WWo7H~t$Tz+_VmwPR$eTSNp+H<8WbR9p-R@%F zj2EdStoJSZDbK?**fdAk0^v1Ol5HF~5ouvsu~sByzz6qr_F3-<5! z$@hP7VG;d#y6TZ{y)+`PTnNg<)QoZX@Ps0A>Ui~>3`A`J_y~ZJ@&EerfXuk2{gG|O z^68H`b&kNgAe#5x3zIVCaXgXTIMh}wJGYl9zv390#slqo|Fb4Pe^*zZ+#PY! zl)2GT#W{3dHMHyf>v}DSN|kTed`BIlu5smiQZ@{D7vvPS9h}H)-=O@>v?fSdZPMpV zMdiTWa-pUuQC_S|3?mjcdS<17FDE_L!zXHVyqz@Aj7O=GtBY6shG)kM{=q$^^6?Ke z%8&p33r1r2QEDPk2)HwqEa!0WFRCdTTk8X8^=Jrea z#~RDsedorfo~o1DrXQ54DV<-V<5E)9sTdGSGWX&Rl&y@rlUCPSr@;_V3p< z?vsJRVJRqUG{y^y*_hIZ;XCru=`Wjo0zCUztsE$rlE7QHO)9TrP3hO^?+?|<`LIJ@ zD@#a!^|*PBF{81u(Y#KFnOL8Mrr(l}>b^Tu@T@+MPab&qNfY5%T9z!=N5hlyhhO+L zIe+2R#3v58uOC)=Jr!z}tKGYelb1zRc|aaMazVcGa(c%|4BI#@kn;S;zo%73CmPe9 z_;zMqi~6>jcKirYDH#&v-=hrSyf%du> zW85j$ESNXUF*|>9FQaaLu+Lbh1;=@0e%`y+7(7Di-ku8(g-V+LTmyOn?E!9j#av`B zLCLKfXpRO(T8~Yu~(~63Uq>U$+u#q=z#mrivrZOT;b@Kw41&r{r>&D~|N3&|<38P>>ad1b8G}RPJxe7vS-9}X4 zztQ8&C)QJ@{Le6r)D>WK_)E+xHnVT0w%*F-vVhRg#Pp>d& z;CSKQpY7k&*QxCne&HA7`0>mJA_S*xLQ)`ck<^3R&*=b5=jdw;{q z+l^?ut9%~E+`cy?clw6q%I!hDrjCpL%tNDp6D_DRMnGlL;mI-6hIC)-8J;n1B8=0T zIrSWR?}ddLd-NszFZ&AfmT`esq7FwoB|c+B{T9%SD)ixyH|GW*u-?LHdGeM-};^wS%;iGcSrv4zyF!M{L+hZ_}~Hg>R0|+$GTj8 z??3*YoH=`0T07?Nxv8c|e7<(Mb!SX|_dor2dG+O&q^Y4^-aT_#ni?DA-~Hxq%3JT8 zmxgAYgNd=jnBQ~9FN1vnInzHYH%8;;Z))rHR!9IHhoVGfVsG&_^BMzDd3ojtd;ipg z-0Zp`vyqszwH;G_rC5B*3xxHtJ)R!x zX6>eH>=)N{??VsgMw!m}M~+q}%?m>xUB{lm_-~BbM3U(oOG77_XV7ux8f^;;!8*Pl zYsN5lY|R(;b8Bz{JTH8jrMK>>W1rc5{Bi(oT#K49TgI3SfH<8#eLC?jci_C_kWW>< z*aopl_qn?*^&1Q_H8ohTa|_O!&l);QVK!DE`*tp@i$ktbypg7L17H(y=W<>WIiN)l z9|SjmFiY-dh($Dt#~WVEF(rJCfVUi_K7!(ML9w*r;>8&~=1;OghJvS=4KkI!4ry*a zAT{-ErWF>I$gBz-C1sU!pV7*znv~*srJ%4>rlYx2BIF90j4_qfajC1DC+xlb$sQX- zKG0|D0c(t5lx9@WPS+%se`CySK~y|Cw=l9~)7ApJT8pJzh28Z)-%xhOn4-c0Glp#B ztTpBqhFjZ#GZQ*{o z*1&MlP>&+Zqx{M0X#Mu~h^g74OKeHN13}YiODPPO3xvW0onE(Z^O6ZNlA1jyep|a5IDK^O457f5A$Qt-Ahq^=XHHqT%LZgN|~9cI9!>rJ#?%}9ynMb~h{s+FuMS^N(O{e;BFjnw=-+gUd zF5e1eY~OinTq-KPa{Ne@wrbhAqulJ{-Mt~hd!XdvT<{xsMccYT0L28~qm1Nx8Yz}h zUR3Gl`}S1mJrY?G)4p&br>p|3Q2+A$_Ba~nhSx~K{3Bw>DCAL&KQs$7Cr`k#_vbL88f^O9{xD)p`@y-D3tH}cuS(zz{18_xNt2n zXNozJ&r}?^tlOLL(Uu;R{qNvow`Eip4mg) z`{+i)YK<|_6^teAI&Y{wXq03#G1C`LttyW*C$m(frZ>hYpSop?$thNAj9Ct#shktA zChb_!FZ5F?hLnyrHXM-g@sM1+eBFG8v(VJkl#%Isdwb1iZetA2ay2!3WF}G|@0>Yr zK7+3%y9+WdWdcBx%8=F=6VmayJ`|NdePvQk_s8YC-AaGcwA$^pb8~Vz#+dN*q$%Lv zR_~Qv?LG-bn&qedw_lVmeep~3oo|0r-g)Z{{rfHR_t*dJZ%Z)jm-5Qwbpq+Y7}L~H zsQpqRfsof+x1pgy>g(%OCTLJOv02JWS|vDrJ&AWoHOAD}79^dcwzk%shjY}`v}oI= zJi_I~(GIxxojZ3(B)&_$6$iyveNeoPWBF_g)#h=6dL27MXEu@!ag%JYs(n3 z2|;1~e0ZG>3=AkiBy8GIz@%$#1i$f;ih)05hm zo9ofIHh>{>gZIAj**Rkj%5uxB1DNJ?Lf=}!8e}Wy^eQeMCZzK8VZVhps27> zMkYQiH+uKVjeGfRuf6M)bJrWCcd$}Aw>#;ZvNgsqEYKo6k%@L;jgbZiZ%NiG%mXP4 z5Z>{=Me&0&`>sikGHVzqatsrKyBtHV1=r;oq0p?MPwg!wI_XiYIQ6dh4En`=!o(m{ z=4ZYque*(elHvpU{JAwiAt++duzPaqUhRIL`uZRK!+&UmqHN&v`Q+-=tBH5H0r#+! zfhRUwphDq5;@v#hH!fZc2ox(E%g@^1LT*7iu+g#PHNUN6#zc{91n9C*;XG!dWWaKa zGNdGHZH}6>WbUYw^#TInuI*(~TI!K8Wo0K_8J&pgX=x(GPyW)PLi34^;ru9OP|(0* zK=)Bz6Me~^-QKzpqGD1(!R*K!e^y-*mrs45LH6%mS-mfmj-*p+sxOwFp5UB8#%+ut zt%s6BdFX*^IeM_t@b*NuvOnX{fa3&xN-<&f+4GmDj58MZN;)kBcayqF&xMj2uU`5d zV;gifg&j5EvxxHLckYG-pP)=_T*nbTH0ijg)d0`WHj5&Q=n<6PZOx@~ya~Jq%4?o- z_fDUb>wXV!!hKj=zBXkP4v#-vXa3R;+uF-aVP@_d`G9%jRy13XP8EYgTFhT!Nnj*I zN&E2e8na%g0mQwSe(w#L@zJhVday9E0-lLfbvU8G+fXY2M>w7p{_6atNj=W-#;+6ucwb|)xPVTaGd7<06<+}uYhm9{QIuZ_1bF9!PuW^`kE8nvLhEt zeg4TnjWjmwkgtF1B|{H7Iy#JD37uVOX{ou-j%{8k^*M%g3rI(=(!dK>XT?*{Y829i zg~j>|73SKcO5+^G#U=XeKBYfxQXoz%E7_*=eY@0X>*=qPE4QjtMn`sa&QV(GGyQ4n z$9TOZdR&D$CKC1Qn1ziormp#uGVb3l4ILkl+UCclr1IEYt7$wT`}UvG_289vPJb(L z*N!pffx{2T@Wg|<@b=2K&QByAN87XS5jk}5lzi>^|E6=SXv-M0La@FzzcD76rUU2# z&qfh{rUvU3x@GAqNN13-&%Du%G1>2mTgVAe3`4Y2n^nfp(tW?&Mo#%$gY%{X3hlLM z{y=&G6{Z)Vp)f(bmsDQo5O`|Y>yeN4=m8bjwzH{~C^Jwd#}8KY+KNpTicR;Pb({ReqY~Mx8V2f z+qO%6eT@>*LKUWncJWAivq(#8ME2};42-FU82YD8h4qyJ;jgV9b3lAs@y2@!U(@le1~f z&CRlZ|Ng{TmIkyoA3#7%w+GVhn{ZGeYU_v$yh@SfH%VN zB3&c;XDL|aevQf(G3^!{vXDnmPU8sXy0s+K8AE|b0zs8srkyBVfXu+_ohrXT=EGsf zp@wq<<_zCGpwF~N=W%N4RupcjeP{uN;k!)Df@eYrM}LFxG`y$BD0eWTa9?xENxK)h z0Dr}Ok}3-Y%4=_p$?I>A%d2mW$y;Z}jjWTTsG0t_RBZd#(sbZ=7PJG8{bxD$;Kvic zoCmyMbha|7jr+^wh1XD~Vo)tHMmNw_RUl6uDVMSm*F)aNzz~Q+?9x@IZccTz*F;fW zx;AB$XB*83v2rl?Y}>+ez#6rHUJ(fgodL`b4CJYe$TK&{TGQU%o|FM5^_Wx#x%21G zn`6*RSTrdub|2%uw@l!7md{-Y#&iz}x)jKOY&q0>M*n9GMeM~~%dIfS2t6^40r|Mf zY14AAZ_+5EasI;5n?@Z;S}Xt|LEgSvp?lJND=w@ujg-u@;%af9Ue{}MhW1$7>@iJs zM|2N!bRqHC8Hvq=B^sU(|M-ac%#DzLL~h>H4L=3(xb97QoKjB-PmSollFY}=#v(E~ za(8P<-N%6U*`d7VLML5nYdicLHLNoMdeL()G-q^yCrgD>)ZcNCw+7~%BM)5bn z?%us?Qh?+V5IdAK);q@C+{T!6ZMnywG=aG15?m9azZ!6km4dwCCl9ADPDZ*Pl#PKI zCmqAGnZ6a?76KWIAGrW8!z24EWo%+b?f> zk`)g*Lg;OX{qX3F@r<{EO*$|hOGU`EwLYY;>&Zg!?>k>k1%Q@sMt)HV@#R)(pjnX zd8A5tB6sr#^B)=0S{c!6Cto*HEA_-BnD8>?c}R`2RL=e70tLFaD5cO(oBY7WKZ%ju#rmju*U9Y6pwpk4Pc4V|jqB8|jR2)}&7+)!?w<@F>V&Jdt z4Mb#UIGMJ$wG>Eg?lTN0!FYu0e(Xb`r0bPEr>v~Nq=mw9C?D{v*gz!E*tqhBdfA3L zo;C5M0z=H}Z#&;9>u4~dtbR|QNT-V&4k=Fy#i4%3BS$OE-kA%)1K#LS0bWne-fPk- z>ApES7BNL%@iu1v#5iN4F(^DwKYDeKgJc8dpWA^cK-M4St37YTPTNXyf;P`>ZY*6_!cn?ulWHQpkrC@hkL z`yP`0dmoaW9S5Ynrbo6ndBv+EI;wpI7zffA;jInt6H+;9LhpnAoYv=|5PX&PIrl@K zyYCCY&(N>%TkJ(RKJiTOGqpMfZdr)Pn7zC9OI_0;DbRZ>uoEu6C!eo!hKJ}R-IQ**7z_qcrG*-t4Cbyn9<-29&Q`HwXl=e)oE`jF{kyZ>)g ztTr;n$Tdn~kv)6+!zNP$QDiJy`ad<2X(=!dH-2OcY1f?Rq81SnJJ^bhNe|X2id5^p z4^1Ub)kv&|{bgpHEc}x*a`}>z{U8%goUAuAlDQO(QFm>5kujj5wpH4ib|yu} zQ2d|gL3SWBPfM#;nwq_4t}|yD2T)&qSc(eEjE;|Mavawsq9$L>S5~EK`j)iT$F=YG z>)7e_qhXnx3QAOEfhm=dZ5tozmhZgySK<%M>*_GnpE$fjg5egO`(7Cv8I+LnWFgYc zC61dM8WWqo}r3FHu@_(Eyo zR=!x~Y^mlxCbgyeJ(E4xUbCFnDkj$p`*%(%qrGsU-nknxg&U`o)*wi&6|*y={EJi6 z(;-55*#U}hoA7L9JV;#zGv=f-P~juNDCPnPT%q?z|;|`EE$rLqA9s}Jt!moS(z9gmPr+)M~23dj)8F+iyV~cSf$kY z9H!`U*R%=?=?yWfVK@O}ZZ}1EOil-bK{OJIc1rso06U-0tE}0OQjIZ1+K&(J^U0?_ z+9(ek-66-0?$^KDO?&yxuo=VEBAqb?<5^8@rR;34m5;oCpBy@{U5*@VmIsgTkq3_K zm}^H5b;v`9q9z|ZDf#XU&ToQN34pQ!!QTp3tHEY7#sJ0@xR^dLHyM1m8 z`NQB4DVFB<59-Ao4G?Eb{D!9ODZO zz1EFe&TpFaJ3vuW`icU1 z<<(({7drLi@ao3Uf>-Fx+d-o=fRDhi0W2TJ9?y3aQ>U&B_lna7%D$oDX}verKgy9p z+Uy!@~jvk;~kFTrVA(2>f#+s}*Z+}<& zdEPPN;Lb9$uAckapy99VzQ0kiT4M}=pG2|Fc}jF`Fdp>(O6Uv6ZZ2cY{O6gBF&H99 zo0rM(upWROF+V}RjWGblEXvq9eZwpTxnnY=_rRE@wzj4ND%a1~j3G4{2J&;~&du?@ zRrLi)$28aPHT%6a#!xS&ySsbN*a0eQ3rz}1d(4p1&h9&l>$r|TSg$nGsi_v9ReqwN z!+gFPV+?vhB6jNP>g0_#-Z1YQo4wM|=+Hj5L8iR4Ro7Cf&U+)WrJ+CR{X zEo02ez&hS&#+Wvp%jiBW;5ncpwxK5l(4j%)LGl4;RxXV(Z96}k_(g7z%w=t14!Krt zSh$rhxoQw%TI%Qd00bMtyMy{ImX}csyU?-Vs-OqM zh{ASZcwTnUr%Sv_2InOL2L&%)Zbb#N${=V{!U4koW5xGNf&Ob%0nABR<^ZMY~vR-LU^gqSJ5dc%guFS}dvpSRf!n z{&u-K_<_W)9SjVdlgn40(_@Cs25nn77?faeR;~_xK&GP=iC^nx6d01rm!Ff-p|eT9 zpN&S%H3lYkOV7k{^INO`<~DKfIRZp_e$&jAC>OFr%dY#{D5BfXJpE!*H5(mneR^=l?;TC z{-KD;e~to*zbK=&un^2S=mRYm^UnfijI~YpFANx7C>Us|S!2__K&$v1C6~pd3HM!X z%Ce~Qx)-Ombo(`*;UTvXkZGTHV=9U2%nO^Tz*sXdRAkP3yUVNle*VQD!%w6! z#AJeZWxByljhVz2vwMg0*TTNXSd$ScG%1&WUq=y4+E^3>@YqDQz!RGYjf(jK{s6kC zRMLFUK1wPZ8VZlo=O^WbS4QRft)LO^vjMa7!6Q}j2bN;P0F;O zaoorclJCo+vB7KP8fuKZ{Q9W8!Lz+GV*0J6*>NnZtzO&+$2gH8fagJZLL>@{>RMx8yf}{r_*;=RW;C@?$^w59BYt^1AV`rBMqg5SWzV{@c=h z>)gV2^PCKiOwRqDcDp+`rx<%L0e%uMXvQ+1X%{yOoU~TXTqk<1N7tWC&GlXc^oF!V z7Fk`h>L(rJiA#zNS$^Ute!}qB?u;?+V`v!9 zmjY2dfMA}QIKhmcJJRSt)aAqjfK=ya~ML_3tSsR2}T(IRCY#~hB{{t=Q*e;gHfir zF>_=OMw#K!BDs<<%H->L4L`AnA%+xIsqik6FZ=$$%J}|80i7}}@jgdj+(?6lH}bm| zC*>P24$D`+HDnAc@bf5}-LQ@nM8}-J>^DXaqD$X6J#Gv%{N5U9vT9{c8q>wFo#Oi1 zh|b07szi@#sxL8x`xj!qgV^)g|J~quj~=Wv>FP|R(9J2ic_$#3uleOpcW}8j46Ywtf3{xq9{LoI@6Y zFa3i~>PV2uAcHKC4fq}NE)|QVBTmJ|TS4jWPp1DEkM``@Bek`)re;k#OzYk>5l-H3 z00t=V+;h*FzgxKf0Bd&lUQotdQ8^f1$O_|b=?pPtr5?i%3@S^xv4_3 zK_&&vavJAIZRvhT%LmdC^OeG_*vYn~ON#N!3yJ;lWjwRz#Q^4{u^mN{6}fq z!|(qUlfnj`o!U0rTFX}DOvQXXa-dR<9jux&^w3Z&TcyeQON*!RId}R+>FK^Mqr-jX z@AWHZw4Ig_eV+~=|3IT0=yVjWfnc%rXQ6RUGKQI*K3(rlgbR*m)?kwh3{K6;SfW-9 zc>VR)jrTn1#I1LF)Mc=W=yo@v$GB1Et1!=(2@}&IKa0%Q+20)c=~ z6DC_AC%RKz0q&P#|3n<6o_{HP?sK1$haP%JKK$ViCqCK2{RpB%N$YC2L2B`hPtGK@ zbf~G$eNeyhk-=EIJ8gao=(vI;kXLfVmvNQ!ChU( zFqc~fnY9P>V(knv8(#sTGd1xlcVPd;pv>QF_Hg%iD}hxU?8bETjI~M4$T0@ks6Hf@a-)nCSt=4ygZ3~;dgEN{fQ%0a$MV?eHC(e ze}z1JyjmVO?4-sa6%O+uU4tJ^ZR7qznN@z-Q&^t1Ee3d6irr^|iCETqPmuFD@EooB z97K~K+oa-|$J2YGTZDpBbFDXFl(DZD!-U_Xd`N)|4lCoKd!dPFsdGH%X&9$cJ>+u< zl!`4aEpqDAsl+D^=nrH$u8-n)IjAZTsVVW8DEKYB_dxxIErZO`$mD%5{>TH2e^5Aep zUVSTlTCT-_ajCv>n|b{UKl^v(=YH-V%J+Wm^YWpOe%$<}{o{Z1GqQcV!wjSvWL5)Y z49mX*(zay_(pC2MEsTo9aclqn{qpFej~Zjra&Z3qc@quP+uNJ?WDEBzB9WL$+j*-i zXy{@#SfNO~DY0dY$$)&MDNC0p-mQqqWm}H5J6jMHld6>S4&}ZAKf>XmX8(XNjj79$9%2@+n?)*ypo5k8#g4hqy;jAlNbxN+>2$=UMyWEXv_uE||i3WzmKX}8O!;R_5ei`q-ns_Is_;puLNN#oo zjHl_gj$|2dbS#-(qXh0Ig1;+hqUhcA5_k?1ZKHG9ExVu?r6{l)>|rS6Xaxnu5>*B; zQ}gKe_O}+KJ;OQ6>IG+_v%>P>y7VQ{{WQC#@&%k4zWwcQn*!QyV2JVgs-&!9pU$J? zd+6BSX_Ukk7>yWj+dle4z5Mw1wI&r&-okqeTLziM!Skoe6-3JH-R0A@S1O&m${o7l z@k&W~ZQ>X6C@AzwWo_F6osFkZkBJvav9D%<(ZN$tXpSL@(Ke&AX|0y>M|Mm3!@Hz= z_l~6YuKxayMr!27w0rClFP4c}aiU*7{E-jKv!D8mJp0M-NopVc=!d1fL!T)D`Y2Zh z8JwyCGBGc&FLDf{k@OfUuBleU{Zg zM>z3{4K*%z?}ZE@d+ec_xoDPCCu>xg@|ptm*?@f01H&;H8C!g__s@7_BC@=;jv3@O z1O~d_k=a<@fJGs`P!|ZDV9n@Kwb=G)6Ypo==bJYzA!#ED*x%Xe?wk> z@xRKR%0D)3d)c4K&WbPTb$?$ff_nW#Yc2Xh;wXiVcX)c%cy^YS!05(xemZlONGTXt zD_C12z|A`pi_N|vysR}Mk+}T#Kkql~wbQweMp#Se7LjLz%;s72v$KK3tK7jI1qxEI z)q#{>|^oZ~xAJkzf0lzbaq;(ihF&Km0%cv;5oN_$~R;m!CJk;TkA>;p5rYA3C0# z*@3#1Zf{f!H-p1^{n3a_Psb#v@9*}84efTr$TY5W#q3dm@a$as!k6yJ={NsC{`(*P z1Nm3~;-}i>)z;h`|tp;?~Olq((!YEU!8wzKZSQElVymP3pB!aNZjnMZ3H0 z+U}dH5xIr;7Idl1Vap(s9z6G*yJ7R!0z*t{HjdiLb5dFImW*`&(Sr8&OTR6D`X~R| z@T3mnvU_`pRF_{i$E7=_=j!jvcfR>sGNkJlx=TZ5Evzk=X_cj>rL=fFsRaXrGU3-Y*{3vjByq$%iYnWsykcP%p0e8QvVBK# zZ5#RsgG}l^v0PvP0n3SsvB1AL;bWYHL^;*%}h&p?-ejxx3G5qt(t>!}8rZ;-e-diie zG9M$P!U_2_=Xiny@Mgg4EVoR#b8|$+^z=`gln7vWG^*E|H3C02XoR$urjj`YK_=jt z#y@^WM1y+>QJ!bY>9|r5Y_qF*S~?qFld|XwQaabZEe&O7mEnlX+ZU%K=2Gfa7RTkW zLzi5?)i(2jl*eDvjXoq7uLotsKhLP((06F3Us}puGQV@T`m$U4Oi?+1(_xS?qEUNi zC5Xkfe?6I%7ys&CeMSE0zy6WD_R33g`t3L6_y6PX$nX4z-cuCza-k!xp?Mfe4md-H~aJ*nGIT2y$_vv&EueFmW zPbSW?G`{kcujC~%1|exFoII4!mZsqJdB36Cq1fhI6Yo`&md-9Pj`*hvq^>rm`%&V9 zRRDv=-5#&p=`NAbA`vGTVYYS5$gUlc1qPyAL6@e|vWU#a1I9QqF`0hvBvK|kU0@6| zGc(Y^*^GU$977C7hOS1D6@=C|I} zeMY+^q~t0Ppg)|x!f$MBf_u^54Lg6kdYnGO5aaF_8{L6We{g51NgtLS(vPwI7{2}L zov=i8%E7Oc>b?lyZuiA(K-3Gy4U9503b^wZk8AjAK>zv!QI#(XObX#cofW1Y%7pTw zM6s8bDX)}p=wd1rOGGYSjmk?ezaazt{c_{_HS@Q&rbhnP|N5FlB9l^Df$=b6j4)50 zs$G~?cywm2-{75YbvyMXtr8Lk3+62;fiS|MDAuiL4$K4F55@W{{bMn?c6ZveJADzk z(iM=qgDM+p=Y?lIGNI25|6b{mcP3OOIe*&hRKp-J5zy}G`%U+4qI znZC~#;9Gchi?*hna{1C-ea30+%ZMrP4L@X^9I9#xrM(^R@mcYfG|FJlWr^y%@Rd6A zuDH0wH2=h?d0$i+OX|CWJIf63``p(C4G(4a`HhP99rHA7BY>2E%sF6dRlu{_3>2)d z)OxWTW3y6l4C{&1P=I-CqYF?7R##?AKa%0Dn^C3bunwT^&)ZwejAN6PZJ+_HH=E{= zc}`#3`+>h^{go?UZE3(-f%~$?T6cc|?w_@3QJ~+Gz7WIjn9>z$L2#_0SLrnM8IY|Z z=E&}H@fP$eE$oxn^z8-h+}Vrr=DQaYPM^v@w3o`GM{CS6v~fRQEnh zuWOa=w>D*t6k%+ycZE#tD2sCa`Hy}^Y5ATh*}ro_cC`;BwHr4sDV@Bo*SRBski##x z)q7>v?xRvtUM^MTda~IuiOmepwNOCi?R&i{XTK=}1Ks8r3+9Ngq*ZB3>72t9hU07v zE6617-$IM5jItDlMy|`YhPa$Ox?3kfo4oYOo4TH+rLC<^=d3=9-pAC`l=SQVR9aRb zwGH$1zf5WVC!cPTg5tx{)!i%CuHQDFV*p2fdGg68<(+rlF`u<|6zl$0Y;+!5SUy;b z)~NzLs9R1S9iMlkgl?r8MRI{md=vCx=XT%R{$ltK{T+1C(raiVe5j4Ws&di)^#b=f zqWl$WkNbl*?%z=*Z96}g_(g88zEAlc1Xk%x1IPxHue>vnc$XeHO!ewd(zSep zIo&(y$+``N3slG{G8-z9FhG~D+)|-EsOyAW;4s~!z#zx^_Ks4WL)2GVx}oseLhis? zf3K%3Lou6cV2nXPvC5ZpEgguA>FY~h=r|P@FJ8<`y%-Ea>GofDtH@9AU9Q0*#0clv4=R>2k!c1h>25#sI@JV&}!^;>OdD zd1SW^0pAU3AJNKvBA@y=>0=TowQIK$W3g0y0!*Fur_fhX(b!_PFx!OjW^ zXdezJA80{e2b3o|cCb>~TS~>FbEdYsSRQ$>#_&s|8@Axp<(~Pq0Il!n=rE0RS^&i$ zj#4O4G48OhOa)MKI1kgS^YHSu`EccCDGlT^D>p0#o--Rm3?Pl+ zV$I5!5O54JB`F~oe81ormqB(tP*wPKsV(@T_88Tx;$|5H6?dQ0095=NklH#voF~uflC{!bAeQd+Mvh#uG3VM8hGdhhiR?anbHAY_l+k!Go`tzP`0%#RNgI(h1b4uJ1DpNl~(KU zEH^TSs16gEqJ8(^Q763>`=TR<5Fs2fQ6lsu%1izp*ju6Jj_dFAczvES?PENzBYHiz z!xFQlV76ZF^$i;SksSYL&YY1S{J|fTvuDprNvTJQOSM1rhr74?Ouat#WsDk(8+*~pbU`tXNz{|iZbTcf^@N+=RE<3==hYx7ZQ+WsLq_0;#s zz9UacL(3l1cul)}{VkPm!iGnpjVO)j9*js2wSV;5c8}kva7V^4U-}28&D>_)ao;Fp z*Yft6x0^LG1{n@{n)O07oMi(yVuTF$!+3+GB4Yr34qao7GX^{p(}t)SbP>o3ne-gX zF~nd@zN9qf;*CJYHlp`7t@qR6GQ>cW`}O{A_k`su-yT|U%;4CJImXH|pi$+2o{KR| z*D&Jr4M&n9V~F^8_*iD==c_lTWN1=lro?+dWDI+4CUC9P2pl)cOIIEllMbwFWWS|o zQ*m*(oI0l0^&C|iS1czUJSltk9hQ9uj>wLkJLg(^OM^sb2PG7|W9B}sQ=hlFX@|;` zEz;c5EJq%AQ1%@~~?^bD>-L+{-cn2Z!XynECyh`?FZ<$QVlt0me{E?*R1Ae&;^kOc*3$$-OkRlJ5~rN- z&!;AXaXoRQN=}`qQAWR3o_M5A_U!N(1Id^YLOjrN1#SyM)!OXUb4TRe3w{$aJUluh z=Pvmjk1i!7m#&i9$}g|KJ!Y)Yc;1}7I4Li`F=jTD^#FUt#onmAcp;Rwy>%m^%u;g4 z4}=QzyYRwx(P;zo4uA%eGafm8XJ+pE)ONNT5Aei~SBNriSc+yYNYQL^IB`0V0s$io z%+q@Tq=RuYcNn`?Yqa2WY}&qrFt(Pk3`1&LZ)PDEpkLps5i+rulRhBVVD8&=q3QOs zOzq~)n@iS?`QjJ9n3t#+fblWieYsmYLkz(14Ymw1n-3U6_U>M2+>1m!ay85PDSW?P zHDQ(m>#<4X#~bgAN?%{E^!1M^e>SE(^r+O;W~OQGnlk-^Wn$BuWirGR7C1Fx($$Fp zM1`z1Ftz{`)9j^BKUQm$SsiVq^6-gjBXnB99lmv=psdWx01wkp zM-hE}ufvKWiF8BUCkiJptKTJVSK-`eCa}k0%mEmeSR2S3q-f%NJ@=ftIb0Xxlzn!- z<9;x3U_i2Z*|pAUFe}ya^FRA{<)8oaUzT6~=f7gwXFmIR`SsuYE%}vy`j6zuAtz#v zF}!gnAfZT^R8-Z8uc9VxyWQ=T?w)x?HqSfXmzxL3j{SpS9UI3mhr`XtSVV^O^G*0T z>k8)nMu?E%oT-MZWMnt8oCl{#4EiXXD|D~$6hMDwj3SlqM@G}{>3p{wLk!NXQ<3-* zP3ev9TkeRMYuzC^du>Wycylbx@0|wSapRqfF(XVycP9KJ;|GeDwVdM&QP3e&t5)i&tj@c(J8gD)>yNLB^JfbiYY$s|AchfhYaEO!aE| z#y7rUQk4;5wisaEQ^7~RqIlZ27D#v9#hS(aV5oSn03LXy1{w0@6KUqO=}ps!XuMT^~_z$loR z-CFmX5jE8@V@|!^u4GI6z-cn+e3e-Au38j7_hcURiz(3jEjcqm^@tU?ttg0Ks;Mj0 zvWV0*&Psgdii9WMS-;kc3`Ai=c1)dpmoUd#+?Qz#Gy=+pmxv#a}u=9xd*mXB( zB4cnaz*s#r;><4`4to1SGN7N~j7?qKAiR}629D9G>)<^L*K{Vb(LKMbDw5Z)1yL#Q z6?n$R#;^-!q?M zI2VW~ZVaZ4@MZ)p7-_(!aOGye+y^L_9PzAS}cY<=_Xq5>oUJID;&V*t& z=U4?LgR#rL7;JW6BgU)r%p1<8jWGS_qmQbvqYPLg=lAEo?^)T~*(P86&KJykz*ym- z3Tzm-w=gdIT8rewk>rRv@PGeR`>NL$;J%HP5`TgX2!Cfw=D9Up}ermb~m-3>75fYJvA5i}0v zP%2Qa4h$B_z5d+t2N+_S8xwEV80^KQo`H8gdazPR2XXNle0Ee?n~SBVH*6erNCQS1 zo!vV&POUc5;Q)<6r<)kS=LX%2>}xRz@aK5gIHknx~BZMy)Wh&(SsPjaL^(p8qb3Ava-C;L{iPe zIi_%?Q{Fy(-n^!k$%jAuVfmv!`Xlqcy0$=e@AH~^FIKUOlH=H+%A|8)9J#AwiqYrs zM`}%^g9ZHMt8a~|%;25lfp_V6TW2C_y4e0kiPGN6d7baR^NPx3+IJ5esWPc$EZ%r$ z%-qwC_A>L#M2s;ehYwWD$!8d^E?)IZk*+(UrWwDM=G7}Z7lWf*bNZ>hrcgfp>Hm*x z-~Z{k2-Z~m)pP%ceEr*BG_TS3{_w{eO|73)V5s@SFW!?^&wEvth?}&F;K4m*^6~dK z$dCVni^fo9oVO6rHYmR5dz?rt3X|icW#Z5=^<5N*VibM?t29E0rDVo$EF_w$X2Q6&jfh-!68S_R9jQJ;5c{x zy88=2!%#$9U?75i96Ma4Yr4=F!&%$jqPVud#>mQ^&-~{- z{8NY7GuH;_jBF}Sv!}XfwVOV5DDBIKvD@$qY4|2X$8^muMYE{8X6HPm6EYcUmJ6${d9+%eBYlWevun&8Do~f3opDNr%&fs0cRC8*%DPZP}sPY zHTlA|YbvR&AySo7?>jXq4<1?=#X+RWpZ-OkOh)3`90n+_q3&r`%b*e;ie9pL;&t|* z3MSK$sKlbP;`4cBNExe}cLKWE&l=%&rxNW=yG5UGO56;@yvxu*}c6?s#UrVU2PQjIYfVlc?0GsgVQcfT;luw^pFJa({5 zo_e%a0;NAG(ZW6Ed+@uz`CALt%Sw=HjH#}vm7n~XpOyZ;yHe_%KR?%MZBOIv)l=Nat1yH{7&YRedtUu18PiI`Ltn;pK=Iyuz&$;7+- z0OyN|i3yYLb1}HrGW+|dKmBRx?Ci{IYBG!d{(f_f#puaX4-U%%`xizM5oPq1Zw!ln zra=7BJnq3;SQGfC3gmWIiSnl_-&;1a5oWo-C^IyIp~e!=YAB1#=)`_wjDdHgL7zYMsZYrt|M4G7Lw$j4?{p$hI4{mlq#g6=9{r=AY?w0~ zgr;Ni*MBo6A9$+4JlpJSL|!=UpEJbZjKpu76E=xwKh&Xnk3+*RULKLFHv^`xf>M+) z#sH6;zceYm{b8dxtE?=VQ&e$37?*6lKpO?%(cfX1f@eUvff2Bw)@z;><*Ka(k}sqh zWB&H%+RW>8z=-!JUm1|`glF@6!5H&{Khl<@EW_Exuk#f7l87tnB4Cior!gkg5aS** zuvv^TtY;LmsaT0YCKKqRYF&3+XAzdoz{+13PExU4V+=Ipfy3xIW+fDI=oq!4E?)5) z`a=Yu^Zd>@Ip?2$o{eOPS#LlN8tSMkw~+RwGsqB;q10CP?K)=09GYU4>eT9L*8QtI zK}Sc&BjOJfX}=UoQ&W@q%)%d-P#$mC)H5s8{R(>Q&gMbdOy(+zmBG=A5}66e$$jPW zv1jU?AEW{E|En*Kia#=czo1IT?0@^AcC#;L!bUU3Fz<0zCenqm*}n%pS&?y^z(|dw z^E>Azb?+`RS!YU03Qg22&&a-d`Fg;l=45;^d{~E!d}E^;V*vDOF@sDxdY&sVE{o}2 zGhwZaF_aQQaXEC`X`)Ch*W#lf{zf(=7fN+EMV6gOR6U2^{XdGq^x17l3;{n%#lzDI_%?-nx5XD?03$f)jrCKbj8BgR`;Hc%=y z)W;+~>lChE4%V|Uf4+b)ckGZ?4(#)ox*8*kXB%Ar`g70Ds66v{k@ipG!*v3R0iw52 zoS`_t@Gv_&qkCP{)Eh)0h7gZpuCc+pq4-1SD4wX0B)c~O=(xMVV}z*>pnH~I`KZ+I z^}n=0kp&Men1d$%++G|1Vr=XAVc#*k53;oKwrf=4!DW#Cr76ij<%M?L|~C*7Lq6aB8So?27L9EIi{ zr)RWp^lz;`GyS12O;n93=$~hx)U=8!6okhQEsQj`U=3Wj7Lc&Rz8fC=XlHpMm0U7V z)SS8Km%D?7%0uux&Osdw#k%Hw^4!;k3@^{~(>5yVo4tk>V64SpR#S!YF>1yLMdYon zka<>X?8r5iGQ_iY)OxT|}4zwSM~a(w@koIEt8YbhjWE>%k;F?2Y6yVEM(zI$HACNE24E)^ON%Sx%BPU-H<64Kudz&{Q1lN zw8z*M(dm~cpJw)h^)BE~KQnJ5y0>vZEzPAme?7`K6l#AE{pB$!`&cXJ&`1Lq7f1G~ z@D&)t0(6pbW4$w$YXR1Qji7_}upTYevw%OKFW@^FT4)z^j|RWgHyAdr^95)hM&#uJ z+L&6v|3DrJ_-`3wmH5VZ4g6AeYc|jW5Wtk?JLKsE7-tOKD87nloB>4`- zWs?%@rC#KgAoLYgJZN@gnhwZdfj3%xmvV$eC+l85@rp4==~N z#sSQ9F1+ftj4}BK!<&sk2E~}u+^;uB!+V!ChQL|krPy))^9JGI!Tw#T>x+HfZ49;F zu`a0r$6xz>zCpy!V)d+;2bJYB^60Vj^>to(bJ8fgCT8-ZsM*5W0~WKoDkjZMQC%03Jc%z8aR=YTYZ9mRhCTdI5zSya~!X_Gg@lh~%Zg6S7C6*oV$H)UUJUC=K92 zP;~h8{;a3B+k2RCvZ;FA3fOG05@QUodm*X5a5zC0LHWpdb3XPM+qhTw@|g1O?6dIi z)ID%3dG!%wZ%36p`-z{CAOEqxC4c8<{*ip_*-x7G`5*it`Toy*)T9ABcjev05%b{K z&TS=gyw+^IL`DOLq^8CxP}J9RO-6^(*BzUkjmqH%Ka_YgCSGy!|DV0&Uto+Odc^Xp z7*3lY_f` z(%$5it5^I|?)6AnF-lvVFFN1gFPZl%HOS0N$E3kmAk`(L#L|1#XUFEkbt)1W3%Cx? zRg^}dpAD8{jA0FNE&3k1RjGYQmW^{4Cyj#DDm+`7oc$6|V}tpGv1IS=@&(4cr3^7# zkN(*1irBFr;*2OFB1jlt=uE1Tnfs@Ina@1mYJrpC_&EKHfy?2O(l@6*S7l{fXX(u6F6kTY(m7Zx^>xJ(4n)2*x@N5B}#r?yhrfbmu)O%nqZy94YF;I@65V?BwYT}dp1LF&Z z7ouNK*kGXHHA))pXDxwp7H`@0#K)iUOMSxA$ZZV4BjfdVCS(fBs(ww5nKTNEdDE;vmN}klKl~YCjWIv< zxBs4e{F9%T2OoY^4jn!sk3ROeoP79UdEoF)q31(0r4k9eDOb83gQpd40jVrt3J_Fs zZH&Q~YrXG5u8c86!rU2D?kWW+c5M2!)ndySvo>Iemoms~X2769A7KV314GhOw@*Jy z78LUZ))5XEI9kACkb=fKWAOP}D{b!FxuZg+OCm~xk32psb=C7U!eV4BDi;%;)8W|W zo)cSG2)2mQ(zrA>L`~YU`ueDen&Ev*^NcaRv^GbL5|Rjz`w7qpYls2V-{|QhC6&`B z^aFi@!K%KNqWD4O-$Qcvz^oiSR3N){c$80b>TbZF8k(cR{d(}K7SI;x9{dS{D<1F& zu?U+@^-e@gHv2Wk2A&J0Jjyu~YD9`J_H6K-!}@!o=s4CXd=D*LKHcCxNy){tq^8td zoiV0hNu|PKz`(^mNk5|m#3{u#Qhr^z9x(ansWn3+LOrQvjB%+@_ktob4%AzC?0BvC z>YtU`=3U}R*_R3my%Goq<;{1Tl(%j$Ro%vz*sOPfF-GDJ9j~gclQLh0)HSr40`NNs8?*l^45ouA(e%P};!w<{H@=V!(PCW0(Wh5QAZ)rd0QZZKWnfkyY>? z+FxNJH+UP;d4_Bs)b-D?+_Rf5G7pwA$Q<0|lOwy7AJh{*^F+No_E4SfDOGa(NVPF` zAiMh~B2uD159(5c{<7BW^Jk0Y7-Lwk7#3Ma)PiDe++(bC7@C#d@LU*atl|>`7Lhwc z!x2MUsk`Bp8>qd(n55e?xc0sNu!{9@IdWiO6dQ8{Lkx=VDZLKQKnv^nxChQlfpz}! zIjOgZbim+Y=h{j@^jmXNOj=vAYl|6TEZ8qH8D!ESJWaYsWH66$pkQxdZPe=A!5H)E znMNZ=pi4x)K$looc~9rbU73jobo?kXAJ=hmQco8uLxZy}`!T8L-1K{`u@Q_hI226! zXPo^)`-yqao>fudRr*+LB45y_vDcTEJCU7LRVBL4i{$3*fLY6yPT{Dqn)$XIFwZx# zF=n->sVbDFMyHlxrpEqd_iYRMf6ExN$pIl-i|Ck*h3psH%v`N1vWD zuTydQ+=NN9HRA9AYnP%d4gG=vu?*Bqbk<>Ll@QbLU^#ivC(pjWL5}Yzk>i~{(~j-+ z$phN_;}PliJI@QVQl*SuX*??N>8O;?M&;QjYvtiX74pErN@F}Zak$d7!<`lK?v;Ra z_jzUa4p9N$oMHiB&`^-WwBiZQJ+Xn1znM)h)k|dyxq&st{Mb+YYZaW6H-W;!A}OtC zklvmyBLHVI#=ywt(-`B9uFIz}22W9UM9fNA0LTJ`AS017sjZ%`o0CsiV@zDvjbe2)qVr@US;V)H7odzNE+*_7Un`Q37iF-?tL)8{Bc;8)Xec^J>&m1sO;u0T2&yzfy+a#i{f-0caOx{cNl z<|rV|SBrw*pvYk!7{h6bVkZ+wrELu{%t6QFKPLCOof;vmxs~whYlZe54z0r*AH@~Q zI$DLUWehR-aNJvtAqLb`&l_9T(iqdNa|zUzdQ_$t`S=GK<;cM*bAAh6qx>Xt0hy;q zkFf?BXq|iQ0OkUpr8CHo67Q7C`K0;VwZmt4a5uOPh98VFce;YcAQOmi9q0?0RT4kU z0?RSRfO&^grEN;Xs7LG6t#MMNk%rNNwK=3~6D19wGmq$t85I$^)>P1;=jrO!vS08V z2lrJjc>YV*{ALe8QHtS(dJq`KTD3nIXKH8Qu*-d70P585ps~yu6zpy#^+o}7CmVwd zbKdVKWm!~;y^g`3eb;S_xpb?=WYIx?Xlrl^yD>FeqzWvgOsO&3#r7tiv>%F-`yb-Wj ztSs87(g0EsK)ZLT;B~MxA|0o%N`2puRQ3$XBmeZS{PA;r^3q#la{bDYVXOs=F-A9~M<4x!M8Z?bl!qi93naCPiD4;JZapyi zO4i1hSYf*q#Qjn@J80VLuU#>7Z?#BgjPWT0H$2!SvFQP6uJKDr;h2;bjZ1mSloZCD z>(e|l-Qp{7q6gi^7>e2MR7N;giYJqjP?^V~qH<}d-JAF{zp%y_(sxV-x(y@jZWSs- z+|R}s!1PLIkV)-}&D7?jd*%%?!((GQo^8r-udJ}^W<_^*x6+xY8Q)Cpqfd@VU3IdN z)#8O$#*BdHkLG5bZ($4T4QN8Ph8PQKXkeT;w69#M>kdj;`iB zMK*#m2)+U30tyfWRT{j>$n+PA1Aa?G0a{jAD2MJs$4pSICIh(WSHKe2&u80$i{535@QT~j2?n@!MZmzSNAsV#SIJ} z?0W!X428}^A=V`K>Cry*$iOfuKa=S`N^bg`G3PjV{Tlix_7aBw=M%v!Z=tuwN{jZJ(Z!MN2mWrVQ_Wjp|08Ec9~Xc&tg zB7oNjias`SHn_Dw>TR(x;GMU37aN5N1p_nEKM0fJF;;#)vrO21gGI(>J@Bu7_50-O zU;JSiy8QQK=+b-})K)Y5JJMMA`-xwIrEk7$`Z*~N|JS*eFAVhElP~@8f0LJA{8Q<= z@CE6+_Q$66UipGtc=fmC!YlLb=Gp&S-Z(vB+ThT1ymY}85o_V z&~tCvgsiV8iVNbVxp}JrWn!=24$950kTFETAXp*%egd?DaOIG)`A z#>@7D&D->kxnHXgde68Zn4UXqK6h`c|r1-*s(X0FbpKk;p^cQ&Ia!{Y^ ziHB?D=z&Uk@{w9OcCgYYN!f2uD46JGm0iL*okHQbQ4V5|;raQEZ73u>o@ptJ_lrb( z(>5ZKnOjavkEJ=vd}8r?TP;S%=6Ox}y``a8%1aBR29IlP=;UonLgKdE-=}Mg19btI z>nJZ#LNC>z8E!+&=7k-*{ET0+A%?XOUD6O^mBfHFL2CsoBV&j;*ja8AhuMG{AEtg( zqPC0OA5uXd@LSs#q(O@r%Zz&rGLHlFckixpskGM#q<5Oh1-MUi2PmegH%n9#jn{QG z>16}x9*+~yeE~TFN8hQbu+fnq58CH;1Nw(To5&zA6D^SFY@u;-#n^%&0zC!>Lkg&K z{+U>TX`HXM#YtsUS5u;W$(~FED0&&k@d_pT!v0m6K=%|3F*wrlo(Ph)mg#sF?t%3{ zWRVm37m;f>141og_EaK^h(f<`#cxuzL3`Zz@Z;Tb>hOi6R#uYC!_berw);#p5k@o| zb5YU*YlwL-13eyKf8N$!I;YRTU~Rv{015A7fgI^JzF<^)ufkVWVCd3PZF~E?(K(&Y z2tYS1;FX}sZhpzOfYQF@INz)cnQ8G#u@xD!47``3V<`4DG&Hn8DYKUCN540q8*TbY z|Fv%ps^F*0xbki$G;;+O&s8Hm&6oq;R9Iqi{AuZqS}CrdCt3)>3nOE|{Ef{jP3jw*Hr|+cjFEd4;}8~eyb9Um z@#NzD#>Ntzy#Zk(W7vzgH5M5mJQHBF<|AX~y${)RP;jVNE)gk^!HKxs?43z!_wH32 zrgXJPjf??&<}D4&bbLnc3}n|v1A4!4=YH_)f$;?}n76ybMv=qZ4Np7XB|IPAt^BpW zO$Eve7)}@<=5j@Om9DQ{iEr}@8yQnt9Fu1r7?XY5N~BC>j=s_44PQx?@!Vp}c^;HR zFvz(Wn~eef^!;}Z1W6i^&(vw;hxtJNjjx zuK$RR&uG9Y2#%*beVJ{ubiiV>r76pd+}!&@LyTk4&V+P^m`p}k)>|$kW1PBJ&OFB$ z^UUM*O1rb?b)a*%?*vtrCpA~xC~wn&c`=eOF4mP5$ornC&oZNc(}&O=B1R(0H_zxJ za@}mF8hvREPVW8!$ZhV(nA)28`WM_YGC(E;D&TzdIrJU6hfGvgTcYFSHIa^2u9N-5 zp&jgrj2+jca5`&->v7EFL`csOHhqHZ2tDFHh=##9hGA!DXiE3%h|}h0p=;;k7F)pV@u>#(0XN#=w$ovv3<@FvP@SP65Ti5l3j9 z^vC857d$u5n$94@Tt~q}gc8!l}l;1>#OsbH6qi11?1UH;KzIark z=wBW~ve5y(h0%j?uPArMI9Cm37a`3JBfu#mh0<-c4KOwqI`xwbG9J&Y#Ko^d;o8iv z^+a!PuS`x(E}#YOcBC^XM?2Gdp}u`KAmr+&R!r2j?zgao%?JdxYz;B&U1Q@>jrKGe)2KufUy1HEOe0W~- zZ2R|=OGBMkd^M+JeDtnSq+zV5&oGhj`S*}30!4}_KHx+i@@cTF1$_(eH7iRoTv+iZdItID4RqdLCfdonW7D|ZJ5<+XSH za{FFH0y7>dR6b^P#uy7{eXSOgCRLu^zY2m6AFeQ;G5=z-#d3S_{c_;YDQRly)X%Eq z-i>#qw9uQ>JaMngMhoP`BcGO?dmfg?=DpHdds=zCLb-U=pT^L&e8AJ*Re3e8oz26AnTp~e&Ru0%;wjjrW~jytLTvITtd`OAJ? zTSRWeO`-2}eathV#HD|Tq&ao6#?ZlR0UhN!1awU6oFlzlw#rtnovkqjg=Y41MEhCK z$8&KE`vH+BL^`6!A^HQFNuL086ezXfJ3~5Fq^(3wuCJrEEwx2T^!^Iu-3ycEp1BL< zQq7vGt#u4`{Dw%FbC;B_)$e&8BKk4VR8^|%ruTCB+LVzgIltY@*y~xV(2xDPN6~*6 zeUN9N+5C=cGM?)N=C!G*qJNQ316Y=tkD3tu?GNA7nDdfGuN;12^A9M3LnQ=o8jYx<;LCyRNb^#=sZiAdw01SJpUb zpV@uqk{KDL(eGkC~KZ_cN|vzpe~OSSP$P=K9o6J z`IR@vj1eZJYZ1W!1=_k{kxOF$A=m7!I|0LZZvT`AL%l z6($Ge0N!|nTM`*Vx`at5+l+zRV34j^u<@k(K3%hbkf!@SU9*4?ru&|AZFImK-<=eB z;Y?8e`c;2Y`---&zV4U16Nw+Ypi5zHQ(X)VO#`}Krz98*W^92#V9CasC)coBSS%`z ziZ>;+IU6wV5R&X>k0J#_49xD}2wnzp*}bDoI(PdFQ_1FwXDK1;*`zF6Z{Ug9+~7@W zD2Ldn-Smk0>7>HSUK#XW28xwbb6&}UD-57Qd!BJ%9h=?nWKsGh$(X#~4)Y>|y{3tQL(V9#1kjToE*z^MnT zbf2u1ikgR{zOGV^9jY+GH$rBg(i9Zd(3>3{r6vb?dn;*I){k$Agzm|3-;2fxXSF~v zQCL)|f^?PA%UOxJ_%Zfz`hmJA?lc}K&k735w10y_@n&eRdw=9Tp1-6p#pwz@&(vE{ zo`H0`92=dj)a%8KaLl%z~MRYxW=edQjD_K*=I0R&@=Eq7q3joEqyj;uM5j} zUL7_4NbLnT49}~NwNy(7=UC;D)BK(W%}#~;dj8<7jH|3bTkM#XgOjc9gjTr&NPTzt zdTwMadsn2shKJ46vQ=aum#w8TZtbxAF( zG7K2YRfuyPn$^oMZ)EZZ#+or=9NSt-9A&?DBXS=`lKMI)wHae=6|yKzF^Uu^4J9MO zJMT^?-So?)tA6?ROT$V>XH9e@siTlrZ+8XdwYSEMkp*4LORtR>!!Z~fnwHn!8Iw!; z9Y&nj-ySn-7Y6_$I*%T#GAY)qK?CJ6sn5`r7-rG| z{v@7o_+#D^QH>)|YU6WTGj8R8dfK)&@QjU(Z4{clX+VDUFMQz(#-sFp!`-`gWpL2R zb?pYq)3rdU%Blb4XENu4ed+ZPlQ(lDqyn6-Uqb%Z)ffXZbPcsI0xE3!l$U(+fl7I% zLmB+j*Ufjj$4lq$r8hYJ)`yGba|az_GOhyWt;7XN4)Sj^!6rR5+=JZmY1E2^hd&oWQ+) z=NXp*j7(d?8x)3OF{`!(1h+$(B>+Q4LB3QV=)=@y#M(^Tw7?6;$iFt&xSV@9%^@zL`VkM_wozB_7Y2zwQKoJB|LJP$CxVm8;>Aw3FolNxD6i9Yl| zmG0#zuVze+@OREl8pjHv5T86%GuNjm&)+yRVLpHCp&H|8!gnafUU+5H7+rQLFY1O> zxMR3L5%$>08mX&mG?6x;(5N)l70Zf}m&G_|c{O?leh3GF?4wFng6!rP%58x6b(J=7 zH&L$#Fn1keqJtZ^=6Rqt{XDz0N)F(Yh%UoXY`NfAdrttl=M#@r%L9ii&3hta-o5=9 z>Fn&(IaVNJ!}nyc=d6T+j>lR1_D;Ee<&1P}-z%fT{nEDUq%^heHs6)a{Du^IB4*6K z{N4192o|gZ3JEU;r}%qZP8_W=%5ofz0N(bjCF&kg^J6Jg>rcE1h4HzIlRBS*(zdfg z3b1e}SbI3uVfdwJH2p(5CO1$z10uE3VfCKUnU7z+Att##lw*i-WE1#CE7KBnXq|0X zbF3?yBARq#$dUkMG*N6z!HzM@v#q*Ne&ln@;|GbT`18N+Gdc@0UF_UOq4|aV#Is>+ zqILUz_Q(<>0^lX^%`y$7M?A8%oJ+omx?BWtr)u)dIa`5p2y(J!Piv}4W@ z7+v_?_Ks3*J|lkvWCClbIkdmhoM&V-Y_3~hUuFzB)R7?qVy$56sp>jm%|LreD+>K6 z)3uHvYc*hPu{UjDaX>>XcIbQ|%|CN4m4@!#QEuj)UB?#o^R)u|jn%KEjg zS>v(kq$RUO24PwdNXR;e#TX`(5XB}X(hxuhHaS(5tW@s>ZD>r!|;>|6aE=x z5b#7LWZP+6ue5}*cbHh)*vR^aP^eG@ZN7PRvm(@;^*%gGG2*BU3>GPq%lzQ;>>Cb5 zwoOiX7A z%DlxfIkLy8j}ZvRP5O^?V7=kB1QTG>VKK(@sjwE#fh{m6opdx7sfHMoqrLqR<1Kwj znIn{eMEB9Jq=UoQw^Wb|4M4+qzgWt$Xslm_w|X<*?kAi(ch1m@)P3IFe(G~$ zQeCx>=7QUIr{(NLzf8}1#6Pn&pSQ4ifdH6|AqJ%skqx>u44q;>LMY$8vrPX+lundM zVB(t6l$dn)VyG!F!XvZ<=K{Qf(<$7Yt0wRF8yV0=cw71cXA}1A3ZIj2{=$_hV~C+E z4gr1ImLHbM@%}k_%l8;M0D|tB3x2~VwKmQ74|^vLK`27`j{Tn=fcR#N*O&MzpLq2^>|17sz1*!#eZ{IeGP&+(wJYFdM z;|HX^zFxocNI2-1s~2A8mohmqB6n^&vU?~PFz=h&_eptWt@*5Y_7$DK6bBZ$+_ku& z1*L9DiIc)86W}jMM~rfq$Z6y&_-w`>$3m1u@Vm^}#oCPW$mps1MrI@w^QgR7u6%Ws zbnc;`e2Gzlkp_#19_AIaiS=WTXO2+}oxjM3?sMCgTg;y?pN1H~nu9I__&df0xm55z#=KOxT0*-cAR)271b4C<)T%^C_LkZao2L4FD$vTcGmRcX@6(Q#8;o(WHu|5mL(nCz&7NuvF@V?5 zQw->wpYN?_JogDLv&WLUi29=yI=A-hf~VJY6)V(h5LF~bH$h}0bAjrZg+Qa~+ezy{E4;YfT?*|{KHilG;tQcIWZG*!ja~SZquEuMgi+;_j zEhCNHdl}iMDRa`1F-I)D0PC5ij5WkQW3kq0$^d+GHlW|k`dI{=%hsK8(|~kHjiQ7W zu$CNTcTa$GtVNo#t;m>F;Kq#`@|S=4mx*_q8>A`9##1(*_&Yx^V~h%!@F!osrwctQ zeF0_0b&YL^s2Gbhw{1OjydGtA#vM-V15edUy%J|YQOtMFj*CAuD`V5nb2wgk4#B`H zZ#JMprwVWB0Fk)SHzQYX*U2-FQ^XC1$0^Ex<4#bH9CW-p0EPkUB~|P4bf$3I31#RJ zge|`H@`#N1XXnCMf%_N)wv$Jz&Fi<$PRM{VDRe+E>Pb4L+DmA*^BOM>ydlAv3zKvA zGOa>I&?U!I7RSZvsu3ujc*GHqNI^hxLcle+7FaSe24tR6d4)SNrc}pe|K9RB1%VrE zLT{a!Nb)ZC>hF~eHLvj++OsR!qTf4|Ed1Tkxsf17Xn$yTMR_ z+`YGa?->*hY+hVz_l{ZFyUSw~TsKu%zsA(K4kR)gDj!*k3S^Mih}VD4aK#_NYvIHZB$mwvzYtu7lpv^gdl zxX95%cM7p%RsnLV)1#p zWkJ6Y1#tgk;j?dH17nHdN@s{cu%-Asdl2*@6(|mm9;z_BXh`|2)93w$o@{F?F~TmX zIG2KRTbpApvF@FSXy|doq!6=wI6Me4GVS5x)zaM5q)h2H>FYVIJYbRB>#)QRQK&7l4wC<4`7$4s_@CGQ&SyzZEp&(x!Z%drw`D$QTRyhm>v9 zi(&jx4kEV}A`Q|^4}Tyk*9Yh4rDHI}DaW&j*K3*+DH?ST zMQND|#+c&UAQzD_tg*!u@hbuIZK=qZZ~oPPG~cDeGavt{6-CBauof~!$S~$zcSA-& z+_}5lC{uA@yP`79n97Cp`*Qd})*c@6CyrGcB{t_m$&69-?8OP$wWHi*J8%ph^Y=s_ zQIH(CJ*4vul*aiq#DL_;n0Z4;1Q|U=@hfB_7$^Q6eAvfYQ$_@okmc@8~@1n{w)J?#So`z7T5>8M6|k&f(R< z?p@5Uqlc=L62@g@BxFcpOLMtgx;mx%KXWN@Kmx2C_ukL`LUaldI!rrjbmw>UJ?oho zvHWhOplCReJ@5}r4Me)>{p+<#y&f4EQ(5{>&=~T;uI=+_*0zv4q|U#s$e5+!j*Q6{ zSZ9kFW9(kw1~iL(ak*Hl$e1l-%qsEftFOvyuf3Ldw>c4wM&-{eoHSofk$AhQv{%IC2R_|mURzk} zIUZh2gFpE50V%C?3W|oOW8#a>%pHROV53po9$|m@SFeile2I7I@zJM(^5_GZl_h`kolzsuW=c=?-Z8|uu}ng_h4n?6;Yw$S zVUOy$Hw}3)N&JzCce;x=j_tcREoq*}}Q4jX#&HQVUwj-fW`_ zQ4(V;CtVi~KF5z#&Ur~9_>+!|_oVQ`gB_&qgV1#Ngky&)jgf_D8i!9{FPKR3Iz`C= z59mud$9fuLGQn+-=^t{GcZ&ht+9w{blKp!!I|1N0_4?JY*~6HVC=LMg6{Qhlkm_~L z9%!N{^!m(MJY+G#&}T%JkW$!G12;C{v(!m-<=&sfZ zk3924!-CX}=|JSow_h4bq(akq)j*BK?Dw5~8e1%j58BB(<1?<0K@npI`vQ?X{2paI>zZ{%EjSD_L_HzvcJ~C0QzO4! zDWK8NnnU|=sx30nN%VS|&L8^o^7Sbr3$yl7_-`S%NM{H{e+T`B*0_x^WN~OpWTHtu z4w}mxSu1QtV+{R+zKXR&-{pGEgDqpsdjO;>d;a<76Yn+`h=@6V{(R!y`rxO2FuG_& z3^}1+(M>X->w8R@&-wZz8*u6-ZV9G&Cf+2C%||8Zza#GaB;?dd&w5?w3* zvsK3;5s0@;RBa9b%L>@U& zX%u$!9km&5>l}wJ;gN_CJ*;d?nNF|T>g6$$&R95xm*pB{3JYrV@5AQrX2hjSmzIo( z`SI`d%g*-93dq+_Ps!zLehJ1rG9FntcT){9jHkP(_eR9%Xrb=S2;b~|C?iNMAaY>u ztO~yK``OZ1Ly2n(IR%O$n>x!4qlli0$-^hAq@k|Z6sr$~{BrFEo~bi>9O-}x%->WT z+8>n%jx2PBSPIT8+W2z`g#_t=P)J$f8G6a*6dcCr0{@Bfl>MC4k|?-Z8ofrjWEHd& zb4ICcY43p2f6}wSFICs=l&L^a!ofk^e+%UN~)H=mM<^)kj_=)n6P0{}c2 ze2#riU=1?afQa}{K2eo;mmby_WBZ%PYZShW2aZzwtBEfDRr?nwF6u+F@1eM1 zJm9N}wcoaNDF0PFf6uux#-uaE80EW-{8w?HRz@CU>$#OmCxhKXC-sQOR_Y)J) zr>N<}>ME}(ZjK_I6inF|V|x1vb!-b|`!)G$c|UB%kh9yzct`!xj88)DoYn*8i5 zHN=2?8)G;(1`p<%Pf2}qWud(9iTXvOT^LR49E5MIeoT~0G%Y82hWLoOzJ5dL5XHS9wTzi zg7LtJ%Gx1jJjH5iGAjM+l&kj@a}Hn=d())?dd9B>@RgCZUJ#q?(Rz(zC1u=nD4 z08N8#SpBCPr252|307jv$p%}-nD+=Me2+n9GZpp6Ll#fj#lpSviJGdoF~smU6A;Y4 z@;3u>h8Q+C(vvyZfKxYdOKir|kwU3$I40A<%gQuQ8E?4d7-Jw_2r!v2szM(^*dq_r zNU>Li;MlA(7=?y;AO+gVW7US(a!b?)Na*Y32R~4g9HEg0uU`zvTiSXD%B8M)R{r-N zb3D!#!|7{5x!OJdJfD50+SDOg3|H??%L{M&rL6W*@x=Y|*~j{f5Sj@*%h~HeId{w1 zC{va88LJuX3+uw5Ez4!m_ zeb>5XmPE&(q`Efxm0$l&l@Ipw;LxO5_#0H0^-ELr`{uL5JEzCxxwq`KlgStcGG@zS zK;xjr`97&_n`Z+Y&#X*lC1I2$gTAm)$r!+E-k*d_>h_r{ZfV_;%NfT{vC6U&4_0aW zu;o^v;{Immj9lxSHe?Jvo?}6k8pXN7*2VG&8B&&&m3+vwzl{R=EUC#{-%W**;;8)A z7sjNiA^muByE`mDeQC%y5z{{ySrw%^pSX0TSPhr-ZK$StUUu(FUv8VYzX1`9y!pga zby8XLu>8$;FUi1wT|+DzPChKs-WL0^3|P&^r+%|efRlo8n(^AEG=U4Yfr^ zzhD7nFVJ;~OoBMUncx=dzj3R_=&M^BLMAeXea=~k{)a;i$DfxJx))>&>jb&`18R=v z+s=$nkJFv;zQTutt~eBsUwXVznhyRuX>3Y8dFt}{m*n66pZ`y@b{hKA(Sub+pEK)z z>Hb&W95&9ntqn!SDT?D3!sLfAu>403l zR-|n@Ahk7&gZ{_z>_m(g+CEo6#DL|KG0E3VUm56yF7gRNhLmOWxd$JpHg*ebpJ<5A zu4%K_J7nlo%x?kQtom&5mKB6deW|?<5pr7^n0#p09U?UrQ8(OYTD#9sEGq@XfLk-g zFY-;sP>QA_f{B(@yx8P!%$&VhDXA3{pOTe zAB~By;n@0#MIjykR0iGEZMh5nBeVJk!m67W7&3;*wP18~&SXBp$xc0(F|{r(lQ*$4 zq>@$X2$xJm45+Ds+)FRFRs-vaj3FwVHFJ>7qTD?&l9Svt7XTI9dh^X zU74El@1(m|xPJY*baizZr7oWv`FT_Qp1ctW^G|+jPK812fl`2((m(id-y#tMTAE8e zia=(C;GQ7%NcxKUoKcC)_Lv#mLw(aytP1b(1C`Rgy;z#nunYyGGBz@6A}5^QX%`Q* ziWH&j)8ncLL?SXjH@{>n((}Wr_`mXInU*6_2lH~PE3Agulu-;({s51}^O#Uu-5%VN zeHKMm|C|hs&CBp;NXp9>rn9%LM5^jfNVMpL1PZpQ5fPGi z-*{0b#^>xd5ir~2WI&G(NpWG~777$fV4=Wl4?OaBB~ZB4Y(t}@-U~@M!s7W8Qd`~? zyQ{_B-dVZYZ3j_ix_XT(j4}))3}o6O?UTp{3=0%owrzS z3#-0OPmLL4wWe}b_O#j@;+YokPX%6ycg09?DP3?dZ0tq-?R(?{7|BF=;grGILmf|Q z|6xWAhEk!nr@lUwm7#!9@F+VJN!r!>=O@jYQf5)@ab#8`C{M%UQsmi58^0fdGO;+S6WU^cqMK#uBeC z1aZK%vu%t`TWgA?spaERQC$~1I}w9@x8%n^d(Jpa5ALmyB2@sVR5wA~GZUW~-;AxK zA*1{_?#Q7kQ#a_R9EUTH-&u^G$Ps+n-bMO(j+HFnpN)vQ-8EyzeeUDkaGIaHG+`!} z;b6kKX`+tw9HQ0G5vY6G0_BDN0B}TMJ8f$&kw=f$nnDII}=ad78Mi%)7ZXxF~9rGbth>jT;B1%U4QrUuZb%*3uXGq&e zK-yYowfy||pWKKT+CuS)h#0Qz)z`R|OCQI3n)Fh!wUE5BfHsgEDYX>wcEUB8!43JL zs-(vidH(Xm z;(bU>J*n?AtoMl}#xVC;&g3r2n?46@dBq6?`c*Cq_@^RbC~MveQhGgXlo9WNT&!0) zy`|o^!BoexZVR@C^```6U|>RKrf1D>$j?EQfjH!Y0oI?HH2ccSLTY2rn|fPLeE`ag zv`t)}XgHkNox1Uz2?%b&B&pD-vrViV`6ObHgWH?eK4OV}yj~XYuc}i0Ovgr}o2gFd z)g98od;W5OK7)=(1|{Ie24t3>tV78_o^3ARzX8GQQzB$o+<(2|^5x5_blKT`D=}Vk zJ=Y!oe0*wEzYxV|DeZ&_&Opc^*S-@u=&Owi9r+L9Ei-zgS$)R*x{=-rg(^iS#F6%%wd zdX6_T<_ojkvNgpyBRbBFg=6P@dY_4mdFRrUK3{=+a=u6Qq;OuK&=P(PIOk1$w)3~R zPt-VPGbx4%u$NdfxX74)^}l>u$}8(6SdcjDW^QIo&b{}hOixWod)=SPU;b=V>v5NS z=&^qqJ0cOt6xMfYtA9!B{T;3Ur32PtWX!HF$b9Gt^V`JOkUaOz|IK{P6<_(Ce;NBE zhP-uhqoMM;v~PLce0F%}^q4&NmL;Mwl#>_X2R(gu)@w3c)udbO*vvZB0h*{723zpa zV`b7<<3rJ1g?i65GRA?vdH+PnO^a33JPi zou#I2;cU2iW7a(NGPDbMXJ^f4N zc{(g7GKQ2TJm-lAtBuZ#0}m$z1OkKt<5?=AA`|ehJ$-VE96I(jsjY96%EsNXJr>i$ zopR>X59Rm%?2pU>;g396V~B>qVYM6dTy!PY1|&*^neHqIjq~`?hidfM3XC2W(0^4` z1#+Wv+RT3EIGl_vv58z@C6O_Hh#0Tq9Z+}FH|gkj4`#D6YaIfHnZ4)(TN`YeI9jB%#viI1JAkpk_^VU?$(z@J-ua}KMWs|!X3qlP1?A;z zTN4?h&yWqnBX{M+SO40OF~9Sr=9EqmlZV=^KBPLN>kIVo3snz37&wP75PdE1(ord{@f+4%e5i$6&b^`CKEAbrCJ6}Ywwg^Eg)k6W$^ClQ6p1X->kaIj#IQf_Pz1W zu#sCUwd?Fy3JD!Ba*T-yUh<``wnWFCjb=NpKctdXD!cHOK=)$;51>zOrYZY?VPSq!e*Wx#C8sX7X=jWtHhix^ zN~F%tPV+e(k&?^rxn85Abw)n_2|Keq6L98y|3`^L3<4!RtGW&V4MFn0o3K6-X&NS{ zB1YkU;%KF4|CRbvSIlmRj|cyg75qg0c=2yO8IrFYu!HNUzW?=D7p?yAE-Bs9U_Jxb z979(7 z^YTlyQoXrWIg>ac#z1`m8H6=UC4P+AOGt8=cm`zI`VgGvrF- z;$?ET`)fD(Bx8WRtN%8;5n+gvnA|mFj*bWD6D(3pqziomn6{MU_(w-TS8za=aQ!A1 zLMB%-24@)#$c~+5vRk*|F&1?WNJ()(q6-W1!fV5Zz{s`jJ2K|V?FZ%Jl^YT)ERll; z4@y;4mAwA?>#`7;k?4HCL_$Nx)?l*Q;r*2f4#5|GF=QfSAZB=XQp4g9!3j;22{W%D zMo4!wGqYeOIq;mMR&!V`8AE*#<=_SNk%@@ezAdqws5jn)zK#PDvikJ-aYHuX~Yv~gNK_HeB!3uGwu0hvHukw(fJec#YfBn@>P(%kqdX>M*dSuR!^*KWKg-~Zts z`X*zrr5uq$nc+B3E<1W4*@%qJ#GC z4#?qy!IaKTFESG`POnSvJhKka`0>d^jJLbSRS!Hnut>#2g-wS3AvkGX6PZ?wifF+9uQLRJHj(pAahyU(F+K9ut~;z z009~E;*Wk^UOF|c3Vo$C)Ev@IkvhzLEr3&Ibad1>a&sY7z;gF_(b_yNj~(rk%JN87 z_ucL8S^3EeeK`;@4)?wpqqGbYR!;n~!YNOVjCra>q|QUe?D>P#it4}pWJtaoBV!;t z92rxSf{gj^|KHc-cFz`h_!#LN7Nn*sXcl?9cy&UBMwv0fKrUp=!Y3b)|KH#CoABt8 zz=Hhy9euH*65%Cd3O;vK{^HpI88u`~RQ_;BuTlP!;U!~2pFb+!{L#Q7vGOmr4M;=b zQe)Xm#w4G!5y+T#U$;u`Q%^l5wY9ZowmOSxgJ1jAUy>&tZIznhAIP^~9akfa$}Jq8SpM?Pab7Z(RizhR(bu%@rq)f6rg zIq8TPP*V}in$pf-73#gaZ&q&Hi95SZJ1q0r4iy`nkgP`hpw* zL`l*)PN9G~@3Koyc1^FaoNToJASuHiSN2Iv4+5C1dz&OwPM*aQ$v0s*s z(U35odSX&)e56phc5_BvdVTo5BVr(7AY*dHu_Mz$y290fad@iI|Dh8#i@FX52_z(r zFytYQmyHVgjEhuQDHuaoOOTxT$bl0_t4v;YW_K@Wr+xSAm`N)DK}&ybUxon&Fv83@ zrDIuNzjcO%}-iR>7Nea2^kcx-_oQLk=bWqBqQ=gI_|MOxtN*DbyMkAg$1p$ zbH~&7gpB#k&uv$kzclp|?dWfQ+$Td*HqyxvDGs~~vJgNzx$?}FjPb4wQ&B-$r3pQ@ zRArvFn~=x@2ZMT^$Q!4IRq7PVt=oyuQCx(RYFcX|fo%FQd<@WN78-KY(IsUo;qAW!`CG&9lX zb?^wOvRah$R#-?L;Lwtd-;=ij)t0?m`}Rrs)Z@41z^+kM9IWD$sk^^(W=dXtqd#Gd z7=J{}y~p5)8g4zRP=@DCr$s>X21c<|dDp52(atJWl;s-NyCkb`Pu z0eGF^m_A+7Rx6?UxN?JVsj4oP*WOt$N^g0YU0(si3ugp^)+xLwQ~_1$`?|*E{6KWc z_FivP-tSwG>yriYPM<1Q^8u6EtS}IjiSDs9=Pa15Yo)*J5yBK;F`POq1I z4)-|KvmiId1M*g1KuEv7s9z3G%7vcDl5mHe&no#Aj!jLcQv&76^xzl+?4juo5xdveU2_kwxS@H0aHDkbqPV(id(W~zc z0f;dUS%%?c@^0!eL_t7YeE4Lo860tzVE~Y07bgbBB=w3hm5zu3Gg=6&-EuFs(Fyy0 z4km?)_BWTSIvdb?Hrg68)FIBPK2^57Yq8{G8`HW6lnc%hWDij?IDy=ZOgAeUxkpZa z94vmzI~kBau5H@7Sl${k$lHL*_+a6T4E0`=x#?~R71v2Y;o8jxgoGjD^~Q}GX1zL; zYPUJGZJRR-^gncnly32NNr&fO9+uM=Chj{T2FyhQ($}A;u=_#t)`*Vhu`hWBIl*y& zFl)W1KO%vGT9u#LB8B;(B9qJbJ;exh6A9_AnUvixa9(Q!2-q*CFHi> z-Cia)x(em4)@fO3RBEe(hS+5WH)V!neL03EWscK@F`V4;HX+;)FaUdd&gwi~;00oNRy zj7o5!Ub^r08It|jv18KF(IGFs_@X(cus9&K^#$hrSTk)(?T+@=G8xzRve7c+Y`5=5 z7r-9Dfe+cWduO?s7z23$x#7wiy@r|iZu6$Yh)gYYEEf{3&h61^Keah&V?!72;yM|1m)+KGHz{pb~n@GpTS~1u^I7<8VnF_TG zh!CP)*-UhHq*Cv-PoJ?;+sMit^j@4hcTRrycYjyjdh0Fu{V+UN2IcH6ZP6b6R#YhR{B8uvGSR6zYCRHBv!Zd3OCK*QM;EW*xPT z_BoT9?9l!aJw9mq_}~z0B2gzneI^$FkJmN7wQkq8;28%T5d+~?SOBS3Bs;dJ?=OiC zP{ta6L=3-E{|>a{RHSaMp#L-0xGfIv=anPTP)^bOQXaBl^DXS*RDc1Vk=CzHP1m#4q9{XmIQ)CQS!zPj(8RJq+w6wIyx4!i)^Ba*dyZ3C9 z=U(`8^SvMtl%}Fu^LfwyV=^^0VMr0sKQv|fS)?p1(O~NO@Dmxs_39d$WoY28`Pm}q&EPn!hu2ivnRMqa zO&SB5K^vzD$I|~(5ivPI>l_6oSwUC{xR#fUakyV2WCn*Ls>r49&l?r_j*uB2n36)( z2#ZRaq`iHQM5INgXLFy8;|Ht>GcYh<{w4#$g(#S#`@&{{e!qZJgorUIvhG771~3Eo z%(>j_WVIq=XkV<^(7L@u_I8x1%wLd_(mE+E4a(49zx?8zQRB?bIo(#C!Sgu>s2?Ev zA#c62d2PRnx1Hs{tUERtk!v@n%veDrz^yxlGCHASMSVo7D`w^AuMHWa2@;oxoRt{J z7~IZrfA)N_%6)%juv(EZUf8#~x5hsh9$}2-Z&Z2*ED6JR2gdg=e{Kz)Q=1y?&YP|b zcq3$JkF4#%WSI+BCXHO*u`QA0!I`$b$+lA$iIoXl6aAXM5I8slNc)9@V>#=^cu_F7 z*F?quCh`zf{l*(_nD5oKLD{u8?qI;)fQ;dtSaT&6(5smI@bHmpL&jXaIqBQEYa?Ug z4ykmJF-)TIrYP%ZFEfswY(&h>PMfL`xq%LO_)vwBeSC(Lql~FDoT16jOdodVQsP2_w$G4M#fNg zeux;#AH9)OiuVJO^@-$mnJch!v3WOfZ-Lx^)OT?8x>1N2kV|9?W8uJ{B@xTZLppY> z+{Q?bjLDRu)s6MuD96$wESOXU__hvk*JXa8 zPY<3`C8zba!`~zoaB%7CURi;5_AT^5;plmfTC*ae#QmQNZH6Guqdg?Fhj{6c_0Oa0X*cVkG5- zh*6B|H6c70@bk6NpHO57iRGCc@);pR`Q>{C+;V`k-I2}r8}c0?Q&bv~ndyiQ>*Ly| zx}>A|mOQX~SldHb$NiAX=jA)1nPf3IIA};wqF{!GbS%-axS@7l$6?*J&da`Cv-0T= zO_@|=kTKcTgzF&4+IaS$!c=u^&^ zwNY>^*4L$8JbA5DUSv6>wTqIW{~+sDqT68vGp-JLZpHV3*iD+N2 zj(Af1F#8TUj5C*6#mfbHT)DmnYfjwMVR0t4k9!GPwlOO__GOhpn_g=`zL*0nFr%6A+&hDm@3b*U z91}UC@;#Z1_kwGp^KcApoiT;Cwd6o<{U#YMGR95h0oSizH-Ae?ZDb5U<)|wQ$df0k zrKUV6{k_vtqOauLigcURcSql1f*{WV522f^0s&haFK!QRVUGJQh8@HxRqzhXz7>`|q3~7SU9ho6q z6e^HvwQH#RbTYKOtZvmJWA^UdYxL$XeBleSbLUR;+ssVA>WXLOKu4L@Z@IQjt;1+o zCdP*nx3NJvd-*jjm&lUH7%ymdZZ@>3BW<^|L2qOXZT{ugg3{G(Cr*}?(dHMlZsIxu zZ5SOE5)mSscHdARkbS!gQDmgxa>y1LLn6~aKP%y&L7EZB1* z^E2AX=457i+9-Fyf(1jU=pLEU2F}1AGW?+M$`KS+fM;0sDxMSRNAJW3@3fJZlVp zLc3A;9)Gx2mHD976+)WmfEl@Rd0ZYnSRw!A$13u^X3W3&lP-Dlbd}cgs2UpNsY)M2y3wE5#}s{P)lL zx`?#5tsWssn?g=OAne&`XP%Ou{Eo^_bRyP2xmWNKF&Lp<@;Mzau$+8E_UAJ~hU-DN z@GR(DI35q|DK}+Cc~Nfk$z5%wW?w$W5r-c>uLk94>`NA$e3;Zfu`g=?E0NbuF8B6} zJpYolJF;OdBV!y~I{}QX=o%k+yiO{rJEX7osdcr)iJ5Bsh+HCMk{A3( zHKpG!Hv3$9N-Sn9%#{PdAw7#SU-|884oBu1{{q*7cwd zo_L^A9yw5Ij`b8>0-k-oU#|4oYb}k8aWido4D=BhA{p*pknwuVTUL?^lfb|UK!nflarv`w!=(G!Ju;j+E| z?p?FeP`9v1#Ps#Y%a(mEE!oxUtRbUvzB!_0%fze#BQJ=I3D4RHDerUfdvS48p8ZKw z9ykz{!w2I|#B2^w_pa%F_sS^7gY`SnGya@jxcX%bosTRSGQ<&|&Sx^Fx)}0@I;6eO zSB(EBjn9eW>|)sqMvq(2;)U4R+E{Gbj|2DgM#fOK=z__5a5f^wA^E(G3MRaI+vIY9 zEmc{$5-0d3Rs*i>ZZskWEN9J_+>lOFu&|La_WtM!&Msz>xbs6IpLXc|-9&1)u1mf^ z;@JB7VjXjADpHW2$e3aiHMqHe{|3Qw$e8TNTunq|kPA7aZM#MrKQrV3PQjB8)n=Sk zW3h_Oz;o&8u*j*?qpH|hixwY0M9jSEZ{+0Ow&F0>wQbHgP!N2E?bWhBe4x_gYDUDc zcs{b{?3occ)K)CN^O-sc+_5QT2p0J6rFjV!70THw6LNjP3JjbFpW0O*t>reVf?3vW zyDFtre=plvD@B!Y!OH&s^XuL6%G(vH0FSD$nKee$M<1^@3OR(E;wONo33qzIQt# z8B0&#jKL_YZ)h@WxqyvG#sEXe zXrG`x0?GwP2o5xi@raJw%zDHKjOsrY!Ob@jvz(dTxnQ*jnJsEe-K+FOsfZX`j#h!% zC_px|hD0{xn~>@0osqJ@yc7qm!10nY>j5~VSRnrD4eOX;_A}8isU*w&M8p76O`X5! zU)Na8#rqwokG_Gh8Z5CN6zh$M@zak$yg#fCA%l~aevR(M?0GLRx_EA$0pn}=6ML3o zJ(DpG5VmW9-u|dO|B}BxVab@)8-Ekvc_bps0Bw&p_{1YMQWz@I?^DJR(O4gnSKk~l z%_?z(v+3tm5f1F+>AMaITvt! zKQ#p!$BzbO-)?))Yz|QOp6Q90IB-mEgp3*YM8N7h|3yYmyzZ4%cr@X?aJ?gi!}3a6bHCVmK#qGdTh# z8GebFXICOgD6`61^8j!bNRJIEEN# zQPfgn6$Of3dO94CH{TtTpS|3xoi!{G9dky)Q5jYJ5#@o|PT2_~KUiDANclp5u%-%* z2lEbE_z)mY8G@8Jdv;95A_3WQut5s9*T{T*r4*DDNvF1vNU%UcrRRJNyJYFCBmW&+geT|w(a+)$0UTtk{m2KO$$@}lWZ+>%W%DQg9FA+6( zylKjsn%iV_WKhP(Y-&4~rmV0yBI(pwm!_8 z#uohs0_KVu=NJWq$s-3KV#w>gQmiEr1GqkhKkwzh=jEgGpf{wrM`yz zyy?c`)dlVH4IPVLd1F-d6O|?U>?3mpG9C%0RK0T{V(MxN4FO47r}ezmRFT#*pmjkj z$&ANN%u7R^%CHpI$>+vG^Cl`#+eTwUNc)>z&_C6&Yq62m$H^{?P`^YBNbCM-PD@XRM|@;UGX~b~-O(F>Nhf$}+}5oFC|? zk3Cdl#z{7gzs&>_y$t$Ku0VJ1Xb8&4M4d@fcJky&X>4pX(J@Dk95HFBYbpa$RcEhF zS3SIMyHqy+9Vx3lDWQsomTX;jN2I&2#~cqBlR9=ZNm=7pq`dAiDbiz-x6#Q`xpvD& z^t%*T4&JmUe$teA)0zRw6Q>DsAbElV`Wt0SU66JRc|oK<<>^SDbl@03xl?y83WoYX zHju{Zp`%r@v$f2mWSX9-kUhH&txB4*R2UiUk@wHNVcvNbKa`HWr6pF++u3nQ?sQ%? zpTYS2w0VzIa+3F?j7n7Tr;KQau8z=U_zvmOeK)Q{!aqT-q}yVeQ_^<}$e2eSDmMM( z>J4XAV> z7>VrQy0o2LZDn%!V71XXl0h0Su9Xg(L`?43Bx2S#HYyPV%$O2uOX$DZ7VwWFeIL&S z-ZW)Qwm@G3-g^V~x%(&YO9#@z;~ye}K&B0u2pH?#wW+J+rzxA&vCxuR=nJcorfg_v zC_go@iABsuCgtUy{GB{U#(?Zq71hC;!FXVJ)+k|B#Q~{wGnw^t2JyYS%8fGW?WA$! zw>fm)3CsB_lhSo(!dw~>W=sttQj!5WWU5&kE63V2YZMyN6JUJw>0i>6MWYL*;})rs zgCYeRjl#?sYA566D?M!$pFi@DBAfaBlMlw*=&Rr^2MGNNE9{bRdYEz~} zQ9u$E6k6jFWQ&Yx-d?`AfPYn`B@nYk#%yUUl}BO=_`7qmMaI-#ybI zb81v1r72@UeYa)|kue2@MXEH1<*n<}ri~?o$e4XCs_1E%LTsd(g-@GdHYf`Esms$c zrACt%kcw`W=&wFmxj2}bLd#NasUl+>Q0QHR3=TQgQ-U;sG^7pScx0C3O0k59LFTSO zeS>^N$e{Fj9iMyJ2FjUcA_T?^T2h_vCL`;eu4?<|auK zDbuFqy1Sil?Um>SKA_J_${t79X5yNrry*CPG^;OPZ2*{|_$;Q#@UDnf=e9MCzA zAGT4CQ`4-4r^lBB9bs+!c3mVWrXe=mRglfRCAW5S-uZ+z}?X+8LVmxirY zw@$|UZ$B%4^k@IVe0EV64&Irzq_mr&|iiQ>= zV;+6tGcq{PBUdlJYt+_)Ez^s-S2Ct&?1UK7R+VVeWMUKgZgOPI)O0}3U9fEzlDJW? znJZ4cZ|nW(kF(xTKt{*r<@pyO)Z;RS^OF~A!cQ&FC{7RLvThyk=){0hu=uhG78So;F+NqkxtD6)jC9x}Vsb}1B8D}ZyleGr zVtpXF?XG7c2ILkQlmB-}7a2oDsu##Amu17dk1;tF&;gbc+2W#ZmV17>$e80#eIs^6 zey~Z#tODX>%%};I&mS2B{8bkY&WVXR8B}9~T%Z-&=u5RRI-L&ZPrVurZ7pRcjGm|& ziYVAT(*W0|SwnU>LBcFM1T;>zveH6h=-us| zF@_070ZxKk$QUooeY%z^(06)fjPgWTvNp`%h+V_x@ct^}kno}+8j)Wbz8U+L2-c-R zapPL=G_}apyAdfWS7S!6@#{l&vH4`&9*dfKE!W3=y{T2M_e7*nEke%uH9aSlnD3pm zZ9t1h-fY?-xBBKJTFm+&#q#vfEvc5J(KN$qaExfX@}3h36)v`)IC8A>Rc<1VjM=;6 zqte*4TY{nZ^UlxDOL(GB`(Kk(l+8$(cC0I;8c|ml7@^+&LO)8JO}7*{2fgG-yg%fhka2M1$!Z(O z8;y(swnXw@F6)Vmu?xLh-I1A@$mUQ;?H!L}kv76Yu{bJddo&dsmrhSk9%ua$GLSLI zTB2eg2#CO;9oAG8$PE^q*R8#Ed1TDfC%4F`B?N=f9Au+AUI2 znMmTyO^wLQFZ_SyZ=SO$If(rCj!#R-m{`OLeLSApD3CK5bLZ}~4s8K>{6vk)o1ofI zQA0QovHgp;hK)WFw^>sonT%narmps@9ll-bdTh)tBwVc3SzFyM&5fU47i7%t{m0A% zEVpJ%+4l7M%Bb2G6O*LZE-~hwRu{X8NFs=+okes@Qt<&0*~W#d>VO ztRLf|>`DJ;(v#_-hYwa6I}s9@ndHUVt?(tByEMM2_ou=p5tBR85iy%<$E;5zx83zl z#DJw_OnjX5rUUb)3CkzakuiRN&PC=3ul?W!#4;0U9MI!f^C}tWedr5db;y|Qa{Q@0 zuNkvR#^fKXOU3~IRpv+;9K+0nCtDSy%wn{Rf~z@l1_c*o+l28~6iBf)>Qu9K34_Dw zh!H{v7X(b-U_{?N?o6kT%xGsBSN)8811|~Vg?l49*Vy=+Oi!oojQ)|mjDlJgC>s^3 z$gZSb`UhrI_>g`BV{cBC8XF?acZ?(yDBc@nB4d~pfpNlq49aANm}@gD-GTB)>pK2G zm6n_Rtw4>Ht2ZZ&(fR1HL}RReAuNAyp)2++5f=v*3`r6!Dv;V=J0}0fpLZKFW_w+s z{MYm837nA``;1%u-ox_yU%x8>Js;!tzniAZ1W>v2Zf>;E(>8FTgORc#XyDV+UrS~8}jAZnsxz{!Vd799s(U_gE6hrQJTn9POt^LG=C?Od^vDoIPkfK{&RWUQ2sak=h6u8}p%MJ`0lMu>u7 zY=SI7ab8b^j6;#i>Qe2mB?a+l8Q{nn(p51gGj_0HPNpID;sHG?wYg~iS>wm zJ~JPbiAX>{rx46Z$eDygvQ>=#}eGSA_S zCh-eL#vFa(-^jMuqV8Tq7v|;4g;(YG{^LJOAY-D1ACt1`EmB%#BitPzZ%)1ajJ$o( zrpN`n^56aJgAy$LtVm&*l+`rH_E^k}+>!U+{abnc>@O^F(vVn|UNUBf$F@l%V~C7l zR=$5ShI7&19y?KM(lIfvAVaFF3gpdqN6ZAnhPupT3}e!E)nlo{UL6l1VrVO^Ev2%z zqfG5Kl|OpjMzuYvtJV)0!+J5S7wIBnAY)jFxI`-}l}&|ifuo5m4ZNe94V_F(aBf{q znVh}AJF^B_Y)2M22jsw@m^EMM%MTo!Sv((m0y3to)XD6ERl)GRCbJGR98O$n759^OJ$xLna~1 zfR!&xeZ@^%OQoXB)|1mwnAEXJ#(coAl#B_RPH`{D7zaq185Jzd+M1l4H-j}YyfhS$ zV%7RXJ{7afh{~MGu4z>cr?oHf8K9t7Ras@AAeA<$;EjwkkVRzj0{>-%aK-7hoP2@+ z1qQ`_blko$Wer)yER&k@pjj`#;lzVA#_0g=^n}gg{f=KD7p!v_-c}(~h?biMC|+-# z4a?i_h2*oJo;T^tNJR#bhEw{|wQ+gyQ1zm51UAW-B;;`Da^T3AKlr_0#C}C#!V&iEpAJcK20Gddv#G!@KiL+W4IPqMHL!5#(5_30rc`#=wQRh|l%~ut zmQyVmi5RfTb)5<;A!OE?jJe;47>D&v$T$!sQ=(f@K~&s=|0{tGK{6M$L@S#g0>**o z-6Uc*;RSNQFA?K#KN2#Aj2Vf2$pS;h?2LU`N5~f`vtGy;)}15$7~?M zAuSc_EO;Ff$SdbiVO({FeL7?#WQe?Y>wU}6LC7>W+IwBNLW=5H*`~+2h>=|2$e4#d z_J`8gWK;Sk)7N{=8Z!qE9yE*nkByC)^tfQ(?gA;RkH0Tn@#BxQ z$zObTMy}uJl!qUFSnBHP%sJ=JpErNEH3enct|Dn~O$--w&O`?mn0Gq=5;7*X&pJlp z?aw%fQ;;!TcX2oecT z1??VE4B$j^i~0l3r5=EnM9YL^2P6c`@CfVYEy(ufh}KD>BdnsVNN(OPFl)mAqHl=8 zaqvE0DkMAaKZryOb7zf`3M1;$#p`9_Iv(=m!Xwur_wuyNiASC|wXRDHoqk@#x*Xg!-p;_$(i}l@ZE)x|tx^ z03kz}lIPfKv^8ko|Kt;OstDO~fb?PJ9w682pM0lB#$tqqmyAJ?*;*QvPkpq(eD{K= zB~mc_FaK#!m9awk%I8#Ji{*c-tSFM9ky&kblZK4(3fr=IRoX_zr8F=vPoA`ndIwU0 z5y@2ApaYH?1zs|yc6d}uW$8Jr{WGieUtC!%p{9xiGG^Q8h!jR5@{z~fIrbeV^f6~t zP8aBL6+3GZh?VVQBNCX6$j2T}T-cviV=GXlBl(=v$f4eIYa%&eF*4?#{()4K2F#+} z$+&*~nndTPq&E0XL&i9K_VG$7i#a)yL0Y`8|9E(@A9~@)n3i2%l=;wy%x@E8L-O1= z|2OkFSA6An{$=cw8pvH;Y9!b-eHtpSOZygU;Cpc|$e64|jKeC{bvh&yGJc(!Ye~i| zmx$qaq`n7a3uE)F z%0yQLDjFLYB=MNWW7ojwq`tI1~IxR={0jjHbMrc=6mPH z7uzwV%k$tQBf@bxz)WDxnBzyb#(r6fpS;j1uU`(E@rUuEsi8&QetUe8i~)xZ9g=T; z^PA>#+s;C%+Zvb4oKsi5MJ`_o8ZyS6Q&m-E^gXu5#-JQHTxudn9Fm=e*69=9&%X3z zj6)zT8G{p-6wf%BaX>q#I=1xLixVc&$k|cZ;3Z@_yJqCVl?n4KC2CLbmwWBmwO>B{ zk$XeNJn`r!)sAXWS+O*Xj@I=7~3x(TAZ(hw&}Iey^c)UEAPnr zky4DYmE(!@{GZcRz=fXXx- zpE(|K2bnn$yC!RxBx93^$sPG3Vz3>$dx&VWS!|dvNuOqX3(pemR+NWPeG|#R=0a{c zd9!x#r&}dsJ&`f15C3JfNydBtu{LB3Sb5dCC=Rxnu>PI1-%XgmPoQK$4)B+JwOMC@ zC0#ld5mR2SiouG7U-oxEXnB2!DH-oF35lL zWBb0tp2ZIl_OJYAp;X6G$aRfJWjt&juKp`WrLZDy>@e%@KYn{muHP(`uYS?yO=PA7 z+r_KnDnRDt?K0#@Q&`jRv z$QTUX#}AgslP42Nreq|OG3Bb@rg}VoWXu<2KJd=oJsmkZ|+{n`!)c?QVH z^+d+3gos(si})i;y~N9UB4n1}9<|GCSS}I6`?j}Ohk+NQcN)=cVv@f$pFBC@*}TAU z8`6!xq%x_gj%wS(xf45Jg9B&2dvCYRCU!w7(k4Y2uy##tb?k4(_g^|Ltp;$Kx`oRD z4i_Q=7#mqX3I`6(XD^wO4?>1A>r?fqt2?^5wh!$Gxc1`K`mqaC+u!qzoXHsct7}s= z%fd=Xne{-%;CNtcy`ef$OLK`lu)jhIOApFW|5+Ww0ut8t`RZFEW(*AkLMr!*R0odt zJBP(KWcpda$eXQ6>schXec&Zz=m(wM(=s)ME)JoA{=EG1b!5zghbm&fEXDIL4=$21 zps}Gv&YZGj4EWvO{ayL}-~WB{8EkJWl*Xn+U81&ni`=|o$r$k4zx~_tCx7xM<}+yC z9+D?MTp9aj;dSPFo%{~;>Fi{Tov}~qGaJQ`Shlvj!)C1h_>&Fhd}PF(?inL*azQd7 zgU*Od;+ojzd)oKO!w-J`o{%w5edt%Eq+-9cwWZE!_!r;&A5_kcnsVZK!6Fe8gCROv ztfMIvIRU)&l#PtZM0k*rY+$fJMn*`dy|hmwf44M*)gDTEz7H@FW7?hSNU7Q_WrM6> zGAI5B{6!Ep)ED;rLacMUy5}pt5qvFXva9~y8?%8Re@TysJ&LXGB~^B{B|4Ppb3Hol za!)oE@GoYPq@JIu{A_A6FW~|?y*fk;x&-y;ecp`-p5NJ0V7WvL7#g2nJhV-l`Uw;JTMg{eTKOs3aXMT~}IOYfUHyN}1^4cV0K7g=f%va@wcShDd z8Iuk;*CTUL^EVY(lVsAYSzN(mX1rJJ2o zW~OpeWkA08=`GT6y;Dkiht2-)U!IrW{b6b+*Xe&;EY-zU0ZB*$_G?SYm_Pc?xC+-2 z*|%p@8fru49eRu)o|B^otISN8WTYlz;{OMZjG6Mt)72(p9Gc3azQ~w?$*57*P#l-S zbDwPRaVTx{y4ELY{!or9^`3_hRH*V(AeXOCN#B4~vdI&^b4SUdz)vP)P99Hhv+3OKlH(+Dq3jA#;z~qaWmhh{3nl)g3TSbmur<32>O=WPf0PG%v)= zH~z-Iq5q}NBHv?Qas4p-?h95qUP8R!;1)TS#&*tvr@H(SU zpJfKFziUuu2lgfQiFkjoat$X#Dne#(ut+Xn&At8bjy2jw4j-_@Oun!zGR7fGaoxBn z^7`BUgaYsM@u&RP;p=ZP6FT-K3wE^y)3K9$!nL7?js#_L8VBQoX`l219HX>P#!4?ClZvoe zE+At%wy^e0+`;zrM;o;7*w62t9g}mHCgs+MU7Hek$rz$se(Se>OWu0xEqUgdXUzU= zWK2_2ll-H9^pA|L$2p`a+u2?$CmxNHEy>PS^!@58k1$fupK~H(wA}hqlpFU!ZtQL^ zTXZTj#^3Epj8gIgFCoJkGG2Mq*w7)zk9=;;$e6A>r{x!K{(q#o9wO+IG8cHj+&dMX zfAL?atc?rzj6{suvxb~V(Pe0_&9Mn=naCJFgonfUcu>dqkm^>*S(O_P1y$Eg@q8a} zB8CZcwAaBwGH1-2cPP{Pp#8fs5MZC1$QHHxNXrLEHAmzMptURVSn44y6wPTUu%r_guh$$0F~fyYX%~h26sXbUqr) z_~d-Twi2bp4d^(7Q*8?i0evsq;ZQbsPTte^rb^?WmJRt(y~sZilNr1VIXB5I=nNVn zgdjFhUY7%m4ws(bGf&pZmf9jIxjQ7GNvk+s9*oMfS5q4j|K-DlQWA3#4(s8h^aACF znj}~huTLEPr!LN#(D1^-3DZUfhh|NA($)^`OPtB(fRHXPj2g1WAz9_&-QPGpF4J>S zLnxsXRjE8bemH(kGAO$@&rC=_HD=0fYI;Em7v|NF^`7IoQ|#k6f6ynvP=UDz=Ulol zDxd#!;=-fJc>C;xOoXGxS$Id4R~*KKR`cGp9Sr8K?ywnny47eyxlNm2I{D?3aI1CXqRXrlI zpuF)8&nr4MC(guQ4tW0=6?qUk4fWx~ z`;G_n`TWTUt`iK-Y5mRVxxACV&1+!Y?(%Q+A3g~AS!f&%u1~oBKwAo_k%U~t+2qpZ z_VyLZ>9a-VU6<2-IEV749dZp8^Gvs3bS|JSXA;FiTJxc0r}a>0X-(P zsN3fP*M_d%h|16~3uA|6U^pyc)jhEh7)Pe{FLn|W0LW3!eHl*}6IKcyd2li+cSq*q zo64Wqs!6N897vvT;3U%h>QF&RN zG;iIf`gWz1lw_YQvrH{XX{dNlilZ+t*}A)*m(CtL0SfpcV!VhI zCHfnSDFY^lViTo8E<_Ay)pjv58Z_hb@uNXKerDH0+5OZ{O?9E^Q|a_}|3r-aeI-aHVz8-^-5Ys}X!GvYvY}rrhlm0A zI*_M0lpD8{7(YZ`-?+?7hqc~ACRHc>+Snp0=k&IVHY4(RSoe>P&zXBs#$3nk!+Fm5 z$$5-jv@5`|kUWfYeD?0+K7-mO(btf{{OCKlH%?CB8mD-8lJ9d-6_L_Kv?0 z!O7WN@&Vce`cW?6Ik5rI5$N-)0c47wb>@;m+sC&`Uq*Jb#@7C}Drw&N<=7GV!6q5A z3P?xBF!&<;SSSsH)6ZrMVHLtSKD?Wml@)V9q8u-#81ro8m0S&&*_w&vi>y zq}y~5a!f7ziCAG>m6dNg5T*FNEM`Eg1|j3HYg@5#P_8B!b3&D17Vl$$O%yj2KiVCi zli|o1-XCYH+X&s~FG9Rd4ccG4J1W<2&&Y^g2L-Ee9tYN({OIQca`K@X`N2>7<(uE_ zF?q5PRyR9mq`QAkf?AedG6n<7-Q#^d_9rh6ntI*8r$YYnyLaW4w?XQN4zq&Oh@z` zvus|l==S8Swt=arboQw{iEX!ayE70sa+8sXjCu5lUor$sOY0uF(|JYOI}XW_;~&<3 zP$_%%ACsHc&Y9na2JY(bPnu)y1sRh~J)kZ(3K0WnN6tuD4`fWfi5QM4(Z6oP_&~8= zOCWFPb6XpWqkg0mc-5ThAL~pnGQTwq4864-o@! zw0GWFy?!}0t#Y;x9cW(fX?2NQHrCte=}o5}CF&)hp?*$Gv~Y@RdAEVVpqx2hq{@3x z+eGZ-JR_iEWKGSiX-n?Dg*vA952TPQOJBvHpkP5tOYPX{cXJpSDbT*=UoU#}VGMOE z$Iulr5i&F30(tx0LK)8C`q|(}1IUQB9oa^g%*d6Dsi?4I0sV#d>v8iVYz3y@WqVCS!_=i_PYjjB)3%W(-l#=zNZhdFTC685p*52Rjy>8{L+7hY0XS z$1IPGNiMI%dUtm8Y7jDOO~y=2_GzCyCDqzqcBsyh3OMJV``Li>49;misLiV7J9nI=El=OTba3Tg!=KX4`GRAeZm&&32 zRYo7BY-r23ZciE6!6e(FP=V~*U16NrGb(fD)efZoSd(^iY~JXo^ciM&<5=V~eF43b zNE@PN+*rzQtS^%-brt7xoze06MgNDx+7mG@m73bbTF<+V~~aX#gBti9A`TV{_`6$8~I0D^X@~Ya6CE+liAqM^Af4- z_8}uVhq@Wl_hD^hj^P~aoLM~w8eaqc27U*27LCBc8V}J_iAY5N0<$c2|Bx9N- zh^IXU$beVhn^wiTNFIAwjlvN-V6r$V?EobJ1=T6A4#T7K(mN8B8+Rj1w(GjRd2U*6 z_0CKE7Q*=h=KQJYs0^yI{r;61=^c&AOte7GUJJ|B?m4;LKX1-?02qlL1ixx$nUu znAIR+l0gbfuQG)Uq0d0Huhxdlqg?m2m&t-y!lkhxq{c^d@p+g5xR!(re@T^7r}w=d zHp&N>wvd5{p{@6;j*y=0$Pc2?fR3}|IA_+hSM$jZ&W%4`_H&!JM)dt+UowE`6rO1{ zQCNslFl~$}2cE6Jzd&_QTL;;IlV{78t+|nG5#9IfVLrk zuH^`s-oBu`_^N%j)c_8|J9nu|WI*i49FYqdQ(n$Y=dhV|$~LO{rgek{jLb?N!q*EK zLu#%a8-$F(k%(ME?xG8fjRoaaXPLII*a3M(Kqe=NvMJE=3Cfl_)}YaLI}kP#uCNu* z`B#&W@scr&V>mvzFF-}uQduQkcPtsx(a|Aqyzz!KHa41Q7qF#X$IJ3~--R1&s3@1d zeoMx*wYACJyLXMAM|2F4F*|n@t1UZe`YjIFJ-f=yx&`!L^lFG!9D>My76Av&zH(R| z8RLb0=|x*ww|o*ZMWLECC1ZN~yXB3ye<8g+GjeEmSxP+?nQ`jexJ>Hv8JpEJW0*2n z77;_8r07n|C1QXhV_2}iw8TE6dA>~|#yqc^49dDNdpjy+L3NLCIAC;;a_x&IqQNXZ^$fxUo^d7`Z;ln5AWnPOzn+#Qb&O*;Ajt zG9X(v$(RoqGLbRMMM(S8&bmT5xU*DtY$=i_9;}u}534ZTRi>?XLAKQv%C`ED+#RyS z49GVb0}(San&`;G;6QO$$+n|8PQ(!Q&p_qCAm7_JV+I|JSrlnAlS9kXKT-=E%4szS z8O}vPq29-a!^S~aH$0k$$e8#uK*qdwdPWD-A{{U>E?Cb5qe6{BeSm%)Y#Zx~mk8Tu zpASh-e^J_PV5nFwUk}R7&VW2}JfzB4v7EnDA!8G2;6}<-FqO;MORS3!(y}R2C9YiS zr6hK4NKPEH&-nV=g>vmy;q zEH(G&8!S$^PTxRC>g#5VGB7-f5x1ZNj?Jx&^1;laa{W9wqUECHM+z~VKg^okvE9F+ z1))UrO@}@kp_2tcHtWpAVasoX%}U zV^&7Q#APx_N5ru9iq|lsKeX?#YdaxBS8J<9PzRi zgp5IK9Jya$+Cmm0rmH8c-^qWzx?~J+giKSTNOh&v3;b;Kr(3uE_o;myQEl_tuOFT* z(0;b^zPbdSc2rg#);1S0;~i}lP~ObmpPKS_@3{zhy-DAd`aP02`a4EFy3N(=g{Iv7 zU|Ta$3pUM#8_W31cP}Ax>vlliJF^PqmIR0thzX)rmP5$oLdH~9svap3=~ulOIfHBp z=qvK>Ms}#&GKdxB`iYFu@-a&a2GVHG7VCkG0q6n9?V+K7blpks(8?EBn~CVp`Z{Dz zq1?DVZ5(dM6lNb|GprUNgFa6`G@n(M@TT@-xPI#4ZSv-O6WZP;&6+Vpxg0xoOs-wK zW{8!>dL84m&pYU2%O@UdmUqs~8Zu`8{{7l7=cJ{j#pru%{e#m|S{XFDF3!0E6*i=? z#tF`ZCE7N98m_<*#Q7&<9Bg?alPGUP$mm$RQbMM-re5o8_nMJ0!y`R%`Rdz-KpP$k zt1UDs&09;2(-k}Shd&=MQTe1}4kr~0@4jpzCK*~M$%My<+ElN;F>j(DsWV5gI3$xF zSFT5N+|fF&#Zhmg#5Rc-3)&?~GX|Yj=BvUd7r#OdP-l#fQ|~SR^}J%guPk z7=lhhc|jmM1%+U@>+6c;&9mdC(SUrCF{y|c?n`oWm*Lf?5mJcS&-=kt<%yH83~n0OM9i9 zI9e^mdce*-)zY@J!fboC7RkUuq1>7-kgl+H{JjklsIQR9-Sv94_&YF=zI6_gsz{C= zMCr3L)QXD>O`Bss_2U#Ahh1%U@!#Za_pYc8$m7!9I&TP->gtFJ^m$bTgIe~4xK7Ap z4;M;n%YrJDbJD(ZL5?0G6naLDunGCt6UB0HpH&_qNNTDV90*8LCms#SfxY%RY|-er-nYP{ z4GU`<;hy9`WndwXDY3}JGK zV}N6X;>@ORqEHqW70AGFM0(WldGKJRIR{0FaPzW~fHAbPZ4gUlAl2tWUZhgGlMPxg zGLbQ?5d-N$6byd>zd^dV-}pN;&|`iB>xGQT3lWo{u2&NnE6!lKS7gk+Bw~_f&}w5r zJ1E37{eEoRuDwLRauCxwGGRvxYx>NY@x_rb z0DWm}%)idp*ia~KJ5s+#^5#g-IW6a_*ZtRNTkD+4JTb%zI*}XC_{(>GXA$Tt*OnQo zvJ4P4!8$U#cjewTb0K3Q3o}|zHk}8KYWl~-BA_gD2#~qbH?#dy9Nrzklq*$ECVrTKYzM7xm2&wKI=Buvd;g_{;LiPkmC39DmH5 zv+uw`dE&{Z+pNO{IK&M(yNj9zB+V{PNk+2Nmzv2uk5=8f{n z2Cq$R2pN@8l=*TAnc|{asVrZ6GDb~V=^tCL+xUW9x*e7aH)iD8ov;i|t}+p$FoZ{I zBH?lM#;n}!p-nN-A*khntg_{rOnzXm_x7ocqvJeeOifi_lZf$v_B@8uTy;s_gvojI zp?Td=5gP-^=0G|z`p%%*j~q`srf-n;n#c#7^1TM?!TUi7;NgbhkcgS zz;cKf2djVKgD5Z#VMwZCwbPj7LA$~~#`xff73vGw%o;QF6C#lDUEtSXA4JXeZDq#R zL7qC)*;7&iNOKCVeL7j=cciM@o61>$FBhOvOLB$m2T+bPdS|Fu4o^x&RMp5-q- z4~QP;3nab0+lP*bZ-;9F$V~`qyN{@NOJbr^aSls6un*bpCNA)7teZn>Pxg`ak9SM8 zkEZDQ7j;GYe7BGFo!m37N6>%p{Wzww1_a^gsJd^;T9TANGd)FtZ>1qh;M9gO$xg5gdD8^*XAWDL;( zghqOSQ+rts(KJXVVgRHDp_R>BOQb-x{sw&?3>-o=39&@bVi2qplvh3onY(>+(mya` z1{TiaZy>UuitwDARpbBcbg|j`gC!EGD3*efkQ_c%FU1u_vc3I5+0j}dH*{3FURWuw z4TWU9tW0_qLed#7lnbhm*=^GNg$x*+ASG6z4(4+zAd1yU)3VX`xN&RB2pyEwWE5$W zNVU->`v+%Ka5Dprav=AtbyzZR4Gx86SDV&D0fQKWxec+N(lVNwj>PscV=yWa9U!@8 zSt*LVUPC`~49?))?WOvi2$OlKs_8QdROI6=1D+}s9Su_U$fPd`==z zP*$mrW>sLdv*~~HQlbh4ieYzeSQV6@X(tQw^X43g8q$qX$0&Xb(*1+hVahWykURYg zMaHFktEwo_W5vt_=NS4g(K0ODk8sBE%EF4w?86}J9hj3VHzw664(fZBnd{O2$>R$c z$g^QWWrds7!2MDg8&1(kg=~>Axnez#F?k_k?jdMr&S+T<8N*DbmAvzMAY#~uk;P2f z)!0a(#xt;(DKiNf8+iWnm!^!2!C2v0jI8$%FRMk!V8Gmun}ey}3`7hV8!yyzvdg@D z0LO64Hri+Ghb+J-&4r9{6AiM#IMn@+F{#D3FVxmdoAPG7WZZFJ^2G4S(!QAvl)`N9f_U>$rEE@T#2$}JTsJwS(?T8o$2o>ro*EM9W+@P(;zGOit#N>}c z`Ot|P>DXCn>I)eNAyZpZXyk^ABmhKQtR@-5_5ENe8Do)5$>R8ckh>$wq4S^ZQJ73 zSYIuTHMit$f2VOMu2aZxHu}!P4m*YW!@0w{R65`l|II0?_O*KA_mYmY15PwPGbBhL`qOctO0cT+?c6X6Lp~P%RZdVtbfQmv(ZN!0fP?G zm|`v1<$!0}2t*9O^PI>Id_N{tSJK8lHsg%f_MW^yw{31!HvCy$yWR9>pF|8m#?j_! zJ8rDO--2F_y;HAkWNwzVrDjw=z`-4q8=ccC7gg3*7s_l{pCh&pa)mm?)^I0D{Eeh&jPFz1OzU(~e`7)|{mFYCYaQ`h|Davp*zMyt>J#7M zfLm8PwvVxcefZ00Gv0j=FFcEB3)&aG`^t$XisZna3e%xeZFKtF$QTHN zsJwZ0%rqL14>ATP6@ttQFA;;|3Bk=fE_b6d_9fkecYqxySuo49eOT zRZ0kz^lo+9*>HMu-K9t`c(^uYPG?&VA;W_4;}cfU!R*3LBV77N=jHP4unbSD@jnxl zzOjYHZD3pnQ8jJ|vER~kTnY-SWOn+tumJp|3bb)8k|8zR2Pf>t@jZGy&ebtc2Ld}I zX(2jgh>17f9g#~{C-nCPdFV)ud5?5Jzzhtj;iE4{+hlM@S!5t0H5u&<#gB4eW;qKG zBFtC=0dfY1C(fK(oinD)h>!vt139AqH}B?vQp#Y-0LSqR`cwK27cNieJyn^~@}hqb z-NlTHJ3Vv85sVX+Fk1&R*y(nsd&Y$8(iVsY3Ts(0gNQ+t_KMJD5jhl+?%s%Wc1@Y+ zDk8C%rHYcktUmkhe7CR*WX2+Dw2hO-h5G4KWsr@!Vc+5X71E@An09-oCmgHqh$-{O zAFi<%1E%p6?{vmnQYzq;IsTKWI}JyY!(|A!N9=es_@=ILPkTjr9_oK}Z>Q^(3}27Ar-L-|e-> ztUhesdLlpl0NJ@_WK2wd$Onk{ipr!J7ue{Nv|Wr~o{#&_&-;@RM2H;Rms|b3^{ze7 z4|eaunV#riO(tZBX7C$n;un64+pcpEP@^>VgAe2q8B-U^2)5f8>M6e}AyUaSNgg^0n2^5&@#W7A^?B3GQlpMFa}=Xq%BWU(N97v+ot z8ri}z>t#zuqw2`ZSyzQ|1UW}!3=vb18pu3~5Z&4@ z(P9?-$In3dA$#$=a31aA{j+06Kju7i{aQT_vIXDD`{&2ZyO5EDc3P`)9kK_K@yhin z8@;9Nv%1R4@?^Mr9vYc7^@h!c3@56EI)_}MuDg5fKE?t-eM5Lq&rHl@pL6&l`*{~g z9QM)2cn{hZWCK0~h@!p$-KX!sJCiOJTbz6I9D~EN+IHq+dbH{|dM@@L(L<0m*p%FZ zF_(6Q?}>@I^kMGD21&&+JS*2&OT_z699tVgT5oY5Fk>^%=wK&5=l?mWGgmhbkjX?- z(FXC&dB_;JUzL&Jj7kJn8OvVI;hKBP0)*o=pM<(UvpL|tbcxObe+?X-~ zgi3TyeAa(C)=?(E{E4N?ud^g?chAUw{%()`qA=&|D%Eqg#(r4}2BY8m%PwOifHob} zR*KF$)20zRBoi?#=(QT)maG-?;gj_y`XUlxKtaI!Q^JUz!026y%*~w+%R*=jcmO4p zfx$bN(xDM94h$efqW}~JgbC$@;GUS6Gru8xILGTu#eiwqRw8pc=oJ(-={+MdKQ}Db zZcdt1bjd*Ax&`VTc;0qZYKZ7~=k%xhBWQ7r??hS}!`s2iO#=A1{5S7%j@A#etCFuZ&t7N)EJF++pF;qbuT}^VWdNisX{Xz_6-zhDqMpxhln>Xo*Qz$x z0z~f+7Mm~_>G=!-)6;WWcLioMKkM(*DGC4~u@FQK)IF)uXjLdkIAYU*V^IK-;RdBC zRdA6N4m?{&Tk4rJltEW_Sj#eQ;DGW_R6cUNLbf)wNF-Wiehbe`$<)|VFAvvv;jJ;5 z$*^GZfn9s#p(EB?Ra!iwWicmZ#nVz=s(nifhO$T50p~AI$_r;x8;Q$-EfuSLHg7G? z4-w-ox`v?bK-hsyb?RW`Nv9=3=m+#2N0ML|VT?NYlnMTcnCPk#F>3)7Y5F=O9&H=Y zca410$Kf-^4{`?uo@Z>`9xqGU@!dX4I(vWj`wm3XK|*|xV8*1Rh#1O%GKZ9S`So}^ zB~qfijPaAdkXQEikf+EdC(&a9#?gbbH$9eiWUl|EUx|Img4sEdXZ|+!#RtChS$q9# zAZ^p@i4&fE!IX_>$e)}-w#LiOp|EgH>gy+r!vgGSx3a`dbQm59$hGVK^}dfkDbl!w zPfPEW3g39fzX1K*)ATiK%n+H1G3bCU9G)rGvPyluYu&a9Sup%)=!!5y#(eG?}TnkP?WySDbx{;2%)MgQ$#Ip7_)Zb|#=p!08UvSTMs8`c!e2XM+Z zH5M)EobAm;a{OSsR5W}-b=TD6&|vTD@;5*JMeLjE%UeS7p<{cbsOm}8`%~*BFTMJn zJoD`L%|s!bOgM<=wJ);_cG5#7#m&vE> zXCLj&>{I&^-v?z%o1`AFbtp4zD9V+VMXYMmZpH-8V;>;ei17$w1Us4j z#Ic+RQNjdm2rI4)K}UH<^gWoI$HW5qKg0|Z0T`#5jLR5JTjM;4CB_x5%l)zCoqV7z za$hDiBR5#5m^a36#w6iPL>v9wO=5R2zNPxyWly~S#F0$IAWLrE#*ayf+CIoS&8q>( zG)Pnj>_P9dfcO|~-=B8lZmv_=>#|MT}&M#iK@mg>&1d##8V2l7_#*;S#!&n|3EXF?Gm0)^C1EHsu3 z1hd0h5i$r53^0T;Lh;Fybyx^yfGSjDjrzyAij%d;lRAtX%%(hJj{`ZveK?VQ4j4fW zqzl7Y3V2RO#8}b{r>YL{u>mm?=CzSbP0i`xM5to?c*^|J^(ix0q8u~GFfblDSYc*9 zF#CYtOc<#ST#p>DF$}w3F!(S?@)sj=n?5h)jBsYwoDB=LGw@*20ZIS^Bm=4ot>k!= zHK!cHxNnO&>`B*xa|$+_GD0C?F*;w!+%$3qbp^4C(qP^}e{0h^+tXgAZDwA}deRVf zydy>>N(N+?12Tj6N(IWGORw!U+={flX?6L=OhlEl4DSrN<8XL?rRj@{puP8mO}lWI z)awBh3h#R?2ky>!Az>WyT)%#R0!dmy2QTrF3PU3ixps5PD2m7oKs(0SkFu7jO*pKK zh_SyrYy=|43*@woNR5~jK|DV|wp_U}ZTby{1K?TnO~@d-J_tbWIES2rBVquA2V_jk zHrkkVeEJ3FLdbZ@96z1+>5r)a>cf||9>^H3_pv8!BtkMU7Fnk+62TZHQaUJM){v`? z$o6ekAE14@{!E+h?j^lLRNj5xKN&-6w+}xS`(ofN??ha>8kJM;$G&7iNZ;+tpNn71 zw3Q@6=B-n?8%FhY3$klxyv;dTNPXg%KXuwaS>o`}(SWdSo*(2w#xyt0$VWe<`q=`L zO(wKmMoq-tnF|xviLPV)#wBBL1c^MK0~zz=Xk*As{2n|v zWx!WR?EX~!6sLBl$~XKn=stTp;%i^?Y^TqU8FH-tZN?(nn*;AoxfA8a{UCQZHx*nz;=LFzt?aRD9s>xY z=0?`!F<&zx-hbjqO~hdL^38T4`b@SpeU=L^nL^|@QCAN574aVe*LHaa>Uxum*(77~ zj`dB(fGky>W;enU&?s>hdQnpn7fk6esRQd=TrbNC1l7)*P1qz}^Zw8$o}oQDX&m{oJK->FJ)9L;K3j zcW~@T^7R0o;V16*b-t#1e{lv4T`3Jl6Hf*NNc zsoJhwpEUi6d*keB-@z=F6qS$xw2f0|RKd{e(O%1RaAz<=aboa6sidwM7%6KAJ@&J2 zk;u^d8;4WOkWU8ZB@;5M1!jA=87UT)BuhnjW_o77$lgnrfmOL^X3&OiXRdI*qwfN=Z%;i!}rBg@F4JY!OsK_ENXn|$Au z5;FP4J!r7YgqMiP7i@G*?28Yae27_ju`e009>^F-n5RD;`;r1<r1~_`ka|S8F-1KOvr_dDKDRp_BN3t2W(_1&-}t`Lq?}V zZ$qwljl=tyjG>Ib^7)nPre5S46@#PrsmHRvSFVH%{rHzYo~kdd9U%jloA%kKYK+q? z9e(uUklY@PzZXOQ=RcD9oFBh5B%LFf%L0cA6QJme&hbb4Zqj~*P6 z{9q-7%z7YW)(a66Ru!kaht$sjlcH>qh)IsvQM(W)=F6|mrzB&n({X(gF*w);wExjI z=ECzPQvy!q`i5eye>=9)U)_Yje8Nny(*JO_x_4d+PV1v!6tTxElu7x`>>shLs1zV4$JkMQ?h4QxtUx$GphxuU>|jjpAi3Kd09xGi;O3>9bCIHB`h_- zz7mtpUiTFQq^NLSPM;q)$FW>QAQ061SwbbG``$e>X41Fq-(9ZHN5qVMKZ!C%0y2hk9#G|hMfB5vRT%MF~{@kvNiz4VH zWBTq+$>T>VjSz?~aJ09!iQ%Ls5?qB~H|lNILCv3V81^Jd^r=R95;#NP!X=Jfdq86BN9 z&s3oGOWo4eARO+h5=fXYIbBg!NPASK#~nRXxj3-+0kg(0UY(RHlJ+lUb-LIajyxPO)_TrAXTB8EyWC^U9Gk+v)0js+DA1N z{BC|q0Qr4G+NChy&S;y3Bt?76R_DE~wZax}5fR*Q)7UL#*1f-|i0iM2LpyUa{K ze`PX(i~-zt{SY$usFAKa*fPJ}6;c`F&k<8!H!tmN*`1v8^8tDHbQVX8ry7nOozec8 zy#8Wo^c{(85X~T}lW!9W)i|KH;H!3f@;=dn32&Ib7v4~&iFLFpx z_W4+fvSctuVSKS@|J1bqvGlPMQE6|r$GdA}B4i+ra*2?E=pkw%8*(9IDk~?|pbyI@ zpR70EF^Vs!>_Mht=wobq)0%FQF}dNz*ZdPEMCEc3-Psnh7`Zirzu|?`?TcoXZpT0-xae*1z0K1nIKG{I}n{*`Cz|b}6y7Ol2 zTRI}fJ_o6AlF12&)rg2;4VWv}?0B1&h%wJ+b=Xv7jC1NctQR7NXe;z^;}q6=jrK=m zY;?l34B8Hg*%-$I1L;NXl|>!Yr=*f_<>Na3=VB*R8Nt;{~n1RTnwlqVV=Sw!Rx zeimdU&qiANE!wVeyi*6HiCZbqhn!qO*0T1cD{tx_IRe<{UAL4n$3_CA*z(#%>GoN@ zly#8oKKxAC$SwQ?H*ZfFUm(#fjSV3!CtIh;dVFE0PLIjnjtaBp3|U~E^cvaAr5Mc?1mR%+6f;d{iHPc+FJ@2CQ(Ww?7ML<~{cHYFV8^UnLDhFGCI zSl^m;g&i1&$dJ<2J#EOFk=`j8)i#Y?ijGjL?Y6G5R9bdcn0A58OP5{5_LC$zsdDOG z6EPqi8RN!&+FvpuLqBoZDmKZOP2>&vAY;IP`kT8Z5`h`>%K>tDUsI9%oiA7t#lc(Q z%>MuVq-dIshC=zxFSo?LEd@rz?|q{yA2rE*bL}F)m#XLJGJ+#(}5}j0T77gp9vt&wcz7G6)rnt4AKJF@l+ALI5x* z-?%v?fvK?k!M{2rHP4@x$V^1$!x8!CFGl3Tz=8~^Tpf?v_JNcBfvrLLgQr6h(9t5O zH@mLg6d_j9TqU)iIbe=+@9_2S^~(2O3>h+JTa%qZk0ZalENBKy3>gLyA~AS=gdmD0 z>CY&$2UXc&wtX^KDmW9UQ^*De!+9O7s3Q!rBL^#GAsUb~EcT{1fc@v$8RQ;1YS%GY zd&J)bW$*I!Njdg_B}o8v$6yapLfM==9-kd>5LS$C6&mFHT=TfG_BMs$^hz-Y8;q z)j>1hpT00I9cs7|_0_NYa8}gU6q@#P>Dr{JzeVCT_UOoudr8PFrq%Pn+pp*=9jc(@ z6Pa7!GO;Qb%?vLYLtoe(3z;4nvqID;vuYf9F*dPaNN95SlKu)3fbeM-2A&*UvpPf! zi2uG8L=0`%>u6mLNR@(tM*nj8iIK_gotw~dnl;WIS1u0R-xndHV{-C3Dfz)YXqX!S zM0s4glGxVMfko4I?^-4qlcD%mgN!LFU62P3&1!!RB{=0*3LMGbf6o5R2HwaMT;^E8Ig&QF+{;j{+<_*uI))5Q4_h4 zF>O0$RZh6&5jp1Jh@&rSfV7m!#6V#6L(H0V>O5vV8{>81ief| z3`izplAZVKg@~bVkYxe~<;-+MYKt4?>Cb#o{`J58cRCQ-H778LaqzcxR7h)Exp}sB zEj!xoMg?`3e_YxQ<4DI}gZ_^!#7WN>j2vF+gu!$$z69F1z8cXSkV5EVv@z@w{0Yc2d@-v{ z46PU7WbeE)qwgItQ6oEdlxQ8z%ary-N1%~$hxW%l>eKCm*eC7S&bBgXZY(l>2MCRt znj$mNd2(vOENMV?81_-W6&02^;q%@-l~P_BFcZ6prlOC(acV?uIvZJKBXe}0why+K zw0%Le?AfI{n#u;UQ$VgTk(X;SuI}GmVcO!fHd#w3=~&-G8a5jt%019o9j@M(k}KD3 zinG4XN$r5k3L6bqWT>nxY3~q!ndN&rMVvut{VK(cp!~n~k$TItTL4+BzXq?fH z0u0H6f{_e_CrZwn?~TYE70M{=r_WEu2HuDXc?6~5uv7--O=`DWqfxmy7?r-ss7&iI zY($yJ%$zh7M5Mk*1$1%15Np6ATT_C;hIM3~c%)X2sR8upu^KtDzrrXa%mVnxd`e4t7W?yWHOb@t+fymxlglo3wn z<43AwXKRTWM9y5Wso3r%FkCPiG4%Qe=cT8g1;1^WBm>6-`zlQT>+YME;W1U1n4zG? z9ZuX_z<|R50E$AY`NxsbnCJylY9V9uX7AS`aZ@qw@|6 zQqHbuW3j@wPmdc%81F;hx^UI5d4=LkxiGFehYc{YUhnN>J+chNfAM!MD~idKPu`3; z?&Y>kq(WJ#|FTK7=zUsvi~b%JKW&Tl>g~%b1#*M*SPsdr>D>US;4%Y8zB@WQaOP)1 zcTWy=q}b77Q>K!F%{hkXzYwb4C?PXG#+;-?xulQwS&CfJn)wC#4~x1wlol5(5;0ER ztqA_Bh{OrY zWImh;s|m;#oF6QfOqBez+3dS9+Z7!nSJ2;?MU1Xa8RB5^j@6lfV++TgBX2k#-F|m_ zd2B1oc{8L(>@^^}l0nL5Nma>k=Ngfk6Ux9*M9HW zh@3g6H;t9mdLd!}3*+-HEI?i`7mu~c?-?3Pe*xfGRDNT{?z<`#-&xL4m> z`w;DrneiJHYfr=gD&KBof>;g_1MvIMUUA}Hx;kNG8593rd1KhTmvMyac{e+!<=jQP zpD2j8-W@fQvA73y&7Fw^VPY2N;j>`kC~}w?`Ktxw5R)n^^}hICAgt%+Snt+84{ggF z7w=y8H6X#Tscf5^G7}4#1YTKLWc+1k&X1dVBXZ>0&GiWj5NwaQCp$d?o zZupb%v*C2VdVSo;ecBY%2C2rFfXw=f7cY++k_5Y#>%R5wi186Z+?=~OW{4gZ_{a8p z>9rx#J_cDoIo9rq^*q*cg}?#x+HB?*m~g!y<6~1YIx=B=bYXpd=NpWAW^6MCb1(YA zQ16s9Y-^M1##X7`+9owk?NX~-_11O?ly1}OsT~u>C&fhk#P(_XNs^pgM?_2}kb2Gm zdz=)0sm9Wkpr$Hh#tgrXSrMA3NMyKYC;(X%akI2V9@^|DTA9-4WCGq3g!g5FkCt78C zVZTHpcjWD}{RzZCLuG*p7flD8%#4rGfDONU^k|iAkL6ZO2FFgT0w0OmV|g|rH(-rn zty2L98^^MK3j-f;`7oVAhp@$XcS^cnAUF^jTn9%wi?3l=L$I*V3o{VtZwwGP@2vnP z#Z$3#Y%4ZpRC%R4cC^S}otu}t6G<0Qv{VJ;D+lenvbQ&OOhHAllEVS&()*6YCFoSC)el(V&iy&rYMfKB8SWCx@YL|5g?o(76?#h|0#(I0U#QI3qg=65~bi~(9NOb(zdiE7Aw zvkQ4{ZrL~L;@0h8LiBDr6stHrv@d(vB3rNCh*?cO!1^cEs^g@(mUoLp3Z$oZX6lJi1u3l%{h<)*a zj&@5j(>EtnZ$?I$1y5BzGA^V-w$*=tI9>j$M)r)+u22H)|9z zISO4B+XH7MePy*K)9~E%O`?66^ff%H{Z)Tp#y3tO#&=^QXz{pNs(yiPNmg z@5btENVdE40i40e>SQo+65SVl!EJ70RXVJUh_T1UQWh^$oj_4SE z52+p6P`|MB{xL`5y&z%$Bqft^=ywn7*)O{~4$Iisn7r}kn=(1hBH;S2v8GiRj7o*d zXT}$FbiYL4dIEK~_C!n^$R5(8FRf>Ym{M&|woK!{C-xV{c={0z^`T+4nR{lm4kJcZ zZqxRUUjrF~BOYfuJ{N3z9Qx=#^m_=H!v`ycHLFOMNWU4?Yj6zq7ka~L*sMIKk>}c; znDmMNZg_Y`<>Q>T>yYZRHoFQk8QJ_nu$!@)=zI9js4q4qI^XHmdL47_ecD8H17HC^BxryW0~sVb^|eKA)cMO)_Q`kd2JV1e|LqP3BnbvFMl|aJX3NDlf_9&IzONKK$^n%L9i$V~?vy+-B!%rR(Y~9mG^% z7F}5+V?JCqDUX&+$-%-YDeE4P=#74}&0g!5q4Rw*d8JPxJ!4YRRwuVq;MF(iGu0o_ z!RG-Po!+n89V8LmJ!=D)t%ow9S>&t_ACSxod8ABSChPrtZbu_0&5#$Gp zmC^QwMpVG-z<~lp*dt}YJ5cY;7^tgTx*)JEoz!JS+NA;A4(+QjPRXQ1t zrGqhsChK+h1?9=$KA_44@6KS*r%J*NHI8Y2C~VU@=#-b*@Yf4hr}g+5*}JQJaUpEZ zF@%gN6Rw^4A!L}119`d9twHM%g*X+EQz$?VD3r+qVJ4uAj!*KA(M37ufMcHPJ7X{x zqHwi9L<{xCEOzsJ88(O#X1}5YqVRbY5M%@jAjSp;fdhS!x1^qtU&vRgoO_a93u6+c z)Quw?htlH6Fo*mSF_zHaog8SBYemG^vWS|t;*NFTH})m}4k%;VA{)vzq%*P@BDg@6 zznv{CjuUx%t~zC#1JOsK!lDjfS8aFF`qX$^La4#LM-YdR!mIS5ReL zP{$j_V^cjDQC=1>WK61idpFv^h0C#%eBjt&7W7ShE$=oy9?*6iJ1GmiWDLkBA%i3N z)@|!F^MmRtqLE`?l0Z5tzfN~jlqE0RpNumX{1Y0GL`{u}ebX-?Q(s$X$P>RH#ZL0N zAIVskWQ;?GV!z+Wn2T59PT*`HDyFJ3pkp56UT)j1F6&^<2HtPauJrG>+Jp?}F^2AG zFE?X2&rW}!jWH`1eZ#v>Kt92HaDT>9mmUl|z&OogPXXgUb}D*4X{6XsG@g?WWJAH}J{JiZIgZYbUQgL@9VSGwXnO2& zc>{I{HX!~X`a2GKwu$0k3&q{tt!Qx%?oh0_6b)9qxVyW12wvQ!xV!7g`^|UGzf6*uWHQROB!C#zhHAYe`J*CAc#ju1t<1b|Ih z`8E{6UQ<)JL$rE}j0c@dke#IWQWAu7lB-%8Lp?7O{Y$ksAzaLvA;y_;nw@ky9+6wC zX=Y=F1x`BByG$0|hlYSKu`kFU@e^`k`)huu%TF*02{htJH7P=2E#EX1Dd~CY;dm~} z?cFhd-zScJUfbba9ci6ENc)8x938E7BBNpfI(T&bmJUf#1CRjlo;<(rBRM!FY+c=; zUAd)r$ibI`hT0tZtkptYovRvt(1B1Lw!f>xm_q7^?Q2ZD_|tIUKhi9A6F0aif`2KI z@z6pDcYBtyS40p)%%|P)B1B0L8?`(PrzHlXR$ntl)}pw~n8Znn9B?|)JCP&kQa*{` zvxvkR!jJf+J+;g?s1ll}su-NU$Z;ToKHa#E*byBP0&VJ468|Tdm$c=88Zf~zG+bPe zgC>GByn}?QEMyG#SXmB>6cA1gN;82+hFzT}=A_$vc^BTZRJ}*el*TY&BATqso~$O+ zzy}9GM#(aG=6EquL~w88^_g@QD`EL;Fgt6Jq#Z+16s$yes*{ljv@3t@!r9EYLhr@R zjD~Wh7LO6;WBA^FF^5ZNB#ul^)z07ax&Elgw2)S{fFtCBwD&#gymJ>X8)nnQKx{ z7~$6+*SuE`E`7L-AiC_7_~}hl$^yTX8&b-U{^2Ix1X4bSDI*N;f7~bI-K%3t>@Ply zvh;<>t3aN}Iz;02EePR5$`c|M^&5ezPDLhkb0+uWxu=EoV(kGaN&lja?L_PL#pDqB zx+lno^FoRI2s;NIx%$m(QR&4`g1;iYOz(U4{v%3wv?7hHHyLUN zkf1?rETLa0&g7Dk)EL#y-w{gcXH8GtSn7Us0(_fAsUS|vn^(T#|N6KpY?=7(b<6#g z=~DcFmER5wwOA5ix|b@cw>`|l^s{eXmZQBFVcpwePkT8LE@gQz(Nb~(|3MLwQgkHt z6@ZXXx%XD!ivRvQ1El)iQ(?F}WQ)lTMNi=ugIMKOxm-TRxPpHd@}1&suyQju zL{8c}!QP=R`q6yn!0ch&PSx`P7IP<;s&6SDEK{9@^ffo~r7hZpDY=5KcyGQjA-fq1V^O6gQC^Iiy{l{a1D9JQ1fB({Oy74zJ0 z_36;O&_n9M!qD(D!7+~WB;NWkzZ~%^)P`Tmc-`Hk$Vo@8BQwK56Vyv9Jr8M*2Kpgz zvc)7@af-GJH}UhSh!2?-Ad(_~@3d8cc*j_bb*d>I7YZx>3n~JLf=-%Eo(hX0VVW|D z-A{*X37pk>+IKNmSRXD&;X%Av5G!g_c`ye6IvIT+l);qTzIpR31i1>d<7WQt zxXUp6{m@C?MN8wL`-F1!1qI8{lS1VZ6C$?lqcU%vkn8+Y;C_wAi!Q0MWEK+=Y_i zvqcX`Z~?!K6Na;#A;Ln1fAvm;Ml%M|Wj>>mm2)*Lst5IfkUue_nayO>(V@ViFIx5z z6X&ENrw%K(;t7iQOUhThlgeK0x)Ud6oupt<*%nspqJ{&<{lFy`0f;&Ge znm(Hf{M|^5BJ%Zk*-?xkSwZ*q_{EdGs)NQO5GJqnxC+S;yd!wNCQ;{hn< z@<3E#2bY8``Ta;#baMF>o1MV&>Vc=;3pIk^7(adYJVqTA_^R=Xcy*Z}%aPo{N_{wb z(7g|y6?$f(;?Y&*gl8)My*6)Sv%t*WworQw zL8vEugub!A=+5b8rZMNnyBt1xyB(fpPH8UNuVOs-eh6ho8hwxr*~4HK(w~4L$SUsu z-xD8j3}giKF@|+W0093w#QFXLi(G?E3QJLy_+r^C{r1g3h?G+`YQ1 z7x?fpdQcB3f7C@cpOWgQ%hmpteoL6<`}4-?jvnP zB1#J(^tSzKXy{&8sjfUa0=?RA>D}&Vs+gWyliZVp7-pRoj*5O?QRjs9bGU=>k{3Tg zkPIYp>|A_}6tI$TGb?8Fbx(9=zwJLS>=`ga5<%G%4Aq=Rjz7Mid&Ck2NOD}dHJ+9K zUPm|$<^QqclRiR;580`(F&hj_7I(zf+l!=z?_8VcDa5HI6d34S47)@al-Z5{vXF+q zjTRdO-gL?C5xASF)0{W~)+uI&m$55fc5hSBiQ@lFrizQ+U^#5~RacUHcO&oFcDn38 zN(8els$432H3WMFv3@fCh2Q9jcUdxl50A8ay$qcm$E0OK;nVC;5g#%OJatPXea-rQ@L`mXjLpIR%KS8)K^+EsvK@-&lEOj=V9Rqo z-rfpUI^K-THzTy&u+6SAKQTpwLoRBpl+e?A04GO#{MiK`h5}<_Z9;N5`TJ|ol|~1F z%!wXa+nxQhP9f5KPt*XcWUb+22?CUuC0(VvCaK=>v7w4Yy5nLC{W8X!qUb5~DY#72;$A*9esKm~!z8<5*yC(`DVzw{?1dt5)P^r@*v~R^83U zW^AP(V*{!F(AR=4SjW~4t^<3AmT7C@Fil28P(P`RA;8+EGxCq8DNDVQp~TZ^r4hk* z_PFiNI6B8CG^5D!g>3#*OFQSLl+>lgW>3nE81i^qNP1EN%q$INy3nz`z|Fv? zhb3n7td)c8>N%3JU9Bx4ard4F8IOWA3&HIBu$#~a1D4jQH?hIMg|jP9XeH~f<1=qM z23K?GE)L|3)WQdJ=8B}Ihh>Y0(Ef;o`R4W1;b9&*rp{j|tXLnZX;Xf2Nkfh{+j*x( zdL*|sul*l4!dGcA_v2yN8@Y_<=@xlDKOm_uj9R@=6adipdMmFWCH}IXZ_PLgvZcsj zgA0c?`p6w&wQ=ZaEP!O-2_s!jC&F{}F9Rya%oWJ{M z&{Z-L?qCQ4AX!MX`-V7PxyYITyC?HK+kY4S3~#N8D4$U+F0u{BCqrk3n4l^cKB76`5Q7a(``l{r;tDXZ$UA*HmkwE!yR z1y0PJsvKNQcKNA#qTH^nMu0NXit<#I3koAAv!ab1~`$9WY`LusA3juU`7uzi)r zjH%SF9<5defoAhv733TK0l+x`{z5nj&j7pqlMAT>T=<|zOq8npf@PHT3K@E24I zXJ!5_L8Z@`FmgMQ(NY4e7Ud>N!HQ&h7J^FPx^t(Uamm#i6$V7(pJYWqj{ty#vW*`h zKRBQ-(F(cm6u}tMaCL~SERd#!I%GHqLU;EDphRf@qBe&LS%nsUUlhUo_KjOu@_lx& z5BuOT=Ph^fOJ^*Q-(@?Ls5dbz>FIf~$1&CoFn;LO^Ljep6JOh=LdP28okZB;`S8 z%$oaR!Ss1-i7j`IhwsP0;z4N6y-o#1AqNWJ+{}Ll8+jpI!PxQpVHw#y9MyXqC9r(R zVBG?!S||dB>KW*_!YZCtJ`EOaWkk-Vw>v>%SOWj6lIW!;|*Q!f0|{K z<}3PVK3hwucC-mFQF3Iw4P;gY%O%8n`iYsc0?K{GPs@#MYRsaR^%|0V9j zZ`ASffc=*`R*}o1DZOx4p7`dYJ5MuXGr5PQdB{A_ob1l-IRsi}HMz>I_u4D)Xl`ug z_2!_6_1Kpfrz-)Xau*#*1}^u|S6-9#(~30jNq{puR4eN#v$_)^d=uHxMKF>>UbY`V z)*du!jLRL203{RyPrn4nI^z9sGOL>&AqaH%{Y?TS<#2ol^~{Tgbc%3FN_V@C%tr+h zh-wftiOlspnN$^7{+y1A?(p~!7SUH0er6T-4H7#~r<^e@z+^|`TX>#ZpjXeUVP(QL zFF%M0)!IZke332cu9IqZWaYGp6D!v}Kf!DcaKK_WQl)!av5F5O4=C?@1?^5xu4<@j zStRr01sDsMa`uSDUNKc_eTq2eeJ@n@%?+IV3GpnAlH2Krl~8eT@KHB#RvzH}t{;s* zwXR`1(Jbnhp)dnjRjV~LPaE$AuX#TEGldR{4lHMMZ%&HeJ#!hGdrM|Wd@ zYTlOMw7A_=;E1x%+F-qDc&WXd9}a2~j;=i#MBGSt=NL|IUaGZY>Q zea~U&DEEDjpJAMG-JP-wD&|0?2?7cQ-b66lbunMQKpC&UvBV$~>^Rf%ifW~Tapbbj z7BDj^iIVe*qASf*3J3F(#!o6s_dw_KIsctZ3V)yNpYS0_)06}PXej5M^o85D_J+2; zMRaD@=A{^QaL!*ETT%#Q=l{xSh7E(UjZD;WIWj&6$MtzgUrv9zmLGH`&E{WEVg1h* zjt~4clvldkIY=D{VEIbvr#}a7+%+9VJ`dLj_nm;qZ6WNq_nGyKmFc0PKP@=SD%nsn z@~0|FL5-0`CZv&_SnN10t2|JhaT#ZI@^RkUtGOdKl^^U0d2Q?o6aY~Um$s!A`ujcv z8JYNjI#%{a!+}qOkp%H)XKw@d^R1nMY4Yb8w-yJg65n4UAI(7CV7g@y+8pr@gzhGYGJp%N2RxB}#vueA5+8*)k2k3`D`heGFng5)IOx75!={ z6pBCDIMcV@qv8IUw)cFKc(>}$b21yX(ifzdu=xy-kDi3zER{kDEVQ5VsZSY|6wU4MFRS;YslnJ}P*^rWGlaT!U6t zhggTih$j=6tmJM8hIHzA z7H1KdzQYwIAkIjhtY%1z84hwwSOsQyD|#Q1B5140uLFU)aD`F8JX1c(Oc4(FrQ=H( z5R{Kf+3WSNMwYqwXb~i8SRD!(bWYxUuG-{a8125vx=7nG0E~lmdR{O0de}m~>nlcf zUaf?#wThTinah3qt^<~M)Np;iJsJY1Ew{PwyWO!)xc5ejUg&xNP(sJECco}`IswKd zMmm{rhHyhQ6Ch;%u;{J=m&HWe_ zs`l!iX{B_%SAIptM^2czZV9UkNB=t5MgOwl-=cHEXZZ9uh!jr~yXLzXH^UGRm1!aV$K# zl9y7GYAA65|*B=-xt^MeMUbQdYxn=!lG z$;<#tn3k-ifV>=GR@=*gJ{Qj`W@Rx&=P_e+5sZQxMS5;@#Fx;u?i;HBt`1X~8vqXLcV#_ukmv5V%#KseisEt)25*MG!b2G<(1-*bxvXmgM;B#gg!w$&qy98?^doI z2^RzhzDV!AK4B6Pj-I}jmb3h>TD1qedDrSBcjq$tO1thpCc56N@ZY?gu64Swgjkzu z=93M}c6IYcZ7cK!qELcdqE*k)ZGjYmENz%JnLU!tLS0wdbs8}rY#Q^StxGgpDro2d!BiN z!ZFF0iO9Xi`c{E>KBA6L5z+lkytn3I|PulCmu zNbeuMKLm~0Je>S@R{O;fm~*`Z&+YWD+bj1K~!m3{XQe zU#z{*(#T5l?_36J9(~s)X5WmCD$sjK>M(TPL`Tx{EUjwdZ|8Jy!;HZGm|FSEX1A** zHKph-+@h>B(~L!`bEK+97BBe{B2)bL+@)7SA>W6>(;!N-*XkD4DXGFZ$vTnV?+>|{ z?=}#jM1?x_?7&{tUERX%R8jA*@mq;9EC#!UMPpFWGf}|P`B?_`igCP4C3n~wpToSO z@lq2f1?thFGPlZfMi#V#;QNZ%7|%Ry3HF|?02Mq++%x^ee|6YbVT7%AgH3duu~JAE z+zuP=pv6$_0^#As&&bE1xPaAAmx$S$6?*xHbIM@&}} zCeQJpA04Tywx^>&2>zs_r6NntUG!cPG;5{##OPb%)YG=_JvB_27jEWK38B@>=XjV6NX)w!J=4l-9==y#>CGh1_nQ$h1?j?s^#% zG3~Sn3)8K(MKjVWW&8f1yYkLw6CV4)2#A0nQ#80z((!k?K5JcN<6j{N{LfrTmaJo> zYvbk(rpsJrkCF##(N!$gXVHd6@tXob^=o`X;de>&f&JdNhMp?*Kc4=y{}l)b|ARr} zLliv;{gWhwu=z*S=6v+ZF-1{8e(&o-N{z>t;eglSeLj3bP9Am&ZKr_MS9k*e3d9)1 z>VFk|Z542Dwcim9OwS}sybyM(fn~`g{7tOQsqYOD;B_KDT15emtXVl#qBJkE>~^Fh zEaKu#gG4h~1)MpNjRdI=)B+|kp)kmZ88|G9Z2IjZ_w=?O&1kZ`4XzFs53Bp_!KQC2UI(TOMfOAGZ?35N;bQq^QX${Wvi~Mbj)Ei1 z`2v@6Xy=*IOpX|Qq5s=8*%D@0Foc#6jC&!h4P)uw>e1y&RV?+fa&fB9Oa)@F2=rGV zmNV+zM5iG5scGpmMLhp3f%!70;V$4Ptu;a|9PcpY)WuufGeI0|dBs1&WtvoL>bm}O zSB_-N>4C3OP7?QXDMz^i^`Ls)yTw9$mzC7XboGn$PZ27Pk%W^>>b77zj|VZDl@a)H zI*z;Q)B<77?y67PHTW-dR8R?&f~%GjoAzE05ZzfQ%A$Z5MaRFXrdCUy))is@A1m=P zkvh*pupw}+JKw*5?+?6l(COWj?*Hqd{Z)c4_1CL69m#dTl@f#|w52n76@4LMMf&9b zx6xhP!~Rjgys<->$U=5;r{@n8fYj*aH>BWU*KKe-|vm6v27o@sUt2E{WZwXJ7WegvYoo+5Oe8v7($E|Dam^?P4a!&A( zoT8#m3t3kzTOXr#0aOE=9+oSvBWc1fap`cc-*W1`**XDA@_U`*xRb2aR*By@;0X%o zsVTAN(d0(!$D^&PlYpkvFPLYCUn==V(=fYh3VhZ2M(ER+FWl$Q;%aM2qw%%@#)bLg;-UUDWXfx5J z@iyzn;@H8y=N(-XaI=3)yr!nE=iq;wU6k&CyspWT$ODJT?dKD?FA!IEj>T2=qJJB5Wsfo<LuEE=R|O^0Uf+>NO$j>zo;K1zCg0x9zu$V5o{^SJ!e!^#KBBvA1!D zmq!asE0BAg%ij$8#EM1rYsaiYf*gGr?+HLjAhBTc@C)VJY{i(Bg!#aXdvslLdT5rA zKM_YU?ZbbzBpx;jbEBsb?Y#pVFaas?I1^6z07AK0&Z!AMml^K0&H@W8zVgioy)fCh z&O}1{@IU>jhq1j34cGm-MoM#?&X4|I$gbOii2q4*G{yfI(U>bl$rN=R9b9LnhABC| z@){BI9!*e~FNt0MVTVpnD*kh@`_Mg2>$YMnqR&T>?52n-p8eLm(No7nvA6fj)lxsh z;4C|t)cvJURn`r1Su}?b_W$e*gRB7GUsOy>+jgu zM=5G6YNZvCeIc?f(L7QSA`{y%XsvYD!qD2YvP@ueF)?Ng4&U)S|E#Fo1Sv~t8+WAZ zT8lWFNQ^NvUUV80zRdTGz5+=BbRMjy)>8lJ_5odCTo#h_nuNyyES|u zmMM`Wuk9OFgj=s~!`fT%FP9^~q&Y&(Wn^HlZ-=*g_+Kxr#3hq_&u3RW%pUwqK7w7c zz5m_&y$-B=Xc|CXtSrM^O^0Eg5DM}8Uj6Y#4mWPh+BqEPHgNC9ZiT z{JXA(nsGR8X{U{MDjRsFj0{RZpkU~J>YBTg+!d1^ilAIzV{);LiG|y7X#x&dl}AfQad?i$ zFbX5$SQY7Iy~D|ihN@%|SV4kZwpMo*!5vPZD0(XwGXB0}EzOzuB`euJeAfl)aPkTz*eB z_QAfjT0w{bO0dJZ7H1@AeUF2SXr7&$aXwjm=Ty`a(SmcMSoe?z2PrLrWGg%8iZM&# zCB`fMOnqsLW!vo=Jy!4X<@iID{V4qI(X2>5S1aD)C;7M(EaP{3s>iitVBh?lP!N5Blp4h})2|JUb-YfFuD#P?0WuxU&yQ)NnO z_v`_r)TneltJgn7oM0}0tW0I;Pz&(@$3kZKupf{P;~@S+1?>l=@mS=~Hj7u#v$D2! zQA!_oX4DV`xgzK?8-oC#B_Eb3dn^7-Wl~QO{rVzq?pLR)zeGujxRX?txd6O^$Vr!b zA@EBmr@V`G+?G=3zq1sH(1aR>N+rsbEHg1eKRXvHD`1R7&1Y+v#+$(5=p@MnyO&cPL=e1hW0;@i#Acb=*a9~XPk)&a5+RP(4Mbk}zo^LlqD`Qk)nlzA z$2H%9_WsE9!}px%A~m%sjW)hHdr$z13AVDmHgUF5YmQQK)fBK#j53 zcH9dY5t6@YpcZDkr_>~2F+`PHG{ouRquhxg_#Cxj`?9(V5Hk{$-dKS=6>Dc7F*+=o z>9wN?KzVpy3dbMkCTV>bt3kjUNxOIh-)8|_!F|%D&JMDJ&XsN{>bxb5r=6iFJ$0XX z4v*2mMRp#>YT$FvMVg;`KBD!bVV*q<)WS|a4YYvswXDQce>Emr+6KMFS=UFgUup)H z2d5ok;JG>AAt#R97fq^?4c3_+`8|JT3eVd=-JjE!&iAm`cM@-AW)E^oO|l4G^LTji zD%Mcbez=aS43^s1GU;(SUdQZVvVT__PmX}z(0yscU=O@A{G!cDI4c^OC|0OGTuC+6 z{{#-pOMt_!Qq{ubno?{;9>#!2rRa(u+p`c~?kO3^K*8X+$jRUur5YArJ6&$$D7sH+ zrksgPa7Dq0+#xxVI>>C}qcmN=Sg?eJ4RPD&W8<16R9J;MIYY8Z1X(l2sHvE zkSycr_b_2QmQuy#|9nw_Oo$k>+%-|A|A|x(6BKVFg29k<$|8ffVti`5C%13xUPS%G zbBtfWDh}jFpD9+S%#AzcW>I^dE9%fi>WBd2EoJ~9c_lodcJR&J?mNzPRft}=EJLEFl`*<4WH6Kr?;p)T`cme0x4S#py%N^vo(D-; zca){GhJrQNE&IHzI#uDHC+E!^^S_XQ!d{9G|HhY^`|xfzrRa7y@KFCHe8nsfi0ep( zRJhT;g6`MP_R2%>e`#0R-+}iOg0ZqDT{}iie4V_S&F+OL?mfO3)n;bLJNG7aH6yx#5L-+H#lptR zPN4_a8dHZj5`RsR>p82Ux;Cxj6JorU(NQD@7KW6*ZZhE#xj#gX;M-GRq?flUsEDfe zM?C$|lB$x^XFObmyJ?5|+>p%_P~0I!>s$ppKYy7*rf^=RmmJGxE2HTdAXnwr(l*Td zMsRdc4oo=(la$v7gxH}pYM2C%GV`UP4F9fW>T~o2km~}dh=4P;$Fvo<6RSIkep;hR znXhp5*qLf2EDW@$>{~X9f}~;JcC)#lX=ouEGDP}`M<8MApQmc%H=D9pBHBz*#jJL8j;QcqlGoUR zTME^HoMPNYHus<@`9X;{y4UVuH*L4kPC5r&A{I-=$OfzK=kS`1U-RiMUFtt+Lcd7$ zu*ZFVa~V8$bKGE#o1(B^%$$&i3)``^a|B!l>`y=3r4^&da?^@3N@asQq6cy2XfAaj z=?qvaR#ju@r+(Ii?cv|5_7nO|!oXQN7~4~+n1bs$!hD^4SLYg9{v~InT5+nhsd*}1 z0UJAyudK7(r!GbYUE=4KBqsNNNX9(zbUmV3LfE^UthB`f8XmTv`LN>1qC^Wk-3~ho z?s5;r|1>rYJ~WiNNVkEX#-Mk6&Dl3*em}m~A+FM?2+2u_ZF4ge^qCSLHE5lTWDVS< zd#@KO*WfH{>=~=;D|1yqE z?hqj+-kWR~FRflbXNdcu^Oed{!2;p>-?aIBm~U0tcfyrY4&yy^n-ZNHgki<*x&H%V!2g)NOBZHRc{la`i#L}g;_>tiA!ve)AJ7ziUB3O8j zf+%6z6rLOOpCKH;iL_e>@OL?al24K#?R^Z3Ex4(r8YG%Q^ue*bu0040?;4C76(OGNpa;0Z z4sptT&ruxbZy@$ry4F@Co)sSViAS+?GGR?ZpLe)|+3$Az)3Vkj`%g_|jOOOq_&{8Y zdiZ+}n;<5ER@VC=dKQD`PX;^`sU8=Q83CwjccYpkd?8j>R$_{>4*OcC@1YWEWfh8D zUZVB%^B0PEcZ-{yKP}qpki?8$44v0mUzyi(KF5j%FhCG_mX%6F@z>~qgJq?DuBZuF+zyI#B3$ekS#-R6) zUxj&x=yC`4-29B5_ZOJovw1mTu+-CY#<~!~^Ji4auY~e6MZO@uAG<9}DWS9^{xG~n?4FXTJOxbuynf_l$?jmw`x$EZ zccTyDqkL{t<^3z^<(O&7l;7R9*GwzO$Qwxz&^y)87WhGT4tLm~@@+UWj&)Rt%aZDc zx2jyjuUGdB?bOW(ND#RRs)zamVS;GV4a9n|bzgK{X9<&t05sM(TZ_22d*;tzchCrY z&-S0#xi!f&h=zOJ;qHlaM;2f?F}viQ52OA>FEWY8>(k({Sb)VCQzN~jsxDca|9UCO1HIg?MJ~6L&O>GUv=UjJ#c4u&bZdbbarNyO^6?^;?E6R093 z%pfrYhvhI1(_|F3vi=4^9v>L5^kd&%ciTYmF`)Iex(^97t$~1Cg zYKbTaW`@cs8_AM;iGQPsy%%MNd`MkYd{FF5t+2~X^H8esgXe@VOpt-GcHxwob!P6k zigT$}K|wX0Q4Y$FyuYJ3^ScKJf}!xALh&((MgpDX;oZdvyM5@ap2Ot+7|e77 zLQ<7ntetS5j`1VyBj4hw)eUDAxuye173MLdY*-kg6inI5k>rl2xeeO_PDkd3ed@kL z7HZkgQ|IKPn>Wdua-k*e{D|MW22#RPy^#$IkS6K~5+)`mWCg3n?^@?8W6bxre;rZz zLNaGiqm-%~4s0--&u$H)i=OmwudN7_l( z^eMRK@5$ic_FNlo!hq-oNyjrPk>du2Yx~7D@-~OXn#t}X{imefH*2jf?MW%$!GBfb zP&R~Fn{ZpOCn0Z4RPEyyK8Ov4Y1zxV+2LR>0!>In8pNc?uXi)6yPH%n+1GID*A}Ua zHft-|X#5IgbfEV+cnw`UZKvsa!!Kg|A=$jRnbIDm!ob?jFuy0PuFXxQwTF#`BDFig zX&#-xK8~X34DuEcD102@oskA_wGJG~E~Avlk+wjn-Py_MDQtVtx_|HUWps4&nz1vA zp@z4oL$oXx;HNBjx~8@dEFAkx@(en$*f5Ed^&J$@ErmEWLN$%oyDHssEo#{+Wc-7q zsGylc(rH2Fo~$p<=M#qqrMGw3&;!rBwQ~#0B;N-ThTak2(@nW66h1Q7&gr!2qVHI{ zir0q&6U{bBv!n0GQUnwQE~rhjUGRRJii z`024GkvkMuKs3RsQZRa{g}W5jL2gKM#~se;y0304Wb&fgUk0du&A8JuRtaujNNp{WW8P5&`{X+R3v20#FEM>VggcD7h1=-=xYyZ`;58 zE98?v2qf{aP=2EhAQUyYh0Q&EJmmoiKdfe4#2zix#$Uz;{@J&eBV8dJ#=>pLeGA&m z`mybu|7@_<65yA$@pCaoi$l4z5!9FExRk&e;AVq63qshWx4K+TtQF ztoVYKb{KGAe4W);YCJ65Z^AuDnTn1#H^WKhzp`wv6!bAcoPAX}73Zg)A@?KJnqa0R zB&F`-)0I{!C078%6@iTe?bMj2qSW^|yQFISZZ?2ZjvAtpgvBuTQ*dMGh0Tvt6nT*? zk)SC~kTms->qOkz9(CYMLhJ3`;QcrEep?0k-1 z-vLdyT`vgMi~=?pmRokh#+9>;){ypD6rU}cFC(jyblOd(r=_KmcL`VnH3abVy?iGN*A);xhmpVfiiHiIUP*?S+E81>@tguo zxc>Vd2J?LNhjm|}VxI-qIYIn!wa!vVWxb#22ZKNm6AWdN$|zk907b&ogU9w-oSFm@ zES=yqZ0E5Uy`A3SrlS>y`F?*4AB#irJD6LLg5S|Ie0*WmX|tf-Ol7r<=py8oo)xrB zDSF0o-Uh_(raGoxSncs0j&<@rzV=XL^2Y@am;Gj5aa0q#&cWd1Wkp%Ga;uS!`=g*| zBvvn`og~4TydGeO0@jCYL7;8DaE;!Hq}^U-x1Xm6(KJR z@Kj+AGI^Wys_7RQnxFqNPryu~6b>{8kF)@e1a_mN z=(UwE0Ht)Efs`{3AZ(H+_6C`yDoy?W?+`&m!+Opwc7A7tum3`#9O37dg-mfFRD z)=+m-EQrZk^ea>CbSD&+{|}}w2P~l}O>~pz9_p7CWCICZg`9x3tc)9{zv7x~looU- zb%=<>+}D((e02E1K_>-PZ6_L2EN1>Z_U@69Bf0z_RvUH8+Ze7aW<<`Paq?Z=#<>+S zah#Gk95dalTY`5d*-bBwd862LR`HfR?&~<^d_@~?-S}cMZs;qRgQO1@*T{SO*>F;L zIpI4573r@*{x)}d>RZXlrjh_h-bnCkW-N--MIW7%N&)`b>7NB3h+KHht1I$_9Q-^_ zWky0UMrq=#aD$)qNf?Tt|JTd#k2+rr_N8&KI;ae_Z3wjF)ATRN!FG+t%oX~~8&a7a z?1F;)7k{LX%dJIB}o0;rxim9XJSXYLlA>)qD9jncw_`6WN3M`udn^IwKA0 z*rs6KdlFor16cJ4mo&v)0xNs@VF?f(xbep}pClTdvVpuC#K~61#5_6j!xGe=Ak&hJ ztBaa6=%n)3P(Fb-AIpp3*d(N+sK2h4B)M%~U?ldIjZre-UQus*VJD=oPmGuFUMLCq zD)J#2r=zr;yk;(nII?OE&Nk9NEw%^KD*QF*H@s61BW-praB4xgyoEUUu2Shxy>n18;fm%G0ux_(q?!r`dg zGBCHmv{i1Noa`5l7w$(=3zf(?1<2idh`ElBr6XH_wj4J8q`lnlpP9J@cp8x0gD$eF z{(5xfzN9Yn30`RbNzc?L-d?m{llUav=}2KdX%unX3kl()O`M3VE@D*Uv#?{pPuyJC zqY?+Luc+4_s;Y>o^LJjUh*f*S?^YO(+h1<=nqvCk4bfMn;qzVSq-~y=LkCz6*UO2P zar@ubD{IM&a;kS%h%yQKV0}~Y4f03u4@Y^PsbMsn*qw#6TIpog{)6#?yNNbrn@iHo)&{WJ@G4VhNf9DZMsWgOq+w@GZ939uLGd5OLl zo4=_^pDMdd-h4{kXFW-9_wX2%6#Q88Eg|o@UMTJKnjA#|?K#LF<+uhhh$eqvJarC) z#?ofXD~H(^7{oIiLMJ`vGOnZX?J(3}osp9Z>rus#Rs6o}M@z4HtQmh-v@%MWbrP`? zDe13y8wjufkl0nKnFt_WrM`~2KnLG3F_Kv*_iQ~e1km9*3-^-WU;GvL_vG1J z$cvEO z;04fJEC)Eq^BX>)-=R@np1+a6ipEL(2tm&0(Wht;0T73p1}E!_M@c}+e0KnystShp z*uc!QG(2&Zm^3uNYc_>yCo|9Cd-}y!JI{{`ii z0t+uT0}m?q4m5oI7LbZA3OEgtY~*!e4V+x^w$cl8C%GW6Z5JqnEo2GM<)lkI>zR%q z*fQ+Ru{t1y645+3P=W^lXPr6^tb+9)$+yfs-$nAHD7)6WD|kFqfbk zEweNpUl_c6>7IvHDU5$Nwuwq#_yY2lpK!Wf4Z6kRHhtf5{GQ8bCdShb&(Ozjdrd!u zsTjwHJ)cb@UPo-YF=b(`sCd zeHYP({TGWvyIOK2&)E9J2Yc;KQlUKyUQ#U!qD8?2B=Py915@N^As$Wmg)yfN@!?x7#aj{uXG08yAyqXo_5_5B0hn zdC?UVFk!O)w4;|2(|486SnreJN37gp_u%}vCK(V#RlHU`VtS*}5;G!O?w?SlBJah4 z)BxHy({!&Bzc0C|iw`LwQzBNy3fmhI^*-Dh-xT{aWZBR0CvPG-8M5)mY|fhc_Mx$b ze;9ka2VZ;Laq|Z(!qk3#znvXAh-ujzjvY&8Wi348{DymOr3k&h6Zg$$=oz)w3%O$H zts~=lZ<;%F-flv#a^iYS+so>}Tso2<>t-+4mx>PGu4Q5o%MS8;@r6AK>YTK$Ke=FP z!@v`2i2h~ViLRnOr!!%a$&g$PVZrzx03Si%zH2pj#!$N2LXhM7>TEPw4hoSmiWFId zMks(qCfu0;OCe*R=TI?n*D4ufxGAdvQmOLYlmSqTKskdz@yg8%u6OhIwq_f>{8X1< zQuP2Uk82}xa)I($xhaD=rq>^*ILlbfK|GHGxcdc-pNSbINn4;@< zA_b3|V^NAjL&tyu3Ok7xdx1qYN{7|5+Q zi*W5T$=5+~H_!JW?F}d&PWQ}QjK(Iyf{Dhlz`uhefq%x%78||rNGt8z>Y^h%owR$i zi*^n)QoGASy=_)X#F8{0;LN1~lQz@`lC8)Z6z|q<8y(*1ru|!;^oaw_w6njFS{qEX zzQZP;5lo6f7s_1-$?a`+7DS}m7bsj1Zv_K!Z?{8O10mQv%=uIu7b9X|BDZlpr@7T$ z@!@K;3B~x9O)S9m%6JCqfJ-vCdD^rQu47EX(gJ?k_wCADqmHZm47du}y#v9=rB%it zFW|8_)n2E5+qxNTQ{D%K){~DVY3pEW@i?$2#bup+ul9foD!6pnx;g(hkPa=)Qh|W) zAUrYIDL=^Abq>}YZgD0i5sM{CEiDmFYl7zH(O-xjdl-r~SvLUc8@|d>cd9??p_rR8 zkR>;7L+OIP2*Sc72$fv7JcZnp!4(;Rox93iSvZ^$yX62-c>!u8fYt%F1-t5~A%ccmIjaj&l+p;Ob{e$}# zPqyeIu!uq4v7=rKJRju_GHdsaOr7WwF@2c~R)dH^3=)?$MGi}f?%U(0!3}omZsi4N z`oOO1={W>X4~h1OvAVZ||ML12_vjsHdU5V&Ksj!{awjq$b3JYO_%KX%ZzorkEorGr92KMii#L%scb#C0+5Kpu~W*0-J&-vJO3 zS4LvuJ<2V|a)7pjVEeED1@L?bp(qRNa$e74y%w0Ku>k=>Xo$xu5Fg0$rXH&xv=XTn zO4;uh*UnB23yZ>dEGqKX*3nBn>jy+W@qP2ohs1TrXTU!}T}>JPTWD(&3m6CB0?;DT ziE$F{NpPs~4YEn0^dn~52A-!%EuIjsWq4GMSJguP$XXn0$xWF`E7~8(6U55&&XbGugvD7(>dmM@Cypo-$i0rbK27aer+ zTzBzGr7gdDfMspp`ts@n`M_qXN-g5b1>#=q-dQ{?>v~Oedqlc*T}dEqdv=uHcFFEZP>*5&0LGVuSJKK#`?<`xix z6){xnn~1?CS1-#eXphiGq2FQ5ETqe-6(C<3Zpu~{SpP!Fj*aQirQv|y4!V{G;WGa2 z1?FzJ%SU^|QnSHfS=7^FeFps>#&C7WxUbldxHij0>!z%^32v=9(_GJRwOR;}d!Rc2 zwD%VSh$@>+j#JQetNStDpsdwz(7^*ZS6w${Ur1k39T;Rx4Nxf=1LzSl*iC?-yoVNJ zvB>jU6eD9WahC!nRS+9+t%B>p0%Ea`!K0WWT8mR>n`nH}Uh)WqEj%g4g@O}70{852 ziyaHiZi^sjpooBrlEG9RpH$K~Qi741Tc40U0ztmnkznG6rj+ZG8=N^x^ibSU;VdPWg-oKSRc#*}lci zhl|?yI_z?FI}t=RDbl!Qz)A28oeK~#S8w`sXDeMy?0u?q5H^CtAq5`;`ncffrh8bDNNUA8Ez6_5goQ~}X| zYdc!uA2aiyx865%+GHFU5GT204A8-Kg|x#zJIJg;WDI_jzWC+yDr0Bl^|jOZgTYaVK+T?e>3&= zy-ZfeL9VX>x^{V*rtSo3W{UGNouUS^Q=`dF4SXCt@C@zP{wNLfKR_KFyJ-LRCVF^( zkoNCzisRDtAVt#dYAPjTFfXXK3}6hbH4y`>BpEX^d5dCEScBZ=am7Ji&m8sjZ{yE) z8Xdky+xHz6*DaDUEg3Qfmhx2*9idj8%{cFehLh zLzeZ(n2>*-;t?P9tQ(-_mUeQwnrL!-SP(HFXo`_B;V6&0W2NN)K&2lC2pE-q5C!EB zR_OZ}Z$QW_7n#woGOR^123ToAriDdHSc{gAOpQGK`11RTg2T>plQmAWv#{2x-g8R< z?yvgRBe<%RDIhPS?8`YI=PbvXXVXTx*erA)_Mpv%%{+zI3$+Ad#(Tki+f zZhGg9qwoQJ0OGY3!dfI^5VI9)bIfr#AbWw#Eq-LL`R1}^iQ zJXcErNPE5z#wR0Ux!l!hr@gzHc|GP5`U}L)z=ofdBxEq28f47s0qtevPDtqEKult6 z!-g;bV;t5#ASLc*U_FaGq7PtWHgtb*QHFDBu2+XDo3)BXGKI$}Y^b-V^#K?^p!-C> z(;isEbarH7k(NuwxbW;W;o@*u7Ig+m9w4zcQdlcwjNzuN2B_3cnF1;T3uwefQ3@?I zs9-e% zS7QirkHHIoun&eA6Yt~{f<(zUHAoUl63V4P7ASw`bA2@LYZLb<#5qmdH~HuXuTRs- zYZ=!%88>Aqx_Migy5V()wlvd@?b#Y1`3x^VV}?##lXd>sL+v!bASWLPrKp=Q*9+2! zz{v^_TvYIXC{ZyOpc5mm0F}&%RFK}w%M_Y{hQ;gfWooGLm20tkaEtf~;y|Jn`2(II;FNm$Duh*~Be z7{Ie!mT8IuyNltf4CIF*L;#dCNQM`mO^Uw&lyq=MhVLryFvt%)L+idQ*G-v%B6#qg zLT<_w@C^L^)MF{}8{CxPUFyBLfP1;a`{nzUt1^@ktZ)G22PoveteBfJ00a-7>B_7f zGG+9fEF+Wy+?0W6QfUEj{+$mvKhs1{9_9S-P^ilN&X`WQ+lgLCmwQPfhU>ptuE}5( z^ZBP*d4beT5$7L>b2qPiOefy`uK28n&;05ikjvf1eJV;fZ{DPJt!EakH_-3@@}DNj z!~G4Y#7!9pZRIixKpS2OA_k~yH)R9qm@$lM#*A4m?(q1JF~1gW%D(sWIl49}`v4ZC zm*gr6wPwphdI+-Ibp58C=ltrm&r;aAEy}We>9myt%+FoChQVf{TtJS& zI>CSeAfJc{nw$VYL8# z7`(<{vjND7g$xG6)N z@%|dQDXaa;$3WRYn}R?EH(OKOpw)5mtVdoTP+qHs`x7kSi^1cK)1iGWViIm_w27S- zJGZ(8dx#wbiXg~9|J_iOmvcaA4i{Z8!^h6#U?@h>Xj~8i7>u!70y`=2-9)&aD9$p5 zune)nLIt}Qv8yIY`*t_eeFs_zab{dj*^H-WA}lC`c;RNF2M)E-laF@Nf!$5Q3J1Z! zXXm5z<2P({VQ6pG@!^?naeuj(4{V?dxAt^v`4zqvqQeeG`@?QwB`rNBMw zdh{0n-Ca?BK6U}8xQxNN!@3NNJlq4B`99fZ9gYOIt+-IAK{x|(*T%wPb5oqQZ3%Om zK};W$u##$T%`9>-IY6lop&}P}7J|j^*a8cb%+c9_csd~6GWS67h9LZ{Et%`^`LTzx zv_C<+blb-6+yV?j%9oCHXn&3pBuWxL#S3;2wO&wR(p(*!^I?ydSPg)bDtf zmWV;0L|eTz927?=6ya;)WX&P&6!3mLQ(H!G*`|mX0Dsr_l5iWN1R@K@tP|n z+9IrSO?(Sn6k)e|D8%w-Lb^i7re7ZB#8|hM06Arj*Ht(|p|vq5*8^r|BVwJ+i!ed9 z9NgE;>-ly%xVJ?p$CcFrNV-(oCAWb!0PRp)q$^{SA;?dz{*u6$09mJ8z<2<<@YxU%NPZ1gNVhHu^K)bLo1eW=!ZHQ~L`qo34EF9KciRzpQ5v%|qx4%Z z-;|ay*Ml_0WsZpl=ENYi8XH*%VObQ4K$H=P83b^~fT93jx;wVI1erANNs^t5zNI<4 z&A<;Ugd(A|DZ`I{F(7Y+?#IBWlss9;IVHcAsPtt5N+*;}xq!f@0{24^tE^yvLchuL zQjvx8MJ;3sWH%5@(ku%X+B(I3h#Aq*mS!D_0PbfXoS?laKq-gVQLQaj5f4eZ%Ts_G zLkKyAg4$ObSWu0QW%>xLzEEBue^r}oOb1S@1dz?AW)s44s;ybyRJYt#wi-lCA9=VA;m7EscVDAMr?m1o@bKpfTE+lZM`LvATIK1v#&eE>)}jXEMy-jMT3N;% z+$#HQJc0QLZ6n2PCDT9OI1v#2LyOi1>0~vzIZLbZ8$=nn0!Y)S;h>s6Mg>E zT@*_;QQRc`3eL@pQ8YA7*KddE!tLyF5GAp9$9^%Nw6_p#+c-(ihRlNb$8XNlg;6;k zfn>*6v=V^j$8^N?oRru>Hr&o_U}p1u5FoqKF0kHN|vPpE_5cQ ztTZ-WexK^^i&0N^W$&DvvhbW%M&qjzmSP#BFu!2tesANlsa`v&#F_{|z0Az6Oqn6} z;I_?6E35KRy|Og0wox7tQwaI(Xw`_AG%)^R~J zXSlURJ!3wH~KlD?L=?&_IP)^W( zJzx{RGbip4Hnr!<_SLnFSx1K+|7QA%>cAjlY5+;b{06;oe7-7VOn-a!0QIGpK+MRi z-uz&mj$QVP&j2RRatRql#sq>f7KjoAmtRh&oi203Q)$-saXCm~eN1h^EgJzpOBO0Eh-*|DjY%*rkx`*|j@xpCE z#+a2m(P^5M&Fa3aFz`+}9=un<$q9$_7G?0`dSM07490uC0_X zQwph4m0ks)EGtoz*OZXqI>?1qkq==51flf(ZkGLs`@UB3pNl&aQ3{6SyAVSH_oJ_1 z%)tG4H@-v34aF7O5kAAR2}B6e?dHBwOMrO6;tv3E1j{;1dH~XgboO-GdBW0nwNVV{ zV<5B8n&5s=`TxvCsg|}{7BPj$n2RTWM(v&JM6h*`Fmp5Gi{Br5>Z?V`n2#@p=+cN3 zP}HKR6hQcbOjl534BE=|Tbc7fh}#*)Q2Y+d!)l;bWK1#m0&)SU2jpu|Q~$u!Y>Ye_ zH;+hfN7@<=0-JX3TnQ*L29W917Z@>bYSWzy5G^2Fw9qQ`@w-+bk8z{c0O@i5l8jGM zs_!lbAWGoE5H1%%8k9o4lQDp{?iA23s!7O9PQ$Hbc{TId=S(brrN2}GVl1AEi7^{i z&>&+%5es$n+)rcU^K|y~A|@B`)xWw#43u2OV&WJm z1IuWh%OPR_tfR2T-LS5Kwrp|YG9SI%n4eLjKLbawYhkopIeA7V?Ha5>X9)GX*XpC8B_OIBx4XW z=4PN`G6pDCDIgpaKwxMU#sDVKatN7uZv2}ET-3>vWto5eg-cF@XRA!Ns{u?V^)i zyy9o!AVOPND1dO_4Dfay818u$d(ho6RPUotypi#DmjC$(W(x zgt*^kZe{tWN&K#!VYOQ6z)l}Ma%g6ei~%t5BM3h_F`fZo1xkJh2ZR0jWC{dR>>hxE z9hN~LZJaKo(w z0OJw_WK~o`FlJ#%wfp5@rO6l&c-Y}y2<4D5+LqPF?QkVX3N5Nd#-QB$(wi8xK%dA} z>I2)-3)GbWl%ewrGPphBKOu(JQUJG!ig*E;0mZg*pI8Zy9uP$3V&AUxhY}D0{L3T| zke5=#kzU=QZ&Z_zfzrH`vKki1d1;leSuzwEgSit{xSu-O&iPD<@z~Xf_-JPO@#}LG zi#GCjV&^_m{@e!lUTrN&VdasFTtcQ=kZn9A>VIk`CE9x~zVMQa8@E*89iwBClv&{C zm#Vj1;N2k9P@m{Gq93(F8Ir!BiV%J58g@_Xmqj6du@vGe7ph*aT$6uQ47^Gp z#~fK^8%4U7+4%2qWM|*cafe5@AH#;0O*eaJ8J*3UxHw#^y=DwO1f zZbsp`6hK%;nZi93$_z?DSa#qIy(~0A0Lg<+{gzSXB_XUyxQrkqsX)_0!PJ{kFs(cx zLxQN%5;D2U9JqeM1OieKZF<|FQ~VA>27%OJ%8h)1h|yE3!(svN!L<-dc5QWub`j$C zaD#tCzl2bOb_fDw=QjSG(}1$LIuzo*l1_7{o%+`2D`Tqx^u^nwvaKP%dv>@55rdsB zHm)j6SQoGQMSFrmzEWVqMxO?u0*f1^oX$nL?F?m{Ma1wkK|o}k=Z95;hyg&xJo8`^ zZCKw$=Jr1n=Wbj+Mkn6;zWA(%=fCuSBUe)!*KLe$-nc;h9Ve)#RYugt82I+d0A0Hi z7rU`?+e{&pB4aRSU=iHGV=d}WT2^VFof2c_)O3^rd~KyzX)b0_o45OnVVz6^}jQuSkz!`BDp%?xFRHB@T8~ z1e9IXCt|_{37T?X5HWQQO|z{A5d(mX!MYRidlT^_uiK(L7n`ZG!yzmlKzcyWf%joe z54pOf*(yG-B$h(P;2Nw8ecV=&=IvYEi|YdPzYAA*a`VoXmFi=CRz{IO1V_@;r-&ej+hqVsIoO0$jJbQg_ zqgXeNPZb`g6pE8Eg$oAr)#d8}p_4Jlm^FrKkTF1^iopb^cAo>wC1mD#P>gbeh7t~F zYq3!a9{?0<2)Mu6h$2|+Bu|dKfJaa;_?`rL0P+ZndURr>8y#lbAS^rF-1!ip)=3WA z7Wt4g=I7_R%)+#1dys!i3MHk7%K%(SSflHLc`XE%6hE`ku|IuQ!sGE!A`xX7XNv0^ zN`u?{%s8P4)83{Qfgn>*vSZRg3>jhe$_Lz$VM51m3fMj3@gev-KS!gGhM&US+ua%g zDm!+^QZX_XrhPk`7R`py2CyUK&O}5AD@b1+bQ)%%wptD_@Io1bK^1KoKt7>_fdC{F zOl1->u)4yITaZ@}!q9#H#@1l)lObs=r=$?#N7x= z=`j}WFa~Vmdep{`0r3DOE0m?^mybQr#%(Z_jp@uG#+70=H#9 z_X$%IHM+Ve?7x}*r7%j7F%y$fa=R^bXsL43yF73qCIejLBpT0FubAgm-i@<7=F^WJ424#Ty zZteqz_ce*Ohp`3YDu|l4R;ySL>yb?N3Q#7?BV^P#C(l)#kO8uXw~`pX6A|+X`XlB} zY{tOONQ@t_NJU=Zva%LdECviziVB1f`4_I?!-3O)Tdmqh-O|)1?185(JBLkExUqj}B>;hL|%fV8}7;Nsvb?`v4 zdxx9lPsBPw*$ipNIh*b`!U)OgUe<=BH33A#@+u@QpSH zeHUEa8K@%4QI^yIS~3P?i8CET7iDs$wY#} z(M%(Qf)|r5f~G;(0#rJnTm>*8;di$i3J)7kF7`!s8k1%{5HSFDT!75N4t;bgxPn62 zqAVn7;1KCYUZ4yQ2RG5|w3GZk1kmR?2n2GDFb$7#CmuG@{DO^w;RY5a8Ymvk96qm& zydInQ8;{3zo)MyC%0-RNK7L0##o z2J<2j=5Sc3f$InZi`~Ybxeh=i?A%&?A_fAN-EN_+ET~M)#>vZV0?I&?Gu%+&cPMPo zzOs<>bvY2b@L4#=&JvJK1AUDw++gP`+({&aum@mAKNK@)$GL4-0m2amP6z)6;sXHL zh)ExcDF}vwpy2@=#0xBuP(M&qOCPZK4P{Sa2f93u{L8)o(oz9s1k-FNoz-~=jwnl{ zJswYp-;jR12ZR994vU{$YbaQO;9VxpD*78HER&clOyYjri)%XD?SdQwiGaxj?E&Qg zMHbowo()Tfy!xsFR2-Znb|-V0qMp!3&88H$VeD)*3v*<+jY2tt$V54#+^Tt?Kj@v; z9w6})R)UBD5-CZxB)AfNp%l$}6X_#KlXF~d{Ch5N4)?@U+?F{hxK?{$EJqu%yLOV( zy^+g1%wvhP#w!GEdjz1whKW7eH2MdW+ zzTCT*M|Di_;&{rNq6GKPt-V&-w84>ee_yYi&Rq+0dy{$X;IX3Cz#M`$h9kFJVW9-F z1>`Q;%)>`oD8PLu!p*m}iN{x7ypN1WL|er8(w^QRaxVg9fVmj+1vDqwQtqrRYG?(@^Id{WtJl5Bc|0cAjlYJh5yF|wKI0}Z5FgbaZDaVTJtsTU$f zK@vw&LFll<~=dj z91e;^;A$mK7L%JI@o`Q;W*|Y?!y*QX6bLXN2O1nQ?NF>k*?`aRm#L2KE(e!=qp*g7 zYcgD;>IQ;tHHa7hf(eKpJU@|0lAW6p${4X~px{R!c_=5f?V=D$U!e~ujxZ_j+toyg zl!Y1{EI755WCXJy`fz+)klv^mt>U-f^Fn zj6qw*_`t~*!ruVbH`))};Nf~;lm%ndJMxPiIPklgj3-1Mkp8jBC_hKWQ>qmigEXS7 z@oW%vXwS%ts0&Uf>gv`A$Vs9j``EM8@De(t*4qK93ZT_#_{wKRuwXD0ZGqEmErB*vqQ%xgTvOw3?g9A^ z??Bp?L&!jGs+5fJ_~gdU6sN7F#V%slA%-c|-p~`==Cv*)7^DrdmD>Dyuc8nUvtAP` zM2t7Q?!X#R$)$j{jTk5c*`jmZp%58UOb>#-j&=c*OU5`GZQTFlv(f*2*eqP+HuU%9 zlQFiMkuipwvKpXTZpsvjRS+8RQeBq8Efh?z^q^I0A_WLC4!2sX0Zf=$1vUr`xc-6# zLN1`79^9~-7xvk1#cBbs*Gu8B6kHI424%kx`iTEZr4!0_fd?Q=HaG%2SfqG%Z)&nH z3PqIwf^M~l7yyF|2$u&Aw(#dT#rV71Z5IO7qg-)|6)=mon0{VeHO@iS@ zoFGirP{hF1*rjWJagEl669!+9Q~-o3m`Vd6LJ(U6@r0)5SZGS5sH4py78h`z1rutt zfAklvTe3+OAXUr>86!vvY#uE1>rxmr&$m`0CoVM zzw8s~fQ1tlC{U;=K*^1F;ju8s1~G-0F$y8qRzv4l!91_jy~L;9%Gi$8cL(wr>+JOlZdvG z&0?oW*g^q+<^8*s5Ck3{7K?>i+rzYdM?|ze)D_y+$EUqquW{PD(@pDpvUj7S-IeRI zteS4hrYGBJYO?z6IT!JGoEjQ~v}0#+tD{;0Lh8&+E5$-p4k)1mki2c}KHAtHNS~=b zhSTFANIa0lSZo7WSVMuM5a#&|N_mjg7?&S7*eu3L5NB?eS&%fx&-z$)lJVqL+pSu? z0R6E#F3Ys2ukp%&fwhAA?KwuDHc)LMMgsG-LBy;LESHFZyaAVWc3yiA^7;}AcB~!d z=c9D$oJVX{#9G+J>tt9ktIbSWCA(7AW5c1=?U?X*!uMeVM(!pk=%C=fNRd8RUoXXF z8OWGQ-IT#C`PgJc=9hKP0?rEmO3OeYGG=x@BzB;JGy-6K^2tX# z_?<~17(fUZ9Se)V`PxCK7~sxpdZzkHWC+Qyet|DVxPbEcVs!aNK%^gjU}3dW5IJ?b zlz{~CQV=r({UZ>N0(*0_LnzEaen1e@3jKJ?w#|~P(2_9_vOwA)fIU8=HNoW=6oKb1 z`p6%Q(*|z)fR>QKK#TqfNHWGG>aAQd1^^=uWi=)PD3dW6ppH=>5FmkWZkw%KmWVZz z3kZEkGnAJo4?%?Ty>OKVWhMFsl#!SWP%qd)jD-{k2fP#CLG){xf;>oCc6jk1rB2a$yIetJ)~1jiJs_E*S4tiiiQsv0eOcb<4k6fb|~6DDgSL3n=G; zAk#p^3=PZJ9I%u?V1LY0OC@BgNydzgtmg${?a3IFjn(Rld^s2*DUrL3%r#X0c0gdM36gq(g~=1>K=NZecB| z&V6{&BX&p)umIicwuqQm1|-lQmqW;4&eDgx#()6>rI6_>Mz1kY9#+1kU`}0B#Mg|7 zfqp=GEHH?e`oVIE7yz4vu$d9{Iym6sHK~c>@T6fgiTJX^qhYa@&|(9x!*huk=#XaT z;32|Hy}VY%dL0{luixZ#J|{yjZe}$InWd01kgpJj0_$z<`>@W%eMqbFm~k)1I$0VK zlj637wpX8P6FW{a>*Ez33}m%EWJAVE!w04)}hdo0R|a! z52D&+3>q<%W>EISO_Ls(QY%8HI1!^zqzUExg!jY!1Ud{XbAY~PGyU#wY!sh!0jq{@ zy*?|12`wS>g(o_MFrbI)BkSnmPk}y2VdYV7UDN^?ykLSSU7yGR`mngr5*7uaQ|*-wCTQCj z~w1`HFG9n^|xJsfBB`_h!^v#Xi?w~XDqmsuwPB2tDq>b z2+@{Dt%(?5t&lM(ibvB?G-@GChSgASSlg295M#v9>$_|{9ag(tt1(fA`f-; z&I%LcTC~|>5DS{&o)sfwEVgNCY4=i3n)s+DuH6cXF=6CRM3m)$-EL8ym|w2)q8k>r zXmS`s4(x6cX5+As!F{NEjI|)870Cca60B)JCTJ}R4aokuR6=IeQ76eLjWv_dyBoEr zhH?anlE_b((PAn`RjOjmV0Bsu)>=@E)`p0Ya}SiP3I-9gx~K*b17L$xES{v@+ndB1 z0iF=dEWkB3m{@j>)9G_wp_@?<7BT5HJ9IosS&ua`5VyM84)24O{{pJ@pq_4_`B4Yr&OA#_f$(Ye~bn#|sG6sSD zZMKX85<&T0uJU&|=#eou$KIg_4mXK&00f<(k)YTKtgHw?!k`X7&M1K>7dT(4eyRts z$tj@}Lmp7R7`Vzp&gdb(mOrFGkpyxIf);j6W8y}fB~0`nF7&L1wr!RIl$MNv@)rT* z;pPigK1l!6Oq_1q@`-#wsi*o3%C(wg41jWjqEWd#(*nO#g<4n)v-MzjaB}nuviB6p)Ip4Kl{w=qGp6 zf^anes2wRlA|2cv&?97^R38~DT$alrW6-v5kA_7X!+Yna`&NvMiN+Vm)jCCez50Y{ zErGJSaieR+$e4I)k{a9#Rd@RZOFmfk%`e2oZp!CA*}-*+Hj`o*0h=FE^x;XKGr0{N z+~cM$9;-wATZ6+S#=m2yy#%+J7%$N#L1JT}3(L(~5Jz_d)-)jl)KO9jV@)LT-as|0 zqEbPkDDo3#w3_l!)v8!iSeaI`Iz)_;6OEp*(x?^@13;Dosj_*Ki`U~0nw$&?%b1?- zMzMkB#!z5!<7Ocu27ot^W^B;e)68-Uud@>-GV{W}!I7jZ*ZdS@8Ad2qb(+g^2$^DJ z4D?CG`TgZ?=* zQh4!Jh>TIzF2#U_5(r5JQ+$w2soJ{$SZy*!EG#G1-8E#)EYE!y!ymb?g}i~JSX*1U zNYO4nIN{;^Cg|D6+sVhj0gyG|_xI#^pNJo`c_1?fuT>((7l7+VD>XWbZ)RBv0-+SO zv<*-^JS@IfLdakYUmh8=oO=xzxc5-MJ;vzE_X@BkS{))r4@SGIC6-IXsJ5cwo~gZrArx_@dqL^c~dhBVTd^Il4^ z90TQTAqYaIw{k+J5E-KYQl_)rF7j6h*tnM9Gy~Wmq{{YQgh9llQHdf#2SV3W2I;WY zP_AXmO2Z&y?m<+8j8U;6c5Qcyg}uX$&P&3b(dal&KwN8G1(X!aC1kptCVJ+vPT~G2 zA1M)3{6`-wh;NmWF);UBKkzAvhDRt8xGv6p`I#>MSHBtNk}(SV`W^Hu&-bRkWusg& z27q$PZnq1CoWoImK7c}GOang#N^|6?$!%K{9%_m@>BTY`l_dtsBn)_3s}Cr1aZV3~ z$QS_6!gFA4gU@hX2EhsbZj}-W-)lw2taX$kVzibog#goSNyMbY^@ZwjsVKL|F?oXE zt0h3jyzp2vZ5wpbAOCG93##=gq-)8Tum0Y@qdw=W)YfoIe3wYkfBokvnh9m69}BWU zjR3P$G6p~!(j)nmfK(4;Os=9Dai(w%$e@0zgX-nU zfPuRm_1#;HzI?X>3i^%f>w$>L07`J9?Nt||p1D32>$w6V2E>LomK-)E!7Um7iopBn zdPQtmShPS!gpLZECQA`90Al3s-q9r569AXocAHtq!6#08gxjHFyWD|1LI&+kkC4$k zMoY#lcw%(=oJYuLc20Yf+ah+@<9S^jj>WVY(8oPT#8g4Q)5>jZLzj)Z+i>K!FRYQ^ z`a8g~`<>}1jZVWY;M!Fz8Dz}TV3092KsCr1?C{^c!!6>DcziJt;0Qi7q2#%KD?kB| z8aghV6qZBCfQt4vLF$x{R0CXZg@Vdo6<7YZtz&LB{Bze|>{kuveO20E_dRBO%d7 zuwevNdx!TniQlk@JAJ_~$_0Q0(!O18@fo-^8m3Du@WM?6tQb|fuSKBkBOVjnv$eNW zcL9oLgH(yLJki#i{p@lGnKgyFPx9JqpLZRWQw=p0CiD|#w3@=GC)ut(Q2o}j+C&Vj zF0eTcYhwddf@mh$ZKWb2W+uvVa6+uzK)_(lH#Z*@Yhgvmpx&`r2J#)8iMXBRS;Q!4 zuYR&mBJun z)-b9;#(;F$xy>aeLB9_ZO^RAu8);%HOt(ivV!@3-{Kc?TLZ&bo1EjLZm~0ejO8gTP z0$nWF;V%YuD5RiWkOBPr7k2##|bDi+X!9!S6@L!on;z!2>LU z^()igy9zngR_=fTfe#8h1aU3|Jwis2F=#_~#$@1oEg)b`aG%328;~g`{tt@;T#ubN zAY=?OCL84vF}ddpK}+0J8}(G=1{sr$a>*E*Ia7;>9|9mo+0d}OCzj-1yGmq?Hf?*h zyBEiV3)lSVvod`^Ib@7_9^5%>8IZy`V&lxGcMr+Dt{xeq&F`+Qu0=BDVg>nC02u&M z4gDYEHug54{9qjesGW#d{5$L>As1l`#`PFeHf@xaIUr*URF1ojkOAsG*=w|1?=~!@ z8Ztv)4WXYfqt)bNMXF;>qB^am9*7vNt26_(0p|Y<5rYjjat*6T#6YHp3scBu@WkSB zT7?{eb@k<|K0&}BK8hZeO2oYT!K`q#4VeV;V5Jr*l@c=0m4S2tkT=!-=2=ERd%-J+ zAjr0@tq$sJH>_iFv8IWb6`oWc*zKahb>$I@r7$%guR~Ji-kPNiGG+~<8f1*i1@~W4 z>7kuGKu$pD!Gwuj=%ug}LT2e?3{a#w75E8c%-)@H2W>8p*ONE%g-4Jv`*-1<{D;o_ z2PkIRpZ-=EU?Eekb&MVvbMfX|6i>kAmMmZRK?SrsQ>p>92ar2i3KpI6g-aNaK?u-a zQ{+6plD8o*TK7dz0QarWDEx8>nMERm0pU`RU7F^M*h=Uh`?!5z2QlImKuEZJ%`Zq! zD5l{17FaeJ1Jt-^YmIs&Vo(p#jX^%J>%3lIkTKaPmyGFhB+Iex-yh~SeKSoI-M$m1lec9XEQgHQ)SRS4d);Cj zK`bQz&%h!VWqD>KxoTt#^1EG=->v)?gf;rGBF2!`)0|%nbEU`_$SR{eo?!8YBM?jq z>qIP?k$)uvVc|aSiHpAg>jITl!z#;e_1$WW zHhs52S*Di4N)R!49@cN=!Dx$>K-DuWkd!Q?C1|vO918C%aAUW5las;`6Az1sEysgn zDoO8sG$+WETr7o%foyV%+VZ`s|;G}n0P$SlXGFhs}LCzjzq<-k46V3EEYr>up79%x-S=~Q(Zwur;H)^ z)SQgTfqYx(cLsuS3Wic#?nyCGD?otk@5=~)T0#c-Mo{rWgv_0ZFgh+25jhxMA?sHOiXYu^L$@xW^OOY`E7P+u`4d^IZAOpdj zSy+cq#n`K2))-hG^az=ihaAfd7%)&8_1#;HzI?A>rHB|kVxW8&?XeWHi5Qf(emzMt zCeG_Sr`Rk6-4GOyZkLS@E4}&ttcabcNDp8+L=66x18n?);$F2GJ(NqxOwUBg!t&*w zoy{!6nuJ9R^gK?dS*(9AUG)p=AB)9IgK6t^0~HW4T3MghD&J-}0JB-C*xv1MOLYOR`D;D;W?nh%HlHtg*sgVHjl08b&2#jLU8!hh_)(<^iV& za;9+kR*>eoF+d6VAwLgfL2q|MR`+Rgn8;RS!t(Ke+UU$DWZ=rl=g(J|lpu_eN3fzMH`Wkgr|4%%3Pj6pd9dTz-SAyW<+6AHz)8M<4#C8Y6S1D` z;ghc|La-R+n>6 zjfDe}*>u6O5&sdhDvAek4fbx=%QMO@E;xxQadT_)Lx-qWw`yN`SsVB1q$M7P}nSS?=eW3d7hC&3#coORDduJ+5F#JJ7Q!F4U`0hql(ZPd+Be4#l5& zBVL)raM}X?A}&-5Fgp_b^j&3Z(#!XQ=cc2 zyhiEGR4e^2RpI~=nZbOlvb~MBl6WbYag(FV;8q z$Az@rv`GKgY68?kRv%|Qi`v=7BjBZew`u0J3eEzAjShwdh#QnMcN-X};DN4XID%0# zp)ZMf$R(@`7vU?=fOpcqcZv1$N!21jC*e5QH7M%Qw|qN_aJZ#nedxBXY_FEtkBm}% zjL^t{*RAf}@(2M&k63`uDV%T<{Foo60N*u1Z+cUnRu}YBbtF1orY}-SnlVKdB^Un` z$EG2rxtI!6XU9cYfJ~hKEqxFsY4pQFZTlfM3|FmMi{lbQnQ2v2pLhM~v!N7VzARN2 z6p=M=rSE+y7SyIrX?n;O&aT{Enp%Sz!%@#ppJg}DI0YUPGt2cc;xm|Q>J4;00Vf6< zqIa>Jz%_n$y`v${L->F=>2cS@5D}`T`VI-ahn97QgYLp+S`Ghlx$zSj*d7oE%3*fF zfAe-_GFJ@mczJYv)boWX4At@26|PUf9U6T_iXN=B5{3&l475o$4MSmDj8AS--LJiN zYH?m;IHI7HtB2`E#3RQye-Q$iYH@D$M%HZZV)ga+AyF1Hho{Hp&vn5Tum(})e`Z=| zes6BhQUIuob|gJOd5@U1i3~cdrMItIH5VL#!YIZjyP1G>P_KGQ`TI|Cq21cKKTm5m z!@|HVT0=xJ1omk@NeopX*O^&+UeLryYv-rp+K(IKwEBHaycPhX-6FsE@=U$Rys`to2{CMR^NseqUmyDY zi__@g^qhd!j4kUWW_9|_9QbdN@qTc`QuqGk@chwu(_RMncs!nu#++B1l$ZBQry-H_ z@3Eu@3bCVvCVVcOf3KMaoL|&LuV>dlILZDsuEHQj?>WGAR~04bGR@!$Nx>IRqzPwh-E`$6lXF%;)34cS0Z)P+H=rrDO8vWtKb7VB6UATN zDY&qj%nAq!H?{t=X|Nqa4H~WCRW4i$B`RhDcw>w_U32schBrR>Ymt|1@84Sh`Y89f z-AP*Uftaf=?$~{uaS&VxnVm^rNQ)muxC%hg7E>7F{?lqT`$J~76CY_Pel`2W#l;1v zxG!fw1)YtVax!LVxc*(%b9L-gghS?l?{E{abNzWtiKiadI%1CAi6>|%;$%dsqf-?s z8K%D)1o_mp!;>hhw(zI;Cw!PK*p%gDk+;y+8PGF^d`+9D=B~x+l{8SS zOw7gS2sQM3?Nsp}9hfiGvNl^0ER`OBrr#$_zA`npHpVUe8usSfDLUw3ZSi{HS!=oP zOd#j7tnwFaf9^RinzV%TTwA{$`5ni}?*E82JpWB}DI?_%q^l>xg`0;*nNaz)DBN@) z9xgIZo5f~O1Fk;Mt)iTAZeQD)iZljP)jZTCPt)oEG5m3y{V4VFZ#U;JcC+WpZC5wJ zbYitgU5zYO@Kynkh&gqPJ+kEeu2iYd%3qI|=vtZ0d3$uVja>H`ljUbxZF# z`8$JKx7blvPY<|AmDTpqh*rNAE67is1DO^wwI?MSbLkMSkW=;0K9y75=eHGr(6#Wtxz3Xe?kH4!l63oJ6sqH`eG>h#a;-U}K9T zq?q35Y7jDilxIT!DWgSQ{ML>X7^%|>OflV2SM~%!BG<#pM@Ctdn^4kf(U(D-D?%OF zyerMrNPf==g~~R;q*qOJsZ`B(y5vF4w=A-RH0JnKv$<%kS@#)K%DJ4Go20tUxk5C= zmdgr-b6%dDaEmM~vPyYtiTSr{)Lv)Ra??z2Tcl=vQmG*+OUNpG_5=iFrqer)+ClzX z3X9J>+fUj0h+?&5UHkNI?#5q0@MLwA$?qioKy;ciG{0`j<&s$FVGNlcFd$k8@lqBv z2an}gKXuyy%Ks+JY51!h%^sYt+RFD_D~v10I}hmV*eaNysD2nXm~_QUsW; zO^4_{sbbF4nnH!Zh}GZ`mNYpY_mwql3X$nZ#yDHMzrkILC^WvIUo}<;$G^71mr)=%XBly^bf3M)=sJow>W) zCG3J?tNVFj1R;C4&!qBNj)5SLi;-XXZ}YJo#ZTCrx5!zOid-%a+o|8zGV?KxZ)P)P zlRa|2zVojy{wLgZQCz;|El*9vJ-hQMtgVv$S0N7R$B%R+<)2$sCn52twtEj5(Uri2bo?bG5Ge_ zr35US05kRIe~jy^+GB0N2kM0I>5K968CHs>JwUOA^ho9lP{8A$i)4^vdOdf$kpy++ zabf0Mi3%LQv+urv31(FM5WT)AANVXJY+UoWSr@W(_>H)X%lHh17MCe==ZbKVEiFty z_f+VBzW=-#iN15C=Yz>NP%tGj7B=?RFLaXN8#}P?ZpO^3e6Gn_wTKsRTX>Jck{@oj60NFKQ`kG*jeT0M8y;f>nELi001)L2kz&a_mTF*0 zM4t=9UsYe7Fqc+K%FVh6*!b&(!M2eti8N&h=kpUxt?4Tdzq_OGygEtJY?p@->ejW3 zW7!RQQ9^lx$t;H*m1vTDgV)uwHKh*t^58SGMleEhu4?@~Sc4-O-x?IdBa~MXuBlQF z3s1X)1o6bD(dXb{+WL(PthW5M<4J$JO=|AbG;3li8==PVvhD}A4Z!jblN0VnwIE*D zw!t~-YPfnt>oq(G?PT>5IiBc4nznUOvqLF%q+nLxO16^JX77$RD!92~bB~(#kjLmf5t6c87K|SEzx)^8Q z`}pqKiDCoCv)_H^Blfj=@=6}l(un6cqtsV~odg-7n&sIMoQmHX3`JH}2Mt5}HkB{Q znZEysy{>=q9&8mb*ZCe(Vf@tpkh0;-DS%^0=5UNd$R^nIGmVL8M%2d-O)76ss0Z}& zI_4R2Z*WfWd}^ilD%=&UfJrgR+*(AY-;P-z^Xf8RegFLLc^~l0ENxzUb^tZ-~w>70^8b?*w27Xs_f7+sn@4_Br)bjqFfR`6ruz~>za*o~ObvGpY^2iWAqd0{Blq^{9+P1xTAS zbu$x13qipbaad8R-n9&)U_@9%eI}+|juAXmhi9o*s>tjKlfshnN@o}?^$)7;z)U^4 z)-v3z?XDU#$<}B6c1Hho*JTK4#Ken-UXI%D?)Sa;M9EotB`kInwj`xC3K}u|?P3F* ze%=@2z(0cF#dGT+$FYWXset9ZDU;A3ah?fVg%SVP2s^UqZ}uHrHV!7lsUJ9fY7wSD z^n=nUkuXh>&nOYqQ$OG&#~}c%hPYI>Pb!Br40{=+C32>KXLJX+>D|=Q&xiZl7$BfG z+9iFz)So+xD*TC@ZgB}Mr{!DMKVI#GezY7e?`qJ{&DMg#c_o>wm13Agnzj--r)9(0 zG828_HEF7_yDw|AUKG=xUi{xkZ~lcjgiS)I6#zSq8Sj$oHLBty0^`;W7+jz^4o2j2 zCqpyFeUQuyz!H5{eSVoY^31G=9BG3KzS6^l^cj~;oAUQ5vtI0ZKWKjNg6?()2!q+H z>U`g{51(}P@LbK`X3jw(_u9BLEwb(wPLlyA&TL5M{^q-nOd0O&`@KiIf8@}T(53_0 z)hR~$=Z`fLmB5pY+UhsMGPhxAyIXs9nWX}rhKANj>--n@imuP*g+B#741I3?ihHsd z{6l^3uA2F6LF|Cxe*=z$EUgx&X;vy!d2a9w<*zPrIBtZ@<9O0#{U%* z<6JjkZKrNu7at>z^wh@7{V7%%+ltu#lpm}p%@!b1oOCY7%Rdo_lT?gbEP(I$!-f94q6m!V7@5h+%*I44aF zmM;Ah;(T@CMre2JF!x!WEjY3SUN!jxU7ZYLL!S7>a_h8M){|l-UnLU9p8tTSMjtBu z7KRN3i@$4@5^p61cnBjO7KT6Dy!>$JA zx(XMOh)6Yg8^)%b15HTE`_tc<%ygzOLU7{9Fw|y?ZoJ)g`i#G}P-3zs!a6+WRW63Z z8W3%F|am;3^i#rS#*ARaANEg7<1W@jNi|@@GDH5f>etBDy9zw6>z=&XmC=3{X zL3G1qVrj4;=#U-+!+J2$AU2T>C+pK73i|y*c{q8sXSO?wJ@mO9fBh&nAoTc0YwR?<;br_2Yd66>e$Hq}QG@b+F~jK>6HK zy|NIcLj?mED5}lGp^bb*0~QKmI`e(1lyzI{j)y>YLn zazBBUPda<1oLdxaS!A~^akG4!!nu1OL4RcCgs^`>8skkl(fI;$`!aftMb0_B7cg?h zUz25#S5E(U0YBvA$#zGP|4?saezw#Y5xtg>aLQac{It^4?Dtrb-sa*mJTmADrc~%= zUss-<<0i;j-81~n@^csFkc@mAd^A$oEA{EEzQtpAu&PbT-=s+!==b=7I<5sd49cnK zyq1?H@H%p0Jm$JvYfH$*iXQEtAGxo6xVEChc82J7lsCTWel%~Xm&`EN&^_26Nesqw zPg+oJrZHE8EOffEcG*ZSz5P4=itB&=Z3mC@s~<11WF*^yAA2b;jWp<-Bx~!VyZ*rU zU<>pzU4a!_>vR0NCb!ApDZF?p^AEktmHS__)oG+nEP3SPgxnObbISPtI>CKI#d<%k zlyWaRWm1lw$Qx&SP&1wPw07uFaJkH0M0l&dYkCchqwsGMektdUG=8lQ78@ut!KX1> z_7p!nA629!+GLrAufKG-Fk#Lv!8lRuF zA{Ul@DC9nqBr?zRd_w?B@(*hxGmkj>laEP_&x2Jfl>&IkK9$N0Xwuu>QBY~Xz{K<9 zj^v;}cSa^YG-U*!bhjZov$52!`5e_^Mq)Uq5QrE-9fIC6`i;X09ebs5?qD;mM<#wQgcoRY zk3`_R)qi$t#0CF~6w}pEpfRgEZO1<20n;Y|$BD9^?j~GCL8S~-BtJfPfB4r*1AsJa zNztq0)=E`~M2omgDJkFnVTujZxmVzsk7WSCNj~*}9xWEI{99%e*xx7*MpF{*j{up5 zgo>A@w2R=voM|cEigbdF<7qIWld~h^RS6Kcr%P=L+(ytj_?2!R1)cTP`bL;VV`+m` zeL9o~+UP{4sX-JAUQ@&efON>CzD;1!% zBjh3lVL`7wc%k00MW)5^k<%hZ-Q%;3ne!2e+_0CRnPRI{`A!kE0O+gty9>eWiidtZ zxmc~>8S_Z-zd_^d`3LnzL$9to&=fb@(awLp(Q&TV4Q0$RoCQbu*g@zVY-YHa_GObI z-n?)%bMT{Nf7%k+^$02=TB{SyZ461Ocs%a3Ehi)%jLVyt$i24=5qQo^ZWRi`U4p$M zfJ4&qk=?Ci-%bls-^-M@m}hk7y)fP+6J47YzTx@s(=Bq!1m;Ta@#&G7-Ml|tj77?H zb2jD(aQ~h|aLob~f3>-iGQ2Uf-|J~?iw(-32C_Ulmi`}6^KPaLm%WtOuS~yNxOhHS$y%@uZfk<4dsmey|V#Al* zkjseWC8;Rh3y#-_t*18QNVZ&$N@k$alrPvPq-39(OV_uMczEe&5bWQ#H5c7Ioi!v; zYCZo>BXarMxpbM82n=tL|%&iNqhk2^dr5QJPv0w$6$8Gn2L)qaO3_% z`ZD(?US+^4ht3R=>~nJ#-TweMLOnz{c)8fVmSzqmhfsLQV&hSnb-cZtN4PYbM;;to zZSzk7i1gQw+%49AZsI=`$Z^+{BHUp{@J445m$T$Ev9C~EL^WN z(!;S5j}K~mF6;EGsnkYTt4ZzJ;|L?m=aZC`PUjWmmt|D9lv!0_H~YCMt@E$K{j;Ai zMMO;AO>Q*M$qBC!6H8L}R6A{pin?;bbN)Yp`l4hr`{*CT zmRu+)gu6vs4&rhv%VosI=W0ZfiuGz)!j+k!M5kQ%7m)}m`en7B(24NrwzxN;35rac z#LYpG0bjF;aN^n*G`qaWDfDWN;sQL;AEy#(LrXCIZcDC^f9WrpE3t6_>G1Z6Yq!^E z8S^ql1buDrU8NJXDmSWH-k#rAsv|%oVAH`lcxI^qBG9u9R2=l2gKs~L>_?Peho{X6 zfMO%TJWx@5OKf5e>aWp(dIsE6cJG;uruMk^$yt3m8HA_Ba8d=cd+z>D1W3zEZpH6# z?@=&`j0u$(egQ2FS_HaMInKM;@09TA!&q0USgg5t(}=G_^^xBf7cj=*f2SLD?yHqY zxE%y(w$LfbgB+RRnzW5K8smcDWxmhiE-Y4aN=W!sI>AUYa`5qzi z8r|8iquAV4aqwcjQ*6Qg?-~tmR(4O$x?MhzkT#{~Xd~3^gXSyLL>Q5RO-~IJ`e2F& zkg&K3spYR?NxO{B4d;G_PtR#{L;Xcm-FFc$DuY71kNds2ru*OGvo;cfc%YsA1iOz| z5#0L}B{wuR!#xpJ_A5ErMt%G#X|eF)w5i#A0~W1*I?$a@w3azAuLN-^`UE-+D{d5p zdc16*lMoL4y!f98?iKs8#Ti+jy`{qbyJX9=c+QZZG&XE}2?+^qVb;b*QI9u2k_^61 zZDk^)RPMfZ*hhcpK3YWBla4^8@G+v*S5s{t#2Bp_2@wt#!xfK{-)la(F{E9T$t2qk z38O2=w=*XvW%m(naNh0?MF<oW@=C2CNG2Oi^E@ghBAX`o7%jtOX34JjIW{$pXRAlV4tW|@#ZUfqL z3bKpJ@|TJzBGLVOrdCY++09IH_U^y-_ANy4x18|G zjV7Iq&e~JWED>G!z)85E=i7>I5Dg;e{1zs~!jj+$cCsHc5$C~6h;TP10$D|&VCK^V zr`I6O$l^Agvb)~{6}>W_Ew1(Psma6iSUcjYkA|3kwACmqlaLM#x#3w-P_n_e_VG8=WDzZ4I16r5ui4{TSSuaMT`KvU$O(I3h5m zx#G}Q?OJ2PGDG160gjI245Jsg2OZta5#en3AJ2Y{4z)3dfSq~OpIkgMT2h_H4YYjM z?iHWMw1bk6(4d*dS9KOtAzojgj_n0ow(p5Pj|+pC z2q)EdFlrVIvm`TLls2eyU=8{G?Se@EuvU|_+#b#Dl-c3^vWg%7`}jM^`;DuDNqcOY zB5^1M>e=v*AAzQsGXAM|^wv*%&aAvj+(Ondob@mR;(h$z(GyTMH_YKLjL?c3EYRaG zQZnxQ!;;k#P)xXSExI#v-JB&S8G58ToUD1nU~5>Pm7Mr>P(VkxDY-0q)k6SOW!TyQa{}z0=^P*T{#vOK1GQ$EXc)t-Ij#KPA7K)Y@a)<+R)! z>!p9B;;cPjOCap;J}qn_(?>78vcY2PwO7X4%~HQfOv0`kY`L;PYe1nAGsp!QuUKxy znbsZX^B`+;lwYVf97`5`?(_>jL-&oCh#qbDJfxlyHwpF-a9g4u^i8VKkydyc)u!WzcLtvaEZv=6wh{hYGTmqcO7@8(jYBO*Wfh2#1;Ux~-3V zCq1prB&7I^^ zi)JS80}(E}^?0Kn3=_0cUIDvJOtY}05>Xjfs5af&SNjlC06@-s)$mb1Ku?Y zkU1KUq1c2|^)p;jZ@YDKlMlX%HpZ{^+~T^_x(g(+82M5m(ouWF8Z{9dxCo-tfpGKr zFrxaDnJ#emIGK~iQATJ9PYj#wkAVRYoC1=$U)kXKH(T8=MM&;R1hhFSo-Y|oH@vw? znTPpN{}i(r5f92X*A@S|u-oQqx*vL?f}U}PHXyeFoMVm}4bo}=5)c2P!pv;H&SsCJ zQ3g(ksB!SY5)=*d+eLUOO#+VKOpoP5tY5iyRs3A2Gn;0+bI7U8GDl)K-z4@~POXLr zVP2;34U~9Q^g<$1GdGgnb@`8GyTtN!V}_>(Ar01} zO@VW_vp9;Zh50KH3zK~RWxxJG79}SydbSF`tDeNo0Yqh{R- zI|6(KpHm#2Gqd+5<_(`gH)pP!RWT6Dxq{)O^m1%7g z%RH?QE+i=qiUfthmKLgCJg~M|RcXBaz~(1QX<-X0_)rUhbe%5BQyD~T8L`p^#8!{# z2vEO2uOz3Qt&$BTpfhiZ!ntq*z8e=9SE7C$+ZR!yuWCeHo!PLqx)y8l8N* z1F(`NuiFoHw%#Fz-utUG#Bn>)4g@RJHgK%OaL!x)uas{;Rt;9*sq?Tg5g3n}rL-zH z3iSxz8f%7=yI)^!uFyKOMA9&JzIjhF-wgVT*2w<9kN)}F8RhhV9adbsn(hT7OJqh- zb+uEAZA8;v;xZZgj}Fxyyafl{?;q~);qadp?IAovk)-!RT+D+ajML|$>DX+8&H=~kFE9a+UH3i}&x4MF zq`xcY!#)R0XY+zE?RV*|RykpEOZK9-l9!zK+i?WC7ei}@(W1ZoPbW8G!v0jT$pJOy z`_}gBk_^hDV6RO_^`>L>`%SZmP_DpxmS_?EHJ)$V1k>Zx59MSdCQYq~(nPaWJ znYnqMv;J#OXz$5`C2Mnnlh|$_9TXfq zX6!%Eue!^aS!F@%tz?{NA>PDBg5Ul47nYxC$9E{awymRUuduZpT^=+dRDW4XG{Rt7 z<6jDoh@(Ne8X*}8f}0m_?tbcgWjAACS4cT285Afnnq?p9F1a=o7)P2~IWAQ32YVZ6 zB5(Kz;oDtWmB6UV1+LD*VobDwr`>U8=xX{7y3> zGGMBC0^trFvqD2q*i{lUQL6&UqnZNy*46J5Dvfw|8ok*jy|u{)+4faT>^w=VM*7^F zg<)xN#|__BxVmOxy7f4$`=bGG(;jwbwsd_uQo*v-vwLBIP8HTZYgcMHgNrqt(lxBq zyOHP=yee7sodE->AxB(EzeLCop6tc|ekWeW`pK zjjjzPqDqiN{|!&>eYel;wd-GrN*vf`fBH!AGQ2oIFifGM0(q)Guv7=LW|5Ue9+e-RPtLDTs2%|f3Z#5<#o4=aBsPN&NtuY_z%Qo;d5 zOP%a`)OGq)g>xw`Zfa-X7qu3*UV76yn5R4GZ@g1O+|(kySF=I;o1R^p^zhV^TDh3f z+JxI9WFka=>%yZI5LvD`DMg+AnI9yS(l_|UI=HLJp069fNRgF9(Jb89z$)NFwdir%6}s{wTxH%{O!p8h{#ZILSF@%iZgGTz~Kx5Ijs=GHX5dczVUJrA1=kF3gV z4T;gre04CZY_^t@2Y8;qe<@8IBL~(8ijgZW{p~>o8lkoQ2 z^$UwDRx~_QYOPx^)zZ=Cart9Ng8$+=oTp3npfbDgiiE*Gcm#&$o%VW2q7GI+94ATp zX;EpM6Y9MgKI#DD*zQbxsG3VUA-ta``HAcdf&2Fc*JSHSiFWbf@~GOR7gw{nk-!i5 z&zwi+bu;@Sy^A;eR)JhnYxp@6+R3)l$y9C=Kl_Fz&%0Y4U6Z%x?3AW{n1{OYGFZvD zg!5ci-^G5@IdA49!wo`Trgw`HqZaKMJkXY99CV~W?YAIbANzuCwY<^R0dIlS-H02C z#VANcG_v{lp}5o5NPaq`McQBe&hq=?=!O{fQ1)w$N|?=qK@*nzRsquOzSoYcshYZ` zs=r9lP`LB=N3$dfM4uQKZJ+l>TrMa$i%6c17uVIHeUj1Kd$5NPRfB{9{p{7xUL;M5 z{}Y1(oMG?tge*M+N?~a7s99}~aX38)2l$>@_q()9#wFNr;H<)k+FZUC-bbB?7YBuk zd1h10n|v%PUc(rrMe}uB9^OqhI=h9jgL#9KIV-YUc}KBQvlNfu|LbgQD8T+{K_$X1 zJpw`niIs)Y4@SjmeK|!G*N6=WhP_9UFl=#oAzxncPaT`as)_1oz$%_TE2v#G;}+iD zb92BuEH0=I<$?OUxF88X>^S8655xHFDOsW^DUVO}^c{0^(~Xv>LcHrR#zKZ{jJJfB zXIxShWB>O~cf!tjwgg$$<`H^(q!nGtM zZ1^;9+EbZAFXf24DCJ#*>3F|asZ0(%+S>&8%gbXk9Nh7cPEHy;+`+gHWRuBYYfx}C z-9zZn*Ba31Jk2C5(?4}JU!puvG%~MTyd4 z$BhQoNAPwJ?4IC~J#QI%1w=w1SFO(FKM{z7hwVD*%Fbq7h5bxx2kS^q0jgL8_mG$F z?RDXkQuGzZdf@NncSoMEt5l^TI6KQ;ub0P3<+#_6R4UTv*_kZdle;LR)OH>C=A`lG zl1tf<&H*qJ9aW`=54Q-Yv*rlcVCz!X%5rh}WftBTvZh3rI|n#Q6K zweMMJ0@#JhWUA@8qMW1RCz{7VYoP>)IA&cC3!)vjldmkS+g;z7Z}_?<>{wU-F{dfz zYP`s_2qi$hs;AS)!3o_=a6r3_oV+7uYCm5%MdpJkRR$XWyi}cM>bhs}11!*XrqHLJ%^ER}facMZjEsib+Cb ztNST?yQ|e@I2qBfYPE4xDa*Sd?Q8>pKakSr1~QOjN>^yg(1f~AaL}B4URjkNd%k!b zh;%UA{b$VdG-P3d?48&*Or2ryEMJ`I93`jZQDlXPylJ`IoVp9UKFdP~WOg~7S5%(H z{T{Ra1s(W#Lou7oxJ7ZY`y#Ux)9(hxGY*U7(_1!2f!nIySWmzHq!3BhbSDi{-Dg>)#OiyxVC{>hVGBjJwTgJ% z_~BCVeZ*D7U;(56IZ_t{rza9ntuHQ(%h2^37wj|i{7HH!d)3K~BOY7cE*4Q9rIaXt zW5kYh=Zi{FBx&IOCWq5BV<}DS0Bn%r$6=!9hRyL9$|{INrkZ=tJ4)PNh*z)*gz=x7 zLwHU_Ca~xwSe?U?S5{@}&shk8`4;f7nc+k~YKDBtB)m)C;39mf!-g1D7-Z>S)|rpZ zo$^|{-U}4*$9zj~B`6H@)V822Y3G+>JLaIH;jP8gcm|g{cmitSFC-F-nP!k?N$d)XLm3VnJiG_W=V3%1$lOad$%*FF$+sRuws#lF)Prh3Zp!4! zoat+cvY!#P%Y`>hCy-Oo8XO9ekL9G|fxyE=n4@pN6$tIY09AIVuG&AL2go7gKJA|} zjXJFfN1PeQNl7**xSujtdjCl|=M@lN2e53&11-i2RX^JdBV@TSn;@sB(^?bEU_=6u zR(EO1*LoyiL6rbZ$ikK`^4JJoKtlk_w^cSdL~Bmhl?H7r*|dLm&7KcFRGqfF54$jv zX{imNZn?-<#*-C9lhcRn{EQ)y&8|8PtYm+y!gj6kzSVtsO!%G{*r1c*Y>_;Wui&Zy(^x2SZ-QHoNqHS({?xZq@8T$MOMgwzVonv537shNy z9&lITPh*tP>9_yg4%U6$s?dds>odtlfO%G z#mDt`zw@w1^bqIRA(tas;4AzDorS}>k;=Kv~8KF+Iy>}WZ~eY9F_~P*D-j_ zweMlA8jroE3g^6czr&sfdvo6Euks3!7;+;e-0}DMMm(T=z3S~@T#kpuzxSx5_@viM z<7CP6fnY;hQh>C4OGmRbW!Xb4OsZfZJioO!_A?vJPZs0KAH!eCwj+Mvi#^64Hx`J` z2a5ywZ}aQ;z*S#Oo|+Qj1us5S z`H-SsoOTcAVYR~|G1Grlg57DkZqO{`%dlzOgCqZs!~Ve^HGYG4-^ktj&YRAL&JN2q zoP>Oge~@9snKzg-j|PGgHipylT>Z}JX{6B@n?q!P&<}u&%tZ2x-1D>N{KCSsP?=h{-Ak=${(fQ1jHNfd6=3%yHNq7l4!yarbT8UlbJY=&iTr!G_(F>gCo=>E2E z)s5Oz%g_w0CjUK#eFOf5ugK|^Lc{|1W#E1<22q8^U~t60{yXY7T|x_JLz`;D(&Qjj zds_g>f?_iP2i5sanRbkFKL0QKBc~3Gjd}|hC}cQzoge00%~KP|eA~@iEe17JkWgS% z!`Rt!qe&gh6bYH$?dwsF&GJo-Co@;8^+7=KR?duqXro>lwctGi_o9qN-al=oxuc8U zx7^Fon}2EhIh1_-gsM=4>w<;f%Qy2Rg&q&FrjdSYl#fxtB$Dqxf~@fF{O_B?g2DMt zD+fM1M4gDKdRQOp0|34>isS`yIJ);%0kiS%qe8{^AH_L4$VQV(QjiVW-sN7(Ep?aL z5yP#v{mnZp+3J~Vxm8}~{uBQy&CN-XyV7{Gy~yYa3^$2(c!O!Jc)M1+bx{Rg>@KPHj8nt7Ci5Xn7FUEPTesr@j2t3DHuap zfAScNCYS1mP%-e_@(*th)-(MTC5DHOp8>HI@$YE)DCeW3#GffU8tkxm+$@O7ZWvfo z$N5E%sdy5A|FokrW3!A2KR+)$6jK?0*T-ri+`sf817dsOCimZF#VgU3QFjV)iVH2! zXR_-f)lLy70T~EK@X+N-2c;*SGGFDt!5At4$B906!B;+G5E(D@NW5ZPA`2!Q|MSznkoFsI?^oF@SwR>6CM)9i_@^W^h!!7tN<Zd@z^lnDD3JAg zl71VAa)LaqQyV_7H<1^XO62tSE}0f&==B$vH>MWn5t}Lf^9I`goJq#EdtEsEdtF7DrF zLiq|Ux3`+1W0hs`t+AnMiJYpIy+{V=eDbmSNVaAmGbnzTZ0yj`&rDwoApNf3z#uY!gA>_V-TYk zX=HKA3x@g?Fr5r_Y>R!o+xCReQWg?v8}YP5W!;UJpT&4!B_lJ}9<~+jmyU!*15bcd z3f*I(?3mAEOV=~7A9yESu9vKP(sNg5n5eKa$bsx~XbT+9!Tx@>{WM$sZr(awc_G;4 z#u@s6S(DJ;a~fg6pzUl7hw5g}!+UJL3Nbn0<{zTDMsu>)P)p5-a3UT&+)9APka~Nc zl$yTNK)#LpC0_i7Ux84Di4&)SX^fY7gKvy;%(<<-9B@mz&pEbL3 zG3p~4tEFzOunyDu9{p{2q&I_9U2FgnEjHSu9uI#%6<&m#b5A#%C_MYg6x?M^b7w5# z6R_WouxDK6>8f>LZmx6<^3L7K=3mxrPGvo2pzIRZMF0Zp0F!9i!-i2bQpNFtuVxSkvvtyZgm>e~@!?TIa1- z@bN3kRd-QrRg2sur~j1e7i}yBHl6n6^3-E@->15&yJq`;R%Fweq~KGwvR?GdKPox`5VjC)&*<2v5t))n>e2S@Eox>nmnL#0K@~G9rQf zBkXf6T&8pX^x3R0w^wOK_GQoF)S-=%*QC^uh zJ#ZQ;sVG}^i+@2D7|Q9$4*O#4-PvKNhISA^UkEnT8(uHO&Lcr(AX0Hqa*U#>JzUDnoQKY{+U}hbXQAgs^Em|V){Qr2{wt1s z6&1e3VYK%q7uh$htIdX3??28RMcM}vX&s9w#2u2@v_p7jNSC4RD|Ryoq^pB}mDAy@ z18r(Y3;3u5+bXz;1Ml8vB~Y-jImDB*m;wDh{gm+#n5+EwHHBaxY&s){<>@0DhE(5J zVYwx?WMl0(J;BG&@*pXzv=zlk(FO5Ia=Rk4F9zvvtJ8TRfYnXpcGczPYjT*&hx&-;2SXyWW8;57htZ4|8= zP>d0UcCT$e)h)ipygdkrF|4dwm3%^H`|fEWlM*U&*A&^Z#-G&@k#oU^LwdJIv_Ryl zy&oe=H$$d~os|<$U~y(wFs^)pokO6ccRBTTv4*X(rtsv7yl*JFCcVsi<>l)dKROA+ z<@?6K;kjeg5tvuCD0%jx(O)r{7G4PUV>wYee1&$DE4+*-7w>Q1#A25MF>syF#{u5_ zPE*YEVFMHvC21an4fi70;cVPNyHI^f5l+*o|jlO6|9}+ zT0MVV9<6Lk_z)W3$Xf&KP_Q#TSmpN43_-4r7pBDSeiB={{1|1) zIAas!=#BI-NI=>zb$1Q()CM;g&%cF)6f@lOcvIvqX-}}%$M3l@EAx%cysbY>a?-%e z$LHqmmHg(TVP3-z-Obh>UNukK#2{Jw5O}y!cc{u++zD8c5l z;6Jz%J9(vQ32Y|3j~tnu`M(rrV)zhk9gUY8x&0_N>g#O72>r2h`eZ1d2x;jus`i&9gl2Y{) z((zTou3(}1X|dpFe|^fXxT+Kr9ni`G?eK5{mFe%xz(JeQP-Xy4H$5>3ipD0@Uuael zI5{lYY&vQu^}~56wHaIa9CRr?&_ZbCZAJ95I4_Mra#ck}|4TF}N5+p^N^^z~+<-~M z<6}xu3!xnxr&3rxC6F7K} zg}}PSWz6Req$?vSxDdaecTyCf`o*^hl8dWijHK%C8ZC*3S*$?tZce__eA8?hb0}Vq z!A(Z8^J{}h%s5;=nwW03iEUu%brR(MHz95ZhbDnLo$2N< zsS>D!ek%_8zk|K-MwiJk={-eZlqGBS&B)jW622^qHdDNEIGj4O=}`ekm8@jP zJ@KCc@e&PBw43qAJ2 zO6!?SE<68k*38$tDxL$7HTnmdD#XzObX$n%Jj0_KPb`p5&2WcK(ild3jTq3gfffKX zt0)|sls!V$VLH=E<)fcrOtGd>kv2ja|AY^JFVBB5MlVMtwkg(w>;{(Ws3&TZGt2Z^ zs0uigO{EW~XrU*<2Zc5B0a70%^u$n&#*l2EYWw3uy?q?cJ|oVe{TXFoqq!dFDx<*> zaB=YvFoqBL9|Ptetx4|p>@3jCv$%Ac9+M-pyX&~z`AWNkM8hUxfMJO_8Y9$2M|SN; zn7z6>6N$-zO%zmBJAF2mwLz#ITamyqbh#?hzMUlK^f7z!V&!oj268cOrSQ z@D3wd_A6rLMB)hd>`j)Sm{_8z*cB(}&HXW7J(eTqg}a1?v;d^}JUeY#khkIAgfC~w zxV(Y;I|CWHi6aOR@dKc-`T!apoLMD5l?rKvS##PA)J()fr=>oiN9?=Y^<88WyVava zo4nSG0(i}Y-M@38@Feg(@V#JHkH1hgSn+x_-uF^;dgfxbF&CCa+##TkO>>Z?lT3pq z#GpuODeuoQv9ePF7_wnrnwha1Yt=@-f@6mefjs_9A@vgG<>KfGnCKI7x#W8)Q;oo= zhfOE)bl0Bnjkm~+vkpPof~(7X$D!1dl#JZ0T+Z5L|U6p8*er)lN27qbW<3NGPCd*6&HiOdmvlRifkMNT9a_!QqH zT>9oo8e^mIAFp3fB`M{YPd^yY^g$IR4OO+!NZ`RaRzj*UKn#XS&t3ndq5KY>S*{oV zmnN%GKw&>8yu6gFFj=X@tRex4O_3hNfOJlkR+C)nH*HE-w;sH<(~e3@J29)34P0$) zd@BaExkuL{$pe9H>5R1;D}Y~RE52}}`@cfx4+cy=RX5#-Bgp;;cB&!b4SVp|3&!<5 zLp4=#A4_+sUQ> z_EpL>4DtQWw8EF#zgE;<0UlS^J4ia`glV6hbcW-AX6HT^J1%Tja%qb9Dseq;>i)*l z(tT7L6R}BNVYk>^vUDxqVhGIT+1oxRIdn}tR4^Vt8)F*k9@g<#gt6%fMXH549U4`P zo}C29Rz^&mNF46apFOyW!H6_AdPIz6IDgD_4dGvItL`G5?0oo{6Q9udv>+EU>OI3! zsD)h%!T9)8Vc@QIIJo4AQE92DG$oO$!Bm8*#P!=xSSp!0o!dniM`S~b3teYe_9da% ziTO?`FWXzNu!X2_sX-S0?3P8)plO|lWDQevLdyt+N%5CT#7o-2&^idB+V)axPVwF* z^$Ru_=d<&7PL^P2)+yNaG_dx1Kj;8r068p$xoR?OcJJ{=ilksXfFSWV^~~KZlqn1j zu4yL4%FZJ%9jl?H$r5@Z^ZP8oQf}~uXbEZ&i&;i^LKGNc-@{C+qEeZ}a*%TV;P_af z+z;-@I(*HeVa>P6Kl$1yGG0J#w`f$5GJf0}r=pB9{&j0HnD) zD}jfnjQhtjLXhlSz3To#L#g-ZGz^WYh zQ8_&fs|Z+MR0#E2vz4H^MFz}cv{I7xG@`6PlNeWlzbAEi29joD9@k{j}I z-sEWUm>!=r83uFA75>>(u=I+0=YEv0`3=MTQUh8{R+P`t3Bz zC72M*)Zn_f@04?}WA`uy`j&hA{2yk^l~5s8S?jxdKiswEn}^?S{=5IsT5u?Y#Q0t< z$K3^a6^)dtXdzWffQ3-Bk37jN>lh$D%RGxhk<4^lEJ@m)mf(3XaxrU2CqQHYq z)HtTOH~dsEqCkoU2D`xtHSGv&y1SJhb^dN}%Uv{a3awP85E=I6OY7$m5+V4Vg1}hR zfJDFE+#kvpjmI{?u1ZvSXpnkxoJiQ_fT&#)b5{en|=8HseTJCYGhx;pkY?5U3dhIEb< zcgD{A|I>UFwTpuMenLpn-g@7lmCbwoxNN6q8cQ`5-aF5ZdGh^<7R(SPaine8qF{yC zy%Fd)HlTTBd$~!t1?~O(Ire-%=0xZRNVFTex+w&{cI;ej)gNDL23kn4oWTktA<04M zxE%5-OEArn=-EMgD^8{52c%jK#01Wo`GX%KE)RM7`S?EZPjp-5{w5EPUhdki3!Yw> zL}S2>S!PNCUIJkraw&fMimW3)T1t*sFY$+J=fMSzkQ;mE5W9|!*jLkBjsKpYQC4vr zfa3$_Q&Dg&DO$l$9Qfsk{d+FFSD`$cjnrnd-(w67(4F&N6YFm~A5zliL`o*}ySPzJ zzxrnWhN!HdC1u3Gp4fstid}#}h!?T|{mzLrXlJZa2!xs7W~XrS%=xBj5Qe51baJD`SJ;jPA>WfoVYT)gjm^3;Z+(WSP+g_h`>{w z8+h4d-^Wlc;%Z|@?KdcHV{^nvN{VCI>>`|;ykM0*8e`?0Dnm*q0YxzI(xncY>W=@ zGjr!XE~_(ioQ&@)X;=9VN`Ap{1Ymr|dN7TmQSA3-_K|V{U~xPU;1U7V3j-hk3<|6t zl&RTJ^$4hPok3VI)w~OfYoD;Jj0-H7YXPJdwK1dvVu>GUO<}0OA_8!`qBYo<-~gr6 zbED=GQ!+6_j$MR#F-@IGR+jJE9ny^E2S?i=h*nq>>;o)psop5Nq?A6`PHPf8Dz4co z!O~E7FSU^wIIbx2> zHd%MN@g9x=HsEnaV25Qe#JnNCS#KNZr}W~6esbo@fr`1jHHn9hFyKA?;ZOD+=B!_w zXeXMpHIJz^32b^!=BoP3F^HL8NL_ceIT-yCSzIg*RHoej;d34Vq#aNZ#QzkD7|YfzMSutd|!K z{>y~s_{K(Lan&Lj6+U5C&Wb}r5M9;@I$0IF^|moeQsw*iwGJfJX4Ix@2`sWI7&-Iq zB?b9jBg`tS&vOR9|Fs;_-MN82Ae*eHF`a&)MuK!+BW~82bi z#-^pkgx@oZe;lnxETYwu5^k$X15kCV7)9@$ECD3p>*mpa&pZ5@J4!1Y1Q-Q#)?NIS zG?bF0b=jrSz#rKz=!3*5Or6?U{C~ioe!iWb@qxZ>o%z8u@>8f9;CU;jj3_9J0Nrv| zzNraO0HiTvH+k(GJZ^X~6$j5cJ8H&1@L>5bmg5tVo=kVhXFC61fPH}EnF2(8go`!fy zKdm$}Z)KNIppe*j3}2fLlSb+nqRM%&lE9Y($#R%W<-Ty(kN)2RN@0P@`4ajxup6hj zv4uu4A@(91IG*is4%S_H0tpI^W$$gPi?BzyIR`%pvN|4g6;2VEsjw8KtUHh!TJ_I> zq)|0kqEKRxiksH{0aZ*C)2f2As=T-~c0Iw*KY;7?=%9g;QL7JVLI|@obJ9ng{e8ww zDdEJBIF4mrzHkm>XBNi($T>p6svB8^>mLJ=6>YZZseyvJxR1!?8>`-a$(}fVNoMBz zd;k%5bZKXrfVopWp7+0&RoAc)AOoOS$*GdBpfkdNFC&Kk_u~}`oQkc9JxoUxQq%Q# z^ZZ?#S;U8`q<}*NntLp)Y<5jhH;U-r?u5#;hC80gj*8QAVv66KH-p5vAt85;gT(hu zp-rf`Fu^dqI*pAV-7j~;-_m1@%$LXD{+>Fwk+O;i0Hh=zN7%l1+05RBj_D>B*gSki z2(X+Yu!w)01LnFc5wznsW&9ZfHc7?NCYRz1D}prgN<(l-eKl|<5KrrJAt7)icV8Q| zY9Q{Pknvwa?;7n}s@*x_0COx^V;~EENN`|df#UnnVr?+2!_0ERFTOUneOCy|hwAk1 z_G;UJb&uOXO`)faryFP@Y;7_ag-MEV_!ThGH&L2lB8vL93ghC#cINW0)vvJPXAD*i zkQH70O2t05_i2W7e6*CSXENRc3uERc6kPOCd${s=X%ezKW^$($f z0dA(SWpLYgl@8~pZP{JobNqPbhymaEN8DVhjzBg4kpLq;qW1m5m&9E zn^r^uo}~XR(8I5EsA+;T9G-XI!7pQ7)2gp}f7DE)cCcR8v0fQp79mNoa(x!2`(Do0 zLM(6*K`QqAEIlju_<^aVU+D@a7c5L1FeL+h;REvDp$(l@A~^z(o~Ti0A4Z7i>j5o> ztp$M7aZ1!iSE!@Rx>4iKei@Z63vaM`YjwcIKoLY@IQZvriggq%S zFA!Hfay7$mL7O5Dh6f=^un0-k#;7dxJT&6MNqV)>Tdi|Cv~J;}&}#8JT-fmv%9Yox zbA%tgh;gM5q^J)o)$j-7lrc62M62CPeQ?6YQ<>~y7cI9v|2R~OHjTU~F8>*5m}^&a z_e?E-S^X-p5T!B+v9(vSFc2s!VJ$7!;Y?4}B^gg})mt~M@_ zt|-$*LuOQ+hW)wzaJTE(goM;KfiRG$cTG$1appU2{Y_cFI$*xyV+F(gqg05vMQ+sl zL^d6Ei5w8PrplnwQ-JOudPvb4IoW8Bf&Xxi(L*zyw+3t9y637xbcIaU0tfZ$Hhbsq zmKTK&=9izhTD)U4?Mw;gA#rWrYGk|rgDz>Wf?jD*iCB$_ z{GTq^P@v#9d#phiNU>ou-SkfhL}w|$zb1^)W_W`!n{%sg^?k5iM$jC*qC>|=Nd8GM zd+VYfmGddPLWx5)paZdcgipR4!9BX8APi0uH@1bsS~TfyN?B4ep>M$yLyrs%y}=l&bjjC_Yd+3S6g-K8Mz*7 zw1_4%ruAdtSL&dx%|(#+Dp@aw6evJ8n{0Q;bgWIrE7j&|+umbnH|*TW^dZkzl^!gA z!b`DblO>e>$V8ZyD~LzDwX>-j7nTHxFF_^Ux6V~0BMXTXU99p@SZ@ez_#I2&%-=es ziBJ~ z8J8&jjr5-0*irRiRzF2caIr}q%{%-<7%}Rg-vT%+x>#%3!~`rkv`j;lzHz4ImDjoH zlsQ0HM~Y25$z_yPr0*wTetfJj4b4oOCuNaAR-Bz;8yWfEVP5~<{S{eudeNBRu~KJa zp%0wZuDTLUafg)5*JwoXcUQK2ej^K2pdkxhaaQoW@0#FW05B{G(_$K>AI||P3Py*f zBRr7sg$8ju3rf!0K8A?9f8`Zt7g@j5QcKm z+^(F=pC~){_-D-%0V>rlT&kMiqUP@UE!J%DPF8I(2M5iQ4LMe%8S+uA$sci?yploduYYPl;IGD3F%(9$LBUG>wPi*m zT`h$5vuyIQ9%DE;MIm?%Wt2*+Mv-5MpIcJM<`ED4=@6&SZu&}_uY5U+SWJr%H`q{u zLDNQ@cd-Qy!kQZXGo%HmnY={^=-wls+WH>c7dA?k9eNvcbV26IY`hl-w;J+| z8Viu4!L;$k#BSW7S=0N@JED>ZA>Wm#fj#1>{qi%X3&mCvIMQxH*bcLz#K^@D0ywbe zY4k0=4f2)G7&~a~T13G4WISR5!Y=lBm~M4vL4~*96_ZX%0p8 zn}Iw9ndKikW$<1S+sUbNa}RIz2isSKAaeS51U=`mMZh|I@ofDL#iWg!TAPOmHt-{A z$B0C8kofc*C1|)WY3XR2Dr7;f#ZCtRHK@Jl5;HHN(f6O1nF8H5$c1o&>Z3R+a=D#u z_G?o?hkxr4b{VeWSzeuDUT0rxG#CSrvzDf|EJoabIW6S)5MFb36uXO5eYy9iz$&fM;s@(7UNddPw z+nC))RI^>wh{Lwna6l0!+8g#)o2?BJN5BHRubBOIvIConhW&hynIqMuWb>~;P~a!p zxSdn92dQR=L+F)?$sH@BLaBqk^u^5kG!RD~}tcBZ@Fis+yNl#%f;a zDPhA2>Q+!w5;gsVpy#zc@$sVu6cZ$h6V8jN#=O(pK2pWhMat}vVZ*P8#$ zy!0-kk;}op4x~}Xx-BdAkM0t-(HRX}Aq7a2f>4&^hEP&Gdd$*(sA&Bh;k3~shP;2j z^GE9OXiUw+Nr1k0d zZ2cTk)c_ARcuh>fI)E2_v#?eDwwr^HzQjFBv#^*DjJ34<-FPYs#5k^+?3tRDqM>KY z@N8JJ->aRozXtXrsD&mHSW=e3CX(+mXf-p1`4+4GAPAcKN4#XnDQs^s^lAfjyH=6s zGutoIDN8X{365;~mIRDKkzEN6vcZ4(p<2j{Qcyh)0F#&>FuI5f_tMKJABu9ZH`Mmq zD8K~}B`saXPQyemv#fA@H{sv1y+#RirXlrcQRHENKqM5LpgC9_@Y_8GOkCs*?_iAh zh0Yc#-pl$&il;hdB~!64XfYMh#3(S# z$JkSY=k^mZ;FD0RX9hX_<17t%Pdu#u^o2}kDt=BLOOG(sD+pqTutS~b1e9<%F%mwq z$UwNk_j*(a@G2i@7&}JE690zrIIX=BUaTzEC6H#4<6nD&g9(l?7ylH5KeL#YANj@i z1ju_w&7?&d7^v_E=Tj7d>XzA36u0f1g;)q>!z6%eYZnBjyV9K!bpt? zTLH^7jM})cR=)$Q#z8>G%sVBcF=%$lxIjrsxd^CPv=UX__X>w$6u?NW*OU2nH&HGj zhp?|A=0)uvBT~*QCT4rr(fGJHbm@_@O#~;QbW*fF)OcZevWDvGSZB5#>dup~cq56YCdZixm)OF;UKtN|3WcC!jzKJJsn(C|3#^^%QtjMo1vI03?bKnS zh;WhT-cc%&#ae44mISv%8?bL395l<2G6Y=dI@nNOX zOZ}=E#gCeI{z6nD+HHKCyGfO-Nr{x#Ke#F@BB(U2>xJat}pnvcCZ37k} z#;1?ULh^YfeE^eTzr;EzY^t~$BK)_s;ER+#{@cn7(z+`iX8>G(t`3k8Xhvvq3nONI zZ!K6l`}6weV;Q4kaZ%!{oQ0Iopm3|+>R z)2Qxz34$j8ye~(E-#{u)ih>qKqlTW^n|BYNdrv4A_bR<{3d938Kz(%hSJkEA17oH& zU5MyY&GI4!`@IJNK^1x;j5y5N4}2`VY=&2n{Bcf2`gt4YoM|nm>6KDz)iYG z(`_@!HhlPO7R!v9Hyc_Xsqx`+Z*D#-jt;lIU zf+Uz?S^Sc_B6Mq%agV-(R9;ZmBtlwrklWUw2ataJzZ2Pq-mZU@y*Ahg$CI>Sn;c++ z{$vXW;H8@{p|`vay783_kgi;>u5`q^)8!q5&;HNP720A3XG^=dTPtluy|NMME9R;x z7H*}QTJV91_;+n%clOINE0nAAEQ2Ibc*KT~L|^YEn!!wDta=pO8A^X$DW^q{1}hc3 zrgk+c^v~bE6G+F~t%X+VR!=)I;n(q9AR?ipN-H#Qc6-4eSIDN6QTvlgx|b0w`YfP& z$7dIMAh4&~8)G$I_%S7lWJ?5-|6y_INQEKWdCf3K>T-iZTXX-fPNU(%C;tu=)ZiQK zpVT0iB05vax1EN9M?0W!DcF?q`9I73!FV)0{Lx_M!6z7x{xcdK8{& zz1fCwbbK*={FfEgH^8y+fyh{-$JQhF7i#jxqLUj{Ptl}@@HQ@omfP0~`zlCPeG*k= z72IiugK8_U`hU!nMVAU#&xoSIP?))W2ZRJBf5yl<*RiGF*pp{@%u~sY|7&d3!f*t| zqE{!wauoC1`*rFxOw@Tr@412$lu2!OANKOkQ7=hNWerXi~Me|%4b zU#gJO&|1Qtr0PN=qqwO#WBn-d0B@tcKX8dj!_%-m3DowvkX~vefZ>HXLcmCNu^Oof z-_uUWBASaJMzYav@r)82<0Y_UGdpvDJt0jx>jjLE@@w|+~ zBqc>@1@beOi| zIrc}I{gqv2Is66Evd1*Itt0UdBz%mZDkf1tWOwz4jM$W(DrwJO1B=9~1$x^9^^0yDB*{2%^ux(M-Z_=eZM<^k z@}Iw~<&*w=YdKpD-!~k%WMwF=@CeBVOGYf|*c%_z_q_AHIgmu{KjA9F^kZs`t$Q}{ z0TV3IdE_e_@Fu6piqYZ@2wjheW*CmN$={2{SCJWU?&ADT;ai-e_c+)JvTbGi0WG(j zYz!j!5$i`*^bxtScUo!`T8b@rh7ZehLhQei^Py)8rTkICC~+YjgClB`^?`4ueBpmG z^lKCnj{bB05`Pawn_9J8%(}|;>mlL;ol2m`xfEysc{Rqqo8`dS!Z<&p*D^>;R?L-b zF6D?RIL^=;`DPL*B=i-UT#3MJ$IyK4geP;%5S!?^b+pu#u6VyR@SEsmsp@G5o71jC zlzrS}ylV;N3bkLvjP7@mjK38&N9GtA%-o0egL-a%2U#0ebql*Khsc3<@JOd<_>{JXq--hSP;aP@ zmSB?ce}!w{n{vPa(E{%c0^w}@EM*)n6>Dl3uAlB=dkOy)RZCzR%8L|b@C?hE`Uii6N;@2BhN|uUH!*JJ4-z7@O z&g}QkjKU67`0bEW%-AC86yVUnVFGbPVTM&INRAr%vS57{K<&D%^aEv5JWkl1^0F8) zJD?7-p^u_cOGECz$^}y=dK@T261j5pOdg?z^0iuS5OF$q?>*v2*L-F=>Lq}tNc4ad z;B=W83T06!BfoYRSrS=7a6M?A27QL;O1jYiJ+bsy9FLuACUhqsMn|bQP<3F}xNk^N zEXV$u6}ni~-;gA6Hj)D56Tx~y_8sxWF9OoBRy4m!>u&TFwDUq%g@3n6zRhlvKLomr zW}mQ4HBRn{N&k$J+CPl;SE=r@lEyKvhDqBNkoHvN>o(Gh#nUn!c2F)RH;rB*kMuHX z=jyYx+;uqbI;D4@7*51eX0!Jg5#V$Zl{#0B<=h9!Ee7(lSZ$O^xsoM-jNgG}?G55M z@Mgm32sSPn1I}vV|2%-x29>|Q5qu>H@{Os<`$Hb=ZJrGii&PO$5sYrUhR__HTX}AP zKp(O!P$&Zu>n~*H%!u0H2pzx=Nuo7@5f(SMprvKW{vGbkDJ{|otl42bAm3{9SCvpZ zR(BvNSA&q_6}-!48GssZ{1LMD7n28J>)3YUOeTpMTW&yO>+rjcfx(hd4b6%g{ja`g z$VSmo*{cIEc!!bC7U6R;_o9YM^4+#Su_BI^HKKS0O=occ+ep60_5kpEE)H|NJ_>LQs3pkw&IlbR@Wf#@3K0d5m{*y(t8 z?!8X+{lZ`**75rZj9mS4Wts-KRpf4r2nYixKr8bzJh1MYZdwvtBR^vR5*?VGk#ma= zXC!h|rx*Q%`l&nlKvc8q&qW3!*DHFFADv)3l?4r$hcG7)qB9RB%&2Y{M!du{BMC#Y zIYzL#J=Neuij^D4lyVWEw0P4Im+td|JuJOKaUb-Brz1A`VP7%9N z(Lq9>3rA6Z>qC!7mz%lX^w{{o0hF$jk*GH+&NBG{A%f{3 zPNNXV2A&M=TBXVqy*m8pi*98-g9+zEB_T;rExTlI;?ZN77I}&|tA0Yap8#)N*NY*K ze+%NGc4>tMoDegy+(jzPeC0ucJi;U5W_{ll{kZkPqmFLV^5q|C6{5Zl-Xq^%!RXj1 z!^93MbzOl(S0=jF<`uQSB^B6CH!HQ@v~^oU3>B%79QUM?E6NbDIXd0Bl*n0alOtO^ z#;ggD^u>D1$TTdjngb!ijB@r(NG#UDi$E^Zgq9bz#smW?PBMB8IJ=a-}pf z-Thrra@KE}wlbB)8|MafH<_}*3CC5upZyVYs`3dLNW9l!&nzWBpSxoR)&1Z4YnDGF zBfHt**G{xgy@?5+w+WNt+ZK}53A4yz745G;Xq8?B$lrLlK_m-rZL$a?XQG2lYh`4 z!**|F#_W6z-x$EE8o-`*O*hoPXydZYY(W3QWM#eGr`Ey`bU)~Uw&?Ts2sk04`YSJr zma3%3X%~dD%(EBA+^C6#TmXCQr=7bJlCCnX6%Km8qjOc881C$q_b^dyMn;M5f+9 z|1fqGab5Zw`N$a3OhIj$x8_-+u6K0Px4#lYwCcN^xgNhV_Xg;|3;D2 z5~^47W{cg|bH_&t#-KHKyJYjf=2m;0{*l!*Pet|ptph^NPAuZY^^>6@SI#BX_yP4R z6Km<(Z8F+2HY?CiUT#fNMlDzKfAOzEhPvld;0`U=jCXm{^UW&@l!aH>20@8q%B!h) zLohMyu53ZJg2Iov-)Tz50q(a-?9sSF#j`G3w-7n!#h>`PJccKrJ*_N}02C<;S>zFB zWX?T}c)#Z(ImK^6!(RWT%!NCNKK7xvzrG6DEUt>T>#=~96Gv(&pS^z+H?fW@hBD$t z&GjoVCxf#^-)-anWoE#~W5Jo1}b|16DK%CYxomsv|^6i_?x|E*#PomlRy9RuS zdx6(}&jYNR&owh5o*~Q7hO99m*Yy1h2{t7sb6)|6IT;4q-qL@`>wQYD+D{(Gkq)Gv z({a8r5X+&>hyTHeY}%7&xA&6&hI;apY==5hAtna(Gqy z9lzt^F9{mGLY-ZgG}gOq=VAvZeg(TsW3l)8m?6Am7V_MKwYL7tKbO-BiE=D-X(t0H zpB=O5+n6rOp%;#rHo;F>>W&7H5W^e$m4lT(U3cDxaT-gL;cljC-Rd+i=lXBJKww+d zJHU{^unRBT>v5c(t*aw&C@dWn;2EU4#{9E|@v>g?YzLQZxtF!&j1(bbB6{3j8Kg;8D;O zsJPBBJjTm`)oOb_n3o>v_3%24bHy<-q#{+GHuSa5g#JQ!Iko$azZZ+ixc_>6Ce!!x zB1MELX%lUa&EvpuHMIak(fqN!>bhh??)gFV=OoKs*@$Jnq1P`rj$%csHb3tG-`g4) zZ2X*sd0PAvG{#({%A1_6t;xzTZ#^?&mv2cyy0Hb)IpRqfDLep6%c1N+*$5~T6| z5oI@X#HY6h!9UmCeYy81`vLTx`(d9Ih~TE5*E;x^!eYB!@qBJTWYe9W+T7-pDYLY4 zzllzXd%2n(lCdTGxY%XJo?@a)*#^KHspq&v@{ncq#c!zDt(_4%o^z@tiW zM->+0L5^V#QE#`MZ%0aDnP7P5>o|g<2d?v51Cr;XMX~T|2VQ(&n6meq51RXb9OfA9*g=-!)G$Z(wf{$;HPh8uzMf;!$*GU1z z$xBT?4*74kQkHf(AtHBr#roZz>u-1Mmf~)&#|bBTYX>3dB{%ha-wy6?7;R+In{yZu z0xf6~sCRonGP*<+mi~OJIVE>&KYryzKJazM4l$JTy*?jpZC*vjd|SIZl>uGvHe=80 z$NS!mEZS_()?>ds!?W|GZC?MIxG`mFxjFyiw!6RZuN2HkA-b-IK8*zwLrXMQuR!9* zhJH1C`fIp;H_CczLZd#$n()H6D#g*juu#5T$LY@F?&YhR@-78iPUq__EuD?VV|&V< z0g70{x6wQQ>xZ$F)<4tFH=4zk?rgHiNG#WB3|uB~dVM}y-$2{7^amsC&TL2r$Q>_B zEc)cilX;4}B2f>mz)9;x_FR$oB|vk$VBh# z4SA++$MJpQ2I&3~VV~{Ub?`AK^0HId6f65u&rrM_SDj6Mo|Q|6#J=Xdef{8*92{BK z`FLBGYHr|No;I*Q$`5CJS^-i$v<#a$du=I>wg>oWx<+*KtW z(MXga1e}>)_0rqQ!YPeSYKF~m=w1I`T0a@N;8hdfMHT9zv1jGT7+VgQv6=Y-dv5ku z^=-w{yM#aN_G7d!9wl1gak&4qXRzXYRAnlU#{K>Fx#v&dWu=M@HIh$mEMJ)8`c2yY zG(i~~P67yEQ5Vq16TkVCzPWYN{v(OnB#NXM69#tmzn_EFJJNEOQV%b$b$Nx|oNMC70>iUIi0HRr;vF-f12IzAU&xOg3uFQw3IX`;qWh)=%u)BUn1BTA4y>ks`m3Fyf zgIX9*1uC49$}13*QywXMzU<2;?{=Ix%ZgBH(|Z!sjdyQGHs&&5iU z+u@&|_ATDLMyr-$7cSa`@*%lO6mcnAorZi76{2`A{4bul{C$s&+Mpk{%U3@y95m+u zQ+SqA&eq2)EN_aO^($|DfgCS|YVQx+qZ9qz6YNAlhAOv3C9=1EL3bW}nBR2N)ZrAb z5fN+ooqL7`t1c`ni8AYY+N+w@$1ht%2pOmwT^j8g{%fzU0sr~182!HAZ6{ceAN(4-Mu}I$jqk2Q4}_yM zA|v&pT^$$7XE(>2BDB#GA6Q?lLj3b;%J6?aPHUP~dw}~u{?|nP(<_NZ`|O=O$veg9 z{n`c5i0ox3P{mr>PVVmOf?3< zU|l!cVHl-MNA(~2LCUkEiX^f5osa#*9)Z7pH!(?cJ^AT5tD6_I`|vKC#Zx3^)ZYHU ze|fxG(LNnqFFrnW&%FKaKf=+J5Z|;6O$4^DW6A+0Y>DTerur>R8K{N(gM@;@FR88y zrCfYwSS^3_d=K*8@tJ9DwVzuwjMU7p>E~iq^_6y}9qnmy+SC-=4s){&RQtb;*eR$n ze$~O@Gpm*4)FS6IgZe$z?v)$c4xdKpYTJ+3x!^5Yn%u!OXObZHJ8n2OyFaHDFPrdL zm@Dme{t@oJlyxWy14_$UABko3vG8#EjW_5qWd*sbc?>xn)1Bl>5Q@~mlLOo;o+ zNXW=T8>M=2sGP`!N=(31C)gf+-V!)d!9a*LLH2Iuf1a3d1(QXb?BJbZak$K*;Y>%d zI-hi}Ur7ktO1k6(hQ2ygyC>r0YT`B*f<%Zi2KC1@2dzdJO#ZtY-r9+La#&&!QC3!- z0p(;C+PyskdE!UDj^3aUsnkaSa?tf_zxs#%aNU~Ke zsz{NeeJssUM7ZB|8yOh22whReIDP692He}%#{~)3fB7nbHkdNyitL{4F+t~^v9E8o z?+KTL^Xc>`HPCH3n!%55R1uX0*kRD^u1I2rDgf(X3u zN;RUSCHO-KciZ)ld|=dpYwNG}Cv691Fm|rZOMK4Iz!dw^fxII4?r=7B~>r>lGtn+e16$y8@I%fajjqDC$a!&FJZp2 z%7@IV$)K*LZ|6uiuK$6Nmpzw;c74^Je_nc=PEnDP<^aEcPK<3vvW#)Y)cXf-l_2Y2 zs^43g;QrXwQ?IZ{PRvh=jy@N+FN`*PSVEGr3AFm&tCj*yH;DkWgRix;;%R16X!ttM zr*XgJOb^(0=b}TI%;Ib?cdiz?)gw(6<{#N3t`_>7Ee32n@9q(Se{iunM&UMVlMi|| z>r+BBl=?bmh`kfU%hzNZ%w{0SJea!jlEG;EudX>%$t;c|MzkSDgr6ZNE%ct;^Wj&9 zw&`eBaZ1w|Pnf5L(^_80gF5itF0Dx47MJwdFwP8MFM9{Ao$qjfKXoidg+H5Kf}cD(c?(zQUbe;n~|| zG4Q>ii$LN&3jj#!nI(7QxG2lR$9Vo|-n*{Tk?Z$&UyPoLgYdZkK*HZ{houEy@3^Rg zg>&owK9KbW=If>9l-j}6d1YZb-w7%Hcg1_64uPwp9L=BlkI4Yy&{e^v+x0)1^ zmt4x#Yt&ApH^d8G5Wmyo1m%&Fk-ikEf1h$Vdi%&pJ_a0Go*|5YT*f@L?=)vJ0-*&U*m2AH~ zg_|pibVY>fB0B8hLzR_vRco^h?9#zA7VnWorO=xvBX@SCk)ki9H`??#Oj2NK@e&5# zXD@#_IE5G&_oCW3E+cNrQP{WRU;MA15f$S$+AiRQI(<#=lV1KIbaN#8zbJ7CbcC_l zbSfXH%ZJL{>b9x&js%aqy-FT_3b{WnH7_?WPCG}=$av{}VI&;;{zlY8=`{e->#@pl z5R@JPwgR9#*2d(i!xl21TN`9SFq7@h3JPzsu(n0Crw70J%G@H`L>a9QUuXvWoN^YjSB>0xck>2$=<%|K8T(`?q^gDbeAIYm1b@#`AoN7V zXphwfq6gy-rOme&g+)AC@>dzZOcPNExpkrONzI^iSC*FX@RVZZnZ@JvN8V{ge%${O zobqZWx}(~;N7=IG`3v^z{!BsdUyXbhT`>}ru~YHZsK7we0rAdLqW${jbgwX=s!l~r zf4{8P#W2s_yhT=l|AoUd#?$l3i_lZN|Gn_IlHm#YXcxJ58 z$al@liV6w}E%9Ru3t#N()7$sLH^d;tNV_rFh;J?a)Sf?dTb($t>GYYaJxa|Xto*)t z`@xi*vG;1$2uX_bc&JIrh;yq=Dn=%y-@0zwwQ+?_Rt={;`FR*GNHnbX=QAL|=JJLU zQ07^I{k+)(Gjct3S=Sb9`?M-9af?{giWDU9#1&}zh3|b4W>DuZDE+wz3sch4*^ib2 z+Ek6>f-4IzMIdqEwBx~stF1uQe%eQLdq3i5D`53w{7G7^7lvM&tJYPiXZb5ize^{= zaEA8LZx~?Oi=D=wzn*tTY1Qs7{-C5kr+HBNKSDnYJZTt$3>u}#gjKExd70@n*BgZV z=Gd&aehT@W>r-K!<-0eYThb-=?UX=C}i9hpx+`}lM&XH~Y z>XbGDwPKN{0crSH>9asvFL%1%Zm7Sj7gD4UDgB1=2qeJp(U@p`NV7b!l$+rSJ$9N* zqTu&E?jK3C`CFT<7q)T#nQoO!gm^S@2g}V)&nlz8p(!&0I&+OYYl8XR+l^}+M|!b; z&DMY~)WUatjr+Rvz1RNPb>aqivivEplSF=N6v<_u^<9VoUK1g8ThAN z;eg%jT_!qx?FskmT{g}OaZE%IY1OE~y$f2=GrT!TVi363sYjc@BI01u7TAdiT~O#7 zeB+T!!9hs^z%hJIN~?W&Nl6J!uAI;zH?|FLxqQdwA|j`K66XsL#OAS^`KlJJG1ORDjr32mGuR28_s&8R}=~Ccv%D7@+{BKI`ZBUtE;FKKr747J! z;=0DLKhdU1!)3St!2&F*SeZ|8)-`-g6d%G&^^2>HX=7!$iHJtyR5Vq&Qv3`UJgUTP zT>l0R1uWx+xlSO{P6ZL>V^LWV&-Ctk%vP0;FL_uonWHT*Nu~V^civzRPU!SwoVP_{ zNiu40E}q{FCu+u7@ezY$!sLGcu5==k3vRhqQdXjn8XKPxYi(^^%E63xaC_FVlmw86 z0K)!R030i^!~~4%`;^pZ=lX^OZ<0GN%Hhv(OMO2nVr6F1C(ua)jLbQ9ukvHaFOHF| z>=A;Ah%_O=s^C~oyelBDy@U}KMsVD;Q)$~e%WPv>bMU@%MoC3b06}eiDm@G)LpyT6 z+qH$T+(MF5zp7j4lKi?wn$XmVni!_q_^S{rXw`whY3z^6&V5sCR zFixD(#!lfdjh=6h3cBw9%wo|SHt0Itl=f?Kq7@r$6{sMcpOYVv*vlJy<#n`7tutZQ z^s>-Ac&Ocdxt=b!j~#MXz?<=zEITXfwCsa{V$H@Ky6b_ckSI;+Zf*^}{3aS5k|aG; zhLDJU00E3N3lnp-VE8iWQnlX%uf805{yy4vCT9F={xzt2&}#i#PLFLi0eHF;L!@mB5{A>_ux0hCNV|$nMQ!)r5{e@d;Td0g3B)S>&ap2pkJ$+ZsWlg}(lX zBe5c8CP{A((bj9ULH>(~yBh_LGPMfkEb<^h({21ySe-a3Fb?DOK%S#JJ`M*q3me^1 z>zOiUrJ;_0MWj^dA!pZ;7d&=Ya!Rf_R#)lgtLRhq0{6n5u0EK2pB9^%$@S|;lt`JG znPD=9S=W_+F#Zk)5cpE6GD7xT)AAWtWt}I-lf37vM+ACB+g!Hv)ZRZWV_!{LpJyCc zG7H+W`R(8od|rf-dve{O-ykmE@m#t$J7Z4VH=P@*y}x_hvmAaAu-CK?0!iCEyY{)a zx0T1-TXEeT@3?LAc;KPlSP$^9;Camy3alL*3}u>SQ?GJ-^qTS6Q#Ol9x`cKf^_?j3ZC=o>I>nr5qlF#ZZIoR$ut@Oj zDZdXn{#s!X5(6Ad#}?REfO`twQ9h>9Z)5`a{;(xJCI!A0gZ$Amr;<#S%1#nP_w%=4 z?>gA|;ikqH#RU<6Ogy3CNsPcd+NXvl1Ywzbd3pURDTzo+OY1XL?W!~olV?cG6(R4) zkf59gz%7>OtSg5fX>P0D_{LP$uD<|TeSLE%MFEBI%#=NKa!rpyz7UHbG6ZA1>Q^MC zF|s6;Vp2d_Lj=6@5gn;f+|1QtLVhnlVr#B2abwLfB`e*qmVQ=(eHIs0Q%GD`%M5*L zO18n`(}x^oI;cJqUS6sv)i5*tGmgueqYpJY%HmKZZA%*Nk^nKOq3zbsUYmT=rqrxSSaHv8QP0-WkHflkh3{K{o~M|d z+;>UkNJ)j`ht2}cyGD1z!yD71Fx7S9^B`g9M7lnXdWEP@ppS8%!rBP_#G7ZTQEJs; z#^>$|Gcq|=xA#tjDB7AM#%?fnB?rAA-pKNw>H0=je8(1j==q{KY%;B>l@xuhqS zW2Lxd7i0Rmb<6?8C<@yg85%{ke)3^f#=Zh!PQsp1_} zDw!m5`dn1#9=_E~9c{Mtb98iH`C4~VQa}kfr!nvwlt{E|Z*14Mzs0lPuakb?ZA2Xc z=!c1evD4LJ#?XLt(Ro4d7l8Xye8eSHi`AJ?f*{0Z9aLb5->ReS#Ck&`Y4NSZ?|Ljy z)kwTChOQKgEjJOq`ThO9<<3aP0XG#Ah`eHU@L#X*fYA=vF_XY1;)a8a{rvncF46Xf z;E96o%fqT>dl?4wyH4Ok_gpd>u0ahS$d(5XXUZO$auGkjzLVu7A3Z+Sh1wdFYmD5J ztKs&t&fUiNhJi6}yl+(i`@PSeTKr|ba9jUKk=1OJ;ZCnn3)y~~!te<2{#jS9w$%ZX ztDa6LDO2M)cw<0Qt*jT;}%sTGCc zqv-h2oec*>^}*BdT5%677HAd)pW;(D=9vr1Vji+kZdRLb{C0~h;nBRpFv-n@i{A-} zm&Xg=eL8+J*i3C<+AhCsP1?%3Ekl@S;_a*^<1@l>m}6IGbRM$B-u4{VXMViA@hJQK zUHEobUSFs5y^h7)YkzXgBrcV~z!V-{uT73H6kX+I_WG?kO(hTJ!S?sagY5KPnmGeT z#&vhPrVixCJN~S0w@dp7_?^CaI=ZN*1Mnz^GE25!qKRK#&m-S@GRy4fK*^HGvp0!{ zJw{ddFZ^#-SXDX4yDqxQ1L7}7su*jr5_SpRaPIvQ9icS~ao7erl#y$nvWU+ZM;1 zXtB8ZjQ)s`3jH+9q<%6imLQwYj8r^+O7OXQR&ub4HX(k9HTg{6>p=|Sb@=YH$1Q;d zX59s^ARBy!(&<-?EF#;f$+l=To9Q=u`>vm@UaloSpN-QeRX|)_qZ7pnD^4%^#GAeS zzX*G=b`1OuINswJ+lYpY9ndCRi!0T@skpFDP}`XvM~M>ubl!CLn&TM!Qjve?Wa`q& z6RO}#jb~F6s^4?@?EPk_t+ov@vlxTcw z0El}POaailf?Vq5qtz#Tk!OVEnXbfC zd1a^!UyocxvhhKXuo~BU4bw!xq$!^$(t!cHZekQJB(0&4*ywu@qD*LGBj2-jj1q*v z_9aG9@9P`ht0JsF^IeL)W(Y5d&8OnR=c=b zXoJJ#tDQ6v4t#YYne?4(yzUMcAJp`arBT5otRL%OERQFzq*Q?-DZ&a%**F=yTo>@9 zN}z@@u|Q%6Pf7JNs;V7pU}Gz=RUc#zmKKG#f3s3vsWZ^g(y_kwo&UDzpiJkHPUFjD z`x#i+f61<&p=cTg)QNei9o0t-8K}epGnrWZj|*rOB_;_ z+G_g8VPn-s<%bhG2_xth+0~b2xF=;i2f2S;eZ8yQC+&4x4O45RDNl7%?{e>3OhJ$B z*x1-aiwa4CAAreKD+=!tRT{(e^X0oM;UjX{G&_bhR ze_pnZ8Q@Adv!b6{^dbVk0Z>yA^sA9Ie&@r=$wZ_i9==slxm_8qA|#HrLB~?0)qOMy z>%cN~ci`6G%JK@!%%gI(|AKfzc>9iGIR*5shF+n&^@&L_kvANvB5r;{p2o&)z6>8F z{m(OfFqSF2qEE!y<_TG6I`VG9skP(mJCqh=hcb2b7U=0hj)f zyplKmyvPm@)y=B!+1hg8my3Vg!~yxN$=MoJ+*Y|<%0A=&=m^;&!i^d}JsB<+bzZpl z)T*7lG!j^-v%!Bs&%-KbL|(!Xiy%)1AcAOD`lKxS57P6^UbtB3c#rHj=e&bokdS_R zj!JW~JF?bs-kgFO+#6vk>b1Xo0%l?uzXNJ^`K6bSnv3f^!DPBRnN&)Dsh+nP=J@Ut zs$JisrE?!6Oqd_clrfs1qo;0Z9IrEb#mGTArNU%hJV)u1GzQ3>T>sKVXfiD(<)+T3 zGMHT;OlVHh|qV1>)-nS%Wi@);hh;F>? z?b9>|yiSMuc(fbaM;eBMQCfrkNe||ER}Ne+yTQ6BTs0T7{Riziq-LJ>B_>8verbjclEs_*^Vn?nd5^hz z7?_wP(u0^KLS=Pkyo92OVt<@XwMz!pY}z^UDB?GQ$^`x&Ls(mSA>lDNi_gh{%wqf$i9nh^Bo{TngJ zJ1H7^tTg554@asO#9h7?_at~08tg>(cZPy=^^^+N_8GM4t%*s2i+AqI_9Wl~3GG+8 z==?uR?M=^uF59`z-allhzF1u>Ep-9DeY>vmU|a<&zeCZjGC}W%K&Di1P-qj!uK-vj zm@OkmtDA$rRF)E<(rTwt?^{>2$D+vjP4;eWfnWJzgh|Iz~!kT_RfYGTSTyzY`yWj4Tyn(;gP%fiG%h)aQV zr9eY!-6#!#^Y{<4g0Ut;+hXBBqVHdz0D#5st zw);-CDMA~34LVZqg|lZL`A|NOMJ0H*>si8`R;S$YO>N-*?JaM`ONq*;sj`fLh8{0W9>|9#Ltb*hP#X_M~cFQ=?#H!(<3Gu`rmfT{sCR7C6D zri1X8k0#`wI6vn&T2ud|NpdLT26Z!Ohi&ymWt~->(ywB-k?4|eb`8ueEcsqhCmDPV zPC;k0pZ)@Vr3!&-R#y_?z;rZvm@UG&+7!Vm zQq2PL#T{BSNj$IF1h!HAsXJmA(R;Rjd|VTIwCWD$Eqepc_YjGUnUI6u8RM*p73gB* zWoBB3d|jkdC!Dd)XY9&m#ZN4>Vfmeid}VBtAn;3JRwsGwOIP?vOpYWj zwY^RTOlzTFUf*Cr?o*^fVJXk+D{PZm&Y6qZ;LlMBHq6lAZlU*u!)Cj#x>w&;lW3B|^hOTdEK-;8^$DS9>$zde_4E2Zi+t^Xo!NQq z7WZ#jo+}+yB5b0*g51u$?7m>@>eMgVWg!6a9=PPDsx%`9d8I?7KrI8L34((@!d5tt z%`LlQ8wUg>TDoO~;{T(|!IdB86whGlt)}K?xeqGmD#ZY*B!kI30ALUYg*q;>`#w#+ zgaT^RZ3jptGQ;b-&y^kh9GO(c^!!%x9T3ZY%E%sx0*Mm61Jazya>y^`dY~Bm$V5sG ztL5J5DkISNnx3grx^9KGP#3WLg!iQY3Eato&;M~hePNo+az@qfN+diGQqr+T9BzlGx#)>j9_ZEjUoRfcPDzqx%M}&6)4ya%$@iY zbwe|1&E^yhgp(#XW0#X?DtM$USZ?nQQ@off8Vw|Kh?$ra?;nUC9Ry=c;F5JQEj&o; z$pFm}l@)+UgE<|Qs;F4@P#TwxTa%ZjM5t0+ZN!+bUHi zwa)~`Zb|QTVIem)ZoegGWwNahZ}UwTLcou5(Pi?}?Znb#t#a&EJ)tK)c0qUCym0Rc zC-WmvDqW~9f2Ajz`0!iGyF6+5QikPca#jO^oCr1at?lf-MsG@m0}1j0HLrdZ0uYT0 z=Dywa*a8B&*ZOp_{t!*0D z@Vu+GEMqp`Kdx1kixM;?hmsHRI7l}bU5v%TU%jf=AnioK<=OdrMsFK%fZdE=>(;uP zhEDFA$p5if@{N(r@zK%$ZL{m46qAkFEN$xPLTZiRxGpe}q6JgWnx-c|G6# zg8xji!okIqN`)k7ABJU8YilI#j0j0OfCuOk9DfAXhtyyF+8M~b@+DRL1E^RV@!0IC z7_Kj^%#W$-vWTgXRzl+2-D*P5H@m*fdgxu>+|px5e%{2-X8q*=jcM4guK&FW1RzqF zd$D}c{Xtyok{;h1QSBcQ`I^ZuD&yK|4axJ#*v-&XoXK-$$#k3Oxc!;M9Hw>q%zg(= zv1ID8m@~>EFeI0?8#X`2H}70B@7>W(-8-y2-?6g$c7F{~aDNvRP+z47{sS>^1es4k0V36ygp)kxkpX#liu~eD zAoq-om_tExx8{lipBtO5<^f9Qg(}IOh8Hy`>RR`z1C}~{z}n7^~nE0n@BpC zrD(>)|jp;X|e@(bEv%8#%Bj_?4~{v5z+J`|2_P%|-OB_XK&12@K7A z*vOE0$Sr{Pbvrrxt4Ed|Qd|=y&E}BOQURkz;80;d@?%q z!R!apN9QY2YxZ~`SZ}Xq`-dk!QE6%9EKj?7&5D)GtgIrq^!`UiUQBl#IArwO+OjP*ev-(3ST%Wro9jWu9xlA{17`>8bNsef?4tPWmt{wgK_-mVk znT17_4KUJ;Rp~mUPM|`;<}Ki`p0as*q{l{v7KM30MI@D%evuX z>b2)!lZT#PojybliR5GXfH;mRG^tt2g)9fJ>Ay zOtw^p)lc|0%v(ZQK>%av27KS6T00{t!Jv9@9w&DZ`lAubWZN|J{G8DcenibPykfBR|9tpha=6ULa!IS#6Av+xuNACA1@O zo}o|Eqa1!=v)(UJ?*Nzg&0+p{xnn4U2Y7OYU82ol*Ke<4Cp$A^rxhqPgp{RDhcfJv z5^bD>@gFeC>$NcsTT(~=h!Ts{YTHcu-oEXG*>hlDx4ja>6$4ZSr)i{Eq5qEmLG*5@ zBIMya??ee@Idr-`Kv{-siG*bpj% zxQ3tk?kohqo*aq%`SkDVbgUxOl3N@$?F#m*n(<;~8S-^8pOPyYaJ=HXcQ z__Tk-Hke}lWzmqbYFl_c^Js^&ViKbKm8Bcejit}lp0L68YwX@UiZws2SfmJUnC?M8FK5)%TeF`MIGbip~ zh2r~BJ$9kL8@l~&*tKiOltK_xdC*zrBtWWZo&tZE46+XHhCf^R?}gdo#TyTre5whC zSQ+!XxBh<(>HQQG6@O=G{PU*{+a!qLDdPJxEhemQG23@oert`VKBsahXdWyOs&G-^ z=l+mB{M)iqw7b_E>8g(mA!2v6X?>}{s~iIkINqzhQg#PQa^QoKUz9%kjgRu+UV3bB zPP8X~UPw@gR|dkf;twFl_u(wh+l=bJzK_R*g=_s2E8+XkR(_1^J0Pfjz!~H9TP#8H zCWI%Wd>s>XgX^(2tiV_3_e7^eK{P(Ifud2n5$bY~cR%KRwO@KIW#R`_7DRL?=YIl@ zKTt@?x#>@0agKo-&EcGhfm#%3GBhf58MA0cQ>3#4x~q)MnOJ$AW)1xjdHo7XylKdc zf@!Y&7h96pI4jNX+eyl>5@J#X!*|YBK~l;hJ7KQoglAR01O`|~LsXkG7o?>Q3sjpe zT*S4#;bLP`a$n|g4%g<4EN8EY#mz3f?b(Z@nZ86`gyvJ@`E=B~Qsre0oXi!20LuD=T#>0JW!+T|27vpXa z#g~tuQ%W>QTca(1fvOD{Sr>QuGSuGq`K+%(eAx$iT|k7Iz-|Z`X><3}WqC2+~(9aj34o zdk`RK8<1gGHPQ}mPC%sc)>?Kzw0%QSD80W=;aR4+%59!Qc zsL*C3wroE}^xz<8i_*W^r}90jVTKnMElgyCyF$yIGn;I|3@1z z`b`f*QBF-#?c93(yjQd*`)`h>ZFr7hIeu+}`~z;N8d4PT9Ek}Tl#S}|Xh3m~ZZ-N) z-dQ+0J_cqHrHTF7P1E>TK+t)>0^OyjY#6r;KbALNNn(+NjMsolOm>5@I0V!ASCy*I z5yrPVGHHYssT0{N&*KXDlH8TDZsL1v^K)Ji!CRp>cVe=&@GhP_a0DG}7qsiU6iK<*e%R;y0R8C$KNR#$AYz zkSp->6d06rfMnX3OIP{j7-ER#Xfd3XsITSfwPQJe+g0giD^$(@q70m&-4WfjsQ-@L zL4&)_a0r~)v%xpNa>JM6T9@&a6@!Fo=6_gynCX+Kp(sDfGQb2fQKk+}@#qc*Vi_6L zcE)jkkj<+Z4+a3{c;4PKRIo(X{c)nhRXig=(Aj5z?)Kws{_`1MA!2WLb~D!=Dpa4< z#MbH4IM1nGjv$jB&mxBE+z!cA2oIk(rs_rE>Nk?+H}>#eRaMR((Gc!CEF~ikyd7;j zRB*&*9Vcfc7afm^p<%K?b(;rh;H#BjiA>|=&qj&=5Cef3u%fkXR$x;Fd^ z=c^LxL*}_WVu>}Vee8=Iwm2+Jfj@|<>sRa%l_t168a( zzvEwe8t#MOEXETUQ>aYof+0Zy21=jUoU{Rg=#&^PQ^(a1yhInH~MM!-_p*XDeXuI3Rmw{ zF$I0*%2xQqBNm4u>C`w>tnGkmhS7;=K)FGu@ZL#W(DA(%*kN~d6|^xJo2u1Nxh8xr zgyrd3qs&Tyge&tLXf!i2q?d5AtVaKq=Jbp8n{_?ju>2Lv3qy+f`SCWkBKKIMmoD7enrJg;<@*-#b72q704NZSk)KolD(L-zM#Xl zqvOi%suJsc3~xu;bCr#*004BzVL@otBg2brlz<%f=Rw#Uh1WBQ;mi==7TNgipkrOV zj^+0{ez{CuvIr{w4c-A2rQ}33t}3lG`=$36&NGu%TS(2ZqWm^Dzln-8df9sNE)o>W zT8VYJ`l+GWtuFYE0r37 zsQj9Nvvj(f#_$4cbJ+L2Ju3sAtDBn=Y2_aR+Ga8%5N)DH`FSL`4)UKzFcif000av! zU867_iKHR@W_>@-%I3=ezNQu)cGjjVNw}gaVvy-RWXS6*!;dE6G7UN?z+naR<4@Db zdv(}fOv|7E#*8h>ffBOY{!o)n2FF80BzWpVtrYlxL9WBamFi&tMMsZj?R@Dvjdl*v zX2-H0YiayRvwu=%uWRP8Aj{p$79u{0i)Nr4J(H;?hA#2zKDoc^4p*w8F+`r15!+P2 zV1~!!rdszn=Q>H=fbkVH}#eEBIF(dU;l-~-hZ z^nwF|))bq%SmL_3?lWAczs*&)*is;Y6sM01=O zz~d!La%u!$;<4aA-IyO_%VIe|*57{;{QDamtl%A01O2p6FaglWhkXEJ;6uMuel}J- zW*yx{wKf&J51SM>GejA!_FGXO{_9NPS`Lt(I0uJ0g}3?8Lxq3*M6vt|TIg#|-j)nJ zeDhx!kvZ#c~R!K`+8V(`FPYR}-)j$`f&fZnFL#i)q8*kUqXxJt4=-ae~ zg?l^VOzq0>BKyAjLgjyYDMPS0fFx^jf68dVH_w^!%W7o=>}V0C$8tv$&G3N;s-M%p znL~EFzJAty3*V1h57ZVgI`|I-HJNbfCNu8|dZ-4(`HHrn&6HSjf@~|XIRsas|5Yl( z^3mDkQDi9!%}?vc_?gm8#_D3};eD&6-+AY zEw34xc!GwA*xqeC@DudD#@L!3`d#XSNsOY0>?>I9m20PR9F2vtKb3Nx4~M!w>3J$UclRhpa0`3?1d@I+b6F!yP0PdRCdzSk&AUbR2N!x$P6RAr@# z3gj|A0B5isZP>F8z+ZHKN zWhnQv&^%8MFowo)LONLbJa(9(YsNP5L+9kpTm#vS=M5s}@JNqk*xf6CHF_o$vwYLv zms@4rh-;2)3G+RxZV{p>2Ce}QquocOkt6Ma{d%kWcNe)`NP zq1`?+sKn-7mS+!7j5`ea!}+TD2yj;&cx%G9;DN$6S<1{>H~c*&irdqeUaI~$*wWr0 zs_vX3nZD$eb1M6PE1g&!n@o>5`Xn&Ke^v0oY&k;X>09;H@UvfJfJOmv-Wota1b zjpQMD`z<>@%MO!i3J$=CYKy0T0RL3P%QKgNjBR1ulK?xQ-do;NQ z3HD*)*wASl1C3dUc{@rb-?_D~4a6SUd5+B_DAXSO%pE6H{?Q0E<*3sZHa!|PlL2W= zYDhqHE2}X7nT4;Ha=2e7XiHpE*|QvuFdnzq%}PYuby(DBlIa=or(Q)wMC{k2SFUNq zn`AkAn% zwVKP``o5`0duW=!-H|FX7)+1_79z<2rT*QQvIR?JCg>2aHOufW?A*+eC8-P_cVs3VFi%U?Sf>);A)fLyd1nbFEJNx|axC_$IZLU@~(vacmQGRq#A# zf?;kYCqWX`S&dH+b)B(#32%KR?hXe#6W<%8T8c$!&1gxNcW;H-189om_1^UL z^eM+pAEYKBcoK13muldoYJD3W9M#eiZ1$VdfzW>er;b4@Mi}AUQHnFZbAr|&s}0j{ za^_^odPeQvC6#`zUaUv5d3IT$!fG7CTM_S@E{K+6xCai4&)*U-dpYb=z%H+@$_@z- z5rM&20sl#wTm@l3q#0y)xCzYi!hm;ln)$^A031}-$t@z*U#qx!Nt_t9>6SO#_!yX< zfAzH9OQJES6o+q7SFE6p51IV*0aD>xzQL;rXlkzHv^4JYYlYX8|F3XsMil{^bqLw( z!NLAgfYEXh`6Lr##ZOkkU4j{`oO6*-;4(>MItN|H)s?)~sDYIl^ z)WkgB=@^z4(GS&?(+>e4Jq~1I$LqJ{W7Uk)mq~;P%2u+pz^O;*u^L3|EI-zEo3m$~ z-s|DX%wQGNPcL`}FKTaJdFsc=r_pWJ29`8zoq5GQ8>tc zo{!JzQOYHVE-tLb`wM59ydn5G$hAl({QIR?FhQ}Ln;S0z7c{ed`~jqq44(z_^^ajV zK+R`4ALU)ye*JnZJX4jz0i9QA@N4SAeP0q1fa2nqo0og3r2Z-jK%R_K?K7;m32-v=Vi~aL==l5ccMUJi*z;YkcYMTjeK{vS zs4^ONA4RZLU&B6lJbsXk6$`VQNhY6oAvLR5B<-vb<>da4qD_r^>m+A)aYgu>9PgK3EG-8PI5i zw`GXQr!y-k2~Wf^cO{Spe3*fA$$Uf*yVZEL2GenD^E- z43{d(sIun(@PYiWpWO&qO5j%}cp;8Kt=#w1MLLZSn?d&Wmp`1EXGTn`Cn|)NzuYWu z61*r7&V8OqVw#;?`ogWo@fL5V z*y1nF6#u>1m&RvcJE>g5*Dr91^w0S`k5TUGbHVX+jj@CZOP-9bwmy*EvS{^IjAxm{ zHivs>K@7c*%UjBJKl%xLtZ}+7my>MxNe4@*OZHPbrV3et4sF7{H%G~j_RBN#`*l`V zO$G2Ph0^xherf*Q8l_s5WGczUA4eF>&?y}H|5REygcANxwH4h$1p@M9XqTlNF{q(z zw~&;tNL%bo4RPPzTJdv}uD!pr@}vLPT0Z-*Hv9Ti%Ggi7uH(HIbB^s93pzuWYgVkO z3R2EZ)yZ7+pP(p4DZS2gj#}2Xm8-Cfx*N|d!o>T;V1xGsiqdStC)T75g=dEnrjw>M+^a+emqaUNKx=fcnhP&&dbu{Y% zb(n2PSZ0}CrICIo$<4btzNtGs=Wf`C_gO(cfkQ`OZ2HX~83xxB4kN>HjZp&{#`$GI zF^qOI&T&$&z02*0z7?N6YoSB;5P zA6Wh)uU$+s;T!@u#14wwp>}5_nnoW>5tA3nuPRWXrzYEaJt$|4<3E(pSsgM5!AEjr z(g%Om+N6MIqIt-#d+^ENFlVvzOz*qn@a#3+KrqOcIy_y``?7h1zk6GN5;;t_aa^u} zV@_3 z_9v~ZLne#;9yN0!3J~+K)(KlCr>k0fbF02^zSpk;k?yOU|p-$q=P6zx=a)RMMft#iLV8}+K} zMTH_an9ys2jr&EA>$Nz=(6P*FhR%yyTRNE2jwIwRu%G!pC`@!Y`ytk*P{i9*Q2dkS zm0~RPM6xx%XVnW%?oI$R+O4g_1*Sb1rn~*3|J?{1509ofBU8UL13^CK$~`k5$N%IS z^PJ~HfZ(;ghZXV&diT}*6gY=)6JdmR#ZUrqB`CYD}p!OYz5hvgP~ri}9}l0gkotqx~xwvGdOPPiuU6i)E2 z?yr)czd;5;UM*(N5QOjfy8f=wQN|NQl#AYRQR!3=PNn-%+u&l!e{nfE6p+n&o#+DqCQI=BB>j zR~kI?b|I6PTa1K^3Z(;-b;%R`_YQwq?`8D$_1*7=QshaCO_AQkaDd=Uh}qd(e$9u6 zgQI&_6=5rZdK2rs?S7FI%~0w+3yiC=?cEb*z=uRekTJIP!YXF%PnW5%%d3v z>K{0C{w6$Q3FVP?49y)Y5?$mqT)%o4YISFk>1+tNDZ2M2DUH;6c{Xl^rpQ-F|3_IR zDCu9vH-@e7dB>~>G-fo{D`6B{pi;pPGv;&K!nuAn4OaP?=n_OBSlfrDVNEoXal9JI1gR!Ek(i zEA9F);?(5(!0UU_$ajB@hK9>%AEzrRhE7u{;Habqmvnk&#C6}la9y3;Pqv7m?~?h3 zFL;qs8TN_9yS!VWsgR5xl!zv^qDW5N!o2p+?=XKRdV2)lm#kpKwNG(U66w-rLd?nA zBjgwa|){ zue)d*Z-0n6J{#1)weuJWmvgY>$swB{&^w?PLm7$n=%rpl1d>(~$ecwAw1M69jaFpx%<+WOIbfkbeY@Tp|%%l9)>e8tq%X<1JZ#h@Tl*`f$55#r-Al7)xx> z@pLXfgiw}D>WoG)zqfb9Vfr}7Ur1=gt;qZxnI=-(bQXu%Kw~pF;7f2CLeSZ|iceI97W8Ak=*@F#?kk{yK7|PyaZ>T%aW|ysk`G zSUbheeLC~^Rvp6Xl5Yk=12$Tg3UG1ZZ;7D=rxecv@G0xj=RI3M{S_C?qQtN>SUEyK+c}}yWR~&!#XvesFiP1PDAD*xQzr;%8B~~iAPv(?n z4jm*fW}9nRc7ISPUF4*&K?zwMoEu1OIaI-xjP>$!i4)agS?_UTO{(wkPwBVuNoGUd zK0bHyjDL=Sx~0*qcoS&6W&sRhVPvNN$+ z9g=mEA7m9wf4tVvYR3#XTQyYxR<^IVBQGtS2#L!7E#2>0$Z1;@KVl&{^B0Z-I`01p zBDrIM4fHL$WkWd*E|vqHrDTbbdwk5oMZ@=lQ$^}1y2w#Y0hiP7SbWqUaz$@C&j>u4 zI?fU;e!3vKuPPfTP94JceKv^4(Di+oq{lf#&zpwlt4{(Qy0-p?Xs9uZmOmkbJv_zn zSyvuHN3hrZFI6K%gsgHvR9cNK-m9%|d;SRY1nY-=q{D(Y{8H&#(22tN>#W_Bb+>`G zgA-dP-t)&AI*)|LVQ9ptBwVWB1i)K?n%=aI;l)VzO@r#&KjmQHxO|>L{$F zBbB~EZQ7}6QKszgns90k!>569_Ehw8{O@L)28p{6VlYb;q-BjiMbJ4Ll6m)qe)Z-L z{(kI1_qrd+Bx=ns>UWS3l$_yIACIQpK*`Y+iuQiR$2Rrzdwhb}ov{|39~33JEZ>P6 z-b-U!|>UTgKV^>SiY6*7a`PePjr6W#R-O&@W`>T zrUNS@jThh`1D=Nq;Oet%%~rn0ZjM z_)V(#2Rr-^u-;JG7`cy>mnk{_X8Zo~MRemAt*81jy#JZT{&y>jN#A&AOj|vve-$IX z=jQzh+{j?w`BQ8u5c99E@^Prt&AyJlZskF@-&_C`vs94pi%v|zhSGLwfkJ=(otuOnpKaAkP{ex3RrAW_nIjXo@Q^_wxb%d)*Sr8eP zsVRDv9Oj*pv%6y>ok8{pen$zJGwcq5=)&2sC6I)yTG?&ngcz^q+}2l_fMqhKjqApDs?ey zc+|tLsx%W+_pag?rPAK(9sx78|EEfS_>%kZ3h7OhCWT#ukqR>sZAeNV!u5ybX}LB% zb8Q=|RBJ@UznhT#*D=)J(8N(*OGI(^4{-(~p?II8n<&jse@%BPnK)Gfyuc4%VtoA1 zosjHcgoVN_cudEqodm+3?|d9vYHJ0UMFPx=G{&Y((Gqb?f#HD}2P|sUxIMPej^;1$o>Fllw{o5uK86NJ%yclyAZ*?99-CgQLLh^MXI8` zMrwx*wFxJ9bnXE0oaWr*@#6Ct8VBG~BKZsmn^2`s4WU@q8(O*%RhM*>6%rFK=+w>% zzyPkHN4V$-)wy^CD7LlH1+VeEiNM1J?YkgHzALYoynXfT~X5aW3MTv^vBwyQtk0D zP$?DSueFy>KduBv)Fbj?P!yipf7Oe`hT-P+!_DwE1wC!{C~57ci6N0L&nOO zuE&zU-bF_<^)WK`a1mDOg$w)bBT6Ocn55JtWDM8BK8*%Y`7AWP9S{raWKO2NnLGJ~ zvsMQn4I+~ejaHEFg^gRE_%M7Twuz!$FVy=STPiJcmjBW@3rxE@X62jGpwP6Q=p$*B zT6sV0d}QsRrifXCu64`yNEa9DQNA5RkTO2RMH0{+-8B68XF`f3YTdI%jcI_{dt*qU z8Uw3Ak*KQrefA4L_=pK@oh{!-l})%^x%wPE(>bltK#nKCnf zIe+uC!t*%nFq3X&V=&iYr}SCjD`j2g_ot6){2Kz?wyKCUZRq~9`LVO z#$(}S6>en;z9~=dpb^%VtNXV0YOh^oGvPuh)!SD*hy7FhyA$#>GUpSI5snEqP1Vj; zcH9#dnX1PaG}|C$vvXzPZ%_%~=A|7A)!4p5=UAYnBT$-{V+m&#N0Atb)``Hm(7KMw z$KZHn#~hRCxgbU8PAV}1%Iei;j5gjadF&v4@xzfdG@KQtGFK6N)>5)sJ+u%5v-*o? zMHD`Fk2Ss_SG_-B&Rqr1ok`Nn!SqSLysA85#x~?<*<=yY@L}S)(jbrNUQaEgbSP97 zo>a>6HD){FgFpYGKz-&vYQMoQ_PCuNuoafbPzF}&F8zI zr<{)feVh|{#~98N6bWLCD16l*?|FyB=7?aIrcR#oYqq7Y4`|QlZ-1>A<|T;V|0#pz z0H&>)*Jg1ZoY+T?FAwstE-nU&K7*~&Qq>(wLtQ9i%{wjMpfU1kp#KXf6}BMt{5OXs zd*iB4GlV8381sa106iPeZfQwl26ttw7;9>3{&~dj48BpAT4NyzaE`CYfBcgdyCy)i zvtuMiIYAtEfe7S9qQJm}_7vk_*yiSY92cehu$09Z?l}Z-_W3IelRJdM=Ksp9!DA!BkS==X{h6(SdEJeYc(2WJ8T3QFB?{x747q{eED3O z0VqMnAFB&9JG|bf8>2Uz4RWL;v{IZa#2jP8f_|COJBCvZ|2`*Vz89o`%>wQly6 zow1j+BsJ%ktPWYEmD00=mB;9c2F>ybdEi{XQDRkht+|UqTACsSpPgSnGP=3Bsr7(9 zIzaCP9xI+<0sZ4!e?_0}<}DvGeTs|AVuM^n=}vkKrVdWL_JW5?cn_pMxGyEOQiLyA znp;utG&T{sHjl@P+Gop6bu5QTaVq+_H{PC`Ab@yI6r^wcwU+!6b0!JKnQrxTN)pzV zWis-t1s03?ft1HL1dN^9X4%g`zw&%o;s>u0qxzm9YoH>UG(LFq^k#HCQ>Et(|%T z7Qr~B-r{O&Yj0%v02MU|2|y~GN4%X0DladuelXR%w{Uj{2OOWA>;y!<$3cr5FAPfw z8MyJyXXob52h!E~{++CZuio5LE5HBedqQ%r`m#X;XY4KCaTO@8tLs2<^Ac;_s%9bt zoKO*?*xEy9@&h-*=e^yZ))N0OI1I`*r>aKTtxB?U6$C z+wcAxs_psSuiKbmaBTgvxX65jqxg3^{_vy7v(crW!gEk*;40MAF5De^ISGI9{nLBY z4RU{s(}MaZ%6pftZ={$XU?yiHz~hX-)1Q_3v4Zbx*;!Z458v1M6D}WhN~JF3qJeR% z&=;0$sN&R!vKvBdXx@teGEE;NAam5XIqy*sz?pE4 ze_tttA&WbABs08%6uMWXg~?=BaIVx=zlCS-0=UdtUWQ6~CGOcvxwrqXYG=$`i$UPG z!#zhH;m^=;TQW%kcvUDq6Q$hLaa^o|_4Evocg-AN!SOB7%W^YnW+@HXh+{#5zsGAx zz0lESLZru!uR<_guYN#sCgJNohn7M9TO{}%nnTRVIJDoWkwQHxe*-uJ-QOV39r@U* zW|>3e;5L)WirJNoeG-c3S6wU1X1|{7UFJAH&zb_vv0A%jp8Kifb}41yD}u+d6ZmW4 zvmX4**$V$8O7Egev#RuM0*}{jvGLyPT!k9oPn|e;FLdc$QqYkkKl3v2>M@HVFl&Um zqnV*YyPfT`q5U%U>V4;kh+auJ-N)-jAFr7yA!^*o)X0S1_-fpq({0C0K`#En2XFDs^ zL!0A&HY6Ux6!nUXPx=*RLw_Rl2wxa3!5tq^57i2w>lgHU+X?X=g%~Vq>JBt00m$qs zT`6={x73K=%aHk!*C3$0dwB(tfR*QHu| zQrz7A9R6v?u5!B;@a%UV3BAR*-+7*f=AFQcGPVl5HbZlN0|GOS#e_j4lCMY_9By(2J~3hpdP=?vs_@)!$ae7XOv&bnYF zTR*V#(f)7W5t>Kg7_y}`&$BJyZ3zPs8^KCSN>e2j?VpI)^f%cE2u-NxrZ+h+&W(?s zkgnwXc1_H%K{~+tL)OwmfU10yt3-OJ79-BL$hnyvsILR=J}gc}=RoQm59=%~GyMP! zr%z&7jVs?%KBD(}IbmILJ3T2Eh`_->3+wBr79WB>96A5bo^&}iDfcds*_Nh^$w?)>l9HD2ze zXCnT_tF_DzeMSXJO^<0;gvRHiGx4^VlmYK6--?ox_s2W&I4*Lw_3PA zn|@a-KX`2KMba|2m1Bn((BbuT-;en)x{n{?!bYnIGFnppJdLsuYow27Jt_>`sDqyo zuhZfIJ`7HO*T)YuZ(>#65^in`?@bprAs~fDfA0*(r@y^<_n;^Q_K8iAc_DEKHWDP# zXcj0nt#^yB*`kI8yy>S-|4BRa6>vJ#l(H@xQ_+fZSsA*?8RcpWcql!75jbhRKCyK2 z4+>FZ>R}j*QzFns!S1V<`hf58+UE*5ZhMekf?6~5Yz$pGhnXD1rPgo30B$i_tTC*9 zT@ZFFto}^jL`?Nn&sI7`i)E~52KriO{fY2eU;g(fZ1ru?u-VWDgp3g?_#afj86o}` ziza`@Y-nQQZ)bL2V6}@?El*1E7agS-Hux%Cn=Q!vmr;A>TykLYb$3Y9r-g! z{!|kdo_b`UwhkvsAz*SNB-F}M*on<^Iz_EiATe)!H@Nz9RU^Yl8mOpU##|cuv0M-8 z!`*Ear^EuTo0^c3^jd9m`eW$O$yRM9vwWT<@rSAI9_BUeZI{6t7uY<10!~uG4M1FR z2VM%b78()W%~QbX7g$hmfi0(4%CO=g=Y@`OM|nrpdS{;?)J|{&OJj`He8m7u&~Ez1 ze%V#hl>8Q7KE-atZ0J?hb&bM^l;%s|zp<#+BO^k*0l(h41l| z*?E6bvvvR6eg$RFwZE4Y{bHHke*Dy613{cSgtO}TMaPu!^z^hZKP7cC$*_01h{JKX&n3(s3m!+(uR$)A zYNGzNl5O(#nLb{btco9MOqvDlW^zbQX46Um)tZ8f(=wk;Xh{;4vf`N2OcjWc0UmJ8 z;5R5FEZS!;-{5`tKi?%;tS_5d7!ik58f?HgYT7SKxPQqZlqUg4ZKPT`;R^Mk)KKkS zcjlg4gr3_+cDJhRtiXWv_fdm-m^h@-jXu>a0FC3GgyZfc6|pOxTiH!zcV(N}19NrM zIBM`)^wFJcvqf^G!%s?+aZf-qq>8NRS1hRctLUT1YUmnnWBv)v(G-}d!5-g|!JzB; zazj1IbfD#XO+Gz>GlS98Kvm`|%~VVU1tu^2)o|2$oxQ<+7ZS>(#=drrT+}CFE!(>r z@FWQ27V@+VeSRhGh+~ZTotSl?C@afz;A^Elzx$HBLk9Wl)noS8zW*_iPuN!*UIDl1_3@11wo(40D`8$ zys+@W`@T{b{-=l+SWWt2h+U4sC}ddB|EY@!(XziF#g+%7+fkhblU_S*T#5w5u>j&# z_4VC%43z_yTg*w?ET&NF`!XV96`tCgf%iQKx-7aPufkc~fr`co z0P?_fx%FcJ$tmHggZG(K+SRAu_kk=x%0d|)79c~GXlf_^Hh$X)DY{^0l!|JIxo)qoht^bvf)~HK< zjS@K+*Wulm5SdI8d_{jTwzkadW7Zsc(fVfmw$CBNt&eTE(J~36vC~#VOQlq1lJX)n z1vno4rwzK8WY*>*8_wyoE;i%pBZ_qNJ@|_SFPN7-wr!uziV-9i9v|>*g-R$H5N~6) z>cxcYbH7zo*n@y!^2JX%GBiar^KZ5!?nM@#ax*0`C+Z|{f7mFOA3T&M1cAd@-#e|dmx zb>k@5$v8im%(p%&i73xB!h?kW;24XZ*`nVN@q36lD#wv~h$j(c4SsR-rZj%&GZpQZ zd1HL}1Y~FA0G(A>HAM?6YE?JND1Lg^cm!@7CDiWROU$y!PeZ^n*>n-&EL-rj3T2a4 zvM?+7VcI2u8xXMClTy1CbYJYtQLrWvCANZJ>|)rXko91SC?51UVCnpM>Dq}?yCH6I zN~+j3RY-oC%l+?5J%Q(fu~U?v*n6&YkIUL+mzVeo^8Wp45Bac_bP2i>nG2p z%8h~ei_wQSasUYA|4$2KIGmyxd6o+P{D z?nYSuWYzF{2hambkuDob(8v3^SaU0$k$pAy;C4!~09<=vU=+BTZ%BvvirBn&)0sUX zyNc+)NFH#|W25|OTJl?;K!k+>y!5xl6b$%vIK~K6Iwj=2W@RHw}BVuxU_g8$Ph9QTym;MNN09B67q$G9;m? zcHIc+J?uW`chFE2Xk1qKX~TPb zQZ@BgR;Q?KRa(6zu@2pxQ_F5dYtXbl4wnr#b;OkO0~!uv-j zO>t(jol4rS zr&+^&?o|ml=p8e}13r;EL&CImkNogX{g^St8UDcyCGn3v5Ggq)Hpinez{bQpJ-M40 zkHUSY$-6OUnox&riJedy+rRI;t$LVQ-(GJ%NZNiiGA}Wh{y_i(qYjs>rmx8DtPQFYiSa)60iX6iX1<6Zt7H4be?QQR}7hWM3l!khRW_UDv4jD&+=pv_At?8T#3x z)OzF%^Hn~Q6G}4P)#7~`^e{F+KEx;x!wnzCEG9)f?6s< zY+r}zSP|0AiCR`q)Z?NGI|q>2k+>&>*HQJJCe9ODE)^b5{@5pw|GC~9afNbp*`=C3 zi@K|$bL(*|=j0BPV~b%SV6vOe}r1(ngYn0QRVHmL5xRlc5}cfJdC&NMxm_^_P)) zT<^`AaVL*wHCTR`Y`Zw(uxKF%Of;u=;O~BgwPd=?9{7Z6N@~}`>Vy`Sott$>;}P8Q zEcPh9N1bIvhk5?~NkT}6ZJ(tFZQ{rJ8a0@6B3zy(mG#%5xFI=7<8s3I=P^>Z0XNCc{%78LciG%fD6 zRr740da}LFM>_9Al_>vp4#CH+zpVGSlXOcp-Gc|W#+@R@HJJpxv*uOMdG%?M#I4WE zr+{zvLw17M&?%2qv4bE&QTe^u5c`qR{}koHKBOZ7-S@*kuP!gYnAusb5IMxYkuNtJ zT3Vi}^|Ps8FJz!G?@&^Yo{y&M=?FOT3eUr>to9A}HIV<_D3CkG+2M~3xT`ri9ID>o z^^klMclC*c0Hl~R_K+^dW=HM;7%REy7M?tCi>;#?D2LxabDCj}hLLuusbpjzG_Gg# zYDM>7X#v_&i$hvSroZnM9t)1iYd`qOjKfgh)O@+#Ux!=cyW#RNx>r9`FX;o$>EUHg zRm^Jne~z|A;oYKncFXl=ybWg>%x7Fa4_c{>aJMHd`MBN(464llT2i~t5no?3b+isn z#_m-2-0MxHKi=pZFK&@V14ELAVYdooSgv2!WC!G9`hO5V9LDZguGna5Wny0aXzROr z187oj3KHJezXWW!=Z^`1g9o^lp9&LvH7w`m1IvgkvukQwRnbofog2A}kbO!7 zU;+M<`2T*pCVxc4+>E4n`C<~)5&$k(POBePo6h2xtQ->@EfzEDp#UH}!`&X8R_*wF z-0#F?&k3W0HV#HwxeA#QnL^&sa1_*Pmgrk7{}QuG7@&LPRcd;;FiX>q=j~1_0}!Po zKjn0v=f(nE_J}46VKJ{uR6N%UrSE`_;kqe?Z}6KbgQxPIRuRZ$oIM(km?H^488VS* z&Td}iqxs|$Ge`sF5@dxH#AHFZKbce)EhEl>QnZNbHvKM=_XtmmDG0MDm_aR^IJjzS zU;vHi;{@yDQpKb8Y;Q`1-;qtNN&jnmp*{@cqzI1a(1Za%%XvxZ5Cm>@YL9&l_jQG4 zG;1HIU02SJ)Qpc$=fz$zseTeNG+>;ey2@TN#=KWz00D6Y#eDx+wJ1nhnwgzW0$Xw| z;b}=zlMpnhbE=0pR5F6&1wfGS<=DRT67_SOgTC#_ZjFA;?@3ktxhR>K_6BHcoo}K# z?{l;{kom}Ca^`MdGRRpLoe{|paJ4pC&}c+xny_c%b_o<&5z6qy4LLzSrSmX{Avukh zE1sdmxxHU-F@yK=*D!wk_>{hT%dqoGPmLv+!U6r-&uu}9_|gbzuS?Tv=W4tiQh zNc7ely9Lg9rg`e)%bk)vDb4jP9{*D7g$TtHYXMw3+#eEWxyl-LjZUxoNY(K)%FF8U zjb_0~a3lHZ%2^)ab*Yr8y`JB-!*6)_BKbSJ!Ql;Dkqt{BpZRdrzukuKgi+zz+baEz zoz?~$9kt<#3fVIIN8R(8ouwN;=R<0=4)7hcL)r5*i7%gQx(l!yJSlb6N}9d$pN8>K z663e{)nlnK`7Bs)JQ}gjWmz`VzjJ87sdZns1it-j=B~h){pjG}uycT#9H|bRPs+Qo zZzNhQ6!-*`8jdT4jOEodLXADO)xwM%Y5IPnnZMH1*jeD?Aa4%nx=z#jcxDq6Nb@HM%MV^|1oCoH8{S3xa(eUACJ(Ifm|0i>BE}I^+bH1&lZntC4N0 zm|WcWTkcl6p=M}j57Dpo84d%Gn9Y&4mQhi!TGNEt{IgUFkqxm)m~&^VRbfS5)QN9? zN4SrtJh|iBk!i6Y5RaD4G;GQ5^O{ki5zkIgb~=Xepx7Np7d}@h8b`{T`DHz*do86;pXKn2 zbN2hZq|5%73}jo!KsiT)*(m$#QE*~Dm`WQ}hamHpCXVPSw*R{S9dK+fjGQVICBC{! zj3@s%*P*^aBo%9%iT-6H`5X^yH)?_RE)m`RSw+h~JQ*74Mfc4&*gg9TwCCxa&6Y6B z)@_Id;}t}#Y5Xg*T))gRsDMBso-s88VsurTbRwwEq#xiBKBhl95*DZ&{K#{yJNq%z zI`Ao|+5+=h@XIxTMp%(*`?>}KV&uTP1w_k{9Ehkp<&l$cKU_&D{A2CR_02jbjS!mE z0GGt*iI>P|l*=)+EL_2yC&E;W#JvS?^9q%*H?x21aJ~PtRt_y}mPfgebuI5{Ox&5r zZfmEYuyAiM)M8h*!oXmz_a{dF^06V=(g$X5Z7(=7zCIdTNCo+| z18bFdD$1zGqRg)+M3pvf5@bDXX?x%GVVG~Ux+~->9{DwoIyw^t{r8p{7Adt0j%rAm zXh-uv1l?{(L$cNQ+<4sLQXi9BYtwn8vThFaX_EPf;^=+JMIv0^Q^)gR zg6l4bNBb35yc&_HFojX7DTON~N+_OaW7Z;p1+qw2a!{pCO@)AVcyde!4BqAeirQ#AJTgA;3A5oY}{A^(hU`NBXM8D}h2#_C(JV z3s>;wwr!L^PFT^1FxETH-rXiF{hANMCCZ`FtU+_IYXgCLMaf4>@#K(C8qTf7Isr-J zwam*+6Y$R3?mye^$PKlhQr2AR)$(a`+hnX>@@X`P#7G48;91?D`G}C3B6S`Ij-T0l z7o{|a!#dR>E@dSY9U_wx@?Swr)l-@-yq%0wS3#=96f)qMX?hL^GI#KNDW;& zvLao){_2nAFSy{9$f_?a@6t{XeO)Ou?<6W3%IA0AsdmZBRvq{Oqo>@SR`~qXNWjMr zTeJdoegELq8TWLzle#*V71+KFPM$d{hRaD3yopuKSFfp={=vbCX2sqjj!@H^ZNwnA zeNC9zU*OKkWS=nKxN!GSGfD=x&@XFao?3}&=?3@lJ2_-3|f2v;YZHObEoya+R zfGr)5;n&!U+o~$QD^$(Z?v3c3X@&IW3=!>1x<&5NGY``)J8p%E`~!=HE9R_N5jn!p zgq_x56RrjKbii9upl=a@Qvb*!8pF5B>z%3ZyMu@P7iGV)aJOXqa-xMuWOV!>kZM#( zv;v>V@1wp_X{my??I(CPGp}G97qEXKu_YMq!oIT^<}n=sl($-(U{gok6pj}!SMnB z8M~J$jIGAimY5~qU;g>sDUDu=LPAEy!)36dsVn8L<(gc0D`n*1_L?fwC~ z8uilPIE}s?As9AOz3*PFR3pyVAEs7l2MI~bXS?X1?KvllRND+@S*72*!Y)655OzLc zVCm2NGyl@pWoG(Ppv{j)M)>+Ag%BK* zRr<_epBH*vdCB7!Vh}9UkpK6+_g-Tx%)x+a(jx0Hmv@Z8EiUt&gGB)l=d%Blhgn*R z2OHo^RawiC(2ACBBM7g#theau`#W=(Zzd}5aINPPJ&BWVx+1w#PLb>PsQ)kJao0U6 zR35slUzjYKvTk)h5KqBXRXW2_-1CCFiJ2gx{BaK7yz+|;4vpBtPzH&M%ekF^M`t4^ zsDPM8=7Ef+2LX)toD^zC_h6~f# z(*76^T4WAwl2N}*Lh^~O4KQ$TBG@@SM>!6+al-xvEaOXl$UJFHHuiFMYuq1Q@cbT$ z_AjE)XKQ93UI+b!##GW~o|+PI%8S-H`JmmnP~EXaO>C%>7JYfHBVTIIbrIcCXU3{l z&HFk9@w>1i!af~yAo6GP5QW(ualIs;A5rc4pHDvb$}J9nO!{0#qV9$rl&5w1o;``| z#B0oB2@$VB+T(2|FC%b*T@A9*V?D*lmTeWQo?p>`UX0e$ci!{ty7Yde}N{U3~}DaG}1rqPdjc=u}!^Z_XoFQLq|NrrTxrFc`lAelmo+O1>xVs z{S5rlvERCpPHD zysfFb;nK4((oBE;MulqmF4eZd>SWhSou*yiO@;U;<*$|yX#6Fh_V-SO<(4$)=Z7pd%;bK`Jg{j|nm$a`VLq%1!vi~$RjG1R z!k;GE)mEN?PyJdf*3hIJ=!xxh4E2?-n7pdeV5sy3Q=x{bZT6Bej||?jaDHLGmCls! zr)PNM6&%_LdUm;rO4yNUR+?tne!jhBVjefU&h6svTS$Ya_Ck1Pa(~CS1SHJzLT)Q~ zc3UZy{38;K-jDG1>lb+PfiQ5*n!3+o@Cp;z%(j|%cHB}S-jJ=?WX3~LJtr+EVzvqH z?eUQwc~ee?KDwUbVdq3&jEc%yABe;-#QU|=(lT6R)v&*?&){7o2PkPtqG7P%_SGtB zKw{M1RG}u3r1FK?T>L%B&GRdao6OFe#sLf*QN8kME}m<=XqZ>H?luOTPs}gzb=z3Q z*;tzbVWO&N?o)SEymNRzc)*IU%wKJ&iuMZSV#h2s!!sVkKWMB#UPzZ$>(=(C9xqQ? zJdx9=a`9-}KuC)9^fZt7-v)ymCSHSry|XM;g9F7Y%=l5hv89yc-4B8mF>R@D3Nv04 z!W#6A_a4^k35v}(X!rwu9g%T-zcD`)gl1COC z3CtcsX0HNN|IL=2_25$2&wxW+UX?Ls^VTc7>}5@7#-Yr@Ua3c6I@UN?W?1FD+}%-h z6}t}|l3*w=dbBG%Di&(`K5Fx|EM3f*WtSa+ZM}j4q1&W3S*~OyiOK;N;yy%BE#fp? zJUU!J_LD%JT(T(Kg2{e=|5>JBQ~JvGkr)cE*c&<%{bPT9?J=91k0?$h0a@b?!U^X5 zx!6)L7Cs`D*^TFOI!OkaLQT%Oj6NBi>Sb!e%FlNWokbiM5tTj3z?k-xV(O{n(PryG zup=mfu38$F2A!diV|Fe&(u^Cf z7*pCpu5t!`t-xbrtRf|^L0T{WQP-Gy5K3nIl4%b1_O|@348Hs>Fz}=saqR$gRus^A zfDL}B)En?=002<+9xC#wPn#Iu7J0RSp#3I#{4-9#sl1^5wvcljWo>9D_q~pCmt-+{MwF0?0e@EJM8|9c~x7^0ga|0 z)AZAK({3arR-Vhztxraal3X15PSX+7v*V@bW2RZAoN_FR5zCy!1!MIJ>vcMha8DhV z6nBSF*ZbP}OApywThc(jwf#PBk`T&`a6aCN+>wsSpnL-XowgOX-IcM=u-`DULHW^g zY7bO*v#6kA*C+}M$IwNt3_D0Cc=DUg3n9#wdQ+%ycANRIAzhb3U)(mSsLeZ0q+s9q zclc<@&i1a<16`TnYEG@Q6vk(XUKn{3-0qRFR1PNdhoqzaE-!1jkc)DAYlhtF?lj?M z*rY~q!lz4j_JDMVXPpk5X~*3f9*9O0^H*ziOksgtP%?cP3R-q-a>g1K%}90ZU}qhp zv8yZ9?f$n~uhigon|ZB4mOENQf=1m=TwzaB{L}22InVo|Trd9Nx)S^TB8|tdC?mHW zZQ2k~LGB%|^bK+s$+or9+jXn{3du&0(S&~RZI#t|5|YzU#hJw&QV;h4#*$FAGnUJ} z#hZRyQN`3s{?hd%7eBql;N}tT0iBZhcsmcaE!W44NG*SaFr*ECTE9gjml~5UtL|tU z!^2Rr{Xw)ogqu#ME&s(kdY5Qk`7p#Bb9RTbRK@tRft*}3Tu{VSQc}DW_pB6 z(+1X#OD~zO?C?Hfkf-`>E>;?k|GhxXv=VvfbOCZ!+m2yBglwjl5t~==_4DOA&iwAQ zxGqwtP^mQeiT!vC?-6&&#uwqWu5&+DTyzN~u#M`9*!+G2WMq4!#(fiA2ZJe5JD~P# zdVdVJaG(E(n{bqSwX|I?#VeFm-^af<19~phc0YErTbJb*yC!&->iyMj;x&SN@88b? zGw`ELybxkIijN9{!q-r7G6!08BWYmiqV@}MsgW-L{1c5s8lwlIn=X{QDI87lK|XBo zeLdRw>P0a28)((cy!X^dvcTJY>xOeq&tug%3}#R9J@^(iTMGbX0vWKAA=SttMEzy| z?%|=S>1Rz{*qtsMDb+1gHJoE_Im>+36Y@qqfFQ?H9L3W3t?c(6E!~3*!XqbQjhF1d z;k#QQUyo5mNphi&b0tj2izjUgn?C!%G<+S%2B2zogk{#7u@` z`%6)^KJZ>XQnhx#143FXvIMh0rL!-ti@foR6U zQoO^w9I8SfG6T5d(^JmwP#+d!W^BokK!82JOxY};Oz^2PRDI8ATzEof(^+82vdHes z7cAn5Dhn#|s19x1oOqlUC{eTQ5hi!yXm7hZ5%fR8lrfHJF;Cgu4<1P=Da%t0aO52W z(1`6lKo=f$2D1ofs8DKsR}T}EthBpjbr7_=H-Rn_TI-L6iCF|K$IL_Op%cPC51HQE zuqwDJAsr8~!0W;^&qXsr39wmDerxMi9wvsPZ@oTm9xP3PnrH!DjJw&4<`aH6f15QL zw8bNjJiPo0cl&mWee_3^?jfROY(3`ki8swZ8pDU|rQx4nUzwvC5=!Qi3;HAxwk`gU znOKc4P!=ioH!^Gnf$0#Io0%_X4F(k)di(qgp3|H-EAbwSWd(LKS0VY`j>n>Y9ucVw z($9Z*f6U}YtZ$7&`IQ7^^e*q{1!i(zQR!WtnGK<=$lQlQA$oybS<;x-3x-$oBI6&{ zc%-q$ldE8YRSFg4H+X$gv4qko7`zDYE0lETOUr05~zaaUCo5M5w$VJW7hDRy1VQH^Md7}*f{TG+W&-ZMwtbFyf z!1nVyN^6a7%x&<-C6+ssLKuK}Sp3ZY)lp3^17tKw?t5cBCY~sAx(ioM?&i1ur9YW3 zOAH2Dzy7)E-(zbBjV8bK*&bviB^fErdf0D?)EfRN?D}$gwyIFVp1tE~m}=xa!c|@{ zGRt7h73Jq;=H@V`-~PJ#QUg=s8dbXSncrJ6Kjs1G4H-lz!4&EK`LrR?wnOeR{9)DA zGr+ul2y!9PuAo%`8l6hp!d1*}f8xdW9jxfbZk}Oh(rqQpK55%ByQ5ZwK5Y5hPvFCM z92Dbue-`9EkYCbyPq zEaMEbQR@Bv3YJr|p<@!RNumI8ttWKD%14+#-#8$RchN6td0U`}v$faB(UeTFYDB5_I0C*e2#{1@qGo~cid&neqk0cR$S zbQk7R>dF{SK30VO(oYluYuk0(3&S|i#8wkPFXH4>FSM;i36 zs;jND1Ki!q^_?Ppdx|=dVLhxHsb6oe`0g1X(G zu52&E*hmqf*`a-XGmSjHI|0QO57NDXHb}j7TgSPKF$}8~`Q}i4|FVR) z`=_bdbj~(nI!s{Wj~PLqw(UKec~Y+KFW)2y+HGbuRs89yuUCCTBdCfkImq*G8cZRS z?+GUirpcsF3z)z$NDGyI{>7&X8O~w-rJDx(e;lZ~7rtV#cQ07BNSe$4a$Q#H*Pw2%XK;~4sT{~E^{j;9I_vMk_4at3**N}Vke`M z?i0h>9}{nZ4DAaOeq!($r!;f>-O}x+5aMr&EoV8k!|0Ocse(@u?2&?I!46vEj2{ z_l3z?EIOD=$joIDSAQp7@fof(kwoM8x7o^rQN|>yG={%jD?ondd7GsLeq8es}X=v-QfVJsNT3md;%v;7Z3pkUmv%I!J=HA;i zBp$G~AqSD`u<#aLt{j|c1~f8T+Api@`zCY>k1rv%iC+4iz-zq4Y%iF(D2!Qto zz%BMIK8D}=iZr`2))ZfQ2j@$$*Kt!3mW0~IkT`S03$<1?ZOq{M|D)+FgW77_MvJ=yDFlMMdvOb1Tw2_n z;_mJ)#oeJTE(MBP@S??wySvND^L}&wXC|4QeamHQxwcqY;gNQ4P_vA>+*(GF_6zKG z@THbIXu_V5IM3YY7nCQmF)kR}FsRTdP4L1ahM>-GYRJ4-OnM(a<)I8NnzgeaWm^Ws zJQrO76w;wU5#c=k;}Z0fhdISCziFNS|lK9Lglsmbo74It>;an^9hcX}F!A(ZxuAyLn;0J`xaP^})k8Q8Tyb9GE9i z9Mcf|F6Ql?@N8z4HiLoA{Sw^HjZ^+6ik#Qh*EhL!#&s>58(JVrfZYCzf8C{{!=d;CY)j%8i_x~@Q*a>Cg9S2 z54#;nq1jufbH>Eqbf)|@47150l`;p0E{iztbh#@eC* zXBCY{&gr!}t5Q1fh=GMptExY^#)qGp?UlPZ+MDDsi!DAl>i&E{Qle1x6{qdS+bu!fq+YZR7eO)hpYX${k7E9pgbf*>=S_uJ79(0loH!_X zhD#xbm1Xd7)GIgbi>7AWC(X$4rR$A0i6#{TsAc_iucDUy(u}YsjA0;KYDa^Gknba@ z&Z9_fL7G`<9%J(GZ^A1%y3S;eEL-6&8WkZu!DnJSms2x$>~!jm;Ufc@FzLC+sEM|M}s@^u0SKKp(1j=p6~eLaNE4i1Z$5`!=n?W))tvMSS| z%%XwQ1CHF35tR=?dLIR&IOZbMzL#j@vz5#Mn}cZ_k3zb z?ODI|lz8UMOw4fT+jPiZ=RfD(r?FOT_dLtm*{Rl)G-VO&RaYfC?3&afX)~48PAI(E zf8vc8;CHdNQmnuGJj)xCI)tk?tocatBmv`GV=&|4S}3g7MiFSNI5%%f*FGUdr&&uK zE!{PaxU7(Y$E`InHwgJ`Z|C>(<6<@aK6`^R-?1L%-F@9Y)4LMv&h4#F38{tT$#huD z2`%mj1nIPV$!_mfo+7E!%K7_eUA|r0e!LOJ`NWYE&bakn$c_V7a_nn!{T-}3Ud{ZO zYz5*kikF%)9q(lLVyv^^%RU)+GpR)!;~Xcx-U!=bgMOtsp(~633_NGhe)IS)tGE#o zs>Z*P1V1wZYfyHiNS8&-V33SN3}QIpLy(ai;7) zj>cz6o_O}Eh8P4`5o!lj`LRvm;nfZSb5^f`b=-ejyOjoQA1a0&CnG(8(1B95h~ zr156eMEPe!z&L%!myou?;-puQFkcwCQ;wKtIRxKSGOBEXMxjK1Lnq?PC49uq;OxQoiFZ;mq2V8wneP66lcr({udo_0h(2H7A8gACZ;3??+}Fh@yi1& z1=B+v3@yAfdt4s?(IgYE$2!srj>Ch^m)jfKE|Yfi$8Hp}B*p7&unb6;jR2r@!n}gS z*Bk#4hD$;QuzlVDM7b1U@?D+1gy1>^=zpx*CTgAxRdO9{pco#Dq6Qbanz9q74l+&< z7Xm1fRC@A8Q26f9D5`=ac71b66YH)+n)5-AY7dcKL)rVop=BX04@oT)2xjbr_FPe} za-c93;cvX`Jq$b*5WXHg;;ndb6ije>q-!vT%EW*+edxh~f30H0`#|l|$W^Mx^|Hc(r11J?HhqF+O)z#np;J zM;Fmi3uiai!o}5~pnBV4QF^c6q=7BPOrgUdcgdRUI?!Gos(BOZCYVdB><5rb`rB7& zJm}m)u|Xnc#nUzo?SHP%cTqS8DZ+uDsu@2;J*rX<_z8b&nGZRqzP_gM-#h$!?|4JR zxy)s?&?GY3SYP!f3N&};d>T1OT(xv>f!S4DA^RKh@?BGCO138sX#b8r**0&;(ONSn zV(t|f)_ku7p?O`)aAnmors$BmoW%}#38!jeUVeoi>)q#`Ekm#QaZYr7pMN<$U$nIn z0&O^n-8^xooO$j#)tu)wU2PP+y>$5#rh>|y{*1p}H=*Dz4>M*dTx;Rpv{Y?NS+4o5 zpo663ERGyGML#_Afg>qcASn6^Qv0=k)v_GDHFKfQbsd`!-W{Q#`& z4Z>D~4de`!(DyvbjYP*M4VQ$OY2CFi81}P9TUL3PR=tyyU@R9tC;b zSIozri_3O_6YNr2acjUT6BrEYnI&{lHei+KDvHIb4c~>^z+RD;2e1=I zb{Yt>{v-A1+)B_wg=>RcRo2k<NHUjs@S6)*MR;?M3ONH|g9gsm5| z);JZMN&G_y=G^6;ESsvM31ng$yVJ+i!lgi=L-s_a%3{rnSHTumSmRrK0zbLZDI95qkbDsv1g*yn(kKwMY`Jm zJRoG%fKdNLil$uQZ@SL=Z01*S08??j9Li%)r(om5S7%q|ffe$IwF(NBpts&~s6!tVEr znS|^49jq6T=eJZ6eFz9F0YQ{7WbV%0HNMR%#ww^07bIMir99}FhAN9HVOhTh_mVeq zLIu(Hc$cTQ^x6^o*>KEx8DeD`-UzJi$3OQx|~@iJssSq`%TwzKiTKa34R1uu{<&U8AUmRU)Bj2%Bl28a=f1C0B08o z!|xaf$BO$Zrz(Jr61iR%4%ejXhw)vz(){g=FJ$wQ9W5~udgWNtZTg+n=#58+c9h16 z!Eb&$!33JJ#BC3@R+H7JWc0%^$%7b@rgx}w?*Q}qs^T|`Wt6eCs`=erWpo8NO~;)s zx)>U>aQ0_n+U`i5yI*y(;AIrmJBJ^R7Szf@+6Iinx2rx=Y@fd&rtc@QtF=%F-;=vF z3J)pwfbR4&Y9k-3ICspNoEPnY?wIMv@WbdGe=L&264+i+?s2%J3ke^(SRiKQlKA%w-^Y#&p6F*o;eVfu9;%|7zsSGhnhicL?W3VTX(LrvwEwP<oZ}o8 zKPyEitNqO4?0zfrt*qX6o+qO{G$Vfoe&k~wi~FexQ9fEROXqLi?H zh4l)>i6C|+ffuWug}C3fDP~eyZYX&Mi9N89tm#Imk;tq>Vzngqn?ME3gYh#?qIXpf z=*e_w{lz2TYCDo(uU-~FDIWrCfY@Hfd|d@5JjT~3a>`{=fy$1@_~Xke4*b5LCV%vF zG z$P$T-U)EC+X2bDhJ@E#JIq(Kat`2RZ2E+rLn*w@O6Zu0f0j6m%-QW%wU`DtJu{UCb zW6;AiF+2qZg+0ucicrs>voPU{(VaO41&6$8yh0EWo@qHEU;zdt46YQXk8Vo}M)D_r zgfQCs;D$cPfrQW$VM{hl=UKQ?sHqXhm}VbI|3fMsP$uXtHxm(V`?m)w^8+o$GlQ?S zHNqBgssfJ`+zxHM9Yw-+2aIW$9JL9>Jfr|-61@ceMMhX0A-LYKd(BT2a2Y-jxNv!^rq; ziWy61M-qCY>|!}HpllJ}b!dC2>CNLHn|x$19Jd{;aN?Orlr@uYXWTd(%SYbdKRMvp;R7A? zh?;@vd$>&7{-A4Fdvl|3JYbF%!HgLlofmmZwCbo#(c8?4n8}xEQi_u%_#it|J()5P z{#}%e=;ld@C=wVM(w^|3QaRBucU_ldysm-9vS%i@yGjK2U1@i;p=XEJQW3LDVE<0! z?`0NA`ZbilJ?s;9SB}nzu5G(7k=-6HOy=obFFHA$0s%LM6zhGQZ#uEFHswOD^6TRK zP1N^iP4xjmp@VrAX|@i^v!^;9@wUtYdRTS!y4o8cv>hG>l_JNL<@p+#%8b z%&8`~D27xc(#ih37)+NMjn%ROJ>ub;F2?=8{kcFbjn3qhd6W;gVe?D%Ie$tyK9Th%Sg|<$^4A{frx$;{i>Oxc&iI*WYA`}5r zX6~0oj)!7KK5F0AW1X(fK2-Hhn`Pvfm$mX*M-GKsv8foXPN%LElm!tKw?>k;0&hV9S}oaxO|o!Ut-CGA?Jf z^w@Nyq)(Di+zt{%Y$Q!0Gewo3Qy4b-Hv7}+lN?Pv(vjTe56tCWT^60axv2{~LkjgN5&!%sAju*WnNsjVzxNjMHc0-C zd<0diPeQqN!LUBhC5h9~paPv;hjIUucZjj-ldnQ7-b<}i2KImGl$neFqo?W4ZthO2 zTf1N;&$b!7(tRg{lCwX5U}4?X;a8g8_;4Eq$G1`c-mlg%ZC+gHn2YOd@q-`357^NU zwBVIy#MLeR%+(i;*a<5OBS}3!uRPFL@l%TwKGmwMKa#ruMeKdx3cU6|3Oc}gg{b>i{CD zR^ut90lyRP)Qg@VjEg-FGqv{%inSo^Ei`eb%csA)k8Tp< zhJ!7S4x6SAl0xrJoEW!A+s}($9X$Rh{WIVd6+%=PUSffKD7hK;%TqJzct1ufPuL=fo(G|1)e7nMCOn`#Ih44o8_1cq!zfZ@Z>n9?C%OYcK+s zCZ)G#c-%!7&P&7voEJ&RQIEP2qxhMr zDZoF^b^o8M3I9~;FJ<_`U$w07{*0OPP5kuyWae!zOPXT=aok7;+Ytw);g<0Utd;Y7rjp|)I}T`%XCM+$8F_%4U}YMr zr^z4#ezx=AZvJJ-YgL7~n26Yi7T3*|5iTQpIyYxdQy}&y9*bi`!p_>BQ&npPj<419 z)eh)*3*o`2F;ye~38MvKeau;_G7SqdX`~rxaf+E4@n(}V(P25EhA}hX;#HZxpgCra z9BIL|BI?Hrz`HY|U*F=Cr)ADT`aWc0W};XzT>capLjutW!`$Qm`85eY3n~aDCJGGdp+nNH8DO-(U)}iLu8SNn2HV$URNgq@$juX>( zA8<1wQK~tLs5TqITY{Mp0|9yaul9q@=jDTZ1GWG*;xBjbI3}|p4ONI^%E3@_>?53Z zf|L$1wsUMlurN%2!%!`YPUICrFYF}64BXHVgj&E#A(~&hGxR|*i~OZVJfI5^u!r_riWJFDQ=59NqzlJYx}F1>|$Zh&bD=P)jK7@jQnFgDlu z8XUQ=g_0K)SY4>f(x%7&n5Ph>nDBmT^equK_Mny8&@Yw~2?sv7zG}7>e*13+<%)Vj z>O+4LZT}^7_y#>394lfMl=u?~zo?QWd&n7Ws%jOTrOOe2m@Df0g0{Q?UDt48&pt1& zT8F#m?*g4Kp<)%==YElE-iNghR;?pK8FNMip=TpMabRh2QCBJ6XKcK5`c9H)Nj`T&=VZ#XiM_aI%btVFC?PYE60KV(&Ql0@2_i>HXE@|!L zms82l{`~ULXDG%Cd+LT{AZGk`$h#ldi|gtK;lUET|d!oNzR z&#l4uCZ8C_5W#Z9CknGLuIG6d9OrfQAMX-WU&6h@nj3Mxc%kb|E$5aRtkjz)HY^OB z2v1K49eqMdHwX>>5W#d=C9YF5G`6sGc4+tKH&RZL89@SX00K7Ycf*>jZIi#)hN;ig zt6uF!I_v9-?Z0SS<#@W2EFZ-`(RUTZKb3cSDGy{U>Xml0L$+xC!GIn>HeRZ2<%^gv zgO_~_A;cIE@#DlrIWo}wwzu)d(B8x1ip2OGwBPrSBu^0dBQS(gpHp?-7Cx{r%plq| zs7XBgVAEzk2j?4_<52-B`b=r6(yJcN0vzpl)&<2M;|J+C1b|Q@@9o04+?GvId0T)+ zU}+x1b}MrFVK1%%fSU4$xRVsw04Q7gH})f(X|^UzP_VD5AYQ>kf`0{>e_dLjj7}sr zYgNF@fqKwF1~#d~ri|~nOur!p%5`LgzuzzPI})4&zQbB1FJ(KaxP6EfB?@I+6sSUD zNe}6kCvG>23}{u)L+}=Jdxo>HY^&;_iv6TRa#Rb}N7fD?Tqqi2{Fxz6Dt52`VGxLh^Mz|EcbH;g=~;R_d8uK|LyL$uA)nDHpoGdrSDULLPC_ zh!I8azgIT{J?fP$-6-iEAZtq*p1DkYg*0Hxr2xZFjwCEhL&$mWy>eQYA> zNufT=X}gJ@C!$jD{Xz%TTB#EjR@7to6$sGFVrks(Ne9oyx9WzX00!$~&$Y`h{_yYr zf8MsM=rRrOojnF&Xs)r%d-tD3Ho8^!R76wnfPRG;HfifU>~3L#r^;I z17k*mf~3L2$e0?hCb51C=1YATfOn%7L7)9DEeZ6XK+{Y~5L^Fd>#!nKE#AI=>+^Fy zfdEb+mf#B6OhsfQH8Ny#;jg17U)`~}{f3xv*`%1}E9OfX)Tqo`3v9en0Vm`Q=q3LY zvgPkN%w7)`z z`{Mn-sI!pQ!DeKyomMmYY}8%-5_&jL55ZJzeC_K|;QY!ki6+T~WH)hU(FG1*u&apG z;wBY_?tOF%5p9X&O7+K@lRb=)*BRe<(q-dtOg172+M}O*w$1D5hR^w?@|?N(cD9J> zyan#!qXuzTfw2$0*OaRz)M|GiM#zSD7_j66d`)6_Yv6+tQ#G)v{sj-ih$H5&d>q(2 zFVphg%v(Jc_YDFt2XK|TC;mnis0^q0hFzPuYxb={fNg8{1W~M;%p1cLe}CrcTK{1)I2aucQm;W~crW5q86F86f}M}|c(o%S#_WhBS|X#0&WXg}TxQ_G z`i<~n93Ug5GetG(%t)bPwwFs*O8z44mj<_m?i|TO;9Y_v{zedj0l1{MjDym)zneAn zp{7G5@{+I_2j-BI#W+9&RF@U`)>ife15*gJ+TGPZ|H(PN*m;+ol$=NeftO@fA|}=^ zsg$9(|4CfD({yt)C%#xtUHPv{b1_7>0jvl_)j)VkIuf+0nLeI(!|%Y7!T)Lmu}WVE z&5$B5;8sYasYV5YT)?B&<-`%?Rtq{#DpG6D-?Sa3mUP}$@W zkMg>F-J0om8nc#me$8r6ETMX?GX3rC?RQydg6LybX6DA0O(%E>LieKiGp$`06*@Z3 zm?8{s%?4S8+W#WVXJa@iGIo`Qc0OmG2s~Nsvp+*Kqr<%fx_44G#$#A6%lmD?xQ_aP zyNx0@S2>ON3XasC*MRU>tKnmVQiX+=CeMl-(BBt3j`iiQv?q*7Iaj9Wi1wz!Qf&VO zUpQpQ#I}oA`<0JQ>Sj`g>NphvoiGY_H8$2Y2HyOKK(=Eptmc%&_i z1!Km_zukI#ROrB`dJx=pH1ijm$G3ylZV^@nP z6t;JFfv4-I<&&a+mG~ff2YX)GWyc={Jx3-7i-Te5!{_w)egI2Iv|hk>3o)Gi@Cj6- zZo8%!1F}&_vH1vz)a{r#y`TevF{{4>W>POfw*=-*o1=&ULvQ<=hsUgHNm*(bztT{+ zIFup9s9g0|F3lWpn7D0;4O!%=bk)zrwlroG3S-hmTd|~@?JW4WmZkcM~SGi*pjL=;@ zMUKf-J4D(>_Gff6Cyt>f)qB9zG;h94CSw%s*A+dCo0%MiqqKo1VUOizC7V!=+4HTx z0LSwwNMU}@nsiEhD88BIHxbj};Bpt4P9uA;3_HZl?QUAOVr_Fh9H@c0#mW4bA^3w0 z0<`zk{#XC|T${;<6G=i*C^mLPXw=0D3gjcSO^?cM)EW2>uA;(u(AB!WkxfjDs`tB` z?KypFPD=+S#qJ9^q0^O9&BTzu_s{KG1P^;-hDLEuLRB}&Mx>u7clP=|h>1KyW|%lF zE0^TDpA z&a9bPROEz{b34rI#T}Xj#P+T$xD5JgUk?#Xe+2#T-@YjA`}4A-%lJs9c!@4ZFRLQ;2^?9eyf&i@=Mn$186XJ>6R z%QxQmtrKi~dt2P_uE^%Krr+PwtWzm-Rn-FE7Bt@uY&K5EKPofkSAzOJx)!1;B@v;@ zOOeb8Xc7sRPd%_Dd5Cj)g;8_i{NLf$E!~kii$+8MPWcUd>Apr{i!&#(1jdo{oSB%| z*_SH>h4y61d84Vn$te&hSulJg>zn%rH)x1Z4J;v~IJ4wLx(s@lisd{wE=puP&ht@w z_e%fIM6y(AJRdg!dHOW|g=xHs76Q{r(a1QE$+X0JL<_O|Lv~4L#_d7G$+&ZMOF?Lw zv}7{ydLQ^*hq?76vc|*CVjWxNP!C$?KL;hUk62CkJ-0F5+PMc8J#O7vI?O>SjssSG zI|Qcl9&2w8qoEt2m_p30M)mNYU^tv#h3Ievqf3Q z$23c1sRjAtrR?-&KTkkmQE6GYf5pWZq?f^^J%*oP98a+C1X}Br(Btww>9|Y@5caot zZ(H!2zXx(s6o|L>!GJci@<)II9L!~vO0U&NZhs(WjPqEYl?&!G!?_sYq{xVOD;h?W9LyMxNFup8zq4u{s`8wu~mCXf+~7~ ze8|~x+&#^YNLk8aUgK-lFlM70MGZakMaegy|0Cxx78^xWQ>KUcFuZbFQ z6-^HEjd0i)@{u44`|=y?5$o&Ti_iZqd+n%=%G_PxAcnC1RHl{QT3zFh>?mq&LCojT|D<)DC8e!7$o|(=WTxteOAdLsjZ?;xo`v7ro4LL4%Y7 z&=PN{qo1$7$cmRSDs4wIAqG7ZK-}<^PFj>>1%dnHK#DT3)PWQ-qX?<;*Sn#>M!m4C zSp!re_hCr|HwR>3cL>7-4%h)}+5Z&OXYR9@O6U-vPKea&=LI*jEn2}LeM%+7pt=0z zT#o{uB@RLcs8XPq_q>seRwdu!n%7}qy%D%XAqQD8>m;d-*-?VatN%(+!+RX5W=!>A z0Oz!ZWwkZY#|$_$!Wkrt^@7Y--42S4P_p1&eo`0?i-?-D$C z^1=0gm~n9s{WC~7N5t{eZUB&*eNnP!DTwe-ZlWS4`gu%!G~!#j<&I}@_LQ&mq?wMh{Rog#@|*Op9l zn5xR;#WpY{+wrRMp;tuSe_#Tb%PclK75KDfWxFdlm`nm;2kdT^!i1XomAkJW?;2LE z$iDDi)$*!{?O5KQGc32UE}h2p*o`L~st!+DL9D_4jl)k<*XZ)(P61FsI%G*(np@$M zx-D87#(&`|3dQ(>K_A~uRwF1| zyBB04vFFMgjg$bEKq8Le-p}`>dIrKL&2Xk+lNBhq9B+ILn{c3~zTr4NOB3OM1G%3* zbYj*j9Nc>sZv?zRrP&6)8b#!jdgfwep<2Ex*jlj>X-=?k@|J0S=BE;aBQzw6ar2;H zayTRm_Yi$sCtL7Cop7qLA6H-eBfmqlI8X0>-+fO5*;Co~c{l}g8$`q?On~`A`Kuj_ z&d~qpzC? z&>K)DDSD(%eMvi6MNL=rYMb6~8}pUmwDXl;ZnFnL{(~Ye1vy6F#sqW|s`z7V377Os z=5`#61lTQ`zkmYH%S9XbJySX#FXVx`%aK|y^S|{ekRpW|Cs|p?r^0?q5s8yFw&reZ z<9AeY3dFye<=!K6Y9MW6ed?S}#~^zD-B!tBoJzO@}w-@R;)F&+{eFv{d%WwDC%tyE0n^^zi-U3uo^ap^;g zlSx9Kmet4xYD#@Yc#TRJR9m6!kde$%Ph-y~%Mf58=sJNo7+(8F&F7E8Ua!Z~MpYsU z3tPP%5^qZl0Y^=R2<2D3yQKFmjB8JaK~|&elHq2727z(>W?h?X_XAHm=gasi(h-DH zp2(4B9Q2mG?7`TR>|sW0 zr`KP-B3O9w)=SAD1{n(~{}f_>)}ZQVRSd)oI`|8AU&hyWSohBFlz$80n1nKo(>XD~=`l(Cibl*98tU_MHW_@ZVNs1S*fuwL zO$z^ur#KBQxlVHQiQ{cW#EWnjy!LFNBIVy{4tj;sLZPq#`wIdG&k9qwesQKAB<)4X z5O&V87|un{jnQ}jD2Ud2@(-P$o67YlmkP(CVJFVc7OeP;@h65LtB6Y{s6_n!0MO_G zSA?)W4n(5Yw`$ST&f>l5B^jXTD691})nS1RV**~lz6A9vqF3R?ED>^0QHz=Opok?| z)dix=Tgw`Rxa#U-;fWzr5Ln0O1BB{j(PCn*FtV;Q{}zcP>L4a-Guc9LUP8bty`vz@ zT1x*qHUFf+&|j~z&?=;EcG`oae`MLOo5=(nsSB-vHjRH7GN3*6pi7Bo3=~kprI$sh z!;U0QAP1eeDy$b9#%P5El0IzYZHzlumqsh~QIkEA7fGR+e1E=B#4F{IK{VXeo)7dRp@aPYn^I_{ z%xpHPOIW=~wQbmnG&8P&UW>VZ zJNFZ?_`{9hO65j~DaP<>n`ZJdXpm?RL|9=n4) z5DVj9@Vm(X1QTbHt&=bN68(mMt`M&7ci!3zJhF5?d_o`%IGE-6y^V5V88P(}N&7B%u| z=b-bIN93FikMWc^ov~57NF1<{)4TD2jKPN1*5Ogta-;v)bbpcDG1A#XDMFXHtySv9;ye<8CzqOE zee;yfejTvh>V24w-{*xppl4wjdeol#XTCYceopMHHaVQ}UvmZ{WG={#lkN{PM~-Y9 zbm!iiq0z z{5<0Hiys@uJ`o?(e~XS6F@qNVUQ7XB3s=5T@+K)dn|Z5bm>TyNx~GTNH$p8?bO@3* zYcK+&mWGqhI$ptRoH9!)Qk**_SL`xLz1Qd^!%V&5A{t<@ zjHf8|u(@!MQ8R(Lv6uKG!#p@Bq!-R)R!s6E0#PX^$yo`Z289Q%DJ?1T;FLL@nKFs#AQ^rt3fWb zP}r>5r~Z8W?#^zgE$)vQOytg5GboU{9Zxe%!S37XMMTs4B=7u2c#3*N#a35m1GiX{AyxBk3xZCpG_kr-RA6slkra(Pj=uv$Ac3b70 z>~y6i5fs0?veE`ig3w9m62l4PPMD-`3!)-<3V8m7t>JpUe^^i7t@w;3_Q}8h-YIg@ zX>&?oo-eBIIp<-_FcTbmg&gUDSo~ElKZ`F#rl{3#VcydCmL>g1o|QL$-!iRTpV99; z=nuz@Hm45yh2Lmdtj5b`s*J)tF)=~gvhX3A^CPii6(P{f)E9;&D6~tqdH~pea&kf! z`}>wY4P&~#B`|hPxL#4q5oxKA6%z04>&cVGO2YG*sy8Mpay?Ysr z=byf24d?ku8S}iR&vsnFFO2?5$HF{Ra(`Ztp~+(b?h@dGk`ix>=|rljN_4awy2@*L^HFL0tTtq=pt@YWXTS%`gb;r8#84Qzo4)_Asx^ z=u0=4Co6FhR7#SZZQE@}iAH>seDsB0eukb~z*U_-2}T@1F6G4AnFLbmgdl+*2P4yE zb8D~ZVW)W#yt(0x&dt4-CAnC~C^mz=Ss8cYRfB%KVPP^OY(#Bf3=>x;cyy3#xqEtJ z90U4Nhrjtu@86*;{@Vfc>zZec<#P%R6w_VEf(q}zSa=e%6bNlgA||ehV|un#s=FbS zh$UcgrZdFv9ZxxI)7BI{v>OVlh!R$>po$NGH;fV2OF@t2RHBp29v?SJM}LDuQ28wM z6;FDkDfqThJEi{oGBp_YMCk1Z>|fR-6w~vUp->EQ`=hw`fSpZDas%!=G^i_ook8*N}3aeJ4INmPxh~<#$aHenY$kO>-wQ znE^yHiChox*44XlCZKTA+v9~tPzyCR^?$xCdAe^mX|;agu{_Isj?Az~$N#_hlAV=R zl%G$=HX5|FvR-yMX0%_>jIflsT|sW1NO-A8F4mAk*HKVht=IBHw$c0g^gSLlfyC4R@KHql!-=T?2TuQqCseCTbz zK_}RYTCQ9eAEUb_U{+1a$dWslaK>c27oF?XABz~uAKoWFE{9JP`T15XxN0G?C8(}X zUS$2luic#*Nbj>RlN<1`{1SuH3|wo?Dy=b>V(atitTxQ_NJ>AGNF0VHu)N(XW&FFukx8 zyIbjTA(ku9hvyU77nXTC8@tAzCfY@J4iJ@Ie>)_h!@g{Je_>%=7iv=!6RTHreDTY- z+@nI^B#%G=!ZjOPqOZ{n8p+c$;v~9mhhL>vUuhOm0L&+odlZvs2+!3|kPlN$d3rFA z{8rn4M(2B#Qri~b?Y?nDWj?%83~c;1SJ!#6K4;@2U0hLw_rD9N>2Bet7EU*tJqrx6 zSQ;Q>H&wC)euU`@^XD>tz`_4bwj;b=E-*<l0G7?kYhlEgZulFp#6Nx`Ur zp%5*=GBROe>FJW+OR*m(v;R;~`vcv--5F#(0BiZQQVqU8)w`ds*4xaz{womf0#i(; z9j(bM;#y!bB4R!xLj$uQDSG-wHJk{o$lb$Ygj0ARd7ZR*O|U~KyiAu`m2%rp_Pg-# zPq(L^nGu{LfB$Ri|J3{uWuJ1ad3t*`4FB4K+1R|Z z2x*yyvq}WBiceMcQ6KJhxn#vY`WltUIZ5#aD@t@XT-5Cp43Tj*h*5rC^@-?UGvzL_ zr+Ea$^aALAR!5TjajjaIC`%+zlfse4FM`%TzLZh%B1lhWVg_BrdG8V)4z?^zaw9Er zvCH=t?iHUv02A?SccmzUQ30!Yh51YPr$VaWdr?*DgnkZPAp!6=zVZQ2*5a!7u9=L& zSUkq7dH(N3)p3Hl22@f&2?P_d#F4{FZBoqs;~G*I>9m2-uVVp48GVgQKWAV9d8F67 z^6>{okws@@)^5mXy$bG*`|-*2o^;k%$_VMH=E7=B6f+C={; ze!{`$>0kU7Fit5g9buw7K*Mixa5tJ}o&8g@yRy%n08tH$x40-iT-Xh4Jt78HD!Y&)pHktx6z7_0e-xB+zQ%tGXCqoG6Wq3yPMv`Uucpa zF)CqD;JxyKUKZPDmE2$QFNuos@g44vP&e!QUJS8LJYs!KlF4c=|L7DvV6HLAV#`kg z!-$XfgfHd=nvBTcH{xCPLJ|RQsQXlkD7?d-?MnJ*r59aUxhb!Ai$z>$h>v9reS2<4 zpv-i*WhOZc0BVr-Y35xV*qUdq?aHMMPsCgkO$}Q=kRlXD4V(EkX>+?zlFmLCBJTj) zsAB?|rSNuNCBYg4Bp*bDxtGg*whV-F=d{lOKO>y|BmYr|7IbeBp5l>-+bd=L)+U|% z$BUZd*WO2g{*i~^gFl&}+rb#juyzOg;+MMb{1A4aPcxay3h7UOTD|Zn9p*D2m8HU6 zXBuqHtM(jhrDw!_S>bIGc>RkRXOKTBnhr|C*PS+=J(v^MlG}seeRMfonv35aInmii z)uu**EMApAwA&O5g9OYSL@9+GDI+H?^y53NHdyhLfea};mfn8~-!`(opMJ|hg-$B_ zK&o&RZfrW9S2^(-@_A_(%?DS9WrqZzM&V@lXaROY_B_nl0lU3UKVujk*jIF z6-GWQdD9wCrR2#ma^J(;qqo}m$1enwT4&ZeKjSn9=KHtq^5s(1c~&9zy=kJwiN#im z(6`>1-Zj>`#Rgddm8SKtC zs|50wFIHPaT^Ie7zulY<)2zrJy+9v%Z4gA+(hG#{jr`ueJ_U(-xTVhcuCM35(OnL` z@0vb+6Ll)U4y^k4TFqe{4P=4 zntz!vEd3=dFW_w7^FqW}F&?c1Q#3I_77?dptugObL7FMAa|cfb7r0`wIJAbN?T>DO zR!Sn}&=lI9n92%3G!OxUJt&Oum|NNfciO$K^N6zZVxfkGP>(aG%f`ltborRK=*$^@ z^34h3VMiOcs0$4k4D_RA-N{s_y&*Cq;h0fECWUA|{21zUMuL2?G4DOsOG~nu0iI|| z4Lh|pKRVonhecv7lXnzt*o5AB8Yl9gQFNy#1#@9f3J(CnlW`VAnkHF~J|Msjx6G)c zt8AeF$g8#wpMP z%vb2^fk#5kXJTL+66X5wfalnBZYZWY#kB=4}ZGp@Yz%E;2_|%_#^5!X)^9Cg@JXc z842fWczn5&_0L>%Ja6==aagKUyeiRN4pOi>7Y z4p#UhKz};|B8}CaKzJv5$Bp&b(~A1~!RKykHLdf~{|EIz3cuDiDf9!QBO&VTnNNSy zhr?x|`|qn_MUWMH#O~s8!)}+GZNrc+6@3FMB!zo~XmR<{EctxW*qRRq4^^;mmQez_ zyXI+Pe6cr;7Q6R)sLYcwRsk@+pFXuTVO3FKqn*36SLB>{Q-7Zsh0-!B?cL`|e_I|} zA_hP>ufzMxL_Nym2=PO7=G2rJi1MMdbn$&Jo}ZyWAam_ppdJr!ed1p5M3|Y2iO*2< zcecAI6p`Vmu!0SJ2VtIuM-jTrKu$g%?-?F5I3Gq>VMOQj*aKcNaG_!Rfl(bs9-ITR z0>*M|{10GbcdT%YVSuf%Q!+01lW{twkqCxdFP{q%0%b#(u>PTt_&dP;Ivh!eK^jK- zd$|DH?4vjb`Bs|nj&N^L5A!{jt&*?E?EwwKqG-;V|<1 ziwm+2iaYXStPut>@X*}Z?x2n~r!X`pBXKe(<6J)e%yLxZ=vF#z@)iX>$U#tbw*o1~Gc#6k*k-Uz=hm1d_Rbmo$uPG8JU zr_N7{)X|!vaCn{~kvaPQk6xjko+~sx)z9+sJdKSH(+e-WBJK-0d_90Uy|bf^#>cL) z&hR3A?|a{;x8CU&Wyvk0N^v}E+>kZTC3xtVoea`xoo7QzaGtoqB<4f3MR>wv4)IpV zP^M^)dY(l^+`cdvl4LT^k;OW~ZOF>wluNX0l>ltuZ?oMd3qFb{qKG02fY`u4w#p6s zZ!?)e7l0Nph{2;s0rdti5&XrV+#D!5!vJR`%f;eIMq+2}-s4(}@!1cA>N7Ul7j+399qfcgf* zRLbuao2d&WOyrQ5o{b3uVoQ^QW@ci-K!FwVP(ZQSK0<*&$%SzPKz?{bV6Pm6WrNoO zjQQhyf1o<;83JQDu8lA%_zWQ(N?bm~Vypm%GRif|ul0ffL7?j)!{rekG9z2TLx#UF zq<4v|2T@<^;vtiLe5Jtk`?(zmQii{adRPY!89>w>pM-1T9U&wh#uS9ZD-_6w`@ka$ zWq~mo`v&1&DqI$fkqCjO$b_wr?NZJhY|~jLD$r8MBRXr+UV~P}_6UPqQ;idyABm*{H0-E<75Lrl%q_v5Ys3yTnQk zPPNr`ve~Sx2+9?CSY?k5;3Iq;tfa(P5(p*5@j^XhK*n@;`6#6E6466llUsOQsB(`D z2gx_L^v2vBoo*_xunFTdj1BiOB^soA`ah=rExw7)W z;I7x^28J@k6O<4|!~h_UY&H`Mq84EUIQ8}vC71Aw5%;anzHfhzpCaM>hBu4VM0JgB zdA`OdZ88}}s50yqgZtw>qYqu};_F3{R8?uC1|ATxaunr7e%RenuXx`TWfm@LQf$<3 zwwT0TAlO?7VT?*kEW-Gryd^-8LZ=*^h*IA`NbD~IV?9VSFZWdtd>~)2x*kS-7-`Vf zU<}Nca1VG}D8mHWqt*)sWyX0>a#5Cr-#Cx(km27p%|nLkbJ6b`?jf_-J7gum_3_N} zSjo)y7WJ?O4;i!>KFq%vM16vA!zxJ}ALn)f5)SXNFh?Q`m>Pr2ED7>(s`QxYeNR@SRS&vPC;10nlv6i|0X&zQAiwL}c$h?+`^ z@G{dTv<)GDu^eOMx<$RKgmFm8gv-I}QDL5?e2I3YkW88=8gg+PgSYVdygwL!ZuHDk zZ-0u0M|fN)AWcoPjOm8%m%hjffpJR6cwAr7BYORwr-%Mq#!hGDZ=DxEMQyB$WMJOJo4Da)UzUt%ZYw35FlbARk1S8d z96Ic!3VvP~qZH|YaA3=kF>dbk^^Msp@|PoH98NPewq)l4fsotgKujP6lR{IyLnv~& zn4F5y>nEpaax@_7G#~WtJJ7o{8H0Lk)`Y54Kv|>F1a%LDMBlm5_ZbKxw2zyJyFM8u7nc#CsdA0;Fa}};uEA&^gqOni zs!AE2%w{ze)P8b-`>&XgvEL#>M(=n2yZHC@A!O#cufcGGKDW|@_oS|mXNK_(_ZIcA z5<-UC0>&zY!t3sX7f(`z62o3E_zZ&~JgTsvH1cD0FTA6cN+4K3?4b-WLcy4bx+}9V#*9z-C>qPia?7Py%)mN} ziCP*hqK)NG`oC9}TZP9n>ITnWL=g%IU1l_fcs?8DZ$=)cyhSpmh$4!(qfjJcGJp)nGttve*V9E~DZP3zkp6`` zH!E5{{Xt*)TQ(}4@_FxXvr_0tJH2x)NTIYI`~APy9~>R54?o^&qGxxR$#zmaTx*u9vUM5NxMj9}&h9J>Y$Qa-WH&j&#!58$t4?@B8|T zBQ!UgtxPK1(_o~}95m6)(GI%Y8=~nP9u7?lA-nu(V?GE9C{bp9pN)0)g^*YXR0V>o zw_kes%m?Da$lh3Q7vxPJA4jMtD2@nUhW4O<>nWom?g#HE>=TmP!&aiKnOT{}{xb?7 z5XRDB&j8$i*^p&|EZL-xWm%i{>;0bDLrMNFl@k2EmXKwuMQ;7!-K&sgfT)K;LYDDY zJOk=zdM+l2$>WDg#kmGT#w!8r6d(dC%B1oS7vT=G#Mk#Gm1Sc zAQK}L*^U;67_ZURHZn|Eu5r8Ek|4V&NxM5s=-wllg+Z%9G-e`y$VMYGWi-ZVKI{=P zhfGGX&_jJU86xC%M5wxKhCD7GmAU50V#>_3D+N4)FJ2AM`6~emCyX=`m3%oY)px$8CaC(<==oY9xEZ^Hu0DZ z{f;$v7Iv^NSCY=LTvJhQ77GR|D{NHa%pO=U4`NK6;yQwEsun7ONXKG8%%>|K_ZV9!(2}6Tbr8)-sLDC+AP|x7RZD9OipLKhO_br`$k5# zS8W{kflL6sm&F}Ha>L#URB^qj@Z7o3wkd^?5rhV0U40!Q12)#NY-y6hdC%Zt+g@{n zljX7WgBFp66oGtLyQ#x$EE^t&~gYiMzOnuP&A$7nTC)u)fs zfB)hj`NH!4%aJjtpB=5)#t0~2gTs>GFtecXUmM27=UfcsPxWW+ra$@e5Y45( z|M!M5-8M27NYOYapzfFNrq6w4h{n_PyA<$_K?W$Y0+73gkRT1}WDr*^FAE8{sg|_~1 zC0u{SgiK{d2t{AGbUh%h1Hlm?K89JK$7)e&SkAo5LIC1ME3g83L`+-LN@A23UT5ou zTX4(#*iwbrRIK-t7m1j4#I|ad8(Ubk1%&?6qS}jgm3h~~C_fmXn|&dnuuJ0y_U*#n zZW~9&z+j--q1BiouQkr)ve3I8@$h)P^0qi1w9@(RYMSynX>=O<0m3^0#+}SxgtJA+ zDEt-2HKdI8GsqgNB~BjKJXMxVQC;~cl{!{toCdIR@3oUYnwU+{T+AdqWiY=~c+A3> zvR){XF{{T`B4QNq&Q?Ok+#Z0pR<|U6J&Q_?n;p%8K>9Zo}>C&s~{+#Q)7?W zeY@O3M@*zlWV2bwVTsaNzBcqnw23m7FRClEpB;MOAeRra4(2}|dSg+UO(UIJpxsmbFhv$CEn^W5kOiZ+4sgbjp;I^>PUl47wm>@JW&S{of)c9CTP zs0%E9MgC|!DV_^+On0|g5Ha^2Fpw*c>K*3i80Ys287CK971UA*&&?D)bWbIh1AF}v z{rDAWJH!2^!m`h{x46i}@?a4~EQKN&vyE}5k}(La^qa;3@|qSKw5LP)$(Y}%(kEm5 zJb^4l#sKR<$iP_sZ%T)B$(T`pelq4?)=W~9buk$Of?_E$=C~t28FO}2pN!dIjnePd zOr_7t1_&H28S|xYkI}@OtR!qipQ{ioN5;&~#l++c*tt&rs8OGc!87I~WB#mJpNtvw zWs@;q`@sbDPs;WJp`xPPD)b?rKgNTfZ0}I$K_uitkuicen2E6Pk!=i6KpTO9UXUBZ z8FB;A5)i8a!YqKWfZ(IBn2?DHBZdO%{7xcdvcZ`OguH%4_xgyNudTlo5i*)O0MH-K zUh)ee4|@zLU}Y7qg%wEHHwXfMKHxk(#cVkuW~pmtqtNr#37dSorLm<7vuRk*r^XmC zIu^ZSh!{Kr6xiHy7O^qF7_0@_ONlGH!*&IOhE|MqX*0QUB_vB zGQ#s9#zw0kW8kTRIS>6FVb$$6`K~bs_6~%^Jb(pzm;(_~UHx|TMu6r639*kN^5Pzl zf6(rbN6od+tMNP9*|n~K_*=<&>^3e#x~|oIP>#Ac;E1-T;f+)U@GK=}I1{Ea*y zvoIfFu_7XnAP>rR>6(8b5AJQ^W)FP=Mrx2X2%Xu=`Zhx10~lkG2V)+t=dFMjQKqk; zji5c@U9rd`lGvM--_yjnjn6mIuYa_Rj_=QIV{<*yW_IS%JY62=>jW3~BMaZ=pFHK} zvdiyQ>@{7PvBmtw-;K~%P|l}CGNy<^P$XlvG450{2KY>*hsq5Z8i z-rqo}a%aJ0jH$MaT>ISA84a%!_gIyF)5FW%8oUXxxrH~856SdBzAubIa({|t&4u@)~qtk#d?x4 zb0#aln>uptsVFG7YhtN`-*>qE%E(2RDC zyK{fmBu8*=U)w$BVtgdT*Yl`VP)@X%V3)pd$V!75;558 zOc@S}*nCI>a^_vb8wQ330IM{O>7Veoy;;tYg_ALbK<3jDF)A$C6AzYCQ+?rc{qUq) zc)|3JdeTR-u@ng-{%X8n7S2f@$2_1u%e?Zt@SNel7IT~`OD3tK`ZAT+S>`OTI(i2p z^wOKN6iOIrHXXKXy$G2i8MAV1RU!t^BV!b_{ReFoVQusb(Axoc4y``8*+Bi_edY_< zQ^eN9`V%qvu-dt9bFf{=7`%f(ATAcq?PdKAz&@b(e(|bb82yz;iUQ^*=#JRu^w2)H z3`@;A1W(r@59|p_P9Ekl1n2MIak8z+AwDZP1^cEU#21bM&@rLM1JM6_`5qvCpgZr{ z;h-RjgYbR$#SZv%^0eUa?-m9*((e4f>>$e6vFv z>Hwj`;5D2+6TZC>?fc%Bx<1IV~QL2ZvZxG1OKfB{pT1aJ9V2&sQhpv z1?s96QoOyEJdf@qS4S0DO6_8TJaJ)O7>P%tW_l-Jr+!NbRo>mi=U0jpYpbQQM|M)l zt{SqHJH>$Z);S+f66u?zfld+%CB)>XHho2mONY&{unG#}^irGp4=1cNSy4gu-L>TB zd#e;{t0C{Bo#bk(Ad}53NDL4NzyO!~e8@q*%5riZs9(qv}$(`Vb@(aiWx0?304)s@SPG4?>#~ zRB`VuwW&Y9XI1vh?{d?A`FrNsa(~aasXt;YW5a%sdzpmq%O?oHs(ksbpId);=6P=S z_)XlOKWpm&W3M9OFlN9#94oYO9QBL);JA91LB2kWNfk7Q9Dq{a+GykN@&Hz*26((xK*-3o03p*!||1@g$N{7$zMP`|g5hyhT47~`OOLY}qTE%`!Zzg^*Srn@q_B z4G)E=>t=xNKjxwK1`GYkH7~y>9Agw9-F( zZ=B+hI5pN}@}U0)_!$vm3z00)=9Nte33a2jt-!+tK!1b28Rm8Z4-zaAotR=BF%;$V zNDvcfKhQ(*T>+fK+1_B{ z`>;&Lx@qox@XjLG)33}TJYc4#qr$_83})7WiAKkxLNC_lft(M$y1o|Plqs6z=Sild zt}P;l@bjXtU=a%H0rCgRKQ%4w7zll~qs2)Eqlxnwg+9{P&*O!I=&`%uO_SYrqL;?W z%5p;$>*+^oh}u0yu~+i{JR74hUt1x@Iy@FpHo}ewgFNT^3Pfq<`=O!K;JEH;J;0AXL!ae{IdWIJ~MMM zvh(D0sLeqS-{(#LvKWCtY{4@IfQ@n&3p$_pK%MxWh4gK3eXVCqsoO|Ce@4++>>-mP z=^>Ntk&x>l1Hud)u9hdRhmMp{OJinrSO&5XXD-Ywc*X!=;U7LyO84@lpAVO=&1ZSW zDD1Aai093&#S9R8Q+dWHw0lkT^B-+Uf6Ilu(qDdal%~@HL6vuHVagO5+(iHAQ%&h_ zIpEuZIMRB?0Cg^+U(L$1_({M1!%UbmZ~4kx`Q_CXU$YRvJ3@L=qz^1$W!KB~64CdN z$rvm1ddQ>+0FWHF-a|&#!J=nd#zRI4ifaWzg`png^)uzuddSEUYU-~*4;i5-@c(o3 zG3rgP*4@9$okg}lXdL2thJl*pL}A#%DyTxSS|SFdn>r^O>S^yptnk_I#*QMwGqe$2=$^Z6Uq!(M|%!PE*P;2#a1U`0MvzcuO{?6Z9QON5A;_Bw09UI z;NfvA-(jIZ{pJ!esM|_}NnE~rr%~{US%A#yXZ;g~90k-L-tVpUkP&)F4$-h0zyRIC zZ5o)+@kqrc?hUNxZZ~WVA|@YJ*B;k`?cy0@F{bDfPgk;TE9DMFhTwf-VF2*GpG?yA z3Gqj9Qiz4n!|~1$wha2Fo%Qph2jt>X7~4nE zwiOc#o~oX(*b~QxSvJ8u0-Y1D5p{*J07TcB3-eT)_M}k&c>~WF*hY4DI@6vqF{<#$ z^G=@ei3kx|AP@SYx57dP_LT7VIKMmOK{zuLz48{kT=ermUOu>2=7B9w?zd~Am)@Ak zlJxAk|bG>Hq$%GIHhgwb`#;6o0K;ue-`K^XkFRhsl@S{RBRJz(oK4QQ7`tb_wv~;9Bx1ti+3*PJZ906WHc3P86}Vv00umMKWdsu#sd8uq9rY zC`5KizyRY}Vf@(N?4S=mTbur6G1h~OX>W1T%xr`wfs7Ie1tCMo$c)PoGX2A0o_rEi z!b;LJ4^+^;-Ev~hhP>8RCu3lQUTy<_cv!$N51=k?B^mR%uME@pyqs7Or&JLSg+N|y z@ihwt2pPB?XB&)Ge!Xo=$ng2OgvWA(%Tm7=2ENELfY64}84x`45i;7VEYwjRLIy(N zo=%rA9);2D`9g^0i`7k6Zuo`3efN*3;w+r^Td9 zjCR(Xp}NxU^i}eJi@)B4%zBV9Fa#|}YQPYtj2IY0V8Bwq%4GG9F?VZ!!@b~*3vV2t zq$Ha(P-7X+!@?2BLLf(Q4$6eGsb_>75eRV^xEbSFaSjp;W=f{Y2VEkjF-^pzyM=7~ z*|GrM%Vvf#fvnY?_VfqD^Hpa*9|)PA{*b5-v_VDWt3JFOa4ozic)KlEZ|e!vZ!Qr7 z&MCRX2kH&)`BoA#8$-rq4ECxLwj&v{wTYN~*w}uh)oZpo8S|?js-f~y z@l_XJ|IYX#GUhYSRZ?|D{{Hx_A5AWhF}VQgqQb3e$rwFg?ou8`_Z%w|Zw=qyIyEQA z6U>*nfLAHTY3RbcJ6!3bMDLvQEkydr1?(F5t&YcXt$hdk+CVSHwQ_+xC<|;A`}epP zT2#I~Xb-R_U~b&m?&N!A+62g(+^}W}(7O?Vq`A={_L{+bi~V=%YV7pF&tkU)8FTGs zkjA(jKwiU~iiJv$;~>+(lgiC980LXit^?Dpn+A#~0Gma|6vLEl0Pct|Wjc=mw@o}N zWOR?iM5AM2>h24Y$qY9|IVheuHA7c#_{H(rKvKA0!d(%{w}U4|D0TP^gBIds0`Hui z6&r$ySd(DY(=#Gie1s-TrQj|t4`zof6Nf|?qoqQYVdVi74I58h$v7)W!y!=yY<`d5 zL5jTi+LSnkSeQJ-iircEu$nrgd<v{N;H*9-@({ zSjN+dCwsWKZWb^Z$}m>)JK6<=2OM86q5b200LDzTpRBN63?;k@7hpaI_X6^UEaN)E z^W*w33?M(QyZIr@GG*6&wmiSD7tki5sKS_scB(DkYC@JF{0;h7C6B+N&iNp&h4+9> z3jq)z(v>?!*yzz_g-dvp$BDQYy9x=dQY2!ESSvQO`in%21{+@ScTUGz3lURY37Kwn z?M4vzEY|^EYmCZx&M1V4nVfUbH(%XNmwPLvSi3OHFCOpf8ye~Gv17EOb0<~T)KZzp zBZ!&R0vIg%Vp3eE>kjPW_hxSW% ze_3utxD=d=usLWyNcc_3tmBh0F%|^*I1;W083@{FSzxn?7y#`H??)L3QIB{&tm0K6pHVNY zV$r||>ORizG9iqHs0+wf%OzYBZ3A_SI@pXbU8vvnCt`AurvYfer|8N1Xxq>&Z&k=L zw0~8ea$ADhYq@Sp4I-5}%;aVH*~_wk+Y+ZB577ueq=m;S^VEAC^yu+Y+SP0#r-`45 z66D~&A?{E7+J!uh)!^F&+mnb{3I(*$Ww1!E;eM|?PI7Up!<0cqJG85UVuph>7pkB@ zv}#cr9176ne8wOz^LQz4%%5juG)QB!Vzu5PU@k3BF9<+bG0ac-fc^me6=Q5`6T*AR zITeco^oSS$<1fPh!Ip@9PB8D_9*}!;_rFnqJ`Ms0=ZP?4={z9IV7Jl(>NbFrQq$#&UuoNga(w zs$p4Bi|{46cQNLrN{4J?z@MGs`CF&T57x*qWsf!*&7rJ4zQ!mC6pkiyNOJxF`AtViOB*0L4!@ffSY|m(IEf~a0+1j zF)$-O<>a)UhfH>eu6!Oc({nN58I${F;6{mw14deu8^9!2TVoTe=))1dN3{%Tgb4{~ z=Q82mSakDv&8=X9X8>pmg2Sq}|6pI9?cTkoU zLPK4(G&rNa5PKNVmUXi|W7YzA)j&wq8X%ycZz~TOjQ}Ido|B)23WY__mh(HxWziTL zRtxkUwbFGt4;iIQDlF7dj)x510s8TweIK~J< zGO=pb;aFKe)%Lg5dd6shxi`*Y3SL)Q81O*^NRrMZ?lC?U6GlE<7jh6{ z+~YR@p;j=q!6=GF7-)Aej;d=9b2$+P6|wXoE1(Wx96>%97-fuo8MYWQYeQOxfPq%5 zQ0DGj!`H(-wH`SN1rag)Y+HedQBZQ0w%i!M7kS9Ayb9v$Mt4xiU>IjtD)XV;!N|6e zULkmnjVEGqv3xyX55=wGAtQ8;bXhuUjP%iGGasqPI<)?$~7s>6I6QPq{IUlBI(vbFy$;cF28Mhx1vlI&Jx4C)^u#_&e z6+B~p`NM}PX8kys?WI)VtrW*|F*JOIzVzjPD?TI7FFe;t#LJi)jjYww&A3uoYK;6CquQsx0^^vYW^ z=`$ARahX$OICQhl9? z{^LKZ*bvW{&Dg*n@XOsIl!aibto(H}wwn@O@zPgR)$o_Tm|xh_FI0 zi2^OQ6Bz?+dqRd4R+Sf6Dg?xkzj3OYEat%NWb)+F=;DLp4Y5#7wxCWmh z@Yd-$5t0upa`0RTWrlW)x`Ep`>Kw`yJjbw#DIeC0h?$s9aCvm3%3A`i;O&NOSmdpO z+m(oc_fHYG78^~(V2phcF>oSh~ux`rKN` z7B}@PJj`+%TSE;S%~hWEm76 zUbK)QAVWiTLLDKj4%!LY9gHJK54goW@mq?I!+;Fp2S7W8VfC)VGS&^I6>L!a)@dKh zAxZIEC|@&=by^hc5tAbeVBEb`M2vzSAp?)3wr0rWay*4`4}BT$AMYAO9zw4y2aLm+ z@Kv&YH;Rx!`3oUp@Vx!Q+4AptqnY(vt?mhI6+&hyGNx<%8HyWPskOCLd_Vohx2fy$ z8{)GbKK3jBLHtcd2gn)wA41=G`COQ0=99uZ0(*d&ZPk>B&2wLqdUP%zBj*l2nRbWB z0*i$^_4|6@&LU!#LgpQ;l!yVeWK3C^m8vV2SPij`$R%UKsb{FNzJuC#?ia^%F*P+p zzyEJOBt9!LCSmy)l~vZ$&V9$kaXtLjKeBP-oi1Lod(EZ_d)Gu4q=C_ugMl`#R;AhxrtU zYo_Nn-o)`RqqqEm z#K{Hb1CXTt>QjmFLw)^Fo+1t(Q?^B0%Ab<5U)lQDHr317);}Ftk5^|E5A>@vWmLPDZ^F<>Jf@R>PM{z#`8kBz_XxfO5#L@4Fk}Yan6?K4wOkthAq?|>Xq9a>JLH<>K8&1$fGG%7EfRB zEf{ecc!Gto0Hh5h>A~p&eO~e4hV>0}d z)tIC*OM)JMz(X~aOB;dSzFJGKo@13oQ5Y~WzrwhL5H|+?4<0ec50#4FK%C$&`ZDBt{C4zUiP+nv$}4}vSb(`4)q%}} z5ASn{jfa(y8=*)+{=n-L=xlQc*5ImJ8W|CwyS-8BC@B-0>@qW1k+273ardGxk zVY;|()^jy5>bFoLre_d(r(A@$QAx<#Tu)k^2KA9E@5{Q7I?!eT^P?(**KMGEotfwe z(}5038az~1CRh894qm6}iTp(G-Xl+lzp3OLS(9%IyjxsnS$0Se%9NZJ z{ZtDvR}V)7Q6-ZMEr>o0fUJc_n>vmZ2&EQ6L#-7>B4#o0jElyzWr!F6_AaFhqwg(u z{(3ux1vNXE$Kl8$mBdkAa^XzSPP;I3Qg{6ScDnS<>oCHyn$+NS`L5(%}^T3<4 ze=JUMO`aVr^S9Jn^5%h;>CM4xqDTQ_1LhFS59n*KXG~5bN{oqiv{>l%cjoDpw|#W( zYEY!}{V}>6w$hcjonH0X>1T6JddcUYiuQ8q*i|Odo;{^>bbl%B-&;y$RStSHV5c`Y zy)c8b`po;q>gJ-?y9WS5;7777XGYa zZAHV)%Hl@;a6xSmZ&dhZc zxdEU&@_2S#=?&y4Kdz~~Q)C?_Rz%2PuNnx;;yzqX5HSGihmtdbhym~n_+4982tW%p+Nh}N60`%Tlp2Uf%;tu5u+BO6$-17b$Bjhz65X!lONJpkhl3At9>ca ziBK1L2^lrdWnXIDfi|t~pO1|3cs$}e$QXofs;I1^>B&)QXzrxaGVela+HpjjmrD8s z83Xi=qJPRdHW;luK167E@EZ5^#qAya7i4KJl-!Lzs9hlsU`|;NGNwqxEQUT2vy^-% z8!NnGFm@;)^t!T#Y&5iF%#Qj9ne4}@yStk%Uc5rna{=n>>s?3}&z+{X-h7E>{X+|R z+G-MHa~-4`U43-<@-^K&Z@%#}nw;$wc_7jp>~v7b_z2DTYsnXGSd_-5EHpMfF2+s( zHF1dhS;F=NP5P>J^GwdUIp1&=v9hn-NhbGGG%;7Dn`dUegoek5vhwV1agd|@Q5v7s zFWclS-)DM?$Ma0T>fkx6wDMjWn{Cw1Gc)g|iCI6-nVCM&#(kx{`u@CmCg;2~F*D2a zcwzE*dz+Oy+AK86I&m+{34YE7PaJLXv)nSDG*KYM^9d&{PzUO~*@TH^;xf&19vstp z0&Nr-1E3#Z(I+BrAj~QjG{Bw!83+4Ls}QFchp`WykVW{jnI{S?tj1q77|aVGbCg_C z#AZVFT-cqm$rvN;YIdzV8B+{XwgH$O{W4v-@-2G#)T{`}gw5TdnC{zIl6QsmO0Z>K z7+U8R#Ogzq5!F`NgfVtQp;K+^SCjd#1f>{4t=%RSps5+IqjVT60CiMXyV$iJK#WTe z5daiyD8&o7Ma@9ocJpoygTnY^VL}A}g6tiq9LkuPK!ywIuM7&FcPXPIA>5iua6pzz&!$lq2LVFjmdRose4KwH%s9kvn?0|-MXD>YaJTU#ajVUdX09@q>b zM!f4`c}?sSQ&D21kGw}e-n#3tfs|iykJ`aXP_^VwzoHQ{N zr&t1;^&)&nlun+R7laBHMoq8+9FMb1S`F`(2wk`mU>(Xu^?c9CsTf7$GTasB&odY0 zo)%9&RKd@eWZ5=OW{ZVtD-Gf|v2PsD>1Z=3)5G_A1bKvU7lgnoZ^>BtFor`$HgHwk zf4oe{x-b?a53Yk}hfJ{)wj&Xv1>~&mei`-{h9c~nvu_vn_k@uM0ozC{;4$+vF1LUR z^{3S*Ku%~wS)=XY9YW4gSo(^Kf%@G@A_ifMo;d1eIaI%Ype??5CPXG%4LQtvxIeCL z{%L5ap*jB#1tFG&l~zarC?rf-ON;ajJoDyvDCD0Yhtn;Rx3Z1~`)`QffFln`qf|0B zK(5%IivIJ$J3*S~c^hLA`VQ(`%>}tYyTWR5z+vY8X_D{fxu@k=4sVOs-G^ZZBCYf0r*{ zr@97x&s*gA!e9LFG&MaUzJKfqFO@d@A7nJ!siv+;9Lq&+o)0`!PSx%Ij8aCoAW^N> z#qAV%p8xwlq#HL*i|^0eR}L-yc6(Lc0$9 zIz^LJROYQCm&+}VYk@qc&-{>n{K6O0NAjbh+(urH9RKvfpKE#-T&+rBwU^N|j_#5dn)(1t;m<_<(_*Z$7pQORD2w^ixtVDxwj*Z`Qy*aiww&t@y z00axY@{naIF$k)#S+^VD$pOQ4f+q`*f-vOcnbm3*Sx5RFG7zL8z)MI^gF6kvFv#tr zP(aC$UL=dXQ~($QaL$5<47WM#QKasHcXew$Wb%8!Xn$W1pwBAr7wrmLv`q*%csA`h zQ24aZSEz@Ki^l~JHy}$AoF6f3VZ6ch73z4L#wNX}6FqDe5d%XdHd$6HCO15BJJ3D8 z=}Cq!xlP@3@*VR#`Yk-C z zrKP1=->p_Vm+}0<{G1nDrnLfXTD^lpJY)L0&IzxW@sWP&y?IG|R%zeSC&hWnGv@3i zKb^gXJ!2rFOF34IO?ja8jB%P%^cz1{M|U4|Q>oJ^QjOO_cO7t3O@*1R@i>6-3UkX^ zJY$MP%wnt;5ra1k0$0ud`LPZSISu6*gWiqyad_{8bm7u98Xg%F$Gu)Jz4+pbboA&^ zI(zmknRs5PO7Hig@*LQGFZJ{e(#`HZaop*2(#ex2#r!%kF(HoCHpo19w1b@`JeeNg zxywrJJNJpXI5(A*mDBgX|35_@JS{w9$Z~`meUx_YJ)Aesi!Xka=XANi0G=@x$5Bee zg0yqrk-T}{I`KX7`Q*m=!ZXHwnBw6eb?!M#W!#tb@|-*W3XP4)=Y?lXiRU22!VzlS zd5|h9SdP%ibF=##_4Zy8dEgmSQF)M}tn;?)*h}8ZD&0IIBi(fQ%3C7OQgArTR6r*7BSN`c3n1u%;qDsAnE6rH%#YOgIHqc3HNC{F;zm_+d15LQ5* z-A(c+{|7Jwie!HA@;kNRJX;(j1m0GtQ;31mZeUsw=1kO{E(LXjw9>`NOH#W^=aLXN2RT9zE|3MOLK z*!DLAC?lR9-p?Sn<^v$D{M5@j49Jx#?!$!u<1)N!v^p31zSfY9x*eO8d#maJIaSgE zG(7$*uIpi4}xSIYZVMxion+%MQZ+23A)*?JRL<4=2h*3~^4B>H_%P9j8 z@r}^cD{rK~-C96~012Z<#K0DT`3*z}7JVov;u?Jfwg~HRoT~qJmdbw`AlqOjT8PP) zB?8*?j^ew25D;2$#ll?c98dB5@1FlO}3ya`2of`y>9Y zZ*REWpdB;x(#Al~_P>^77#$tmxYFLC7`pNc^u5<6X?!|Hm#)r>RYmArS)rZQh%NEb zL?O0z^MQAa3|W>DG$3H;hb&{EEB!ba9N{*&nvi7}%*WG4>|E^J;S%=jBEtpZ?t_rFjxz^jF4puI|Ml%hE;yg-r=r#-EWFMg-LtKqknLWtn=_h9q0auL)VU z9srS|`Wh6{r9zgWWH<*(K7^#)y3H4|44VOCrHU4KUbvv*-69r!L#_RmhbGIsFZmAi z6s3(r=DlwVY_sBS2MA;23WylAO%S6n#%RZl^#Tm1xrVeN5wrEMSwsxb)hlHYk0nl( zrG_QLlVOwgFTHS_+fb4fV0eF~sHC)%9(d@H^clAYBH=JiPELsDgSFCb_S4aZZGK0q+7>tq~mW4vT2CIv3vKav{s~fVlwWLc2me;&J5#!FsWnNz`E#}0clF=b*{&$v&=^2hiXsuS z80$&IuoJD@@r_Pd!Dk7|$I(ADupZIx9?>!YAMVJ6U1MKKQ{8 z()jo|m6w;(cfb2xaZDSg?CIk!s%-d0VK+H<@fz(rd@qkDnX$_^J4NTtyhgr=Brj0f zr;od-w&@czAGFh{GZ$#rfxF0J$+Rcm+$>$Y^frx5zfGpJ8v58FC)G87h>WIMdi9OB zslH`5Rd}-(kX$_dI&}}fypZRSgDz@nc@J3~9rV+eUg!Ls;(L3jUNH*v4GP(*=hA|go!sJYx604XiG54Ez3_+c1_ld!{ ziapSBi4obBGxnI$5)18Wl{Uhw-65Jz+s3Tn6diwq~SCBF&_gr49uGa ztTr+ue1k7D89{-?aRtP;gaEIAnBI39&~C7qG!(zxO*U4*7spgpz&m{VqMy`)Kuo^c zuv*%%VF0`{aLz3WS;mviT0)ks2e2vy&y2o?cBjITX+xi=kY(_k!8v$F7=V#i`+VAv zWgtj!4#-iEDRngvYOo3g&kk2)j16!Zj)^+Ov#WQY#jWy)*<2!~h&vrq(*p->_QV;MHyMp=t#;}eW-nelKj5d(k_U#o{WWV8U!cTl$B+41-T z9x?Xk!}m@cq+r-A#(N|fGVXieq4ck}4`38_*d4+koZ^m?NZDvUT17Q({gv*J6Hsph zgCUA0jTB+=Zn@3;A&;Q11CWE1oQgTPkT7Kc3>*kchIa@L8F;H>Zb#^l%5rIp$2^EI zAt)bYQRGpw2gp3+$9W)W)L4LUQaB%TI)1}v5I%U$jl`-vVm7u&>jFe`K>eZKA$O^9 z7#Z=cDamab10NwoZa`*Gj|ycB_GQ z)Jwzd)SR2+xJhV0%XG&7p_pbH#1hi?pWd7&11Ne{`B)-;yiD&ENrI} zZ@xkOy*+f{+*x|<^%GR;VSV2r^B~k)nWuw1Wi|BQ{^T#|^r=&njK}EO)hl%N^eLK~ zouO}i=lf)_#>wTD?-~8w;cO*uMFahhKmQ_~JaLkS2Koi5H1C_EvC$Fw+Sk8H24jLs zHBoBvp}EdMAAQV4I~puhUtywh7vEzhD(ol-*HsA0ZAp6kn2YW?;HF(IHcEwAKZztL zk}!zz26hFleGR0(c3i;zK~Hl2`wlv(t&ZgpQ<5h5y@Ax}xWIKZncZLV!8V+r;2zec zY?$ZdA`{GO2+<0_W`Kp;2+vw6?86o@{-W=7^#+A41alN*pL`2Mw?FuWY;oiZQ&zLi zVakeR%sOLg@QJQR!Z1;04=o{ z=-@6l)v?l|(*B)pDrF^+br8Z_tB#ktj5O^_2r>rBD-@c|1XdNUgp5I*LD@n=J;Cq= z%m?CJudI-ye?vli@1^2wZx_gk)FRS*9x6{C)kiKF11v>~0Qm?Rr8J?Q*OibltdWpm zU{43!Yh_8c@m%N;GBEtCmXN{9nguTz9Av=z2xY*7MWftLZ6=}gVxv9W7j=+J#%v`b z1|D;GMyxnq*Tm1Rd%T$Ln1uF<)yoRY5iu}0<|^_VjY5eSoYPbV+PJq zz;VponB#FC?y1HV08I%pqn_M|c82^&dcgcHj2}9A*BiG}Xfi#Zt|9B8ohYIOo)b&% zX~IzQ8{{>}Wx#q6GNThQ;W0fj9^<^&^w>fjtxgf%RtrVitb~ZcyMs{<`kywP55(3)#t>c4stc3}WraZ~ljJ^2D@iaoqP#FFjf_Whi5LKKv(0MY zcShv*vo1W(@-~kP`I6ZPeE>4Jf%QJ<5!vTQxGPN0rg+S^2$?^~3hn^+59r7$DSaDl z?B0WJN?9JH*`^@a^yo)9#X2rdLnVA`yo}Lzc8Ke)8n`dYH5$-E-I+^y`LBAXx9u|Ll zdV0h$lueN_$g`v60Hu;9dgHBA;@ITmB#%q;f?R^P51y&A+O$B%AWv)49v-vGgl7zZ zaS8Xp-#{QB@`1onWDN2&)$Js&r-pv`!pq`ZjBgmz@ci)jLmrSSii|;?+M0H%@;1;< zUwoa%jf8l1goQhC;sn|4c2N&Fe>pM+B*^<7aEdVqfJ}*Y)!t;I>4`AS@%W-YnrE=1 zis+Xl1mU~;<14S}s8vaA28T!r4x1@`%r5?-d^dVSf{elEtxm>3m{&=W0sz8zVUp4Q4ukjV!>(;j z9B5y@KPQYl5py%r8X=$pzYy0XpdWkkU@X)l=0+La5AS8R)9d!%NFPX zJR_c25i%%0j6ai8ED+AbgmDxTM_F9w26E~41lp4=PYGR zUkWg~AV0if+~x#5^>BG!xy&E7(}^n`l;jBvWQ@mCK}YYpJN@hJ3(ScQhl6F?knoTR z#XVH+7-X3=lwK&GUGFf0_Vk4)k}wj&lrQBSlaGvnjG&Cj3OG+0-eFkBHDQd$+=+za zYQ-qNZ@1ofyAv^M1=`_y6Ec{WM0gjzc1N3&bt}6V?;-Cgtd@vDm}-=BaY|AL&wU_c z`07;ZoFi|^DAjmIcpQq*%)BIn*Mp2P8Ltc3Th#>~0iV~JAXh^##k{!`6dB|5S*hz< z3C+)0DCD>2O*2zg8XYlD!ZgAcvejgq(Qz*#ezJ2lhfHA1rYo*!>6B*6B$!Mvh z*49>0r`m)u{L+=PG&(*e^rAwrG9o5do|l_v-)=+ zB(v>U78&y!zwsN?)zwAsd*A!$op;{JB4d!}xraUEDmg|sZVoJvF~9X&za@y6ojZ5x zdd2{`WXv!B@-Nfn%a;Wip-095yK=~w_rCYNgm8z7xB#?d4A9YzQIC`csx!vn~lpokwwM;&GkE3KhBUbc=pQ5N^!o*qa|a2hT3d0 z24UTro0|n$r0Ss%GUlmcav#@RIC!oAA#t-eD9Dt20HOBt&s7O|A{W@}c7%26nLtu_ z*oeKoSl#*)jM)Z=1g}z*6JRh{Xrk}`p{uf=s7F&!1|g)l;6 zzXiqi7IEu<0SyD)dJ!@Z@?hwOpsR#l2y=*8t;m=|`%1-NyBrWENlV7Sc!29ELIZoY z;3_EFMqs66j20?n1b}mJt`=@53;4GI83UzqYDUIJFY6ngx0p2m0RQw!L_t)e-XGqi z;S2ig*pJ+=BmmlRookimO^kZffoY2yi*c)^6sT7YX8 zO30v$SP_Z-2;l`ro*5Rtp{%29GW%LmMfh(#X^1}I5p3dhQ*I#0N=5}wQZxjz-+9fNlVLpcCLu`-C} z8q|SY!#fP?nFSd-iSMa3+;3$RiI~EGcDP=I4C)x;2F7&EHM@2=Xr5(7UjTW{WHw0; zkc(G?Sw=}MmLg*E0qWbpV35vS4$_sbS?cN;5h<0NrJZd-ehwc^`7r-ExxdAPk#x0W zOgw&7)CJ14S^dDl^=31r$ZAYc2g|ojwXFLkEi^c6Bag=;NDvr(*CSai9J7Rn)V}wS; z0LV^DVXG1`fFfhip6)x+OmW(iMaHzWv4 z@IV2UBV+I!=!3gx z2c8Gx2I>O@&T?c7#)9`g<`s)3^?-Tc@>M_iI;i-V|X^` z{IG4PIR|9UQxA9q0ip-vT#}|=%if!4IV4?13hvd{+hK!&O#=E8KEsxQzskmF;y>7H zT-h5o4qIQ|x|P^0GN!nJ{|XVBKTW~8S1HVY6%t81MI(Mzc#`zJ*Q7h+g{$*4ITfXb zI=e8;tyJk;4qN7>DJ$)k#p3dT=qPwoe~oaa22B71xLQ>bj~Qrw&PdU4W}>L9D5HDt zzMBs1*B2-=NYVA{H|W*ZPSeCpY+NPDxBc6CVQSMh%=8mz%dx(U>E_ebp^$Supn9X?RJZOx_mw;^ekvO<(^0vuJAa`Z5gXl zppYZZJXZ5V;ldc8R>f>(A_k!aK=`gd7Psjwjcr!k?Ev(t+!e(zD5^H9N5r%?Wj1Z! zXsm>Yfe|K`R4QWgf%b%j2zo0Pq1a&mi9&$65eZ%~RkoPev|r5+xfqeNqc-v_Rj- z{HuUD6W*E%FxF`|We0Fh?&j_JfVMKib9?R_xRtPOM9dvDf9btfy>^k?elV}7P5t57 z0i#HFUs!y9;I2|Z{$h-Gv&_vZ7o9jWFRq6WHMsy0)1pJfXxsBjf&GiHav3n0cF^2x ztssV0yMh0M`+p=pU%MHko&l+EVeFh_IaX_kEVU%5atY%m@=VVs$roFE4!pmy@JP+s z5AC;!4YL90bJ#rpjY~V|J3ky|x!Eb6XFc)0M<=PdPQK%5f0Ew5mU-VO$Ms7|N=6;j z*eEv-uc(wd^z`JY_}eqxL$O3CE0mBPibPC)K#l?duh7wo=p5-UI@roY3~-}I+AiSb z^2;ASM3L09R8r!mB$=qZZm0N7Ar_jY^XGod^W9g)cjWnn=Q=29`8eyeteaZxR92gv zClL)$_w~2vtKa_9^bv`VJo_7T`En2audjVud_R8tI2|}}Kz#nIzxpfjS8e*Q@Z3|s zMAK6t`jgLnQG5ppbI(2Z2s!18UrZl6WFf09^Fp3^^yerMv(kV5qtA=)AUmFV>M8N} z-~GFPCywpfZy|>>ljrgKKSWjK&Gaw-&3_V84alVrfB3`VFUkgQnzl|em6d1S;e*HD zBZ!~R{@%Y8goVljG6rQE92}&EX43+Z1>Ak;2|-HzpTGYfDIAW7Jiqiyza*~z!V52m zJUAcu@&QE1KmBwanU;tF_P5_0qu$y4jr9KgZhGwQ#hx_^{exlp&P%g28`W>KmE7Nd z{i7A>Z;LT~DnwWQ-FW(2VFY0E^6u z8~AS#fPk4B{cD;T`3nm9PEaT~BsPSC(GOaV*~FbGlvp5QdIv%@Ivx?5oC^h%|1WyR zY#m5ee03f&5Mq$dzrflMKGGV4&I}gyW|JpyL#~*(WHMi_0o1-yr`n#|F zl)n0n7wN*~F}{b9+ml&b!$3Al#7$(jCdg{f7Jy)kM)}|gu%1|{XN;9^e|VRR-uqOw zFg`n2v2xgq)Y0Ok1G`J;dQU*OgaWsVXABJBAmQHQ36jHv_aG-ul>#xMd6xa-WTZ0z zEBX0zB)#|uiVwyBT&!Tnn2k23U6=&<3*jOP z+1~>sH0A|t+V3eb(&2siSD(Lh;V{p=CJ~}+-+@EqDPMYzx7!u)j)}#vK!NAWCA?#> z8nbsG%(6yGZ03*m1Vgh>UNnHA8|SD+B{&cJM!|3iU>?=;kimDz3@|w8C5$`pfPl=I z>q)U*kY&q+Mq5q7o>fJUn3Y5Cy`o(d>LCMJ5Pt#aDv*InORpdZg1&x&Awqc?O*JpsLs_Vty$+3R% zcRn)D!bip{PY*>RW@%vj){-j-SFT5v8raa7nft!E7KG}Z59Jv!qVqw-)pJ9+Y?I8W;t z<1(j2m@;hOuRLRr2iHePv~%a=GcM;DgT=k~94rw;a6VkP5}?_zEUO-xs;$)4kbhwh z>|57+<-Rd`aPoL`d|!S~Ye&6>dY|_dyk`s$+-KL_Ge!&8KwyKw!X%I|7<(`e7O^$3 zS)MV)H?D(ZB1rz}AJJsrAJEX1U!>9QKcZ__Ptoh@8QvG?**sRoMjBvA`vYk zhfTV1s|2@E!~lKhp@)`CSUrF^q1wDi@Q8uu4$x3xrUT73k(#}k0X@jV<5q_&O~4@K zDn`ozo5K598G|uryJ0+#qQAVDqSr5l==9}4RzHU_4`aR7l~^bZEbIbMgep8%;WCbM z6`+{H<3#~sMbt*ysH5RAtT>cy0{M_1lX>oMFu36UAdUdNdqXG(khh=5F;#vjF?F?> z5MFBm`WZZJwAY3K1Bx*wz3JH)P4HNWSgr^o2KWO>p}dE9?1Vu`k=wg=IC(t9v#^B3 zmqQsL*bMS`i*^U%%IUI-&pkXg!z%_v49>xCxE6@V?Lx#rh%cgu%>>4RuAb1MexXOi zz%aF*3FD105T(ECp%5Yl#-?K0*rWy84EAk+$1Mz|!qdWG67xE|FtjLyG{g1O`?s5t zbob%>s||a`>M0QBv6$tk+S)p*WSQ(vMtOOKFu=@(>nIS_U-=1wp`+DKPLq5Wn4=|7 z=h_5MXN%}_3OIK_L#s*8=qm0_OZ>KlKlVg}wx1?5T6}WVcC~PYcL?8$rYUMGL_rB?dF-|weyzVZnD{i~1CP0k zR(S0o&j&yF!SvDXitKUH-=L|SWsu~#D7YK%I{O;=QxOUnOQ9=Z5eCLf?f9up@a}_+ z3*+uqA4``*F-%z+@#rLl=Hv$aiP)q#R!GIXd47&=4oVlvn|%T5?GFiKD-3?i0m3N+ zt@2XK0&%kvY>5|_CJwePmM$Lz`H}I6F!rVohCgV`&(hzrf!`2s^wCEj<%w>9%!#+e@zdPSzVpVM_zXik!bs_3 zb?;-PVan_*gWS8a2=PhV6LFTl)3xIX>NA0A~zZ2_cWTMnmQ*Py+;~= z@Eizhp$)|#6o8!2T)D=17%v8Mh(QntAX)%)yPJK%h3<#@tSDsJuqI>~Kcl)gt|vp5 z$+j-bpB=I+w;vP^R#+l(6)b>u4Dv)>8!M+#?mz&_6g)r@!XxXchq<3|z5w?@li4WB zd**@+H+J9gGVU{Y5L`4R!Yqh=V7QD}&EMAS5X$(~8v#M`K#8cYwNq^sD-;eW_2Sk7 z+l`39%0RT!H6#5#ZY{P%AvP3S^$D^6(n^5-phv{4C&akZAW3PA7x2oKJB;9qnXucZlO!T)rNluHkul>%{lOcjWoZ`zoo* z>m;MKg`8!(#BqUirCh!ippn@W{q#i{+6DyNEue@p>?nEvJO|3@*+fV2TgZ~>qb0O!&nGAp@n(f7L)bOs z!8n9HZI%yHmMkz#S^lqHzKS_{1xctOD^MsRv`G(hz3Z@ruT_}~6< z`j-qoTl!i0!A({`{tMCD|LSd?aLdGTc)(!)m%#Lo7YG<2h+Wh*Fk57(AB8|DAqbfB zH((Hy-V{9pd@U9z+M69>1)zdj)DzEH-IEJ67=-KbdaMN#Gh5=tDa-0D20Ah}R|k`d z&k&RZG{u9U592zFxn369@fY z1Q0T>y*NT+qnWzOMO}lF?tfS+5b%OSJ?0WJIG(G_!$=QhQk{ozT75$iE=T4W#Xc%& zV+E7|<=Fz@KAS<~?wvogP`oT)c7!xaIn5VZQv}DXj9xo?P zj^nJS%(@T)>+9bgr|T1$r$wF*JXA`R6`6LZJs*qsUOh2Kmxfsu6-Oi)^Qm{&ld0ra z#CdhKRb;E!K~_tq{Ul;x8tQq6{>NYaKjJ&?2r|a(`E80v!_?eVPv){Ve#aU8F_lV? zfBZWA`~N0AYyglk?wZe1G~}n&mPRtT8p!P~P5&w}KXxT656GCx=HH|wtBv(_)s(VT zQ>n+B{#62b{_u1Eg2G|BDZM0PevSL3nHn2vDQ@ymd8OR9Ng*(KlfLlf|CdI_2E=!e zF+2DE63^RCzE2IsjV0u*X%@dJgl78bi(mcE)ZHgTx#=O7jEN`AG&L*Rn$?n^^3w2% z$(V_0w+K@U)OZ6cCS!bl7lqPY1ouZd{^wUlC^%%Ko#$iZ_T`sJibTxvPz21ZZ}})V z7)y=Z`?M+ovLv}zrC+fwFqSG}2H{I_ot0v<$e3-vXH1i&iB2_~qD#9k(WTK#v~PGH zb+&b;er@Zbs-UZC??;sXbuE`~Qk2$Inpr&@}Z8hiP~sBGLp8zT*g$ zlTKq(QR*EI(be9d@PxtNx6jSe$+u_d#EEGN`QlW;FZ+}4t)+Vol+l3>7aiJFLi;=1 zw5QF<$wf_77OLXT?y$&ssAxaR5DK6{VU-V7heNS}Kng?g*2gMZ_c{Sy3g<5Q=;F0` z5gHDmjUXhc)tOqL#-Z>*2%DXY2_tn+e~2fDp!kl^Uw9Hlgo%(ye9Yxo9Di8hsV6>7 z?|IM1=&N6qt0mTg-}}Aa6W%n49hyvQu*T#KGNuOQXD-%>3zFPGTPZKg-qU5RD0I&l zi`hmWdG24)&W?M@TiHrwp2me_G?noH>EfC;QGeel>KTrR_ksG;l9|f^=QNF*zL-gFXaxg!w|=YgguI-k0Ayq`JmV$B%o(xlneX zbYMXDa-E`IBlM1)uZ;-;b&6_60wFfX=fMyG=9}R=bA`< zDuJ=?+$BFH+Tsze&$-DKCR8MLx(zn=wX0zC>B^e&H1knHA;1 z2K>-H@Sf0iAj9kJA%ovQD&;1$5u`=Gv0U85ve{-4F+hcntaYjrGx~^u8Df zZLAI7hBkzLDs+aZfqaqd6pC6Y9(A#PvHp9;_~WyDk2nS5MhfTbY2z>_$&@ftDrq98 zUFve)v_V*T#suOa;*yKcOJO~U81#AA3^1-}qZI%czff-MpHb;HP)Dta_O)4QPm7iI zwc9z_Xm6{Xb~Rh6v%x~O9s^bIc{U@@iOGb>kM|&byyRyr!~^MrvI2!J&@B{bLm)a8 z^6eP|{Z;9g(1(_q4{jweE(3Um-oX%ExRIU6WTqfL%M|OF=dNKdrOeaf6Sfi1o^Nwl z$QMe|$Yh+p^RpT9u?(usgW>65C--&RQF4`(QBBhxD)m&5)n;2rHk+NG&c6EEKZrcY zeW=qxM*BTvvpcA<{Q$X3Jfg2J`3n zs%hRsW#!f6u!Xol`ymgE7SR6d(PEvQzd67pC zAjGtL#tct1(3PG8)H7I4*LyuQGVT!bg)btBBRy#Mi~*T*^5T6oG+sm3yIpkoW;yra z6w8KD3di+rH@SPpoWF5|x(A!MJ(bgyo24{7?qa!ij;72!7PPY5gM|ZJzveV4lPKl! z3>)@8JgHL_pKhc5xkJG0={b?3_$I?ev2e`Dhx3|-oGiO*3laqzkGX|u?fB(ve z_zZNmyV9R>vATCrsAr7JRZhS1^Zy}zG#l6hCm0Np)f}KJ7ypWGj!6NjrqZ@RAgmM^ ztlv35EA|Qj95$19LU=eBO-3#=w*&64cJ3=`MI8tgkTUR&z~n-rPneTue1eDpF#`iF zCPn;*&uC9DGN5dDE*M(WGr*{WP5qUU1E6i7O=wqR16z-X!8K)}H=Kw8()Dv|u_X$z zq1dWVi2k8GV?5RbefTL4E9UxRH3*W4xg@=GP8!v6Jz`os3HsQ3^Lrvdp#92^dg4~**yOL@kq5M?l4m0On%QTF_s&u|-w)1f2Bcn;6Bks>7g{&|WAyXi=S46Bk0 zygzuyEElTGUb2g9&K4d&V&oftQ7G2hK8V$bn1eIWf42Z^y{fN5mg^ai9@ttB8P)gm z0VE6v2fH0BA&s=7#gR4Fiv>M{5%CwsMYJg_FoMAwdz9qL1%+bGL`;Db0}L2_TrXWK z@M0_!*wYDy=vJ0{HVSxukjMSpMlk1~&M>ZH5f$bV59?frRsi7r<$B1h6=J^HKq3ZM zYnU>vXNf$*9;8oE2Bfl zzU(7BV?I*8FeSfz`EHh5rHfU$r;O(;NwA;3`ada=lnX-hh^$5E z0AncZHChr_0SooYT?X3OViVr1HC34iF@*wSDaLE;K?iwbU^K>k#vn+4Eud#W<|&j| zE`}*vAugIP(v#jN1@W@)xA)OE|MNF#SGA1&`1t?TN`Ls&Zt}A*_|mBvvEe>?9Ku>* z?+Cad##oTYYH@@vLMJn%-=C4cBzWS&IR4vi~)=&;^$D|guZ0@m;SZ~vX{yZfniA!GjV5C4!39z2+r zj5&MBN8fsNR(uAwA{o=&-Ay;IohIMpIf~MR*vuYS3mJ3b%&Zt-cXzmi_XNV6AZ)=9 zD{)XJphzFwSIU#P4E=>NLeU1{g2B`0V?l~LbGgSxT|Gge(C_Ya2_rv@i;z*U^6TQ2 zdFtRgg<(KT;K17oM9o9o_Z7bJwO$%tf{bZxbJJ7LGzfAP#G!&78M6RB7w_Qz``Zx; z#$h1H81K=>*PW1IWmgd+*@TSryvaw%tOW~Y(hxE*Fkl0=L;KvqK!+7!STT(ioM$fh zM2N^{P1q9vtqRwIpbVhi)M_=5YZ$);u~DxvF36v=ur-MoAhkI}44_jln~yC~hz-M5 zemeATEgAFicb5x6H6K96{NO}LH#FG}Z*oa81_o0t8M7472i0cJ=;ta_5x%bn5%c|@ zBq$I_e_@n+4D{q9GS5H!Ai?sW__!EcUr#=Y`NTjME+u(x$p3b$s|@tW1MA#h8Q*^a zWnX+>dB2Qodi6$9lu-{4^LaIVz82lRNjh~l`~1cR1KoF5K6y6-yrb^^Oq;+wgZT&w zPe-dm7+*1_pS>IqGPc(H4@Sowtc2x*3Q>l=Vj8?gdhY4$a2pDf^Im%S!d+BeQ9*4x z7RQP&0`DnFlamv)zv}CGLzQ9Qn9(^Rf84}!hEepxTo}zIWOnSLxtTt4m?zSGRIYSf zDbUwJ`lvpu2nQHRRVc%y$Qa0nSlm|0I?~=w=OQH@Wm81V#FX@cM;nAk1>^>VoknPB z5CDY&Wri%H!mF+t`G=1MT(}ZgmPjZq@vxkM4W-L?jD+lN;;}s?V)jR3L7JJF;^&;_ zew5!336B!=)%7N2&?ZoR$Wrh&-^H>#R+j=W&|r^07-+B%N;zSyCn2NmztLDPGA14w zA}2`$DS-ApFvhK#9U_3!wRC+Or^Klwv3D)&}XQ&W?8=h)X_ZhD-@+ir4sq|Ue$ z8Pi!~q>sKkqu-DUIYDpQ{ za3D}+8qSt@aiS0#TM~5Q3s>eT5Qy<0DDMR$5>he=h04K$uY)^_nLA1i-F;{`dCIb5 zYUUyk^3mwT0QC>u;KKQ{8rjM*1zwsNtA+Dpy zn3rFEnLPG4Y5z_+xqju_BQ!K42Q!o@%g~&K)xC>C$rzy3-5`Yiipn|)1?Mv>mL_Jn z4fAAbN>b7tTk!N+Eg1uEpfeYJbYORhAjaTD;jkM7iE^_yNYniL-ABsA%3Kf%@all# z0`jDl`zw@lEv|M2gg|~|f2n9op-`MkOKqYZoxb1`gb&K8C2+d?LR>FFdhEfB0qE;r z?WK{S{A5fAE3!8;-5~gy>URGUnk2pCEUM{w9`ATZm>RUZdwVRGSel4fQxXQc!w;c^-1zT*a-KZw5dg9MNL7+*8< zpBBds!E+DfMT!Q7GjDfrC?)gpwE$dqcc=a}RtuE<>;Dkv`=HF}gA5Q$GqWj{3o?Yv z%Wv=)#$^Jbq6Ln@(4Zw`K*YTHb~5X_>YDAX%M&taN7&y?YcNMxiOHEbEA<$cB+3a`JNeTVYrU5d$4^ zWIX#^y#K}u1KoAdO>NDE*n-vu=z`NccfNJTM}6aoEK&w@XBCfCt6ks-U`)B4$QV7q z!&1!|@G4S^j4)4O0pL>eR3T){yYDSsv^NbF6e=4X_NM8c%!EwBzt3`>^3v?F#Obt9 zWx34r)7NI`^vzh7(fHAW4r;8;e%B6%mD_-96R)0}rMIp`v+_K0z(q}Ui^olEi0&_a zf0hQuGCKWzyX~~2d9gtpQAd=a{MGXzdgoGbq3(|Du+W|z*|sRN89Kf^ALP=HPWZV$ zFFl4M%-=u#l*Th=yqUTNCCMJaG>a?+O0qL4>vGCVgZKsFts}LJz7mj7BvcQ@KDT7rRuf9D+ zT_drq&HpjbV`F(>%e**cCEWnP8>YKgZn&;CGRL22)JEa3i&6#~Sy@QfzpIUo9o!>+ zUnxM$^bB0*N%t~OGK*JOK==R&LH54U^O8Aw;5mBv#nb6;YXf2oL--5?0(ADQRFZde zCaJMmPEI|2K@nB~z{;51y-_k)-Md%`8Pj0(ig(e_+)3WbS~`FFRdIZJF2rp&NhzLC z6Yk6;zgjW|dx_lW4$%F_%UN-V^8^TiCdHGYg%!JySm6i{AsBrSW7=keSDQf)cOYW0 z(oPG+sl3wVr#&661)>H!;uBrh$>g z0-BvC=1=T1(IY!;6uh^SzWL$|aS<1=QZfeEFhVAx30YPkAv44G#tPIzfmNp?Tozmx zMhvl64%aQb{6Mm}(n2fV-{}kUg1Ew@jpXF=R<=~KV-$KtadCi}im&p-d?G#=D%i|>EtGj#Cy z`_tdDfff0~7k{6A{Ki${X=24d-_)+0S}hTy#o%y?UVbA<&ps(VT>wSK96M~J-5r^6 zcsYQy`2Gt?dgOlY&pG7BdP0#gqI{j%&#K6m`|dJQd#h1=A0JQAM?a7~_sX(j(|rTI z|5?+*H9^cg`KTOc0UUqxZOr>AdWw(ddeY>gt2Z+zLSDn(6j(W2Qz;GYAkML`2gW=V zk_gD>eW9SPTWgQfGmn<%Rh+(m`d#F3S5a%5z7cOTQ0jJ31uO0~RbG};G;CQK)3b9t zKTnCjp>Y1WVVf^K9Y_8p$PrtwOJaESh?RJgj}{9wG=SFL3z~zat%D2 zmO@>%TA^rIF&Tr6$VW$P6lW#7q0T^XigG$_R9TjyH%`roK^R6?j2WR&lI}iILT;y- z=6L*YI?QA=B2?_7rt6Dk#y|iu?4LO5;x-}MXD;x3KRp$shDLod1|$qtnJ-5WgN!+U^(*Ob%j5XL z$LVKjG6p2fz&LEy)-xY(|s}1?Zh+X^%YUjY|wvN8|9mu4tNHTO*SV;(RnBt=wfW}x00nrSQgG?ysj9>{D(B@w z^8nbVv6J65&^sCz3ux3hkS`CyhVR|!qVh5m4Nb;{_m-+Vy*yapdL+H~3S_{my^#e% zDj)R87_DcF9G|uV8S~8-{)F2@MA%{TE!Zjo+kV8wyst&MEkO?)c8PtNZv~{M%slmu z#Aq%mw>$vU!VlO0bFo=u%(maaKNrVh$LLGWFHyu0q2K-T9;zyL&=2375`*crt^hZX z7*$kQbdA|&mImueE%fZ8RrJVx6(UU0%CJnwEU@1qY*HDQV{eC>DqM24SvWlzi1^#^ z5U`oZbQ`m>Fp{4-@1xPNa2630jaXQrs^ofbP?C>7a_=E};=#LkV5}0quLf3&jVJ1Q z7BqGXp?PX%eBpioKH^(vn~MizGhsgqkOJ4POj42u{aj!(et5ck=tCdUO%FWqfCy`* z4Q&QN9Nz~9Kr@9kj4 zS~Bqwf|m^XkQNAkh4OXx1!;VW>w5xjy7S^#Q-fU^kcPrEJ{h6jzK|d-KmzRFgH1Uz zb@5+1ee_R{o9H)>o3qjfcA2P>Cua+n!*jTf-oEG;8~7)F~w^C>_MA7+ZCi$Y2 z3`EK3w9?57{w&rW&jTX_NLaiMNvdQv^#|dBbI>LLOe!nh)SurC;&*2@^_OwIGxx^k z%5sGa{^k>4wLp83aom$)H4cnzxPBypvL~p2I3f&kXcwZ)JeEPI#Ds@B2Z@2QYKa&< zppByJA{8(m7KxZ5)&mgG;IWB)j*!rPRQrPv3NJqO8|G<{idz+G1OMiRHhT1lpQDnJ z65TY?{VH9(ex3p`{b#x7*dw%O|NXjo6R|L*{6Awk#!o4hZ!n%MBp!3JzUw4usFhd` zA_nlyv$8kZ+CXR;918fQbLvlq2rrRiLxI*Y|1J-JX-2&u|F4-*`@0i zeE}OnE5Hzf>mNH%B0OQ>nE)~k;sNF+%rEdT05Im~i{Fef6Ytu}N;-_GcONMg^GGgy z!7}O^YonHyR-OwM%k~?Mno2J{e9tlNLv>W;E$2G6lZo4TZgM-Ff~aY2YT)^=jGryQ z^K7=ly3xR#8ID=WW4**WPiEnU0@~R1?hu6%EH9-Df}BtrszWBgLJr6s+JtN39E^dv zeHSYaLB>EPa9LPZu_VZ8#-0nw1)27)-Pr8fN=?-!>h1|r6rqOejdb@uhd4Gd79wBR zKxLfQWnsCP^V^MlZ!X`>ZVSr}vMtT~v2Y09SJ*qoK$mX>g=_>R8|?@(-mZ2RMPhQV zhD6FtB`nTP^O%k2!n}=f1Y=TOY+Uyi<$LYKT-Jgcz~wBVhwgnB9oTgbmr>tyaV5a} zLI`JXc{O>Td+Aj(hTdGzJQIcUL6r*>3VPA z-&p12{u<^vB1+$XX@&-;65QTnA`K1%>7k=hDzT4pUHT{)>CQ@HV>f7U_!8Guj_jRz zv@8@##NfPMjVA?AW=+t$?se0n_jwjA#N13^4BgRUCyOCTvoq2I0-OEg{b7MIbSUU{ zD*>KU8#XBa2L8!~c^xutq5CXs1wg;T;tvIcqcof3{-YTGP_G!9wC`NO&T|0j73Zml z8yFL{z@@b)$XNGkNf0%XgP>SXPNg?ZM%cYmc$LGzjFb@*S zH9Q#?pYc4H+c7tbc|7M_l_Fe)L*p^NkKD>ZTX#Vg9~S2^il`vC7k)?k$*sFwq} zAKRNDT!$wbScaA4Bjh<-df%NZ-6#2Z5<;%fj;TdtfH8MYvna>P@AvMVW_tfqUe+lJ zU);0aK)da1b5c_+&)YL$3i8x|y%C{<__-fJe$CY*(LXk01ON4%Ww!vzQt6Ghxxdy` zIq2n6GvX^&(!-dHNk^>`*TTt);lWlXed|<_sf4m=({s-~M~^-B7C=@Q-CcBZ)F}&4-Jf~G(>^~z#bsidjjG+Hnl8qTg56#Y>YoK6`_gA zD7jn~u2(xxoJl%=#m@q2jG7x3uVTV#Kdj8#-RTySD2)FVji!HiodPf4OrNdsG0V_ZuY%ctk9!o%2Aq1W>zF^FR*ARevm-D?rqTusV z2}U#++n#*bOZ#?7*Z%#x-Biuxg1(PQ5B&(AVWdI$3J_u_8~Oo&cd`@_vr-g^n5~Ab zKfdJx{Sfh~K?q>gol0mo2xoxbuo_7F+rUsnB#<;)8KK}D1*iMc-!e!hxNYhj&&A~E z4GPT;roUwnnxCZT{0Ix1i@ga~)&x@PM#LG_o3xlkF;StfEU5e8@@ z021cW`;ODm11tB+h6l|9cO9X7jvU}QV{>&5hr_{jR-68o4ZJr1;Uoa9u?l?;i^Fmg zRvhLtq+@=?dxt^snTN~h*FIiFzxwe?dhT(4XM7L5+ZvCN>b)kBEG*mOEyGA$@5ON= z%lq=$b^N=`Uq$TCEOI$`NgYdYZo=1}9@TA3_F<1m*;4w+ILl`x2 zE`SiOO9DmFrgZ}9@8vgV7s(2T_T5eId+JkET_IQZt|#EFQBzaPGVwvW|Hv~umhMRZ zB7yxG5khP&fYAzV01Lb@F1&NjC;mc)Rd#;Jeb}_OvDUURsm?}sA5O2v&GYWiPTupR zm)of$D;?U)dO z(w;qggqMsKFrYeF-pq%A$pk(BGv7k`)=Lxg&Z(cJe_en4?Ck*GXO6z}+C0r`_QBD@ zX&I(6^Ut!9Bl#1$as9hAIXxwGqO8PvN^XJ|f1yN-_B@P9JF192^T8_G)44TlK^U*@ zIZ{d=e6oUe)ft6x6Tq0E)$KM0c{Q151@lA-Re?3esMXS%iUn+Qm+KfJzSXR2kTpx?e1o zSeU~gmxIhNr0%vFwqJ?22H;7im0{ow^PxxG^w|9sVjSBFfOq`|o~fim?G_Q98-Na? z^!i(Y+s-ov_!HNkP$U|my01bIGK!7*2Zlq!z*t(cc!fh13yX(3-7JVzZ%N~q-EN_M z9d5FuA~Z0b5Ua^BIAS1HtJ-fDXo(moftaXbQ6tUHl=0sL#lit?b1)(?K3&YO5t%UQrpN`o?fpnwmXBfAQD5P^Nhi>KK*h~O!kx0QR*Im0W>1Qmcerc25*oC2<&0yAuE*Qz>YAP<>SoSb2lIP}G!haH~Lh#zX@_>hAVYIGUoq-rj|D_RMK|`Nf}5 zr6)i)d%E&^#>99G85j)k+#Sfu|LRLG(!~qsDIDyhbJu2QYAzv+x+_g$j>_pvYawFt zddA#H(LDb)IFuCo!i-J8GerNH6}EzBj4FGsXUxcGN<4>3XD`S)eEcDkcy5&ax+pt5 zvJHZ$!TvGoe1vm@*UeJ|9vjni0lSyxlVb9G3h%>X>W zQ?Usuv-PKsWPte}q2U5N&BaoZv{2z2a^JH87FFO~VI{Ee8cZjgtMxLetuT?dR9*}E z%cYwUmSPOFw+$g=WIdj`7@%;%M6J~(o+ss8dii>gW|c%lH~Og zO-&gn!Nb`8PBZ=C@0HNL77Mj;emli!f2&n|b{P{i;Y+fdniAeRXmd_({|KdmRrwy4 zw;`V(gzc)0N2|=Hh!`#LWw$%%=|?_HjkOyeb`R|Vo-(B_FV$4m)4)h~`WI=uTZ@Mb zWNyenkhL&Y!x)Ota)CfHOIAYv2Pv~rsiTqKtMd?#6^FPj?T{&$NxpC+8B@JN$JWBm z?SDtTY@1VaB{Ub5d-R~ZKA%s7^0HW5R9)33#yITxsXSv=g0*^C|zG(=TZ zRl++4o-vi&?ps+7SEQE$JO&_>09YBEo03T@g#r$KuJ!YbQ40c7Q)dSA^WD)$Ixa#+kxBW8``0zuQeG0l|(jN9&kp8eypsq2`YJqyj`Dl0f%9V@N6;03qMy+^qGGSqed}J47d0uI@7J zk;h(sPKU!NWQTlpx2$K3i|2fhwF0Mqh`xNc6Kz5#(EdIEpZX=4obNk^ll$QMiDVS zA3q;YYB1o2{46+5+b9+ZQJm9Lk3L8b-hX#G$Hu{Ez}^-OEPQyWe>mf{kW0wq0`CNF z-WE(iJW#_Jiw)&f+S4h8bblaD-}}ipADb7)u{TbLJAEi^lif@*2Eu{zeo!ccjOpBc zgn~i;qA+D97O2b0_*v4?H!xXa_0nows%&v}nnghfBg#YRp#h z0Js3pgt?cqfb+c`78b(NT^K;T?hx0V5@0r-kjacCOA#_F0s1lii^t+*C(juG&40xU-B6OJ z)V`yYdWL)R#(%zkZGv8W=?tAb@fL-G0iL&~1PSx}^WUWLi7D2MQ#3W_C+_Z|udg)a zDspS}h*^q^0YFk938B4J|CtrGDj72~i+LgQEJ(Npem}TR)?KFTl8m{^*8qW|&c`)s zs^o9^5aM|Y^SlCN6&Q=K`MU+f7`K_S5(8nci1Dcy%NJHLH!0*JW2Re5f_3q(ot{;KF6hOqlvt_-25N04`9CjOxPfB@eqk%;aUi*dgw`?Gc=zJha z;UtVMT>t6uN=wF6SYuS~G*F2xC6b%_H^PT$(>%)?2&Do*sYSRsgowa3S4YNBnv5YK zM+{EFo7_Ov)lz2v=fCDASGq4l)JYgO*H=2wowIsP+x6_TAl8l*|nW4jn4^vZ96TSZW>*5@j z%RomCV((A!bpcbeu`J^>jK*3S1&BrstaH1?c)DI>3`ioUA+-xT@OTIQiKV_*ryhPDilJlK;J;w@H=oj5Hd@V zF=DYwZH@TbH++rd%1LoN7y4n!P)7!;t*Pd6y2Mz0x$A9lPA+uAl*L)zpQ#eulxB}QX~*D5uU`OX?bBO zG6oYn1_?}na&Ll6!Z9_$gQS2#MEg68-`M*@i;?k2)>@8zSkA>580->U?5;Er1fh7Icb1YDoxfX~R03Ie~JmEudR02$f6j>u7!}WwV zj4>rc$jG?fOA#^{Pw|e?&X!6L^g+IXph$7yAq1f;U43Dio{5S+g3Sb-P9r~qS={UF z#eisIVlNp!7x&S&T_n^+?y;rP)O1XgM*+{f)rlBD3G}E(BoW$&>mJ9kLLKAGnvm)4 zw+Oeq00jfaI`j)IU;z}N&LX01ZL&zB}+b}S}i4j(kqBM%tGek;onF+hgU*ji)^%7qR5 z@f<4Qx2rd>03#(rkY&m)2^U;jor`GOxV{|-5Q~d5i2@_%1!r}-(OU888ndl?WR?wk6PTk~k80dOG z&%fL*VSqxKWnJvhE{AyMYb9f_SY;+GjX?;9*V@c^YE9(gc~%cYqabg1oVJ<8+=?+9 zZ3|E<=3%hKJiQ^v(|z7L?c+X}krhD1JoV6r1i7@?fLww7O%SrVwz_cxL{uvjG&LI~(Vnx2!9 zSaQ+C^_p+b7?d#c(2T5Cj#V=&WfE8J=mh`^4ZL*?Y)D7Jh?(r`AtE5gQL|YO4kM2i`>`D_0$@4pxe-f*^ypBUY5dix9_JxvfD- zL4OZwP0lfH}Xm$|jWhx6jYhD<|gY zBFj8@hqaoq5?IQ>qm*`RS-e!3G@H9I{b^%?y;^`Aa{Z6 zf_IJ9Sd6(8p$p*^y^-m}86S@$AxZ`($UifZzIz7Y*&!MoxVkW=s|3R%7EoYOlG8dv zEtRK4YAioVb>8(QO)+j3lH5)MB@N}=Po3oA1TtuLc8>18`)=_U$MBoB2cV5Ze$=9- zGDFss^Vkf7wE{mqne6@4)I7N2bneQ{{OR)Ii5U9LN)q(TjuuCrBuFo!TV0jaty&@F2MJ!mxdR3mkw z4caAP+X3$vZ5>cV%)1`libM?hS-u22nwg$_$V1H)w6I^|X5zN@jDaB(gAP`TE5krd zi40AqHI8jJl$Bb^%@c6fU{rWafQiRoyV5X1TLB1{aQWIi#aQ6Q1QQIzX{0yEN)gsu3`x<6KtHWfXNbjt|%a0wlcgcz%Z}KK9{SU z-v5DrMosO9sIF-@Ro1qP&qx-#ho2$F`J>d?+(&c46qO0LJ{bZc5R|K20T?b<>LIgL z0HGuqj?<|NKKk)1)AXPJw1*ylsFJ?(;|cnge{h5T{s-eM7)7XOBu107SUsPhp|J>! zb3OaG8nsFBV5M9~2M?7CA!s3`Nin=rtnk`+4;ic&O^EA4sLSUeQwT8DV$)E#ctR0| z@P~T9>PSWWpv@y>0)%0#I>E}J^$Jav3q0R;B4U;T-T_uGVP%wBc~!*50Asw?_=GkL zqsG3SF51)S6o%xg3aeOEh`6$GeyvclK+<^lH_@I`203PMvrx(kyk^QZ1nRBC!k#hQ z%#~-%u3ftbn|x!1?cku?l>g|_4pvHg#AiLsYdmB2@88eul*gk`NaTlSOl1vL&t(iT z*i#DQ*Wx5M-Of!2Z39EpYH;CllHPhJDLg&gE_sbJ7vb$mx}Gt5o+k?E-{X@!wogk% z7-?#nk4+eLJ!3!uefLKR;eFE63r`%3sp%hAh^0JZdiq&08qM~M!M)+(q6MDuEI)ga z6=3|PJY!I%riScu;S~c9n&muW0IV|AF7{CKhLh(eygwKt@I4n$;`0G}1ppVa zh93OJXM_QHBLRY>v#mM(ZDUdCE$6;A!Q+X(fnvR2Gft7sFqHn50qPwFmjFCtcz(fH z253EFYDzi3_ro+kzl)}WI~OINFGzjE6C$i(JZ7f(StsYWiSw`ZSm}Cif`*5tc#N>o zgs+8e4wliCZVUDGjq-U`nh({p3{@qLb$5^Q^^834l~eyji#T@qdVu??pQfhFWVeH? z<91qWrq?dLm%4^K7o|Y7hUfDx;e`&PG~^+8EJ6-}7cb^hjL+!bWhFB7)J6jLIeC@` zpfuoNfzV`T^TxD+}YJhx5JjqBGJ681%V`<>S)WekgZDsXXWU@%1IuZ8G( z&m51lV=W+75?-n|2BobM*XG|=9HT`XApq(4dJLx^oeuO^p$xqM+ zKK2Xru}^%G9(&>`@%JO|e^Pjg^$%SU=R;!63x$j4$9qz^-92LzHrqo6{b!K%UvGs)jC+v# zLs1^z4QAFIVb_TZQ?MSfgL>C`yHt8DLMPwR;t=6qn^=Cf@oykl5Hd?Ik9rmyAD@u> zUf?)vZWw2=&;qs@X)nm{A%g{$@D70e2p%z*yVP}EE}nmvsk`MoWZ?1UZzxPknkDXya!KXdxWI~34;KnN=AZzOup6Fk^&Ix_8TEr1;jI(vVAkV5gy z+_)K@F}EEV6A50WcVF%z=byTGfG~>?WeBaKjFMg+IPN;&5u1E(cT`u}$!bW@%^}HZ zW8$<~O=2+KPPo|{6k%Nuo(!(ceOKprkVdF4bbuuN`mg=!sub;LlqV2Q(=#)y;Puf! ze?N_kj0ksbzu(UjMqDUBg_mk9L@P=gfIq!E{xTB;mTl$K*z>J1p-DT1v3ja z+T$40m4Hy|GSL1VPI~gba@viRK8+<5;z6&fg!5PpG{X~HE|90O%1I4gJ3V!OCGBms zQJI}5J{HVMInQ)D&tfu$#2z;a2mz)w?n1EZV?{*4YIV@jLr zoTq-xY75*K;n4~uWMD9Y;Yly8){wPc7#dE|z@(8zXG}CW$!ZHjY!J~J6jQL3tx2400gFeS(i0P`2_w^lL+?JCUgYjPUpNzup{(V6oI0b`)M zkI9RJjKK!}xR*K)>E$<)!qABg{6S2Ch??Q&l6%Y`1f@K`m%m@ShE2Ay_kjMm65;oQ zu}94BHff~D9Ro3UAc1ht1(a{hC;6br7`Hh=yE+_VuFFLz=AxkC0W!elVFU5-J;&0Y zHXaDeQBvZjq0#a5k&S`L5FnRv@rJhW2J9QkCS&kkC#EuU7s#075B(0c?|P8xn-4BZ zv4oW_TzpNCF^RZ?tfofp7o|K-%+lQK4Eg8%;yY3(7!k*iOy)9fPo-jyKy@rdoZnK) zW3OZ3*z6n@hqy(uJL25;!cb2> z!MF=z0HnCst7DaePFZO=ojr4&oF#I+h75>d8V20e0(~BHCXAEH;0J&Jggk?B1TrX$ zfM^GL{eGoDJ2YDA=x0AWN3Xx}7R4fA>bcn^(yK4OM6bR67R6IxDlN-??=Tc13{<`p ziidgJo#HbiEaS^PR#r>KjEr9pM#|-qiQj2e^?tH>_ESkkJS|G%qB4V_oFWw9KyH@6boQZd_k_45S#ejuWU1{dA-Xi9kTM4u+6%q}rpYPja z6SCa8;1)g_LYB?@Vl>5LBEq>LA_Mfje6}FGqdSp|0Z=C^A!H!Or+CPN_@YP1V6MbC zrne{#WAEe?WW*%ZR@sH_H!~CF>tbP|k>#wIka+dT7yxyz$Q9JT90v^)iCaaO_6i=W zu&@C7gt~?{k9rn(=wQ%>zS`ODq>eVH(C3BDlGYpZ5i)Z;c3{lG_vS_$?dfz0uYc5` z%hkqpP|b5h6@RWIhoh1zy)|4v6?}db|0Yw3yOQVUa&BkUe2$mPRLNsz6`$u_I47R; zP$^%>#K!`WT8bvT{2Vs2AX#jjANG$B8IvwSsMzdwzE{ISe!H`hBH>c1uCAd-qLStU zjWVxFHoMT>BCy*T-7Jrqc?`|uM+!yDSTCs}gV{@S!6vR_zL&^v6@LvT3x!zNXUUms z&B|o}313fkyLVHP#q8p~JtyAJtp@tVkjBHX$&;jyy+_~EdTq$a2b%%(m#PXg4Go4U z#PcYy8DxxMbaZrcpLBx(GG?m(KhT%HKf*#>lCIqFliwew8lJ4|tT66rcG3r*O}n?F zc9+4*D`%M;tE%n%nGpWxn?D?-i@kC+4+iY!Mn~SkeM3+{J?6vIOq4EO@ryw+!Ot>q z(?@<`0Of1)|4%*jq;S1n2_n%b&CJaS!o|-DNjwGy8$za3Nbna)9mD2aRaI5Oh_oC6 zAs_wZwSQp6R1y@Z=lhOV@IbyoAtk5Eurd#Ow_rZs-((eSv~Q%6uJ$$yrE_w$mj-(D zH(M>QY@p^HhsotG=AZK0fKgSUnY)!EB6m= z+ktZ0H;_%nG&k-eoYGojp?w-sGZq;qj|)l((cpNLUOnd*pS6G?9AU~}R8qjCE{Oz* z-T?#M=+0lC2lrybRURDE-xZ+TsSs-ra`0^Vz^{E-RC)DR?Edhl+ztYmjIdHf))l;# zlq?4CE*KIU>WuWzebV^%;!j8D^2J$sf({xQo%G?4wxqx12ZY1H(QuXmt0e`{6%ir~ z@!l06bio@%0ju=2VXiP{2p8jY-Qga?{Ejew%HLRVOaHbyaRbNkJA?=`&vAueecs8YV4aEz12*ao3Z*hc zEC(3eVWd;QDj*Ql_Z}_fxd4VF?%W0=c}k4*>d84lC>}lFW`#)pX5#nZv>WJ^x8(SX z6>SRbEg6FFRsrM1&0aaaNBk@=UCt<|Pe1*%*!KlSJ>Vbz%F}e=@=qzCSuv!=_&}V7 zN94;YEiD!KzwwQ4i0^f^)pYDID}OT+ViR5fo(|c_e$gOCpbUZltE*be_#=VqegB1o z7`p+G3{O6q{VX`=>;I6c13h%?h*22K6+@9Op`d}r#++1L6QY(zGwp28^m`B-xUa&e zKDv5?hAiLWF$4e+^XyZZdV1$GjiRV|qb>DnDK?6hC?*QlETs>gULpui< z15(|Ye&lJESG3-?`2ZpYbN^E4O3Ssi_9#8`Soxw5XTWrzisr1pk^Z(Z=xA-;G_M#f ze)`%8emBe4QxrphArT+!mGBX)Z1179SMSHE7) zzWp8gn=k!4iX@E`kCu?du)KV;TBJ-PEXYhzwKGYNz3bnLy{dA7a3_EG-~JKx^K-PY zj+N>C&<}DA_saos^8f5}e?}E`7P8sp*ahR=-G@tb zJ>6Cc7!MH!2w`?0vqP7HJPJaryFVlr3&2>s9){rEJC4ySFLu-L=(q@_i7=ei)z$Rn zFMnD5UR7(PhUS$$6WWU~(3%@)cBWO-e@#tI`q#pN#e?UsekJ{FX*76@^obALN1nES zK^0zo0`J_pm+A9g_~+?w8EAbv zzZ1xgFTF8K*gG{hj~4h1d$y_l@<1kn9C7fZRbG;$i#(4&7Sr}=GlH@trXiTtdAE)z|{Vbnn<~nIF$jDiOyyWX6Of2-9c+$*zLy9b>1ik-#f5_Ky z(fIhdApSQ4k#LAch6ZSCWRTn?9%^oFr;;*H`q$-=h{w4u=BfAQ4W8RV)YjfXPIoD} z+=VaDkForZGK`Ooa2ZOds-}*-RVyF!SA#?%LSy46X?FHHw}Y|t(alHiKv=YWz->v= zFFseneP^W$G-Up*h?8f0bn;S&d@;Gd6YO~Pb#@UZ`+W~q(ZPqLZo6K%?L1?QMkhrA z7wF8@A)1+cvxDgH0V7pa#<*<-=)Sw`f=B~#(%0js>8bp}ij&_-O+CVRB={Z5 zdeQ>~K6uFBJVj{Xc|f4R7?1XY`bCU=rBE&MkP(XG>Oz)nXKY0x2H`k{I6wM7R%T&t ziu3ylar?t~Ff|?HF^AtKzaxz6auqtC!>?{&C@h3>yjuuGI3M}Z&vE|JNzN5pK5@0` z9$!VmSdG4b6@h5iP*O4WES2ycK!_=zZ=$bY!)GWb5YV9DU@y$V zM?F0^C=k;xbA;=4ZazcAARjgpR$=AfW;U`%c(PpJoZUM!=V((^WrAvJ;@o~@Om@Wm-r4RDimTJXea;Z#&yX<;qHQRT zPk5fFYaZeGVJ%pye7ifduZ=Kfdgq}Gxhs@$U4$abz4p!>`OAy<10w+HqQr&8E%G?V zK9I(kN3dcPzbjyD^74B}ohib3DWG5BEO^EsKE7NTnvGDRnj*$S>2Di@gL^u;uWr6f zed6s?WOr=frqW!wWyTZfFBzcTu_>!R&h^dbARL7jP`aOcgk@#Zeli&>WU-f~e~}2y z4$)B08+7T~d0`k#CTx6O;RcgJfH@3CGW;bY>kZuhoEEH5E*C3a6Y*G9ipQe#*4y7_ zc{nLTmcp{gC`d9yoy1KeVUF1suJTG7{gO0EgLI!#hV($0$3{Z(j8ttI3K_1liZd@7AwjjG; zp#$_*g!zPwWw%Q?ON1KdIT!C`t*ET1r@r19n&;=iA_HuEk4^6pjuUXXdCt!9j9Chb zh>>9Zi)FYu-z+DDFdJP+p)ib<z3fUOPGwm`zgv`lfJK90+I1b$f<3IMG zsj9Gu`Cuym&j%S0D7Pl)WADLA^X#%`W2xWPhz+W2Tw@o z($E*rUk^O-XCyo+3&yH=y zOF(@80HzYK=zF@&k+l1?bHX!Z_aki&`+Nm5y~;pRPUIV$>$9jw4)wi zkUw&AMi?2fD!k+582NpQ7ao6L(8(q$=Jc5}lV^}Gb z4&g|Mo__h~eEmw~2PW$G-kfEg#H1!mj*PkGj{nOOUJ18{hn{%wYwBKeam|e%p{7=) z5Gq#2g+d{+S=_X>^*ON(zk^gd54}9Dd`M}yQi8D`-P z!nlqB#Wy!XMj{+C(#(XNJhQnuxH5s&YNf)mS+d$?8^j+Bgr4e3rM^irP(=Ue$!XfM zzKHiT@%^w86AV#VnS+%qzcA2m+gL1&?LprD`YXfKaXy|OJQ>%ouu|RD8uEo%pk{$< zK0^S6>Apc2f8*DidxQ+~_s64P@Eh6)89hVTQX*-{WCryh2+&fg(Be`$Vj$S|vw{dg z7X}EdmV$zGk%f9F%!s_gDyZc*d(%IK@6lLxBhmI1wvY0oF#( z=wm^xx%9XUFB4IBFe;<%@vMBPc~!jkco2A)YIq30AH_VZ%ymt-^$3QOxsF z0)0qE#)P?F9Y3M;Wz4;pKViUo{`u#{w(tJkr|GdLe?r3^{k}EchyEFN#=zJGLUaux zWB$kIs_2myPLnU993PL2d1v%RL}@@#MbTG8IAN7&5A#qfEALgzGhyt365H<%Q8^3k z>)u7HNEZt9FY$EMM~pcp8=%cGVye?b#!UFv(xfqSV|KPc%COsSyiWbJbeNi&rXT#| zr?hJAI(19_VI&_lTfU)wibES2lMFawD$7jtpa}&$+3TnJ#ugD>4x={4|H)&A zDD3ZKA!=e#BV*(OBpDe46o!hZ*ro8**4106ulpQ%SyqQpt7CdtIL48pY(=x3CZ@wQ z>xoi*wOJV0I=a0)w(Vr$G2PNAd2^g+=L488w6$Wc*?KcAYgnazN{@<)3gL(W4jno~ z4?g%{%#i^71w30XGDb^iFBs17oH9jscQ^gy!T+SnI!DYQgZb^o9VPs`;^TsWNDR!W zsKd36Wu3Yz3(q3~auwS7IbtzbfR3DSQ(bLl4%~D|j*LM%JG8^Y4?irv&n7Y^(Gdfk zCL-=78IZe^3y0?#eNtTzrIpQCU}&NpTjMLbv8V@q3r6D$13{V!q`nu6#Uxhw0x&e= z8O#TqABH$ALV^4W!zbjJD(1`b*+BMn*z!AOas}jS8R20uM(Lxs7K+rx*L&x=p$)V;3+7NPU_jJAQsaH-{=XOL$+SR<#&nT^NN0cM z%o(9uNWg)UixUUVpvx7w&zYIjwx9Wcg%emLj(cotYZIT7F*@2w-+kay{BCJT-?Z*{}Rp^VDMAp zKI%C?p?;&_fB*0Qt-hNdM~)ncDP~gPfO3-jn*3f%0A69BhhmuyoqcEMt;4U1_c(IX zx}xmbJE_UiIb(J|`VZ<}3ZPh)Rn+o?@1pu;TP}$+26DG%j-CTPt&+NncM=BvOdT>& z3kBWr!fT5Ox0XrlheZZikdJ`Qjn4e z3dw=DQCBEP+qagmuw@kdXXs!b4fn^}S;EFL)dyFbsJ_%hMIYEm5By?~3W{tQt;)>5 zLk79U6VsAu9Ws|1@w?0qE~O&|fbfofa@&pNqCeq*AzA~%^69hOH+g(rzr9$@BZzdu zcSse38e3SgcK!Ae@q1Y92lfRX0%I`xAo^%Zh=$B}YhM1q9EmoE5g`|#z2O+c${@^L z0NNXc{Ea+p#`*c-`N;3Eq6{nSc-l$8<>rhjbJ*z9zy5#8RoNy!O9cFG3QYHtd-`Zv zXUz4RcF;A~euSK5iTv9$HAsfAoBA(&U&k5q&gqA64B)xKXtil=0hxJDJHz}H*uaYI z3@h7My*TCxQz0wk>*l0kyMk;mk&YOk#AT#cUUks9^MfLS zuA`%acI?;@bHG+s8dyG6R~2aN8BqF_zWAkNX3o!Vr#CPrLt+WUV?eV-oE5rg`d-~RTuMeR#KyAoLH zKbbgWu<)$7xL7?hJzyyNhj0BO%eYZ$YEzDZthj!aQ>59+1=1M1)?qiY8fE< z7sZrOTN0^s@H@$KXtvNgV^G%&`W_;UPMo`GK=0YI zKEAjw81m4Mo}QW`H#U_-sHDh2!LTx39JaX51(|Qym#7cGp#V7Si77F$PzR1wAQXYr zr~s>%%WZMvCs0serF(8G74Oe>c9Qx(4zkbUlnW*lrMkohqHW1n#f1+bbeu)~|L^m0F-4IKp!g z^di0JDG9Xq)U<_l-!fX$#?M7v=!Z7C<>o)6^0LIm%cZ5IqDEUPjE|2~Pfw4ib0*Q% z)kTAYgQDJ<$CJ8Wqyiiia8!U`zq_1(tUG7Vo)vZ6U~|egog3~Aju@FzQxE<9?ey*M zAd8UX_=^WbMv2sQj6z$KKKFrgG0!bFz)yW%?yubMAO~Q)ryJM#0-W1VzB)thAkT4& z=!|*Sr6~hEQ?Jw8r@Dj?hn(-TV?p}=eyb(MMDmTn(I}niWFh->l+JZC2%Fu~gnW6+T^v%&}tBP!Avr8UZ3LSR63@MH`_ za)jUaUYMc~3lS2#cI~3(=FF70&dyFkiZML}L@FnEO-B&Q<$E}FKu}gvp~zLj&-pYV z|0ICOo`$-G8()&slr3w!ndf1fb)wqS1b@Fr{2P6 zgxw;#Mv}|npxK$?InQx1NUp@#dHqJZcB`FME;G;=^9wf%A6WeY;QHa1z&L_niqCit zgE!hA1xLpwgRFe9V#41;sX-fKq8J=zrJwhO5&idCy!0Dui9Wp6lt8z%aDU_9F|nZJ zTwg=`kI$0Tri4Gw2mHo@QkMDWOIa3AONQT&Da$Zs-z`X1P%cHWend?{kOsNk;5pc; ztTY^8fgY>x@tly?9?us7Jm#=LJ};bgSn)P7t?*A~TVh-{naLoo$Ox>zCPR z9n-278%>S-$q)&X-4snAOqIb%;(S?box7jI9Hr6%1633n$i!n6ii}8Y!#n}=aBVSB zxywN1{C#z)i7HEs;uv|nUo8qKj2dZ_prwLLQ`T75L^s_0>r_!yD-2YUuqw;uD5Qyz zlXT|nv6N}bc5J_$+Scu&^2(}&etY=9Il0C**gw#9`e z3i8;q@iVVte%m`35Q=XB_cy0a`Th!WgKTr8DTCuuug`dB1F^)Te#$?_Mn{>iI;p%& zFZv zN&^IkjNNIZ;!=gzEk>HM1gL4s09(XHcB|4);D{L?9TW?gAluA@Jv={}#C!Cuq2U0J zTfcDn!N7*7QUG)P{81S5eLokF8BSrLg^Km7ucE5*x%F-IFfcGc-~ayi>E)MSPB2(O z4wZmo2A}66K`$q$z_V3K2rk^9~rd^ zw9Q4=Y%Uaw4H{})w72~Z>KtsO&Vf35<+V|o9Gs=F$CyCl<0hK*RZ~^tZDe(>rDe@E zv}5ChILFC$4^0OWuL+J4L8PP*!dL`({ZSF^h3~Y0>g8e?%%Ga@=yyCMZBFt2E{mmV`gADDD(xS)P>G~_Q`&9EDjJABU5sr z58Qc!vPf<*;3~V0O6xyNHLbr#6^*}6B{g>nDz3VXO6%^U^2Se4N$tJlC|pgGBZpXC zoIe^VB~mo7Ojm|QHhz|8@hp)BTWh$)w#80UhU^je9W5}2OpaSwS0*0sNXcy0C5l?f z>t?-l)|fyu(?;s)3+o;e46r<=A@KMpg~j;9qDie?LksXR@Ea_yf{u&(MSA2?ZWGjn z85s2PcBD@?@tgpAice%7sE4k{KQcUu?^zDyJ`ed1^NOq|131k5`#kn+kpKA=x&Yp% zBV0Suduo9(1$_Zd73eg@#Vi}BPT$l}_&xT=^M=D4j&InSkopV`%F=mKO~OvIvUN56 z?w9_GYHPMJA6_F;WK~yfrJ9;LA){#Fa5&OB`MqARh!lbI``EE#Jg=M(ju|}Xa2QVY0BR9&X~#Z0Bu@TNH<)QuayvSboNE*jklxJ zH>^x-Fq}uj0cOwv7LkH<-v__OOl!H=*JLi?&Q(VRrMHl?_NtZ3hZz~r@` zlefwDp-@OLJRGkFqk)A3&lFF*%IY*s_z2rvXll50&Y1S&uLy+_bneXCG(9y&KCfFS znAP=dR9vPQB2qbHP?zU;2McEW8+caQK7mPpAjR zWWVw1d#I#ffL!(|8l8?%gr6-SjqPx>KmZCc#}5XA{EW?fZ4ls~$Rg|(`PF?i%6%Hf z*wt+=kq$8!jEHEb;gKM{r#wI<=ERk0fS;Ro0+(Uu$#qp_R?Zk8Zw?t&qEO%uh&?Z{ z9pmEN<&e1?95Dcl5HR?_83SjokK5PIJREJ@dC@DL3%)}?LfeDCyFC%n*We%ozrntN zKuCjrUup# zZ=uSnbrfcWVzA#$5kD(^ej|U5lR0Xqb(`*>y82DDe8n|%@2-BjnvVyCgJJ3#R{GB6 z=8S2mZK0hvDk*TZKz?MK!$lLrd+Fq<<0+jn+qUeY6)Wea6}8%U9^-jrvhOiE*)jEw zbH-q-BZUrlDtICICk(nUWR>!38IMJ*6vK*SFY{r@5HRX$74l2~#dvBuER^Muv5-*e zab6e+l;5Td48-p)pq>O|L>SR3O3fnWMl#&Ag@Vz=OOr4=Gei9YgS2{88@GRM2H{L` z!vk728;iKQJ01uj-6}tWZ@xcf9uZS!rToHWo<^ z1B;UNb70hwpVMJ@WQ2x?M=0PAQ(=iR4#BhF zJb|3JP~f+r`#^?)0T-!_QD05UGl(LB>;ofnE zx}<9!XUu%5$+&CLnr194Q~DoEcr+8bM%4FdYgfU*N$T0L;-1?ThKS;cF@3Z zKtyOKIAeG|!tb>qih|EKKFzv;$--krd457hbt?L{j0{RfZclJwz`ekU1gxsJ&{Z4q zA7xlnc^frv{%0zzxRLAyE4U3(ug=GJR!1Y5ovW#%{RN8h#lh*APq_Hm_OqTcs+v`x zLuh49@V;!FF?i-Mc*3qE32RZII|A4jX_Do4=o7Ntt;VS6gLPF-YHu&6@i8;`JQfQ0 z?7B2HVWx?3%N&}VNPUbRg@aZyn1g&>A<;MOeEsD-UJAIsYstm38m0^^sKiB2a@#;Y zha3mq273geWKfG1Iz6&v;Cz@jP`4x!Q5NW+ehc`NY!jf6`A&0V;T%|q zEp0i{aRH}{Oy8M_9dR*%cEY_$!0CikZn7P5&DxZ00IqrU>eY0^4L2m*FWLc4nfCT} zArHuXm&zFfM~qykT*zX}9lMG%vpZw~N6`jqT=#Y1xONtAB(qgn1Z6T=siNj8ni@Yw z;m{2CSECqv=+9W#ip3m=)&h@8<#=5PFrFtTgLI+CMjrdb#h^M$d=D7|_xLjA)qPKGEF3NjZ^954!nX!V+#Y2%jr)guytkX1*~HnQ<# z42MjE-yBZzCgGMnJ=XbE=1IU{^G9DDl#n_;S+%qz4UjcH?XR=}of;0f8 z3??pL(-GP!`8{5f2@DbwODZ@W1=Mlzw0IBp1Z8faMJBb*m=c~Os~dKa)#en=n3IQJ zQ1?=RLZlLijL|w{!1zap4paBVE|Go=)Ya>yagV}4q3|rVGX}u#KyjPT_$Zw*P!f|T z`Ful8;OjPSrgB#oD??M%JrtxF6tlN0zYS#z0wvl7!jIiyi7DxLR)sDLRg_zVVH}ZB z%bHL}!XyN^ic%|8RoFys*{v226-1d=a64$p!%gp7Sx4o!tPpLTtuqG5i$jJdFkJI| z4jDvY;4>z?%n7Og^tLZOp&hho+7{ap7VV3%x9^aLc>(wV zR+3rySs)j@nV+eF-ag^s=Z0rzpt>5=hJkQr5{?@fGN3qNoT1O+`RkL?H~uS8T{$aG zu}B5(+&bvxvF{5f_Lt4A$Q`Xb|KZS=sjR%7$B~iF9NWi=ot2!nxpd22pQpOUHB?+u z!_UG@HAQcW;{g~syI5|(n1sS6$KR!dbjH|C5o#*$rLg-g@=orZLk7=odixa5)!cXW zU=5E_bHzpSPVoLoAW~RF6M2G(!>Sf@=_-$;5d;rBm8`=79hg)?-p>GzujMP*&*KqBQ ztY@iv@tiT^V`IW#=4E-Ir73m#jeKEZVv_#fkA5QL9}tY?g+-aAlUfK0O-IRMP*QwJ zw0E$~I312TW2!4KPbH4~o_;^gPT5&eRU$nQ8G||;Z@>MvSoL{1IAek=D-R7^6f!f$ z5}Yvr_%HZ7#u5lJjTVrPu;PE=(C3k7FL+o+S9nQLVJWR!xmCQM4{&Y)(3kWaGSF9& zk*v=olLYjiOj5hp?KV1b@|55~CFNE=2ksIz4$Z<4xlq99iFyh!7{b7b)$@?4B)}ha zZaHfpDs|(A8|dZN&I@M@95CpoD_5?h^XJct_Z1Z;s;DxHzJWAp+TYEjMhsM^1ZPat zL?g4CsI06^=(CY-hs54$|oWhyESAO1Q7; zx8*|MDB36thsD*msarCK!&%L9o0mq0+r>PGv|PD59JMH6UHe?8S267K7=mp`@NoVQ z+fcU77>otTAXBz}hQ9D-88IudZU%v>P`DW&EZ94>k`x=fuh5?bd3FgZCX2>YRrNInf7 zjd>8x7udQ$NNWZ_MoM;Sz$pWV1)@n{>p?V*Jnm8uu0czOJmYSu{`oD1q!{TWp@{|1@N z`iqZ@CMy*bHPPtM>--+JUX^$r#GDD+2r}4U{AFW9n-9%AE_c5)Mx|9wVMn-9z&}I$ z7>Ai~PQMF025H*-kcqKDMinEVaGB>&@)0qWuj1t{Z*q`Yi?K|3d8(2mJCeQrjH zjN$9;JUveCnYd63#`*_;@CWLr)Bsb)iZQ8N2mw}gtN_~WlC<09dkMYwm>^O)g;2=< z@!daBnP^lP<2SF%uqb9yb7^bF;HPid^&y_roFe+=(B5ZR_>E685^xZ-v~6eQp+S7^ z={-TG+mA9sPIR6?V1VHtfTKWL+XljWCN*PlUDXR%P&A;<4LD~@fR6RVyY{ zD4m%&h2BD&ClT$V1!AJ$Yr(1dWWmO$XW&7X^IyMulfZqBioozRK?m)YEx_ z_Pz9=*sh0rKK4J!?kp1X6Y3~zZuo)vje=jknte`WJ)kdQ{shnuF;=yZN;H6Rt_Sc0 zSu>`@8m1e!6^Q5q=_u*v{;YLG?0$15WzCosWf9u3rBJ-b@seN4bAXS&{5C5hv6?aS z_0vlS#n2Y-3r-W#)kVY#PvjuK{+eQ%a!2U#Ju}qV7f_U3=8-T!)Yn*2ws$h1)c5qq ze+LF52mcm+N6y&+Zm-#pDdxn&Dq1`v?L55{fKe0+Gtf3zS(yqfg2k>43xUu#(H;xA z-l5ST%SK@;v4p6l#zgPCX>O{pk;uI?8`-RW%0IfhI>jnHD8RSfyo+jUQWvMq2fqGy z|3I^|Zt;6oR@6&N%c-$t@#^SRn}1GDL%aG(!4uDqQTJ$6^gE!rAu;bh95Ltvlfz{! zgDX)rfAS}PB8)6gJn@7unv_)-scE@#{8H77DYFJCO>1_D_vwJh|KZ_bAroVf5?*15 zNk+1h297+)&(f)W>D%A=u5e7&G}?HMQzFEdHQA|cS#I^QE_C~1 zb6ItzjS4ksq!8Jloy!&q%x}N`kx!D{wS{a2+(#;!)Nd4c#=EHR;?HT%{x`&D@Mior zo>!*D`jMvW{u^A}9!mcUN33*W;MZx{vSngC%Nn3apI2T{L%rSS#C||SQyUdmuApTr zw~5c@nZG2nVVZvY$T0QJ=+7tGBK&|dpD5SWb0PjrjNGxUyzk1kX1e>HyVb3!(bqpt z&pp4J28V{#EzJMJAu?DzbmPt<<^?1iFeYvi7^nmnd^=k2V)E+pe#o)}}cBNQWQ%e1IkcM)GPLp^FLdHo5pT6{@RN z(|d0H6MmP}L3EHw%^113Ko6MTP-g{>2RJO?_`x~huz`aGGKSVxcLj0G%v_|&sk796 zcDK4Ef6(#*q~81TM=CS4fz1zF!E$O?`!^|_Fv;jT`(x_wep=Y!Bd`^!uZU2?E7A%& znZ2OqTvkZU7U+>@MrerV;fgAoQZr`Pl>+|rqPDD-3@n?k_+Bx6wRycr8>9 z`|Y6R z`75P%kIz`|Rz={(sps?WgM#hn+)XYpL zpcK}cN-a163w6d|K}`)e!;WnwR8gMf+|zmVIPTe(M`O;I>I&t0lL14ER*Cfctu#5R zOyp2Fp)4*Iq%-FJ`>&!cZJktL9ZPV=09uEP77)&0_)dmWWK`RSlzUqWXAE%pIb`D3 zkqZ`lmJ|mrS!yyqB#EWOu(qv0JddNNW@(0xLx?SNDzVDc$>#=w%qv$kI|#*6U)wjy zya+~3<+~|&h`ip2PzV5gmsw8d{5+FIMV>G51NZ)STDcl4yXGPo2#|mDF&ZD)ov}0K z=)T8=qdXZAexUb${C_Q~GiG!w7%QMCq3|Pvh{D5)J@8d6@I6*AB8pE7^grp0fwKX8 z9)?$$2l$Nx(_)U0z*|HQ>7js+msrtakJS=*;~<|y^wFqr#K>IOm#Z^I>xi)#BUEY) z3C9xJq^8OuR!YhgWY6xIpzgsSO$E*3zQ7aeYm(;26wo?ito%E0IG_;hnpTHMk5RzC z0Ru5sDWismm!}~4J4@}5fiVF>od> zl{2Qw$$D6L8UL2TV>fQyMPs7_)YpAZ^vz^v48|aw#aJuefi5@RzIZ%459!0&;Kk|U&j%pt=j_REQmi3L_wgaIp#(HwG1(C@`;6>?VKvx z;JJM8#v+zE@-vpJTYpc~fyoEDJAO&s=YCFznnETFr=4YvLiJ05g|{V&Prq@(EBH8^ zadIVlN@q+Ggf6J#jKNs4A^Ssxovz!e*hiqpAVL@z_ZhhF$Ip1r&SF~EW}#v0*Xf`B z_AkY@OW}-hn4o{v)D=a0Tk!(K&?f*y@A1v?s?Fj|1sf~Vtq@CX@c67U;o zdJ-8al+Tc>TN)g6{k5B@x_W-O;mrg6^xEEo3G5u2A;=+2w+ z6X`6|l4XNX$U}!-|B{eJusB3GW0;biGIm>(D%I%h80Lyi83A+t3;W#UEV<&0$q1j} zf6rDw%d-f7c#7z7-TRa;^dRm${q4(dkshYI-^Z*->wHOc!WekM2mk%V7oKJ%Dm&pc zeS}QvYt;K@hJ~XCe%3>?Fdp&_O*|3g%Y&&4aS^GnF&VS7K{|eBRtU8|Pl(PQi?6-` z;D~`kWH)(bNWJK(3sZlXtexm^ z8;Ch$YOC#YQW^9ybDv|pjx~~@h0_CB1Q&#X}IIZG&J-Qy?s7W@w|VhgOxDj z9B0hgV=s}z=@P43>zmrBulv0Cj1|~BZ~IJ2XAGRWkG`Qqt(y4pW*R{ufe0w{MF_=X zlgeTSOkY^Fi)a+owgNZh@QCFb}6AHz8SI6UC&KrH~hg#rr&(wQKI z8i3WW=zsVv{3`kz@}>hwI}76go~Due9IhofZ7Z%Vo7HMQe^kt!(kb?t56_jaCL%Y| zWJG^#=L7w{Jwo9FaL*Q&32(pUMyjiw-;kaSzVqD&=t5_gFgn113dav#>l>P=G6N&d zLQ!x2H?kU(#ajT3s}DUjN~3;D%pj!aj9Fhtbo6Wm9X&B1(vyK;WWnpcefy}MFS%iv ziTq3Kj9Itgvm$j;GSD}lf9(eeMy{@2pSUlizk~AyPDbSYhd~?t8ZsdYn@i_wEaI2BZhALnhhzqDOGZAgxTgMQ0NK`u!g$X;N4u zscBU72+TbK{|extLQA9h(vJ1JauyN1jD7J~U;qQW6lSP~G6bg(E(>iBSeq7c8Fr;vJhVk*e;ih<0` zBcOjGb)uF>XX=OnE|oJz0%;zl9Zt$eSCATRcRXF$!;kzKojj#1kjVvD|8z2@rj>d* z2>Vk)|NLTwyB6BoEfAcN6_N5%E8iD?A5jX%l@uu{M6i-89bmk}ezPoO;T69R1ymwc z%@}M#&S5x#GO2R_h2X@QS(;USNH|6s3IXVg`i>($cR024E1!VC14PVz^7EJ;n+XeL z3!&HAHh>`$wU@905H(a_tU$Msq!pQw7ErHGL1FRpb3Ad@osv#Qto@SdZ(fB6zj}^{BGd0!Q zgaJvH__$oj$^8ZjntUGUA1Iy|wb&YSc@sTb(?{%@nrY%tsh#dUBXN zGb3WPH5@K*#GpX*`7=swnB}XlA+tp(N{LYWnxZ3OJAnEkC%b~enS$}87cH0yP_V#9 zz<&@e04{_3gmR7Xi#kKd;f?FYKGH!00|cIzhsO!{+Qbwq;(aLOIhRkRN4&o&_CAC9 zx-j5c8(AkUDa!Ub77xe^?)CB0X5I(~$qm<(@bgb?FvZ-^P-kOVBt%{}9~(9a1sO_l zx&q*Mj^J4^-c{H_v}0>AU9~Z_F%*2FrO~eBG3QAYzaz$+oMsiHjhv^U6&{ty57&va2l z;DFaF26E)YHk-^;QdY_`$^3@$g`&uKi2GqY%5QKaC?c_@Lvh{&UaFOez+OO;5trK%ZIV2RTDEgz(o73-+HswsiWDjVp)!6(J? zIRJ74WS)AS%U5up#v_K~y^8xWs}%`8b&WVCK*!CNk#mJ`W6s1F0c=({;4hu6LE8gICsHGn85GF>C@U_C8!F-?lI~KWEElL`=?2tGHVQhyUIij+6q}zmSf^h^H zL;^a6-spwiC|AR4QO*0WY)Ng5z0e;LdaT5{Wy-#8(`~f>&DX^HOd|2}0i$VxdA?$Z zz>vObV>9#pDr#M|j#jN*PmN8@3DnZEoJvb8Xy02;iDR^Y>=NZZpX{tHvPP)FWuPKv zp=N`XX53EZ3pQapLd2-7V*`GU?Z5LozayeMP^4Xt)~{brcinXtJ@(jRv11($7a6ID zBB2=?n+gd19C|)7R=B-t4Idtd&;uZ6p$2Jzh%hv$I+{{92>d#gBL=o66henxK}!}} zIjvi>i}%p$C5ZrkIeYdj9X)!KPMCH5;dW76R>me0_$WzQ-fVBES$RQQCMUb*Hy%C=;PJ5PW6`1Yyi z`naW{!uf(NA`%9lnZVd2fj@8C`QK^v#t(~Q7XrWgG>u;TYxR>v>T68(&FOP)`q}d= zNbwF(pzAiDPuYP5l?O&L;!i^Zt8i)5eYJ=hT3AT__Wb zm|~&6*L#&n{+tR>bg*w_Wu>}hE{4bY>7_TGZT402+1*ihW*l{!L3xlScQCa#nx zN61_%BzF@44$RSsplBxr@x3r^F-D*mA{sz%yrhC?12r-UZKrj{i07+`nn~w~0T3DU z$@{8=0-p*GJ~2XFWASUp3eJz+SuTodrozL|j?tNcMB$>kB5_6O9OyM-mVjdR_Q{!; zU?w4XD*EM?b%i>S0eSfGEP=6!72Lpzx=pmA?RqM!N?fsZ;p{PTIV`M59i!)7JxEi5 z#P(~eh|s!~PFmeowxF6ZC_1^N@rS}-0mmMqA&&MaZ6Q)xsZmdvpsPn&J*=$eHqv!h zBX_$&@O{)@yU^_wkpvjmC?b0GCdKiDc0e9^IB&6<7tXG9fB{mbGwbB`!|~Yy&mZT( zbMNf&r#uHzdL-6a3PpEPbwU&K|!jplzO zvmqWPhv<#t?Oq!3$DfaWWQ>8{|DnI7lJX{UlqS{R80(@FZ$Cy4Kl4-au{;|LxX2h; zn#h$0B3UFJWj}x!fs?*#jd%mi??$RSE~BkIr^_h0_t~ zc$ze+pcabbXWX&$hjv>5-F@rF<`~M80jC!0=sb4jM#kVh?n%!fqumB01q@i}2u4Gs zDw_|_Jhz)poIFhiW0V?}DQU{kFSc(f5Xxk>;pb1$BcE9xF| zv0>9jD&z44yz$nf;x{q@u5;HGCv9$3uFYU{lA+@3;@Kn3-2)FiAhzd<`|rP>c5WUb z-{f=j*y~;)i)f!mWx4f|I%Bjrucj!&X#dE~Mf^N+AH&PG{*Wy8{6{JFbUsGCosVF0 z;jzmU36Y6{ROV9VzFe^X?HPLYxK9-Fm#NC~8X2R5RFN?eV;OzrTgo`URFN@X{N#-^ z<=sV1%hyn0X{C_WwTJ|Lv~T~j^x#kbM%|+5nrH{b#$uol{y>@+~JeplJG>Zk01 zRAq0!g_>Pb*5OykJ@A(DYXq-CKH`DFRAh6L*_hdUnhL?Ni6&(+_}X`FnjR-)vH#`8$t~w1fh6}(N*<|s_*ftB_R28Drl7$ya%ChSSp00Av)K2 zGS&vo4OkJ8UMayU1!d(v_aEGH)K1f5H7o?Uc;dE`l@)M{B~JL9Oxo}D_A{A~D;iNQ zW>zr6+$Vi}?`jjP6u;9r276r8an8iThndf55%l+e|Mx-&U$<_ZDD;_%1_lP`JKy<^ zc$LRO5Wy?j-B}PNMCW3xK!6yXm@DM5=){e>w2?74ZMV?fHy6-`Rwo@l=OI5UWnS*1 zGD4=I(n6&g1q04DI4nR=7*AjD(yUKuO(RHVbO0+s zVFXMaArlq*q>7NaT!4r!tO%FFu^hMPXXsnFHvspA6=2%ci}L}zQ{F$6Z*96aq}`EG zhR8La&JhDZ_}{d;Ks;N0MCo|@+{l;>ZBDV`DHTqipBov2)uW4r>h zqU#V9<1&Zowq2!Z#%&_7;04bHQPhZ90bfc^(ItWJ-~h*6msmq|{dQJJ=XoX)CVniq zPUM33gp9)RvT;p;sA~bI7TVg!O10CWL`3Bp5k1B2fj)-S*)aGaB@X)4^lXIhHyV4! z5tiVS>_`!=^-avGcvm5@8SUj3ARz*sG66RMwM zH^Hxn5@by z4RSihFd_|#i*g%B08;%)N)rxpVJZg99Cb? zhm)ty&^Yp2@=q3*L3UJhUo0v>G|57NIR{ZD(qXH|AMjhbM94&V-o4Ntqz<0X^{8tw zBpm6G0nntl9&LmSUeQlx+?eMf2P&x;u@C~X8v2PABHDmA!5DPm;#s=Tb(;6>;E|U4 zpVc}}lauGTjn4_bhjz#WklPI`d#qiq=l})-|F-isp}S%c9U@%hiu8p73-SKv|NNgc zJ8^)#GiT_<{cge2CD1-u7ffCxpzlCG0FZ8U7Z$Flm$uMeTGsH1oQ#L_VR-OO(Z>}M z7AO7}C5tIH-3$HlY^RU>5oN&!QkQ9?Vt|E2#(2WlQr}oL4UE?$(4@PVW$m(G-E`AURLJrGoDztT*W%#8 zgY@X5kEW!jo_b0*Dh*?BZ5vsca znCffng0E?j&JhDNR8-Kq4Yz3eXCmnVa~m9PXameGaLAx7Brq?*1_Or;Qo12BGu7e* zd5$Z{9w$!jVIB9p`e|Xn0$`qA1g_ucqVm!lvUD&SEi^K;m%<@0 z^Dgd#=!WQvAYqe;N6H|g1rahfQ|dmR2~5T)Sy`Xqzf{$<@SqDlq?ZKWLHHp5gB>>p zJQ#egCHmLig?Gg6?nyEk!u${rGRn-3Tg=S;(8TA4l4)j*7e*1Y#l){H&=%&NN7_+x zgZggafH9@GAl@J_uwIUU^Adwcj3K-gf9D4nJroE%=Zhpj`#v4CN{xIEnon8E1rF{% z8yao2b!DlTZ1PFkRVR&A7P{-YD!TXjk{I2(#l`(u-9d$knH5$rLV(v2RxUsYn2(-) z_SredVuF?J+SXJ|AG*0j(ED#F5=`xKfV1|~6t%2KFpNS79T@Zpp*|hps93*-1qF@L zh-15ZHP&^;)=fmaSdO1VI}&M4o04K{+r}cnS6~eD2b8pQD9#SSZ`~>vD}+&@6k?y6 zN}J$Ah^7Hx+(c1w09`*>_!6n{M&jR>mRLo)BMAuK{e15dBATWu^A-F{0XR#r%3mnJ zEG0yPVX_$_RLr`ljUS_MB5^ywc!~ap`_)q_azP-F+4=l40h;QZ(j{EC9>RR?sm^I# zin#ThnDZbrojxrp%d8^e0m44?j%X;tA_-QU@EGFmgEq&Uh&D&DzXM07V@|%y1rYqP z3JXz{+PuYBHHdUN$w0As(BPPxUU}_ng7zQ%1&xL#Q_@3Eev|&=KmU||@#t4+cw&V5 z$HFwt!%3cNA&^%FR*Er;mBTPx!6=0^PH>2U7vOstX(9|-!HD1!(oiG?Y6)zua)fDl zMKng+R+#9vtu{ex>I@0r6D+WO7t@ObDlCX-^PP?uur1dKuv}ui#kilj;91*oG z;4Hz}P0i@5!1TaoP2T4bn=r>rHla8QEWr8W5KLz+Vqbc~?LV)=T>EY(`heTNi`yoA| z z{Zk21J9uuG|1KA3opny0dkQrEdwi2jnV`J!6Y9JC!)CAG>wuAupPzxpBGTa)&DVRwUSz$0lyyp`k;&X; zl5C+BdBe;Do_KLo%(!3st8de9e*U*<=k{&%H(&b-efE-{2`L&Z~yjhsj@0wH*aDxNaL)VNZB)v+Bh|Vxx9K6BBW5+r@3-wlBt&XPC+%#>1YmAKf1>?0j9DqB9!e{-KWEtXP> zubu}P{|6mSO`KU-&#xj)2LJ^~b=l9$lz_2Sh?YUojGP0LwE<^m>^K0i z#hw`UpDoZ~3N;4e`Had-3r!pGTV~tp8q#|ml zUEFZp=GE_~^7>u0acxnIniEoKDS*L64`2DpS46?bbo9wjeo}WO2e4to2Kw_q|8x5I zCqAxj!C0F6V;EalA-B{poAnvAbgG;_H!Gq`QUMBLO_gn4hfF4rxtAe0!H|k``~5-g z%b0lL#gdi&iJa#l(PsEwj&TQ16eY!WepRjq2J&~CLk8DeTW)6d9-_OiE2OXgeiQxO zpR~|df2V=|`2Wj~6xySVLF}@VXECtYx8&(xiOQnIXX*1LR`C={o?H@JKpMSZQ{^YY&^pTqj zsIg3Ka~{iBJ&lxRmlKe`8R6~?4Gnxhap!BUP{yYrfwbcd(@667O25nuI6nX$34$R6 z;zpPSQI|^@=jh)6_y7nC58AHx^Kdi+K&xJ-3u3 zd}q_#lLR>ShLv{Ber2?IjYD&eVzEuq(sTGsq3};A9O+Vwr2=?1=Fs_`D(ejb_?^@a zA6$#1MBteB-c%x@VSsj4$h(kE%omS(nqvMgi|*$F6ov)Rhon)`%KZxcsFeAu7U-j9 zmX{GNqgQ-5l|u#*pXq=UQUD?~5S52|gIZ`)Y%Lawii_2E=>bDRcW*BpICPkvfAJ-H z?1`u7k;k8)Up@1zD9(?lm~;@W#&f#>zm}BdUXvyr>;~40OghZ=f0u?& z|FJH0p7^1N*v0dm^)8)(<)NoW>9Oa=)lbSjVH*nbYa>S$!@f=Q>zCe`q;s8K>fn9w zKE(Y@jwLLD$v0qt$^>%3nI37s(}Pz3fxM`7z9dtobK%rfJl(NTGmhtu_UxhX2h;>e zOM~}nVmcinJ@54+{#gSOn>rz!S3NQ>|4*A9!B{^O=Rsf$~{PLUhZrWy?gCl^buoaSmO5_0`ne z+?<#8x&j4g>pSoGD1GwR|AKz!zx|RbDzYd8z(YsY-2#}EP=SO0NcNCS86sa1hDy5D zu;P$mg0m6wOw2JOoH9&U{9-hdpK?#HwphrVqg=*#*7Yp+67_=w?u_MyZL?+cTaB%B z)AH;G_t4Oc>Vz@yWT`q~U}%E#MRmkTCk#l0UFKt@+F)=YN@f;ZD-THJY)FQ~ z>7;Ld^P6)fLJ0DDp|o1kbHrdJ#}9t+1Nz+OK1XF`>5U3d#FjTXxzAooga6#;Vlp{t ze0C$fc=#52{Iy*P^vdz~Q|ItCV!zZ5ne@h&WFWK>#Z<>9q2w9J?*Pp}GQSJ)tCB)v zcq~NI(-HCBVvY!Bjm>Iig;g=MhFMU=cfpWBq>>S7H&jB3hC)|jKX|7(WX4zl98(Q< zMV2USZMD+h{_o{<{~Z+~k2l&L(M`ySd*6Gj=(j&!O`Dck$YN3>Xn0(YjOh!li-q5; znx#8dnC8%y8pVO8hmTcwbdR~Vp6_FR_Lf(4_xoe1zM#+{_wyfpu8w~5W3|-M!2O*C zGqibawT*UNQ$oM{sT#Uvvz?qaM2#AR0&t?;EskGm@Z;76qGRBU!D~7oy+x5FENFd; zg*LCS3WCE)Zf6d`WTnCa2h~>>CQwzmi$Xz*ph9Qj_gGygbI)f27+;`N!@&dRYkP-B zq){m;Hj{(f`oPf{9_Qc(EUU2WbLO0qBOA42FpnKRt{7t~($pc!50-XryPSYkmzg2n zM)7)A0Jck-AI$niAFs2s{K-<4i{(=|-{8DJIv+%@%m+l8AUY)#N#`}@XYNLHiu)D% zS80(+IAyc|KSMgQ@{;%*m<&CK4CXEv?33$8NWgK4evR~gL2lzyXA>7W7|EwN6&4YQ z{y>CGO2lp_sSl_hSu#~#lfF&_zGOKRfBC^yR8`MeMVfCE7}}LL=txZGJH5hSl?goF z5WVr{QF`sQH*{(5TOBkwf@c~gf6z@)%L#Hhj?(Y`dN2L)Z}!or-``0N`%!M&WAw52 zT@c$qr3G*ELq9<`ZfTEgTV8!s9KWjZcx>Cw4X4RyJubGRUJNkoG1B=l6P+J5(nGI$ z1?@Qzq5-ds%%v`>t+BD3sigD+@QR2}$V(Ud{K6Rn9Rkk){8Z5?#IAWoBpPPzuZj9dIB zQU`-CA?*{Q)fc0WqywViks?i-77XL|r%w*kPo5Z~A3oAc4?Y;LYqxjrUiIC=f%+BT zO9xn%=o@1_S>28rbSb*uB?BT;C2A`(>)U$3SwKZqi|dR5;>JXyVA@uXq&Q#TaACz)`(AazNQX?Am5zMC?%JllTR2M8x(7feiuqCjh9wypVX-QChZUtk zQ8?x^l1WHKHGX`0NQaB|Jroi7n*1Jw@XB=X`Mi7q>W6nYFacuq#h1SHC3VZffpa0E zMhXzg2#1suI{*~0ruxN=4q6DzCM$jBV}C)n-ui2_ef#zVLfA1BSQOBg$kicp>THyr zd)Y)ieZ}QL3H+A+Pnf1R4onFpt)|in8#!=~Q1N;|QC@1Z0-lDl_X;tEjO22C_P;6C&Sa;dv~)gR|Re zRrCo&mcb#@)9)9NhPgr;l^6*6#ERui068<+@dCm%CV!p}THQtxB5X2s`U(9BO%auq zcev~F8&-YuhQ)HopbpsDIzw7YPQ!V=!$7A_8K|(pD)=gR4~k(+K(54s2REzzBO?ke z1X%d7zQIJdZnn~$*Ej@SyULPqZ56h;aw6IQhIRn+)b^ul8OvY7x{|f&)Rg!> z9k60-zQ`3oI$pHzwWL){l)HmkJk-ewR)hJ3_A?NKAKPwK{}TNsrKP zfKXCoR4xvg(vlEuSnU(EYK4c&ODAd9ju5@~rYJSk%}`ywH!qyax zjLp)$?=#Y!?;-JBI;yRX@HuSM(&!LEro{9N3)Umbec*xXMd-k|g~qcuW}!g7beZz% zsiy}rHc%sijZRubN&`gvWkX1j2Ht@PxNHHQQmU>(MXD4iSH&zGSMvLYI-79Pps~^B zmE~4pB!Zz4-y@9(4BD7?7o1Whtq5`X$QKKREJiQWVab$DnF3KGC;$zlQ(|T6FKMXm z?#pg$zzO0kQ26u7b`Kpp?WXn)FP%K=5pzwyJ4Az?kf_0sPoUqSFQM3s=`LM{)IHu=yKo+ z=(m8?UPnfggCgWi7@vszgqRQ6eNCH_Hm`Mws86x7drT=@n~wz?fqN7Y>E!>`@;bKkT87GYTC$?53gi zFr9eKFZRK{L;e1=BOkx}p6g3RN-abXfVQnK;Oi=jk-Rp{-!LvqfG10bj20GKkWQUC zl`?C=kACzcdiddoQ_>f|_(gT^IA9R&>gp8l5gDXBBk}RFf^?oD8l)IS4Re6ewD_y^ zJ?>%V398{xCE=9e+X#yq2)O}st+sFH3ON46E9<|5z3nv6bB50!rl#g);yuVSo18xM za+nR~0*il}nwmstCmT{KtQ!GiT1wSHJqzlquY^0j>>MNcx9Isk+ia^>s=OPoycXu7X^q$W!2j zsNYn>+c2kL;X!>Z>fXr?klAxs-gs#j$YS2o(iL19Xl1{mr0gmSfvq5mG->l-da93t z0hXmeF{h0B3a3nvc`EbONLW&oLV2hgvlz&)1obWgCPE9GEUNPbuZrVE^B%9fk4e0m zgz?@z)2*H%HyBOMoEKqJ1xw z5&5b|(ixMSKU5E66Y)tlTSrWQ``D>o7U%~vQ_2>K;gO4U;LH%cetb4Y$1nPY0cEj( z{Hw`8uHk`UzaYJIQSe+NqEzol(vbtNsC&kd zi9?3F7b};F5lg~kic(8?i0-@IK_9)ffPU-#68ikTCG?S73g~0Ex#)BE7SsK^9JH>* zNF~Jsc^e+l*8n{DJSy=ZnlSE-e;5@obcK{)c}K z-SQJZJ$X*wx$(zu8g!2VedoXej6w^%Rg6&-=?w)Vv~{&Ztgh2yaLh<&yTWw7D@g88 zVk9SwwAXJbh#6B59djum&4NfraQp4I3rEbVRjb4{;Kr+6WaY7>2XDYZ2J1>elb$9z z)#2iCYo(f+8sS{YhOmGDbIU@2aS6pr(^Bj)pfi z%voiLJ_m;%sKOqm73E>tP)~I4wKiS)AkSqu--@#EyeU-BmtpXgsmhX{&0O3V&KvXCedh?AaLuo$mM2`C%W;dXYjDX&V&^1Y?_ z+_OeHb1F<8PkJ6VAJ7(H(6UCmpcTzF+PvA%d?YyMdBeH) z$AA3C!U?A=B-N)o?zltLZ%95KGDvHSLoD#fcbn%M+%znUsvi~zdmfF4sW3IsC5(ol zpi%=NBpfnPg_u=^qgl#pI#7}?E*{24`sv)6x7AOVC*a6b>gRCB&@in%d-l+#O`AmR zm}EfShSSB(GTQ#5)3j&rB<(vqt@6IP&&6O+<`yjY`isB#3wra-H^pZykb&g)fB*MW z5*(q)3tC}QdEkKu_!^Z3-;lqs*b1a4i^0Z*?;Hz=T(j`}S&(c@^;-Bdk&x{Cqm4z9WGZVm%<&pr#9Ukt2wD5SR=;0sysi2pi{3q%?_eSjV z8@vC5hI-G^`943rab&LJP;tm47TAPCMy3RV0S)ka=Ni|q-cn3gZ7QZ6+e$>b8LV=@ z;hIvh?W#>EK&BXCVerN{y4b6%;D(Zh@Ab&25j=r+nnMQ86Lb%sCrH;_ofs8!{46WF zZVy>ZNUIYePxuCk8f(;VNhoA1TafAlJVx1;kF+D1pm!!pz0-4PI?ZDE9-aN?J7zI} z@MN^o?4*x&UY)plc4*wdybsPA#i3{}xSPV}_o?41SkYuBn+Z`M%JW;QHlGiJgNhMS z>o7K&Gb@yhxqkKP#ZMoU3TR8ziD_xHizqknm};ihWe%#Xwu*6GSz)1N-1hj4@9~Q7 zJ1?5(g*{3^QY~iu4Rm(oto+dL_ei&jpNlf!?gFn<^N*IN8fz3=P7X8HTap5TPM__sN>-Czby{m+}hF1z2 zm{=hUBA{ZIQT#@8eP(lrOeZzNZH6`nNuX}bQaEH_^e!u}pu$)*0S_k4c#4fJyb988 z(0ojR?bq$3x`w%n4Hg616lKDZ$OPx09uOrtGN!b5hy^$FRX8hP1c$>SW#3H#_ImKK z5&HL^57SdGP4Z`@LE1ZgA^Olw z1!4iqd$!sHUANXk*R8S8u62H@DH-R7fJH%y9EJrzaKOUA3|R=jH8jrm6Ead0-yeYc z@GQ_yl8`i_p?R7L%e$$p@*=HW z)PlTIvSmRg(~a%Xv?;d7}eA+u^^fQ;;plA7|r^r zw)2U;?tK(g4Ti#KC>%1dN$@yj3P*AqWBHC;(}U0Jrt*qf^^-pA(Zrf8O9AK|GUG;l zg^8|PKeukgHP>7toF_YW%uOE*-U4|I(dUScD=$+bO=MI|GOTtVxk^XLWY&)iMor#t zeB&EpQCKRv|Ni^MKB=7RIRVpVGU-6{n0fZOg8y1TbZM?In)4HBI5K!F=6p#>YLtxN zt->)AWS*L?GsDi5`d=LR9}tVrq2Hl^P^&mz;DkX$jIvq;q;;4{67wkn$*}VMZ(hYpQQS{)D( zNlOXz@3v(QL4Wi=K0-hF(F64D@BRz@k3afj`osVAr{et&fA9eP`JeuOymw}W{V>YFHRTC09TwDsCA z#=a}9x?0^j7oYhO&hZgJZENq0og);s(AMj|6#Gu^9GWTgk^=@)v>75WCIV&=h4RGn zV{_7CNgO#jE53(=WGbjk9!TLdAHZ|ru)zqz?~G1__&npWR8a!>QXO#E{?OB7V&TAe zK;g$oLk8mj##uFw&+<|;HPuV5Rzh1boQ5;%yTt`~KxtVy zRa91~Tjoc6hK;`iw4ZkFx=}cKmI}qjx72q;`;X2FCkXm|GO)k_{07+qfbq#N4UI+l zGs`z}UQoZA4{$z?_$@Jl0~3zLGlN9W?Dx_Bb0IN~aJD|~N7(k#(EyF9eZG6bD7Jyl z3>spN8wq46Xlb+w1HJ^J$G|HwRuNHkvDY7yyKvbkZakyPWj3C$kj?_~0p<@Fwex8Z z)7GjP85 zA*1SxKq`j}3RYL4CPWIDjD@sz<1V^(*S&LS$4#H4oi~44-BXG3LuwyaLH?e9Iv5OA zs;O<&y*5z&x<3{Bq0gd^PEGm5b4&+qN>W5!{O}ipF?#gb3H2M)t8^!Pr%lm`ac~8T zi-Eo);`zuG+;NJCC>eg@f+ywz&G5+>+WwOae53sqIxD#_kT7>Kl{Nq)GbSg z3m3iAJLr$ea8W~|?2ei-sPXdJYp;n^WvKwR3i%L=Am@X{8la-`5h^Gdr1Iikx^3qy zefEPML7%yQmX5vl1v>ib=i`LWDt-N{AEf{DXCJ2j`&XYOi?ffc1^o$Rwl2N#BpUJH zukzsv{_Em0nhH)G`6cVL@n{%@;!!fF$*27+oilKBqc7|KyL6bJtNa&*DBN$c#8Z$- zCyYre^s=B1igi#FC7-4Ki%+Ycb3-^Vs=iwo{DB;oaxEfY@PI*Dyf4xU&paGhz(j8U z*I$1_-IgAB7MM__LqW`%ct z!-3!Hj;$Kk0wJ}CmPtjAJo1Pr)}IVGWDXrVB;G?2EGW8+JTMxxt-FDC?r5bOca$mu zCjXHn;bbAR=i*uQ(_GBwkU=qX04p&kr$WLQS6*(XY*X850V9Jp5BWl%IAoG*$XsR) znKZ)%b!3v243pWxhb*nJ94pkTDs0qHYp42}rTuO61LO$S3z=Uiz@xZnW0-Sp&6g&V zdcR3Z4h&gZBi*HpjHzi@K~)VaskXK*f$Ex;lg(AB?zMD)l07gK$e2dQ^5L;S`=@^f zFwl9-pP-J3FHofHTVyoFmFrYSzGNWnjoX`fj8LPg@=ZLR_%JdwU5>@4j@fJqn zQNM+T#>4dN%MCv98x|L2M=MvYkDVve`V@KqKY>FAJs3uO7!0)$8CvJUQUIyM>bPAT4t3E~Y#vIQ zkW@h;l~KQW*>ZaCUGJyDqJ_6jwlEte$xKSr7Z!-X>4<);2YKCoe^{`6=tj{fWNAfy zfQ$orCqkxonVbp>1AmdrNYxcQF6~iKhY8=yT2iJwOt0G79>Zh(}NPAaAS@+o(uf^f*xs16wnc_uxF z3;@2E${`bthWQyd1s~EQ=zr;ej2YhGBI(sUplm$0^sWnJw>!oCLRN?Ky{5v%&sse; z1rYUxu?aB@wF$K}<}=WNGXX(o`y+F{pAIS~FBEB=-kCsGiFKG5Wrv_Y_j(`c&~bKm zq9aDE;>N3Dp9r(8D3N?8TAB|UQ9NV7`GAPCWE5E2?I_Pct06g4R6=Wn~^diwlteu{qMbDyW%-g^gq?AJd@WtCO*-@g0>y5^cS zVxL@LwuHD1{i1$OSNFJ}1Bcq_+2`L(r03pbP)(&R;kxoI1&LDG&|zQeg1U zDB{_tZn=X0ia-JUToDOnp8h!Yo!Vq%0m?y)&!H27)rrd4#u`)*?4pA`y~h(g@% zK`O3rQ*Fxx*&GX~cd-Pp7j33Mq)bzx;UTS_x^UV+FRP>a3#9V0i!#Unu^(LQV zDC2Xu-BEh%>F~Vt^zQJYN78^_*Hl^(9VG!XO?ZuTz9&E(OkIN^VZ0vnS;?d3AV$53 zZ0fYg-+>&275;GO$lvK63QwO4-%vo*ZYwS{Qe745 zV??RrqE8sgQOrBvz(NZE>2zg^x=b+bE~IHs(Hx2z3e`Olfw>cl4-OogrJeylO|k5Q zelp7CVh$PAfrjgunF+I;nz=*97@efBdx&Pndetp)cqh8a8a~f` z%_L-A2^kRvbPWb+aC)wcpD7?$!|{26$4zIqkH#nClbM0}mm%z?>7jOYOB_MZB=w!& zD|E-cLBD8&Od?h=$6#KH8jQk$t))p;4Z3)q0gcQ==X?+6Kca3?L+PCik0)90#Pifr zdgRM^m!~~UBid>#S3Z_5!gFl$Nr2QR??>WCm)23-<2I?XDxUYo@?dey$ z=mETCiUkzmc!6*$7>@d#_^VEHP#EBZi8*6qD<*SUg`aO=g;Ru^Y;qa}26+Rw20vsxE z$iTsZ<5M|gq*De16lu=jgu$xdOffjpOFp?UMVVnQLybbul|G#nS?E!+mT>?kF- z*GgwDV{ zeT)05iO0NIvwu*Dd`XU28D@oXcr+mT2*zTeYwq)Qd&9JRYMf>d_tD6Skp%LzkC6G| zC>3m~r31%jDZ)GnMm*$eubG}A-=SXKZ#042?W26m7&+Ed(cv>53b25u_qzc29Ig$D zi>w_412BYiS)dipD!j_#x42h7_i1@f#VBJGPN{qX`~XTQbmHJ_fIe_nRg4$Ih%zyi z_Jaq>_8oVNdqY2i!j0?I1M(}&d%~(=?dod>w}EuJPEMl_h_^yv zm63i*KUT(GUyqx-tO)6$%weD%>s?|(fdDQsJm{sFDg6~t4!*4G))(;n0^^x-jP|$l z1+){CezdQfujT#kDHHuoVtf*Fp7P#ga!_gI4dT5a@RE21&^9mcn<11%!oKx2in9*= z2hIo}x$tB@fxg?r^BgH&;!f^Ahsif}D1ibq`^exw#N*0M{%~SD!uWpnqL(`R zrUi{m!|C53J?N*zW=NTJW?KYM(T~ycDNNuau2nS3}UA=Pf5(7@FO4H-w zJ@~-h!!sf^nAQLUz7Hoh=3Nll9jp$|3Wi{8JJIeD^S>x?Y>iN{JxWfCK4JV|EwvU7 zmYquM5%GOZiIJ||=%5k@&z)m_u`S3v*2mMRVh}dcj5{KtV2f2g=w>+$X-c&y;NvDk z_fXGB(;S-d7SY(mg*n$T!SWg&7PgK}glJ$m$g)^O%&X$J_=}n4B*(Ltw}!UFXD7>a+Eiwc?-0d>#S8!p!6st~J^lPKdf}zl=+vpx zbo%5;dUekpdTZ}qdhD^ssJr_JRa7AY4_PpjbK!XTyx_1L=wo?;M^Uy0$gqKRP8N!6 z++H$5YI-It(zliuv1}c&(&(gaG`e*|zV4x6%F5bsloaeW!t46*?ns*pcXQ>V4w z&O9phoT86-+eX4}DsTJ*zsv4swRz<7UUQH9@!#wXfsG!J71unnX z{{y>Rw6V=j8(N)o@PxvDAU`h!ET#$O`HDVR$TC$piD>y3<&!`0Ya!goG{r62K$b@$k(kz9q^PxTQ|<1Vxqgx8#CSlo7NQ4 z@s4;kq~clLcW9kkAvQs)I)*E&SLK!kq!SU_7t7H;2}7<(S@O8mKN*(KIT&7 z(*`qhF%Ld>!A)-;pN>&8U%!)ue1z}+@aMg;?I+u3#q*m@oa1$IIXPnvo^;a$D@ZWF zfsB4-;z40TtJOy1Y8bY3#?)3|^>ip!{2vZCFH>z&l!%v=`-#brXiqpdgs~qDq``fT zX}Z10O)JZd3ADVF$B8P7yEZ2}W44=T>7&InbB<|anq~bNKT)uuW?p9uaJf2Ua1ZZP zXH1=UmYQ5qT2^96pf%+N`pPZ~?YOI+E)0ceGM=KF>H}`7w}?Kx${AC@{Y_#a&KNi&v6>ylG|{fp{7li0(56}=O1^;K$1?&v;}^&lIZGo0 zCuw~6Bsq*76mYjwU(X5ZyLe9Y4@4qpoiT`tK#dM91wtMg7&<{kt_HsDLcXtf-^c`7 zXH39-fi}0WaNA&}W!0uRRBDgX$Ta3b)kvMAVMNavW8voce9@oLj@}(<>2BZMwAQwk z_P_aap)6`)4H@Y3#s7zP^ynWe=??cDw86fC_V4}09A^yj^51!ziP}~$?^0>SG9%Sg zN2#&FNSoHhw=X5&oG2~=zc#UA%Dj!A0~|Eyvse|5$QBrjQ!GT!7&tEszxW+tMCAEU z{tjv~R99GqK`r0o1O`1&DWAKI`=J(>qca9TyMX71qTEgtq1o9GwYI1R9>XMgqN^!P zi(hnE4~R&BoZu=fq6(HPE32wS1Wa{JEmhUjP%+D#kV`Km%8W0P&7edEJn_PWsJ}BE zia&eI>EPAE0L}l=Lq$#_o$U#dhh-Ry352OBQn9bWhKpQq}pyuZ01X{jg9UVCIWP&qhWGpE7Amjn0enNz=a8k3(gLxiKKCBAQ zXS6Gfn&|TYbjOn?PE%!hO;!#W7`c#A3k%6$q>_3LbQ=Kgu?^p&U^F6OvRP~bTGuYq8222icu)RNy|$w4!-wQ?dfmA>-la519}^eLFZc(m7->x7(ccbl|{wI(6y{ zZQZh&UfBISO-)YF`EzH*HZQkdahaWuQ*<8y=f#+SO<-Ahl-kdsjng}0(EiEa7ZmZ> zD>KpR)&gp2w2RcTNM8)+95QZ1EyXl5X`+|*yg@zP7swp$=(SWDaMX#WC+T zzn|!W`&MDajp~Q&@yJhp zhbAZb1)mfPq9xB1#8<-G#CA#84%@tVWqqMvQUTuK_T*cC+Woguk+DabW#mGQ?IM<7LMWZID@s>(kr-^0%EmA zfnwZ64&ur>r#hg}-WXL7u)XxqL%&py$PQrmSPfQJS0~bJtXj27ICh|@;XSr5L^19g z>ZH-}5$+etzhzDHPZCfTq;Lq-RoiLC8=+_RPSWv?+|to$fwoIV??`~2**7JqZ#qgt z9)+aAeLi6F##zUFbLqet550C|mfkovJLkJ`rgs8Do)cs@4v5uM9Tzc}Pb?G<$D&l+r)MLgI4l6=NjNE3Nq}QU53H97<3=)Jd`LX@?6Bxd5)hj7j?wB- zPro=SoGO_B3f^U3Lnaf<9R`;K-@MsGKfK2}hu~C6rR)CTcBAewe|xJ%^pSTepzQSx zC@DI+d;Q}5*hEmI?O5!3GVYL(o_otfPrg1&FCFs6a-~1F&n>orJiLzt3=vovn@kG< zA~I89{c0!e*jh+ySC!I=W#xj_tu7PWYSl=h`7ksRrQW{zX_k3@GO$uIRZ1HP81$r} za4axafrirx3RXH`E=Iir%uf?)x~=&DK86}0_Tc~x@C#Y@1hp4*lTKef@-SpPJ zK05eTBE7!1pT7P5^VC05O)YJ=Q|rc$QBBJo>REC?G|ar(G>7zf6c!p`9B*FdqLs@X zv}%Qewrz0n{stk}08=yhTUY|XxukVCI*U#8%U}LdEIi8=;N9S@r~w0q)0#DFX#M*2 zw0ZMp+O%ntNDWw1Q?nq$CyZhH_aESQLK_pW#pO29H{kGStby(${GndRXwL zSAz*iZZ=T4Q(5e$%{-zdJzz1yr3My`hP~%$y6Z2f_sDP0p$Go{nbuEr1nCqL@FVW+6E%O2FXY zkWf}G7wkXsig3b6v^32h_74F-3kXB`23E!CIb+N@PV9)9!S(uBCQPQmv5;`~^p6JT zeCN-v4!dXw&F-fMAH7HqJ~lYVLA80u-GYqPVk#)9kA1%C`uphGTRuT{N1?iB9B3~% z-q1tjM4^noM2B3q_?IIQIx`d@4^{-L<5@@NOTc#ygy_U@l-!ZTm2l~hABPMJ`#Oam zv&BMM3y}u_H7e{<0EW}HWlll!tu8cbl*UY9a#`rs>q|w!ZcvF@N8wT-9QKmW?-!&X z{Zm6O_lk0hNY^($5n@G=dB{NAn7SB1{&SfEU_z5CeZoz#?TCDlKvDGNO?E-j5ChUH zW;!2IIXlA9B6{rQ<@DWOtfpu7T|@iN-Yn=sf98diffx2f=#@9M6xJm-QlBR=3_K|q z?ryv7wv@DN*)o2{shK&>fyE7a$4Y{cFx5Gbf(*2j*n2>~jdt$|)0_O=QUXqxSKi>? zPoR)WxF+O4R(H-by88okq1#VypLElybMr3>f%64Lde?8cf%ZKA3uC20Iuuu^QZBs}Ru~SjoS(4e3RSskpR(n(A$0{y}sYc%wv7aWOS7Yo*GXdY<13 zsc&E?Eg>aLX+?uLrl>geYT0DKS(^+$%Ub>2r)Xw+OqaAX6J!?jp@upKA=MVrlZ{R) z_19V&Y+^+y24{0)?u)tq{Rnht6H9?Gjhlj&aEK>2TXl^J#}<+s9O;EY@`B*f$Y}Q_fY1T zUj|5Jj0Vu}CMW$OG8l^?5cNo!F$hdgPm7h{xVBTLQrBv`0)1%v#E525>KtghtRx-e zVnEcx_rLQAo=5vAq%k1INH}2>M+{zzT`4Xq3wSjVgi_YR_z`_igLDp=WK_A{pqA2K zQP_Kg0<(t_sIT_`jf|d6*QA#O(8_=G$RPdT;gOW2O&OgJSdCFy*5IUVYh4);95Jyh zJc|bTWG<(ta|KHS?Xyp&xzO5;d;uk^g%)~eNhU2&gKK*D1@%+rIC}7L+WX2+m`6${ zOjOv`Von+1fKe&tkO3)O8=HdHqRTd`c3PM356qMb$ZEY z^HFa<(L_AzGXc1^WCp7R6xQl0JGC@AsJ_OYKr+WXR)T4_Bl72+g5wu_G~^~4^&%CK zx{={@6jR%}ow`&}y-e(rtaPCtBSn=-EFK6mKZtM}DLJk^tb`#NEEQfFG|=aN6_`W6 z^;CfF|7C#o4H>AV!68UGLe9*Zb&vT1A9Eic^Tt5@7;VA-`H;T|naqDPUznWeWTj$O z{d8%;vWqSSxq}qn(MraGx$WadeF~jp;M^>F&vM;kbP;C-IV0_<_{;I}2|?+Av2pWt zC1U0AW>z{@t#At7i4$_B}iEs`WK*QEPC8A#Q(5QmHw;L&~`^JWWDUzCdw zeDH3hok6XMY;osp#w0SOqQnMNQLX`ww1^T&H` zGBI5m`6Ri08tV-ro!e46WU4C-bl2^s7@;tFX$iKO1%2c`^b2+8OAJK6IGHBK2C1Q` zjl7;&8XFxDuMTISaMr*HgQyrdXch~Q&EW(9Q11lk4`1IuEk2_r%9ZGtxe&EtjLHh{ zm)@8ZP8YPD7E*o$uQpkV$!IPRuh@z@8U}-zTxHjivuHh;tyRKljn)0@R?c0J(;IG{`bFMtn^1D0$u_6xuB$m%Bma1wro(wybI~7w7~tGIQ$|#`^#?%>Nx%) zz4Fup>gT_klZzj>YcVTP;*eo|KGxwPibH0;g%r7GAQ=rxK7P~y6wov&bPHs0kmDr*i`O;Z z70^a}Ow5Kwy{U|$?Y1hxfH*Pm7=OqOQxpC4op0PjgZ=G$|b6wvm~nbFcC)svA=O^+5An2WV^1xpY4qzydBN`4w*J~BF?ERxTq zCrpp*=D(RA{oE7ZpvQmlXM9AIB4UwDMB|iE-pkLiC>c0pVosS5^S!7@^_&l&gh{@U zT4J~YfzlF-aH`1kV}iu{xbr1}#J(UHVwFPi6C>^P`qN*gi|6Jq2!^N_-^^k4)53AF z$4fyqozY?{6}bX@7OOL)q1aJiriNw3JWl5h^<&45(b1zv)lW;0lkG>SZ?G#S2t%N5 z5TW|H!BOBRgOwF9OM0rV8>EKjp%~RQ4$ax8dw7`IyN2jO-#A?yo~6?rL3(X333~BW zL~5u%ssU1z3=H|GpD7*SR6tHSR6qmApmXrpmqH`*9Qfuu& z^^*b^Igy7K?NL~0q0&;NUk{J^x$R+O!-`Y=`#m~tq~|Y0=Fm%BsTGL}v--#EX37=s zRELav`UH)QWL_M7F@WO7pjVq)sQae1GSOC1#>f!|GTpKGs%lgf}XUD;v)T|j#cfQyH@ z{Cv4MVt}_^e_BMp^mU)3UM9RB9~}_eL3n@c@N2yNu!xRXOkl2sffY{*M)>Z2zev3W z*bQB=bX-@UpxX3v@w)%WtVr!Psgo`ch7Z`0kqR{&oFSiQgl49CgvcxF#QD6#G(9yW zUNZq|^PN9`UKo{;Cw|9{9rW4HepWbQvV}ho6*V>h$c=EwB|Bu20jHrJWGW-1+=77; zJh6bMWJHn=^KU@z0e^xqBHzGou3H(8oW-Jmss@*6t4r;W`QG=w7fYFju?3!A+gvE* zJ+wznCF^Th7etQ=+3{kJPqgjm1oyw`phy#k`b0=wx==X=ZJ4P;MyqQyHa60pJ$q=F zbtdWXfD9rXMS_^8XleIrlhiqe5YxGs&v1CY%S&$@m=gD0S!NcgE=R|MB2{a$0|?^; z&*1p+NYJ;@0UZLA}nCYYMbI=EF zwF@dM4bsrqWWq5e4i9Zz>7|AmKQ+|_Y0Wae#!c23t!hPjEA>ZpfTHW&z1}$rOs-)4 zEhVj57GGhf*fYc2ApK;r>X0Q)QQk*VRqZI1R*X2h(1tD3)VfMhtdRe@ zxxtY@(P)7F^Ot{3PdxTlG~NGQvUtB2qt?owQ)}HxajX_l_VkM6V>MxUnN=8wp?D`l zOeh(&yE5S<(tJqXKhydEz``9e@w8J*>5xJDyBrf#UUcbFJD?vA4EY7Ub$BY4J|`7m zAAkW&QYPu$kDZ?7^9KZB++Io`x}mD*EvhMkaFzOAVeI0ml6OHtz>w%Wh!o2ub>CtD zhMZ*5jv0K`0;^y_aJp!nGJZ8}+hP|geR_A89(y{J5h3kWE`XB07(lS8avuswX9!Y< z$!kYVmwZC+Y;e#dJBJ?S-|p$3yZ6LoRD6fmr2QBn==KQbdC?SN9_D_7E$sX%%%IH(3k0wNvVbkHPHyd?twGeOM0 z4hqz~^ZMZA50fD}O;&S2tlq!a>!XP&A9<&bP}qBv%qF6vr`&Y#*evbYt3)N~K^E%8 zE20pPg6a9^pBLM7SN$g=X?Q7y!pt2qNUNs@$Tr(I7si~)NKfS|Fj9MmmnNn|A`%Ed z-Kxa^jG$}VoG}Bw&0(h6mZF$LX8->EV*647zx&N^ep7YCaHFg3-n6n*yvp=s+LUye z0x}AmFz9~+!+!p)uyF1{M(St6{0iqsCi1KvGI7YX)thNub9^rD>FE)*M3F*M){KE@ zj%$g{{r*Hc(ZjNUv<7J~-+~MPvK=xI?0v0&TTKy4p@Qj~cIpR%8Q+%v;f4P14UO1wb28enC zlA|FP8^M5y279eE)MpcP;i7|{*d3((XExH1=k9r_Va5AtXt*SHJZN$(e=C*@hK2Fi zEBLPqDGLD?nI}X@pO0jN;fw!DLBGCiHZ?Iozk28^%s20%p@DNkMuM0mUd2BK{)jh< zO$%9QMCvk?hvL2DsaQZ#R+9S|LMq$7(flqNm556&SCA4emyHSv%<;&VnDYhim16#J zVxcTX2!GcSF_S(-FFy7~`sMd-rGu~i0}b{arrGHM@jK(a-xiTExx(v19glb_t;^jR z0~ER}B0@&4R;y_$q_QggkWHj4)2`lHOyD_pbe^SsM_wWk_A2JFC~aC-C?Y@>3uuN9 z-BnHZzPE)|uDqTGr|zJ~pKqmq{O$~W{hR&t)=M)q+Z!P-cO6L%+jeSPb|2kx?K zdw!F?_InNVr(Y_J(XMNZ!f=6*FTw};5Y`;c*x9L{Mf zDxM{qeVPgjXUSrl5T7$4n=P(9A(AJV`~j@u>!gYCPBKw1IV}Bgvg)t2LKnfxw`AZR z-5%twoU5?;Sjp?^@zU7j+~c&sGr@jZns46ON0yi*)9aOyf77SW%< zqc0Z>4*RLQ7e(vi4)Q5(Ke-L7LnYw28A3s7^}AHZcy$WCUJ9U3SjVz6!BzI_X>hmom6#%3=d_pH97sG1dYt)u0@ z(OHq|4l-2*%Q7(LLixucg2h5zHKG%d{!JOTNChSxGH53_W$=En0iEif{^_5Rek)2X zD@(}CauuRuu%Ku~i<9S&?0F1~7>Iy@fdmF&EPiTjafsshF!rLKK~|m0Av$(GhfImf zNJdk9PDW&w*XyP3?(WQ-f(*T$04I!GkdY2ZPX=+}|)`(~-T^Dw>e^xxCp zf9+;^=)vEo=}A`5lYU<7kO9Mur7dF}alnjEuIPe%dGOy(xQ zBTbW2!ynTk&2W+P)fN2LfObxuVV*EHk^88Eb9?CgKd7IGMuyJQp|^fXKmFlv)4%+~ z{dD}u(>zxq`wrwVCh-cV4EH_tRdvfKeU%B0ZIQ-Ib;4lYN4>+%8;X_vas+gw{?Wy; zy_o*s5B}gQ>ic&EzUTZNO`BNw#_ZF>0@uY7YAerOm~px6!r0{XU=>eTFnmEgi9(1} z2opi_Ya+pzfmalm9v(PJXHPy&Cl3FDLhfIY(>AXDT5dRgYKl&D#*M{Qm6;obE)_7o z;M{=21GP1{`N&mdV*!N)0{2{H-R*V@MGgiqtR7kn%+Aiz6DxVXgve0@XD% z(uY3zN3^1CjS$==!>TPiPi9m6yytuUWVM;7xX2PC6lz7md9*v60sst>F!nl~W)T^- z5TK7sr-aKwbn^|()IW14d3>!jIa^Od<5ko>SWjmxNMe>p{M+o_`I{j|LLJXKdH&*0d32wO&KR12Y^{{;LYR=zDFl|nu+!OsMb+`%&a z=!l&nGbQ#ld)s_CT5qI3~0XQW!bl+?e6-hx$_s zt8g~7tVk?y>*MFtdolGYWGK+fS0+wGP=?WV*#P&1`c58CC}xm_q6>u*+tL1ZRyOe} z)0v>pV>O{%jRnOMQ4|Y_XHWLM@%JFht=Q129P0Re=TPpO{kmJ`}+7 zJ$^dP%1PHifXsZIgX1AOeA-Lhg10QiCG#Ohl7Uig`W$aDST*)Y5bZG%Cnnm z5W+K;ZH!bVrNyn>7YYU6Oh!7ROhB!~j`}c&oC$|~G(GYnHB?-r9UDfduDpl7|KJ5` z@9>DWnGP65A3_`HEvkT#tfkRN%Uers|+FUy!ysNqEFyBE!}$ar_&mZrlzKZp%3TS^V%X5%`e zxK21ere}z*z1m3Ix0$H9$wSFLc6*)T~F zvXeiWnX&cVh$_>=WHF4=Lr;&1bTwmv^xi{^N$_SoaWGbm_L*6Zbp^>jI;l5!dz>=y5F?K5FT zzJepBupmCZF0yQl2?&ufB`g=C9|BGFw!F!cdcbufRVHK!$cDH^$mocYnVt00*w~nG zU_r+zDalVHz7~^{lVV{Tegl!65}1oyR+W;KWe@N`v;k@Z)z_r&J9@x8gPMuM{7fNt zZCvZ(e#0^V-)D8DMJz^{;eGHO`Wxz)DagLv(Vmb~pvyou1u$RvxL>w5TBxviD;;>d zpT@^0#bSw(kr7(Ie!XxE0yQ+9oV4OGeeAAl^dnEmqI0JM*k zF`?*(i<=T3+;d7$8`M2Q`Fae zg8QIf>BZbf z#T<(HM+>l)tJk~8%KSX zc+2m_Ke1UMbXz9Kj`b~ad7#JAHKgYd<*j~P! zdMrIGf$@hoi0=4V6aD2!)8r9sqAcazanKto-}=o^3c9ooC^koZmyxR!^1_5jr^+rr0K>Ewyy z!iZU8et?AprKsrRuTPR&HTo|WI=Vb5`&=quHEC;$Qz(>E(-C1bbl45T@ObL%tWXM3 zXJ|!>Bi3$E9DDkGEZ}?S=)ny-JJ0cX#^2v#N<2z9*tKAtSSK`M0FsC9YVI1C5JKRh_hO0>dLlogb7 z+W_ZT)~Kvr1bUedA!UmMLS1D95TcFH&wLc zG5(N8TmsjzqFMht2`E_dw_}Juo&^DIz5nR6=(mGi)AVnD-6{-N61{_AZb!6vi2HPa z`5W@T8|kL&;sQ3>=1>2jk0!iCPHt;B;v}TAs=%oj6%a9op{CRlv53OZmjX~gFLWz> z+F^>2#i%sosufOFl9lK13iHwO%J))HaUDPFL>?4U4O*#Elfl6c;|d(z7rI}giRlsH z^jg2Vfa=vTviIP$a5Cb#qHh3LnN(jJA48b}(IhBH4+jSd_( zdp&e?bcn?dxVNu;{nym3iTLifUZL9BTJ_UhVD&MStK@Uk*I4Pfmk|A;6w{ZG*ZqkP z$J-H6F-Tj6{bX&Gg#zb6B+0hTaf2*y=3G>DY`{<${|!XQJheL{B8+6T3>-1JUWXoj z@n}#uRc_p=--qDO+j{`D4U~4n^(@2@19bH&d^HzTRVc=5IOj*l_2mmZXYJ}biR9lG z{hasB7U1av+^4~>%!Vjc*n-qlXQNwo77J(0Q23+di?*nH|JMQP<{&!giQVI3&KdGq zbDbJ=;WUL~ys~x8F1l*RedK1|cH+qE^yrhXi|wg!%Z*!U&3zEKcD03`eI60uN*~&|^#+kL54DXT%Z)`wsiZW~5rbMF zaD-?9`3NcSB>!D(;J&ap0S+grM|#~s8t$28o}=*T>gsCRv}u#jb#jG_yg?n#WLRt_ zYHlkP>2$S@7#N8c0z~>kZs{KiPz#@W;g*hH`Fr1yO4QBeykKRm<;yZaRuB6h2_3BXy0`4(7 zd*Wr*?Y}8LLx-^ExFF%b0%V#kwA8vrBi(aL_PTp2439@>WE>7*Mb?!y3Q+Gwc~uDM z>M@`(uEoG+@TUYBU3qJu&FfsWaycu^3wpG34|?cVBXn+5*^b4Rs8y5+Fn%y!U_K2% z;mk82FF=<{UU(&+S2pNmIWeq?9m#3fYO0x^v}AVAx!?mg#M7+@ja%sLb8G04M;;NM z^>l$Re({TR-F4TgpXLI3!UGRHpv#|c-!)Bx(^=L);(jM}S}pLLJ9%DBwsT-E|MEv` zsK6H2eYJ2j{+s$PGl;&g0i0!GF?*8!B!TP#u=&8Y2h`Nmq}5TbAT>HWJ4K|J#G8A6 zOy|x&tA5HHuwg>R21*XmwctMZXe{#-_Y*9Lj|yIj z_bNXHC&jDyul6zV!uoRs%l|i2icR^zqtA@e@T`f-Dy?+S^_8^ohKJN|@`HDEWQ_5m zfy|HEXzQ{PvHCw(fSHw)y2#8meLcQdzRoo$$N}!x0=Z**ImOn4COyigxebO~3lpujuUAb5vAmW`P|eTy03kLLD){LLy_< zt=mXOi=r@eoPLW6T#9iy1d9-(tU@tifOaLRp!(wuF84r@t zprk@-@6K;3H9g44m~7Bk?+~?Na2N!fU?3<~0K!HKhXS@iDAwk$l#ww}Pmlr=UUIRL zl}w-5V4^Q?HPN*nULjJu@K6vyWK3|>t$WOUt4#EVJNTIUTIl>mAISi-g+#_kfCtVW zA%oQnxkt!oo8HSx0e;Ut6`&8_9gmE`^`O7{S)uoO_#WLsn(>&ZzRr~pl8*?cqa6X! zr_smp43bwC;#^us44g2@<1*9881#Kyqn5C`SEf!t+u*vBw?l5nsxQ47(I7KXHB1Azf&R(8up7 zqwBV~sI}2Xgl1WhKTW;N z6VNWJTMJ_IG*U~zVTrboPE#m)*`^zvbw_F60i}c9cUR)E+K8|B-}ReWMaJmiuJ`>$ z#*s1Fb07+$qcbYTK--FVJN5R%DMBJrMgoyChzP-caB$}WoCoK}?`R2AXR;#(fB~(n z#6agRC~bDtW)t)J#p$2vB4Yqt3nFCBb-+-9IfrG1HHk)zOo2WI9)rG@iogyfpVI?Y zy(4lFhMQEtbJknbksR%SD2Mq9vg-kS5Rnl+f0P0|e6bQZzZ_ zw|*_ccOy_E22nB65i{zyFyC36J{x4c26cNt14BJ@=+JIDcH&JM9POpja${PWoEc&s za7rB0(Rng<9(k>)B4Z@95i%?4%+ztQoQ$LhJJq!3M+;)1)SkH7ET!G zI(liIi%M+N*jgeSF{lY795D@cYUVasD8L`UXE5hr@deTf`uXuden5MhOi`AN144ep zbB4T=Cb(2Z`e%do!!v};BprCsV3;`_qh@l zjfur${2pUJ88Uqz&{}DvmMSCFmMBzFXrpRA9%N(wKJ8cT1q))z$`tzOdz|#4_ZHK8 zu5;0?*A~$An=Q1aIZhV_SkLCuE6*r@w7SU>vys@G%W1`$`{<^dZW8<%whOsHR^s5n zgY@X5kEW!jo_b1`KV!l1@+L10PfY1vM{43fNq{W^3mlRiF#uQ#B4aFRB4e_F91oJ9 z2Vf3Ey9^8r2tt&iq|wn)5j6{Y7UntF^R7h3EDXpX1i3-Bt=(2j)m2yX9Bbyji8^gc z-Q@Xz`9|u-ets$A$5B<0olcqx4i+yeN}?2sm|5<_A{Z0T&rGcB7>pqFU-X^KqGi^v zDWYq(mEqKR!$1GOJ}Rm#;JMedD3LMmYG;h8(@1r%6;a1&58ZNoxw=R0a5$_~Ra3$p zIYLuYUg7wVju(*f-k>;PSg8mLGVy-g`N_)Upv@c0Y3s%k9vJx%3?!a^Wt0Y4@dBXy zR_KH!UhWVM85Y`M$nvldkI4d|`$eU8R!~gjomGrn$pCYQ(FabMS6_WqC>~%!nAE`3 z@f||Hu?;zrPo6wU&$CkU^2;yNxpU`P5O7mrX#p!EMf^J$(s5K**=YOLg-6}w>WuNZ z$ElkY)#}=2TC@HdYG__bV%w!6 z`OPh6DraQ@DA`g=hnWZF!x;m>a4^3^Cci1m@T_ru82(o+vr`R^M*zQpj3kqjUJ-3E z?X}Xn)x}g(k;qqn`s4_WyOp&QU>%i7d=dAQ?1({BOfqnsRDx4EV{lDywj~py6eZxC zh;L^B1Q%v%;4#L0&J~J%Cmk_>_82YY+Ytlc9^f?bc(4kEXt3WyH(wWbM5Bg>&mRWDtJ&%}F}l%^j6bhN93gv|vs`U)Z#^K(r+cX(p3VgwW6OZy`+^_C^1Y zPOqf|?o|q$4pWpiuW^d&d2ZiI>gX+}bKRwMw#!QXa3%L&hv1cPuISZ=fglM-4CW>2 zkbyG>jt!GJMEye-grNX!0pkj9W<-U;iUD%ZB)G zN+4S1*_RYvg&I8rgHe8F27WfVU56g#bH)JAz8E5;c7xNXpRYxxEXx*!1>C=Q?4={{ zL>N?aK_<=^q%KU(S)UCczrXfuQ)~K<1V@ZaYxz!t zo-+nUeQo_c>5y5s%u4pM`>1X0Rn)kA6ImT4R8UkU-Zw1UNRv|sMc)AQ95Ib`mrh^8 zIDvMC&0C+Z-YcQW-kpb$&fUnqC zrggH6dhUW($ca+cQEKRjw;4izXYd200F(9J>^z_E*jh$~)wjhKwrPP>isNIQbo}H# zA#3VUeW`(7e#1wz{CtEFC<|=e;-s}KPoO^|ZB{tS?cg%d@)if}y1I~BYAs|dy_TwK zm#as_0mo4&6rh*){9Js#;*7}*Xrn29{*dc}u)}x*)Vj=}ew#ZW2bUIN0S@cvtY4u| zfH0QDEAJz>;Tj-u;h*|n{8_uQfOcNZe9D=FysOg{UV3AahGvyCx6sFsW^y6GwS)iW zg;f126|~NnYd03s&Z}IawiIaA_z9LhTghNu!+K{O%?{6ycfwC$);}bjZV%I2heOme zx{5~K+i1#NP9=piehuJog)U|N0nD+j2@s9LGLIoE*3VR6)RRyQ&Urnunp1n z_#P?E5>n4yLB@bH3u#WZZQI%SU!0yIgU`WPpUom@WfV?JFerXhckQ`84i;k(8FXsIH-m91a^R24V8B z;)fi^+9;T?8U+(38t8;q@=#qJI5`$V;}fdqB16Ctle}^r zeHaSpTL&k_^Tk-KVr3ho9hVT~VW{8e2vB82d3IXx?b5JY>F2J^wPIC*FKiHwk5)&B zT8(p$!QMl&$}t5SYFMGSk~f4^hxswyL)l2}kWm~l`EJ89K2WOZEE8B5>+J29F$;1(ZRcmrJ7w%OW?Exq{FkUPa z{-A}-R#w7|MP!J~T@jTPQnSRYfYm6--4A81uh&bvt|=C6C%)sR!gH*vafq}cb(M4P z{qfxsG!tY&iq8W_5}XV;C!Y7JRwwrrI3kty#@vkOi*zPrczlZspF(P#c-(M;R7MwAdCK2I+b0O-* z&aWMvNRyiAxRS;C0XT2gt>SC$ir0`SbQ#DOK*XKG^XG%o=Mj;j^tWW_Ib*Xjy*uM%s>Xn|{j!5I$!Oq_Y*ceoE4xx2}0!|~D?<1&Y-z!D_~E9uE( zGcx~Y`B!oA#erkCth7;UgN5qKO$jtH>L<5fiB^E&tT<^7%@&v+^c*tX{eEhwF;cO$ zo4nNeu6D@45mO%dAwBxsxG+S%lN~XDo-+n~14er|?>J9f&ed7u$DydAM z!r}^g`^c|o+KqzoLBSs+F0~^@0%Hy-*C0#a-f+L@({Pp)me@p=07S{aDFZ;qfpZ0p z80a<7aiHr+JqHWXK-fapc;a*KvNUznMKOIArc64l-0^|BVSi#G4sPR4_P9o$UCu@ zJbXRL^w2}Uq+!*dd&L=(8Ssqom}Jx@#{9B+3(xualPz(6=o}TLMk?f2q@WM7uBDBX z!5_tBr~uI+Yv6>rszm66`3BN5BPzzLM#Vrs)msd4xxvr#Hu^Pc*KBHYFz=7^g4xgx zaut>c!}6-t>uCMvYiRJ|K^_bC1S%}BP&6=3m6eq|7u-e>%MP*_E|Q6+med&opk_>Y zdAW#$=}D6fBoo|q*ImM1a=!hEoSZT9Ibr~?mc@3)NI*ZrGsW|Q(c2Ylv-bCnstIwmbLR09V3C%%N20S6tI*I)@VRv zOsZ%Z)c7;evL**zcU3X#Ob)?2@{RBOdmkAbc5W|aA;}eIOa@4H##HYuBoj|ag)DTo zY3g+33t%KJo&aj=N~o#1jB09%nTn{gs*q}Hi&y|Fq4jG^#cJ*5223uCXJC3__b?5s z0|gWBJE3rYIzW&rVC4hKn9&d=FHh8%NKGu%!zoi*6|ezQo(>A0cT8k#VS@Jmx<5q$6lk! z@j>B)0q_dP%*@m{Uwi2sXG~dPKb5;W>8004S%L7-iS`-l84hwAMuZ_51ZM_brEy#W z?VidZgYV?=G18n<5}Xk7*kotS{(XC?tgKYr^Z2+TG+|;u2<7KK_c`jgaDi@n@B75Q zK(aGtV8~B<4o(Y016I>Rc$2@2?_k7~j+)FVasOY;bcc@%=yyLJ@#~%j-QOs zsWbY7C=QHII3G|1A4UD8GX~v06K4$O6gX5)9DQPrGX{!VCe9cb4e@&P?I-3qV{mQl zXCu^pE-J2hbX)9;;WA0p|r4h|2>0IL7Y4YVZhu zhdKvQQMeyzz|g*ctPz71T-u`kW##DC5ppvdPId(A!NcqYdMBYvxB+r*oEAKkqsHeW;cuI73e?EVZxAUARuM|i`7KM zWp=7-DWQr!}P}iiF&>_pJ^(b*hWbcO+h4Z{IMvL(1`2oH3aL^FQP)=&-&Z_eExm zZF!82kwCXabZ2?7f#(?`Rh9EItwaq(6Vq ze9SB0lqoETQdKGI$mL;vCFWyBkqW)3)GKH4D5ejI`mKwPa>xaC2)R-FZu;aEK%z17k||4K&XY3u^Jy2jQE2hbC$F z{)t#rOl`GY7(|x@;wKk$QyBwwc}B*4Vnq>FD9IF6FzDkELMaIZ!W8g@$TJ%htH&_m zNMjisI8Z`BHda3D1#>;^awua^uUqA!`r7;{>zD{TyW>T)v<3Wu2w&$IGd8Rs16a?Z zb*p#Ls+cuuhljgqaQHty;S`ej_ZBc(s6A9q_ zBclN^)`xm#=+hspq7U3zrGBeIbI?U@|5x@+QtvcYtAST222E+?&zB>nw%R5lIp#<5 z9W4^__%nEBs8NKJFcYIbT2*hNKm2l&&iy9-=$<1!8ktn0?~o1#Mq?@eqm~TXbMv}5 z4}^kn?DVWK*3@x()>d0HY}5Q>Rv7V#HZ3#Ly5%!XI3?gXmbr{E|6~Ik z2d9L^=A(}8J)%Ejte}9u#ECO*QOFdAX{;D-=02KgRU@1QhmOFpqHdT6NNcsa)kuRQ zN&$aF#(e9WFURIdJ&5bIScK#Jxko=u?MWh|*%+m-ef5R3=Rmtb3BWnN`|Xd?WKiLm zDAqnOh?GHa(xM=}f%(4pDgmg;hurK%E(2YAb^3mR%RqY5Sx=OOchnwIzt8~1?-5-h zBX5*rqQbB{Gi?&G!|FE08FP@^cMZQ!F4oUe674+@rmMFaMW1o9T;WRX(~1GV1H-Z~ zLR#jw8Gf&^j+G9LQ^m{2Oz<(iy#|(H6Tbs+EyqsHJq~j|qO2@Dhm;iR_aQCdco}CI z1coByaR$&PSiKH36o%;&_r{|VPmO#@7$qmi`f1;uU#eT@V#m$DMkQs{V&CSXpOM2d zCbl0ti^v};+HHIS^S`w3>C?W=5b%eAQ&;=PjrnfRe!jR?Mhg&lRZc514#&^AhJV$0@MQ{4B!w@5WhhfjNuT-6pQJQfivb0zVaN|?S(Yd zb&S68ci*AC`wpq!&INw+;h#M~HOsb;(PS0QnB)6@Akqr}NPl)_Ae`12gE6oewKTLq zREVC#6H0S;Ut+Y1);S@dxppXDJ^jk$R^yD&=Re*c-X|h{z^jL6=xkry`g-kZJFRO= zKi>cCXM;2}qntxH5Ay7&T?~herio&JvO39q5eo76u!mZz&2;Tm#k6yKi6}5XI~x|f z;o)Bm(<=w3sda6sZW@4mIbu-%C*irKh29-40`mAXcy66NUcPTXAyQ*{!cYE5FWvXP z3K15(qD5KU(9z|gHx5kEW6zD#=Rem%v%a|(0i)i~Xn-QjmXNj&!cA3$MXXwcF&q3F zH6!p$Ry5D$MN0vsbLvzD%~ETae*OLBWU{yx#Tj#T#RX{vwN-=~L=;)V7P9Yq<~_gXoRgePW|Eo7nI)6o zSB^Pnl9@T@%$c)1zwxLUm+QBsW>GaX&=;>x~9eFw_U9F;vUJ*pn}WYyYl zOM1o#buk!I^Yf5|F@Svvnxw)$26LSe-=PZQ#%S-e?BaYW@4Qx;T+{SF9>P*O-;n+L zo>R+;JNwP=m#$0WJs|Eb{Rqth;F?b5e3_x@eR6eM=ncthBB z`ka2=fG}p`8qc*i-~FJWJB-0GCJ%Qr2Pt^48;%KO746#jQM)Qw#?4#ip$DIfFK~?m zxG@&vSO+*yM$MzbQ3)Yg7x=7j-G-lLc#q&W!x^WJb#}9cG5#8_T?@we5a9HoEmxWL zJ=AMv_Q1aAymqWdliOI=Xif#^y!eS@y+2eKV{>p7&9LsVkHGc-qtd$M#;bGHF(;bf zoNnv$ zs)}>6Y}GB2H+rgiZm`1`tM-;uX>Q1tNs}hY4L97N`Y%R*U4w<%KpQq}kQZM5wYHv4 z8IJ}IWdOKlHsL$MFebX$5yk+{7jYf}3EH-D!^$k}93lwSW5R6v%N26;yi3kj>feKr z`AORTR1agOFZ{pSb$q^h+zwG6#>~IJK)PyURDl_qDw{hcT~;jBFB%jd&Sd>xK?6L) z?-%U<2~R(FPCh!-Q|kgjjJG>!gTmLV0UP1KfdbTuD!t8NTqL5YDeDCa4%Yq68ZJl@ z6XGN%J6nzxX_f^%Xn%{F_U=3vKS%dnkxCb$~z((PoRhxEFiqJq?jok(cWXzqf zzi{zBdh}#9e&)<4(rEN$;tfKyw6xe>&#|r`j9Ta0ogPs6T0m|upMn^$%)fgWbK|x8 zojriS2UM*uBj|Yi&*!De@)jeKyJY=!*5~M-H9lkY9PQr|&z+YFV;2#OFb3=nWO`nu zH#3mI>tQ=@sBTrY;kt~fUr8wrNzX|ZhtYN@E_|&W_J=2k0dGrWGn?NApX+gL+0UM9 zRsCI{f3%jS4r!@xQ~O+3r%O92iIb%C1aGxW4Ye=^aGXGGY7~S5`nJhRKp|+1EWbEI(sD0Uq0CSeD=pGq_8a-@-jCIE zRhvWFj3xkmg@XQa?cy5yUu)AjI4{9D->hk=sul|N->79(as+qs$EsR;CTkcIpZ_fx zHEy*u)mO=9NB$vSzT-RUac?$#47npwHB zr(axmxJKBuYnR8`G>NHa#gWkWdes+b^#$7lYGu3ccl-%sQpY@EjP)?X^*}I;2@Si# z7;G!naC=0mOTKV*uC`4L;bW59=KJmkb@G9BeNx#PC)L_{FV2(36eg;3@6=XUKY>Gl(`pV=uhxr2jc$<8sHgzzo7Rgyu7t z&SVBM_N+lypCCrxfp~5o7X_(j&$p^OwM^au8Lz_d(Ic#hL_P;GU|9rf7?Y8pHwOZ! zUOs20euDDu{#q%o)C(M%wQEas;BQKgcZtI|ugcAdmxXinecJ~m^?Jyly%$=pXzI|P z6Ra=>uuYvl+cKy?1_fs*aOm$-#`hg}I|E*`zu*-Yyr^|xLg$&G4`QIdC9+A7-U9pB z^V;^OcRV}rn;^LG)GoLFI_>H+c87}utkZB6&SR-iFlmM{xZ}rcdH}Uk@O`YP(Jlnj zE+2FllbO{njm>X)yn_~STpB$xNziVtZ7d&~HH^9I-+n72@<*%3%Z~j~I_kEoamb(c zKjJX%{;4{Cznna=&tn*~{$KuE;#2hg&8kj4B~6tts&N=O?U&kX=*ba>Q(seZ-l9IO{Rsl&MwP8$V|9&_xcEqPi ze9}nOcSU>aIlb?aY=aIW1zmiUcUW} zuc?9-6fB`24S{T3U7dQYu&_}6dF?v6@+!RzdiOBqoquTO%a$Mp$7J{ZU94e@uZC0@ z10D{!INw3@wyH@+ZC_qnr`I@fhd=@S>)^9YO^H=^%bT@|$Qygs54K&LKbn0aV&8*v zS9kbK&>nw+whzR%X*Q)x_Ojm5jT(~6=cUT*86j*%B#6*Y%!kLd^GTy$A=G*Zd0EgP zS;Lsgxq9EDQzm7o8ZzaLmq=Cf1--(UXSRG_{jDdHW-RUwWA^X8SB`&nNKV$psa+|` z$x@T;`Hth72H$H{1ZV80JG5i*snS$wX-@1@_?@4hFONU|xC&$YgKLGgYuBpfv>G$6 zQnIoFyD_#uSdPJjG2ZwR(lCq(4ZFe^(9gT{Ye8(uv&K2(%4HE8ZV$W}cEk1Yi?3Hn zS&M#7T~XDc`k@>@M%!;_$7X~vM2~p99fnV2%^U6pKcnry+yfb$ z91NBo^zc5&@YNAIMcQ-6w27jZM(3BF^i`<GBxHtel_d^QQOE)8!0f zh7dF_h!6t`(mG_r^?D5m_b}$ezrCOyZ*HnrKOs3KT{RsN31JMNzyTLlSSCO%8E1T_ zBx}3#3FES)XxcwZn?vt>HziY!-Aq>WG4%bNW3Aqv%pCKLX z&C=O+Mn;W@myC>DNzGcI{&e!(rRXhbTFkHhJk8D0{5ZJd;ajt~(eSGK4^CtAc6v~?d zhcoQ|5hj}j{%MX*xptXTo%0W6hmJJLU*B(#%2xfn3bm_8=MSO%o532!nBNFA4V0O# zAKz-~^JVtTD}?n%Lz88T(YA~nAIFHdUM!j;{-Q9HvJZ;qd8k(TB- zLFh2J_Xe|&#hqT*8+hT(K(I}rd9^0({f(Bx)O=w3LI{Kc=cFY4r+MP7wmEG*hH9IO z${;2LP|Y2mE!sFoC&~yZa0gz&s6^GgSXPEZ-SjXJ><5#zZ9s)E+7Kys>SBM2U5wcXy)-qt-}y1uqbCe2u+I@-nG9zFc3 zR94lhKo`vxo~v;QdUU~l0|k@8guvL`-!wLB-$7T5G3m=d zZh{Y*QsS*f$e2rUSWWMFeeq&G-q4BvJkCNCSnxBGu3PHfN;Px)uvIma3eo0OHGi8Q zDNCnJ2ulBz;9)vMk;=8)&&$o+hcet&NftOc4rRzR{oLS?n4E83g?{jeQUYwi`t`$uA?*TFAdcx2Al#}ks z>hSf(cqOK5b7yV++TT22?#+$Y^rXN=MI<0;ZC|1Go0sC<9nPZp)Igi`VfftvNVn%^ zVFOv|qI?+T6Ls%bwbiC(q8TBu_(kN$)+pu9=%B36?yj+t?(D2^We5QEjdc$ z)_ac;2W|%@aL$%^TzlR-p(+fU?yaE=QT0+N$asfAFuaJrtV$lH|3&1_RuWV}AD$#O z$^}&9-??c?6w$mrD0)iMX_OsydZ~J2lSEk;l z$^2f-^0ES(#aUK)l_HMZADfpso@}Uv*bSp-@vSG76m^8qB;DKVn4#^PM1e^!i#$t3 zb8^sWX}nC2f4-S8~+Jt3J0P^;V^*#Gd9IP=XGD}W9Kcro|oyT;oZUJ9s zUSbB_`ca6ouiI#8Uy-Kz~d)~GAcevrY5E5~=QBsQ+3t;6qzGx`={ zRs?cmy1!SbVwTlOH&gvCNaJfIcThPiq`NVWoU-#p0LpAgwA1^f5no?qYh4AHe33I2 z|MK*9BerxW#v|fH262-L=TE@vwctWUrgcn^3?2}Y;4YC3NzEOb(=LgNah|>ZxsUm{ zLQHsDq;II9F909tkU|uc8$sRyxB?*a#f+g0kG%&!@aC|fm$=`x&2Fr!-tnmkpn;BU z^qc0LJ`^rmVm!OszQO>sGIGoP7SMK+*oI}ajPsK`S;X@gg_e=zkIf}pc@XaA-H+~M zkRHQv0d$0&7n*jxjhIArKn^0Hz=Te9|9+E1qdXV%%B)CqHInP?ZyS24tpiW zajmd^UrfBkrt4d>zd#=L?kHX&%Tnj*vl*kXVft=&n(YP7?K_>~k~iuV2rtFVvkK5) z($>e2A~PH&Jbtym%4!^Pu!VD9FE8drd)M_1Rjsi^wCH>DS9rAO<~{i`5=i+p<|8c( zPmhT76iQJ!nrmH5D2TZ4mLfJ+8Jo_+fysG?!SpuLy1vo?rmJ5#_R{O(^D;gJjQ(JRWTvMISv(`Hw^Lj+?E6E%K@_gM6Qy(XlBUntznL znWkNt{euul8OBcX>)FQL6tTLoua;rKzGmWZr~7?m5R&hbfv)u*OHt}P)BbdwY%uz* zZfCvGMgW?O)xq^c-{TkZZa>>LA&L+}4Bty`N(b`8;x{DhF={^MmpI0SIs<@N1C|dbjgEoziK8ZP3wki~A zAlN>j%~)`UP|fFjPsP?>Mrb*xytRUH&=8jVaI@|pGjz!Jps*QPl(Id}SDN2hznwHO zUz(z&KHZeTfkyyLAdDP!K$kSq201fGz1$+iB7`$m9#?G!d>~E#);X-Lm@7OK$|Baq zE@qy=*=upT#Vbxi_tlF88{3t>WO^a?S^D2TP%DtbEne7PCvpU0g60C_tm<@j5zkv` zeiPs63$O?&E7YRIqs918Uo;^c!5_QKPan{@^XcUi#d5AM{-&FR|B{?fOma>stmwA7E^MDk6d_mia zQs%ViAN59|eC!xpQ1h<|=vX92tG3)XDO_xBL|BVJ6nmHIFyJDatnmp;0eR-6uh$UtTml9BZr z;wIt~rdVn8v+>b4G6*P~*cO0}P!Z?=d^z?w*K_ufxLuzc27;RfCxBH}&H`@Jol|GG zqD*<2gU0j104F|RF+yjGWt;B)$@Yi(nh_?z1HMMX#4IGNwMI)X3b>!rQ}v85d9mA6 z9|7!smNCjS3B-i(q`jS(E)^|c@9Zlszt!kqQ3y(V=OoS0!vVx?_`Yr7Q5nCOtFjYu zMbneX%*%~=)Rt2B{eZ81rU$RyO4_x`&W{DDwi8?>2oU{cL<ceJ}y-!y-gKmB`-aQ=pe!+bZ571r`&=uLXCT$%m54bL8&LFYBB zQSFP7y;(IPp^)ZFy=3VCC zlqIuG3*=KPR$|vJiOConuCKS#pT-X*y$Lv1nwL0^$quu`NyYtsah|=$8%ms1+D#b0 zL}V#qpSeb3~jd|UkA2gz%Bhc9}W9dU-gy~6W2JPgmPrEH=#i?P8~V# zq3iW1+h4_0;d0zh9&2*IGz#>)`S_uv z+!4G;yjNZN;8}zq$I}nU+HGdFCX(Y<}@2`&v~e<*YTnli|k`TgL;FKo!#9%L|fK-xMK+*m&1n2M~P4! z6$C5mnau|W>h(IVTvNV)xn9(%3+#1RldEei?W%4bx7cCGcf(Z~d-hJZ6=Pq!yq3YS zpoZ$+C+~&&6=aPHKcgoelSg`&~ zym|HyX=zavxAlIT?MsDkGm~G~tnLR!UEpm$BYTQ`OcmMvm5b)r^dY5@^o3dR4xAL3 z{c|;u`@`Z=d*fPS7JW8{@JpBdZNei9(%XM&bf$}($J~s}(41Lo%U8G4(ntVC#w6Mu zLclsnk2!}d^UxJ`A+EWw9%ft6T2qF@K^P9-d`Td4m=k-y)r1{JaCmqP4Khv8hv-;E z(p=ET|JmeC*O}M9<<-Ii1Iv}S)L%YGCZ6cf7|a^^`n9Bwn5q+YFM&&Q%ihAS{82{M z!v~x}-N$dwG=TO)nK7l{=Ez3UfJmT^VbyzHK}MUCfH9tTZSr(u@qN6eV}#*_sn!td zT5>(Tl}iV2qO-V%TlUY)%9m`r`uEj6Y<`M|h~B3lJkGMu-^->b05M)Y8f0B_M*EZ5 zUe>p&95n(&C%gV<)#f0R`asD! zD3eLmRD9`RhZc(evsMWGp}s_>Y}sGF<|5xd4`D59dQ7&(YiS*cjxzn4C>hh)JSFmM zkM2-WMdHPOpdp7E*}b09h~G)vq=B1xzbpg+ATyf`Hakq^hJ&lMjn)O#{j6E%mtb7F zTP7xCx5Grgxw(1bdvh+jflsBwR=r@rVvI=6AH%@CQZlqSOFAFE@L>SAMFw%FV+Ti$ z3zE7Y_VuwFWBJ3#-V1o|R3t!(rt`m3@jq61>?y1U%P8NaX4SQ}hB-CKNby>z#C>(6 z6b(hDrK3Qcmn zt!5--z)?Z}K;VO@n7)j%hN_h+QIJgG5#Q9?0LbiYzoK08f&)$aR|K)jo4H7*afcNoCA3+tY0rp{5S>KWx0>D;8X7u;Ce>gjok z(K5>A*>Lj2^cXpIog=Dv)CZltn{~u{LaZ_>Bid?gBAQ2!UB(5?1VrS~ah|Fs$87W> zN3yj~54*!zOWRWu6XR_McTikjR}Oa?o0Ko>3oKN!M1$#7COg04-`!{RkRvUqz-Skc zM=e_0uG}ihM8L~5j`%A+sEf8*@_D=+E92-Nsf+Ws46d0$de+v5;zJbotPVcDBz=<^ z2aNW(Qwx8aS!d7N(Di1s05&qr5`nF3`)i!r@Km6kB0$beSqaxffqjN%d@sGcpILdA z52U6(TsWSAe1_}&5#L%gsaBFhhsAE6Ne9PdEX|JUJ2lA4 zGjFV(NW}?#hXBVN9M|T24~+eO>jdD~6j6p$zhm8Gb9qRUCJHouB}h2o>g5ruu9@wa zq=*n!Q+6pDt&Q%KoWa`y=#vs?ykqC+EVf&#P+39uX2uXFW(nyCJ~ihYYNkcIg>mw< zr#`*!XL3L2@I=?df81ATB~b`%w4^{f`uj%TPiq@{%|tzOV)Pp;{3`@aY#*LU3=sviK@m=vY}60V70Spa(vV*zSmp zuxi0a1d)!NyeIJ8inc(orZ#?j6rxn+i6FaR-_03TP@dMsR!i%g{`FKg_{BF)lKxM{ zrZ*6LVni7)BcY1TiZ)7i<*=ccqydXinA8qJOG6RP@D}c+Dz!br&Jbn|`Pr2w3AP(D z9v0wGz;W#My-7a)&EL5|TA4|>T_O6JgefKESNa zL2cNSHSI&?d-11NwtLOvnKq@L9@Nx1cP!+wIiBv@Ci-_d zT(nvEhbXD-+S#O&6A2+AB90+q+*t3T% z1Cya^)`Wb4yf9|{+Kqr+o4q}OZt^cG9qzWbPnDPHUgv4OSbzWX&4J$AH71-lwM&B@ zO};W83Oud_iUfMrrl>hD+M|<;3wvrvC)BOiZ!IQ#Wq4%;YcLVmHsDL=ji){Rz81Wj zpOW$nm%_#A9xvk_B{tsiD-^7(JhGRyqq;yY<^aZv{chph*&gY1Ugx#3v|nMW&vFp= z)B1F((tQ0T8(Ym&4X^i^JWsffyy`~g-mXd~yLS?8DKlc#`v(RRW59*aOc=D@#YF#U zJxE;s2uDXpU|}H6B7~(Qfi5mCBcr1>AaZ^?0CnXJw3BKCFyI8mY1**8+HjYQhBhv7 zFr)R+#<;nQ^d0&;$J_5=bxL0pou{oOKh zW1MNW#e{RV5Gd(LAu@aTR{poOh2FT43-a(l?x|Yh ze@ro{Bt3>GR}X8gH%+Y`GtiH z@wy*#c;V6X%`Bosc7)4Q+(r>}2Dh-WMW>2u*(mS8IUa`Xe*v0>RK$ ze0u6#xNH27D<(iq`|{(ndyqHRx;dgTk^okih(mj)V6d_zbv?dynj^uUmaFF5I|D8 zx7wi~oo^vMQak5mdtBE$9Ca6^0~_Yj3&H>iSv4-xN7(RdJW~?R`Ku!}ONzRVRgFo%kj4k%=lP|&6*Zz(^A9X_jc@3AJsi`%KdS`56ypk?+ z=(@VValq^A6!as9h`J64rgMf%E*6QkzB9CF1lbMQuqggRN=N_a9Te|`xla~D>vFpD zQf}0J-Nl7nB;o?}Cw^1p@<%vDU)_X78JfFUS`-Xj?iHY+YhYB|ztN%kQu2G8{WTeq zGvlfk0nti!gXy-g$nG$FQW!8HV7sv!@WFkfAx-cf+VbSeEm}-&-xGfhI_l}^d51e- zUpjB;HKw2V{=MzFihae@g6mX`EzjnsJv5{3=43VcL(_ysfQIOc$>*RoZS`L`t=K-e zZ@{UUsa@rB{`=)3Rl>_fbT27?^VgjNknd%lax9EHA?WP*D7|6rdy%?}O9gO@an62i zq~O)X(L{eForQxm#?Z^FZgUFx^zwJNY~SU@*=I|N;co1grrPn>)uECs2E#}mvx05MXsql`3S9JZA^_kEMOEwcCjs77EChpaKT_)(JK?{S zsqMG>A??`H^A%ZspP83YCczsU3#UdZ=eKuk1v5b5xO4?$IF?!iuF0|9$-zMYjg5M~ zP(SS|ROopTNoPRBqRrc-XSmY1bHIrR906>QifCd*xG{tjw8GyPwVnv) z)W2D)>F3)x2;klD|FS<5crb`|^Bk7F3OqR|EiGLdH+9>h)wH_rvxOPEU;sRA6)>{c z2*{%sr_SDSIhBZTeLe{IM<^uphjFiVT22_ilDA0lJH24*qk8vYdDcz zee{#;+j|n$u(hfM^{6Wprpc=eScoe=g2GKs5SmOZ0^w=~peg^x4IR~%OY87wjteFH&tN-vnN4Sc(;T!Y%wufXhtnu}2#djNm5yG6Q-@ z5UW}BG4NnOXcz#IbaqL@6>?{QTuS)v<^Y#75a&yry4u<~1kEcrU5=ZNUYA9`a2jZN zfGevg6)Nt%nF>@{XcxE!V_|&^3NI!<<{B0q5`mh>uyR|J&c0Tnyac{OavHJ59Spaa zi;eM!A_l(TRUrdUUx~;7#?!ejznsbLe!*+O#&h%X3ZXrfm6g#(&u2QANS;7}|KJwQ zT_WpX>~{q2A(o;>!c*oT&o6~tU(ZwPIF}>TJFY18hB; z-GMz-szhO(Adh};H*N5Z4U?tJlErANJ8WU*la`SMY@%xuhwbNK{L0bY& zN-5D#+;?v+#GXnY(jSb1wNA~Gx-iUS=@J3B#5Hl;Ezr2C+#$L1l9n*r5L|I%826KR zr?_PJ5YSq=Mni6+sI!rxB1OkFoquDpN`c1c(POKCK?|go0%(Hac?>U+O*zwn?B(yp zmYeVbbvOg032}A4f=<0EZ@V2y_^<1oa5d{=f#cH!a0@3GzTJ4aF^<=${r6P>i2qjV zlYnCYn9cHH-7pTwly2~O@vW2|IV-i~a>#x!r|sU)uKoW)T)BuBI-c1Lrt?Vv#`?EK z<`plOSON}Bg(evu;O^njsXaJ^jRVd-Zg39cp~0vsXkfurcpn zN*wmQBjPzho$gH90StljGMt)aS5LauSHFG0*(Lnwqg4mgBIMvdI3PK2GS?FDD`WoL zuF4B96?M9t@hg<@{wnP{3yp%fO}dy{Hg4WK9ypYQ12zBAU8P_nT)NcFxfav72Lkd) zs|DyKWMG$AKEAG=Jd)7)8X!>NI~=W#p;PaNDTQT8`7l66%Ftwy|I&fH8|MCN1?bc{ zX`@fhxq60%{TXg3M^McAE}}i&itKM}q0)K%^=d$5!VCh6!ELA=0MdAzd_7O-!u?E9 zfqyo+f9)s2M3&eQc$3tEEYAF~^n6hie{eJSe32Q4f3BNf5ZCTUxT1}OuGxJwSM+s> zQBmPjT~|7`JeGgWq(q~19iyV7!=kT~jq|dA*R+a_jfCyG5i2RlcU}jb|L@6#*{+zu Xt6VQt*)yDO;F_AUrc$NC^RWL1WnWdl literal 0 HcmV?d00001 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Airvolute-DCS2/README.md b/libraries/AP_HAL_ChibiOS/hwdef/Airvolute-DCS2/README.md new file mode 100644 index 00000000000000..b747dd3f54be07 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Airvolute-DCS2/README.md @@ -0,0 +1,256 @@ +# Onboard FMU on Airvolute DCS2.Pilot board + +DroneCore 2.0 is a modular AI-driven open architecture autopilot designed for complex use cases that combines high computational processing power, redundant connectivity, small size, and low weight.The autopilot represents a one-stop-solution for developers integrating the functionality of carrier board, companion computer, and power distribution board into a single compact form factor. +This system usually uses a "CUBE" autopilot as its primary FMU, but can use an onboard STM32H743 as the FMU. This board definition and firmware on `the ArduPilot firmware server `__ is for this secondary FMU +For more informations on DCS2.Pilot board see: +https://docs.airvolute.com/dronecore-autopilot/dcs2 + +## Where To Buy +info@airvolute.com + +## Features + + - MCU: STM32H743 + - IMU: BMI088 + - Barometer: BMP390 + - 2 UARTS + - 2 CAN buses + - 4 PWM outputs + - PPM (RC input) + - external SPI and I2C + - SD card connector + - USB connection onboard with Jetson Host + - Ethernet + +## DCS2.Pilot peripherals diagram +DC2 Pilot peripherals + +## DCS2.Pilot onboard FMU related connectors pinout +### Top side +DCS2 Pilot_bottom + +#### PPM connector (RC input) +JST GH 1.25mm pitch, 3-Pin + +Matching connector JST GHR-03V-S. + +RC input is configured on the PPM_SBUS_PROT pin as part of the PPM connector. Pin is connected to UART3_RX and also to analog input on TIM3_CH1. This pin supports all unidirectional RC protocols, but for it to be enabled, it is necessary to set SERIAL3_PROTOCOL as RCIN. Also RC input is shared with primary FMU, so it is default disabled on this secondary FMU. + +5V supply is limited to 1A by internal current limiter. + + + + + + + + + + + + + + + + + +
Pin Signal
1GND
25V
3PPM
+ +### Bottom side +DCS2 Pilot_top + +#### FMU SEC. connector +JST GH 1.25mm pitch, 12-Pin + +Matching connector JST GHR-12V-S. + +The DCS2 Onboard FMU supports up to 4 PWM outputs. These are directly attached to the STM32H743 and support all PWM protocols as well as DShot and bi-directional DShot. +The 4 PWM outputs are in 2 groups: +PWM 1,2 in group1 +PWM 3,4 in group2 +Channels within the same group need to use the same output rate. If any channel in a group uses DShot then all channels in the group need to use DShot. + +5V supply is limited to 1A by internal current limiter. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Pin Signal
1GND
2GND
3GPIO/PWM output 4
4GPIO/PWM output 3
5GPIO/PWM output 2
6GPIO/PWM output 1
7Serial 1 RX
8Serial 1 TX
9Serial 2 RX
10Serial 2 TX
115V
125V
+ + #### EXT. SENS. connector + BM23PF0.8-10DS-0.35V connector + + Matching connector BM23PF0.8-10DP-0.35V + + This connector allows connecting external IMU with I2C and SPI data buses. + + 5V supply is limited to 1.9A by internal current limiter. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
Pin Signal
1SPI_MOSI
2SPI_MISO
3SPI_SCK
4SPI_CS0
5SPI_CS1
6SPI_CS2
7SPI_CS3
8IMU_DRDY_EXT
9I2C_SE_SDA
10I2C_SE_SCL
MP15V
MP25V
MP3GND
MP4GND
+ + #### ETH EXP. connector + 505110-1692 connector + + Ethernet connector is routed to FMU through onboard switch. + + The onboard FMU is connected via the RMII bus with a speed of 100 Mbits. + + #### SD card connector + MEM2085-00-115-00-A connector + + Connector for standard microSD memory card. This card is primarily used to store flight data and logs. + +## Other connectors +### CAN 1, CAN 2 connectors +The board contains two CAN buses - CAN1 and CAN 2. The buses support speeds up to 1 Mbits and in FD mode up to 8 Mbits. + +These connectors are not part of DCS2.Pilot board, but they are routed on DCS2.Adapter_board. This board (DCS2.Adapter_board) is fully modular and can be modified according to the customer's requirements. For more informations see: https://docs.airvolute.com/dronecore-autopilot/dcs2/adapter-extension-boards/dcs2.-adapter-default-v1.0/connectors-and-pinouts + +JST GH 1.25mm pitch, 4-Pin + +Matching connector JST GHR-04V-S. + +5V supply is limited to 1.9A by internal current limiter. + + + + + + + + + + + + + + + + + + + + +
Pin Signal
15V
2CAN_H
3CAN_L
4GND
+ +## UART Mapping + +- SERIAL0 -> USB (Default baud: 115200) +- SERIAL1 -> UART1 (FMU SEC) (Default baud: 57600, Default protocol: Mavlink2 (2)) +- SERIAL2 -> UART2 (FMU SEC) (Default baud: 57600, Default protocol: Mavlink2 (2)) +- SERIAL3 -> UART3 (RX pin only labeled as PPM on PPM connector) (Since this is a secondary FMU, default protocol is set to NONE instead of RCIN (23)) + +UARTs do not have RTS/CTS. UARTs 1 and 2 are routed to FMU_SEC. connector. + +## Loading Firmware + +Initial bootloader load is achievable only by SDW interface. Then it is possible to flash firmware thrugh onboard USB connection with Jetson host. diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Airvolute-DCS2/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/Airvolute-DCS2/defaults.parm new file mode 100644 index 00000000000000..6ffa986988d26c --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Airvolute-DCS2/defaults.parm @@ -0,0 +1,4 @@ +SERIAL3_PROTOCOL -1 +NTF_BUZZ_TYPES 0 +NTF_BUZZ_VOLUME 0 +SYSID_THISMAV 2 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Airvolute-DCS2/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Airvolute-DCS2/hwdef-bl.dat new file mode 100644 index 00000000000000..e11d30a2ba3901 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Airvolute-DCS2/hwdef-bl.dat @@ -0,0 +1,58 @@ +# hw definition file for processing by chibios_hwdef.py +# for H743 bootloader + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# board ID for firmware load +APJ_BOARD_ID 5200 + +# the nucleo seems to have trouble with flashing the last sector? +FLASH_SIZE_KB 2048 + +# bootloader is installed at zero offset +FLASH_RESERVE_START_KB 0 + +# the location where the bootloader will put the firmware +# the H743 has 128k sectors +FLASH_BOOTLOADER_LOAD_KB 128 + +# USB setup +USB_STRING_MANUFACTURER "Airvolute" + +# baudrate to run bootloader at on uarts +define BOOTLOADER_BAUDRATE 115200 + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART1 + +# this is the pin that senses USB being connected. It is an input pin +# setup as OPENDRAIN +PA9 VBUS INPUT OPENDRAIN + +# UART1 (SE_CONNECTOR) +PB14 USART1_TX USART1 +PA10 USART1_RX USART1 + +PB1 LED_BOOTLOADER OUTPUT LOW +define HAL_LED_ON 1 + +define HAL_USE_SERIAL TRUE + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# Add CS pins to ensure they are high in bootloader +PD12 IMU_CS0 CS +PE13 IMU_CS1 CS +PD13 BARO_CS CS +PD15 EXT_0 CS +PD14 EXT_1 CS +PD11 EXT_2 CS +PD10 EXT_3 CS diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Airvolute-DCS2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Airvolute-DCS2/hwdef.dat new file mode 100644 index 00000000000000..313d8e62453015 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Airvolute-DCS2/hwdef.dat @@ -0,0 +1,174 @@ +# hw definition file for processing by chibios_hwdef.py +#following exapmle: +#https://github.com/ArduPilot/ardupilot/blob/master/libraries/AP_HAL_ChibiOS/hwdef/mRoControlZeroH7/hwdef.dat#L105 +# for H743 bootloader + +# MCU class and specific type +MCU STM32H7xx STM32H743xx + +# crystal frequency +OSCILLATOR_HZ 16000000 + +# board ID for firmware load +APJ_BOARD_ID 5200 + +# the nucleo seems to have trouble with flashing the last sector? +FLASH_SIZE_KB 2048 + +# This is the STM32 timer that ChibiOS will use for the low level +# driver. This must be a 32 bit timer. We currently only support +# timers 2, 3, 4, 5 and 21. See hal_st_lld.c in ChibiOS for details. + +# ChibiOS system timer +STM32_ST_USE_TIMER 5 + +#optimize for space +env OPTIMIZE -Os + +FLASH_RESERVE_START_KB 128 + +define HAL_STORAGE_SIZE 32768 + +# use last 2 pages for flash storage +# H743 has 16 pages of 128k each +STORAGE_FLASH_PAGE 14 + +# (---FUTURE REVISION---): PA0 AS VDD_SENSE_PIN +PA0 VDD_5V_SENS ADC1 SCALE(2) + +# order of I2C buses +I2C_ORDER I2C1 + +# I2C1 (SE_CONNECTOR) +PB8 I2C1_SCL I2C1 PULLUP +PB7 I2C1_SDA I2C1 PULLUP + +# USB setup +USB_STRING_MANUFACTURER "Airvolute" + +# This is the pin that senses USB being connected. It is an input pin +# setup as OPENDRAIN. +PA9 VBUS INPUT OPENDRAIN + +# order of UARTs (and USB) +SERIAL_ORDER OTG1 USART1 USART2 USART3 + +PA11 OTG_FS_DM OTG1 +PA12 OTG_FS_DP OTG1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# (---FUTURE REVISION---): PWM output for buzzer +PB15 TIM12_CH2 TIM12 GPIO(80) ALARM + +# (---FUTURE REVISION---): RC Input set for Interrupt not DMA +PA6 TIM3_CH1 TIM3 RCININT PULLDOWN LOW + +# UART SETUP +# USART1 (SE_CONNECTOR) +PB14 USART1_TX USART1 +PA10 USART1_RX USART1 + +# USART2 (SE_CONNECTOR) +PD5 USART2_TX USART2 +PD6 USART2_RX USART2 + +# USART3 (RC INPUT) +PD9 USART3_RX USART3 + +#LED RED +PB1 LED1 OUTPUT HIGH +#LED GREEN +PA3 FMU_LED_AMBER OUTPUT LOW GPIO(0) + +# microSD card +PC8 SDMMC1_D0 SDMMC1 +PC9 SDMMC1_D1 SDMMC1 +PC10 SDMMC1_D2 SDMMC1 +PC11 SDMMC1_D3 SDMMC1 +PC12 SDMMC1_CK SDMMC1 +PD2 SDMMC1_CMD SDMMC1 + +# CS pins for SPI sensors. The labels for all CS pins need to +# match the SPI device table later in this file. +PD12 BMI088_ACC_CS CS +PE13 BMI088_GYRO_CS CS +PD13 BMP390_CS CS +PD15 EXT_0_CS CS +PD14 EXT_1_CS CS +PD11 EXT_2_CS CS +PD10 EXT_3_CS CS + +# CAN Busses +PD0 CAN1_RX CAN1 +PB9 CAN1_TX CAN1 + +# CAN1 Silent Pin LOW Enable +PC7 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70) + +PB5 CAN2_RX CAN2 +PB6 CAN2_TX CAN2 + +# CAN2 Silent Pin LOW Enable +PC6 GPIO_CAN2_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(71) + +# Ethernet +PC1 ETH_MDC ETH1 +PA2 ETH_MDIO ETH1 +PC4 ETH_RMII_RXD0 ETH1 +PC5 ETH_RMII_RXD1 ETH1 +PB12 ETH_RMII_TXD0 ETH1 +PB13 ETH_RMII_TXD1 ETH1 +PB11 ETH_RMII_TX_EN ETH1 +PA7 ETH_RMII_CRS_DV ETH1 +PA1 ETH_RMII_REF_CLK ETH1 + +define BOARD_PHY_RMII +define BOARD_PHY_ADDRESS 0x0000 +define STM32_MAC_PHY_LINK_TYPE MAC_LINK_100_FULLDUPLEX +define HAL_PERIPH_ENABLE_NETWORKING + +#PWM outputs +PB3 TIM2_CH2 TIM2 PWM(1) GPIO(50) BIDIR +PB10 TIM2_CH3 TIM2 PWM(2) GPIO(51) +PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52) BIDIR +PE14 TIM1_CH4 TIM1 PWM(4) GPIO(53) + +# BMI088_DRDY +PE12 BMI088_DRDY INPUT + +# (---FUTURE REVISION---) EXT IMU DRDY +PD1 EXT_IMU_DRDY INPUT + +# SPI1 (ONBOARD SENSORS) +PA5 SPI1_SCK SPI1 +PB4 SPI1_MISO SPI1 +PD7 SPI1_MOSI SPI1 + +# SPI4 (EXTERNAL SENSORS) +PE2 SPI4_SCK SPI4 +PE5 SPI4_MISO SPI4 +PE6 SPI4_MOSI SPI4 + +# SPI devices +SPIDEV bmi088_g SPI1 DEVID1 BMI088_GYRO_CS MODE3 10*MHZ 10*MHZ +SPIDEV bmi088_a SPI1 DEVID2 BMI088_ACC_CS MODE3 10*MHZ 10*MHZ +SPIDEV bmp390 SPI1 DEVID3 BMP390_CS MODE3 5*MHZ 5*MHZ +SPIDEV icm42688_ext SPI4 DEVID4 EXT_0_CS MODE3 5*MHZ 5*MHZ +SPIDEV lis3mdl SPI4 DEVID5 EXT_1_CS MODE3 5*MHZ 5*MHZ + +# Enable FAT filesystem support (needs a microSD defined via SDMMC). +define HAL_OS_FATFS_IO 1 + +# IMUs +IMU BMI088 SPI:bmi088_a SPI:bmi088_g ROTATION_NONE +IMU Invensense SPI:icm42688_ext ROTATION_NONE + +# 1 baro +define HAL_BARO_ALLOW_INIT_NO_BARO 1 +BARO BMP388 SPI:bmp390 + +define ALLOW_ARM_NO_COMPASS + +define HAL_PROBE_EXTERNAL_I2C_COMPASSES From 3dd27b7ac51f2457e8b1ae89375fa7634b710559 Mon Sep 17 00:00:00 2001 From: "tomas.vrsansky" Date: Fri, 8 Dec 2023 12:10:06 +0100 Subject: [PATCH 0045/1335] Tools: add hwdef files for Airvolute DCS2 onboard FMU added ethernet config to hwdef updated readme.md hwdef: MAC parameters redefined according to ChibiOS hwdef: add default params for Airvolute DCS2 on board FMU update according to new changes in ChibiOS MAC driver added defines to support ethernet communication bootloaders: Airvolute-DCS2 --- Tools/bootloaders/Airvolute-DCS2_bl.bin | Bin 0 -> 17732 bytes Tools/bootloaders/Airvolute-DCS2_bl.hex | 1111 +++++++++++++++++++++++ 2 files changed, 1111 insertions(+) create mode 100644 Tools/bootloaders/Airvolute-DCS2_bl.bin create mode 100644 Tools/bootloaders/Airvolute-DCS2_bl.hex diff --git a/Tools/bootloaders/Airvolute-DCS2_bl.bin b/Tools/bootloaders/Airvolute-DCS2_bl.bin new file mode 100644 index 0000000000000000000000000000000000000000..1c9935095b9f4541d3c401bda7047c2ec1bd3ace GIT binary patch literal 17732 zcmd6O3wTu3wg2AdoO$E{OfpgO0_Fi42+ELvMB|lVCY*!}m`Jomw6`aTUe16@e6`re zWgyW;ur&&`k>D*Ft*8|Un*I%t4iap&_Avv-hM?E9s6&X>6B3w{2Xp?veP)8_?Y+1E z`+fiKyZOGIz0Q8Dz4lsb@4fcgYlxB9{=yOSsed3DivO{84AMiu>zu`#;$3>;3*G-w!YNlD_{*|NpMfz5k!_|99j6 zZ>s0|h(gp@cZ-nOSn5CFJ)=H=bW`?;p<+YLQ>Ft~<5%U1l-!}s2-3OS9XBN3u_ z)U@U4Un#@52MN|OaUc<5Hh)g~klR>UUkNd@@;i`Zq@$%M!y36XUDdBtT=ltS%bRLy zD1_AcnPp4oY2|U^tRG5i%oBH^4^^heViBsmdVzctix5)OPLz{loU&rnAaY7zR1iZQ zQ+&^OvO=`*8PAfljSJI*f=Fi3nZ(8^C8McrMER~tlt(WRrFc9~B+B#=qTHimMzcPT z7{q}H2~uL(X9nKr*sehvzsj>}iMi9%zT|8=&)MnjS5?796w^4r?^~)cR@Cm&she8H z%PDPCX^9c%W#tva-@DgZMwKo2Vzj3(cgof_r%a2TQZ1lbK(*4O75N(qJ8I?ccW^eM z92hTf)=K#s_P)hC`f>I95w_rK}xmueMkED$8@lESb(H%F_X%aGOUB*T~Bud-vHV0zO}h%ny=U z{v0XX;Rz^>0mw`_Hpbbs=)2ldAF&@-PusfG)0X3^#onb_(pY|6{S0NFp)3Ps87Rv@ znSwF}Wtk|;L|G=v0yd9AYPyg!*l`J*sJriyx(V2I->)i^K4+I|Uh!T(5hhlIqx^{4 zU}0ZXe&=wYu&SED$JBt!d%o{GT|@5}x`u8nyp8f_jH$E5oM9iSr{8OY^fG5(GNyHpYCgwDx`;l6Z-b7;c#}oO| z6k>iT(eF{fpP+8yoAsH%^`GTzOr}G(#z>x98QDZyIJ;r@fk86G9LyE5o(f-8Gq9Gb zN1up5&+CYC!>DQcz)99;G5UNOqKggl$k~72^wDXP!Y5C%Sg$cS1>i7jBZ@dWwNJ3$ zQZ^D1?5oSp_Eekj&Jg$+2?aDlPj%gk1eXC|>hyn9+3Zf=MKKEg|sv3haNQ ztgJXTWAqW#jeVpXd(XZ${%N;JuX%RR&E4d=X$es(MoHf1;RB+;=4)m1zd?-8`qPoi zBeNh=Et(aZi52*Y$8>`2N13D4Sp-9CG7@9i-&LD8>eaG z@Hh7|3Pvv!K<>|u>>DIz?fi(IJ|7{lydWcfqzoo=2?8+v-gd2fsKo!H|$OK zy|I*TbAA}-_ah_FogHM3c7Fa|eg|DdTX>b`e~vwn?bQv~JHEc}2yE{`N@ev(Z-WBA z&X>i*Q})idDy`?OK^vF+$}EK^4a+=BGfVP<9+5stl$%HC4$Z!?j3^I|R-D<*zdiIL z?gz{AL<(6xFlq#67Z2aPm$n!N>J5bvHnV@az{)<}LzLf*FzBN_(_glhRH?S>4cpwJ;4r)-EF#LtXh4iaionx*Mhs17BY#jc0!({| zk~hLdi1QA+uv@_BQ-OWs@V-54OkN-Jl3<55b;>_~oz?G{0lT^C}zRWhj9H=;$K9M8p0^w6kvpMKUt!}9k`XxJ5d7?k&%oN(s5DU#(zgoKc)4l9}8XAN@$J3?MZ%j}X_lM;k_0=h9HC zCp~I4$;|Q5M7OEH?t)q%%l-PzM z??Hzx7%u~!8A z_i47aXH*l3pY;`r=7OC-k|9NNyB2*`3n-Kv-tYFnKJX=ruGh0R7=2Z$-AzTOY!g59 z3%*~9u0v8O2{Jku4f?#>Ez8L)%Z*g&9k&Hsva_+?liEXO*&1mPRenG2Y&4Y6;`Vca zdCtJ_@w!f`92qZ^QC8S~jw~*eJ~@6m@;>l2AyMU#PBKU&a*nu&42}YRlCUqTm@p@U zFIzVFavEE*>pk2FO9@qW9s(yySzm^u2s|;ZnBA5q+e$i57rCkO{2>NYtH*RFf*zA^2R+LA>8a~2tKs|W$Wnm+@Qb>g;!-mhWc2!;PV?xaQ5WU zF!eQ8>of@5DlU%?bH0jUQn2HaG9k>BSNZD|j;~^+Xh)ou_H7ov)kx=dfjj&o0Zs_vn`z#aXi9{oEXYZAE7y9_Gq}Slq=!I zZ5}QJN^?ddb*0dE?~D~0qDgENf2z*3tvvXVTGzDmHNdX?4z@1K#CbJZ^pu7YvP3*Q zXyyz90rH$DFX#~8-~S}hqI+4L>-n6iCDTiqNk(sFA!shs}NY zYx#lAe7)ySAuXDZvUkJ8hBZ=8ZDSE88_t)#0jZAhW@3#LwP!ESUSY%9{ms~Hk>!6I zyGmv!MYq~yJEjUnUU2CMa(1StVecl&z&NX$vVzs-$xhTyTDHr>+Efhxr7%UJA);Iu zmE~O?A!J;}G>jYnU3=;ZL7cuJ)pv_}g>8ptQYabL zXQm@l)S|03L82ncN$2T0U^#Yx$$Mg5F?fiXBlf819mr8tFW-0hUxN@uPRSxr3311fKwzf}R&baWzs4$p; z-2s|&U-B}tohUbsBr!d@FKL-DSVUOKZ%0h!Cg0KisZMSm^d;B>T1s%|c-TVBC0Ahm z03Z3wIRpO#SNqK6WOimSRiyc8VTZ5TGa3Jx?a(@Kg6QCv~(Eh=|w}ntZy~E||+~^#QEOz477knG*h0)CHTG+Iuzq#8WE|Q1+cGH5I z>`;bcrkTNt;lRCrHI)UIC^p(^s!&`!gWXip%K}utrA^bKRa)Gt{i`9lJ8t`;XLTNG z#6%7HCgEI2&QNUTqHwYC@@`gQ7%WP*87Ta;*h%9z>x@;z4nD{Ym2oN=X@rEG-z z*XCgb-eJjtE*%)zf|6nXuOjTNLW}OXK%c%& z?33pM_ii0`e}wgV4)Dhj3)TRc*;UQ8G)QksTs2>FxF3FmenXn2)7&2FHxz91(C}t? zbH`?x7HpPQ=X$EM>WDqmFBI(X%nWwP-fE&e79%!uCp+`TKx-ZDxq>)ZWHNq1exa>Z ze$G#eTcxVp*6PbPIQ-kt@08qHeafHGW)quB<8sOqO?~tAo#YnS^MCDq7`^K{uj-Fh zFkDl`W-+AZHbM5ujQ`Mxl*`0B+t?{@!)%slyeM@n(fcn%|3Tb}*!UZAc->a%z)gY= z(I%Vtb}4Pyiki=}rLeNNVP_d0SeaPxcW^F`Tm+6G~EMwtG9o1GTUdWbsHAKmJb2x|ibZz!$2tCfYp|Z&$$D z-4B@Y!_xj$s;25xWrS}9RV#I>CWjf0VvQ5a+8A9G!|wa5L09K#3wEQ89hOe_I_w`9 zgPlto+tYn?mT-k2G9DWqAcGB@SDGy{UZ?uFCg9q}Fp#IH@_8)DC!F8zVVqn}xb1)F zC$+4ODz9t8zPe5`&fB!9#JuowVosLht03i}ltPc{B)*5NdcO4`Yg@bo^Qh`lpU>nV zQTUx8H%3oUJHJs7t!+)}&8}BE=q%eb&aOpW8k606h0Rg13iP zB;J;93^%EpY{Y4w!}rXXW9(tvcgz_JAMT%4$oKK(o;4=N<~3bw;x_35*cpqMY;Nhk zs4>~PY^GkKF==5kxLmM_R2kA%wb7Rtbe)DCmuSynmEY&;q=PBE(q5@LrHA)1J&v`- z`6&!MY;sLAgX&+z#$+RAbDKX$&S|4fRB>vwnSY5YX}awBmbjhOtj2dX19tf_d9^=X zCUee(a<jD@dmNdKUvHWd!@`a+_o_D`q5qf3HXPj^Tj+!uMW41 z_6~OL+0cepsFjUfFIj+l9dI-4r;6)<@;aRbtU~FdKX!jC|C9H5|I$rPX#R6jt)v{H z%8CPoOtdj2+T7tce5Fkn+SIj!(piEy)4|tawWy7isV=uF+^$6zV6+Ccu97Nrq*l(6 zoo!4Gj6zs~o%{wvKBFudR?=fGgOjiGqD>0;%FeY`iSdVSFwAD!_n6Hqb9FiLgbi8O z-lW#K*yCSJTV7WiT>DB%UPH($*RJ8^)-~DaXIXzu$bFvkZ1Zd!-mv#} zU+o&s*}8@}yFf1+Wh4ASY#es0cpmxD{%N;-vSvf%b?}glHd&{JNpcJJjqj;(4pNfwLD^qB4H&s4UX`T?`;2p`>oA28Z$@ewmjpDdEq|bz4 zCg#1Yj}`4-3uPN^B8Oh*#$H9MPsd)q*y`M#iB`KpIf+)k8{2_a2giOE$+#%veAu2$ zW8r(#XVCxYx7sedSo@_0td3pyH05IXm%XIeDcJl)I15}z3y_KudQ0+e2pNle_fMI# zpl3>c0p1sQWzqckW=FyN#NVPt53k<`eSF4~ajZ+u+0s5Xbe11Wzvb?ZIA7zVXwj>6 z%93?Wp4^wA=kXTAX%n->EKr|(aZl=6&$qGF6^X>xL&aD;Up)5Jb@6BHgO&uX8TqrJ zcgB1}i1y^PSvr%7x%{!7c)xjx{xiPTKdbMu{Qhu?zBVVQiPQ3a!WZ8g>B2sG8|2*` zo}h}Y#y>`gbF<7p$YU>mT7JSac5JoGOCHH0t&*^#ezmUW(mHdyIbm<6{E!E=LjI&s zeg|8t=FY8t;>gzTX!X@v^p9AvXCvW$Qec%gbWU z2V+tBKv^EUGrQV9lzq8B!U;4blrJWg%eXn+IKp(}l*Zl_*mvc~Zodg9mKHssjYL?# z52q8e0N>C_xe5DHvuAq{{u-Q~tj_GSwCBn_vLi9x2a@AKE&3CU>U*Tc9gEJ<$1Z9& zEvMLFjmu1B&bm7#sx*&tSS@T#F~8A1+{xY0ErydQB^`YEO>&idTXwT&tOp!pzM8(R z66Z8mo5ii0>q_h8R%Y3#8FM+mS1p9oTycT(#-ZHCQQ4f~1nos^rar`WXU?Lk%_m$?=lLY=vtCgfs9{p!SS zY3?+l&$VqHITJFlN?u7otuM%KLUI1^;FmF!Ept+(lqo(9xy=oN2G~W+3b4ry9uh9< zr)k3xUbeLFl%Ip2?{;~Mlp-yc?9#2$)AE+=9dYU7R7uatkw1gXlV=wN zlkLn~IY~^uLdv4b$7ApdjtMz0c=(YgBC6tbNK(_e-iXO z=lS?V8vL3TcTzU|5<#NV!2BB@sfPmQL5pebjXkObcEGf;9yQnfvdrh;J-jEQ1b5M- zZqV^IO4(X`OC?Qc>3R(}J*r$j#ykk!{rvnqoYrxjTIVPEJt3;7qig-U285)|V)@cZ z$2c48l`-Oo_ce!a(k&qccc#2xdbXqFY$SakDQUJ?Bo+nB!Lxx_dnC~|lu?4wi9P!z ziFqxcv%l7T5<$j8eNAD#vNv$1dvWcAzRyk#@w0^xooy=1#G0-v<>wfB3}s~C2-*o{ zXp1ru%=E%91$+4SSf6$6JN6kwGwe6|5>bw*bayP;a>1KR9KYFr8?lIQ^^*n8I^M}G z5L9|SeI>k~TksPP?a9V{!V148EkJpypmMo`5i{<4Y-i)kwCFO}lkr`S1et#>Znw|i z=p2)7x2MeE!^FvK^~?I=_PjZ~52s{)2eazqHoefJMNJ1Ba|S}Ak+0kH#h~BRZkRn4 zrxaDPF6Xnd66@PiPVKY_{`*nd%-JWEYtdImCxN2hkHjg8`}5 z5V;F{X+mOj7r`r;x_pk93U8m8XwfyAVeogHFlZr3%e1JZ8P5IgK4CBu{_yw><(ts6 zCNKPdpl>;Fd;_T(iLGceyC+0H8~@FISbq!n4JjR&VqIqePV-pw56t6^H_G#nDbrDd zn2OT($Mcu{W`7=Z<0H-7X1eD5{ycbIwP+8%EcmLuI;H0$^)bAeJl5o__(*@_+ z#}#!Wo_UJl9Jx}7N-iiy3Aq8R4rxSe6AACTwq?<6`>2E2kU~7 zBIp*IZv}EU5;;9MBNd6gt>et`-((sOvj~EfCKVoXoC7wp(%e4Dm$TuO4lVkbmg4J` z!zQ6SxqP+64K^06mX52b_G2bvx3RoS73{2xyF>lD> z;8E2wUyFW2+l4oh938_^HFf@bNM86!oj2id&5#5Gtr{AXrD)H4yH%!u43u1Ewn9ABKe{Lue>wl zhjKp*3y2vR2^$7Ccyr2fZ^VsaMvkv2mRGPxwqZR&LyMk{F>cu$c6dGV#6taTp%A-!GgisLP?5MV zl3^z+Q!y{Rt**4Ngl|i`dAV~#URw?{sXIntjo`MHKOVASJy^iG&wm})8Lq_SJGLK| zB+hC}XGt#EkJn?uqNMuv4@XF_(oI%PhHaI*ex_h}FL!)! z?;Q@@@03hFhQS34h@rZT?Dwj+N*x1>4=LkTF+8Sr>cGwlZXRW~e?4x8dO3Qg7#ME=C)RJKN))HuAn9Uclu=1x{#*FJ$IyPVh&<&r+}UFG-cu`d(f6R|akc$xOM>%fAo<+y)zBi}$=Hk>-cy6nw zh{YJ#W6^s?bIV!mO@oV3@!ySn*Vjg7qfJo%)d-%tPUut)?)y21!LyR3#LQyOCK991 zgjbgyi~S6tUC58C#O^plum`YsCo&%^9WtzgzkH^bIG~FQ|4kMKJl2~iYLiHwp_k=u zCE!MnB)}<&vXn$w3N5J3e9D6erdyG2>pNBfkH=9pw}{zlk5cxELaTXyi*fwDbm&Ii z0r>6l-V}=#YDvDMYLm;1|Jz+=y==CI*Cmu0^)gH6Fq1d7*9PpbO(KH@H_jZKG4NjC zW$E^?*B4To+|8a<;U&Jw_B(BuYa$M-2Qa~Y$6~Vdx&Bu%T8Phib-ciLN-Ds}q=-22 z-X{UN;jq&wRSXN(*4jc?KI6UAnQAMs^N#-^|F>cE%}#NbIos{)OF~T=4g8 zx8TK3q3Msypw4wvT~Gvi^MnC!IxYM;UO0&#Y26XkoP?Be_E?I{UP9ken_aav7N@oP za{uLu#W)sbeAqnl9(d;*j@2?AwqmuoonFPlw^k=P!4F{0C`$1Sz|KAF#dk52KPd*} zM}BQLaKf7Bu*R&wZ)>elJ0-~49Uyp%Z-QO5#d0ix-+P8yL01twr`TIF^Uk47WvUnu zd*vykn?}m$<+4%XjrULI@(lw^te7+19{iP1bR#1Baxh~G%Z6_b8V3X4pricI6Mn$w zh)8B%7y9NFVQ>{)SOy@KP ztGqp+xH;2vhWAoLMcKu-)n<|>8U{9VRnUm<$IJtd66Qzno@uBmTQJ>w2fg|x;4Yfs z1?COx&Dt=qZ0es?l4BnxOMZ)-jch-|^M~QtSULYYd>C{=M}AGns`=oMYZ<+5m35f7g%JMFNDabr$2nj2 zU(|uO^j$e?ZHjD_e7Gw!o-=;48~MwAt9)F_>Tu^b1l>-nv~Ej=%w&~Y!VN63(Cd@- zzdklJT15LgK|PysIfoFowj=cq1fxTs43HIurJu@0+{dhlb_AregG+ly8%pOGiyJ z^wN{2oNmKF1AjvPeaBXR*_PGv{xRh|8N1xEr6W`Bm76@1j-_XJ^^=)#3)v34P>XKW z8erwa#@vM0o>AfKx<{R`Db{Uz7k-nW5Nm_FC7GpcymDFxjxZkI<-bDyRQkrj>=IZt zwj-(~X^za{G@x^m_fLjRXg2c$o(v1-i}jL}5yVbf=~hT3RzVVK*nF|$3U16di8_v} z3(VXo9i-kabwMU}jSlzK;I_>s+2rh!tG6^{(d%CyJ3s6`bJWeS{08R{TN4vJs-Ouj zJ({V|Dd5wixuN&58c&)sbw0sfJp2J76tP?O^~z5zbsc+dU^2&UhS?JA&!#v(m|e$i zgPBTT$~5#}P(-izg}cx*HN?0|7hqSYWSBnQKd%JXY=!}00p`(nlYH;ejN{#C?>u8P zzNId}>kr~Hz)gCV*SX1W`am_q4;cR zkM9#wySt&OR>e4FKz0t-Riy^K!X+E^87W;ip$18rPV&-3|cEY=!8fIhc z_}W+uUlsh|Clg-SA&v|l2>c)JithK+rY3SF_NL^dfl^)TdF-IDHRq*am5^eRKdHCo z(d1FnkOTWd?IvO1N6_+<@TXr3%eA?bE_x3qskXmG{<-JF6N)j5VI_7m7A=K__WeeKUYZe<@Hox0V`RSR+L=er3!!H8#wy$qP@ zusgO6F!K<@hK|hx%P&Zt?k|y^sKQ7BZU~b~_l)Y*@Es zHkp&l?4j8nr3n@fnH?`1J9(|hIITs0H0HP{A7?^7Ef?jJGDuT?7kR=&!`SBnra9ao z<#q-UGqttiOlIEVh%ODtqE|kqW@1g6Z6EZL+-C<;Q;Gd?M1HWBuO0Gr@D{Dc|JBm$ zNSeY=iDP?gDRv0j5JXg&j_p%KcBqe=+nI;rff(}?A_n*%vk&5BYZGO42bq1qb}fEj zNm`igw8O;uCUUmVUs8T;qWs#gl^5d#`n&BD<$C)hN(Ln_b@1n^z3=R=SBaG z)W_fJPfmYvz>u;sd)v~y;5PB#pnFQri9(TCC+v4HPk6k#FQj#?`x^H`cVTM{dLX_i zKK@TN7GKio={d$mdne)&SBn>-pN_Sz{pXTzmE2a+S`$J14YyM$r1$Y-g8e9yl9hS6 zk_&mrO8APbytTNUVjp6%IU;%1LRJm}DJDB&(Vjz)6UJq7a==SesS3p@%*JqLilca= zfVBLy@IP`l7TtSj!WYft<%GPlr#)BmS4iQj^4f}<^riA*Isgs0?mue4r4oa`5k9_2 zh-gpKqk$e-do|?tTg{?Njmd0U9g`cyuS{BNgyVnl+eG17EgI6|5d@#>XA$#lH;GS+ z6R|(!ir2&!*H&~a(4{@ZZhwf(7O#W6CPQBTRB}T}G3510B+lolVZ8ga)vw*! zCKR`1PYzk7E<^@(NnQTzl6rWWxx{Knf#2S&s?DzE z9KB3ddKpET{)Kw9t(_>>eYfp7KK4fa$i7w5Wbxq|T1%9a5oUqEAbnDEv|lJ>ccY{I zq~vJ7aiJD{N6SZqsW7;J+Qg&%W@o^eT0ZN}SoF3r>P#;0lgN|&gR*#^OrP8@|Dm6A z;_lNgER03(A2Y&R8-J78iMzwINauIKCc|`{4}h{-@|JbfNw9CGM`5rE&_Zw0pASxKmx7<{CWa@4Dg-=yc_WD1bh_m za|yT)@XiE04)`gJJNMYVYz!^hq!HyiBa?COZ*s)_eNC_;wD)S+{L_k%$GyBRlC76<~Nu@%sl&jSm9VK`oqyF!1e)d*37T?0cI=M9Xc%FRxQjo z!%yQ;%v`p_ashcPYS-VVV$tJ=pdSo(Cdd5pB&8;MQ`(~ucOR%e?Nj69C zck5LL0S?ek_))_xfBfZJxC!;S5V^*7-pRh(WZZdbGeU!Zvs?!%8gTEvU%viSb&~Jo zI_JMMfR0%7^oXU+h`YL_)8HG6uzrYz*L_ipwt0AeD?myEH%@~RGq`aY+_1pUz+j6# z71FoNKfcZjEAV*jZyia#9W~JHg5Db9*ipT@wimA~)UmpnopcGlAa0zksibmvcKyfY z6!(e!EvEHnFso`)cij4pMUN$X`j8Xa8g*%K(6_iOEPw=fY=neA=Q{WlwE66JXEh4( zO#JSQy97S2HsCjG4e$pw;Fk)3FpCD#v)-*}ZuhW8+`}K?HnEZPtm#>ALzxX_Hk8>C zWmpYl{TX-V`ZJZ4SPg`IA0A336EJiSa1-$BIj}dO&32S+N12|ZY&*)DQPzwyJx5tH z${s`6V<^*els$&BohaLhvYi&DwaDSK>F9{_5O180Dj!>YRp87pB*Q@(!)TQY$uKzA z&S4GY&R_0>1mq`#@$T|+_R73NT2|hRcedCfAg{eIY{*AzrTcy=&7L@naEGS1E z!&Q(i%|-hs_yq2iY^|`7=9XWzYzMSsb!}EHJ@*6JTT9PI(w?qeeMeq-Hd1d58*ew- z=b}HS^o6O)-0Jt@wqvcf`gx^@&qNt)-%7ld!vh^~Ge0uE-SIc&Kf!+tKf+D=x`lt29LBG3 z5DtWwdP*9b%nqBI)N)C*bh5$xVM>tN2=mQROOmAz8MWYRWrecOV{Si&h!(^^A)X!) zE^Pv0&r{keaW9XLGauuWz%skEEsMR6x7~)ep^I&E{!UxrVp}UBax484cnyE2t@&cx zZD?lzEaA!;VXo%zZ!&YQ@Qmn)ZNuw+KMlsd>g((_=l$nFK2G?2qW(6hr?DsWf&In%Qs%~CUSWvcT@#4iK0TynUx2Ryl#Mgqt zd5adZvyzLu=JOx_*lfNHcM$CSs7m%JndIsrHqz93zk=l@0*PkLb zbrVu2(o0C~NY5hu80jITcaT^+EIR$K7Ia*X_r_hYUs%k^690YQS%24q58O#+c`BBy zESYtc2LYv3OII#ivV0bLV7=;p?V0!uYZm;d#7*E&wbda_)bWWnccY$x7Nh{`89XsA zyE9VCk!xoX^D-xXAB*%3k{4~>13gKcmvH!jSV5A2P8>kPO#BYSFq0B0%;Y%3Oe3Kt z!)6|j%1HtxTrxVE43u-TY!k~!I+6``M>@4&B%FomOTG!D91kJ{K1oQ-kX)SeRVCi4 z0^*uqP`F^>HH(U_UE=YUEER!;kax1d*J;Fj6=HwboaaI}SYq?J9(e${8y^>$i%B#1 z?rQ%%#DB+KcLFA4*Bk;uUdA7|GE>v^LPB0lhHI7B*jK!cST0P|fz(8+i8^wzpI%XU z%a{EsZ~1Cnyl(=h@U=Rg)q4~XJ_*?PuU!(t2AKEetfTSCnB;L^{K YS0aA_d3-Hh%ydR9fG)81fA8=A0-t$e#Q*>R literal 0 HcmV?d00001 diff --git a/Tools/bootloaders/Airvolute-DCS2_bl.hex b/Tools/bootloaders/Airvolute-DCS2_bl.hex new file mode 100644 index 00000000000000..2a7d8442644c08 --- /dev/null +++ b/Tools/bootloaders/Airvolute-DCS2_bl.hex @@ -0,0 +1,1111 @@ +:020000040800F2 +:1000000000060020E1020008E3020008E302000805 +:10001000E3020008E3020008E3020008E30200082C +:10002000E3020008E3020008E3020008053B0008C1 +:10003000E3020008E3020008E3020008E30200080C +:10004000E3020008E3020008E3020008E3020008FC +:10005000E3020008E3020008ED3E0008193F000833 +:10006000453F0008713F00089D3F0008E30200087B +:10007000E3020008E3020008E3020008E3020008CC +:10008000E3020008E3020008E3020008E3020008BC +:10009000E3020008E3020008E3020008C93F000889 +:1000A000E3020008E3020008E3020008E30200089C +:1000B000E3020008E3020008E3020008E30200088C +:1000C000E3020008E3020008E3020008E30200087C +:1000D000E3020008A1400008E3020008E302000870 +:1000E0002D400008E3020008E3020008E3020008D4 +:1000F000E3020008E3020008E3020008E30200084C +:10010000E3020008E3020008B5400008E30200082B +:10011000E3020008E3020008E3020008E30200082B +:10012000E3020008E3020008E3020008E30200081B +:10013000E3020008E3020008E3020008E30200080B +:10014000E3020008E3020008E3020008E3020008FB +:10015000E3020008E3020008E3020008E3020008EB +:10016000E3020008E3020008E3020008E3020008DB +:10017000E302000885340008E3020008E3020008F7 +:10018000E3020008E3020008E3020008E3020008BB +:10019000E3020008E3020008E3020008E3020008AB +:1001A000E3020008E3020008E3020008E30200089B +:1001B000E3020008E3020008E3020008E30200088B +:1001C000E3020008E3020008E3020008E30200087B +:1001D000E302000871340008E3020008E3020008AB +:1001E000E3020008E3020008E3020008E30200085B +:1001F000E3020008E3020008E3020008E30200084B +:10020000E3020008E3020008E3020008E30200083A +:10021000E3020008E3020008E3020008E30200082A +:10022000E3020008E3020008E3020008E30200081A +:10023000E3020008E3020008E3020008E30200080A +:10024000E3020008E3020008E3020008E3020008FA +:10025000E3020008E3020008E3020008E3020008EA +:10026000E3020008E3020008E3020008E3020008DA +:10027000E3020008E3020008E3020008E3020008CA +:10028000E3020008E3020008E3020008E3020008BA +:10029000E3020008E3020008E3020008E3020008AA +:1002A000E3020008E3020008E3020008E30200089A +:1002B000E3020008E3020008E3020008E30200088A +:1002C000E3020008E3020008E3020008E30200087A +:1002D000E3020008E3020008E3020008E30200086A +:1002E00002E000F000F8FEE772B6374880F30888B5 +:1002F000364880F3098836483649086040F20000E5 +:10030000CCF200004EF63471CEF200010860BFF36B +:100310004F8FBFF36F8F40F20000C0F2F0004EF637 +:100320008851CEF200010860BFF34F8FBFF36F8F8B +:100330004FF00000E1EE100A4EF63C71CEF20001E3 +:100340000860062080F31488BFF36F8F02F006FB6D +:1003500003F02AFB4FF055301F491B4A91423CBF26 +:1003600041F8040BFAE71D49184A91423CBF41F895 +:10037000040BFAE71A491B4A1B4B9A423EBF51F83D +:10038000040B42F8040BF8E700201849184A914280 +:100390003CBF41F8040BFAE702F01EFB03F088FBB8 +:1003A000144C154DAC4203DA54F8041B8847F9E7A6 +:1003B00000F042F8114C124DAC4203DA54F8041B21 +:1003C0008847F9E702F006BB000600200022002063 +:1003D0000000000808ED00E00000002000060020FA +:1003E000E04400080022002064220020682200204F +:1003F000C4470020E0020008E0020008E002000814 +:10040000E00200082DE9F04F2DED108AC1F80CD064 +:10041000D0F80CD0BDEC108ABDE8F08F002383F338 +:1004200011882846A047002001F01EFEFEE701F0DB +:10043000ADFD00DFFEE7000038B500F0DBFB02F0A9 +:100440004DFA054602F080FA0446D0B90F4B9D42A2 +:1004500019D001339D4241F2883512BF0446002570 +:100460000124002002F044FA0CB100F077F800F00B +:1004700089FD00F03BFC284600F01EF900F06EF804 +:10048000F9E70025EDE70546EBE700BF010007B0FF +:1004900008B500F0F7FBA0F120035842584108BD11 +:1004A00007B541F21203022101A8ADF8043000F0B3 +:1004B00007FC03B05DF804FB38B5302383F31188E3 +:1004C000174803680BB101F09BFE0023154A4FF457 +:1004D0007A71134801F08AFE002383F31188124CCD +:1004E000236813B12368013B2360636813B1636819 +:1004F000013B63600D4D2B7833B963687BB90220F3 +:1005000000F0BAFC322363602B78032B07D16368B9 +:100510002BB9022000F0B0FC4FF47A73636038BD51 +:1005200068220020B90400088823002080220020CF +:10053000084B187003280CD8DFE800F00805020803 +:10054000022000F08FBC022000F084BC024B00228D +:100550005A6070478022002088230020F8B5504B55 +:10056000504A1C461968013100F0998004339342C7 +:10057000F8D162684C4B9A4240F291804B4B9B6899 +:1005800003F1006303F500339A4280F08880002075 +:1005900000F0D2FB0220FFF7CBFF454B0021D3F840 +:1005A000E820C3F8E810D3F81021C3F81011D3F8ED +:1005B0001021D3F8EC20C3F8EC10D3F81421C3F8C1 +:1005C0001411D3F81421D3F8F020C3F8F010D3F8A5 +:1005D0001821C3F81811D3F81821D3F8802042F05D +:1005E0000062C3F88020D3F8802022F00062C3F8B4 +:1005F0008020D3F88020D3F8802042F00072C3F826 +:100600008020D3F8802022F00072C3F88020D3F835 +:10061000803072B64FF0E023C3F8084DD4E90004EF +:10062000BFF34F8FBFF36F8F224AC2F88410BFF31E +:100630004F8F536923F480335361BFF34F8FD2F848 +:10064000803043F6E076C3F3C905C3F34E335B0154 +:1006500003EA060C29464CEA81770139C2F8747224 +:10066000F9D2203B13F1200FF2D1BFF34F8FBFF32C +:100670006F8FBFF34F8FBFF36F8F536923F4003336 +:1006800053610023C2F85032BFF34F8FBFF36F8F17 +:10069000302383F31188854680F308882047F8BD0E +:1006A0000000020820000208FFFF010800220020CD +:1006B0000044025800ED00E02DE9F04F93B0B44B38 +:1006C0002022FF2100900AA89D6800F005FCB14A95 +:1006D0001378A3B90121B04811700360302383F36C +:1006E000118803680BB101F08BFD0023AB4A4FF476 +:1006F0007A71A94801F07AFD002383F31188009BE9 +:1007000013B1A74B009A1A60A64A1378032B03D0A3 +:1007100000231370A24A53604FF0000A009CD34696 +:100720005646D146012000F09DFB24B19C4B1B682E +:10073000002B00F02682002000F0A4FA0390039B17 +:10074000002BF2DB012000F085FB039B213B1F2BDC +:10075000E8D801A252F823F0D907000801080008E0 +:100760009508000825070008250700082507000848 +:1007700027090008F70A0008110A0008730A000890 +:100780009B0A0008C10A000825070008D30A0008D0 +:1007900025070008450B0008790800082507000810 +:1007A000890B0008E50700087908000825070008FC +:1007B000730A000825070008250700082507000818 +:1007C0002507000825070008250700082507000859 +:1007D00025070008950800080220FFF759FE0028A9 +:1007E00040F0F981009B022105A8BAF1000F08BF73 +:1007F0001C4641F21233ADF8143000F061FA91E773 +:100800004FF47A7000F03EFA071EEBDB0220FFF790 +:100810003FFE0028E6D0013F052F00F2DE81DFE831 +:1008200007F0030A0D1013360523042105A80593CC +:1008300000F046FA17E004215548F9E704215A4828 +:10084000F6E704215948F3E74FF01C08404608F149 +:10085000040800F073FA0421059005A800F030FAAE +:10086000B8F12C0FF2D101204FF0000900FA07F780 +:1008700047EA0B0B5FFA8BFB00F07AFB26B10BF01B +:100880000B030B2B08BF0024FFF70AFE4AE70421E5 +:100890004748CDE7002EA5D00BF00B030B2BA1D1C1 +:1008A0000220FFF7F5FD074600289BD00120002617 +:1008B00000F042FA0220FFF73BFE1FFA86F840469E +:1008C00000F04AFA0446B0B1039940460136A1F15E +:1008D00040025142514100F04FFA0028EDD1BA4692 +:1008E000044641F21213022105A83E46ADF8143029 +:1008F00000F0E6F916E725460120FFF719FE244B24 +:100900009B68AB4207D9284600F018FA013040F046 +:1009100067810435F3E70025224BBA463E461D7039 +:100920001F4B5D60A8E7002E3FF45CAF0BF00B039C +:100930000B2B7FF457AF0220FFF7FAFD322000F0B7 +:10094000A1F9B0F10008FFF64DAF18F003077FF4EE +:1009500049AF0F4A08EB0503926893423FF642AF56 +:10096000B8F5807F3FF73EAF124BB845019323DDCA +:100970004FF47A7000F086F90390039A002AFFF68C +:1009800031AF039A0137019B03F8012BEDE700BF5C +:10099000002200208423002068220020B9040008DF +:1009A000882300208022002004220020082200202A +:1009B0000C22002084220020C820FFF769FD074692 +:1009C00000283FF40FAF1F2D11D8C5F120020AAB4C +:1009D00025F0030084494245184428BF424601924D +:1009E00000F054FA019AFF217F4800F075FA4FEAAF +:1009F000A803C8F387027C492846019300F074FAE3 +:100A0000064600283FF46DAF019B05EB830533E7F5 +:100A10000220FFF73DFD00283FF4E4AE00F0CAF9E4 +:100A200000283FF4DFAE0027B846704B9B68BB42FE +:100A300018D91F2F11D80A9B01330ED027F00303BA +:100A400012AA134453F8203C05934046042205A9FA +:100A5000043700F0F9FA8046E7E7384600F06EF90F +:100A60000590F2E7CDF81480042105A800F028F9DC +:100A700002E70023642104A8049300F017F900287A +:100A80007FF4B0AE0220FFF703FD00283FF4AAAECA +:100A9000049800F085F90590E6E70023642104A896 +:100AA000049300F003F900287FF49CAE0220FFF7C6 +:100AB000EFFC00283FF496AE049800F073F9EAE7E3 +:100AC0000220FFF7E5FC00283FF48CAE00F082F92D +:100AD000E1E70220FFF7DCFC00283FF483AE05A924 +:100AE000142000F07DF907460421049004A800F0CA +:100AF000E7F83946B9E7322000F0C4F8071EFFF6E0 +:100B000071AEBB077FF46EAE384A07EB09039268FB +:100B100093423FF667AE0220FFF7BAFC00283FF48D +:100B200061AE27F003074F44B9453FF4A5AE4846F0 +:100B300009F1040900F002F90421059005A800F06C +:100B4000BFF8F1E74FF47A70FFF7A2FC00283FF4FA +:100B500049AE00F02FF9002844D00A9B01330BD096 +:100B600008220AA9002000F0BFF900283AD020226C +:100B7000FF210AA800F0B0F9FFF792FC1C4801F031 +:100B800079FA13B0BDE8F08F002E3FF42BAE0BF0D6 +:100B90000B030B2B7FF426AE0023642105A80593DD +:100BA00000F084F8074600287FF41CAE0220FFF70F +:100BB0006FFC804600283FF415AEFFF771FC41F250 +:100BC000883001F057FA059800F01CFA46463C467A +:100BD00000F0CEF9A6E506464EE64FF0000901E624 +:100BE000BA467EE637467CE68422002000220020BA +:100BF000A0860100704700002DE9F84F4FF47A738A +:100C000006460D46002402FB03F7DFF85080DFF8AC +:100C1000509098F900305FFA84FA5A1C01D0A34230 +:100C200012D159F824002A4631460368D3F820B07F +:100C30003B46D847854207D1074B012083F800A0E7 +:100C4000BDE8F88F0124E4E7002CFBD04FF4FA70E4 +:100C500001F010FA0020F3E7D42300201022002036 +:100C60001422002070B504464FF47A76412C2546B4 +:100C700028BF412506FB05F001F0FCF9641BF5D106 +:100C800070BD0000002307B5024601210DF10700E9 +:100C90008DF80730FFF7B0FF20B19DF8070003B0D3 +:100CA0005DF804FB4FF0FF30F9E700000A4604212D +:100CB00008B5FFF7A1FF80F00100C0B2404208BDB7 +:100CC000074B0A4630B41978064B53F821400146C9 +:100CD00023682046DD69044BAC4630BC604700BF4A +:100CE000D423002014220020A086010070B5104CEF +:100CF0000025104E01F0DAFC208030682388834202 +:100D00000CD800252088013801F0CCFC238805444C +:100D1000013BB5F5802F2380F4D370BD01F0C2FCF8 +:100D2000336805440133B5F5003F3360E5D3E8E7A8 +:100D3000D62300209023002001F086BD00F1006042 +:100D400000F500300068704700F10060920000F587 +:100D5000003001F007BD0000054B1A68054B1B88E9 +:100D60009B1A834202D9104401F09CBC00207047BA +:100D700090230020D623002038B50446074D29B122 +:100D800028682044BDE8384001F0A4BC286820440D +:100D900001F08EFC0028F3D038BD00BF9023002066 +:100DA0000020704700F1FF5000F58F10D0F80008C8 +:100DB00070470000064991F8243033B1002308221F +:100DC000086A81F82430FFF7BFBF0120704700BFD9 +:100DD00094230020014B1868704700BF0010005C8E +:100DE000194B01380322084470B51D68174BC5F331 +:100DF0000B042D0C1E88A6420BD15C680A46013CF0 +:100E0000824213460FD214F9016F4EB102F8016B02 +:100E1000F6E7013A03F10803ECD181420B4602D216 +:100E20002C2203F8012B0424094A1688AE4204D16F +:100E3000984284BF967803F8016B013C02F10402EA +:100E4000F3D1581A70BD00BF0010005C1C220020B6 +:100E5000B8410008022801D1014B9861704700BFDA +:100E600000040258022803D1024B4FF400329A6169 +:100E7000704700BF00040258022804D1024A536997 +:100E800083F002035361704700040258002310B539 +:100E9000934203D0CC5CC4540133F9E710BD000089 +:100EA000013810B510F9013F3BB191F900409C4267 +:100EB00003D11AB10131013AF4E71AB191F90020D6 +:100EC000981A10BD1046FCE703460246D01A12F9E4 +:100ED000011B0029FAD1704702440346934202D015 +:100EE00003F8011BFAE770472DE9F8431F4D14463C +:100EF0000746884695F8242052BBDFF870909CB3D3 +:100F000095F824302BB92022FF2148462F62FFF7A5 +:100F1000E3FF95F824004146C0F1080205EB80008C +:100F2000A24228BF2246D6B29200FFF7AFFF95F843 +:100F30002430A41B17441E449044E4B2F6B2082E99 +:100F400085F82460DBD1FFF735FF0028D7D108E012 +:100F50002B6A03EB82038342CFD0FFF72BFF0028DD +:100F6000CBD10020BDE8F8830120FBE794230020CB +:100F7000024B1A78024B1A70704700BFD42300202E +:100F80001022002038B51A4C1A4D204600F0C6FB3E +:100F90002946204600F0EEFB2D684FF47A70D5F814 +:100FA0009020D2F8043843F00203C2F80438FFF767 +:100FB00059FE1149284600F0EBFCD5F890200F4D62 +:100FC000D2F80438286823F002030D49A042C2F881 +:100FD00004384FF4E1330B6001D000F0FDFA68688B +:100FE000A04204D00649BDE8384000F0F5BA38BD4B +:100FF000B82A0020B4420008BC4200081422002095 +:10100000BC2300200C4B70B50C4D04461E780C4BD5 +:1010100055F826209A420DD00A4B00211822184676 +:10102000FFF75AFF0460014655F82600BDE87040FE +:1010300000F0D2BA70BD00BFD423002014220020DB +:10104000B82A0020BC23002030B50A44084D914244 +:101050000DD011F8013B5840082340F30004013B38 +:101060002C4013F0FF0384EA5000F6D1EFE730BDC7 +:101070002083B8ED026843681143016003B118474B +:1010800070470000024A136843F0C00313607047C2 +:101090000010014013B50E4C204600F091FA04F107 +:1010A000140000234FF400720A49009400F04EF936 +:1010B000094B4FF40072094904F13800009400F024 +:1010C000C7F9074A074BC4E9172302B010BD00BF98 +:1010D000D823002044240020851000084426002046 +:1010E0000010014000E1F505037C30B5244C0029D7 +:1010F00018BF0C46012B11D1224B98420ED1224B26 +:10110000D3F8F02042F01002C3F8F020D3F81821F1 +:1011100042F01002C3F81821D3F818312268036E88 +:10112000C16D03EB52038466B3FBF2F362681504EE +:1011300042BF23F0070503F0070343EA4503CB60F2 +:10114000A36843F040034B60E36843F001038B6006 +:1011500042F4967343F001030B604FF0FF330B62D0 +:10116000510505D512F0102205D0B2F1805F04D0F0 +:1011700080F8643030BD7F23FAE73F23F8E700BFF3 +:10118000C8410008D8230020004402582DE9F04748 +:10119000C66D05463768F469210734621AD014F029 +:1011A000080118BF4FF48071E20748BF41F02001E9 +:1011B000A3074FF0300348BF41F04001600748BF2C +:1011C00041F0800183F31188281DFFF753FF0023AE +:1011D00083F31188E2050AD5302383F311884FF495 +:1011E0008061281DFFF746FF002383F311884FF02D +:1011F00030094FF0000A14F0200838D13B0616D50C +:101200004FF0300905F1380A200610D589F311880E +:10121000504600F051F9002836DA0821281DFFF762 +:1012200029FF27F080033360002383F311887906B8 +:1012300014D5620612D5302383F31188D5E9132320 +:101240009A4208D12B6C33B127F040071021281D9A +:10125000FFF710FF3760002383F31188E30618D5EA +:10126000AA6E1369ABB15069BDE8F047184789F31E +:101270001188736A284695F86410194000F0BAF98D +:101280008AF31188F469B6E7B06288F31188F469CB +:10129000BAE7BDE8F0870000F8B515468268044655 +:1012A0000B46AA4200D28568A1692669761AB54222 +:1012B0000BD218462A46FFF7E9FDA3692B44A36128 +:1012C0002846A3685B1BA360F8BD0CD9AF1B18466A +:1012D0003246FFF7DBFD3A46E1683044FFF7D6FDC2 +:1012E000E3683B44EBE718462A46FFF7CFFDE36887 +:1012F000E5E7000083689342F7B50446154600D23F +:101300008568D4E90460361AB5420BD22A46FFF745 +:10131000BDFD63692B4463612846A3685B1BA36022 +:1013200003B0F0BD0DD93246AF1B0191FFF7AEFD02 +:1013300001993A46E0683144FFF7A8FDE3683B4471 +:10134000E9E72A46FFF7A2FDE368E4E710B50A449F +:101350000024C361029B8460C16002610362C0E932 +:101360000000C0E9051110BD08B5D0E9053293426F +:1013700001D1826882B98268013282605A1C42615E +:1013800019700021D0E904329A4224BFC368436136 +:1013900000F08CFE002008BD4FF0FF30FBE700009E +:1013A00070B5302304460E4683F31188A568A5B1B5 +:1013B000A368A269013BA360531CA361157822694D +:1013C000934224BFE368A361E3690BB120469847C9 +:1013D000002383F31188284607E03146204600F0B9 +:1013E00055FE0028E2DA85F3118870BD2DE9F74F2C +:1013F00004460E4617469846D0F81C904FF0300A27 +:101400008AF311884FF0000B154665B12A46314624 +:101410002046FFF741FF034660B94146204600F0F1 +:1014200035FE0028F1D0002383F31188781B03B028 +:10143000BDE8F08FB9F1000F03D001902046C847F6 +:10144000019B8BF31188ED1A1E448AF31188DCE7A7 +:10145000C160C361009B82600362C0E90511114451 +:10146000C0E9000001617047F8B504460D46164614 +:10147000302383F31188A768A7B1A368013BA36059 +:1014800063695A1C62611D70D4E904329A4224BF18 +:10149000E3686361E3690BB120469847002080F35D +:1014A000118807E03146204600F0F0FD0028E2DA1E +:1014B00087F31188F8BD0000D0E9052310B59A42E2 +:1014C00001D182687AB982680021013282605A1C97 +:1014D00082611C7803699A4224BFC368836100F06B +:1014E000E5FD204610BD4FF0FF30FBE72DE9F74F3B +:1014F00004460E4617469846D0F81C904FF0300A26 +:101500008AF311884FF0000B154665B12A46314623 +:101510002046FFF7EFFE034660B94146204600F043 +:10152000B5FD0028F1D0002383F31188781B03B0A8 +:10153000BDE8F08FB9F1000F03D001902046C847F5 +:10154000019B8BF31188ED1A1E448AF31188DCE7A6 +:10155000026843681143016003B1184770470000F7 +:101560001430FFF743BF00004FF0FF331430FFF794 +:101570003DBF00003830FFF7B9BF00004FF0FF3328 +:101580003830FFF7B3BF00001430FFF709BF000089 +:101590004FF0FF311430FFF703BF00003830FFF782 +:1015A00063BF00004FF0FF323830FFF75DBF00002F +:1015B000012914BF6FF0130000207047FFF76ABDC8 +:1015C000044B036000234360C0E90233012303742A +:1015D000704700BFE041000810B53023044683F394 +:1015E0001188FFF781FD02230020237480F3118806 +:1015F00010BD000038B5C36904460D461BB904216F +:101600000844FFF7A5FF294604F11400FFF7ACFEDC +:10161000002806DA201D4FF40061BDE83840FFF7CE +:1016200097BF38BD026843681143016003B1184792 +:101630007047000013B5406B00F58054D4F8A4380F +:101640001A681178042914D1017C022911D1197961 +:10165000012312898B4013420BD101A94C3002F0B7 +:1016600059F8D4F8A4480246019B2179206800F07B +:10167000DFF902B010BD0000143001F0DBBF000044 +:101680004FF0FF33143001F0D5BF00004C3002F0B2 +:10169000ADB800004FF0FF334C3002F0A7B80000A7 +:1016A000143001F0A9BF00004FF0FF31143001F0F9 +:1016B000A3BF00004C3002F079B800004FF0FF32B9 +:1016C0004C3002F073B800000020704710B500F5F0 +:1016D0008054D4F8A4381A681178042917D1017CF1 +:1016E000022914D15979012352898B4013420ED11A +:1016F000143001F03BFF024648B1D4F8A4484FF43F +:10170000407361792068BDE8104000F07FB910BDDA +:10171000406BFFF7DBBF0000704700007FB5124B46 +:1017200001250426044603600023057400F18402A9 +:1017300043602946C0E902330C4B029014300193F8 +:101740004FF44073009601F0EDFE094B04F694420D +:10175000294604F14C000294CDE900634FF4407334 +:1017600001F0B4FF04B070BD084200081117000872 +:10177000351600080A68302383F311880B790B3380 +:1017800042F823004B79133342F823008B7913B1CD +:101790000B3342F8230000F58053C3F8A41802234A +:1017A0000374002080F311887047000038B5037F70 +:1017B000044613B190F85430ABB90125201D022125 +:1017C000FFF730FF04F114006FF00101257700F0FE +:1017D00079FC04F14C0084F854506FF00101BDE82D +:1017E000384000F06FBC38BD10B50121044604300C +:1017F000FFF718FF0023237784F8543010BD000052 +:1018000038B504460025143001F0A4FE04F14C0064 +:10181000257701F073FF201D84F854500121FFF754 +:1018200001FF2046BDE83840FFF750BF90F88030F8 +:1018300003F06003202B06D190F881200023212A99 +:1018400003D81F2A06D800207047222AFBD1C0E9FE +:101850001D3303E0034A426707228267C367012002 +:10186000704700BF3422002037B500F58055D5F809 +:10187000A4381A68117804291AD1017C022917D1D9 +:101880001979012312898B40134211D100F14C04C4 +:10189000204601F0F3FF58B101A9204601F03AFFBC +:1018A000D5F8A4480246019B2179206800F0C0F8D1 +:1018B00003B030BD01F10B03F0B550F8236085B0E3 +:1018C00004460D46FEB1302383F3118804EB8507EF +:1018D000301D0821FFF7A6FEFB6806F14C005B698E +:1018E0001B681BB1019001F023FF019803A901F0CF +:1018F00011FF024648B1039B2946204600F098F8A4 +:10190000002383F3118805B0F0BDFB685A691268A3 +:10191000002AF5D01B8A013B1340F1D104F180026B +:10192000EAE70000133138B550F82140ECB130231C +:1019300083F3118804F58053D3F8A42813685279EF +:1019400003EB8203DB689B695D6845B10421601885 +:10195000FFF768FE294604F1140001F011FE20464D +:10196000FFF7B4FE002383F3118838BD70470000F1 +:1019700001F0C8B801234022002110B5044600F848 +:10198000303BFFF7A9FA0023C4E9013310BD000082 +:1019900010B53023044683F31188242241600021CE +:1019A0000C30FFF799FA204601F0CEF80223002010 +:1019B000237080F3118810BD70B500EB81030546DC +:1019C00050690E461446DA6018B110220021FFF764 +:1019D00083FAA06918B110220021FFF77DFA314681 +:1019E0002846BDE8704001F0B5B9000083682022A8 +:1019F000002103F0011310B5044683601030FFF797 +:101A00006BFA2046BDE8104001F030BAF0B4012571 +:101A100000EB810447898D40E4683D43A46945811A +:101A200023600023A2606360F0BC01F04DBA0000A7 +:101A3000F0B4012500EB810407898D40E4683D4343 +:101A40006469058123600023A2606360F0BC01F03B +:101A5000C3BA000070B50223002504462422037097 +:101A60002946C0F888500C3040F8045CFFF734FA7F +:101A7000204684F8705001F001F963681B6823B1B7 +:101A800029462046BDE87040184770BD0378052BF5 +:101A900010B504460AD080F88C30052303704368E3 +:101AA0001B680BB1042198470023A36010BD000000 +:101AB0000178052906D190F88C20436802701B68D4 +:101AC00003B118477047000070B590F870300446B5 +:101AD00013B1002380F8703004F18002204601F039 +:101AE000E9F963689B68B3B994F8803013F0600536 +:101AF00035D00021204601F0DBFC0021204601F01A +:101B0000CBFC63681B6813B1062120469847062367 +:101B100084F8703070BD204698470028E4D0B4F8AF +:101B20008630A26F9A4288BFA36794F98030A56F70 +:101B3000002B4FF0300380F20381002D00F0F28083 +:101B4000092284F8702083F3118800212046D4E90B +:101B50001D23FFF76DFF002383F31188DAE794F864 +:101B6000812003F07F0343EA022340F202329342D2 +:101B700000F0C58021D8B3F5807F48D00DD8012B67 +:101B80003FD0022B00F09380002BB2D104F18802E9 +:101B900062670222A267E367C1E7B3F5817F00F0C5 +:101BA0009B80B3F5407FA4D194F88230012BA0D163 +:101BB000B4F8883043F0020332E0B3F5006F4DD043 +:101BC00017D8B3F5A06F31D0A3F5C063012B90D81F +:101BD0006368204694F882205E6894F88310B4F815 +:101BE0008430B047002884D0436863670368A367E4 +:101BF0001AE0B3F5106F36D040F6024293427FF4FC +:101C000078AF5C4B63670223A3670023C3E794F8B4 +:101C10008230012B7FF46DAFB4F8883023F00203DB +:101C2000A4F88830C4E91D55E56778E7B4F880303A +:101C3000B3F5A06F0ED194F88230204684F88A3034 +:101C400001F07AF863681B6813B1012120469847B8 +:101C5000032323700023C4E91D339CE704F18B03A5 +:101C600063670123C3E72378042B10D1302383F368 +:101C700011882046FFF7BAFE85F3118803216368B7 +:101C800084F88B5021701B680BB12046984794F85C +:101C90008230002BDED084F88B30042323706368FD +:101CA0001B68002BD6D0022120469847D2E794F833 +:101CB000843020461D0603F00F010AD501F0ECF830 +:101CC000012804D002287FF414AF2B4B9AE72B4B4A +:101CD00098E701F0D3F8F3E794F88230002B7FF413 +:101CE00008AF94F8843013F00F01B3D01A062046E1 +:101CF00002D501F0F5FBADE701F0E6FBAAE794F8A9 +:101D00008230002B7FF4F5AE94F8843013F00F018D +:101D1000A0D01B06204602D501F0CAFB9AE701F0CD +:101D2000BBFB97E7142284F8702083F311882B46BD +:101D30002A4629462046FFF769FE85F31188E9E621 +:101D40005DB1152284F8702083F3118800212046AC +:101D5000D4E91D23FFF75AFEFDE60B2284F870201C +:101D600083F311882B462A4629462046FFF760FE5A +:101D7000E3E700BF38420008304200083442000860 +:101D800038B590F870300446002B3ED0063BDAB2EE +:101D90000F2A34D80F2B32D8DFE803F0373131085F +:101DA000223231313131313131313737856FB0F84D +:101DB00086309D4214D2C3681B8AB5FBF3F203FB45 +:101DC00012556DB9302383F311882B462A462946D4 +:101DD000FFF72EFE85F311880A2384F870300EE099 +:101DE000142384F87030302383F3118800232046B5 +:101DF0001A461946FFF70AFE002383F3118838BDFF +:101E0000C36F03B198470023E7E70021204601F0A4 +:101E10004FFB0021204601F03FFB63681B6813B1B4 +:101E20000621204698470623D7E7000010B590F812 +:101E300070300446142B29D017D8062B05D001D8B2 +:101E40001BB110BD093B022BFBD80021204601F03D +:101E50002FFB0021204601F01FFB63681B6813B1B4 +:101E6000062120469847062319E0152BE9D10B23BC +:101E700080F87030302383F3118800231A46194606 +:101E8000FFF7D6FD002383F31188DAE7C3689B6967 +:101E90005B68002BD5D1C36F03B19847002384F84A +:101EA0007030CEE700238268037503691B68996868 +:101EB0009142FBD25A6803604260106058607047DC +:101EC00000238268037503691B6899689142FBD8F7 +:101ED0005A680360426010605860704708B5084651 +:101EE000302383F311880B7D032B05D0042B0DD0F9 +:101EF0002BB983F3118808BD8B6900221A604FF05B +:101F0000FF338361FFF7CEFF0023F2E7D1E9003210 +:101F100013605A60F3E70000FFF7C4BF054BD968B0 +:101F200008751868026853601A600122D86002754B +:101F3000FEF768BA482800200C4B30B5DD684B1C12 +:101F400087B004460FD02B46094A684600F04EF988 +:101F50002046FFF7E3FF009B13B1684600F050F9FD +:101F6000A86907B030BDFFF7D9FFF9E7482800207E +:101F7000DD1E0008044B1A68DB6890689B68984275 +:101F800094BF00200120704748280020084B10B55E +:101F90001C68D868226853601A600122DC602275D0 +:101FA000FFF78EFF01462046BDE81040FEF72ABA33 +:101FB0004828002038B5074C01230025064907486A +:101FC0002370656001F098FC0223237085F311886B +:101FD00038BD00BFB02A0020404200084828002039 +:101FE00000F044B9034A516853685B1A9842FBD821 +:101FF000704700BF001000E08B60022308610846B4 +:102000008B8270478368A3F1840243F8142C026921 +:1020100043F8442C426943F8402C094A43F8242CE5 +:10202000C268A3F1200043F8182C022203F80C2CFC +:10203000002203F80B2C034A43F8102C704700BF12 +:102040001D0400084828002008B5FFF7DBFFBDE8A5 +:102050000840FFF761BF0000024BDB6898610F206A +:10206000FFF75CBF48280020302383F31188FFF777 +:10207000F3BF000008B50146302383F31188082020 +:10208000FFF75AFF002383F3118808BD064BDB6876 +:1020900039B1426818605A60136043600420FFF74A +:1020A0004BBF4FF0FF30704748280020036898422C +:1020B00006D01A680260506018469961FFF72CBF7D +:1020C0007047000038B504460D462068844200D1B0 +:1020D00038BD036823605C608561FFF71DFFF4E78E +:1020E000036810B59C68A2420CD85C688A600B60DB +:1020F0004C602160596099688A1A9A604FF0FF33EA +:10210000836010BD121B1B68ECE700000A2938BF72 +:102110000A2170B504460D460A26601901F0E4FB59 +:1021200001F0CCFB041BA54203D8751C04462E46C7 +:10213000F3E70A2E04D90120BDE8704001F01CBC71 +:1021400070BD0000F8B5144B0D460A2A4FF00A077F +:10215000D96103F11001826038BF0A224160196918 +:102160001446016048601861A81801F0ADFB01F049 +:10217000A5FB431B0646A34206D37C1C2819274611 +:10218000354601F0B1FBF2E70A2F04D90120BDE882 +:10219000F84001F0F1BBF8BD48280020F8B506462C +:1021A0000D4601F08BFB0F4A134653F8107F9F42F8 +:1021B00006D12A4601463046BDE8F840FFF7C2BFC7 +:1021C000D169BB68441A2C1928BF2C46A34202D9F6 +:1021D0002946FFF79BFF224631460348BDE8F840F9 +:1021E000FFF77EBF4828002058280020C0E90323BD +:1021F000002310B45DF8044B4361FFF7CFBF00002C +:1022000010B5194C236998420DD08168D0E900328D +:1022100013605A609A680A449A60002303604FF082 +:10222000FF33A36110BD0268234643F8102F5360AB +:102230000022026022699A4203D1BDE8104001F0F9 +:102240004DBB936881680B44936001F037FB2269B2 +:10225000E1699268441AA242E4D91144BDE81040F1 +:10226000091AFFF753BF00BF482800202DE9F047A7 +:10227000DFF8BC8008F110072C4ED8F8105001F0A0 +:102280001DFBD8F81C40AA68031B9A423ED8144490 +:102290004FF00009D5E90032C8F81C4013605A60BD +:1022A000C5F80090D8F81030B34201D101F016FB08 +:1022B00089F31188D5E9033128469847302383F301 +:1022C00011886B69002BD8D001F0F8FA6A69A0EB8D +:1022D000040982464A450DD2022001F04DFB00223E +:1022E000D8F81030B34208D151462846BDE8F0472F +:1022F000FFF728BF121A2244F2E712EB0909294618 +:10230000384638BF4A46FFF7EBFEB5E7D8F810303D +:10231000B34208D01444C8F81C00211AA960BDE8D3 +:10232000F047FFF7F3BEBDE8F08700BF5828002054 +:102330004828002000207047FEE70000704700009A +:102340004FF0FF307047000002290CD0032904D061 +:102350000129074818BF00207047032A05D80548FF +:1023600000EBC2007047044870470020704700BF70 +:102370001843000844220020CC42000870B59AB0EF +:1023800005460846144601A900F0C2F801A8FEF768 +:102390009BFD431C0022C6B25B001046C5E9003419 +:1023A00023700323023404F8013C01ABD1B20234A0 +:1023B0008E4201D81AB070BD13F8011B013204F827 +:1023C000010C04F8021CF1E708B5302383F31188EF +:1023D0000348FFF749FA002383F3118808BD00BFC3 +:1023E000B82A002090F8803003F01F02012A07D19C +:1023F00090F881200B2A03D10023C0E91D3315E09A +:1024000003F06003202B08D1B0F884302BB990F88A +:102410008120212A03D81F2A04D8FFF707BA222ACD +:10242000EBD0FAE7034A426707228267C3670120BD +:10243000704700BF3B22002007B5052917D8DFE809 +:1024400001F0191603191920302383F31188104A5B +:1024500001210190FFF7B0FA019802210D4AFFF720 +:10246000ABFA0D48FFF7CCF9002383F3118803B0D2 +:102470005DF804FB302383F311880748FFF796F9D2 +:10248000F2E7302383F311880348FFF7ADF9EBE758 +:102490006C42000890420008B82A002038B50C4D64 +:1024A0000C4C2A460C4904F10800FFF767FF05F1C0 +:1024B000CA0204F110000949FFF760FF05F5CA726E +:1024C00004F118000649BDE83840FFF757BF00BFC8 +:1024D00090430020442200204C420008564200084D +:1024E0006142000870B5044608460D46FEF7ECFC54 +:1024F000C6B22046013403780BB9184670BD324687 +:102500002946FEF7CDFC0028F3D10120F6E70000B4 +:102510002DE9F04705460C46FEF7D6FC2B49C6B21E +:102520002846FFF7DFFF08B10736F6B228492846EC +:10253000FFF7D8FF08B11036F6B2632E0BD8DFF8DC +:102540008C80DFF88C90234FDFF894A02E7846B96A +:102550002670BDE8F08729462046BDE8F04701F027 +:102560000DBE252E2ED1072241462846FEF798FCA7 +:1025700070B9194B224603F10C0153F8040B8B423E +:1025800042F8040BF9D11B8807350E341380DDE7C0 +:10259000082249462846FEF783FC98B9A21C0F4B37 +:1025A000197802320909C95D02F8041C13F8011BED +:1025B00001F00F015345C95D02F8031CF0D1183436 +:1025C0000835C3E7013504F8016BBFE7384300085D +:1025D000614200084F4300084043000800E8F11F33 +:1025E0000CE8F11FBFF34F8F044B1A695107FCD160 +:1025F000D3F810215207F8D1704700BF00200052D5 +:1026000008B50D4B1B78ABB9FFF7ECFF0B4BDA6845 +:10261000D10704D50A4A5A6002F188325A60D3F8C9 +:102620000C21D20706D5064AC3F8042102F18832EC +:10263000C3F8042108BD00BFEE4500200020005271 +:102640002301674508B5114B1B78F3B9104B1A6984 +:10265000510703D5DA6842F04002DA60D3F810215E +:10266000520705D5D3F80C2142F04002C3F80C21E3 +:10267000FFF7B8FF064BDA6842F00102DA60D3F8E0 +:102680000C2142F00102C3F80C2108BDEE450020E8 +:10269000002000520F289ABF00F5806040040020FF +:1026A000704700004FF40030704700001020704762 +:1026B0000F2808B50BD8FFF7EDFF00F500330268CF +:1026C000013204D104308342F9D1012008BD002039 +:1026D000FCE700000F2838B505463FD8FFF782FF1A +:1026E0001F4CFFF78DFF4FF0FF3307286361C4F8DD +:1026F00014311DD82361FFF775FF030243F0240353 +:10270000E360E36843F08003E36023695A07FCD485 +:102710002846FFF767FFFFF7BDFF4FF4003100F0D9 +:10272000F5F82846FFF78EFFBDE83840FFF7C0BF39 +:10273000C4F81031FFF756FFA0F108031B0243F065 +:102740002403C4F80C31D4F80C3143F08003C4F8EE +:102750000C31D4F810315B07FBD4D9E7002038BD29 +:10276000002000522DE9F84F05460C46104645EA78 +:102770000203DE0602D00020BDE8F88F20F01F0023 +:10278000DFF8BCB0DFF8BCA0FFF73AFF04EB0008AD +:10279000444503D10120FFF755FFEDE720222946EC +:1027A000204601F0DBFC10B920352034F0E72B4641 +:1027B00005F120021F68791CDDD104339A42F9D15A +:1027C00005F178431B481C4EB3F5801F1B4B38BFE7 +:1027D000184603F1F80332BFD946D1461E46FFF72B +:1027E00001FF0760A5EB040C336804F11C0143F002 +:1027F00002033360231FD9F8007017F00507FAD1E0 +:1028000053F8042F8B424CF80320F4D1BFF34F8FC1 +:10281000FFF7E8FE4FF0FF332022214603602846F1 +:10282000336823F00203336001F098FC0028BBD02A +:102830003846B0E7142100520C20005214200052F8 +:10284000102000521021005210B5084C237828B1F6 +:102850001BB9FFF7D5FE0123237010BD002BFCD060 +:102860002070BDE81040FFF7EDBE00BFEE45002030 +:102870000244074BD2B210B5904200D110BD441CA7 +:1028800000B253F8200041F8040BE0B2F4E700BFB7 +:10289000504000580E4B30B51C6F240405D41C6FFB +:1028A0001C671C6F44F400441C670A4C02442368F4 +:1028B000D2B243F480732360074B904200D130BD05 +:1028C000441C51F8045B00B243F82050E0B2F4E736 +:1028D00000440258004802585040005807B50122F1 +:1028E00001A90020FFF7C4FF019803B05DF804FBC5 +:1028F00013B50446FFF7F2FFA04205D0012201A95B +:1029000000200194FFF7C6FF02B010BD0144BFF3E1 +:102910004F8F064B884204D3BFF34F8FBFF36F8FA7 +:102920007047C3F85C022030F4E700BF00ED00E020 +:10293000034B1A681AB9034AD2F8D0241A607047B8 +:10294000F04500200040025808B5FFF7F1FF024BA8 +:102950001868C0F3806008BDF045002070B5BFF373 +:102960004F8FBFF36F8F1A4A0021C2F85012BFF386 +:102970004F8FBFF36F8F536943F400335361BFF33D +:102980004F8FBFF36F8FC2F88410BFF34F8FD2F811 +:10299000803043F6E074C3F3C900C3F34E335B01E8 +:1029A00003EA0406014646EA81750139C2F860521D +:1029B000F9D2203B13F1200FF2D1BFF34F8F5369AF +:1029C00043F480335361BFF34F8FBFF36F8F70BDFC +:1029D00000ED00E0FEE70000214B2248224A70B5DE +:1029E000904237D3214BC11EDA1C121A22F0030287 +:1029F0008B4238BF00220021FEF76EFA1C4A0023EA +:102A0000C2F88430BFF34F8FD2F8803043F6E074C1 +:102A1000C3F3C900C3F34E335B0103EA0406014666 +:102A200046EA81750139C2F86C52F9D2203B13F1A4 +:102A3000200FF2D1BFF34F8FBFF36F8FBFF34F8FD4 +:102A4000BFF36F8F0023C2F85032BFF34F8FBFF335 +:102A50006F8F70BD53F8041B40F8041BC0E700BF24 +:102A600044450008C4470020C4470020C447002054 +:102A700000ED00E0074BD3F8D81021EA0001C3F8BD +:102A8000D810D3F8002122EA0002C3F80021D3F8BD +:102A9000003170470044025870B5D0E92443002249 +:102AA0004FF0FF359E6804EB42135101D3F8000943 +:102AB000002805DAD3F8000940F08040C3F8000987 +:102AC000D3F8000B002805DAD3F8000B40F0804063 +:102AD000C3F8000B013263189642C3F80859C3F8D3 +:102AE000085BE0D24FF00113C4F81C3870BD000041 +:102AF000890141F02001016103699B06FCD4122089 +:102B0000FFF770BA10B50A4C2046FEF733FF094BA9 +:102B1000C4F89030084BC4F89430084C2046FEF7B7 +:102B200029FF074BC4F89030064BC4F8943010BD11 +:102B3000F44500200000084084430008904600202F +:102B4000000004409043000870B503780546012B4F +:102B50005CD1434BD0F89040984258D1414B0E2164 +:102B60006520D3F8D82042F00062C3F8D820D3F80B +:102B7000002142F00062C3F80021D3F80021D3F80D +:102B8000802042F00062C3F88020D3F8802022F039 +:102B90000062C3F88020D3F8803000F0ADFC324BE7 +:102BA000E360324BC4F800380023D5F89060C4F8D5 +:102BB000003EC02323604FF40413A3633369002B4A +:102BC000FCDA01230C203361FFF70CFA3369DB07D1 +:102BD000FCD41220FFF706FA3369002BFCDA00263A +:102BE0002846A660FFF758FF6B68C4F81068DB68DA +:102BF000C4F81468C4F81C6883BB1D4BA3614FF074 +:102C0000FF336361A36843F00103A36070BD194BF8 +:102C10009842C9D1134B4FF08060D3F8D82042F0CE +:102C20000072C3F8D820D3F8002142F00072C3F834 +:102C30000021D3F80021D3F8802042F00072C3F8BD +:102C40008020D3F8802022F00072C3F88020D3F8CF +:102C50008030FFF70FFF0E214D209EE7064BCDE79A +:102C6000F4450020004402584014004003002002B4 +:102C7000003C30C090460020083C30C0F8B5D0F889 +:102C80009040054600214FF000662046FFF730FFD8 +:102C9000D5F8941000234FF001128F684FF0FF30E9 +:102CA000C4F83438C4F81C2804EB431201339F42A3 +:102CB000C2F80069C2F8006BC2F80809C2F8080B34 +:102CC000F2D20B68D5F89020C5F8983063621023D3 +:102CD0001361166916F01006FBD11220FFF782F976 +:102CE000D4F8003823F4FE63C4F80038A36943F431 +:102CF000402343F01003A3610923C4F81038C4F83B +:102D000014380B4BEB604FF0C043C4F8103B094B39 +:102D1000C4F8003BC4F81069C4F80039D5F89830FD +:102D200003F1100243F48013C5F89820A362F8BDA4 +:102D30006043000840800010D0F8902090F88A107E +:102D4000D2F8003823F4FE6343EA0113C2F80038D6 +:102D5000704700002DE9F84300EB8103D0F8905054 +:102D60000C468046DA680FFA81F94801166806F0C9 +:102D70000306731E022B05EB41134FF0000194BFB5 +:102D8000B604384EC3F8101B4FF0010104F11003D4 +:102D900098BF06F1805601FA03F3916998BF06F5D2 +:102DA000004600293AD0578A04F1580137434901B7 +:102DB0006F50D5F81C180B430021C5F81C382B1890 +:102DC0000127C3F81019A7405369611E9BB3138AEA +:102DD000928B9B08012A88BF5343D8F898209818F3 +:102DE00042EA034301F140022146C8F89800284610 +:102DF00005EB82025360FFF77BFE08EB8900C36896 +:102E00001B8A43EA845348341E4364012E51D5F88B +:102E10001C381F43C5F81C78BDE8F88305EB49173B +:102E2000D7F8001B21F40041C7F8001BD5F81C1887 +:102E300021EA0303C0E704F13F030B4A2846214679 +:102E400005EB83035A60FFF753FE05EB4910D0F8FA +:102E5000003923F40043C0F80039D5F81C3823EAC0 +:102E60000707D7E70080001000040002D0F8942084 +:102E70001268C0F89820FFF70FBE00005831D0F854 +:102E8000903049015B5813F4004004D013F4001F44 +:102E90000CBF0220012070474831D0F89030490122 +:102EA0005B5813F4004004D013F4001F0CBF022041 +:102EB0000120704700EB8101CB68196A0B68136031 +:102EC0004B6853607047000000EB810330B5DD684C +:102ED000AA691368D36019B9402B84BF40231360DB +:102EE0006B8A1468D0F890201C4402EB4110013C1E +:102EF00009B2B4FBF3F46343033323F0030343EA5F +:102F0000C44343F0C043C0F8103B2B6803F00303F5 +:102F1000012B0ED1D2F8083802EB411013F4807F58 +:102F2000D0F8003B14BF43F0805343F00053C0F887 +:102F3000003B02EB4112D2F8003B43F00443C2F8DD +:102F4000003B30BD2DE9F041D0F8906005460C46BD +:102F500006EB4113D3F8087B3A07C3F8087B08D582 +:102F6000D6F814381B0704D500EB8103DB685B68D7 +:102F70009847FA071FD5D6F81438DB071BD505EBA1 +:102F80008403D968CCB98B69488A5A68B2FBF0F6D9 +:102F900000FB16228AB91868DA6890420DD2121A1C +:102FA000C3E90024302383F3118821462846FFF724 +:102FB0008BFF84F31188BDE8F081012303FA04F24A +:102FC0006B8923EA02036B81CB68002BF3D0214687 +:102FD0002846BDE8F041184700EB81034A0170B56F +:102FE000DD68D0F890306C692668E66056BB1A44FC +:102FF0004FF40020C2F810092A6802F00302012AE7 +:103000000AB20ED1D3F8080803EB421410F4807F03 +:10301000D4F8000914BF40F0805040F00050C4F8CC +:10302000000903EB4212D2F8000940F00440C2F854 +:1030300000090122D3F8340802FA01F10143C3F870 +:10304000341870BD19B9402E84BF4020206020681C +:103050001A442E8A8419013CB4FBF6F440EAC440B9 +:1030600040F00050C6E700002DE9F843D0F890602A +:1030700005460C464F0106EB4113D3F8088918F0BA +:10308000010FC3F808891CD0D6F81038DB0718D513 +:1030900000EB8103D3F80CC0DCF81430D3F800E067 +:1030A000DA68964530D2A2EB0E024FF000091A60A2 +:1030B000C3F80490302383F31188FFF78DFF89F361 +:1030C000118818F0800F1DD0D6F834380126A6409C +:1030D000334217D005EB84030134D5F89050D3F870 +:1030E0000CC0E4B22F44DCF8142005EB0434D2F811 +:1030F00000E05168714514D3D5F8343823EA060648 +:10310000C5F83468BDE8F883012303FA01F20389A6 +:1031100023EA02030381DCF80830002BD1D0984762 +:10312000CFE7AEEB0103BCF81000834228BF034693 +:10313000D7F8180980B2B3EB800FE3D89068A0F1FC +:10314000040959F8048FC4F80080A0EB09089844DA +:10315000B8F1040FF5D818440B4490605360C8E7E9 +:103160002DE9F84FD0F8905004466E69AB691E40C7 +:1031700016F480586E6103D0BDE8F84FFEF76ABCC4 +:10318000002E12DAD5F8003E9B0705D0D5F8003E98 +:1031900023F00303C5F8003ED5F80438204623F099 +:1031A0000103C5F80438FEF783FC370505D5204632 +:1031B000FFF772FC2046FEF769FCB0040CD5D5F889 +:1031C000083813F0060FEB6823F470530CBF43F478 +:1031D000105343F4A053EB6031071BD56368DB68E1 +:1031E0001BB9AB6923F00803AB612378052B0CD125 +:1031F000D5F8003E9A0705D0D5F8003E23F003032A +:10320000C5F8003E2046FEF753FC6368DB680BB14F +:1032100020469847F30200F1BA80B70226D5D4F8C9 +:10322000909000274FF0010A09EB4712D2F8003BBB +:1032300003F44023B3F5802F11D1D2F8003B002BCB +:103240000DDA62890AFA07F322EA0303638104EBC9 +:103250008703DB68DB6813B139462046984701379E +:10326000D4F89430FFB29B689F42DDD9F00619D59F +:10327000D4F89000026AC2F30A1702F00F0302F4B6 +:10328000F012B2F5802F00F0CA80B2F5402F09D1BC +:1032900004EB8303002200F58050DB681B6A974231 +:1032A00040F0B0803003D5F8185835D5E90303D580 +:1032B00000212046FFF746FEAA0303D50121204640 +:1032C000FFF740FE6B0303D502212046FFF73AFECD +:1032D0002F0303D503212046FFF734FEE80203D570 +:1032E00004212046FFF72EFEA90203D50521204622 +:1032F000FFF728FE6A0203D506212046FFF722FECB +:103300002B0203D507212046FFF71CFEEF0103D552 +:1033100008212046FFF716FE700340F1A780E90759 +:1033200003D500212046FFF79FFEAA0703D5012100 +:103330002046FFF799FE6B0703D502212046FFF7D1 +:1033400093FE2F0703D503212046FFF78DFEEE06DF +:1033500003D504212046FFF787FEA80603D50521E3 +:103360002046FFF781FE690603D506212046FFF7B8 +:103370007BFE2A0603D507212046FFF775FEEB05E5 +:1033800074D520460821BDE8F84FFFF76DBED4F88C +:1033900090904FF0000B4FF0010AD4F894305FFA90 +:1033A0008BF79B689F423FF638AF09EB4713D3F882 +:1033B000002902F44022B2F5802F20D1D3F8002951 +:1033C000002A1CDAD3F8002942F09042C3F8002901 +:1033D000D3F80029002AFBDB3946D4F89000FFF728 +:1033E00087FB22890AFA07F322EA0303238104EB0D +:1033F0008703DB689B6813B13946204698470BF179 +:10340000010BCAE7910701D1D0F80080072A02F129 +:1034100001029CBF03F8018B4FEA18283FE704EB39 +:10342000830300F58050DA68D2F818C0DCF8082071 +:10343000DCE9001CA1EB0C0C00218F4208D1DB68F9 +:103440009B699A683A449A605A683A445A6029E7F4 +:1034500011F0030F01D1D0F800808C4501F101017A +:1034600084BF02F8018B4FEA1828E6E7BDE8F88F21 +:1034700008B50348FFF774FEBDE8084000F07ABBCA +:10348000F445002008B50348FFF76AFEBDE8084090 +:1034900000F070BB90460020D0F8903003EB411153 +:1034A000D1F8003B43F40013C1F8003B7047000023 +:1034B000D0F8903003EB4111D1F8003943F40013F8 +:1034C000C1F8003970470000D0F8903003EB41118B +:1034D000D1F8003B23F40013C1F8003B7047000013 +:1034E000D0F8903003EB4111D1F8003923F40013E8 +:1034F000C1F8003970470000090100F16043012262 +:1035000003F56143C9B283F8001300F01F039A402A +:1035100043099B0003F1604303F56143C3F8802135 +:103520001A60704730B50433039C0172002104FB1C +:103530000325C160C0E90653049B0363059BC0E9F2 +:103540000000C0E90422C0E90842C0E90A1143634F +:1035500030BD00000022416AC260C0E90411C0E928 +:103560000A226FF00101FEF7ADBD0000D0E9043280 +:10357000934201D1C2680AB9181D704700207047F4 +:10358000036919600021C2680132C260C269134434 +:1035900082699342036124BF436A0361FEF786BDDB +:1035A00038B504460D46E3683BB162690020131D3F +:1035B0001268A3621344E36207E0237A33B9294611 +:1035C0002046FEF763FD0028EDDA38BD6FF00100FC +:1035D000FBE70000C368C269013BC3604369134451 +:1035E00082699342436124BF436A4361002383623B +:1035F000036B03B11847704770B53023044683F35B +:103600001188866A3EB9FFF7CBFF054618B186F3ED +:103610001188284670BDA36AE26A13F8015B9342E1 +:10362000A36202D32046FFF7D5FF002383F311885E +:10363000EFE700002DE9F84F04460E46174698467E +:103640004FF0300989F311880025AA46D4F828B034 +:10365000BBF1000F09D141462046FFF7A1FF20B181 +:103660008BF311882846BDE8F88FD4E90A12A7EB3E +:10367000050B521A934528BF9346BBF1400F1BD947 +:10368000334601F1400251F8040B914243F8040B18 +:10369000F9D1A36A403640354033A362D4E90A2306 +:1036A0009A4202D32046FFF795FF8AF31188BD4264 +:1036B000D8D289F31188C9E730465A46FDF7E6FBB0 +:1036C000A36A5E445D445B44A362E7E710B5029CD5 +:1036D0000433017203FB0421C460C0E90613002314 +:1036E000C0E90A33039B0363049BC0E90000C0E9FF +:1036F0000422C0E90842436310BD0000026A6FF073 +:103700000101C260426AC0E904220022C0E90A2223 +:10371000FEF7D8BCD0E904239A4201D1C26822B98D +:10372000184650F8043B0B60704700231846FAE730 +:10373000C3680021C2690133C360436913448269CD +:103740009342436124BF436A4361FEF7AFBC00006C +:1037500038B504460D46E3683BB1236900201A1DC5 +:10376000A262E2691344E36207E0237A33B929468F +:103770002046FEF78BFC0028EDDA38BD6FF0010023 +:10378000FBE7000003691960C268013AC260C269C0 +:10379000134482699342036124BF436A0361002397 +:1037A0008362036B03B118477047000070B5302384 +:1037B0000D460446114683F31188866A2EB9FFF739 +:1037C000C7FF10B186F3118870BDA36A1D70A36A8C +:1037D000E26A01339342A36204D3E16920460439CB +:1037E000FFF7D0FF002080F31188EDE72DE9F84FB7 +:1037F00004460D46904699464FF0300A8AF31188E8 +:103800000026B346A76A4FB949462046FFF7A0FFF6 +:1038100020B187F311883046BDE8F88FD4E90A0754 +:103820003A1AA8EB0607974228BF1746402F1BD924 +:1038300005F1400355F8042B9D4240F8042BF9D1C3 +:10384000A36A40364033A362D4E90A239A4204D3E0 +:10385000E16920460439FFF795FF8BF3118846454F +:10386000D9D28AF31188CDE729463A46FDF70EFBF7 +:10387000A36A3D443E443B44A362E5E7D0E9042308 +:103880009A4217D1C3689BB1836A8BB1043B9B1AE0 +:103890000ED01360C368013BC360C3691A448369D7 +:1038A0009A42026124BF436A0361002383620123B9 +:1038B000184670470023FBE700F086B9014B586AB1 +:1038C000704700BF000C0040034B002258631A6190 +:1038D0000222DA60704700BF000C0040014B00225A +:1038E000DA607047000C0040014B5863704700BF1E +:1038F000000C0040FEE7000070B51B4B002504469D +:1039000086B058600E468562016300F00BF904F141 +:103910001003A560E562C4E904334FF0FF33C4E946 +:103920000044C4E90635FFF7C9FF2B46024604F1FF +:1039300034012046C4E9082380230C4A2565FEF79C +:103940005BFB01230A4AE0600092037568467268D7 +:103950000192B268CDE90223064BCDE90435FEF7AA +:1039600073FB06B070BD00BFB02A00209C43000866 +:10397000A1430008F5380008024AD36A1843D06210 +:10398000704700BF482800204B6843608B68836005 +:10399000CB68C3600B6943614B6903628B69436207 +:1039A0000B6803607047000008B53C4B40F2FF71A4 +:1039B0003B48D3F888200A43C3F88820D3F88820EE +:1039C00022F4FF6222F00702C3F88820D3F888208F +:1039D000D3F8E0200A43C3F8E020D3F808210A43D3 +:1039E000C3F808212F4AD3F808311146FFF7CCFF5E +:1039F00000F5806002F11C01FFF7C6FF00F5806052 +:103A000002F13801FFF7C0FF00F5806002F15401B8 +:103A1000FFF7BAFF00F5806002F17001FFF7B4FF15 +:103A200000F5806002F18C01FFF7AEFF00F58060C9 +:103A300002F1A801FFF7A8FF00F5806002F1C401C0 +:103A4000FFF7A2FF00F5806002F1E001FFF79CFFA5 +:103A500000F5806002F1FC01FFF796FF02F58C7122 +:103A600000F58060FFF790FF00F076F90E4BD3F879 +:103A7000902242F00102C3F89022D3F8942242F03F +:103A80000102C3F894220522C3F898204FF0605237 +:103A9000C3F89C20054AC3F8A02008BD0044025882 +:103AA00000000258A843000800ED00E01F000803D2 +:103AB00008B500F033FBFEF77DFA0F4BD3F8DC209E +:103AC00042F04002C3F8DC20D3F8042122F0400287 +:103AD000C3F80421D3F80431084B1A6842F00802F5 +:103AE0001A601A6842F004021A60FEF721FFBDE86E +:103AF0000840FEF7D3BC00BF00440258001802483B +:103B000070470000EFF30983054968334A6B22F0E0 +:103B100001024A6383F30988002383F31188704705 +:103B200000EF00E0302080F3118862B60D4B0E4AA2 +:103B3000D96821F4E0610904090C0A430B49DA60F1 +:103B4000D3F8FC2042F08072C3F8FC20084AC2F887 +:103B5000B01F116841F0010111602022DA7783F86B +:103B60002200704700ED00E00003FA0555CEACC519 +:103B7000001000E0302310B583F311880E4B5B6812 +:103B800013F4006314D0F1EE103AEFF309844FF010 +:103B90008073683CE361094BDB6B236684F309881F +:103BA000FEF7E8F910B1064BA36110BD054BFBE72A +:103BB00083F31188F9E700BF00ED00E000EF00E0BB +:103BC0002F04000832040008114BD3F8E82042F01B +:103BD0000802C3F8E820D3F8102142F00802C3F825 +:103BE00010210C4AD3F81031D36B43F00803D36390 +:103BF000C722094B9A624FF0FF32DA6200229A61C3 +:103C00005A63DA605A6001225A611A60704700BF35 +:103C1000004402580010005C000C0040094A08B53E +:103C20001169D3680B40D9B29B076FEA010111619A +:103C300007D5302383F31188FEF7D2F9002383F3ED +:103C4000118808BD000C0040064BD3F8DC2002436D +:103C5000C3F8DC20D3F804211043C3F80401D3F8DF +:103C600004317047004402583A4B4FF0FF31D3F80B +:103C7000802062F00042C3F88020D3F8802002F058 +:103C80000042C3F88020D3F88020D3F88420C3F802 +:103C90008410D3F884200022C3F88420D3F8840051 +:103CA000D86F40F0FF4040F4FF0040F4DF4040F0A8 +:103CB0007F00D867D86F20F0FF4020F4FF0020F489 +:103CC000DF4020F07F00D867D86FD3F888006FEA14 +:103CD00040506FEA5050C3F88800D3F88800C0F312 +:103CE0000A00C3F88800D3F88800D3F89000C3F81E +:103CF0009010D3F89000C3F89020D3F89000D3F838 +:103D00009400C3F89410D3F89400C3F89420D3F827 +:103D10009400D3F89800C3F89810D3F89800C3F82B +:103D20009820D3F89800D3F88C00C3F88C10D3F8FF +:103D30008C00C3F88C20D3F88C00D3F89C00C3F817 +:103D40009C10D3F89C10C3F89C20D3F89C3000F052 +:103D5000B9B900BF0044025808B50122534BC3F85B +:103D60000821534BD3F8F42042F00202C3F8F420A8 +:103D7000D3F81C2142F00202C3F81C210222D3F81E +:103D80001C314C4BDA605A689104FCD54A4A1A60DF +:103D900001229A60494ADA6000221A614FF44042D7 +:103DA0009A61444B9A699204FCD51A6842F4807275 +:103DB0001A603F4B1A6F12F4407F04D04FF48032E8 +:103DC0001A6700221A671A6842F001021A60384B1B +:103DD0001A685007FCD500221A611A6912F03802DD +:103DE000FBD1012119604FF0804159605A67344A74 +:103DF000DA62344A1A611A6842F480321A602C4B33 +:103E00001A689103FCD51A6842F480521A601A6845 +:103E10009204FCD52C4A2D499A6200225A631963F8 +:103E200001F57C01DA6301F2E71199635A64284ACB +:103E30001A64284ADA621A6842F0A8521A601C4BC7 +:103E40001A6802F02852B2F1285FF9D148229A612B +:103E50004FF48862DA6140221A621F4ADA641F4A0C +:103E60001A651F4A5A651F4A9A6532231E4A136013 +:103E7000136803F00F03022BFAD10D4A136943F0C4 +:103E800003031361136903F03803182BFAD14FF0C1 +:103E90000050FFF7D9FE4FF08040FFF7D5FE4FF0FE +:103EA0000040BDE80840FFF7CFBE00BF00800051D2 +:103EB000004402580048025800C000F0020000010F +:103EC0000000FF01008890082220400063020901E1 +:103ED000470E0508DD0BBF01200000200000011087 +:103EE0000910E00000010110002000524FF0B04224 +:103EF00008B5D2F8883003F00103C2F8883023B146 +:103F0000044A13680BB150689847BDE80840FFF7B2 +:103F100031BE00BF444700204FF0B04208B5D2F890 +:103F2000883003F00203C2F8883023B1044A936852 +:103F30000BB1D0689847BDE80840FFF71BBE00BF33 +:103F4000444700204FF0B04208B5D2F8883003F063 +:103F50000403C2F8883023B1044A13690BB15069D5 +:103F60009847BDE80840FFF705BE00BF4447002062 +:103F70004FF0B04208B5D2F8883003F00803C2F819 +:103F8000883023B1044A93690BB1D0699847BDE8E2 +:103F90000840FFF7EFBD00BF444700204FF0B0429C +:103FA00008B5D2F8883003F01003C2F8883023B186 +:103FB000044A136A0BB1506A9847BDE80840FFF7FE +:103FC000D9BD00BF444700204FF0B04310B5D3F82F +:103FD000884004F47872C3F88820A30604D5124AF6 +:103FE000936A0BB1D06A9847600604D50E4A136BEA +:103FF0000BB1506B9847210604D50B4A936B0BB15C +:10400000D06B9847E20504D5074A136C0BB1506C8E +:104010009847A30504D5044A936C0BB1D06C98471C +:10402000BDE81040FFF7A6BD444700204FF0B04365 +:1040300010B5D3F8884004F47C42C3F888206205A8 +:1040400004D5164A136D0BB1506D9847230504D55E +:10405000124A936D0BB1D06D9847E00404D50F4A16 +:10406000136E0BB1506E9847A10404D50B4A936EA2 +:104070000BB1D06E9847620404D5084A136F0BB198 +:10408000506F9847230404D5044A936F0BB1D06F47 +:104090009847BDE81040FFF76DBD00BF44470020C2 +:1040A00008B50348FDF772F8BDE80840FFF762BDA8 +:1040B000D823002008B5FFF7B1FDBDE80840FFF7A1 +:1040C00059BD0000062108B50846FFF715FA06217C +:1040D0000720FFF711FA06210820FFF70DFA062145 +:1040E0000920FFF709FA06210A20FFF705FA062141 +:1040F0001720FFF701FA06212820FFF7FDF9092113 +:104100007A20FFF7F9F907213220FFF7F5F90C21A2 +:104110002520BDE80840FFF7EFB9000008B5FFF71C +:10412000A3FD00F00DF8FDF749FAFDF721FCFDF7BE +:10413000F3FAFFF7E5FCBDE80840FFF7BDBB000060 +:104140000023054A19460133102BC2E9001102F180 +:104150000802F8D1704700BF4447002010B501396C +:104160000244904201D1002005E0037811F8014F8C +:10417000A34201D0181B10BD0130F2E7034611F82D +:10418000012B03F8012B002AF9D1704753544D330A +:104190003248373F3F3F0053544D3332483733782E +:1041A0002F3732780053544D3332483734332F375A +:1041B00035332F373530000001105A0003105900F5 +:1041C0000120580003205600009600000000000067 +:1041D00000000000000000000000000000000000DF +:1041E000000000007D15000869150008A5150008ED +:1041F000911500089D15000889150008751500081F +:1042000061150008B11500080000000095160008AF +:1042100081160008BD160008A9160008B51600088A +:10422000A11600088D16000879160008C9160008A6 +:1042300000000000010000000000000063300000EA +:104240003C420008A0280020B02A00204169727674 +:104250006F6C7574650025424F415244252D424CC8 +:10426000002553455249414C250000000200000042 +:1042700000000000B51800082519000840004000A3 +:104280006043002070430020020000000000000096 +:1042900003000000000000006D190008000000008D +:1042A000100000008043002000000000010000001A +:1042B00000000000F445002001010200392400083C +:1042C00049230008E5230008C92300084300000033 +:1042D000D442000809024300020100C03209040070 +:1042E0000001020201000524001001052401000163 +:1042F000042402020524060001070582030800FFCA +:1043000009040100020A0000000705010240000044 +:104310000705810240000000120000002043000851 +:10432000120110010200004009124157000201026F +:10433000030100000403090425424F4152442500B3 +:10434000416972766F6C7574652D44435332003049 +:1043500031323334353637383941424344454600EB +:1043600000000000C91A0008811D00082D1E000869 +:10437000400040002C4700202C4700200100000096 +:104380003C470020800000004001000008000000C1 +:104390000001000000100000080000006D61696E5F +:1043A0000069646C650000000000A02A00020000A3 +:1043B000AAAAAAAA00001024FFFF00000000000023 +:1043C00000A70A000400002000000000AAAAAAAA70 +:1043D00000000010FDFF00000000000000000004CD +:1043E0000000000000000000AAAAAAAA0000000025 +:1043F000FFFF00000000000000000000000050551A +:1044000000000000AAAAAAAA00005055FFFF000061 +:104410000000000000000000000000040000000098 +:10442000AAAAAAAA00000004FFFF000000000000E2 +:10443000000000000000000000000000AAAAAAAAD4 +:1044400000000000FFFF000000000000000000006E +:104450000000000000000000AAAAAAAA00000000B4 +:10446000FFFF00000000000000000000000000004E +:1044700000000000AAAAAAAA00000000FFFF000096 +:10448000000000000000000000000000000000002C +:10449000AAAAAAAA00000000FFFF00000000000076 +:1044A000000000000000000000000000AAAAAAAA64 +:1044B00000000000FFFF00000000000000000000FE +:1044C0000000000000000000AAAAAAAA0000000044 +:1044D000FFFF0000000000000000000000000000DE +:1044E000501400000000000000001A00000000004E +:1044F000FF000000B82A0020D823002000000000A0 +:104500008C4100088304000097410008500400001B +:10451000A541000800960000000008009600000079 +:104520000008000004000000344300080000000000 +:10453000000000000000000000000000000000007B +:044540000000000077 +:00000001FF From 1c8ab3853ce4c3d9df7ea4b4da66f658a06bc9ee Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Wed, 22 Nov 2023 14:07:37 +0000 Subject: [PATCH 0046/1335] AP_Motors: Heli: Single: tail type tidyup --- libraries/AP_Motors/AP_MotorsHeli_Single.cpp | 206 +++++++++++-------- libraries/AP_Motors/AP_MotorsHeli_Single.h | 34 ++- 2 files changed, 146 insertions(+), 94 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp index fe13951f4d1dac..30f10cda24bc37 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp @@ -31,7 +31,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = { // @Description: Tail type selection. Simpler yaw controller used if external gyro is selected. Direct Drive Variable Pitch is used for tails that have a motor that is governed at constant speed by an ESC. Tail pitch is still accomplished with a servo. Direct Drive Fixed Pitch (DDFP) CW is used for helicopters with a rotor that spins clockwise when viewed from above. Direct Drive Fixed Pitch (DDFP) CCW is used for helicopters with a rotor that spins counter clockwise when viewed from above. In both DDFP cases, no servo is used for the tail and the tail motor esc is controlled by the yaw axis. // @Values: 0:Servo only,1:Servo with ExtGyro,2:DirectDrive VarPitch,3:DirectDrive FixedPitch CW,4:DirectDrive FixedPitch CCW,5:DDVP with external governor // @User: Standard - AP_GROUPINFO("TAIL_TYPE", 4, AP_MotorsHeli_Single, _tail_type, AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO), + AP_GROUPINFO("TAIL_TYPE", 4, AP_MotorsHeli_Single, _tail_type, float(TAIL_TYPE::SERVO)), // Indice 5 was used by SWASH_TYPE and should not be used @@ -210,25 +210,33 @@ void AP_MotorsHeli_Single::init_outputs() // initialize main rotor servo _main_rotor.init_servo(); - if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH || _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPIT_EXT_GOV) { - _tail_rotor.init_servo(); - } else if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO) { - // external gyro output - add_motor_num(AP_MOTORS_HELI_SINGLE_EXTGYRO); - } - } + switch (get_tail_type()) { + case TAIL_TYPE::DIRECTDRIVE_FIXEDPITCH_CW: + case TAIL_TYPE::DIRECTDRIVE_FIXEDPITCH_CCW: + // DDFP tails use range as it is easier to ignore servo trim in making for simple implementation of thrust linearisation. + SRV_Channels::set_range(SRV_Channel::k_motor4, 1.0f); + break; - if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO) { - // External Gyro uses PWM output thus servo endpoints are forced - SRV_Channels::set_output_min_max(SRV_Channels::get_motor_function(AP_MOTORS_HELI_SINGLE_EXTGYRO), 1000, 2000); - } + case TAIL_TYPE::DIRECTDRIVE_VARPITCH: + case TAIL_TYPE::DIRECTDRIVE_VARPIT_EXT_GOV: + _tail_rotor.init_servo(); + break; + + case TAIL_TYPE::SERVO_EXTGYRO: + // external gyro output + add_motor_num(AP_MOTORS_HELI_SINGLE_EXTGYRO); + + + // External Gyro uses PWM output thus servo endpoints are forced + SRV_Channels::set_output_min_max(SRV_Channels::get_motor_function(AP_MOTORS_HELI_SINGLE_EXTGYRO), 1000, 2000); + FALLTHROUGH; - if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CW || _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CCW) { - // DDFP tails use range as it is easier to ignore servo trim in making for simple implementation of thrust linearisation. - SRV_Channels::set_range(SRV_Channel::k_motor4, 1.0f); - } else if (_tail_type != AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH && _tail_type != AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPIT_EXT_GOV) { - // yaw servo is an angle from -4500 to 4500 - SRV_Channels::set_angle(SRV_Channel::k_motor4, YAW_SERVO_MAX_ANGLE); + case TAIL_TYPE::SERVO: + default: + // yaw servo is an angle from -4500 to 4500 + SRV_Channels::set_angle(SRV_Channel::k_motor4, YAW_SERVO_MAX_ANGLE); + break; + } } set_initialised_ok(_frame_class == MOTOR_FRAME_HELI); @@ -266,13 +274,13 @@ void AP_MotorsHeli_Single::calculate_armed_scalars() _main_rotor.set_autorotation_flag(_heliflags.in_autorotation); // set bailout ramp time _main_rotor.use_bailout_ramp_time(_heliflags.enable_bailout); - if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH || _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPIT_EXT_GOV) { + if (use_tail_RSC()) { _tail_rotor.set_autorotation_flag(_heliflags.in_autorotation); _tail_rotor.use_bailout_ramp_time(_heliflags.enable_bailout); } } else { _main_rotor.set_autorotation_flag(false); - if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH || _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPIT_EXT_GOV) { + if (use_tail_RSC()) { _tail_rotor.set_autorotation_flag(false); } } @@ -310,7 +318,7 @@ void AP_MotorsHeli_Single::calculate_scalars() calculate_armed_scalars(); // send setpoints to DDVP rotor controller and trigger recalculation of scalars - if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH || _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPIT_EXT_GOV) { + if (use_tail_RSC()) { _tail_rotor.set_control_mode(ROTOR_CONTROL_MODE_SETPOINT); _tail_rotor.set_ramp_time(_main_rotor._ramp_time.get()); _tail_rotor.set_runup_time(_main_rotor._runup_time.get()); @@ -370,8 +378,6 @@ void AP_MotorsHeli_Single::update_motor_control(RotorControlState state) // void AP_MotorsHeli_Single::move_actuators(float roll_out, float pitch_out, float coll_in, float yaw_out) { - float yaw_offset = 0.0f; - // initialize limits flag limit.throttle_lower = false; limit.throttle_upper = false; @@ -422,26 +428,8 @@ void AP_MotorsHeli_Single::move_actuators(float roll_out, float pitch_out, float // updates takeoff collective flag based on 50% hover collective update_takeoff_collective_flag(collective_out); - // if servo output not in manual mode and heli is not in autorotation, process pre-compensation factors - if (_servo_mode == SERVO_CONTROL_MODE_AUTOMATED && !_heliflags.in_autorotation) { - // rudder feed forward based on collective - // the feed-forward is not required when the motor is stopped or at idle, and thus not creating torque - // also not required if we are using external gyro - if ((get_control_output() > _main_rotor.get_idle_output()) && _tail_type != AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO) { - // sanity check collective_yaw_scale - _collective_yaw_scale.set(constrain_float(_collective_yaw_scale, -AP_MOTORS_HELI_SINGLE_COLYAW_RANGE, AP_MOTORS_HELI_SINGLE_COLYAW_RANGE)); - // This feedforward compensation follows the hover performance theory that hover power required - // is a function of gross weight to the 3/2 power - yaw_offset = _collective_yaw_scale * powf(fabsf(collective_out - _collective_zero_thrust_pct),1.5f); - - // Add yaw trim for DDFP tails - if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CW || _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CCW) { - yaw_offset += _yaw_trim.get(); - } - } - } else { - yaw_offset = 0.0f; - } + // Get yaw offset required to cancel out steady state main rotor torque + const float yaw_offset = get_yaw_offset(collective_out); // feed power estimate into main rotor controller // ToDo: include tail rotor power? @@ -475,72 +463,110 @@ void AP_MotorsHeli_Single::move_yaw(float yaw_out) _servo4_out = yaw_out; } -void AP_MotorsHeli_Single::output_to_motors() +// Get yaw offset required to cancel out steady state main rotor torque +float AP_MotorsHeli_Single::get_yaw_offset(float collective) { - if (!initialised_ok()) { - return; + if ((get_tail_type() == TAIL_TYPE::SERVO_EXTGYRO) || (_servo_mode != SERVO_CONTROL_MODE_AUTOMATED)) { + // Not in direct control of tail with external gyro or manual servo mode + return 0.0; } - // Write swashplate outputs - _swashplate.output(); - - if (_tail_type != AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CW && _tail_type != AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CCW) { - rc_write_angle(AP_MOTORS_MOT_4, _servo4_out * YAW_SERVO_MAX_ANGLE); - } - if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO) { - // output gain to exernal gyro - if (_acro_tail && _ext_gyro_gain_acro > 0) { - rc_write(AP_MOTORS_HELI_SINGLE_EXTGYRO, 1000 + _ext_gyro_gain_acro); - } else { - rc_write(AP_MOTORS_HELI_SINGLE_EXTGYRO, 1000 + _ext_gyro_gain_std); - } + if (_heliflags.in_autorotation || (get_control_output() <= _main_rotor.get_idle_output())) { + // Motor is stopped or at idle, and thus not creating torque + return 0.0; } - if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CCW) { - _servo4_out = -_servo4_out; + // sanity check collective_yaw_scale + _collective_yaw_scale.set(constrain_float(_collective_yaw_scale, -AP_MOTORS_HELI_SINGLE_COLYAW_RANGE, AP_MOTORS_HELI_SINGLE_COLYAW_RANGE)); + + // This feedforward compensation follows the hover performance theory that hover power required + // is a function of gross weight to the 3/2 power + float yaw_offset = _collective_yaw_scale * powf(fabsf(collective - _collective_zero_thrust_pct),1.5f); + + // Add yaw trim for DDFP tails + if (have_DDFP_tail()) { + yaw_offset += _yaw_trim.get(); } - if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CW || _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CCW) { - // calc filtered battery voltage and lift_max - thr_lin.update_lift_max_from_batt_voltage(); + return yaw_offset; +} + +void AP_MotorsHeli_Single::output_to_motors() +{ + if (!initialised_ok()) { + return; } - // Warning: This spool state logic is what prevents DDFP tails from actuating when doing H_SV_MAN and H_SV_TEST tests + // Write swashplate outputs + _swashplate.output(); + + // Output main rotor switch (_spool_state) { case SpoolState::SHUT_DOWN: // sends minimum values out to the motors update_motor_control(ROTOR_CONTROL_STOP); - if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CW || _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CCW) { - // Set DDFP to servo min - output_to_ddfp_tail(0.0); - } break; case SpoolState::GROUND_IDLE: // sends idle output to motors when armed. rotor could be static or turning (autorotation) update_motor_control(ROTOR_CONTROL_IDLE); - if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CW || _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CCW) { - // Set DDFP to servo min - output_to_ddfp_tail(0.0); - } break; case SpoolState::SPOOLING_UP: case SpoolState::THROTTLE_UNLIMITED: // set motor output based on thrust requests update_motor_control(ROTOR_CONTROL_ACTIVE); - if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CW || _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CCW) { - // Operate DDFP to between DDFP_SPIN_MIN and DDFP_SPIN_MAX using thrust linearisation - output_to_ddfp_tail(thr_lin.thrust_to_actuator(_servo4_out)); - } break; case SpoolState::SPOOLING_DOWN: // sends idle output to motors and wait for rotor to stop update_motor_control(ROTOR_CONTROL_IDLE); - if (_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CW || _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CCW){ - // Set DDFP to servo min - output_to_ddfp_tail(0.0); + break; + } + + // Output tail rotor + switch (get_tail_type()) { + case TAIL_TYPE::DIRECTDRIVE_FIXEDPITCH_CCW: + // Invert output for CCW tail + _servo4_out *= -1.0; + FALLTHROUGH; + + case TAIL_TYPE::DIRECTDRIVE_FIXEDPITCH_CW: { + // calc filtered battery voltage and lift_max + thr_lin.update_lift_max_from_batt_voltage(); + + // Only throttle up if in active spool state + switch (_spool_state) { + case AP_Motors::SpoolState::SHUT_DOWN: + case AP_Motors::SpoolState::GROUND_IDLE: + case AP_Motors::SpoolState::SPOOLING_DOWN: + // Set DDFP to servo min + output_to_ddfp_tail(0.0); + break; + + case AP_Motors::SpoolState::SPOOLING_UP: + case AP_Motors::SpoolState::THROTTLE_UNLIMITED: + // Operate DDFP to between DDFP_SPIN_MIN and DDFP_SPIN_MAX using thrust linearisation + output_to_ddfp_tail(thr_lin.thrust_to_actuator(_servo4_out)); + break; } break; + } + + case TAIL_TYPE::SERVO_EXTGYRO: + // output gain to external gyro + if (_acro_tail && _ext_gyro_gain_acro > 0) { + rc_write(AP_MOTORS_HELI_SINGLE_EXTGYRO, 1000 + _ext_gyro_gain_acro); + } else { + rc_write(AP_MOTORS_HELI_SINGLE_EXTGYRO, 1000 + _ext_gyro_gain_std); + } + FALLTHROUGH; + + case TAIL_TYPE::SERVO: + case TAIL_TYPE::DIRECTDRIVE_VARPITCH: + case TAIL_TYPE::DIRECTDRIVE_VARPIT_EXT_GOV: + default: + rc_write_angle(AP_MOTORS_MOT_4, _servo4_out * YAW_SERVO_MAX_ANGLE); + break; } + } // handle output limit flags and send throttle to servos lib @@ -655,9 +681,7 @@ void AP_MotorsHeli_Single::heli_motors_param_conversions(void) // Previous DDFP configs used servo trim for setting the yaw trim, which no longer works with thrust linearisation. Convert servo trim // to H_YAW_TRIM. Default thrust linearisation gives linear thrust to throttle relationship to preserve previous setup behaviours so // we can assume linear relationship in the conversion. - if ((_tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CW || - _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CCW) && - !_yaw_trim.configured()) { + if (have_DDFP_tail() && !_yaw_trim.configured()) { SRV_Channel *c = SRV_Channels::get_channel_for(SRV_Channel::k_motor4); if (c != nullptr) { @@ -673,3 +697,19 @@ void AP_MotorsHeli_Single::heli_motors_param_conversions(void) _yaw_trim.save(); } } + +// Helper to return true for direct drive fixed pitch tail, either CW or CCW +bool AP_MotorsHeli_Single::have_DDFP_tail() const +{ + const TAIL_TYPE type = get_tail_type(); + return (type == TAIL_TYPE::DIRECTDRIVE_FIXEDPITCH_CW) || + (type == TAIL_TYPE::DIRECTDRIVE_FIXEDPITCH_CCW); +} + +// Helper to return true if the tail RSC should be used +bool AP_MotorsHeli_Single::use_tail_RSC() const +{ + const TAIL_TYPE type = get_tail_type(); + return (type == TAIL_TYPE::DIRECTDRIVE_VARPITCH) || + (type == TAIL_TYPE::DIRECTDRIVE_VARPIT_EXT_GOV); +} diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.h b/libraries/AP_Motors/AP_MotorsHeli_Single.h index 595ce98a04f90e..870d4801c96050 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.h +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.h @@ -14,15 +14,6 @@ #define AP_MOTORS_HELI_SINGLE_EXTGYRO CH_7 #define AP_MOTORS_HELI_SINGLE_TAILRSC CH_7 -// tail types -#define AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO 0 -#define AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO 1 -#define AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPITCH 2 -#define AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CW 3 -#define AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_FIXEDPITCH_CCW 4 -#define AP_MOTORS_HELI_SINGLE_TAILTYPE_DIRECTDRIVE_VARPIT_EXT_GOV 5 - - // direct-drive variable pitch defaults #define AP_MOTORS_HELI_SINGLE_DDVP_SPEED_DEFAULT 50 @@ -72,8 +63,8 @@ class AP_MotorsHeli_Single : public AP_MotorsHeli { // has_flybar - returns true if we have a mechical flybar bool has_flybar() const override { return _flybar_mode; } - // supports_yaw_passthrought - returns true if we support yaw passthrough - bool supports_yaw_passthrough() const override { return _tail_type == AP_MOTORS_HELI_SINGLE_TAILTYPE_SERVO_EXTGYRO; } + // supports_yaw_passthrough - returns true if we support yaw passthrough + bool supports_yaw_passthrough() const override { return get_tail_type() == TAIL_TYPE::SERVO_EXTGYRO; } void set_acro_tail(bool set) override { _acro_tail = set; } @@ -103,12 +94,33 @@ class AP_MotorsHeli_Single : public AP_MotorsHeli { // move_yaw - moves the yaw servo void move_yaw(float yaw_out); + // Get yaw offset required to cancel out steady state main rotor torque + float get_yaw_offset(float collective); + // handle output limit flags and send throttle to servos lib void output_to_ddfp_tail(float throttle); // servo_test - move servos through full range of movement void servo_test() override; + // Tail types + enum class TAIL_TYPE { + SERVO = 0, + SERVO_EXTGYRO = 1, + DIRECTDRIVE_VARPITCH = 2, + DIRECTDRIVE_FIXEDPITCH_CW = 3, + DIRECTDRIVE_FIXEDPITCH_CCW = 4, + DIRECTDRIVE_VARPIT_EXT_GOV = 5 + }; + + TAIL_TYPE get_tail_type() const { return TAIL_TYPE(_tail_type.get()); } + + // Helper to return true for direct drive fixed pitch tail, either CW or CCW + bool have_DDFP_tail() const; + + // Helper to return true if the tail RSC should be used + bool use_tail_RSC() const; + // external objects we depend upon AP_MotorsHeli_RSC _tail_rotor; // tail rotor AP_MotorsHeli_Swash _swashplate; // swashplate From 5dcdd238a9afd6b18f8f12645e718727cdc47fd1 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Wed, 22 Nov 2023 14:07:58 +0000 Subject: [PATCH 0047/1335] AP_Motors: Example: allow testing of heli tail type --- .../AP_Motors_test/AP_Motors_test.cpp | 33 +++++++++- .../AP_Motors_test/run_heli_comparison.py | 62 ++++++++++++++----- 2 files changed, 78 insertions(+), 17 deletions(-) diff --git a/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp b/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp index d65c940cd86f89..29e86eca9b5e0f 100644 --- a/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp +++ b/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp @@ -130,6 +130,30 @@ void setup() AP_Int8 *dual_mode = (AP_Int8*)motors + AP_MotorsHeli_Dual::var_info[1].offset; dual_mode->set(value); + } else if (strcmp(cmd,"tail_type") == 0) { + if (frame_class != AP_Motors::MOTOR_FRAME_HELI) { + ::printf("tail_type only supported by single heli frame type (%i), got %i\n", AP_Motors::MOTOR_FRAME_HELI, frame_class); + exit(1); + } + + // Union allows pointers to be aligned despite different sizes + // avoids "increases required alignment of target type" error when casting from char* to AP_Int16* + union { + char *char_ptr; + AP_Int16 *int16; + } tail_type; + + // look away now, more dodgy param access. + tail_type.char_ptr = (char*)motors + AP_MotorsHeli_Single::var_info[1].offset; + tail_type.int16->set(value); + + // Re-init motors to switch to the new tail type + // Have to do this twice to make sure the tail type sticks + motors->set_initialised_ok(false); + motors->init(frame_class, AP_Motors::MOTOR_FRAME_TYPE_X); + motors->set_initialised_ok(false); + motors->init(frame_class, AP_Motors::MOTOR_FRAME_TYPE_X); + } else if (strcmp(cmd,"frame_class") == 0) { // We must have the frame_class argument 2nd as resulting class is used to determine if // we have access to certain functions in the multicopter motors child class @@ -152,8 +176,13 @@ void setup() case AP_Motors::MOTOR_FRAME_HELI: motors = new AP_MotorsHeli_Single(400); - // Mot 1-3 swashplate, mot 4 tail rotor pitch, mot 5 for 4th servo in H4-90 swash - num_outputs = 5; + // Mot 1-3: Swash plate 1 to 3 + // Mot 4: Tail rotor + // Mot 5: 4th servo in H4-90 swash + // Mot 6: Unused + // Mot 7: Tail rotor RSC / external governor output + // Mot 8: Main rotor RSC + num_outputs = 8; break; case AP_Motors::MOTOR_FRAME_HELI_DUAL: diff --git a/libraries/AP_Motors/examples/AP_Motors_test/run_heli_comparison.py b/libraries/AP_Motors/examples/AP_Motors_test/run_heli_comparison.py index 118a5de193fcb0..7136c65fef806d 100644 --- a/libraries/AP_Motors/examples/AP_Motors_test/run_heli_comparison.py +++ b/libraries/AP_Motors/examples/AP_Motors_test/run_heli_comparison.py @@ -100,8 +100,15 @@ def get_fields(self): 1: 'Transverse', 2: 'Intermeshing_or_Coaxial'} +tail_type_lookup = {0: 'Servo_only', + 1: 'Servo_with_ExtGyro', + 2: 'DirectDrive_VarPitch', + 3: 'DirectDrive_FixedPitch_CW', + 4: 'DirectDrive_FixedPitch_CCW', + 5: 'DDVP_with_external_governor'} + # Run sweep over range of types -def run_sweep(frame_class, swash_type, dual_mode, dir_name): +def run_sweep(frame_class, swash_type, secondary_iter, secondary_lookup, secondary_name, dir_name): # configure and build the test os.system('./waf configure --board linux') @@ -110,28 +117,28 @@ def run_sweep(frame_class, swash_type, dual_mode, dir_name): # Run sweep for fc in frame_class: for swash in swash_type: - for mode in dual_mode: + for sec in secondary_iter: if swash is not None: swash_cmd = 'swash=%d' % swash - if mode is not None: - name = 'frame class = %s (%i), swash = %s (%i), dual mode = %s (%i)' % (frame_class_lookup[fc], fc, swash_type_lookup[swash], swash, dual_mode_lookup[mode], mode) - filename = '%s_%s_%s_motor_test.csv' % (frame_class_lookup[fc], swash_type_lookup[swash], dual_mode_lookup[mode]) - mode_cmd = 'dual_mode=%d' % mode + if sec is not None: + name = 'frame class = %s (%i), swash = %s (%i), %s = %s (%i)' % (frame_class_lookup[fc], fc, swash_type_lookup[swash], swash, secondary_name.replace('_', ' '), secondary_lookup[sec], sec) + filename = '%s_%s_%s_motor_test.csv' % (frame_class_lookup[fc], swash_type_lookup[swash], secondary_lookup[sec]) + sec_cmd = '%s=%d' % (secondary_name, sec) else: name = 'frame class = %s (%i), swash = %s (%i)' % (frame_class_lookup[fc], fc, swash_type_lookup[swash], swash) filename = '%s_%s_motor_test.csv' % (frame_class_lookup[fc], swash_type_lookup[swash]) - mode_cmd = '' + sec_cmd = '' else: name = 'frame class = %s (%i)' % (frame_class_lookup[fc], fc) filename = '%s_motor_test.csv' % (frame_class_lookup[fc]) swash_cmd = '' - mode_cmd = '' + sec_cmd = '' print('Running motors test for %s' % name) - os.system('./build/linux/examples/AP_Motors_test s frame_class=%d %s %s > %s/%s' % (fc, swash_cmd, mode_cmd, dir_name, filename)) + os.system('./build/linux/examples/AP_Motors_test s frame_class=%d %s %s > %s/%s' % (fc, swash_cmd, sec_cmd, dir_name, filename)) print('%s complete\n' % name) @@ -149,6 +156,7 @@ def run_sweep(frame_class, swash_type, dual_mode, dir_name): parser.add_argument("-c", "--compare", action='store_true', help='Compare only, do not re-run tests') parser.add_argument("-p", "--plot", action='store_true', help='Plot comparison results') parser.add_argument("-m", "--dual_mode", type=int, dest='dual_mode', help='Set DUAL_MODE, 0:Longitudinal, 1:Transverse, 2:Intermeshing/Coaxial, default:run all') + parser.add_argument("-t", "--tail_type", type=int, dest='tail_type', help='Set TAIL_TYPE, 0:Servo Only, 1:Servo with ExtGyro, 2:DirectDrive VarPitch, 3:DirectDrive FixedPitch CW, 4:DirectDrive FixedPitch CCW, 5:DDVP with external governor, default:run all') args = parser.parse_args() if 13 in args.frame_class: @@ -171,6 +179,30 @@ def run_sweep(frame_class, swash_type, dual_mode, dir_name): else: args.dual_mode = [None] + if (args.frame_class != [6]) and (args.tail_type is not None): + print('Only Frame %s (%i) supports tail_type' % (frame_class_lookup[6], 6)) + quit() + + if args.frame_class == [6]: + if args.tail_type is None: + args.tail_type = (0, 1, 2, 3, 4, 5) + else: + args.tail_type = [None] + + # Secondary iterator, tail type for single heli and dual mode for dual heli + secondary_iter = [None] + secondary_lookup = None + secondary_name = None + if args.dual_mode != [None]: + secondary_iter = args.dual_mode + secondary_lookup = dual_mode_lookup + secondary_name = 'dual_mode' + + elif args.tail_type != [None]: + secondary_iter = args.tail_type + secondary_lookup = tail_type_lookup + secondary_name = 'tail_type' + dir_name = 'motors_comparison' if not args.compare: @@ -185,7 +217,7 @@ def run_sweep(frame_class, swash_type, dual_mode, dir_name): print('\nRunning motor tests with current changes\n') # run the test - run_sweep(args.frame_class, args.swash_type, args.dual_mode, new_name) + run_sweep(args.frame_class, args.swash_type, secondary_iter, secondary_lookup, secondary_name, new_name) if args.head: # rewind head and repeat test @@ -237,14 +269,14 @@ def run_sweep(frame_class, swash_type, dual_mode, dir_name): # Print comparison for fc in args.frame_class: for sw in args.swash_type: - for dm in args.dual_mode: + for sec in secondary_iter: frame = frame_class_lookup[fc] if sw is not None: swash = swash_type_lookup[sw] - if dm is not None: - mode = dual_mode_lookup[dm] - name = frame + ' ' + swash + ' ' + mode - filename = '%s_%s_%s_motor_test.csv' % (frame, swash, mode) + if sec is not None: + sec_str = secondary_lookup[sec] + name = frame + ' ' + swash + ' ' + sec_str + filename = '%s_%s_%s_motor_test.csv' % (frame, swash, sec_str) else: name = frame + ' ' + swash From 6d546eed8f974c8ef26ebf3a8961e330669ce728 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 8 Dec 2023 20:16:10 +0000 Subject: [PATCH 0048/1335] AP_Motors: Example: allow setting of COL2YAW and autorotation flag --- .../AP_Motors_test/AP_Motors_test.cpp | 33 +++++++++++++++++-- 1 file changed, 30 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp b/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp index 29e86eca9b5e0f..491bb0fc60bff6 100644 --- a/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp +++ b/libraries/AP_Motors/examples/AP_Motors_test/AP_Motors_test.cpp @@ -38,6 +38,7 @@ SRV_Channels srvs; AP_BattMonitor _battmonitor{0, nullptr, nullptr}; AP_Motors *motors; +AP_MotorsHeli *motors_heli; AP_MotorsMatrix *motors_matrix; bool thrust_boost = false; @@ -175,7 +176,8 @@ void setup() break; case AP_Motors::MOTOR_FRAME_HELI: - motors = new AP_MotorsHeli_Single(400); + motors_heli = new AP_MotorsHeli_Single(400); + motors = motors_heli; // Mot 1-3: Swash plate 1 to 3 // Mot 4: Tail rotor // Mot 5: 4th servo in H4-90 swash @@ -186,13 +188,15 @@ void setup() break; case AP_Motors::MOTOR_FRAME_HELI_DUAL: - motors = new AP_MotorsHeli_Dual(400); + motors_heli = new AP_MotorsHeli_Dual(400); + motors = motors_heli; // Mot 1-3 swashplate 1, mot 4-6 swashplate 2, mot 7 and 8 for 4th servos on H4-90 swash plates front and back, respectively num_outputs = 8; break; case AP_Motors::MOTOR_FRAME_HELI_QUAD: - motors = new AP_MotorsHeli_Quad(400); + motors_heli = new AP_MotorsHeli_Quad(400); + motors = motors_heli; num_outputs = 4; // Only 4 collective servos break; @@ -215,6 +219,29 @@ void setup() exit(1); } + } else if (strcmp(cmd,"COL2YAW") == 0) { + if (frame_class != AP_Motors::MOTOR_FRAME_HELI) { + ::printf("COL2YAW only supported by single heli frame type (%i), got %i\n", AP_Motors::MOTOR_FRAME_HELI, frame_class); + exit(1); + } + + // Union allows pointers to be aligned despite different sizes + // avoids "increases required alignment of target type" error when casting from char* to AP_Int16* + union { + char *char_ptr; + AP_Float *ap_float; + } collective_yaw_scale; + + collective_yaw_scale.char_ptr = (char*)motors + AP_MotorsHeli_Single::var_info[7].offset; + collective_yaw_scale.ap_float->set(value); + + } else if (strcmp(cmd,"autorotation") == 0) { + if (motors_heli == nullptr) { + ::printf("autorotation only supported by heli frame types, got %i\n", frame_class); + exit(1); + } + motors_heli->set_in_autorotation(!is_zero(value)); + } else { ::printf("Expected \"frame_class\", \"yaw_headroom\" or \"throttle_avg_max\"\n"); exit(1); From e48b7cea12216be0423a21b2bd09aa8e62a565b8 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Wed, 6 Dec 2023 10:37:33 +1030 Subject: [PATCH 0049/1335] Copter: Use RTL_CLIMB_MIN in cone slope. --- ArduCopter/config.h | 4 ---- ArduCopter/mode_rtl.cpp | 6 +++--- 2 files changed, 3 insertions(+), 7 deletions(-) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index 329678e1b889ca..ace8cc43f2edc3 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -433,10 +433,6 @@ # define RTL_CLIMB_MIN_DEFAULT 0 // vehicle will always climb this many cm as first stage of RTL #endif -#ifndef RTL_ABS_MIN_CLIMB - # define RTL_ABS_MIN_CLIMB 250 // absolute minimum initial climb -#endif - #ifndef RTL_CONE_SLOPE_DEFAULT # define RTL_CONE_SLOPE_DEFAULT 3.0f // slope of RTL cone (height / distance). 0 = No cone #endif diff --git a/ArduCopter/mode_rtl.cpp b/ArduCopter/mode_rtl.cpp index 7c74838a3fe742..a8421d9009741e 100644 --- a/ArduCopter/mode_rtl.cpp +++ b/ArduCopter/mode_rtl.cpp @@ -483,14 +483,14 @@ void ModeRTL::compute_return_target() int32_t target_alt = MAX(rtl_path.return_target.alt, 0); // increase target to maximum of current altitude + climb_min and rtl altitude - target_alt = MAX(target_alt, curr_alt + MAX(0, g.rtl_climb_min)); - target_alt = MAX(target_alt, MAX(g.rtl_altitude, RTL_ALT_MIN)); + const float min_rtl_alt = MAX(RTL_ALT_MIN, curr_alt + MAX(0, g.rtl_climb_min)); + target_alt = MAX(target_alt, MAX(g.rtl_altitude, min_rtl_alt)); // reduce climb if close to return target float rtl_return_dist_cm = rtl_path.return_target.get_distance(rtl_path.origin_point) * 100.0f; // don't allow really shallow slopes if (g.rtl_cone_slope >= RTL_MIN_CONE_SLOPE) { - target_alt = MAX(curr_alt, MIN(target_alt, MAX(rtl_return_dist_cm*g.rtl_cone_slope, curr_alt+RTL_ABS_MIN_CLIMB))); + target_alt = MIN(target_alt, MAX(rtl_return_dist_cm * g.rtl_cone_slope, min_rtl_alt)); } // set returned target alt to new target_alt (don't change altitude type) From 782605e7ea60c3ff15e15b62cb94056049599bf1 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 5 Dec 2023 13:32:45 +0000 Subject: [PATCH 0050/1335] AP_Scripting: CANSensor: Add filtering of incoming frames Co-authored-by: Andras Schaffer --- .../AP_Scripting/AP_Scripting_CANSensor.cpp | 35 ++++++++++++++++++- .../AP_Scripting/AP_Scripting_CANSensor.h | 9 +++++ libraries/AP_Scripting/docs/docs.lua | 8 +++++ libraries/AP_Scripting/examples/CAN_read.lua | 5 +++ .../generator/description/bindings.desc | 2 +- 5 files changed, 57 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Scripting/AP_Scripting_CANSensor.cpp b/libraries/AP_Scripting/AP_Scripting_CANSensor.cpp index d3b0ab23756535..39f1bf9f870a09 100644 --- a/libraries/AP_Scripting/AP_Scripting_CANSensor.cpp +++ b/libraries/AP_Scripting/AP_Scripting_CANSensor.cpp @@ -16,6 +16,7 @@ Scripting CANSensor class, for easy scripting CAN support */ #include "AP_Scripting_CANSensor.h" +#include #if AP_SCRIPTING_CAN_SENSOR_ENABLED @@ -62,8 +63,25 @@ bool ScriptingCANBuffer::read_frame(AP_HAL::CANFrame &frame) // recursively add frame to buffer void ScriptingCANBuffer::handle_frame(AP_HAL::CANFrame &frame) { + // accept everything if no filters are setup + bool accept = num_filters == 0; + + // Check if frame matches any filters + for (uint8_t i = 0; i < MIN(num_filters, ARRAY_SIZE(filter)); i++) { + if ((frame.id & filter[i].mask) == filter[i].value) { + accept = true; + break; + } + } + WITH_SEMAPHORE(sem); - buffer.push(frame); + + // Add to buffer for scripting to read + if (accept) { + buffer.push(frame); + } + + // filtering is not applied to other buffers if (next != nullptr) { next->handle_frame(frame); } @@ -79,4 +97,19 @@ void ScriptingCANBuffer::add_buffer(ScriptingCANBuffer* new_buff) { next->add_buffer(new_buff); } +// Add a filter, will pass ID's that match value given the mask +bool ScriptingCANBuffer::add_filter(uint32_t mask, uint32_t value) { + + // Run out of filters + if (num_filters >= ARRAY_SIZE(filter)) { + return false; + } + + // Add to list and increment + filter[num_filters].mask = mask; + filter[num_filters].value = value & mask; + num_filters++; + return true; +} + #endif // AP_SCRIPTING_CAN_SENSOR_ENABLED diff --git a/libraries/AP_Scripting/AP_Scripting_CANSensor.h b/libraries/AP_Scripting/AP_Scripting_CANSensor.h index b6f19d28d83e7b..962aef8fbfa5f2 100644 --- a/libraries/AP_Scripting/AP_Scripting_CANSensor.h +++ b/libraries/AP_Scripting/AP_Scripting_CANSensor.h @@ -74,6 +74,9 @@ class ScriptingCANBuffer { // recursively add new buffer void add_buffer(ScriptingCANBuffer* new_buff); + // Add a filter to this buffer + bool add_filter(uint32_t mask, uint32_t value); + private: ObjectBuffer buffer; @@ -84,6 +87,12 @@ class ScriptingCANBuffer { HAL_Semaphore sem; + struct { + uint32_t mask; + uint32_t value; + } filter[8]; + uint8_t num_filters; + }; #endif // AP_SCRIPTING_CAN_SENSOR_ENABLED diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index 1d57957c7b0e30..7e3be1f487dba4 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -1057,6 +1057,14 @@ local ScriptingCANBuffer_ud = {} ---@return CANFrame_ud|nil function ScriptingCANBuffer_ud:read_frame() end +-- Add a filter to the CAN buffer, mask is bitwise ANDed with the frame id and compared to value if not match frame is not buffered +-- By default no filters are added and all frames are buffered, write is not affected by filters +-- Maximum number of filters is 8 +---@param mask uint32_t_ud +---@param value uint32_t_ud +---@return boolean -- returns true if the filler was added successfully +function ScriptingCANBuffer_ud:add_filter(mask, value) end + -- desc ---@param frame CANFrame_ud ---@param timeout_us uint32_t_ud diff --git a/libraries/AP_Scripting/examples/CAN_read.lua b/libraries/AP_Scripting/examples/CAN_read.lua index ca310faf3e0e47..789f9e32002f4d 100644 --- a/libraries/AP_Scripting/examples/CAN_read.lua +++ b/libraries/AP_Scripting/examples/CAN_read.lua @@ -10,6 +10,11 @@ if not driver1 and not driver2 then return end +-- Only accept DroneCAN node status msg on second driver +-- node status is message ID 341 +-- Message ID is 16 bits left shifted by 8 in the CAN frame ID. +driver2:add_filter(uint32_t(0xFFFF) << 8, uint32_t(341) << 8) + function show_frame(dnum, frame) gcs:send_text(0,string.format("CAN[%u] msg from " .. tostring(frame:id()) .. ": %i, %i, %i, %i, %i, %i, %i, %i", dnum, frame:data(0), frame:data(1), frame:data(2), frame:data(3), frame:data(4), frame:data(5), frame:data(6), frame:data(7))) end diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index 74cc6c109de8e3..7ddc378d843fdc 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -620,7 +620,7 @@ userdata AP_HAL::CANFrame method isErrorFrame boolean ap_object ScriptingCANBuffer depends AP_SCRIPTING_CAN_SENSOR_ENABLED ap_object ScriptingCANBuffer method write_frame boolean AP_HAL::CANFrame uint32_t'skip_check ap_object ScriptingCANBuffer method read_frame boolean AP_HAL::CANFrame'Null - +ap_object ScriptingCANBuffer method add_filter boolean uint32_t'skip_check uint32_t'skip_check include ../Tools/AP_Periph/AP_Periph.h depends defined(HAL_BUILD_AP_PERIPH) singleton AP_Periph_FW depends defined(HAL_BUILD_AP_PERIPH) From c93fd0b5347b0aabb4aad0b7b6f15df541ee8ebf Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Wed, 6 Dec 2023 17:17:12 +0000 Subject: [PATCH 0051/1335] Tools: new standard tunes for Holybro QAV250 and X500v2 --- .../Frame_params/Holybro-QAV250-bdshot.param | 55 +++++++++++++++++++ Tools/Frame_params/Holybro-QAV250.param | 54 ++++++++++++++++++ .../Frame_params/Holybro-X500v2-bdshot.param | 44 +++++++++++++++ 3 files changed, 153 insertions(+) create mode 100644 Tools/Frame_params/Holybro-QAV250-bdshot.param create mode 100644 Tools/Frame_params/Holybro-QAV250.param create mode 100644 Tools/Frame_params/Holybro-X500v2-bdshot.param diff --git a/Tools/Frame_params/Holybro-QAV250-bdshot.param b/Tools/Frame_params/Holybro-QAV250-bdshot.param new file mode 100644 index 00000000000000..5ee424b27b2c96 --- /dev/null +++ b/Tools/Frame_params/Holybro-QAV250-bdshot.param @@ -0,0 +1,55 @@ +ANGLE_MAX 7500 +ATC_ACCEL_P_MAX 247932.2 +ATC_ACCEL_R_MAX 280459.7 +ATC_ACCEL_Y_MAX 70449.61 +ATC_ANG_PIT_P 20.62971 +ATC_ANG_RLL_P 21.77228 +ATC_ANG_YAW_P 12.07662 +ATC_RAT_PIT_D 0.001443983 +ATC_RAT_PIT_FLTD 40 +ATC_RAT_PIT_FLTT 40 +ATC_RAT_PIT_I 0.05448329 +ATC_RAT_PIT_P 0.05448329 +ATC_RAT_PIT_SMAX 30 +ATC_RAT_RLL_D 0.001218464 +ATC_RAT_RLL_FLTD 40 +ATC_RAT_RLL_FLTT 40 +ATC_RAT_RLL_I 0.03652912 +ATC_RAT_RLL_P 0.03652912 +ATC_RAT_RLL_SMAX 30 +ATC_RAT_YAW_D 0.004205064 +ATC_RAT_YAW_FLTD 20 +ATC_RAT_YAW_FLTE 2 +ATC_RAT_YAW_I 0.02155114 +ATC_RAT_YAW_P 0.2155114 +ATC_RAT_YAW_SMAX 30 +INS_HNTC2_ATT 40 +INS_HNTC2_BW 8 +INS_HNTC2_ENABLE 1 +INS_HNTC2_FM_RAT 1 +INS_HNTC2_FREQ 47 +INS_HNTC2_HMNCS 3 +INS_HNTC2_MODE 1 +INS_HNTC2_OPTS 16 +INS_HNTC2_REF 1 +INS_HNTCH_ATT 40 +INS_HNTCH_BW 20 +INS_HNTCH_ENABLE 1 +INS_HNTCH_FM_RAT 1 +INS_HNTCH_FREQ 80 +INS_HNTCH_HMNCS 1 +INS_HNTCH_MODE 3 +INS_HNTCH_OPTS 22 +INS_HNTCH_REF 1 +MOT_BAT_VOLT_MAX 16.8 +MOT_BAT_VOLT_MIN 13.2 +MOT_PWM_TYPE 6 +MOT_SPIN_ARM 0.06 +MOT_SPIN_MIN 0.08 +MOT_THST_EXPO 0.55 +MOT_THST_HOVER 0.125 +PSC_ACCZ_I 0.168 +PSC_ACCZ_P 0.084 +SERVO_BLH_AUTO 1 +SERVO_DSHOT_ESC 2 +SERVO_DSHOT_RATE 3 diff --git a/Tools/Frame_params/Holybro-QAV250.param b/Tools/Frame_params/Holybro-QAV250.param new file mode 100644 index 00000000000000..af5072de6d9038 --- /dev/null +++ b/Tools/Frame_params/Holybro-QAV250.param @@ -0,0 +1,54 @@ +ANGLE_MAX 7500 +ATC_ACCEL_P_MAX 278477.8 +ATC_ACCEL_R_MAX 344115.3 +ATC_ACCEL_Y_MAX 51274.09 +ATC_ANG_PIT_P 25.66075 +ATC_ANG_RLL_P 28.50734 +ATC_ANG_YAW_P 8.258418 +ATC_RAT_PIT_D 0.001949416 +ATC_RAT_PIT_FLTD 40 +ATC_RAT_PIT_FLTT 40 +ATC_RAT_PIT_I 0.07421205 +ATC_RAT_PIT_P 0.07421205 +ATC_RAT_PIT_SMAX 30 +ATC_RAT_RLL_D 0.00120043 +ATC_RAT_RLL_FLTD 40 +ATC_RAT_RLL_FLTT 40 +ATC_RAT_RLL_I 0.04598495 +ATC_RAT_RLL_P 0.04598495 +ATC_RAT_RLL_SMAX 30 +ATC_RAT_YAW_D 0.009076501 +ATC_RAT_YAW_FLTD 40 +ATC_RAT_YAW_FLTE 1.3176 +ATC_RAT_YAW_I 0.02884508 +ATC_RAT_YAW_P 0.2884507 +ATC_RAT_YAW_SMAX 30 +INS_HNTC2_ATT 40 +INS_HNTC2_BW 8 +INS_HNTC2_ENABLE 1 +INS_HNTC2_FM_RAT 1 +INS_HNTC2_FREQ 47 +INS_HNTC2_HMNCS 1 +INS_HNTC2_MODE 1 +INS_HNTC2_OPTS 16 +INS_HNTC2_REF 1 +INS_HNTCH_ATT 40 +INS_HNTCH_BW 75 +INS_HNTCH_ENABLE 1 +INS_HNTCH_FM_RAT 0.7 +INS_HNTCH_FREQ 150 +INS_HNTCH_HMNCS 3 +INS_HNTCH_MODE 1 +INS_HNTCH_OPTS 0 +INS_HNTCH_REF 0.125 +MOT_BAT_VOLT_MAX 16.8 +MOT_BAT_VOLT_MIN 13.2 +MOT_PWM_TYPE 5 +MOT_SPIN_ARM 0.06 +MOT_SPIN_MIN 0.08 +MOT_THST_EXPO 0.55 +MOT_THST_HOVER 0.125 +PSC_ACCZ_I 0.168 +PSC_ACCZ_P 0.084 +SERVO_DSHOT_ESC 2 +SERVO_DSHOT_RATE 3 diff --git a/Tools/Frame_params/Holybro-X500v2-bdshot.param b/Tools/Frame_params/Holybro-X500v2-bdshot.param new file mode 100644 index 00000000000000..51f8733d21b439 --- /dev/null +++ b/Tools/Frame_params/Holybro-X500v2-bdshot.param @@ -0,0 +1,44 @@ +ANGLE_MAX 3500 +ATC_ACCEL_P_MAX 165167.5 +ATC_ACCEL_R_MAX 176726.4 +ATC_ACCEL_Y_MAX 35955.46 +ATC_ANG_PIT_P 21.2236 +ATC_ANG_RLL_P 26.35878 +ATC_ANG_YAW_P 8.53887 +ATC_RAT_PIT_D 0.005201788 +ATC_RAT_PIT_FLTD 21 +ATC_RAT_PIT_FLTT 21 +ATC_RAT_PIT_I 0.1466683 +ATC_RAT_PIT_P 0.1466683 +ATC_RAT_RLL_D 0.004905871 +ATC_RAT_RLL_FLTD 21 +ATC_RAT_RLL_FLTT 21 +ATC_RAT_RLL_I 0.1255951 +ATC_RAT_RLL_P 0.1255951 +ATC_RAT_YAW_D 0.02224096 +ATC_RAT_YAW_FLTD 10 +ATC_RAT_YAW_FLTE 1.3176 +ATC_RAT_YAW_FLTT 21 +ATC_RAT_YAW_I 0.1204564 +ATC_RAT_YAW_P 1.204564 +INS_HNTCH_ATT 40 +INS_HNTCH_BW 40 +INS_HNTCH_ENABLE 1 +INS_HNTCH_FM_RAT 1 +INS_HNTCH_FREQ 80 +INS_HNTCH_HMNCS 3 +INS_HNTCH_MODE 3 +INS_HNTCH_OPTS 22 +INS_HNTCH_REF 1 +MOT_BAT_VOLT_MAX 16.8 +MOT_BAT_VOLT_MIN 13.2 +MOT_SPIN_ARM 0.07 +MOT_SPIN_MIN 0.09 +MOT_THST_HOVER 0.2905434 +PSC_ACCZ_I 0.6 +PSC_ACCZ_P 0.3 +SERVO_BLH_AUTO 1 +SERVO_BLH_MASK 3840 +SERVO_BLH_OTYPE 5 +SERVO_DSHOT_ESC 2 +TKOFF_RPM_MIN 1000 From e95b1e5dd31acc546f334ba53be31c9f28038f7b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 8 Dec 2023 11:03:15 +1100 Subject: [PATCH 0052/1335] AC_AutoTune: add and use header guards --- libraries/AC_AutoTune/AC_AutoTune.cpp | 5 +++++ libraries/AC_AutoTune/AC_AutoTune.h | 6 ++++++ libraries/AC_AutoTune/AC_AutoTune_Heli.cpp | 6 ++++++ libraries/AC_AutoTune/AC_AutoTune_Heli.h | 6 ++++++ libraries/AC_AutoTune/AC_AutoTune_Multi.cpp | 6 ++++++ libraries/AC_AutoTune/AC_AutoTune_Multi.h | 6 ++++++ libraries/AC_AutoTune/AC_AutoTune_config.h | 7 +++++++ 7 files changed, 42 insertions(+) create mode 100644 libraries/AC_AutoTune/AC_AutoTune_config.h diff --git a/libraries/AC_AutoTune/AC_AutoTune.cpp b/libraries/AC_AutoTune/AC_AutoTune.cpp index 1e672f2e325505..3c081f31488f11 100644 --- a/libraries/AC_AutoTune/AC_AutoTune.cpp +++ b/libraries/AC_AutoTune/AC_AutoTune.cpp @@ -1,3 +1,7 @@ +#include "AC_AutoTune_config.h" + +#if AC_AUTOTUNE_ENABLED + #include "AC_AutoTune.h" #include @@ -757,3 +761,4 @@ void AC_AutoTune::next_tune_type(TuneType &curr_tune_type, bool reset) curr_tune_type = tune_seq[tune_seq_curr]; } +#endif // AC_AUTOTUNE_ENABLED diff --git a/libraries/AC_AutoTune/AC_AutoTune.h b/libraries/AC_AutoTune/AC_AutoTune.h index e152af499993f8..a901b50e06b692 100644 --- a/libraries/AC_AutoTune/AC_AutoTune.h +++ b/libraries/AC_AutoTune/AC_AutoTune.h @@ -18,6 +18,10 @@ */ #pragma once +#include "AC_AutoTune_config.h" + +#if AC_AUTOTUNE_ENABLED + #include #include #include @@ -327,3 +331,5 @@ class AC_AutoTune uint32_t last_pilot_override_warning; }; + +#endif // AC_AUTOTUNE_ENABLED diff --git a/libraries/AC_AutoTune/AC_AutoTune_Heli.cpp b/libraries/AC_AutoTune/AC_AutoTune_Heli.cpp index d72a6db6fe4c09..0defc67f671503 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_Heli.cpp +++ b/libraries/AC_AutoTune/AC_AutoTune_Heli.cpp @@ -17,6 +17,10 @@ Converted to a library by Andrew Tridgell, and rewritten to include helicopters by Bill Geyer */ +#include "AC_AutoTune_config.h" + +#if AC_AUTOTUNE_ENABLED + #include "AC_AutoTune_Heli.h" #include @@ -1941,3 +1945,5 @@ bool AC_AutoTune_Heli::exceeded_freq_range(float frequency) } return ret; } + +#endif // AC_AUTOTUNE_ENABLED diff --git a/libraries/AC_AutoTune/AC_AutoTune_Heli.h b/libraries/AC_AutoTune/AC_AutoTune_Heli.h index 6329563b02bae7..5da4dc658182e9 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_Heli.h +++ b/libraries/AC_AutoTune/AC_AutoTune_Heli.h @@ -18,6 +18,10 @@ #pragma once +#include "AC_AutoTune_config.h" + +#if AC_AUTOTUNE_ENABLED + #include "AC_AutoTune.h" #include #include @@ -296,3 +300,5 @@ class AC_AutoTune_Heli : public AC_AutoTune Chirp chirp_input; }; + +#endif // AC_AUTOTUNE_ENABLED diff --git a/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp b/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp index bf988c187ae9f2..c8ff8cc4114b3e 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp +++ b/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp @@ -1,3 +1,7 @@ +#include "AC_AutoTune_config.h" + +#if AC_AUTOTUNE_ENABLED + #include "AC_AutoTune_Multi.h" #include @@ -1246,3 +1250,5 @@ uint32_t AC_AutoTune_Multi::get_testing_step_timeout_ms() const return AUTOTUNE_TESTING_STEP_TIMEOUT_MS; } + +#endif // AC_AUTOTUNE_ENABLED diff --git a/libraries/AC_AutoTune/AC_AutoTune_Multi.h b/libraries/AC_AutoTune/AC_AutoTune_Multi.h index b2a02fcdc6bce8..c199c18ca2dc9b 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_Multi.h +++ b/libraries/AC_AutoTune/AC_AutoTune_Multi.h @@ -19,6 +19,10 @@ #pragma once +#include "AC_AutoTune_config.h" + +#if AC_AUTOTUNE_ENABLED + #include "AC_AutoTune.h" class AC_AutoTune_Multi : public AC_AutoTune @@ -168,3 +172,5 @@ class AC_AutoTune_Multi : public AC_AutoTune AP_Float aggressiveness; // aircraft response aggressiveness to be tuned AP_Float min_d; // minimum rate d gain allowed during tuning }; + +#endif // AC_AUTOTUNE_ENABLED diff --git a/libraries/AC_AutoTune/AC_AutoTune_config.h b/libraries/AC_AutoTune/AC_AutoTune_config.h new file mode 100644 index 00000000000000..ae2b22b712205b --- /dev/null +++ b/libraries/AC_AutoTune/AC_AutoTune_config.h @@ -0,0 +1,7 @@ +#pragma once + +#include + +#ifndef AC_AUTOTUNE_ENABLED +#define AC_AUTOTUNE_ENABLED 1 +#endif From 03218b11acb41796579dc669d2541f3ebf473e28 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 8 Dec 2023 13:02:40 +1100 Subject: [PATCH 0053/1335] AP_MSP: add and use AP_RSSI_ENABLED --- libraries/AP_MSP/AP_MSP_Telem_Backend.cpp | 5 +++++ libraries/AP_MSP/AP_MSP_Telem_DJI.cpp | 4 ++++ 2 files changed, 9 insertions(+) diff --git a/libraries/AP_MSP/AP_MSP_Telem_Backend.cpp b/libraries/AP_MSP/AP_MSP_Telem_Backend.cpp index ee01834cb19d6f..2f4fe9c63bb188 100644 --- a/libraries/AP_MSP/AP_MSP_Telem_Backend.cpp +++ b/libraries/AP_MSP/AP_MSP_Telem_Backend.cpp @@ -1261,6 +1261,7 @@ bool AP_MSP_Telem_Backend::displaying_stats_screen() const bool AP_MSP_Telem_Backend::get_rssi(float &rssi) const { +#if AP_RSSI_ENABLED AP_RSSI* ap_rssi = AP::rssi(); if (ap_rssi == nullptr) { return false; @@ -1270,5 +1271,9 @@ bool AP_MSP_Telem_Backend::get_rssi(float &rssi) const } rssi = ap_rssi->read_receiver_rssi(); // range is [0-1] return true; +#else + return false; +#endif } + #endif //HAL_MSP_ENABLED diff --git a/libraries/AP_MSP/AP_MSP_Telem_DJI.cpp b/libraries/AP_MSP/AP_MSP_Telem_DJI.cpp index fcb3108c71609b..bafa921bd0263c 100644 --- a/libraries/AP_MSP/AP_MSP_Telem_DJI.cpp +++ b/libraries/AP_MSP/AP_MSP_Telem_DJI.cpp @@ -224,6 +224,7 @@ bool AP_MSP_Telem_DJI::get_rssi(float &rssi) const if (!displaying_stats_screen()) { return true; } +#if AP_RSSI_ENABLED AP_RSSI* ap_rssi = AP::rssi(); if (ap_rssi == nullptr) { return false; @@ -231,6 +232,9 @@ bool AP_MSP_Telem_DJI::get_rssi(float &rssi) const if (!ap_rssi->enabled()) { return false; } +#else + return false; +#endif AP_OSD *osd = AP::osd(); if (osd == nullptr) { return false; From b2a12f406f15af34a65aa87176f7a0681dd0cc5c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 8 Dec 2023 13:02:40 +1100 Subject: [PATCH 0054/1335] AP_OSD: add and use AP_RSSI_ENABLED --- libraries/AP_OSD/AP_OSD.cpp | 2 ++ libraries/AP_OSD/AP_OSD_Screen.cpp | 2 ++ 2 files changed, 4 insertions(+) diff --git a/libraries/AP_OSD/AP_OSD.cpp b/libraries/AP_OSD/AP_OSD.cpp index d4284cc7208981..8034e0ee92b111 100644 --- a/libraries/AP_OSD/AP_OSD.cpp +++ b/libraries/AP_OSD/AP_OSD.cpp @@ -457,11 +457,13 @@ void AP_OSD::update_stats() if (voltage > 0) { _stats.min_voltage_v = fminf(_stats.min_voltage_v, voltage); } +#if AP_RSSI_ENABLED // minimum rssi AP_RSSI *ap_rssi = AP_RSSI::get_singleton(); if (ap_rssi) { _stats.min_rssi = fminf(_stats.min_rssi, ap_rssi->read_receiver_rssi()); } +#endif // max airspeed either true or synthetic if (have_airspeed_estimate) { _stats.max_airspeed_mps = fmaxf(_stats.max_airspeed_mps, aspd_mps); diff --git a/libraries/AP_OSD/AP_OSD_Screen.cpp b/libraries/AP_OSD/AP_OSD_Screen.cpp index cdc0e2a59a9c19..c63a481417b3d7 100644 --- a/libraries/AP_OSD/AP_OSD_Screen.cpp +++ b/libraries/AP_OSD/AP_OSD_Screen.cpp @@ -1410,6 +1410,7 @@ void AP_OSD_Screen::draw_restvolt(uint8_t x, uint8_t y) draw_bat_volt(0,VoltageType::RESTING_VOLTAGE,x,y); } +#if AP_RSSI_ENABLED void AP_OSD_Screen::draw_rssi(uint8_t x, uint8_t y) { AP_RSSI *ap_rssi = AP_RSSI::get_singleton(); @@ -1431,6 +1432,7 @@ void AP_OSD_Screen::draw_link_quality(uint8_t x, uint8_t y) } } } +#endif // AP_RSSI_ENABLED void AP_OSD_Screen::draw_current(uint8_t instance, uint8_t x, uint8_t y) { From b7710a78d8e1714c2e0ab9306e6384a0007fef94 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 8 Dec 2023 13:02:40 +1100 Subject: [PATCH 0055/1335] AP_RSSI: add and use AP_RSSI_ENABLED --- libraries/AP_RSSI/AP_RSSI.cpp | 6 ++++++ libraries/AP_RSSI/AP_RSSI.h | 6 ++++++ libraries/AP_RSSI/AP_RSSI_config.h | 7 +++++++ 3 files changed, 19 insertions(+) create mode 100644 libraries/AP_RSSI/AP_RSSI_config.h diff --git a/libraries/AP_RSSI/AP_RSSI.cpp b/libraries/AP_RSSI/AP_RSSI.cpp index 883ae2662e0682..033e6122b76795 100644 --- a/libraries/AP_RSSI/AP_RSSI.cpp +++ b/libraries/AP_RSSI/AP_RSSI.cpp @@ -13,6 +13,10 @@ along with this program. If not, see . */ +#include "AP_RSSI_config.h" + +#if AP_RSSI_ENABLED + #include #include #include @@ -272,3 +276,5 @@ AP_RSSI *rssi() } }; + +#endif // AP_RSSI_ENABLED diff --git a/libraries/AP_RSSI/AP_RSSI.h b/libraries/AP_RSSI/AP_RSSI.h index f46438480013df..20f0db1b39ffb1 100644 --- a/libraries/AP_RSSI/AP_RSSI.h +++ b/libraries/AP_RSSI/AP_RSSI.h @@ -14,6 +14,10 @@ */ #pragma once +#include "AP_RSSI_config.h" + +#if AP_RSSI_ENABLED + #include #include #include @@ -102,3 +106,5 @@ class AP_RSSI namespace AP { AP_RSSI *rssi(); }; + +#endif // AP_RSSI_ENABLED diff --git a/libraries/AP_RSSI/AP_RSSI_config.h b/libraries/AP_RSSI/AP_RSSI_config.h new file mode 100644 index 00000000000000..28f6e724f40656 --- /dev/null +++ b/libraries/AP_RSSI/AP_RSSI_config.h @@ -0,0 +1,7 @@ +#pragma once + +#include + +#ifndef AP_RSSI_ENABLED +#define AP_RSSI_ENABLED 1 +#endif From b0b94f50edf24a188069f14e68b0d8022829b4a2 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 8 Dec 2023 13:02:40 +1100 Subject: [PATCH 0056/1335] AP_Vehicle: add and use AP_RSSI_ENABLED --- libraries/AP_Vehicle/AP_Vehicle.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AP_Vehicle/AP_Vehicle.h b/libraries/AP_Vehicle/AP_Vehicle.h index 1b12f3505c3124..38e65f071fb4ab 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.h +++ b/libraries/AP_Vehicle/AP_Vehicle.h @@ -301,7 +301,10 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { #endif RangeFinder rangefinder; +#if AP_RSSI_ENABLED AP_RSSI rssi; +#endif + #if HAL_RUNCAM_ENABLED AP_RunCam runcam; #endif From dcebd072be28607f57e687d731fd3cc1f51a5e9d Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 8 Dec 2023 13:10:37 +1100 Subject: [PATCH 0057/1335] AC_AttitudeControl: correct compilation when GCS library not available --- libraries/AC_AttitudeControl/AC_WeatherVane.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AC_AttitudeControl/AC_WeatherVane.cpp b/libraries/AC_AttitudeControl/AC_WeatherVane.cpp index 087f4b2274c51d..7c0e6b81547105 100644 --- a/libraries/AC_AttitudeControl/AC_WeatherVane.cpp +++ b/libraries/AC_AttitudeControl/AC_WeatherVane.cpp @@ -219,7 +219,8 @@ bool AC_WeatherVane::get_yaw_out(float &yaw_output, const int16_t pilot_yaw, con } if (!active_msg_sent) { - gcs().send_text(MAV_SEVERITY_INFO, "Weathervane Active: %s", dir_string); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Weathervane Active: %s", dir_string); + (void)dir_string; // in case GCS is disabled active_msg_sent = true; } From 87c0543d9fb0279b04731e9d5018f463bdb32e8f Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 8 Dec 2023 13:10:37 +1100 Subject: [PATCH 0058/1335] AP_Arming: correct compilation when GCS library not available --- libraries/AP_Arming/AP_Arming.cpp | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index b617c6d134c491..bbfcaf73519319 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -244,6 +244,7 @@ void AP_Arming::check_failed(const enum AP_Arming::ArmingChecks check, bool repo } hal.util->snprintf(taggedfmt, sizeof(taggedfmt), metafmt, fmt); +#if HAL_GCS_ENABLED MAV_SEVERITY severity = MAV_SEVERITY_CRITICAL; if (!check_enabled(check)) { // technically should be NOTICE, but will annoy users at that level: @@ -253,10 +254,12 @@ void AP_Arming::check_failed(const enum AP_Arming::ArmingChecks check, bool repo va_start(arg_list, fmt); gcs().send_textv(severity, taggedfmt, arg_list); va_end(arg_list); +#endif // HAL_GCS_ENABLED } void AP_Arming::check_failed(bool report, const char *fmt, ...) const { +#if HAL_GCS_ENABLED if (!report) { return; } @@ -275,6 +278,7 @@ void AP_Arming::check_failed(bool report, const char *fmt, ...) const va_start(arg_list, fmt); gcs().send_textv(MAV_SEVERITY_CRITICAL, taggedfmt, arg_list); va_end(arg_list); +#endif // HAL_GCS_ENABLED } bool AP_Arming::barometer_checks(bool report) @@ -1656,7 +1660,7 @@ bool AP_Arming::arm(AP_Arming::Method method, const bool do_arming_checks) running_arming_checks = false; if (armed && do_arming_checks && checks_to_perform == 0) { - gcs().send_text(MAV_SEVERITY_WARNING, "Warning: Arming Checks Disabled"); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Warning: Arming Checks Disabled"); } #if HAL_GYROFFT_ENABLED @@ -1685,7 +1689,7 @@ bool AP_Arming::arm(AP_Arming::Method method, const bool do_arming_checks) // If a fence is set to auto-enable, turn on the fence if (fence->auto_enabled() == AC_Fence::AutoEnable::ONLY_WHEN_ARMED) { fence->enable(true); - gcs().send_text(MAV_SEVERITY_INFO, "Fence: auto-enabled"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Fence: auto-enabled"); } } } @@ -1752,7 +1756,7 @@ void AP_Arming::send_arm_disarm_statustext(const char *str) const if (option_enabled(AP_Arming::Option::DISABLE_STATUSTEXT_ON_STATE_CHANGE)) { return; } - gcs().send_text(MAV_SEVERITY_INFO, "%s", str); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s", str); } AP_Arming::Required AP_Arming::arming_required() const From 6df3f184407362dbbaa9ebfb87dbe101688326aa Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 8 Dec 2023 13:10:37 +1100 Subject: [PATCH 0059/1335] AP_Landing: correct compilation when GCS library not available --- libraries/AP_Landing/AP_Landing.cpp | 10 +++++----- libraries/AP_Landing/AP_Landing_Deepstall.cpp | 20 +++++++++---------- libraries/AP_Landing/AP_Landing_Slope.cpp | 14 ++++++------- 3 files changed, 22 insertions(+), 22 deletions(-) diff --git a/libraries/AP_Landing/AP_Landing.cpp b/libraries/AP_Landing/AP_Landing.cpp index e3947d40f680da..8a5800d3179d74 100644 --- a/libraries/AP_Landing/AP_Landing.cpp +++ b/libraries/AP_Landing/AP_Landing.cpp @@ -253,7 +253,7 @@ bool AP_Landing::verify_land(const Location &prev_WP_loc, Location &next_WP_loc, default: // returning TRUE while executing verify_land() will increment the // mission index which in many cases will trigger an RTL for end-of-mission - gcs().send_text(MAV_SEVERITY_CRITICAL, "Landing configuration error, invalid LAND_TYPE"); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Landing configuration error, invalid LAND_TYPE"); success = true; break; } @@ -486,14 +486,14 @@ bool AP_Landing::restart_landing_sequence() mission.set_current_cmd(current_index+1)) { // if the next immediate command is MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT to climb, do it - gcs().send_text(MAV_SEVERITY_NOTICE, "Restarted landing sequence. Climbing to %dm", (signed)cmd.content.location.alt/100); + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Restarted landing sequence. Climbing to %dm", (signed)cmd.content.location.alt/100); success = true; } else if (do_land_start_index != 0 && mission.set_current_cmd(do_land_start_index)) { // look for a DO_LAND_START and use that index - gcs().send_text(MAV_SEVERITY_NOTICE, "Restarted landing via DO_LAND_START: %d",do_land_start_index); + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Restarted landing via DO_LAND_START: %d",do_land_start_index); success = true; } else if (prev_cmd_with_wp_index != AP_MISSION_CMD_INDEX_NONE && @@ -501,10 +501,10 @@ bool AP_Landing::restart_landing_sequence() { // if a suitable navigation waypoint was just executed, one that contains lat/lng/alt, then // repeat that cmd to restart the landing from the top of approach to repeat intended glide slope - gcs().send_text(MAV_SEVERITY_NOTICE, "Restarted landing sequence at waypoint %d", prev_cmd_with_wp_index); + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Restarted landing sequence at waypoint %d", prev_cmd_with_wp_index); success = true; } else { - gcs().send_text(MAV_SEVERITY_WARNING, "Unable to restart landing sequence"); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Unable to restart landing sequence"); success = false; } diff --git a/libraries/AP_Landing/AP_Landing_Deepstall.cpp b/libraries/AP_Landing/AP_Landing_Deepstall.cpp index 550fa92ecc6c3d..d6f24c6ecaca82 100644 --- a/libraries/AP_Landing/AP_Landing_Deepstall.cpp +++ b/libraries/AP_Landing/AP_Landing_Deepstall.cpp @@ -345,7 +345,7 @@ bool AP_Landing_Deepstall::override_servos(void) if (elevator == nullptr) { // deepstalls are impossible without these channels, abort the process - gcs().send_text(MAV_SEVERITY_CRITICAL, "Deepstall: Unable to find the elevator channels"); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Deepstall: Unable to find the elevator channels"); request_go_around(); return false; } @@ -533,17 +533,17 @@ void AP_Landing_Deepstall::build_approach_path(bool use_current_heading) #ifdef DEBUG_PRINTS // TODO: Send this information via a MAVLink packet - gcs().send_text(MAV_SEVERITY_INFO, "Arc: %3.8f %3.8f", + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Arc: %3.8f %3.8f", (double)(arc.lat / 1e7),(double)( arc.lng / 1e7)); - gcs().send_text(MAV_SEVERITY_INFO, "Loiter en: %3.8f %3.8f", + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Loiter en: %3.8f %3.8f", (double)(arc_entry.lat / 1e7), (double)(arc_entry.lng / 1e7)); - gcs().send_text(MAV_SEVERITY_INFO, "Loiter ex: %3.8f %3.8f", + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Loiter ex: %3.8f %3.8f", (double)(arc_exit.lat / 1e7), (double)(arc_exit.lng / 1e7)); - gcs().send_text(MAV_SEVERITY_INFO, "Extended: %3.8f %3.8f", + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Extended: %3.8f %3.8f", (double)(extended_approach.lat / 1e7), (double)(extended_approach.lng / 1e7)); - gcs().send_text(MAV_SEVERITY_INFO, "Extended by: %f (%f)", (double)approach_extension_m, + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Extended by: %f (%f)", (double)approach_extension_m, (double)expected_travel_distance); - gcs().send_text(MAV_SEVERITY_INFO, "Target Heading: %3.1f", (double)target_heading_deg); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Target Heading: %3.1f", (double)target_heading_deg); #endif // DEBUG_PRINTS } @@ -590,7 +590,7 @@ float AP_Landing_Deepstall::predict_travel_distance(const Vector3f wind, const f if(print) { // allow printing the travel distances on the final entry as its used for tuning - gcs().send_text(MAV_SEVERITY_INFO, "Deepstall: Entry: %0.1f (m) Travel: %0.1f (m)", + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Deepstall: Entry: %0.1f (m) Travel: %0.1f (m)", (double)stall_distance, (double)predicted_travel_distance); } @@ -620,7 +620,7 @@ float AP_Landing_Deepstall::update_steering() // panic if no position source is available // continue the stall but target just holding the wings held level as deepstall should be a minimal // energy configuration on the aircraft, and if a position isn't available aborting would be worse - gcs().send_text(MAV_SEVERITY_CRITICAL, "Deepstall: Invalid data from AHRS. Holding level"); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Deepstall: Invalid data from AHRS. Holding level"); hold_level = true; } @@ -652,7 +652,7 @@ float AP_Landing_Deepstall::update_steering() float error = wrap_PI(constrain_float(desired_change, -yaw_rate_limit_rps, yaw_rate_limit_rps) - yaw_rate); #ifdef DEBUG_PRINTS - gcs().send_text(MAV_SEVERITY_INFO, "x: %f e: %f r: %f d: %f", + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "x: %f e: %f r: %f d: %f", (double)crosstrack_error, (double)error, (double)degrees(yaw_rate), diff --git a/libraries/AP_Landing/AP_Landing_Slope.cpp b/libraries/AP_Landing/AP_Landing_Slope.cpp index 9499dc80f47d70..7c7a9da3253b2a 100644 --- a/libraries/AP_Landing/AP_Landing_Slope.cpp +++ b/libraries/AP_Landing/AP_Landing_Slope.cpp @@ -38,7 +38,7 @@ void AP_Landing::type_slope_do_land(const AP_Mission::Mission_Command& cmd, cons type_slope_flags.post_stats = false; type_slope_stage = SlopeStage::NORMAL; - gcs().send_text(MAV_SEVERITY_INFO, "Landing approach start at %.1fm", (double)relative_altitude); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Landing approach start at %.1fm", (double)relative_altitude); } void AP_Landing::type_slope_verify_abort_landing(const Location &prev_WP_loc, Location &next_WP_loc, bool &throttle_suppressed) @@ -106,9 +106,9 @@ bool AP_Landing::type_slope_verify_land(const Location &prev_WP_loc, Location &n if (type_slope_stage != SlopeStage::FINAL) { type_slope_flags.post_stats = true; if (is_flying && (AP_HAL::millis()-last_flying_ms) > 3000) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "Flare crash detected: speed=%.1f", (double)gps.ground_speed()); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Flare crash detected: speed=%.1f", (double)gps.ground_speed()); } else { - gcs().send_text(MAV_SEVERITY_INFO, "Flare %.1fm sink=%.2f speed=%.1f dist=%.1f", + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Flare %.1fm sink=%.2f speed=%.1f dist=%.1f", (double)height, (double)sink_rate, (double)gps.ground_speed(), (double)current_loc.get_distance(next_WP_loc)); @@ -122,7 +122,7 @@ bool AP_Landing::type_slope_verify_land(const Location &prev_WP_loc, Location &n AP_LandingGear *LG_inst = AP_LandingGear::get_singleton(); if (LG_inst != nullptr && !LG_inst->check_before_land()) { type_slope_request_go_around(); - gcs().send_text(MAV_SEVERITY_CRITICAL, "Landing gear was not deployed"); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Landing gear was not deployed"); } #endif } @@ -158,7 +158,7 @@ bool AP_Landing::type_slope_verify_land(const Location &prev_WP_loc, Location &n // this is done before disarm_if_autoland_complete() so that it happens on the next loop after the disarm if (type_slope_flags.post_stats && !is_armed) { type_slope_flags.post_stats = false; - gcs().send_text(MAV_SEVERITY_INFO, "Distance from LAND point=%.2fm", (double)current_loc.get_distance(next_WP_loc)); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Distance from LAND point=%.2fm", (double)current_loc.get_distance(next_WP_loc)); } // check if we should auto-disarm after a confirmed landing @@ -226,7 +226,7 @@ void AP_Landing::type_slope_adjust_landing_slope_for_rangefinder_bump(AP_FixedWi // is projected slope too steep? if (new_slope_deg - initial_slope_deg > slope_recalc_steep_threshold_to_abort) { - gcs().send_text(MAV_SEVERITY_INFO, "Landing slope too steep, aborting (%.0fm %.1fdeg)", + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Landing slope too steep, aborting (%.0fm %.1fdeg)", (double)rangefinder_state.correction, (double)(new_slope_deg - initial_slope_deg)); alt_offset = rangefinder_state.correction; flags.commanded_go_around = true; @@ -319,7 +319,7 @@ void AP_Landing::type_slope_setup_landing_glide_slope(const Location &prev_WP_lo bool is_first_calc = is_zero(slope); slope = (sink_height - aim_height) / (total_distance - flare_distance); if (is_first_calc) { - gcs().send_text(MAV_SEVERITY_INFO, "Landing glide slope %.1f degrees", (double)degrees(atanf(slope))); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Landing glide slope %.1f degrees", (double)degrees(atanf(slope))); } // calculate point along that slope 500m ahead From 6efc6d0f2dc38d477548282041bfca902cd2eb09 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 8 Dec 2023 13:10:37 +1100 Subject: [PATCH 0060/1335] AP_Motors: correct compilation when GCS library not available --- libraries/AP_Motors/AP_MotorsHeli_RSC.cpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsHeli_RSC.cpp b/libraries/AP_Motors/AP_MotorsHeli_RSC.cpp index 57a3046fc82198..bb5a1ba4f88ec3 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_RSC.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_RSC.cpp @@ -313,12 +313,12 @@ void AP_MotorsHeli_RSC::output(RotorControlState state) _idle_throttle = constrain_float( get_arot_idle_output(), 0.0f, 0.4f); } if (!_autorotating) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "Autorotation"); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Autorotation"); _autorotating =true; } } else { if (_autorotating) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "Autorotation Stopped"); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Autorotation Stopped"); _autorotating =false; } // set rotor control speed to idle speed parameter, this happens instantly and ignores ramping @@ -326,7 +326,7 @@ void AP_MotorsHeli_RSC::output(RotorControlState state) _idle_throttle += 0.001f; if (_control_output >= 1.0f) { _idle_throttle = get_idle_output(); - gcs().send_text(MAV_SEVERITY_INFO, "Turbine startup"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Turbine startup"); _starting = false; } } else { @@ -408,7 +408,7 @@ void AP_MotorsHeli_RSC::update_rotor_ramp(float rotor_ramp_input, float dt) if (_rotor_ramp_output < rotor_ramp_input) { if (_use_bailout_ramp) { if (!_bailing_out) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "bailing_out"); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "bailing_out"); _bailing_out = true; if (_control_mode == ROTOR_CONTROL_MODE_AUTOTHROTTLE) {_gov_bailing_out = true;} } @@ -563,9 +563,9 @@ void AP_MotorsHeli_RSC::autothrottle_run() governor_reset(); _governor_fault = true; if (_rotor_rpm >= (_governor_rpm + _governor_range)) { - gcs().send_text(MAV_SEVERITY_WARNING, "Governor Fault: Rotor Overspeed"); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Governor Fault: Rotor Overspeed"); } else { - gcs().send_text(MAV_SEVERITY_WARNING, "Governor Fault: Rotor Underspeed"); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Governor Fault: Rotor Underspeed"); } } } else { @@ -577,7 +577,7 @@ void AP_MotorsHeli_RSC::autothrottle_run() if (_rotor_rpm > (_governor_rpm + _governor_range) && !_gov_bailing_out) { _governor_fault = true; governor_reset(); - gcs().send_text(MAV_SEVERITY_WARNING, "Governor Fault: Rotor Overspeed"); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Governor Fault: Rotor Overspeed"); _governor_output = 0.0f; // when performing power recovery from autorotation, this waits for user to load rotor in order to @@ -594,7 +594,7 @@ void AP_MotorsHeli_RSC::autothrottle_run() _governor_engage = true; _autothrottle = true; _gov_bailing_out = false; - gcs().send_text(MAV_SEVERITY_NOTICE, "Governor Engaged"); + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Governor Engaged"); } } else { // temporary use of throttle curve and ramp timer to accelerate rotor to governor min torque rise speed From dd6d1f04c2ad62bbfc737f66fb6784e9e12d1675 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 8 Dec 2023 13:10:38 +1100 Subject: [PATCH 0061/1335] AP_OSD: correct compilation when GCS library not available --- libraries/AP_OSD/AP_OSD_MSP_DisplayPort.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_OSD/AP_OSD_MSP_DisplayPort.cpp b/libraries/AP_OSD/AP_OSD_MSP_DisplayPort.cpp index 0e46dfc2cd7848..dccc059b570cfa 100644 --- a/libraries/AP_OSD/AP_OSD_MSP_DisplayPort.cpp +++ b/libraries/AP_OSD/AP_OSD_MSP_DisplayPort.cpp @@ -39,12 +39,12 @@ bool AP_OSD_MSP_DisplayPort::init(void) // check if we have a DisplayPort backend to use const AP_MSP *msp = AP::msp(); if (msp == nullptr) { - gcs().send_text(MAV_SEVERITY_WARNING,"MSP backend not available"); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING,"MSP backend not available"); return false; } _displayport = msp->find_protocol(AP_SerialManager::SerialProtocol_MSP_DisplayPort); if (_displayport == nullptr) { - gcs().send_text(MAV_SEVERITY_WARNING,"MSP DisplayPort uart not available"); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING,"MSP DisplayPort uart not available"); return false; } // re-init port here for use in this thread From 1bf85a0a15237f02e50c0d5f9a03b6b88bbd4049 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 8 Dec 2023 13:10:38 +1100 Subject: [PATCH 0062/1335] AP_SmartRTL: correct compilation when GCS library not available --- libraries/AP_SmartRTL/AP_SmartRTL.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_SmartRTL/AP_SmartRTL.cpp b/libraries/AP_SmartRTL/AP_SmartRTL.cpp index 049e7506b6aba0..0de442dc7faaad 100644 --- a/libraries/AP_SmartRTL/AP_SmartRTL.cpp +++ b/libraries/AP_SmartRTL/AP_SmartRTL.cpp @@ -118,7 +118,7 @@ void AP_SmartRTL::init() // check if memory allocation failed if (_path == nullptr || _prune.loops == nullptr || _simplify.stack == nullptr) { log_action(SRTL_DEACTIVATED_INIT_FAILED); - gcs().send_text(MAV_SEVERITY_WARNING, "SmartRTL deactivated: init failed"); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "SmartRTL deactivated: init failed"); free(_path); free(_prune.loops); free(_simplify.stack); @@ -390,7 +390,7 @@ void AP_SmartRTL::run_background_cleanup() // warn if buffer is about to be filled uint32_t now_ms = AP_HAL::millis(); if ((path_points_count >0) && (path_points_count >= _path_points_max - 9) && (now_ms - _last_low_space_notify_ms > 10000)) { - gcs().send_text(MAV_SEVERITY_INFO, "SmartRTL Low on space!"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SmartRTL Low on space!"); _last_low_space_notify_ms = now_ms; } @@ -866,7 +866,7 @@ void AP_SmartRTL::deactivate(SRTL_Actions action, const char *reason) { _active = false; log_action(action); - gcs().send_text(MAV_SEVERITY_WARNING, "SmartRTL deactivated: %s", reason); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "SmartRTL deactivated: %s", reason); } // logging From 673fad04de7115536f4ed541fd3a5f2c8a038ec5 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 8 Dec 2023 13:10:38 +1100 Subject: [PATCH 0063/1335] AP_WindVane: correct compilation when GCS library not available --- libraries/AP_WindVane/AP_WindVane_Analog.cpp | 6 +++--- libraries/AP_WindVane/AP_WindVane_Backend.cpp | 2 +- libraries/AP_WindVane/AP_WindVane_ModernDevice.cpp | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AP_WindVane/AP_WindVane_Analog.cpp b/libraries/AP_WindVane/AP_WindVane_Analog.cpp index 404fa4ea94d8f7..cebd664f51b502 100644 --- a/libraries/AP_WindVane/AP_WindVane_Analog.cpp +++ b/libraries/AP_WindVane/AP_WindVane_Analog.cpp @@ -59,7 +59,7 @@ void AP_WindVane_Analog::calibrate() _cal_start_ms = AP_HAL::millis(); _cal_volt_max = _current_analog_voltage; _cal_volt_min = _current_analog_voltage; - gcs().send_text(MAV_SEVERITY_INFO, "WindVane: Calibration started, rotate wind vane"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "WindVane: Calibration started, rotate wind vane"); } // record min and max voltage @@ -74,11 +74,11 @@ void AP_WindVane_Analog::calibrate() // save min and max voltage _frontend._dir_analog_volt_max.set_and_save(_cal_volt_max); _frontend._dir_analog_volt_min.set_and_save(_cal_volt_min); - gcs().send_text(MAV_SEVERITY_INFO, "WindVane: Calibration complete (volt min:%.1f max:%1.f)", + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "WindVane: Calibration complete (volt min:%.1f max:%1.f)", (double)_cal_volt_min, (double)_cal_volt_max); } else { - gcs().send_text(MAV_SEVERITY_INFO, "WindVane: Calibration failed (volt diff %.1f below %.1f)", + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "WindVane: Calibration failed (volt diff %.1f below %.1f)", (double)volt_diff, (double)WINDVANE_CALIBRATION_VOLT_DIFF_MIN); } diff --git a/libraries/AP_WindVane/AP_WindVane_Backend.cpp b/libraries/AP_WindVane/AP_WindVane_Backend.cpp index 7f9ea4026769e7..a0fa4e10582452 100644 --- a/libraries/AP_WindVane/AP_WindVane_Backend.cpp +++ b/libraries/AP_WindVane/AP_WindVane_Backend.cpp @@ -31,7 +31,7 @@ AP_WindVane_Backend::AP_WindVane_Backend(AP_WindVane &frontend) : // calibrate WindVane void AP_WindVane_Backend::calibrate() { - gcs().send_text(MAV_SEVERITY_INFO, "WindVane: No cal required"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "WindVane: No cal required"); _frontend._calibration.set_and_save(0); return; } diff --git a/libraries/AP_WindVane/AP_WindVane_ModernDevice.cpp b/libraries/AP_WindVane/AP_WindVane_ModernDevice.cpp index c88fb13cff82b1..e01d6aad199eb1 100644 --- a/libraries/AP_WindVane/AP_WindVane_ModernDevice.cpp +++ b/libraries/AP_WindVane/AP_WindVane_ModernDevice.cpp @@ -70,7 +70,7 @@ void AP_WindVane_ModernDevice::update_speed() void AP_WindVane_ModernDevice::calibrate() { - gcs().send_text(MAV_SEVERITY_INFO, "WindVane: rev P. zero wind voltage offset set to %.1f",double(_current_analog_voltage)); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "WindVane: rev P. zero wind voltage offset set to %.1f",double(_current_analog_voltage)); _frontend._speed_sensor_voltage_offset.set_and_save(_current_analog_voltage); _frontend._calibration.set_and_save(0); } From c15a73c79866767494897502aab47226fa157e9a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 8 Dec 2023 13:10:38 +1100 Subject: [PATCH 0064/1335] AR_Motors: correct compilation when GCS library not available --- libraries/AR_Motors/AP_MotorsUGV.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AR_Motors/AP_MotorsUGV.cpp b/libraries/AR_Motors/AP_MotorsUGV.cpp index 357815613e6ae2..c1b2177a46b9e0 100644 --- a/libraries/AR_Motors/AP_MotorsUGV.cpp +++ b/libraries/AR_Motors/AP_MotorsUGV.cpp @@ -465,21 +465,21 @@ bool AP_MotorsUGV::pre_arm_check(bool report) const !SRV_Channels::function_assigned(SRV_Channel::k_scripting1) && !has_sail()) { if (report) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: no motor, sail or scripting outputs defined"); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "PreArm: no motor, sail or scripting outputs defined"); } return false; } // check if only one of skid-steering output has been configured if (SRV_Channels::function_assigned(SRV_Channel::k_throttleLeft) != SRV_Channels::function_assigned(SRV_Channel::k_throttleRight)) { if (report) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: check skid steering config"); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "PreArm: check skid steering config"); } return false; } // check if only one of throttle or steering outputs has been configured, if has a sail allow no throttle if ((has_sail() || SRV_Channels::function_assigned(SRV_Channel::k_throttle)) != SRV_Channels::function_assigned(SRV_Channel::k_steering)) { if (report) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: check steering and throttle config"); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "PreArm: check steering and throttle config"); } return false; } @@ -488,7 +488,7 @@ bool AP_MotorsUGV::pre_arm_check(bool report) const SRV_Channel::Aux_servo_function_t function = SRV_Channels::get_motor_function(i); if (!SRV_Channels::function_assigned(function)) { if (report) { - gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: servo function %u unassigned", function); + GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "PreArm: servo function %u unassigned", function); } return false; } @@ -613,7 +613,7 @@ void AP_MotorsUGV::add_omni_motor_num(int8_t motor_num) SRV_Channel::Aux_servo_function_t function = SRV_Channels::get_motor_function(motor_num); SRV_Channels::set_aux_channel_default(function, motor_num); if (!SRV_Channels::find_channel(function, chan)) { - gcs().send_text(MAV_SEVERITY_ERROR, "Motors: unable to setup motor %u", motor_num); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Motors: unable to setup motor %u", motor_num); } } } From 93907f4a6d2a35b94449e93adef1fb1b2cfa2b3b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 11 Dec 2023 17:44:00 +1100 Subject: [PATCH 0065/1335] AP_Avoidance: correct compilation when HAL_GCS_ENABLED is false --- libraries/AP_Avoidance/AP_Avoidance.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_Avoidance/AP_Avoidance.cpp b/libraries/AP_Avoidance/AP_Avoidance.cpp index 45f28874fc10c5..14e0d286283e0b 100644 --- a/libraries/AP_Avoidance/AP_Avoidance.cpp +++ b/libraries/AP_Avoidance/AP_Avoidance.cpp @@ -396,6 +396,7 @@ MAV_COLLISION_THREAT_LEVEL AP_Avoidance::current_threat_level() const { return _obstacles[_current_most_serious_threat].threat_level; } +#if HAL_GCS_ENABLED void AP_Avoidance::send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_COLLISION_ACTION behaviour) const { const mavlink_collision_t packet{ @@ -409,6 +410,7 @@ void AP_Avoidance::send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_ }; gcs().send_to_active_channels(MAVLINK_MSG_ID_COLLISION, (const char *)&packet); } +#endif void AP_Avoidance::handle_threat_gcs_notify(AP_Avoidance::Obstacle *threat) { From 283a1edb9f840eb7b045527272db2baf85a9f56b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 11 Dec 2023 17:44:00 +1100 Subject: [PATCH 0066/1335] AP_VisualOdom: correct compilation when HAL_GCS_ENABLED is false --- libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp | 2 ++ libraries/AP_VisualOdom/AP_VisualOdom_Backend.h | 2 ++ 2 files changed, 4 insertions(+) diff --git a/libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp b/libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp index b0974348e1467a..5519f86d452d8c 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp +++ b/libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp @@ -36,6 +36,7 @@ bool AP_VisualOdom_Backend::healthy() const return ((AP_HAL::millis() - _last_update_ms) < AP_VISUALODOM_TIMEOUT_MS); } +#if HAL_GCS_ENABLED // consume vision_position_delta mavlink messages void AP_VisualOdom_Backend::handle_vision_position_delta_msg(const mavlink_message_t &msg) { @@ -69,6 +70,7 @@ void AP_VisualOdom_Backend::handle_vision_position_delta_msg(const mavlink_messa position_delta, packet.confidence); } +#endif // HAL_GCS_ENABLED // returns the system time of the last reset if reset_counter has not changed // updates the reset timestamp to the current system time if the reset_counter has changed diff --git a/libraries/AP_VisualOdom/AP_VisualOdom_Backend.h b/libraries/AP_VisualOdom/AP_VisualOdom_Backend.h index b17eef76e73915..ce2033ca4ce2f2 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom_Backend.h +++ b/libraries/AP_VisualOdom/AP_VisualOdom_Backend.h @@ -27,8 +27,10 @@ class AP_VisualOdom_Backend // return true if sensor is basically healthy (we are receiving data) bool healthy() const; +#if HAL_GCS_ENABLED // consume vision_position_delta mavlink messages void handle_vision_position_delta_msg(const mavlink_message_t &msg); +#endif // consume vision pose estimate data and send to EKF. distances in meters virtual void handle_pose_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude, float posErr, float angErr, uint8_t reset_counter) = 0; From 21a9f8e3a2751f05dee853493bdfcfb05f9e214f Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sun, 10 Dec 2023 17:40:29 +0000 Subject: [PATCH 0067/1335] Plane: move landing servo override out of throttle control function --- ArduPlane/Plane.h | 2 +- ArduPlane/servos.cpp | 7 ++++++- 2 files changed, 7 insertions(+), 2 deletions(-) diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 80e3cb8636ce1e..b40ab6a1321723 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -1091,7 +1091,7 @@ class Plane : public AP_Vehicle { // servos.cpp void set_servos_idle(void); void set_servos(); - void set_servos_controlled(void); + void set_throttle(void); void set_takeoff_expected(void); void set_servos_old_elevons(void); void set_servos_flaps(void); diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index 6048aed8042a02..51a28e1ee34f09 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -829,8 +829,13 @@ void Plane::set_servos(void) quadplane.update(); #endif + if (flight_stage == AP_FixedWing::FlightStage::LAND) { + // allow landing to override servos if it would like to + landing.override_servos(); + } + if (control_mode != &mode_manual) { - set_servos_controlled(); + set_throttle(); set_takeoff_expected(); } From 740b04aed36c6003833de1ed4be782d45ce2b1d1 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sun, 10 Dec 2023 17:42:03 +0000 Subject: [PATCH 0068/1335] Plane: Mode: ensure flight stage is correct on successful mode change --- ArduPlane/mode.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ArduPlane/mode.cpp b/ArduPlane/mode.cpp index b6c3a2b44fc863..6eef3fb0fab389 100644 --- a/ArduPlane/mode.cpp +++ b/ArduPlane/mode.cpp @@ -135,6 +135,9 @@ bool Mode::enter() GCS_SEND_TEXT(MAV_SEVERITY_INFO, "In landing sequence: mission reset"); plane.mission.reset(); } + + // Make sure the flight stage is correct for the new mode + plane.update_flight_stage(); } return enter_result; From 5642d2449a9483039406a709c72e64c4f1425909 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sun, 10 Dec 2023 17:42:34 +0000 Subject: [PATCH 0069/1335] Plane: allow set_takeoff_expected in manual mode --- ArduPlane/servos.cpp | 11 ++++------- 1 file changed, 4 insertions(+), 7 deletions(-) diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index 51a28e1ee34f09..35dc8b08017280 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -472,13 +472,8 @@ void Plane::throttle_watt_limiter(int8_t &min_throttle, int8_t &max_throttle) /* setup output channels all non-manual modes */ -void Plane::set_servos_controlled(void) +void Plane::set_throttle(void) { - if (flight_stage == AP_FixedWing::FlightStage::LAND) { - // allow landing to override servos if it would like to - landing.override_servos(); - } - // convert 0 to 100% (or -100 to +100) into PWM int8_t min_throttle = aparm.throttle_min.get(); int8_t max_throttle = aparm.throttle_max.get(); @@ -836,9 +831,11 @@ void Plane::set_servos(void) if (control_mode != &mode_manual) { set_throttle(); - set_takeoff_expected(); } + // Warn AHRS if we might take off soon + set_takeoff_expected(); + // setup flap outputs set_servos_flaps(); From 58d4871177efc0594825c2e8a5d92fb7bac7691d Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 10 Dec 2023 08:55:59 +1100 Subject: [PATCH 0070/1335] AP_DAL: remove tmp_location from global namespace removes this from the global namespace and means it isn't included when DAL isn't update the location where we update the fields. --- libraries/AP_DAL/AP_DAL_GPS.cpp | 16 ++++------------ libraries/AP_DAL/AP_DAL_GPS.h | 10 +++++++++- 2 files changed, 13 insertions(+), 13 deletions(-) diff --git a/libraries/AP_DAL/AP_DAL_GPS.cpp b/libraries/AP_DAL/AP_DAL_GPS.cpp index 8246157691602d..c57cc3d0631108 100644 --- a/libraries/AP_DAL/AP_DAL_GPS.cpp +++ b/libraries/AP_DAL/AP_DAL_GPS.cpp @@ -3,9 +3,6 @@ #include #include "AP_DAL.h" -// we use a static here as the "location" accessor wants to be const -static Location tmp_location[GPS_MAX_INSTANCES]; - AP_DAL_GPS::AP_DAL_GPS() { for (uint8_t i=0; i Date: Fri, 8 Dec 2023 13:12:45 +1100 Subject: [PATCH 0071/1335] AP_Arming: correct compilation when RC_Channels library not available --- libraries/AP_Arming/AP_Arming.cpp | 16 +++++++++++++++- 1 file changed, 15 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index bbfcaf73519319..e51f3c75704f79 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -718,6 +718,7 @@ bool AP_Arming::hardware_safety_check(bool report) return true; } +#if AP_RC_CHANNEL_ENABLED bool AP_Arming::rc_arm_checks(AP_Arming::Method method) { // don't check the trims if we are in a failsafe @@ -835,6 +836,7 @@ bool AP_Arming::manual_transmitter_checks(bool report) return rc_in_calibration_check(report); } +#endif // AP_RC_CHANNEL_ENABLED bool AP_Arming::mission_checks(bool report) { @@ -1523,6 +1525,7 @@ bool AP_Arming::estop_checks(bool display_failure) // not emergency-stopped, so no prearm failure: return true; } +#if AP_RC_CHANNEL_ENABLED // vehicle is emergency-stopped; if this *appears* to have been done via switch then we do not fail prearms: const RC_Channel *chan = rc().find_channel_for_option(RC_Channel::AUX_FUNC::ARM_EMERGENCY_STOP); if (chan != nullptr) { @@ -1531,7 +1534,8 @@ bool AP_Arming::estop_checks(bool display_failure) // switch is configured and is in estop position, so likely the reason we are estopped, so no prearm failure return true; // no prearm failure } - } + } +#endif // AP_RC_CHANNEL_ENABLED check_failed(display_failure,"Motors Emergency Stopped"); return false; } @@ -1558,7 +1562,9 @@ bool AP_Arming::pre_arm_checks(bool report) & gps_checks(report) & battery_checks(report) & logging_checks(report) +#if AP_RC_CHANNEL_ENABLED & manual_transmitter_checks(report) +#endif & mission_checks(report) & rangefinder_checks(report) & servo_checks(report) @@ -1576,7 +1582,9 @@ bool AP_Arming::pre_arm_checks(bool report) #if AP_ARMING_AUX_AUTH_ENABLED & aux_auth_checks(report) #endif +#if AP_RC_CHANNEL_ENABLED & disarm_switch_checks(report) +#endif & fence_checks(report) & opendroneid_checks(report) & serial_protocol_checks(report) @@ -1592,11 +1600,13 @@ bool AP_Arming::pre_arm_checks(bool report) bool AP_Arming::arm_checks(AP_Arming::Method method) { +#if AP_RC_CHANNEL_ENABLED if (check_enabled(ARMING_CHECK_RC)) { if (!rc_arm_checks(method)) { return false; } } +#endif // ensure the GPS drivers are ready on any final changes if (check_enabled(ARMING_CHECK_GPS_CONFIG)) { @@ -1772,6 +1782,7 @@ AP_Arming::Required AP_Arming::arming_required() const return require; } +#if AP_RC_CHANNEL_ENABLED // Copter and sub share the same RC input limits // Copter checks that min and max have been configured by default, Sub does not bool AP_Arming::rc_checks_copter_sub(const bool display_failure, const RC_Channel *channels[4]) const @@ -1800,6 +1811,7 @@ bool AP_Arming::rc_checks_copter_sub(const bool display_failure, const RC_Channe } return ret; } +#endif // AP_RC_CHANNEL_ENABLED // check visual odometry is working bool AP_Arming::visodom_checks(bool display_failure) const @@ -1822,6 +1834,7 @@ bool AP_Arming::visodom_checks(bool display_failure) const return true; } +#if AP_RC_CHANNEL_ENABLED // check disarm switch is asserted bool AP_Arming::disarm_switch_checks(bool display_failure) const { @@ -1834,6 +1847,7 @@ bool AP_Arming::disarm_switch_checks(bool display_failure) const return true; } +#endif // AP_RC_CHANNEL_ENABLED void AP_Arming::Log_Write_Arm(const bool forced, const AP_Arming::Method method) { From 1aa6ad5bc3eca656ed82627347b20865d5f88c0c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 8 Dec 2023 13:12:45 +1100 Subject: [PATCH 0072/1335] AP_OSD: correct compilation when RC_Channels library not available --- libraries/AP_OSD/AP_OSD.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_OSD/AP_OSD.cpp b/libraries/AP_OSD/AP_OSD.cpp index 8034e0ee92b111..e88e2363959a48 100644 --- a/libraries/AP_OSD/AP_OSD.cpp +++ b/libraries/AP_OSD/AP_OSD.cpp @@ -511,6 +511,7 @@ void AP_OSD::update_current_screen() return; } +#if AP_RC_CHANNEL_ENABLED RC_Channel *channel = RC_Channels::rc_channel(rc_channel-1); if (channel == nullptr) { return; @@ -566,6 +567,7 @@ void AP_OSD::update_current_screen() break; } switch_debouncer = false; +#endif // AP_RC_CHANNEL_ENABLED } //select next avaliable screen, do nothing if all screens disabled From 22c1019767c421e733f858ddd65a58f9dbfdb4e9 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 12 Dec 2023 08:32:58 +1100 Subject: [PATCH 0073/1335] AP_Scripting: correct compilation when AP_RTC is compiled out --- libraries/AP_Scripting/generator/description/bindings.desc | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index 7ddc378d843fdc..94557841c84a0e 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -849,6 +849,7 @@ singleton AP_Filesystem method stat boolean string AP_Filesystem::stat_t'Null include AP_RTC/AP_RTC.h depends AP_RTC_ENABLED include AP_RTC/AP_RTC_config.h +singleton AP_RTC depends AP_RTC_ENABLED singleton AP_RTC rename rtc singleton AP_RTC method clock_s_to_date_fields boolean uint32_t'skip_check uint16_t'Null uint8_t'Null uint8_t'Null uint8_t'Null uint8_t'Null uint8_t'Null uint8_t'Null singleton AP_RTC method date_fields_to_clock_s uint32_t uint16_t'skip_check int8_t'skip_check uint8_t'skip_check uint8_t'skip_check uint8_t'skip_check uint8_t'skip_check From f6bff8c19ed50049b45fcc506e443e6670e74d7c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 9 Dec 2023 17:09:26 +1100 Subject: [PATCH 0074/1335] AP_Mission: correct compilation when RC_Channel not enabled --- libraries/AP_Mission/AP_Mission.cpp | 3 +++ libraries/AP_Mission/AP_Mission_Commands.cpp | 2 ++ 2 files changed, 5 insertions(+) diff --git a/libraries/AP_Mission/AP_Mission.cpp b/libraries/AP_Mission/AP_Mission.cpp index 3487d3a974fcaa..22d6f60c364fa3 100644 --- a/libraries/AP_Mission/AP_Mission.cpp +++ b/libraries/AP_Mission/AP_Mission.cpp @@ -10,6 +10,7 @@ #include #include #include +#include const AP_Param::GroupInfo AP_Mission::var_info[] = { @@ -405,8 +406,10 @@ bool AP_Mission::start_command(const Mission_Command& cmd) } switch (cmd.id) { +#if AP_RC_CHANNEL_ENABLED case MAV_CMD_DO_AUX_FUNCTION: return start_command_do_aux_function(cmd); +#endif #if AP_GRIPPER_ENABLED case MAV_CMD_DO_GRIPPER: return start_command_do_gripper(cmd); diff --git a/libraries/AP_Mission/AP_Mission_Commands.cpp b/libraries/AP_Mission/AP_Mission_Commands.cpp index 83716ec71849cd..9d82550e482326 100644 --- a/libraries/AP_Mission/AP_Mission_Commands.cpp +++ b/libraries/AP_Mission/AP_Mission_Commands.cpp @@ -10,6 +10,7 @@ #include #include +#if AP_RC_CHANNEL_ENABLED bool AP_Mission::start_command_do_aux_function(const AP_Mission::Mission_Command& cmd) { const RC_Channel::AUX_FUNC function = (RC_Channel::AUX_FUNC)cmd.content.auxfunction.function; @@ -28,6 +29,7 @@ bool AP_Mission::start_command_do_aux_function(const AP_Mission::Mission_Command rc().run_aux_function(function, pos, RC_Channel::AuxFuncTriggerSource::MISSION); return true; } +#endif // AP_RC_CHANNEL_ENABLED #if AP_GRIPPER_ENABLED bool AP_Mission::start_command_do_gripper(const AP_Mission::Mission_Command& cmd) From 575314d31e08d9a8ce5677f969eb51267f5bad9b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 12 Dec 2023 12:44:11 +1100 Subject: [PATCH 0075/1335] Tools: mac: force install to avoid npm installation error 2023-12-11T23:04:39.8671350Z already exists. You may want to remove it: 2023-12-11T23:04:39.8679620Z rm '/usr/local/lib/node_modules/npm/node_modules/@npmcli/agent/lib/agents.js' 2023-12-11T23:04:39.8682240Z 2023-12-11T23:04:39.8691710Z To force the link and overwrite all conflicting files: 2023-12-11T23:04:39.8700070Z brew link --overwrite node@18 2023-12-11T23:04:39.8726220Z 2023-12-11T23:04:39.8736300Z To list all files that would be deleted: 2023-12-11T23:04:39.8744090Z brew link --overwrite --dry-run node@18 ... also remove hack to force update to succeed --- Tools/environment_install/install-prereqs-mac.sh | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Tools/environment_install/install-prereqs-mac.sh b/Tools/environment_install/install-prereqs-mac.sh index 69f647c1b23c24..cfbf9858617225 100755 --- a/Tools/environment_install/install-prereqs-mac.sh +++ b/Tools/environment_install/install-prereqs-mac.sh @@ -104,8 +104,8 @@ function maybe_prompt_user() { find /usr/local/bin -lname '*/Library/Frameworks/Python.framework/*' -delete # brew update randomly failing on CI, so ignore errors: -brew update || true -brew install gawk curl coreutils wget +brew update +brew install --force --overwrite gawk curl coreutils wget PIP=pip if maybe_prompt_user "Install python using pyenv [N/y]?" ; then From 4226f9e97cb0f39d77d540a80937e17d0b1d571f Mon Sep 17 00:00:00 2001 From: Luca Scheuer Date: Tue, 12 Dec 2023 10:14:04 -0600 Subject: [PATCH 0076/1335] AP_SerialManager: reserving serial protocol for Vertiq IQUART --- libraries/AP_SerialManager/AP_SerialManager.h | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_SerialManager/AP_SerialManager.h b/libraries/AP_SerialManager/AP_SerialManager.h index b548656297f91c..30bae549f6b879 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.h +++ b/libraries/AP_SerialManager/AP_SerialManager.h @@ -80,6 +80,7 @@ class AP_SerialManager { SerialProtocol_Tramp = 44, SerialProtocol_DDS_XRCE = 45, SerialProtocol_IMUOUT = 46, + // Reserving Serial Protocol 47 for SerialProtocol_IQ SerialProtocol_NumProtocols // must be the last value }; From fc9e6de99a229f6aaca6c976b03aa8b9efe70fa9 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 13 Dec 2023 13:44:03 +1100 Subject: [PATCH 0077/1335] Tools: size_compare_branches.py: add canzero to linux boards --- Tools/scripts/size_compare_branches.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Tools/scripts/size_compare_branches.py b/Tools/scripts/size_compare_branches.py index 41e93bc7a5c5ca..08751595854634 100755 --- a/Tools/scripts/size_compare_branches.py +++ b/Tools/scripts/size_compare_branches.py @@ -164,6 +164,7 @@ def __init__(self, 'Pixhawk1-bdshot', 'SITL_arm_linux_gnueabihf', 'RADIX2HD', + 'canzero', ]) # blacklist all linux boards for bootloader build: @@ -197,6 +198,7 @@ def linux_board_names(self): 'rst_zynq', 'obal', 'SITL_x86_64_linux_gnu', + 'canzero', ] def esp32_board_names(self): From 71a64d50465df90148d37383572c4e8a6c045ccd Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 12 Dec 2023 16:39:09 +1100 Subject: [PATCH 0078/1335] GCS_MAVLink: correct compilation when compass not enabled --- libraries/GCS_MAVLink/GCS_Common.cpp | 16 +++++++++++----- 1 file changed, 11 insertions(+), 5 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index a81f3d5a38cb7b..377c08304183d2 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -22,6 +22,7 @@ #include "GCS.h" #include +#include #include #include #include @@ -38,6 +39,7 @@ #include #include #include +#include #include #include #include @@ -68,6 +70,8 @@ #include "MissionItemProtocol_Rally.h" #include "MissionItemProtocol_Fence.h" +#include + #include #if HAL_RCINPUT_WITH_AP_RADIO @@ -2031,16 +2035,16 @@ void GCS_MAVLINK::send_raw_imu() { #if AP_INERTIALSENSOR_ENABLED const AP_InertialSensor &ins = AP::ins(); - const Compass &compass = AP::compass(); const Vector3f &accel = ins.get_accel(0); const Vector3f &gyro = ins.get_gyro(0); Vector3f mag; +#if AP_COMPASS_ENABLED + const Compass &compass = AP::compass(); if (compass.get_count() >= 1) { mag = compass.get_field(0); - } else { - mag.zero(); } +#endif mavlink_msg_raw_imu_send( chan, @@ -2063,7 +2067,6 @@ void GCS_MAVLINK::send_scaled_imu(uint8_t instance, void (*send_fn)(mavlink_chan { #if AP_INERTIALSENSOR_ENABLED const AP_InertialSensor &ins = AP::ins(); - const Compass &compass = AP::compass(); int16_t _temperature = 0; bool have_data = false; @@ -2078,11 +2081,14 @@ void GCS_MAVLINK::send_scaled_imu(uint8_t instance, void (*send_fn)(mavlink_chan gyro = ins.get_gyro(instance); have_data = true; } - Vector3f mag{}; + Vector3f mag; +#if AP_COMPASS_ENABLED + const Compass &compass = AP::compass(); if (compass.get_count() > instance) { mag = compass.get_field(instance); have_data = true; } +#endif if (!have_data) { return; } From d5cc1d4ad074bc78c3ac8ff9e10126902cc7907b Mon Sep 17 00:00:00 2001 From: Lachlan Conn Date: Mon, 20 Nov 2023 12:38:28 +1100 Subject: [PATCH 0079/1335] Plane: QAssist speed warning added Also updated the severity of other QAssist messages --- ArduPlane/quadplane.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 48259c89a4462a..db7df54d9b7313 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -1496,7 +1496,7 @@ bool QuadPlane::should_assist(float aspeed, bool have_airspeed) // we've been below assistant alt for Q_ASSIST_DELAY seconds if (!in_alt_assist) { in_alt_assist = true; - gcs().send_text(MAV_SEVERITY_INFO, "Alt assist %.1fm", height_above_ground); + gcs().send_text(MAV_SEVERITY_WARNING, "Alt assist %.1fm", height_above_ground); } return true; } @@ -1541,7 +1541,7 @@ bool QuadPlane::should_assist(float aspeed, bool have_airspeed) bool ret = (now - angle_error_start_ms) >= assist_delay*1000; if (ret && !in_angle_assist) { in_angle_assist = true; - gcs().send_text(MAV_SEVERITY_INFO, "Angle assist r=%d p=%d", + gcs().send_text(MAV_SEVERITY_WARNING, "Angle assist r=%d p=%d", (int)(ahrs.roll_sensor/100), (int)(ahrs.pitch_sensor/100)); } From 452f9989b94be6b9954efd6d08f5ab0df2663a6e Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Mon, 11 Dec 2023 21:19:48 +0000 Subject: [PATCH 0080/1335] AP_Scripting: fix some more of the easy luacheck warnings --- libraries/AP_Scripting/applets/runcam_on_arm.lua | 4 ---- libraries/AP_Scripting/examples/OOP_example.lua | 2 -- libraries/AP_Scripting/examples/plane-doublets.lua | 6 +----- libraries/AP_Scripting/examples/protected_call.lua | 2 +- libraries/AP_Scripting/examples/quadruped.lua | 3 +-- libraries/AP_Scripting/examples/test_load.lua | 5 ++--- 6 files changed, 5 insertions(+), 17 deletions(-) diff --git a/libraries/AP_Scripting/applets/runcam_on_arm.lua b/libraries/AP_Scripting/applets/runcam_on_arm.lua index 8f99b0a289af8a..6a1924d36b848a 100644 --- a/libraries/AP_Scripting/applets/runcam_on_arm.lua +++ b/libraries/AP_Scripting/applets/runcam_on_arm.lua @@ -19,7 +19,6 @@ -- presses, I want the script to be responsive and start recording as -- soon as the vehicle arms, so there I use a shorter delay. --- luacheck: only 0 -- constants @@ -46,7 +45,6 @@ function update() local is_armed = arming:is_armed() local delay = DELAY_SHORT - if is_armed ~= prev_armed then -- a state transition has occurred if is_armed then @@ -57,8 +55,6 @@ function update() rc:run_aux_function(RC_OPTION.RunCamControl, AuxSwitchPos.LOW) end delay = DELAY_LONG - else - delay = DELAY_SHORT end prev_armed = is_armed diff --git a/libraries/AP_Scripting/examples/OOP_example.lua b/libraries/AP_Scripting/examples/OOP_example.lua index d555cb4a0278e7..a6b7cf0638d91c 100644 --- a/libraries/AP_Scripting/examples/OOP_example.lua +++ b/libraries/AP_Scripting/examples/OOP_example.lua @@ -1,5 +1,4 @@ -- this is an example of how to do object oriented programming in Lua --- luacheck: only 0 function constrain(v, minv, maxv) -- constrain a value between two limits @@ -25,7 +24,6 @@ local function PIFF(kFF,kP,kI,iMax) local _kFF = kFF local _kP = kP or 0.0 local _kI = kI or 0.0 - local _kD = kD or 0.0 local _iMax = iMax local _last_t = nil local _log_data = {} diff --git a/libraries/AP_Scripting/examples/plane-doublets.lua b/libraries/AP_Scripting/examples/plane-doublets.lua index 60618b66aa5f18..2c34a381f6cd55 100644 --- a/libraries/AP_Scripting/examples/plane-doublets.lua +++ b/libraries/AP_Scripting/examples/plane-doublets.lua @@ -7,7 +7,6 @@ -- It is suggested to allow the aircraft to trim for straight, level, unaccelerated flight (SLUF) in FBWB mode before -- starting a doublet -- Charlie Johnson, Oklahoma State University 2020 --- luacheck: only 0 local DOUBLET_ACTION_CHANNEL = 6 -- RCIN channel to start a doublet when high (>1700) local DOUBLET_CHOICE_CHANNEL = 7 -- RCIN channel to choose elevator (low) or rudder (high) @@ -19,8 +18,6 @@ local DOUBLET_TIME = 500 -- period of doublet signal in ms -- flight mode numbers for plane https://mavlink.io/en/messages/ardupilotmega.html local MODE_MANUAL = 0 local MODE_FBWA = 5 -local MODE_FBWB = 6 -local MODE_RTL = 11 local K_AILERON = 4 local K_ELEVATOR = 19 local K_THROTTLE = 70 @@ -30,7 +27,6 @@ local K_RUDDER = 21 local start_time = -1 local end_time = -1 local now = -1 -local desired_mode = -1 -- store information about the doublet channel local doublet_srv_chan = SRV_Channels:find_channel(DOUBLET_FUCNTION) @@ -65,7 +61,7 @@ function doublet() pre_doublet_mode = vehicle:get_mode() -- are we doing a doublet on elevator or rudder? set the other controls to trim local doublet_choice_pwm = rc:get_pwm(DOUBLET_CHOICE_CHANNEL) - local trim_funcs = {} + local trim_funcs local pre_doublet_elevator = SRV_Channels:get_output_pwm(K_ELEVATOR) if doublet_choice_pwm < 1500 then -- doublet on elevator diff --git a/libraries/AP_Scripting/examples/protected_call.lua b/libraries/AP_Scripting/examples/protected_call.lua index 7446092c5f4e2c..ff7cf45cd7a402 100644 --- a/libraries/AP_Scripting/examples/protected_call.lua +++ b/libraries/AP_Scripting/examples/protected_call.lua @@ -1,7 +1,6 @@ -- this shows how to protect against faults in your scripts -- you can wrap your update() call (or any other call) in a pcall() -- which catches errors, allowing you to take an appropriate action --- luacheck: only 0 -- example main loop function @@ -12,6 +11,7 @@ function update() -- deliberately make a bad call to cause a fault, asking for the 6th GPS status -- as this is done inside a pcall() the error will be caught instead of stopping the script local status = gps:status(5) + gcs:send_text(0, "GPS status: " .. tostring(status)) end end diff --git a/libraries/AP_Scripting/examples/quadruped.lua b/libraries/AP_Scripting/examples/quadruped.lua index b36391e9899040..a8d5536512d7de 100644 --- a/libraries/AP_Scripting/examples/quadruped.lua +++ b/libraries/AP_Scripting/examples/quadruped.lua @@ -18,7 +18,6 @@ -- Output12: back right tibia (shin) servo -- -- CAUTION: This script should only be used with ArduPilot Rover's firmware --- luacheck: only 0 local FRAME_LEN = 80 -- frame length in mm @@ -183,7 +182,7 @@ end -- a) body rotations: body_rot_x, body_rot_y, body_rot_z -- b) body position: body_pos_x, body_pos_y, body_pos_z -- c) offset of the center of body -function body_forward_kinematics(X, Y, Z, Xdist, Ydist, Zrot) +function body_forward_kinematics(X, Y, _, Xdist, Ydist, Zrot) local totaldist_x = X + Xdist + body_pos_x local totaldist_y = Y + Ydist + body_pos_y local distBodyCenterFeet = math.sqrt(totaldist_x^2 + totaldist_y^2) diff --git a/libraries/AP_Scripting/examples/test_load.lua b/libraries/AP_Scripting/examples/test_load.lua index 0178cf0ed9708e..f09d6a48274036 100644 --- a/libraries/AP_Scripting/examples/test_load.lua +++ b/libraries/AP_Scripting/examples/test_load.lua @@ -7,7 +7,6 @@ gcs:send_text(0,"Testing load() method") -- a function written as a string. This could come from a file -- or any other source (eg. mavlink) -- Note that the [[ xxx ]] syntax is just a multi-line string --- luacheck: only 0 local func_str = [[ function TestFunc(x,y) @@ -23,9 +22,9 @@ function test_load() return end -- run the code within a protected call to catch any errors - local success, err = pcall(f) + local success, err2 = pcall(f) if not success then - gcs:send_text(0, string.format("Failed to load TestFunc: %s", err)) + gcs:send_text(0, string.format("Failed to load TestFunc: %s", err2)) return end From c6c41cb60962386c042b6c84a31ddba9b7b5af9d Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Mon, 31 Jul 2023 15:52:31 -0500 Subject: [PATCH 0081/1335] AP_Scripting: mount-djirs2: fix parsing for latest firmware DJI R SDK version 2.2.0.5 released on October 30, 2020 added CmdSet and CmdID bytes to reply frames before the data segment which need to be skipped when parsing replies. Tested with gimbal firmware 01.04.00.20 and 01.05.00.20 (latest version). --- .../drivers/mount-djirs2-driver.lua | 18 +++++++++--------- .../drivers/mount-djirs2-driver.md | 7 +++++++ 2 files changed, 16 insertions(+), 9 deletions(-) diff --git a/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua b/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua index ac050cabc66339..013c28b0c7a0a7 100644 --- a/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua +++ b/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua @@ -653,12 +653,12 @@ function parse_byte(b) end -- parse attitude reply message - if (expected_reply == REPLY_TYPE.ATTITUDE) and (parse_length >= 20) then - local ret_code = parse_buff[13] + if (expected_reply == REPLY_TYPE.ATTITUDE) and (parse_length >= 22) then + local ret_code = parse_buff[15] if ret_code == RETURN_CODE.SUCCESS then - local yaw_deg = int16_value(parse_buff[16],parse_buff[15]) * 0.1 - local pitch_deg = int16_value(parse_buff[18],parse_buff[17]) * 0.1 - local roll_deg = int16_value(parse_buff[20],parse_buff[19]) * 0.1 + local yaw_deg = int16_value(parse_buff[18],parse_buff[17]) * 0.1 + local pitch_deg = int16_value(parse_buff[20],parse_buff[19]) * 0.1 + local roll_deg = int16_value(parse_buff[22],parse_buff[21]) * 0.1 mount:set_attitude_euler(MOUNT_INSTANCE, roll_deg, pitch_deg, yaw_deg) if DJIR_DEBUG:get() > 1 then gcs:send_text(MAV_SEVERITY.INFO, string.format("DJIR: roll:%4.1f pitch:%4.1f yaw:%4.1f", roll_deg, pitch_deg, yaw_deg)) @@ -669,16 +669,16 @@ function parse_byte(b) end -- parse position control reply message - if (expected_reply == REPLY_TYPE.POSITION_CONTROL) and (parse_length >= 13) then - local ret_code = parse_buff[13] + if (expected_reply == REPLY_TYPE.POSITION_CONTROL) and (parse_length >= 15) then + local ret_code = parse_buff[15] if ret_code ~= RETURN_CODE.SUCCESS then execute_fails = execute_fails + 1 end end -- parse speed control reply message - if (expected_reply == REPLY_TYPE.SPEED_CONTROL) and (parse_length >= 13) then - local ret_code = parse_buff[13] + if (expected_reply == REPLY_TYPE.SPEED_CONTROL) and (parse_length >= 15) then + local ret_code = parse_buff[15] if ret_code ~= RETURN_CODE.SUCCESS then execute_fails = execute_fails + 1 end diff --git a/libraries/AP_Scripting/drivers/mount-djirs2-driver.md b/libraries/AP_Scripting/drivers/mount-djirs2-driver.md index d4b19886e2354f..7f4d6e058c36b9 100644 --- a/libraries/AP_Scripting/drivers/mount-djirs2-driver.md +++ b/libraries/AP_Scripting/drivers/mount-djirs2-driver.md @@ -12,3 +12,10 @@ DJI RS2 and RS3-Pro gimbal mount driver lua script - Set MNT1_TYPE = 9 (Scripting) to enable the mount/gimbal scripting driver - Reboot the autopilot - Copy the mount-djirs2-driver.lua script to the autopilot's SD card in the APM/scripts directory and reboot the autopilot + +## Issues + +If the ground station reports "Pre-arm: Mount not healthy", update the +gimbal firmware using the DJI Ronin phone app to version 01.04.00.20 or +later to correct a mismatch in the way data is received from the gimbal. +Completing this update may take more than an hour. From b507075701ac7abf6fc6bcf0a364e0651dbbe6a4 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 4 Dec 2023 11:46:13 +0900 Subject: [PATCH 0082/1335] AP_Scripting: mount-djir2 handles both legacy and latest ver --- .../drivers/mount-djirs2-driver.lua | 42 +++++++++++++++---- 1 file changed, 33 insertions(+), 9 deletions(-) diff --git a/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua b/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua index 013c28b0c7a0a7..77e5f95b5a8f9c 100644 --- a/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua +++ b/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua @@ -118,6 +118,9 @@ local MNT1_TYPE = Parameter("MNT1_TYPE") -- should be 9:Scripting -- message definitions local HEADER = 0xAA local RETURN_CODE = {SUCCESS=0x00, PARSE_ERROR=0x01, EXECUTION_FAILED=0x02, UNDEFINED=0xFF} +local ATTITUDE_PACKET_LEN = {LEGACY=24, LATEST=26} -- attitude packet expected length. Legacy must be less than latest +local POSITION_CONTROL_PACKET_LEN = {LEGACY=17, LATEST=19} -- position control packet expected length. Legacy must be less than latest +local SPEED_CONTROL_PACKET_LEN = {LEGACY=17, LATEST=19} -- speed control packet expected length. Legacy must be less than latest -- parsing state definitions local PARSE_STATE_WAITING_FOR_HEADER = 0 @@ -653,12 +656,23 @@ function parse_byte(b) end -- parse attitude reply message - if (expected_reply == REPLY_TYPE.ATTITUDE) and (parse_length >= 22) then - local ret_code = parse_buff[15] + if (expected_reply == REPLY_TYPE.ATTITUDE) and (parse_length >= ATTITUDE_PACKET_LEN.LEGACY) then + -- default to legacy format but also handle latest format + local ret_code_field = 13 + local yaw_field = 15 + local pitch_field = 17 + local roll_field = 19 + if (parse_length >= ATTITUDE_PACKET_LEN.LATEST) then + ret_code_field = 15 + yaw_field = 17 + pitch_field = 21 + roll_field = 19 + end + local ret_code = parse_buff[ret_code_field] if ret_code == RETURN_CODE.SUCCESS then - local yaw_deg = int16_value(parse_buff[18],parse_buff[17]) * 0.1 - local pitch_deg = int16_value(parse_buff[20],parse_buff[19]) * 0.1 - local roll_deg = int16_value(parse_buff[22],parse_buff[21]) * 0.1 + local yaw_deg = int16_value(parse_buff[yaw_field+1],parse_buff[yaw_field]) * 0.1 + local pitch_deg = int16_value(parse_buff[pitch_field+1],parse_buff[pitch_field]) * 0.1 + local roll_deg = int16_value(parse_buff[roll_field+1],parse_buff[roll_field]) * 0.1 mount:set_attitude_euler(MOUNT_INSTANCE, roll_deg, pitch_deg, yaw_deg) if DJIR_DEBUG:get() > 1 then gcs:send_text(MAV_SEVERITY.INFO, string.format("DJIR: roll:%4.1f pitch:%4.1f yaw:%4.1f", roll_deg, pitch_deg, yaw_deg)) @@ -669,16 +683,26 @@ function parse_byte(b) end -- parse position control reply message - if (expected_reply == REPLY_TYPE.POSITION_CONTROL) and (parse_length >= 15) then - local ret_code = parse_buff[15] + if (expected_reply == REPLY_TYPE.POSITION_CONTROL) and (parse_length >= POSITION_CONTROL_PACKET_LEN.LEGACY) then + -- default to legacy format but also handle latest format + local ret_code_field = 13 + if (parse_length >= POSITION_CONTROL_PACKET_LEN.LATEST) then + ret_code_field = 15 + end + local ret_code = parse_buff[ret_code_field] if ret_code ~= RETURN_CODE.SUCCESS then execute_fails = execute_fails + 1 end end -- parse speed control reply message - if (expected_reply == REPLY_TYPE.SPEED_CONTROL) and (parse_length >= 15) then - local ret_code = parse_buff[15] + if (expected_reply == REPLY_TYPE.SPEED_CONTROL) and (parse_length >= SPEED_CONTROL_PACKET_LEN.LEGACY) then + -- default to legacy format but also handle latest format + local ret_code_field = 13 + if (parse_length >= SPEED_CONTROL_PACKET_LEN.LATEST) then + ret_code_field = 15 + end + local ret_code = parse_buff[ret_code_field] if ret_code ~= RETURN_CODE.SUCCESS then execute_fails = execute_fails + 1 end From 95033b2ef5514db3fb81b4c98493f3f45180fd28 Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Mon, 4 Dec 2023 12:43:42 +0900 Subject: [PATCH 0083/1335] AP_Scripting: mount-djirs2 yaw angle reporting fix --- libraries/AP_Scripting/drivers/mount-djirs2-driver.lua | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua b/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua index 77e5f95b5a8f9c..7c6272600fb4e3 100644 --- a/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua +++ b/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua @@ -673,6 +673,10 @@ function parse_byte(b) local yaw_deg = int16_value(parse_buff[yaw_field+1],parse_buff[yaw_field]) * 0.1 local pitch_deg = int16_value(parse_buff[pitch_field+1],parse_buff[pitch_field]) * 0.1 local roll_deg = int16_value(parse_buff[roll_field+1],parse_buff[roll_field]) * 0.1 + -- if upsidedown, subtract 180deg from yaw to undo addition of target + if DJIR_UPSIDEDOWN:get() > 0 then + yaw_deg = wrap_180(yaw_deg - 180) + end mount:set_attitude_euler(MOUNT_INSTANCE, roll_deg, pitch_deg, yaw_deg) if DJIR_DEBUG:get() > 1 then gcs:send_text(MAV_SEVERITY.INFO, string.format("DJIR: roll:%4.1f pitch:%4.1f yaw:%4.1f", roll_deg, pitch_deg, yaw_deg)) From 56a2474e1ce89e38f81ff307c07eedb47f529f37 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 4 Dec 2023 13:19:08 +0900 Subject: [PATCH 0084/1335] AP_Scripting: djirs2 reply timeout reduced to 0.1 sec --- libraries/AP_Scripting/drivers/mount-djirs2-driver.lua | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua b/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua index 7c6272600fb4e3..61113d05d7d545 100644 --- a/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua +++ b/libraries/AP_Scripting/drivers/mount-djirs2-driver.lua @@ -74,7 +74,7 @@ -- global definitions local INIT_INTERVAL_MS = 3000 -- attempt to initialise the gimbal at this interval local UPDATE_INTERVAL_MS = 1 -- update interval in millis -local REPLY_TIMEOUT_MS = 1000 -- timeout waiting for reply after 1 sec +local REPLY_TIMEOUT_MS = 100 -- timeout waiting for reply after 0.1 sec local REQUEST_ATTITUDE_INTERVAL_MS = 100-- request attitude at 10hz local SET_ATTITUDE_INTERVAL_MS = 100 -- set attitude at 10hz local MOUNT_INSTANCE = 0 -- always control the first mount/gimbal From 3ba2f3117fc645496121ef08c5111021eb99c9a0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 12 Dec 2023 09:21:15 +1100 Subject: [PATCH 0085/1335] AP_Arming: correct compilation when logging not available --- libraries/AP_Arming/AP_Arming.cpp | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index e51f3c75704f79..fc836b90d4ba54 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -324,6 +324,7 @@ bool AP_Arming::airspeed_checks(bool report) return true; } +#if HAL_LOGGING_ENABLED bool AP_Arming::logging_checks(bool report) { if (check_enabled(ARMING_CHECK_LOGGING)) { @@ -346,6 +347,7 @@ bool AP_Arming::logging_checks(bool report) } return true; } +#endif // HAL_LOGGING_ENABLED #if AP_INERTIALSENSOR_ENABLED bool AP_Arming::ins_accels_consistent(const AP_InertialSensor &ins) @@ -1561,7 +1563,9 @@ bool AP_Arming::pre_arm_checks(bool report) & compass_checks(report) & gps_checks(report) & battery_checks(report) +#if HAL_LOGGING_ENABLED & logging_checks(report) +#endif #if AP_RC_CHANNEL_ENABLED & manual_transmitter_checks(report) #endif @@ -1660,10 +1664,14 @@ bool AP_Arming::arm(AP_Arming::Method method, const bool do_arming_checks) _last_arm_method = method; +#if HAL_LOGGING_ENABLED Log_Write_Arm(!do_arming_checks, method); // note Log_Write_Armed takes forced not do_arming_checks +#endif } else { +#if HAL_LOGGING_ENABLED AP::logger().arming_failure(); +#endif armed = false; } @@ -1719,9 +1727,11 @@ bool AP_Arming::disarm(const AP_Arming::Method method, bool do_disarm_checks) armed = false; _last_disarm_method = method; +#if HAL_LOGGING_ENABLED Log_Write_Disarm(!do_disarm_checks, method); // Log_Write_Disarm takes "force" check_forced_logging(method); +#endif #if HAL_HAVE_SAFETY_SWITCH AP_BoardConfig *board_cfg = AP_BoardConfig::get_singleton(); @@ -1849,6 +1859,7 @@ bool AP_Arming::disarm_switch_checks(bool display_failure) const } #endif // AP_RC_CHANNEL_ENABLED +#if HAL_LOGGING_ENABLED void AP_Arming::Log_Write_Arm(const bool forced, const AP_Arming::Method method) { const struct log_Arm_Disarm pkt { @@ -1927,6 +1938,7 @@ void AP_Arming::check_forced_logging(const AP_Arming::Method method) return; } } +#endif // HAL_LOGGING_ENABLED AP_Arming *AP_Arming::_singleton = nullptr; From 66da78abaf406fa4e112c15f89db94103ee088f4 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 12 Dec 2023 15:31:06 +1100 Subject: [PATCH 0086/1335] AP_Logger: correct compilation with AP_RSSI disabled --- libraries/AP_Logger/LogFile.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_Logger/LogFile.cpp b/libraries/AP_Logger/LogFile.cpp index 0666943e94b87e..e4d3f1ff895b79 100644 --- a/libraries/AP_Logger/LogFile.cpp +++ b/libraries/AP_Logger/LogFile.cpp @@ -248,6 +248,7 @@ void AP_Logger::Write_RCOUT(void) } +#if AP_RSSI_ENABLED // Write an RSSI packet void AP_Logger::Write_RSSI() { @@ -264,6 +265,7 @@ void AP_Logger::Write_RSSI() }; WriteBlock(&pkt, sizeof(pkt)); } +#endif void AP_Logger::Write_Command(const mavlink_command_int_t &packet, uint8_t source_system, From 70cc84dd89d416f58fb1c18bd24803f65e65662d Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 12 Dec 2023 17:35:29 +1100 Subject: [PATCH 0087/1335] GCS_Common: correct compilation when AP_RSSI_ENABLED is false --- libraries/GCS_MAVLink/GCS_Common.cpp | 16 ++++++++++++++-- 1 file changed, 14 insertions(+), 2 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 377c08304183d2..1e706b8b008038 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1997,7 +1997,12 @@ void GCS_MAVLINK::send_rc_channels() const values[15], values[16], values[17], - receiver_rssi()); +#if AP_RSSI_ENABLED + receiver_rssi() +#else + 255 // meaning "unknown" +#endif + ); } bool GCS_MAVLINK::sending_mavlink1() const @@ -2028,7 +2033,12 @@ void GCS_MAVLINK::send_rc_channels_raw() const values[5], values[6], values[7], - receiver_rssi()); +#if AP_RSSI_ENABLED + receiver_rssi() +#else + 255 // meaning "unknown" +#endif +); } void GCS_MAVLINK::send_raw_imu() @@ -6643,6 +6653,7 @@ void GCS_MAVLINK::handle_manual_control(const mavlink_message_t &msg) } +#if AP_RSSI_ENABLED uint8_t GCS_MAVLINK::receiver_rssi() const { AP_RSSI *aprssi = AP::rssi(); @@ -6657,6 +6668,7 @@ uint8_t GCS_MAVLINK::receiver_rssi() const // scale across the full valid range return aprssi->read_receiver_rssi() * 254; } +#endif GCS &gcs() { From 8ef98c0f4150dff75613d4a6804270e9b9066ff6 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 12 Dec 2023 23:10:17 +1100 Subject: [PATCH 0088/1335] AP_Arming: correct compilation when AP_Vehicle not available --- libraries/AP_Arming/AP_Arming.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index fc836b90d4ba54..6a8bae36ccb1f8 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -902,6 +902,7 @@ bool AP_Arming::mission_checks(bool report) } #endif +#if AP_VEHICLE_ENABLED // do not allow arming if there are no mission items and we are in // (e.g.) AUTO mode if (AP::vehicle()->current_mode_requires_mission() && @@ -909,6 +910,7 @@ bool AP_Arming::mission_checks(bool report) check_failed(ARMING_CHECK_MISSION, report, "Mode requires mission"); return false; } +#endif return true; } From 105acc605f4b591d89472a82697a48b6c0e9b287 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 12 Dec 2023 23:10:17 +1100 Subject: [PATCH 0089/1335] AP_DAL: correct compilation when AP_Vehicle not available --- libraries/AP_DAL/AP_DAL.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/libraries/AP_DAL/AP_DAL.cpp b/libraries/AP_DAL/AP_DAL.cpp index 0e4f309fad0b86..b05c411e5d523c 100644 --- a/libraries/AP_DAL/AP_DAL.cpp +++ b/libraries/AP_DAL/AP_DAL.cpp @@ -6,6 +6,7 @@ #include #include #include +#include #if APM_BUILD_TYPE(APM_BUILD_Replay) #include @@ -46,8 +47,12 @@ void AP_DAL::start_frame(AP_DAL::FrameType frametype) end_frame(); _RFRF.frame_types = uint8_t(frametype); - + +#if AP_VEHICLE_ENABLED _RFRH.time_flying_ms = AP::vehicle()->get_time_flying_ms(); +#else + _RFRH.time_flying_ms = 0; +#endif _RFRH.time_us = AP_HAL::micros64(); WRITE_REPLAY_BLOCK(RFRH, _RFRH); From 0f4262de3d6cfec5443653be466b01f5885c4d9f Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 12 Dec 2023 23:10:17 +1100 Subject: [PATCH 0090/1335] AP_Scheduler: correct compilation when AP_Vehicle not available --- libraries/AP_Scheduler/AP_Scheduler.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AP_Scheduler/AP_Scheduler.cpp b/libraries/AP_Scheduler/AP_Scheduler.cpp index abfbf2fec5614f..93f55a22778646 100644 --- a/libraries/AP_Scheduler/AP_Scheduler.cpp +++ b/libraries/AP_Scheduler/AP_Scheduler.cpp @@ -31,6 +31,7 @@ #include #include #include +#include #if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include @@ -113,10 +114,12 @@ void AP_Scheduler::init(const AP_Scheduler::Task *tasks, uint8_t num_tasks, uint _vehicle_tasks = tasks; _num_vehicle_tasks = num_tasks; +#if AP_VEHICLE_ENABLED AP_Vehicle* vehicle = AP::vehicle(); if (vehicle != nullptr) { vehicle->get_common_scheduler_tasks(_common_tasks, _num_common_tasks); } +#endif _num_tasks = _num_vehicle_tasks + _num_common_tasks; From 8e1fc605504253f86fddaeee89a3c712be0ba2c2 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 12 Dec 2023 23:10:18 +1100 Subject: [PATCH 0091/1335] AP_Vehicle: correct compilation when AP_Vehicle not available --- libraries/AP_Vehicle/AP_Vehicle.cpp | 5 +++++ libraries/AP_Vehicle/AP_Vehicle.h | 6 ++++++ libraries/AP_Vehicle/AP_Vehicle_config.h | 5 +++++ 3 files changed, 16 insertions(+) create mode 100644 libraries/AP_Vehicle/AP_Vehicle_config.h diff --git a/libraries/AP_Vehicle/AP_Vehicle.cpp b/libraries/AP_Vehicle/AP_Vehicle.cpp index 7a1595b7e5dc06..9908cf767d60fe 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.cpp +++ b/libraries/AP_Vehicle/AP_Vehicle.cpp @@ -1,3 +1,7 @@ +#include "AP_Vehicle_config.h" + +#if AP_VEHICLE_ENABLED + #include "AP_Vehicle.h" #include @@ -1029,3 +1033,4 @@ AP_Vehicle *vehicle() }; +#endif // AP_VEHICLE_ENABLED diff --git a/libraries/AP_Vehicle/AP_Vehicle.h b/libraries/AP_Vehicle/AP_Vehicle.h index 38e65f071fb4ab..1ccbe4d5500140 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.h +++ b/libraries/AP_Vehicle/AP_Vehicle.h @@ -14,6 +14,10 @@ */ #pragma once +#include "AP_Vehicle_config.h" + +#if AP_VEHICLE_ENABLED + /* this header holds a parameter structure for each vehicle type for parameters needed by multiple libraries @@ -490,3 +494,5 @@ extern const AP_HAL::HAL& hal; extern const AP_Param::Info vehicle_var_info[]; #include "AP_Vehicle_Type.h" + +#endif // AP_VEHICLE_ENABLED diff --git a/libraries/AP_Vehicle/AP_Vehicle_config.h b/libraries/AP_Vehicle/AP_Vehicle_config.h new file mode 100644 index 00000000000000..8cdfa764a05294 --- /dev/null +++ b/libraries/AP_Vehicle/AP_Vehicle_config.h @@ -0,0 +1,5 @@ +#pragma once + +#ifndef AP_VEHICLE_ENABLED +#define AP_VEHICLE_ENABLED 1 +#endif From 6515df72f0473b8982f3d25bdade74f5d9df8be3 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 11 Dec 2023 18:55:05 +1100 Subject: [PATCH 0092/1335] GCS_MAVLink: correct compilation when AP_Vehicle disabled --- libraries/GCS_MAVLink/GCS_Common.cpp | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 1e706b8b008038..f2fb1c5bb04c3e 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -71,6 +71,7 @@ #include "MissionItemProtocol_Fence.h" #include +#include #include @@ -656,7 +657,11 @@ void GCS_MAVLINK::send_mission_current(const class AP_Mission &mission, uint16_t num_commands -= 1; } +#if AP_VEHICLE_ENABLED const uint8_t mission_mode = AP::vehicle()->current_mode_requires_mission() ? 1 : 0; +#else + const uint8_t mission_mode = 0; +#endif mavlink_msg_mission_current_send( chan, @@ -2603,6 +2608,7 @@ void GCS_MAVLINK::handle_set_mode(const mavlink_message_t &msg) MAV_RESULT GCS_MAVLINK::_set_mode_common(const MAV_MODE _base_mode, const uint32_t _custom_mode) { // only accept custom modes because there is no easy mapping from Mavlink flight modes to AC flight modes +#if AP_VEHICLE_ENABLED if (uint32_t(_base_mode) & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) { if (!AP::vehicle()->set_mode(_custom_mode, ModeReason::GCS_COMMAND)) { // often we should be returning DENIED rather than FAILED @@ -2612,6 +2618,7 @@ MAV_RESULT GCS_MAVLINK::_set_mode_common(const MAV_MODE _base_mode, const uint32 } return MAV_RESULT_ACCEPTED; } +#endif if (_base_mode == (MAV_MODE)MAV_MODE_FLAG_DECODE_POSITION_SAFETY) { // set the safety switch position. Must be in a command by itself @@ -3285,7 +3292,11 @@ MAV_RESULT GCS_MAVLINK::handle_preflight_reboot(const mavlink_command_int_t &pac // when packet.param1 == 3 we reboot to hold in bootloader const bool hold_in_bootloader = is_equal(packet.param1, 3.0f); +#if AP_VEHICLE_ENABLED AP::vehicle()->reboot(hold_in_bootloader); // not expected to return +#else + hal.scheduler->reboot(hold_in_bootloader); +#endif return MAV_RESULT_FAILED; } @@ -5629,10 +5640,12 @@ void GCS_MAVLINK::send_autopilot_state_for_gimbal_device() const // get vehicle earth-frame rotation rate targets Vector3f rate_ef_targets; +#if AP_VEHICLE_ENABLED const AP_Vehicle *vehicle = AP::vehicle(); if (vehicle != nullptr) { vehicle->get_rate_ef_targets(rate_ef_targets); } +#endif // get estimator flags uint16_t est_status_flags = 0; From 56cc78b8538487eaa1d47160e2e59d597292338b Mon Sep 17 00:00:00 2001 From: Abu Mohammad Date: Thu, 14 Dec 2023 10:41:16 +0300 Subject: [PATCH 0093/1335] Tools: added name to GIT_Success.txt --- Tools/GIT_Test/GIT_Success.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/GIT_Test/GIT_Success.txt b/Tools/GIT_Test/GIT_Success.txt index 9f00eea02a121e..2b89570700cd59 100644 --- a/Tools/GIT_Test/GIT_Success.txt +++ b/Tools/GIT_Test/GIT_Success.txt @@ -178,3 +178,4 @@ seba czapnik Ramy Gad Matthew R. Cunningham prathap devendran (Tamil) india, 11-23 +Taqwaisneeded From 61b3ad326dda41449bbd0f954cea126b19b3028a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 3 Dec 2023 11:36:18 +1100 Subject: [PATCH 0094/1335] AP_Scripting: added SCR_THD_PRIORITY parameter this makes it possible to run lua scripts at higher priorities, which makes real time lua scripts (such as IMU drivers) possible --- libraries/AP_Scripting/AP_Scripting.cpp | 31 ++++++++++++++++++++++++- libraries/AP_Scripting/AP_Scripting.h | 13 +++++++++++ 2 files changed, 43 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Scripting/AP_Scripting.cpp b/libraries/AP_Scripting/AP_Scripting.cpp index 82c6f220cbf789..1240c6e070b2cc 100644 --- a/libraries/AP_Scripting/AP_Scripting.cpp +++ b/libraries/AP_Scripting/AP_Scripting.cpp @@ -153,6 +153,14 @@ const AP_Param::GroupInfo AP_Scripting::var_info[] = { // @User: Advanced AP_GROUPINFO("RUN_CHECKSUM", 13, AP_Scripting, _required_running_checksum, -1), + // @Param: THD_PRIORITY + // @DisplayName: Scripting thread priority + // @Description: This sets the priority of the scripting thread. This is normally set to a low priority to prevent scripts from interfering with other parts of the system. Advanced users can change this priority if scripting needs to be prioritised for realtime applications. WARNING: changing this parameter can impact the stability of your flight controller. The scipting thread priority in this parameter is chosen based on a set of system level priorities for other subsystems. It is strongly recommended that you use the lowest priority that is sufficient for your application. Note that all scripts run at the same priority, so if you raise this priority you must carefully audit all lua scripts for behaviour that does not interfere with the operation of the system. + // @Values: 0:Normal, 1:IO Priority, 2:Storage Priority, 3:UART Priority, 4:I2C Priority, 5:SPI Priority, 6:Timer Priority, 7:Main Priority, 8:Boost Priority + // @RebootRequired: True + // @User: Advanced + AP_GROUPINFO("THD_PRIORITY", 14, AP_Scripting, _thd_priority, uint8_t(ThreadPriority::NORMAL)), + AP_GROUPEND }; @@ -179,8 +187,29 @@ void AP_Scripting::init(void) { } } + AP_HAL::Scheduler::priority_base priority = AP_HAL::Scheduler::PRIORITY_SCRIPTING; + static const struct { + ThreadPriority scr_priority; + AP_HAL::Scheduler::priority_base hal_priority; + } priority_map[] = { + { ThreadPriority::NORMAL, AP_HAL::Scheduler::PRIORITY_SCRIPTING }, + { ThreadPriority::IO, AP_HAL::Scheduler::PRIORITY_IO }, + { ThreadPriority::STORAGE, AP_HAL::Scheduler::PRIORITY_STORAGE }, + { ThreadPriority::UART, AP_HAL::Scheduler::PRIORITY_UART }, + { ThreadPriority::I2C, AP_HAL::Scheduler::PRIORITY_I2C }, + { ThreadPriority::SPI, AP_HAL::Scheduler::PRIORITY_SPI }, + { ThreadPriority::TIMER, AP_HAL::Scheduler::PRIORITY_TIMER }, + { ThreadPriority::MAIN, AP_HAL::Scheduler::PRIORITY_MAIN }, + { ThreadPriority::BOOST, AP_HAL::Scheduler::PRIORITY_BOOST }, + }; + for (const auto &p : priority_map) { + if (p.scr_priority == _thd_priority) { + priority = p.hal_priority; + } + } + if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Scripting::thread, void), - "Scripting", SCRIPTING_STACK_SIZE, AP_HAL::Scheduler::PRIORITY_SCRIPTING, 0)) { + "Scripting", SCRIPTING_STACK_SIZE, priority, 0)) { GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Scripting: %s", "failed to start"); _thread_failed = true; } diff --git a/libraries/AP_Scripting/AP_Scripting.h b/libraries/AP_Scripting/AP_Scripting.h index 3e68fbbb3e16d2..158ad429ac3ebc 100644 --- a/libraries/AP_Scripting/AP_Scripting.h +++ b/libraries/AP_Scripting/AP_Scripting.h @@ -159,6 +159,18 @@ class AP_Scripting // The full range of uint32 integers cannot be represented by a float. const uint32_t checksum_param_mask = 0x007FFFFF; + enum class ThreadPriority : uint8_t { + NORMAL = 0, + IO = 1, + STORAGE = 2, + UART = 3, + I2C = 4, + SPI = 5, + TIMER = 6, + MAIN = 7, + BOOST = 8 + }; + AP_Int8 _enable; AP_Int32 _script_vm_exec_count; AP_Int32 _script_heap_size; @@ -167,6 +179,7 @@ class AP_Scripting AP_Int32 _required_loaded_checksum; AP_Int32 _required_running_checksum; + AP_Enum _thd_priority; bool _thread_failed; // thread allocation failed bool _init_failed; // true if memory allocation failed From ddccc92e7dd92dbf28805ee0778ee355c066b323 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 1 Dec 2023 08:59:18 +1100 Subject: [PATCH 0095/1335] AP_Math: added rfu_to_frd() method for Vector3 --- libraries/AP_Math/vector3.h | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/libraries/AP_Math/vector3.h b/libraries/AP_Math/vector3.h index 08f6337cef4d90..d4d3a1baa63cb2 100644 --- a/libraries/AP_Math/vector3.h +++ b/libraries/AP_Math/vector3.h @@ -281,6 +281,12 @@ class Vector3 return Vector3{x,y,z}; } + // convert from right-front-up to front-right-down + // or ENU to NED + Vector3 rfu_to_frd() const { + return Vector3{y,x,-z}; + } + // given a position p1 and a velocity v1 produce a vector // perpendicular to v1 maximising distance from p1. If p1 is the // zero vector the return from the function will always be the From ee1975d47a68e59556fc1f25184a8aaca32ed0ef Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 1 Dec 2023 08:59:32 +1100 Subject: [PATCH 0096/1335] AP_Math: added tesla conversions --- libraries/AP_Math/definitions.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AP_Math/definitions.h b/libraries/AP_Math/definitions.h index 024838a1c62c94..7317a19906e0b4 100644 --- a/libraries/AP_Math/definitions.h +++ b/libraries/AP_Math/definitions.h @@ -95,6 +95,9 @@ static const double WGS84_E = (sqrt(2 * WGS84_F - WGS84_F * WGS84_F)); #define INCH_OF_H2O_TO_PASCAL 248.84f +#define UTESLA_TO_MGAUSS 10.0f // uT to mGauss conversion +#define NTESLA_TO_MGAUSS 0.01f // nT to mGauss conversion + /* use AP_ prefix to prevent conflict with OS headers, such as NuttX clock.h From 80730d6c02bebc5d36b520c80af757c977e60ce5 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 1 Dec 2023 08:59:51 +1100 Subject: [PATCH 0097/1335] AP_Compass: use tesla conversion from AP_Math/definitions.h --- libraries/AP_Compass/AP_Compass_RM3100.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/libraries/AP_Compass/AP_Compass_RM3100.cpp b/libraries/AP_Compass/AP_Compass_RM3100.cpp index b191a6b52b7ca4..7e4fd7970b5819 100644 --- a/libraries/AP_Compass/AP_Compass_RM3100.cpp +++ b/libraries/AP_Compass/AP_Compass_RM3100.cpp @@ -61,7 +61,6 @@ #define GAIN_CC50 20.0f // LSB/uT #define GAIN_CC100 38.0f #define GAIN_CC200 75.0f -#define UTESLA_TO_MGAUSS 10.0f // uT to mGauss conversion #define TMRC 0x94 // Update rate 150Hz #define CMM 0x71 // read 3 axes and set data ready if 3 axes are ready From 376426a088f752dad3898643039cab592bd81422 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 16 Sep 2023 09:19:01 +1000 Subject: [PATCH 0098/1335] RC_Channel: added AUX function 112 for AHRS EKF type changes --- libraries/RC_Channel/RC_Channel.cpp | 10 ++++++++++ libraries/RC_Channel/RC_Channel.h | 1 + 2 files changed, 11 insertions(+) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index fb85273f26eccb..32023fe9ab9199 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -207,6 +207,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = { // @Values{Plane}: 108:QRTL Mode // @Values{Copter}: 109:use Custom Controller // @Values{Copter, Rover, Plane, Blimp}: 110:KillIMU3 + // @Values{Copter,Plane,Rover,Blimp,Sub,Tracker}: 112:SwitchExternalAHRS // @Values{Plane}: 150:CRUISE Mode // @Values{Copter}: 151:TURTLE Mode // @Values{Copter}: 152:SIMPLE heading reset @@ -700,6 +701,7 @@ void RC_Channel::init_aux_function(const aux_func_t ch_option, const AuxSwitchPo case AUX_FUNC::CAMERA_MANUAL_FOCUS: case AUX_FUNC::CAMERA_AUTO_FOCUS: case AUX_FUNC::CAMERA_LENS: + case AUX_FUNC::AHRS_TYPE: run_aux_function(ch_option, ch_flag, AuxFuncTriggerSource::INIT); break; default: @@ -1613,6 +1615,14 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos AP::ahrs().request_yaw_reset(); break; + case AUX_FUNC::AHRS_TYPE: { +#if HAL_NAVEKF3_AVAILABLE && HAL_EXTERNAL_AHRS_ENABLED + AP::ahrs().set_ekf_type(ch_flag==AuxSwitchPos::HIGH? 11 : 3); +#endif + break; + } + + #if HAL_TORQEEDO_ENABLED // clear torqeedo error case AUX_FUNC::TORQEEDO_CLEAR_ERR: { diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index bf9d70f5bcf4ed..fcf61047733450 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -216,6 +216,7 @@ class RC_Channel { CUSTOM_CONTROLLER = 109, // use Custom Controller KILL_IMU3 = 110, // disable third IMU (for IMU failure testing) LOWEHEISER_STARTER = 111, // allows for manually running starter + AHRS_TYPE = 112, // change AHRS_EKF_TYPE // if you add something here, make sure to update the documentation of the parameter in RC_Channel.cpp! // also, if you add an option >255, you will need to fix duplicate_options_exist From cbc14d1fa5e9ece28277ea501cf4caa6cb5ec89e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 2 Dec 2023 08:59:27 +1100 Subject: [PATCH 0099/1335] AP_ExternalAHRS: align origin with AHRS origin automatically set origin to AHRS origin. This means if on boot external AHRS is not the primary then it will use the origin from the active backend, preventing a jump on change of backends --- libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp | 15 +++++++++++++++ 1 file changed, 15 insertions(+) diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp index f75d6ac1d4fd7d..8d9881011106c2 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp @@ -27,6 +27,7 @@ #include "AP_ExternalAHRS_MicroStrain7.h" #include +#include extern const AP_HAL::HAL &hal; @@ -242,6 +243,20 @@ void AP_ExternalAHRS::update(void) if (backend) { backend->update(); } + + /* + if backend has not supplied an origin and AHRS has an origin + then use that origin so we get a common origin for minimum + disturbance when switching backends + */ + WITH_SEMAPHORE(state.sem); + if (!state.have_origin) { + Location origin; + if (AP::ahrs().get_origin(origin)) { + state.origin = origin; + state.have_origin = true; + } + } } // Get model/type name From 3954425f773b87bed88b303fe82f44a27acba3d9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 2 Dec 2023 11:52:50 +1100 Subject: [PATCH 0100/1335] AP_ExternalAHRS: allow backends to set default sensor set --- libraries/AP_ExternalAHRS/AP_ExternalAHRS.h | 5 +++++ libraries/AP_ExternalAHRS/AP_ExternalAHRS_backend.h | 5 +++++ 2 files changed, 10 insertions(+) diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h index c825b0f609b6b8..cdd2d63fdd285e 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h @@ -175,6 +175,11 @@ class AP_ExternalAHRS { bool has_sensor(AvailableSensor sensor) const { return (uint16_t(sensors.get()) & uint16_t(sensor)) != 0; } + + // set default of EAHRS_SENSORS + void set_default_sensors(uint16_t _sensors) { + sensors.set_default(_sensors); + } }; namespace AP { diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_backend.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_backend.h index 07436b7ae43888..02eb1b5319b7d0 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_backend.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_backend.h @@ -53,6 +53,11 @@ class AP_ExternalAHRS_backend { uint16_t get_rate(void) const; bool option_is_set(AP_ExternalAHRS::OPTIONS option) const; + // set default of EAHRS_SENSORS + void set_default_sensors(uint16_t sensors) { + frontend.set_default_sensors(sensors); + } + private: AP_ExternalAHRS &frontend; }; From 771dfdf8262a712a70fd5dfacc768ae9b3a8db8e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 2 Dec 2023 12:10:08 +1100 Subject: [PATCH 0101/1335] AP_ExternalAHRS: added location extrapolation this copes better with slow backends --- libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp | 13 +++++++++++++ libraries/AP_ExternalAHRS/AP_ExternalAHRS.h | 2 ++ .../AP_ExternalAHRS_MicroStrain5.cpp | 1 + .../AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp | 1 + 4 files changed, 17 insertions(+) diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp index 8d9881011106c2..a18659028caa6b 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp @@ -167,6 +167,19 @@ bool AP_ExternalAHRS::get_location(Location &loc) } WITH_SEMAPHORE(state.sem); loc = state.location; + + if (state.last_location_update_us != 0 && + state.have_velocity) { + // extrapolate position based on velocity to cope with slow backends + const float dt = (AP_HAL::micros() - state.last_location_update_us)*1.0e-6; + if (dt < 1) { + // only extrapolate for 1s max + Vector3p ofs = state.velocity.topostype(); + ofs *= dt; + loc.offset(ofs); + } + } + return true; } diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h index cdd2d63fdd285e..da36e5d706d1d5 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h @@ -96,6 +96,8 @@ class AP_ExternalAHRS { bool have_origin; bool have_location; bool have_velocity; + + uint32_t last_location_update_us; } state; // accessors for AP_AHRS diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.cpp index 141b4ff857e7c9..ed6304429c28d8 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain5.cpp @@ -163,6 +163,7 @@ void AP_ExternalAHRS_MicroStrain5::post_filter() const state.location = Location{filter_data.lat, filter_data.lon, gnss_data[gnss_instance].msl_altitude, Location::AltFrame::ABSOLUTE}; state.have_location = true; + state.last_location_update_us = AP_HAL::micros(); } AP_ExternalAHRS::gps_data_message_t gps { diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp index 8e8515b70aa17d..13acaf4fc993c3 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp @@ -475,6 +475,7 @@ void AP_ExternalAHRS_VectorNav::process_packet1(const uint8_t *b) int32_t(pkt1.positionLLA[1] * 1.0e7), int32_t(pkt1.positionLLA[2] * 1.0e2), Location::AltFrame::ABSOLUTE}; + state.last_location_update_us = AP_HAL::micros(); state.have_location = true; } From bdab1054d6e722981aa982b86e4a9f1639d799d4 Mon Sep 17 00:00:00 2001 From: "patrick.wiltshire956@gmail.com" Date: Sat, 18 Nov 2023 16:44:06 +1100 Subject: [PATCH 0102/1335] AP_AHRS: added set_ekf_type() and DCM logging --- libraries/AP_AHRS/AP_AHRS.h | 6 ++++++ libraries/AP_AHRS/AP_AHRS_DCM.cpp | 16 ++++++++++++++++ libraries/AP_AHRS/AP_AHRS_DCM.h | 2 ++ 3 files changed, 24 insertions(+) diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index 0f5c985eeb1a70..25881d2f11b1b0 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -421,6 +421,11 @@ class AP_AHRS { return _ekf_type; } + // set the selected ekf type, for RC aux control + void set_ekf_type(uint8_t ahrs_type) { + _ekf_type.set(ahrs_type); + } + // these are only out here so vehicles can reference them for parameters #if HAL_NAVEKF2_AVAILABLE NavEKF2 EKF2; @@ -700,6 +705,7 @@ class AP_AHRS { EXTERNAL = 11, #endif }; + EKFType active_EKF_type(void) const { return state.active_EKF; } bool always_use_EKF() const { diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index 5dd7f681ba1951..b26bdeb472714a 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -101,6 +101,22 @@ AP_AHRS_DCM::update() // remember the last origin for fallback support IGNORE_RETURN(AP::ahrs().get_origin(last_origin)); + +#if HAL_LOGGING_ENABLED + const uint32_t now_ms = AP_HAL::millis(); + if (now_ms - last_log_ms >= 100) { + // log DCM at 10Hz + last_log_ms = now_ms; + AP::logger().WriteStreaming("DCM", "TimeUS,Roll,Pitch,Yaw", + "sddd", + "F000", + "Qfff", + AP_HAL::micros64(), + degrees(roll), + degrees(pitch), + wrap_360(degrees(yaw))); + } +#endif // HAL_LOGGING_ENABLED } void AP_AHRS_DCM::get_results(AP_AHRS_Backend::Estimates &results) diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.h b/libraries/AP_AHRS/AP_AHRS_DCM.h index 690ef22810bed0..0d3dedc5b54d96 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.h +++ b/libraries/AP_AHRS/AP_AHRS_DCM.h @@ -286,6 +286,8 @@ class AP_AHRS_DCM : public AP_AHRS_Backend { // pre-calculated trig cache: float _sin_yaw; float _cos_yaw; + + uint32_t last_log_ms; }; #endif // AP_AHRS_DCM_ENABLED From 7102205be3f20739bf55eb42c4177305f881fed0 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 1 Dec 2023 09:00:05 +1100 Subject: [PATCH 0103/1335] AP_Math: added crc_sum_of_bytes_16() --- libraries/AP_Math/crc.cpp | 14 ++++++++++---- libraries/AP_Math/crc.h | 5 ++++- 2 files changed, 14 insertions(+), 5 deletions(-) diff --git a/libraries/AP_Math/crc.cpp b/libraries/AP_Math/crc.cpp index 985a02c290baa4..de81543b485ccd 100644 --- a/libraries/AP_Math/crc.cpp +++ b/libraries/AP_Math/crc.cpp @@ -599,13 +599,19 @@ uint8_t parity(uint8_t byte) return p; } -// sums the bytes in the supplied buffer, returns that sum mod 256 -// (i.e. shoved into a uint8_t) -uint8_t crc_sum_of_bytes(uint8_t *data, uint16_t count) +// sums the bytes in the supplied buffer, returns that sum mod 0xFFFF +uint16_t crc_sum_of_bytes_16(const uint8_t *data, uint16_t count) { - uint8_t ret = 0; + uint16_t ret = 0; for (uint32_t i=0; i Date: Fri, 1 Dec 2023 13:57:44 +1100 Subject: [PATCH 0104/1335] AP_Airspeed: support external AHRS airspeed sensor --- libraries/AP_Airspeed/AP_Airspeed.cpp | 24 ++++++++ libraries/AP_Airspeed/AP_Airspeed.h | 8 +++ libraries/AP_Airspeed/AP_Airspeed_Backend.h | 3 + .../AP_Airspeed/AP_Airspeed_External.cpp | 58 +++++++++++++++++++ libraries/AP_Airspeed/AP_Airspeed_External.h | 38 ++++++++++++ libraries/AP_Airspeed/AP_Airspeed_Params.cpp | 2 +- libraries/AP_Airspeed/AP_Airspeed_config.h | 5 ++ 7 files changed, 137 insertions(+), 1 deletion(-) create mode 100644 libraries/AP_Airspeed/AP_Airspeed_External.cpp create mode 100644 libraries/AP_Airspeed/AP_Airspeed_External.h diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index a13480b531c7e9..65c0b7b2911312 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -52,6 +52,7 @@ #include "AP_Airspeed_DroneCAN.h" #include "AP_Airspeed_NMEA.h" #include "AP_Airspeed_MSP.h" +#include "AP_Airspeed_External.h" #include "AP_Airspeed_SITL.h" extern const AP_HAL::HAL &hal; @@ -433,6 +434,11 @@ void AP_Airspeed::allocate() case TYPE_MSP: #if AP_AIRSPEED_MSP_ENABLED sensor[i] = new AP_Airspeed_MSP(*this, i, 0); +#endif + break; + case TYPE_EXTERNAL: +#if AP_AIRSPEED_EXTERNAL_ENABLED + sensor[i] = new AP_Airspeed_External(*this, i); #endif break; } @@ -731,6 +737,24 @@ void AP_Airspeed::handle_msp(const MSP::msp_airspeed_data_message_t &pkt) } #endif +#if AP_AIRSPEED_EXTERNAL_ENABLED +/* + handle airspeed airspeed data + */ +void AP_Airspeed::handle_external(const AP_ExternalAHRS::airspeed_data_message_t &pkt) +{ + if (!lib_enabled()) { + return; + } + + for (uint8_t i=0; ihandle_external(pkt); + } + } +} +#endif + // @LoggerMessage: HYGR // @Description: Hygrometer data // @Field: TimeUS: Time since system startup diff --git a/libraries/AP_Airspeed/AP_Airspeed.h b/libraries/AP_Airspeed/AP_Airspeed.h index 5574f807557a67..8f6666f62b822c 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.h +++ b/libraries/AP_Airspeed/AP_Airspeed.h @@ -10,6 +10,9 @@ #if AP_AIRSPEED_MSP_ENABLED #include #endif +#if AP_AIRSPEED_EXTERNAL_ENABLED +#include +#endif class AP_Airspeed_Backend; @@ -187,6 +190,7 @@ class AP_Airspeed TYPE_NMEA_WATER=13, TYPE_MSP=14, TYPE_I2C_ASP5033=15, + TYPE_EXTERNAL=16, TYPE_SITL=100, }; @@ -208,6 +212,10 @@ class AP_Airspeed void handle_msp(const MSP::msp_airspeed_data_message_t &pkt); #endif +#if AP_AIRSPEED_EXTERNAL_ENABLED + void handle_external(const AP_ExternalAHRS::airspeed_data_message_t &pkt); +#endif + enum class CalibrationState { NOT_STARTED, IN_PROGRESS, diff --git a/libraries/AP_Airspeed/AP_Airspeed_Backend.h b/libraries/AP_Airspeed/AP_Airspeed_Backend.h index 58ca025883a7aa..bdb4dded5c562c 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_Backend.h +++ b/libraries/AP_Airspeed/AP_Airspeed_Backend.h @@ -49,6 +49,9 @@ class AP_Airspeed_Backend { virtual bool get_airspeed(float& airspeed) {return false;} virtual void handle_msp(const MSP::msp_airspeed_data_message_t &pkt) {} +#if AP_AIRSPEED_EXTERNAL_ENABLED + virtual void handle_external(const AP_ExternalAHRS::airspeed_data_message_t &pkt) {} +#endif #if AP_AIRSPEED_HYGROMETER_ENABLE // optional hygrometer support diff --git a/libraries/AP_Airspeed/AP_Airspeed_External.cpp b/libraries/AP_Airspeed/AP_Airspeed_External.cpp new file mode 100644 index 00000000000000..5fc709f069bc9b --- /dev/null +++ b/libraries/AP_Airspeed/AP_Airspeed_External.cpp @@ -0,0 +1,58 @@ +#include "AP_Airspeed_External.h" + +#if AP_AIRSPEED_EXTERNAL_ENABLED + +AP_Airspeed_External::AP_Airspeed_External(AP_Airspeed &_frontend, uint8_t _instance) : + AP_Airspeed_Backend(_frontend, _instance) +{ + set_bus_id(AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_SERIAL,0,_instance,0)); +} + +// return the current differential_pressure in Pascal +bool AP_Airspeed_External::get_differential_pressure(float &pressure) +{ + WITH_SEMAPHORE(sem); + if (press_count == 0) { + return false; + } + pressure = sum_pressure/press_count; + press_count = 0; + sum_pressure = 0; + return true; +} + +// get last temperature +bool AP_Airspeed_External::get_temperature(float &temperature) +{ + WITH_SEMAPHORE(sem); + if (temperature_count == 0) { + return false; + } + temperature = sum_temperature/temperature_count; + temperature_count = 0; + sum_temperature = 0; + return true; +} + +void AP_Airspeed_External::handle_external(const AP_ExternalAHRS::airspeed_data_message_t &pkt) +{ + WITH_SEMAPHORE(sem); + + sum_pressure += pkt.differential_pressure; + press_count++; + if (press_count > 100) { + // prevent overflow + sum_pressure /= 2; + press_count /= 2; + } + + sum_temperature += pkt.temperature; + temperature_count++; + if (temperature_count > 100) { + // prevent overflow + sum_temperature /= 2; + temperature_count /= 2; + } +} + +#endif // AP_AIRSPEED_EXTERNAL_ENABLED diff --git a/libraries/AP_Airspeed/AP_Airspeed_External.h b/libraries/AP_Airspeed/AP_Airspeed_External.h new file mode 100644 index 00000000000000..cd27d757f2ce24 --- /dev/null +++ b/libraries/AP_Airspeed/AP_Airspeed_External.h @@ -0,0 +1,38 @@ +/* + external AHRS airspeed backend + */ +#pragma once + +#include "AP_Airspeed_config.h" + +#if AP_AIRSPEED_EXTERNAL_ENABLED + +#include "AP_Airspeed_Backend.h" +#include + +class AP_Airspeed_External : public AP_Airspeed_Backend +{ +public: + AP_Airspeed_External(AP_Airspeed &airspeed, uint8_t instance); + + bool init(void) override { + return true; + } + + void handle_external(const AP_ExternalAHRS::airspeed_data_message_t &pkt) override; + + // return the current differential_pressure in Pascal + bool get_differential_pressure(float &pressure) override; + + // temperature not available via analog backend + bool get_temperature(float &temperature) override; + +private: + float sum_pressure; + uint8_t press_count; + float sum_temperature; + uint8_t temperature_count; +}; + +#endif // AP_AIRSPEED_EXTERNAL_ENABLED + diff --git a/libraries/AP_Airspeed/AP_Airspeed_Params.cpp b/libraries/AP_Airspeed/AP_Airspeed_Params.cpp index 37c6b69faa262c..749fa9d6121641 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_Params.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_Params.cpp @@ -46,7 +46,7 @@ const AP_Param::GroupInfo AP_Airspeed_Params::var_info[] = { // @Param: TYPE // @DisplayName: Airspeed type // @Description: Type of airspeed sensor - // @Values: 0:None,1:I2C-MS4525D0,2:Analog,3:I2C-MS5525,4:I2C-MS5525 (0x76),5:I2C-MS5525 (0x77),6:I2C-SDP3X,7:I2C-DLVR-5in,8:DroneCAN,9:I2C-DLVR-10in,10:I2C-DLVR-20in,11:I2C-DLVR-30in,12:I2C-DLVR-60in,13:NMEA water speed,14:MSP,15:ASP5033,100:SITL + // @Values: 0:None,1:I2C-MS4525D0,2:Analog,3:I2C-MS5525,4:I2C-MS5525 (0x76),5:I2C-MS5525 (0x77),6:I2C-SDP3X,7:I2C-DLVR-5in,8:DroneCAN,9:I2C-DLVR-10in,10:I2C-DLVR-20in,11:I2C-DLVR-30in,12:I2C-DLVR-60in,13:NMEA water speed,14:MSP,15:ASP5033,16:ExternalAHRS,100:SITL // @User: Standard AP_GROUPINFO_FLAGS("TYPE", 1, AP_Airspeed_Params, type, 0, AP_PARAM_FLAG_ENABLE), diff --git a/libraries/AP_Airspeed/AP_Airspeed_config.h b/libraries/AP_Airspeed/AP_Airspeed_config.h index 4ba2e4179388a2..f12db5cb16c4e9 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_config.h +++ b/libraries/AP_Airspeed/AP_Airspeed_config.h @@ -3,6 +3,7 @@ #include #include #include +#include #ifndef AP_AIRSPEED_ENABLED #define AP_AIRSPEED_ENABLED 1 @@ -66,3 +67,7 @@ #ifndef AP_AIRSPEED_HYGROMETER_ENABLE #define AP_AIRSPEED_HYGROMETER_ENABLE (AP_AIRSPEED_ENABLED && BOARD_FLASH_SIZE > 1024) #endif + +#ifndef AP_AIRSPEED_EXTERNAL_ENABLED +#define AP_AIRSPEED_EXTERNAL_ENABLED AP_AIRSPEED_ENABLED && HAL_EXTERNAL_AHRS_ENABLED +#endif From a17438d52cfa2918c0fdd4087f98c83fb6d9d82d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 1 Dec 2023 15:57:21 +1100 Subject: [PATCH 0105/1335] SITL: added InertialLabs simulator --- libraries/SITL/SIM_GPS.h | 15 ++-- libraries/SITL/SIM_InertialLabs.cpp | 124 ++++++++++++++++++++++++++++ libraries/SITL/SIM_InertialLabs.h | 123 +++++++++++++++++++++++++++ 3 files changed, 255 insertions(+), 7 deletions(-) create mode 100644 libraries/SITL/SIM_InertialLabs.cpp create mode 100644 libraries/SITL/SIM_InertialLabs.h diff --git a/libraries/SITL/SIM_GPS.h b/libraries/SITL/SIM_GPS.h index 63e4b99441c85d..334ea2e0a077e7 100644 --- a/libraries/SITL/SIM_GPS.h +++ b/libraries/SITL/SIM_GPS.h @@ -74,13 +74,6 @@ class GPS_Backend { virtual void update_read(); // writing fix information to autopilot (e.g.) virtual void publish(const GPS_Data *d) = 0; - -protected: - - uint8_t instance; - GPS &front; - - class SIM *_sitl; struct GPS_TOW { // Number of weeks since midnight 5-6 January 1980 @@ -90,6 +83,14 @@ class GPS_Backend { }; static GPS_TOW gps_time(); + +protected: + + uint8_t instance; + GPS &front; + + class SIM *_sitl; + static void simulation_timeval(struct timeval *tv); }; diff --git a/libraries/SITL/SIM_InertialLabs.cpp b/libraries/SITL/SIM_InertialLabs.cpp new file mode 100644 index 00000000000000..728c7934f9cf7c --- /dev/null +++ b/libraries/SITL/SIM_InertialLabs.cpp @@ -0,0 +1,124 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ +/* + simulate InertialLabs external AHRS +*/ +#include "SIM_InertialLabs.h" +#include +#include "SIM_GPS.h" + +using namespace SITL; + +InertialLabs::InertialLabs() : SerialDevice::SerialDevice() +{ +} + +void InertialLabs::send_packet(void) +{ + const auto &fdm = _sitl->state; + + pkt.msg_len = sizeof(pkt)-2; + + pkt.accel_data_hr.x = (fdm.yAccel * 1.0e6)/GRAVITY_MSS; + pkt.accel_data_hr.y = (fdm.xAccel * 1.0e6)/GRAVITY_MSS; + pkt.accel_data_hr.z = (-fdm.zAccel * 1.0e6)/GRAVITY_MSS; + + pkt.gyro_data_hr.y = fdm.rollRate*1.0e5; + pkt.gyro_data_hr.x = fdm.pitchRate*1.0e5; + pkt.gyro_data_hr.z = -fdm.yawRate*1.0e5; + + float sigma, delta, theta; + AP_Baro::SimpleAtmosphere((fdm.altitude+rand_float()*0.25) * 0.001, sigma, delta, theta); + pkt.baro_data.pressure_pa2 = SSL_AIR_PRESSURE * delta * 0.5; + pkt.baro_data.baro_alt = fdm.altitude; + pkt.temperature = KELVIN_TO_C(SSL_AIR_TEMPERATURE * theta); + + pkt.mag_data.x = (fdm.bodyMagField.y / NTESLA_TO_MGAUSS)*0.1; + pkt.mag_data.y = (fdm.bodyMagField.x / NTESLA_TO_MGAUSS)*0.1; + pkt.mag_data.z = (-fdm.bodyMagField.z / NTESLA_TO_MGAUSS)*0.1; + + pkt.orientation_angles.roll = fdm.rollDeg*100; + pkt.orientation_angles.pitch = fdm.pitchDeg*100; + pkt.orientation_angles.yaw = fdm.yawDeg*100; + + pkt.velocity.x = fdm.speedE*100; + pkt.velocity.y = fdm.speedN*100; + pkt.velocity.z = -fdm.speedD*100; + + pkt.position.lat = fdm.latitude*1e7; + pkt.position.lon = fdm.longitude*1e7; + pkt.position.alt = fdm.altitude*1e2; + + pkt.kf_vel_covariance.x = 10; + pkt.kf_vel_covariance.z = 10; + pkt.kf_vel_covariance.z = 10; + + pkt.kf_pos_covariance.x = 20; + pkt.kf_pos_covariance.z = 20; + pkt.kf_pos_covariance.z = 20; + + const auto gps_tow = GPS_Backend::gps_time(); + + pkt.gps_ins_time_ms = gps_tow.ms; + + pkt.gnss_new_data = 0; + + if (packets_sent % gps_frequency == 0) { + // update GPS data at 5Hz + pkt.gps_week = gps_tow.week; + pkt.gnss_pos_timestamp = gps_tow.ms; + pkt.gnss_new_data = 3; + pkt.gps_position.lat = pkt.position.lat; + pkt.gps_position.lon = pkt.position.lon; + pkt.gps_position.alt = pkt.position.alt; + + pkt.num_sats = 32; + pkt.gnss_vel_track.hor_speed = norm(fdm.speedN,fdm.speedE)*100; + Vector2d track{fdm.speedN,fdm.speedE}; + pkt.gnss_vel_track.track_over_ground = wrap_360(degrees(track.angle()))*100; + pkt.gnss_vel_track.ver_speed = -fdm.speedD*100; + + pkt.gnss_extended_info.fix_type = 2; + } + + pkt.differential_pressure = 0.5*sq(fdm.airspeed+fabsf(rand_float()*0.25))*1.0e4; + pkt.supply_voltage = 12.3*100; + pkt.temperature = 23.4*10; + + const uint8_t *buffer = (const uint8_t *)&pkt; + pkt.crc = crc_sum_of_bytes_16(&buffer[2], sizeof(pkt)-4); + + write_to_autopilot((char *)&pkt, sizeof(pkt)); + + packets_sent++; +} + + +/* + send InertialLabs data + */ +void InertialLabs::update(void) +{ + if (!init_sitl_pointer()) { + return; + } + const uint32_t us_between_packets = 5000; // 200Hz + const uint32_t now = AP_HAL::micros(); + if (now - last_pkt_us >= us_between_packets) { + last_pkt_us = now; + send_packet(); + } + +} diff --git a/libraries/SITL/SIM_InertialLabs.h b/libraries/SITL/SIM_InertialLabs.h new file mode 100644 index 00000000000000..448d5bf48bd192 --- /dev/null +++ b/libraries/SITL/SIM_InertialLabs.h @@ -0,0 +1,123 @@ +//usage: +//PARAMS: +// param set AHRS_EKF_TYPE 11 +// param set EAHRS_TYPE 5 +// param set SERIAL4_PROTOCOL 36 +// param set SERIAL4_BAUD 460800 +// sim_vehicle.py -v ArduPlane -D --console --map -A --uartE=sim:ILabs +#pragma once + +#include "SIM_Aircraft.h" + +#include +#include "SIM_SerialDevice.h" + +namespace SITL +{ + +class InertialLabs : public SerialDevice +{ +public: + + InertialLabs(); + + // update state + void update(void); + +private: + void send_packet(void); + + struct PACKED vec3_16_t { + int16_t x,y,z; + }; + struct PACKED vec3_32_t { + int32_t x,y,z; + }; + struct PACKED vec3_u8_t { + uint8_t x,y,z; + }; + struct PACKED vec3_u16_t { + uint16_t x,y,z; + }; + + struct gnss_extended_info_t { + uint8_t fix_type; + uint8_t spoofing_status; + }; + + struct gnss_info_short_t { + uint8_t info1; + uint8_t info2; + }; + + struct PACKED ILabsPacket { + uint16_t magic = 0x55AA; + uint8_t msg_type = 1; + uint8_t msg_id = 0x95; + uint16_t msg_len; // total packet length-2 + + // send Table4, 27 messages + uint8_t num_messages = 27; + uint8_t messages[27] = { + 0x01, 0x3C, 0x23, 0x21, 0x25, 0x24, 0x07, 0x12, 0x10, 0x58, 0x57, 0x53, 0x4a, + 0x3b, 0x30, 0x32, 0x3e, 0x36, 0x41, 0xc0, 0x28, 0x86, 0x8a, 0x8d, 0x50, + 0x52, 0x5a + }; + uint32_t gps_ins_time_ms; // ms since start of GPS week for IMU data + uint16_t gps_week; + vec3_32_t accel_data_hr; // g * 1e6 + vec3_32_t gyro_data_hr; // deg/s * 1e5 + struct PACKED { + uint16_t pressure_pa2; // Pascals/2 + int32_t baro_alt; // meters*100 + } baro_data; + vec3_16_t mag_data; // nT/10 + struct PACKED { + int16_t yaw; // deg*100 + int16_t pitch; // deg*100 + int16_t roll; // deg*100 + } orientation_angles; // 321 euler order + vec3_32_t velocity; // m/s * 100 + struct PACKED { + int32_t lat; // deg*1e7 + int32_t lon; // deg*1e7 + int32_t alt; // m*100, AMSL + } position; + vec3_u8_t kf_vel_covariance; // mm/s + vec3_u16_t kf_pos_covariance; + uint16_t unit_status; + gnss_extended_info_t gnss_extended_info; + uint8_t num_sats; + struct PACKED { + int32_t lat; // deg*1e7 + int32_t lon; // deg*1e7 + int32_t alt; // m*100, AMSL + } gps_position; + struct PACKED { + int32_t hor_speed; // m/s*100 + uint16_t track_over_ground; // deg*100 + int32_t ver_speed; // m/s*100 + } gnss_vel_track; + uint32_t gnss_pos_timestamp; // ms + gnss_info_short_t gnss_info_short; + uint8_t gnss_new_data; + uint8_t gnss_jam_status; + int32_t differential_pressure; // mbar*1e4 + int16_t true_airspeed; // m/s*100 + vec3_16_t wind_speed; // m/s*100 + uint16_t air_data_status; + uint16_t supply_voltage; // V*100 + int16_t temperature; // degC*10 + uint16_t unit_status2; + uint16_t crc; + } pkt; + + uint32_t last_pkt_us; + const uint16_t pkt_rate_hz = 200; + const uint16_t gps_rate_hz = 10; + const uint16_t gps_frequency = pkt_rate_hz / gps_rate_hz; + uint32_t packets_sent; +}; + +} + From 48ab76d06eedc32dc2ae748fa6ca6aa22603d27e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 1 Dec 2023 15:57:37 +1100 Subject: [PATCH 0106/1335] AP_HAL: added InertialLabs simulator --- libraries/AP_HAL/SIMState.cpp | 3 +++ libraries/AP_HAL/SIMState.h | 4 ++++ 2 files changed, 7 insertions(+) diff --git a/libraries/AP_HAL/SIMState.cpp b/libraries/AP_HAL/SIMState.cpp index 9a270445abf71c..b7c562f3b47d80 100644 --- a/libraries/AP_HAL/SIMState.cpp +++ b/libraries/AP_HAL/SIMState.cpp @@ -230,6 +230,9 @@ void SIMState::fdm_input_local(void) if (microstrain5 != nullptr) { microstrain5->update(); } + if (inertiallabs != nullptr) { + inertiallabs->update(); + } #if HAL_SIM_AIS_ENABLED if (ais != nullptr) { diff --git a/libraries/AP_HAL/SIMState.h b/libraries/AP_HAL/SIMState.h index 41505a6263d905..4c8350371a70b0 100644 --- a/libraries/AP_HAL/SIMState.h +++ b/libraries/AP_HAL/SIMState.h @@ -30,6 +30,7 @@ #include #include #include +#include #include #include @@ -198,6 +199,9 @@ class AP_HAL::SIMState { // simulated MicroStrain Series 7 system SITL::MicroStrain7 *microstrain7; + // simulated InertialLabs INS-U + SITL::InertialLabs *inertiallabs; + #if HAL_SIM_JSON_MASTER_ENABLED // Ride along instances via JSON SITL backend SITL::JSON_Master ride_along; From 38960a3db2a3dd976deb2c0020d538057ffdf746 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 1 Dec 2023 15:57:51 +1100 Subject: [PATCH 0107/1335] HAL_SITL: added InertialLabs simulator --- libraries/AP_HAL_SITL/SITL_State_common.cpp | 11 +++++++++++ libraries/AP_HAL_SITL/SITL_State_common.h | 4 ++++ 2 files changed, 15 insertions(+) diff --git a/libraries/AP_HAL_SITL/SITL_State_common.cpp b/libraries/AP_HAL_SITL/SITL_State_common.cpp index 718d80537e182e..f05bbf20b1fc79 100644 --- a/libraries/AP_HAL_SITL/SITL_State_common.cpp +++ b/libraries/AP_HAL_SITL/SITL_State_common.cpp @@ -276,6 +276,14 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const } microstrain7 = new SITL::MicroStrain7(); return microstrain7; + + } else if (streq(name, "ILabs")) { + if (inertiallabs != nullptr) { + AP_HAL::panic("Only one InertialLabs INS at a time"); + } + inertiallabs = new SITL::InertialLabs(); + return inertiallabs; + #if HAL_SIM_AIS_ENABLED } else if (streq(name, "AIS")) { if (ais != nullptr) { @@ -445,6 +453,9 @@ void SITL_State_Common::sim_update(void) if (microstrain7 != nullptr) { microstrain7->update(); } + if (inertiallabs != nullptr) { + inertiallabs->update(); + } #if HAL_SIM_AIS_ENABLED if (ais != nullptr) { diff --git a/libraries/AP_HAL_SITL/SITL_State_common.h b/libraries/AP_HAL_SITL/SITL_State_common.h index 3a2d722fc5ebde..5d5ea6999db603 100644 --- a/libraries/AP_HAL_SITL/SITL_State_common.h +++ b/libraries/AP_HAL_SITL/SITL_State_common.h @@ -34,6 +34,7 @@ #include #include #include +#include #include #include @@ -203,6 +204,9 @@ class HALSITL::SITL_State_Common { // simulated MicroStrain system SITL::MicroStrain7 *microstrain7; + // simulated InertialLabs INS + SITL::InertialLabs *inertiallabs; + #if HAL_SIM_JSON_MASTER_ENABLED // Ride along instances via JSON SITL backend SITL::JSON_Master ride_along; From 59ec0a6b56c044fcbd77a63ccbce04d5f8a5d7be Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 1 Dec 2023 15:59:28 +1100 Subject: [PATCH 0108/1335] Tools: added test for InertialLabs EAHRS --- Tools/autotest/ArduPlane_Tests/InertialLabsEAHRS/ap1.txt | 7 +++++++ Tools/autotest/arduplane.py | 5 +++++ 2 files changed, 12 insertions(+) create mode 100644 Tools/autotest/ArduPlane_Tests/InertialLabsEAHRS/ap1.txt diff --git a/Tools/autotest/ArduPlane_Tests/InertialLabsEAHRS/ap1.txt b/Tools/autotest/ArduPlane_Tests/InertialLabsEAHRS/ap1.txt new file mode 100644 index 00000000000000..ab2be0d1a45470 --- /dev/null +++ b/Tools/autotest/ArduPlane_Tests/InertialLabsEAHRS/ap1.txt @@ -0,0 +1,7 @@ +QGC WPL 110 +0 0 0 16 0.000000 0.000000 0.000000 0.000000 -35.363262 149.165237 584.090027 1 +1 0 3 22 0.000000 0.000000 0.000000 0.000000 -35.361553 149.163956 20.000000 1 +2 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364540 149.162857 50.000000 1 +3 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.367333 149.163164 28.000000 1 +4 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.366814 149.165878 28.000000 1 +5 0 3 21 0.000000 0.000000 0.000000 1.000000 -35.362947 149.165179 0.000000 1 diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 5c76db5d35d888..09041b17dab928 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -3279,6 +3279,10 @@ def MicroStrainEAHRS7(self): '''Test MicroStrain EAHRS series 7 support''' self.fly_external_AHRS("MicroStrain7", 7, "ap1.txt") + def InertialLabsEAHRS(self): + '''Test InertialLabs EAHRS support''' + self.fly_external_AHRS("ILabs", 5, "ap1.txt") + def get_accelvec(self, m): return Vector3(m.xacc, m.yacc, m.zacc) * 0.001 * 9.81 @@ -5358,6 +5362,7 @@ def tests(self): self.VectorNavEAHRS, self.MicroStrainEAHRS5, self.MicroStrainEAHRS7, + self.InertialLabsEAHRS, self.Deadreckoning, self.DeadreckoningNoAirSpeed, self.EKFlaneswitch, From 757607e4f8ebc1d83d9663aa56d4d8df5aa0cd78 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 1 Dec 2023 09:00:30 +1100 Subject: [PATCH 0109/1335] AP_ExternalAHRS: added InertialLabs backend --- libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp | 11 + libraries/AP_ExternalAHRS/AP_ExternalAHRS.h | 9 +- .../AP_ExternalAHRS_InertialLabs.cpp | 708 ++++++++++++++++++ .../AP_ExternalAHRS_InertialLabs.h | 226 ++++++ .../AP_ExternalAHRS/AP_ExternalAHRS_config.h | 4 + 5 files changed, 957 insertions(+), 1 deletion(-) create mode 100644 libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp create mode 100644 libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.h diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp index a18659028caa6b..0bb0d0af22acb8 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp @@ -25,6 +25,7 @@ #include "AP_ExternalAHRS_VectorNav.h" #include "AP_ExternalAHRS_MicroStrain5.h" #include "AP_ExternalAHRS_MicroStrain7.h" +#include "AP_ExternalAHRS_InertialLabs.h" #include #include @@ -95,21 +96,31 @@ void AP_ExternalAHRS::init(void) case DevType::None: // nothing to do return; + #if AP_EXTERNAL_AHRS_VECTORNAV_ENABLED case DevType::VecNav: backend = new AP_ExternalAHRS_VectorNav(this, state); return; #endif + #if AP_EXTERNAL_AHRS_MICROSTRAIN5_ENABLED case DevType::MicroStrain5: backend = new AP_ExternalAHRS_MicroStrain5(this, state); return; #endif + #if AP_EXTERNAL_AHRS_MICROSTRAIN7_ENABLED case DevType::MicroStrain7: backend = new AP_ExternalAHRS_MicroStrain7(this, state); return; #endif + +#if AP_EXTERNAL_AHRS_INERTIAL_LABS_ENABLED + case DevType::InertialLabs: + backend = new AP_ExternalAHRS_InertialLabs(this, state); + return; +#endif + } GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Unsupported ExternalAHRS type %u", unsigned(devtype)); diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h index da36e5d706d1d5..557f1e9c699940 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.h @@ -48,10 +48,12 @@ class AP_ExternalAHRS { #endif #if AP_EXTERNAL_AHRS_MICROSTRAIN5_ENABLED MicroStrain5 = 2, +#endif +#if AP_EXTERNAL_AHRS_INERTIAL_LABS_ENABLED + InertialLabs = 5, #endif // 3 reserved for AdNav // 4 reserved for CINS - // 5 reserved for InertialLabs // 6 reserved for Trimble #if AP_EXTERNAL_AHRS_MICROSTRAIN7_ENABLED MicroStrain7 = 7, @@ -156,6 +158,11 @@ class AP_ExternalAHRS { float temperature; } ins_data_message_t; + typedef struct { + float differential_pressure; // Pa + float temperature; // degC + } airspeed_data_message_t; + protected: enum class OPTIONS { diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp new file mode 100644 index 00000000000000..0ab6857f63ca39 --- /dev/null +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp @@ -0,0 +1,708 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ +/* + support for serial connected InertialLabs INS + */ + +#include "AP_ExternalAHRS_config.h" + +#if AP_EXTERNAL_AHRS_INERTIAL_LABS_ENABLED + +#include "AP_ExternalAHRS_InertialLabs.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +extern const AP_HAL::HAL &hal; + +// unit status bits +#define ILABS_UNIT_STATUS_ALIGNMENT_FAIL 0x0001 +#define ILABS_UNIT_STATUS_OPERATION_FAIL 0x0002 +#define ILABS_UNIT_STATUS_GYRO_FAIL 0x0004 +#define ILABS_UNIT_STATUS_ACCEL_FAIL 0x0008 +#define ILABS_UNIT_STATUS_MAG_FAIL 0x0010 +#define ILABS_UNIT_STATUS_ELECTRONICS_FAIL 0x0020 +#define ILABS_UNIT_STATUS_GNSS_FAIL 0x0040 +#define ILABS_UNIT_STATUS_RUNTIME_CAL 0x0080 +#define ILABS_UNIT_STATUS_VOLTAGE_LOW 0x0100 +#define ILABS_UNIT_STATUS_VOLTAGE_HIGH 0x0200 +#define ILABS_UNIT_STATUS_X_RATE_HIGH 0x0400 +#define ILABS_UNIT_STATUS_Y_RATE_HIGH 0x0800 +#define ILABS_UNIT_STATUS_Z_RATE_HIGH 0x1000 +#define ILABS_UNIT_STATUS_MAG_FIELD_HIGH 0x2000 +#define ILABS_UNIT_STATUS_TEMP_RANGE_ERR 0x4000 +#define ILABS_UNIT_STATUS_RUNTIME_CAL2 0x8000 + +// unit status2 bits +#define ILABS_UNIT_STATUS2_ACCEL_X_HIGH 0x0001 +#define ILABS_UNIT_STATUS2_ACCEL_Y_HIGH 0x0002 +#define ILABS_UNIT_STATUS2_ACCEL_Z_HIGH 0x0004 +#define ILABS_UNIT_STATUS2_BARO_FAIL 0x0008 +#define ILABS_UNIT_STATUS2_DIFF_PRESS_FAIL 0x0010 +#define ILABS_UNIT_STATUS2_MAGCAL_2D_ACT 0x0020 +#define ILABS_UNIT_STATUS2_MAGCAL_3D_ACT 0x0020 +#define ILABS_UNIT_STATUS2_GNSS_FUSION_OFF 0x0040 +#define ILABS_UNIT_STATUS2_DIFF_PRESS_FUSION_OFF 0x0080 +#define ILABS_UNIT_STATUS2_MAG_FUSION_OFF 0x0100 +#define ILABS_UNIT_STATUS2_GNSS_POS_VALID 0x0200 + +// air data status bits +#define ILABS_AIRDATA_INIT_FAIL 0x0001 +#define ILABS_AIRDATA_DIFF_PRESS_INIT_FAIL 0x0002 +#define ILABS_AIRDATA_STATIC_PRESS_FAIL 0x0004 +#define ILABS_AIRDATA_DIFF_PRESS_FAIL 0x0008 +#define ILABS_AIRDATA_STATIC_PRESS_RANGE_ERR 0x0010 +#define ILABS_AIRDATA_DIFF_PRESS_RANGE_ERR 0x0020 +#define ILABS_AIRDATA_PRESS_ALT_FAIL 0x0040 +#define ILABS_AIRDATA_AIRSPEED_FAIL 0x0080 +#define ILABS_AIRDATA_BELOW_THRESHOLD 0x0100 + + +// constructor +AP_ExternalAHRS_InertialLabs::AP_ExternalAHRS_InertialLabs(AP_ExternalAHRS *_frontend, + AP_ExternalAHRS::state_t &_state) : + AP_ExternalAHRS_backend(_frontend, _state) +{ + auto &sm = AP::serialmanager(); + uart = sm.find_serial(AP_SerialManager::SerialProtocol_AHRS, 0); + if (!uart) { + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "InertialLabs ExternalAHRS no UART"); + return; + } + baudrate = sm.find_baudrate(AP_SerialManager::SerialProtocol_AHRS, 0); + port_num = sm.find_portnum(AP_SerialManager::SerialProtocol_AHRS, 0); + + // don't offer IMU by default, at 200Hz it is too slow for many aircraft + set_default_sensors(uint16_t(AP_ExternalAHRS::AvailableSensor::GPS) | + uint16_t(AP_ExternalAHRS::AvailableSensor::BARO) | + uint16_t(AP_ExternalAHRS::AvailableSensor::COMPASS)); + + if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_ExternalAHRS_InertialLabs::update_thread, void), "ILabs", 2048, AP_HAL::Scheduler::PRIORITY_SPI, 0)) { + AP_HAL::panic("InertialLabs Failed to start ExternalAHRS update thread"); + } + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "InertialLabs ExternalAHRS initialised"); +} + +/* + re-sync buffer on parse failure + */ +void AP_ExternalAHRS_InertialLabs::re_sync(void) +{ + if (buffer_ofs > 3) { + /* + look for the 2 byte header and try to sync to that + */ + const uint16_t header = 0x55AA; + const uint8_t *p = (const uint8_t *)memmem(&buffer[1], buffer_ofs-3, &header, sizeof(header)); + if (p != nullptr) { + const uint16_t n = p - &buffer[0]; + memmove(&buffer[0], p, buffer_ofs - n); + buffer_ofs -= n; + } else { + buffer_ofs = 0; + } + } else { + buffer_ofs = 0; + } +} + +// macro for checking we don't run past end of message buffer +#define CHECK_SIZE(d) need_re_sync = (message_ofs + (msg_len=sizeof(d)) > buffer_end); if (need_re_sync) break + +// lookup a message in the msg_types bitmask to see if we received it in this packet +#define GOT_MSG(mtype) msg_types.get(unsigned(MessageType::mtype)) + +/* + check header is valid + */ +bool AP_ExternalAHRS_InertialLabs::check_header(const ILabsHeader *h) const +{ + return h->magic == 0x55AA && + h->msg_type == 1 && + h->msg_id == 0x95 && + h->msg_len <= sizeof(buffer)-2; +} + +/* + check the UART for more data + returns true if we have consumed potentially valid bytes + */ +bool AP_ExternalAHRS_InertialLabs::check_uart() +{ + WITH_SEMAPHORE(state.sem); + + if (!setup_complete) { + return false; + } + uint32_t n = uart->available(); + if (n == 0) { + return false; + } + if (n + buffer_ofs > sizeof(buffer)) { + n = sizeof(buffer) - buffer_ofs; + } + const ILabsHeader *h = (ILabsHeader *)&buffer[0]; + + if (buffer_ofs < sizeof(ILabsHeader)) { + n = MIN(n, sizeof(ILabsHeader)-buffer_ofs); + } else { + if (!check_header(h)) { + re_sync(); + return false; + } + if (buffer_ofs > h->msg_len+8) { + re_sync(); + return false; + } + n = MIN(n, uint32_t(h->msg_len + 2 - buffer_ofs)); + } + + const ssize_t nread = uart->read(&buffer[buffer_ofs], n); + if (nread != ssize_t(n)) { + re_sync(); + return false; + } + buffer_ofs += n; + + if (buffer_ofs < sizeof(ILabsHeader)) { + return true; + } + + if (!check_header(h)) { + re_sync(); + return false; + } + + if (buffer_ofs < h->msg_len+2) { + /* + see if we can read the rest immediately + */ + const uint16_t needed = h->msg_len+2 - buffer_ofs; + if (uart->available() < needed) { + // need more data + return true; + } + const ssize_t nread2 = uart->read(&buffer[buffer_ofs], needed); + if (nread2 != needed) { + re_sync(); + return false; + } + buffer_ofs += nread2; + } + + // check checksum + const uint16_t crc1 = crc_sum_of_bytes_16(&buffer[2], buffer_ofs-4); + const uint16_t crc2 = le16toh_ptr(&buffer[buffer_ofs-2]); + if (crc1 != crc2) { + re_sync(); + return false; + } + + const uint8_t *buffer_end = &buffer[buffer_ofs]; + const uint16_t payload_size = h->msg_len - 6; + const uint8_t *payload = &buffer[6]; + if (payload_size < 3) { + re_sync(); + return false; + } + const uint8_t num_messages = payload[0]; + if (num_messages == 0 || + num_messages > payload_size-1) { + re_sync(); + return false; + } + const uint8_t *message_ofs = &payload[num_messages+1]; + bool need_re_sync = false; + + // bitmask for what types we get + Bitmask<256> msg_types; + uint32_t now_ms = AP_HAL::millis(); + + for (uint8_t i=0; i= buffer_end) { + re_sync(); + return false; + } + MessageType mtype = (MessageType)payload[1+i]; + ILabsData &u = *(ILabsData*)message_ofs; + uint8_t msg_len = 0; + + msg_types.set(unsigned(mtype)); + + switch (mtype) { + case MessageType::GPS_INS_TIME_MS: { + // this is the GPS tow timestamp in ms for when the IMU data was sampled + CHECK_SIZE(u.gps_time_ms); + state2.gnss_ins_time_ms = u.gps_time_ms; + break; + } + case MessageType::GPS_WEEK: { + CHECK_SIZE(u.gps_week); + gps_data.gps_week = u.gps_week; + break; + } + case MessageType::ACCEL_DATA_HR: { + CHECK_SIZE(u.accel_data_hr); + ins_data.accel = u.accel_data_hr.tofloat().rfu_to_frd()*GRAVITY_MSS*1.0e-6; + break; + } + case MessageType::GYRO_DATA_HR: { + CHECK_SIZE(u.gyro_data_hr); + ins_data.gyro = u.gyro_data_hr.tofloat().rfu_to_frd()*DEG_TO_RAD*1.0e-5; + break; + } + case MessageType::BARO_DATA: { + CHECK_SIZE(u.baro_data); + baro_data.pressure_pa = u.baro_data.pressure_pa2*2; + break; + } + case MessageType::MAG_DATA: { + CHECK_SIZE(u.mag_data); + mag_data.field = u.mag_data.tofloat().rfu_to_frd()*(10*NTESLA_TO_MGAUSS); + break; + } + case MessageType::ORIENTATION_ANGLES: { + CHECK_SIZE(u.orientation_angles); + state.quat.from_euler(radians(u.orientation_angles.roll*0.01), + radians(u.orientation_angles.pitch*0.01), + radians(u.orientation_angles.yaw*0.01)); + state.have_quaternion = true; + if (last_att_ms == 0) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "InertialLabs: got link"); + } + last_att_ms = now_ms; + break; + } + case MessageType::VELOCITIES: { + CHECK_SIZE(u.velocity); + state.velocity = u.velocity.tofloat().rfu_to_frd()*0.01; + state.have_velocity = true; + last_vel_ms = now_ms; + break; + } + case MessageType::POSITION: { + CHECK_SIZE(u.position); + state.location.lat = u.position.lat; + state.location.lng = u.position.lon; + state.location.alt = u.position.alt; + state.have_location = true; + state.last_location_update_us = AP_HAL::micros(); + last_pos_ms = now_ms; + break; + } + case MessageType::KF_VEL_COVARIANCE: { + CHECK_SIZE(u.kf_vel_covariance); + state2.kf_vel_covariance = u.kf_vel_covariance.tofloat() * 0.001; + break; + } + case MessageType::KF_POS_COVARIANCE: { + CHECK_SIZE(u.kf_pos_covariance); + state2.kf_pos_covariance = u.kf_pos_covariance.tofloat() * 0.001; + break; + } + case MessageType::UNIT_STATUS: { + CHECK_SIZE(u.unit_status); + state2.unit_status = u.unit_status; + break; + } + case MessageType::GNSS_EXTENDED_INFO: { + CHECK_SIZE(u.gnss_extended_info); + gps_data.fix_type = u.gnss_extended_info.fix_type+1; + state2.gnss_extended_info = u.gnss_extended_info; + break; + } + case MessageType::NUM_SATS: { + CHECK_SIZE(u.num_sats); + gps_data.satellites_in_view = u.num_sats; + break; + } + case MessageType::GNSS_POSITION: { + CHECK_SIZE(u.position); + gps_data.latitude = u.position.lat; + gps_data.longitude = u.position.lon; + gps_data.msl_altitude = u.position.alt; + break; + } + case MessageType::GNSS_VEL_TRACK: { + CHECK_SIZE(u.gnss_vel_track); + Vector2f velxy; + velxy.offset_bearing(u.gnss_vel_track.track_over_ground*0.01, u.gnss_vel_track.hor_speed*0.01); + gps_data.ned_vel_north = velxy.x; + gps_data.ned_vel_east = velxy.y; + gps_data.ned_vel_down = -u.gnss_vel_track.ver_speed*0.01; + break; + } + case MessageType::GNSS_POS_TIMESTAMP: { + CHECK_SIZE(u.gnss_pos_timestamp); + gps_data.ms_tow = u.gnss_pos_timestamp; + break; + } + case MessageType::GNSS_INFO_SHORT: { + CHECK_SIZE(u.gnss_info_short); + state2.gnss_info_short = u.gnss_info_short; + break; + } + case MessageType::GNSS_NEW_DATA: { + CHECK_SIZE(u.gnss_new_data); + state2.gnss_new_data = u.gnss_new_data; + break; + } + case MessageType::GNSS_JAM_STATUS: { + CHECK_SIZE(u.gnss_jam_status); + state2.gnss_jam_status = u.gnss_jam_status; + break; + } + case MessageType::DIFFERENTIAL_PRESSURE: { + CHECK_SIZE(u.differential_pressure); + airspeed_data.differential_pressure = u.differential_pressure*1.0e-4; + break; + } + case MessageType::TRUE_AIRSPEED: { + CHECK_SIZE(u.true_airspeed); + state2.true_airspeed = u.true_airspeed*0.01; + break; + } + case MessageType::WIND_SPEED: { + CHECK_SIZE(u.wind_speed); + state2.wind_speed = u.wind_speed.tofloat().rfu_to_frd()*0.01; + break; + } + case MessageType::AIR_DATA_STATUS: { + CHECK_SIZE(u.air_data_status); + state2.air_data_status = u.air_data_status; + break; + } + case MessageType::SUPPLY_VOLTAGE: { + CHECK_SIZE(u.supply_voltage); + state2.supply_voltage = u.supply_voltage*0.01; + break; + } + case MessageType::TEMPERATURE: { + CHECK_SIZE(u.temperature); + // assume same temperature for baro and airspeed + baro_data.temperature = u.temperature*0.1; + airspeed_data.temperature = u.temperature*0.1; + break; + } + case MessageType::UNIT_STATUS2: { + CHECK_SIZE(u.unit_status2); + state2.unit_status2 = u.unit_status2; + break; + } + } + + if (msg_len == 0) { + // got an unknown message + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "InertialLabs: unknown msg 0x%02x", unsigned(mtype)); + buffer_ofs = 0; + return false; + } + message_ofs += msg_len; + + if (msg_len == 0 || need_re_sync) { + re_sync(); + return false; + } + } + + if (h->msg_len != message_ofs-buffer) { + // we had stray bytes at the end of the message + re_sync(); + return false; + } + + if (GOT_MSG(ACCEL_DATA_HR) && + GOT_MSG(GYRO_DATA_HR)) { + AP::ins().handle_external(ins_data); + } + if (GOT_MSG(GPS_INS_TIME_MS) && + GOT_MSG(NUM_SATS) && + GOT_MSG(GNSS_POSITION) && + GOT_MSG(GNSS_NEW_DATA) && + GOT_MSG(GNSS_EXTENDED_INFO) && + state2.gnss_new_data != 0) { + uint8_t instance; + if (AP::gps().get_first_external_instance(instance)) { + AP::gps().handle_external(gps_data, instance); + } + if (gps_data.satellites_in_view > 3) { + if (last_gps_ms == 0) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "InertialLabs: got GPS lock"); + if (!state.have_origin) { + state.origin = Location{ + gps_data.latitude, + gps_data.longitude, + gps_data.msl_altitude, + Location::AltFrame::ABSOLUTE}; + state.have_origin = true; + } + } + last_gps_ms = now_ms; + } + } + if (GOT_MSG(BARO_DATA) && + GOT_MSG(TEMPERATURE)) { + AP::baro().handle_external(baro_data); + } + if (GOT_MSG(MAG_DATA)) { + AP::compass().handle_external(mag_data); + } +#if AP_AIRSPEED_EXTERNAL_ENABLED && (APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane)) + // only on plane and copter as others do not link AP_Airspeed + if (GOT_MSG(DIFFERENTIAL_PRESSURE) && + GOT_MSG(TEMPERATURE)) { + auto *arsp = AP::airspeed(); + if (arsp != nullptr) { + arsp->handle_external(airspeed_data); + } + } +#endif // AP_AIRSPEED_EXTERNAL_ENABLED + buffer_ofs = 0; + + if (GOT_MSG(POSITION) && + GOT_MSG(ORIENTATION_ANGLES) && + GOT_MSG(VELOCITIES)) { + + float roll, pitch, yaw; + state.quat.to_euler(roll, pitch, yaw); + uint64_t now_us = AP_HAL::micros64(); + + // @LoggerMessage: ILB1 + // @Description: InertialLabs AHRS data1 + // @Field: TimeUS: Time since system startup + // @Field: Roll: euler roll + // @Field: Pitch: euler pitch + // @Field: Yaw: euler yaw + // @Field: VN: velocity north + // @Field: VE: velocity east + // @Field: VD: velocity down + // @Field: Lat: latitude + // @Field: Lon: longitude + // @Field: Alt: altitude AMSL + + AP::logger().WriteStreaming("ILB1", "TimeUS,Roll,Pitch,Yaw,VN,VE,VD,Lat,Lon,Alt", + "sdddnnnDUm", + "F000000GG0", + "QffffffLLf", + now_us, + degrees(roll), degrees(pitch), degrees(yaw), + state.velocity.x, state.velocity.y, state.velocity.z, + state.location.lat, state.location.lng, state.location.alt*0.01); + + // @LoggerMessage: ILB2 + // @Description: InertialLabs AHRS data2 + // @Field: TimeUS: Time since system startup + // @Field: PosVarN: position variance north + // @Field: PosVarE: position variance east + // @Field: PosVarD: position variance down + // @Field: VelVarN: velocity variance north + // @Field: VelVarE: velocity variance east + // @Field: VelVarD: velocity variance down + + AP::logger().WriteStreaming("ILB2", "TimeUS,PosVarN,PosVarE,PosVarD,VelVarN,VelVarE,VelVarD", + "smmmnnn", + "F000000", + "Qffffff", + now_us, + state2.kf_pos_covariance.x, state2.kf_pos_covariance.x, state2.kf_pos_covariance.z, + state2.kf_vel_covariance.x, state2.kf_vel_covariance.x, state2.kf_vel_covariance.z); + + // @LoggerMessage: ILB3 + // @Description: InertialLabs AHRS data3 + // @Field: TimeUS: Time since system startup + // @Field: Stat1: unit status1 + // @Field: Stat2: unit status2 + // @Field: FType: fix type + // @Field: SpStat: spoofing status + // @Field: GI1: GNSS Info1 + // @Field: GI2: GNSS Info2 + // @Field: GJS: GNSS jamming status + // @Field: TAS: true airspeed + // @Field: WVN: Wind velocity north + // @Field: WVE: Wind velocity east + // @Field: WVD: Wind velocity down + + AP::logger().WriteStreaming("ILB3", "TimeUS,Stat1,Stat2,FType,SpStat,GI1,GI2,GJS,TAS,WVN,WVE,WVD", + "s-----------", + "F-----------", + "QHHBBBBBffff", + now_us, + state2.unit_status, state2.unit_status2, + state2.gnss_extended_info.fix_type, state2.gnss_extended_info.spoofing_status, + state2.gnss_info_short.info1, state2.gnss_info_short.info2, + state2.gnss_jam_status, + state2.true_airspeed, + state2.wind_speed.x, state2.wind_speed.y, state2.wind_speed.z); + } + + return true; +} + +void AP_ExternalAHRS_InertialLabs::update_thread() +{ + // Open port in the thread + uart->begin(baudrate, 1024, 512); + + /* + we assume the user has already configured the device + */ + + setup_complete = true; + while (true) { + if (!check_uart()) { + hal.scheduler->delay_microseconds(250); + } + } +} + +// get serial port number for the uart +int8_t AP_ExternalAHRS_InertialLabs::get_port(void) const +{ + if (!uart) { + return -1; + } + return port_num; +}; + +// accessors for AP_AHRS +bool AP_ExternalAHRS_InertialLabs::healthy(void) const +{ + WITH_SEMAPHORE(state.sem); + return AP_HAL::millis() - last_att_ms < 100; +} + +bool AP_ExternalAHRS_InertialLabs::initialised(void) const +{ + if (!setup_complete) { + return false; + } + return true; +} + +bool AP_ExternalAHRS_InertialLabs::pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const +{ + if (!setup_complete) { + hal.util->snprintf(failure_msg, failure_msg_len, "InertialLabs setup failed"); + return false; + } + if (!healthy()) { + hal.util->snprintf(failure_msg, failure_msg_len, "InertialLabs unhealthy"); + return false; + } + WITH_SEMAPHORE(state.sem); + uint32_t now = AP_HAL::millis(); + if (now - last_att_ms > 10 || + now - last_pos_ms > 10 || + now - last_vel_ms > 10) { + hal.util->snprintf(failure_msg, failure_msg_len, "InertialLabs not up to date"); + return false; + } + return true; +} + +/* + get filter status. We don't know the meaning of the status bits yet, + so assume all OK if we have GPS lock + */ +void AP_ExternalAHRS_InertialLabs::get_filter_status(nav_filter_status &status) const +{ + WITH_SEMAPHORE(state.sem); + uint32_t now = AP_HAL::millis(); + const uint32_t dt_limit = 200; + const uint32_t dt_limit_gps = 500; + memset(&status, 0, sizeof(status)); + const bool init_ok = (state2.unit_status & (ILABS_UNIT_STATUS_ALIGNMENT_FAIL|ILABS_UNIT_STATUS_OPERATION_FAIL))==0; + status.flags.initalized = init_ok; + status.flags.attitude = init_ok && (now - last_att_ms < dt_limit) && init_ok; + status.flags.vert_vel = init_ok && (now - last_vel_ms < dt_limit); + status.flags.vert_pos = init_ok && (now - last_pos_ms < dt_limit); + status.flags.horiz_vel = status.flags.vert_vel; + status.flags.horiz_pos_abs = status.flags.vert_pos; + status.flags.horiz_pos_rel = status.flags.horiz_pos_abs; + status.flags.pred_horiz_pos_rel = status.flags.horiz_pos_abs; + status.flags.pred_horiz_pos_abs = status.flags.horiz_pos_abs; + status.flags.using_gps = (now - last_gps_ms < dt_limit_gps) && + (state2.unit_status & (ILABS_UNIT_STATUS_GNSS_FAIL|ILABS_UNIT_STATUS2_GNSS_FUSION_OFF)) == 0; + status.flags.gps_quality_good = (now - last_gps_ms < dt_limit_gps) && + (state2.unit_status2 & ILABS_UNIT_STATUS2_GNSS_POS_VALID) != 0 && + (state2.unit_status & ILABS_UNIT_STATUS_GNSS_FAIL) == 0; + status.flags.rejecting_airspeed = (state2.air_data_status & ILABS_AIRDATA_AIRSPEED_FAIL); +} + +// send an EKF_STATUS message to GCS +void AP_ExternalAHRS_InertialLabs::send_status_report(GCS_MAVLINK &link) const +{ + // prepare flags + uint16_t flags = 0; + nav_filter_status filterStatus; + get_filter_status(filterStatus); + if (filterStatus.flags.attitude) { + flags |= EKF_ATTITUDE; + } + if (filterStatus.flags.horiz_vel) { + flags |= EKF_VELOCITY_HORIZ; + } + if (filterStatus.flags.vert_vel) { + flags |= EKF_VELOCITY_VERT; + } + if (filterStatus.flags.horiz_pos_rel) { + flags |= EKF_POS_HORIZ_REL; + } + if (filterStatus.flags.horiz_pos_abs) { + flags |= EKF_POS_HORIZ_ABS; + } + if (filterStatus.flags.vert_pos) { + flags |= EKF_POS_VERT_ABS; + } + if (filterStatus.flags.terrain_alt) { + flags |= EKF_POS_VERT_AGL; + } + if (filterStatus.flags.const_pos_mode) { + flags |= EKF_CONST_POS_MODE; + } + if (filterStatus.flags.pred_horiz_pos_rel) { + flags |= EKF_PRED_POS_HORIZ_REL; + } + if (filterStatus.flags.pred_horiz_pos_abs) { + flags |= EKF_PRED_POS_HORIZ_ABS; + } + if (!filterStatus.flags.initalized) { + flags |= EKF_UNINITIALIZED; + } + + // send message + const float vel_gate = 5; + const float pos_gate = 5; + const float hgt_gate = 5; + const float mag_var = 0; + mavlink_msg_ekf_status_report_send(link.get_chan(), flags, + state2.kf_vel_covariance.length()/vel_gate, + state2.kf_pos_covariance.xy().length()/pos_gate, + state2.kf_pos_covariance.z/hgt_gate, + mag_var, 0, 0); +} + +#endif // AP_EXTERNAL_AHRS_INERTIAL_LABS_ENABLED + diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.h new file mode 100644 index 00000000000000..bee7d5c28e0cce --- /dev/null +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.h @@ -0,0 +1,226 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ +/* + support for serial connected InertialLabs INS system + */ + +#pragma once + +#include "AP_ExternalAHRS_config.h" + +#if AP_EXTERNAL_AHRS_INERTIAL_LABS_ENABLED + +#include "AP_ExternalAHRS_backend.h" + +class AP_ExternalAHRS_InertialLabs : public AP_ExternalAHRS_backend { + +public: + AP_ExternalAHRS_InertialLabs(AP_ExternalAHRS *frontend, AP_ExternalAHRS::state_t &state); + + // get serial port number, -1 for not enabled + int8_t get_port(void) const override; + + // accessors for AP_AHRS + bool healthy(void) const override; + bool initialised(void) const override; + bool pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const override; + void get_filter_status(nav_filter_status &status) const override; + void send_status_report(class GCS_MAVLINK &link) const override; + + // check for new data + void update() override { + check_uart(); + } + + // Get model/type name + const char* get_name() const override { + return "ILabs"; + } + + enum class MessageType : uint8_t { + GPS_INS_TIME_MS = 0x01, + GPS_WEEK = 0x3C, + ACCEL_DATA_HR = 0x23, + GYRO_DATA_HR = 0x21, + BARO_DATA = 0x25, + MAG_DATA = 0x24, + ORIENTATION_ANGLES = 0x07, + VELOCITIES = 0x12, + POSITION = 0x10, + KF_VEL_COVARIANCE = 0x58, + KF_POS_COVARIANCE = 0x57, + UNIT_STATUS = 0x53, + GNSS_EXTENDED_INFO = 0x4A, + NUM_SATS = 0x3B, + GNSS_POSITION = 0x30, + GNSS_VEL_TRACK = 0x32, + GNSS_POS_TIMESTAMP = 0x3E, + GNSS_INFO_SHORT = 0x36, + GNSS_NEW_DATA = 0x41, + GNSS_JAM_STATUS = 0xC0, + DIFFERENTIAL_PRESSURE = 0x28, + TRUE_AIRSPEED = 0x86, + WIND_SPEED = 0x8A, + AIR_DATA_STATUS = 0x8D, + SUPPLY_VOLTAGE = 0x50, + TEMPERATURE = 0x52, + UNIT_STATUS2 = 0x5A, + }; + + /* + packets consist of: + ILabsHeader + list of MessageType + sequence of ILabsData + checksum + */ + struct PACKED ILabsHeader { + uint16_t magic; // 0x55AA + uint8_t msg_type; // always 1 for INS data + uint8_t msg_id; // always 0x95 + uint16_t msg_len; // msg_len+2 is total packet length + }; + + struct PACKED vec3_16_t { + int16_t x,y,z; + Vector3f tofloat(void) { + return Vector3f(x,y,z); + } + }; + struct PACKED vec3_32_t { + int32_t x,y,z; + Vector3f tofloat(void) { + return Vector3f(x,y,z); + } + }; + struct PACKED vec3_u8_t { + uint8_t x,y,z; + Vector3f tofloat(void) { + return Vector3f(x,y,z); + } + }; + struct PACKED vec3_u16_t { + uint16_t x,y,z; + Vector3f tofloat(void) { + return Vector3f(x,y,z); + } + }; + + struct gnss_extended_info_t { + uint8_t fix_type; + uint8_t spoofing_status; + }; + + struct gnss_info_short_t { + uint8_t info1; + uint8_t info2; + }; + + union PACKED ILabsData { + uint32_t gps_time_ms; // ms since start of GPS week + uint16_t gps_week; + vec3_32_t accel_data_hr; // g * 1e6 + vec3_32_t gyro_data_hr; // deg/s * 1e5 + struct PACKED { + uint16_t pressure_pa2; // Pascals/2 + int32_t baro_alt; // meters*100 + } baro_data; + vec3_16_t mag_data; // nT/10 + struct PACKED { + int16_t yaw; // deg*100 + int16_t pitch; // deg*100 + int16_t roll; // deg*100 + } orientation_angles; // 321 euler order? + vec3_32_t velocity; // m/s * 100 + struct PACKED { + int32_t lat; // deg*1e7 + int32_t lon; // deg*1e7 + int32_t alt; // m*100, AMSL + } position; + vec3_u8_t kf_vel_covariance; // mm/s + vec3_u16_t kf_pos_covariance; + uint16_t unit_status; // set ILABS_UNIT_STATUS_* + gnss_extended_info_t gnss_extended_info; + uint8_t num_sats; + struct PACKED { + int32_t hor_speed; // m/s*100 + uint16_t track_over_ground; // deg*100 + int32_t ver_speed; // m/s*100 + } gnss_vel_track; + uint32_t gnss_pos_timestamp; // ms + gnss_info_short_t gnss_info_short; + uint8_t gnss_new_data; + uint8_t gnss_jam_status; + int32_t differential_pressure; // mbar*1e4 + int16_t true_airspeed; // m/s*100 + vec3_16_t wind_speed; // m/s*100 + uint16_t air_data_status; + uint16_t supply_voltage; // V*100 + int16_t temperature; // degC*10 + uint16_t unit_status2; + }; + + AP_ExternalAHRS::gps_data_message_t gps_data; + AP_ExternalAHRS::mag_data_message_t mag_data; + AP_ExternalAHRS::baro_data_message_t baro_data; + AP_ExternalAHRS::ins_data_message_t ins_data; + AP_ExternalAHRS::airspeed_data_message_t airspeed_data; + + uint16_t buffer_ofs; + uint8_t buffer[256]; // max for normal message set is 167+8 + +private: + AP_HAL::UARTDriver *uart; + int8_t port_num; + uint32_t baudrate; + bool setup_complete; + + void update_thread(); + bool check_uart(); + bool check_header(const ILabsHeader *h) const; + + // re-sync on header bytes + void re_sync(void); + + static const struct MessageLength { + MessageType mtype; + uint8_t length; + } message_lengths[]; + + struct { + Vector3f kf_vel_covariance; + Vector3f kf_pos_covariance; + uint32_t gnss_ins_time_ms; + uint16_t unit_status; + uint16_t unit_status2; + gnss_extended_info_t gnss_extended_info; + gnss_info_short_t gnss_info_short; + uint8_t gnss_new_data; + uint8_t gnss_jam_status; + float differential_pressure; + float true_airspeed; + Vector3f wind_speed; + uint16_t air_data_status; + float supply_voltage; + } state2; + + uint32_t last_att_ms; + uint32_t last_vel_ms; + uint32_t last_pos_ms; + uint32_t last_gps_ms; +}; + +#endif // AP_EXTERNAL_AHRS_INERTIAL_LABS_ENABLED + diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_config.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_config.h index 3b2caa23870462..0119e6857eceac 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_config.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_config.h @@ -25,3 +25,7 @@ #ifndef AP_EXTERNAL_AHRS_VECTORNAV_ENABLED #define AP_EXTERNAL_AHRS_VECTORNAV_ENABLED AP_EXTERNAL_AHRS_BACKEND_DEFAULT_ENABLED #endif + +#ifndef AP_EXTERNAL_AHRS_INERTIAL_LABS_ENABLED +#define AP_EXTERNAL_AHRS_INERTIAL_LABS_ENABLED AP_EXTERNAL_AHRS_BACKEND_DEFAULT_ENABLED +#endif From 6f79c1cee2c8a4032aeb3b8e5cb2fcf42efdb816 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 5 Dec 2023 18:40:07 +1100 Subject: [PATCH 0110/1335] AP_AHRS: use EKFType enum class in set_ekf_type() --- libraries/AP_AHRS/AP_AHRS.cpp | 6 +++--- libraries/AP_AHRS/AP_AHRS.h | 40 +++++++++++++++++------------------ 2 files changed, 23 insertions(+), 23 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index 312471f0e9f5b9..c48b06bfd3773d 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -220,12 +220,12 @@ void AP_AHRS::init() } #if !HAL_NAVEKF2_AVAILABLE && HAL_NAVEKF3_AVAILABLE if (_ekf_type.get() == 2) { - _ekf_type.set(3); + _ekf_type.set(EKFType::THREE); EKF3.set_enable(true); } #elif !HAL_NAVEKF3_AVAILABLE && HAL_NAVEKF2_AVAILABLE if (_ekf_type.get() == 3) { - _ekf_type.set(2); + _ekf_type.set(EKFType::TWO); EKF2.set_enable(true); } #endif @@ -234,7 +234,7 @@ void AP_AHRS::init() // a special case to catch users who had AHRS_EKF_TYPE=2 saved and // updated to a version where EK2_ENABLE=0 if (_ekf_type.get() == 2 && !EKF2.get_enable() && EKF3.get_enable()) { - _ekf_type.set(3); + _ekf_type.set(EKFType::THREE); } #endif diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index 25881d2f11b1b0..1d6841a28a0dde 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -421,8 +421,26 @@ class AP_AHRS { return _ekf_type; } + enum class EKFType : uint8_t { +#if AP_AHRS_DCM_ENABLED + DCM = 0, +#endif +#if HAL_NAVEKF3_AVAILABLE + THREE = 3, +#endif +#if HAL_NAVEKF2_AVAILABLE + TWO = 2, +#endif +#if AP_AHRS_SIM_ENABLED + SIM = 10, +#endif +#if HAL_EXTERNAL_AHRS_ENABLED + EXTERNAL = 11, +#endif + }; + // set the selected ekf type, for RC aux control - void set_ekf_type(uint8_t ahrs_type) { + void set_ekf_type(EKFType ahrs_type) { _ekf_type.set(ahrs_type); } @@ -673,7 +691,7 @@ class AP_AHRS { */ AP_Int8 _wind_max; AP_Int8 _board_orientation; - AP_Int8 _ekf_type; + AP_Enum _ekf_type; /* * DCM-backend parameters; it takes references to these @@ -688,24 +706,6 @@ class AP_AHRS { AP_Enum _gps_use; AP_Int8 _gps_minsats; - enum class EKFType { -#if AP_AHRS_DCM_ENABLED - DCM = 0, -#endif -#if HAL_NAVEKF3_AVAILABLE - THREE = 3, -#endif -#if HAL_NAVEKF2_AVAILABLE - TWO = 2, -#endif -#if AP_AHRS_SIM_ENABLED - SIM = 10, -#endif -#if HAL_EXTERNAL_AHRS_ENABLED - EXTERNAL = 11, -#endif - }; - EKFType active_EKF_type(void) const { return state.active_EKF; } bool always_use_EKF() const { From 897676732157a9b7552ad922c254402646827854 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 5 Dec 2023 18:40:18 +1100 Subject: [PATCH 0111/1335] RC_Channel: use EKFType enum class --- libraries/RC_Channel/RC_Channel.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 32023fe9ab9199..f454515aefab8c 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -1617,7 +1617,7 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos case AUX_FUNC::AHRS_TYPE: { #if HAL_NAVEKF3_AVAILABLE && HAL_EXTERNAL_AHRS_ENABLED - AP::ahrs().set_ekf_type(ch_flag==AuxSwitchPos::HIGH? 11 : 3); + AP::ahrs().set_ekf_type(ch_flag==AuxSwitchPos::HIGH? AP_AHRS::EKFType::EXTERNAL : AP_AHRS::EKFType::THREE); #endif break; } From 8732f582c38cb997f7273ef1ed04ef6378d36445 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 10 Dec 2023 13:42:00 +1100 Subject: [PATCH 0112/1335] AP_Scripting: update SkyPower driver to support new model support SP-275 dual-cylinder ECU --- .../AP_Scripting/drivers/EFI_SkyPower.lua | 181 +++++++++++++----- 1 file changed, 131 insertions(+), 50 deletions(-) diff --git a/libraries/AP_Scripting/drivers/EFI_SkyPower.lua b/libraries/AP_Scripting/drivers/EFI_SkyPower.lua index ba75519a99b6b5..569295ff1bac88 100644 --- a/libraries/AP_Scripting/drivers/EFI_SkyPower.lua +++ b/libraries/AP_Scripting/drivers/EFI_SkyPower.lua @@ -11,7 +11,6 @@ CAN_P1_DRIVER 1 (First driver) CAN_D1_BITRATE 500000 (500 kbit/s) --]] --- luacheck: only 0 -- Check Script uses a miniumum firmware version local SCRIPT_AP_VERSION = 4.3 @@ -27,6 +26,9 @@ local MAV_SEVERITY_ERROR = 3 local K_THROTTLE = 70 local K_HELIRSC = 31 +local MODEL_DEFAULT = 0 +local MODEL_SP_275 = 1 + PARAM_TABLE_KEY = 36 PARAM_TABLE_PREFIX = "EFI_SP_" @@ -62,10 +64,6 @@ function constrain(v, vmin, vmax) return v end ----- GLOBAL VARIABLES -local GKWH_TO_LBS_HP_HR = 0.0016439868 -local LITRES_TO_LBS = 1.6095 -- 6.1 lbs of fuel per gallon -> 1.6095 - local efi_backend = nil -- Setup EFI Parameters @@ -174,6 +172,34 @@ local EFI_SP_LOG_RT = bind_add_param('LOG_RT', 10, 10) -- rate for logg --]] local EFI_SP_ST_DISARM = bind_add_param('ST_DISARM', 11, 0) -- allow start when disarmed +--[[ + // @Param: EFI_SP_MODEL + // @DisplayName: SkyPower EFI ECU model + // @Description: SkyPower EFI ECU model + // @Values: 0:Default,1:SP_275 + // @User: Standard +--]] +local EFI_SP_MODEL = bind_add_param('MODEL', 12, MODEL_DEFAULT) + +--[[ + // @Param: EFI_SP_GEN_CTRL + // @DisplayName: SkyPower EFI enable generator control + // @Description: SkyPower EFI enable generator control + // @Values: 0:Disabled,1:Enabled + // @User: Standard +--]] +local EFI_SP_GEN_CTRL = bind_add_param('GEN_CRTL', 13, 1) + +--[[ + // @Param: EFI_SP_RST_TIME + // @DisplayName: SkyPower EFI restart time + // @Description: SkyPower EFI restart time. If engine should be running and it has stopped for this amount of time then auto-restart. To disable this feature set this value to zero. + // @Range: 0 10 + // @User: Standard + // @Units: s +--]] +local EFI_SP_RST_TIME = bind_add_param('RST_TIME', 14, 2) + if EFI_SP_ENABLE:get() == 0 then gcs:send_text(0, string.format("EFISP: disabled")) return @@ -211,7 +237,7 @@ end --[[ EFI Engine Object --]] -local function engine_control(_driver, _idx) +local function engine_control(_driver) local self = {} -- Build up the EFI_State that is passed into the EFI Scripting backend @@ -221,21 +247,16 @@ local function engine_control(_driver, _idx) -- private fields as locals local rpm = 0 local air_pressure = 0 - local inj_ang = 0 local inj_time = 0 local target_load = 0 local current_load = 0 local throttle_angle = 0 local ignition_angle = 0 - local sfc = 0 - local sfc_icao = 0 - local last_sfc_t = 0 local supply_voltage = 0 local fuel_consumption_lph = 0 local fuel_total_l = 0 local last_fuel_s = 0 local driver = _driver - local idx = _idx local last_rpm_t = get_time_sec() local last_state_update_t = get_time_sec() local last_thr_update = get_time_sec() @@ -246,6 +267,9 @@ local function engine_control(_driver, _idx) local generator_started = false local engine_start_t = 0.0 local last_throttle = 0.0 + local sensor_error_flags = 0 + local thermal_limit_flags = 0 + local starter_rpm = 0 -- frames for sending commands local FRM_500 = uint32_t(0x500) @@ -264,6 +288,10 @@ local function engine_control(_driver, _idx) temps.cht = 0.0 -- Cylinder Head Temperature temps.imt = 0.0 -- intake manifold temperature temps.oilt = 0.0 -- oil temperature + temps.cht2 = 0.0 + temps.egt2 = 0.0 + temps.imt2 = 0.0 + temps.oil2 = 0.0 -- read telemetry packets function self.update_telemetry() @@ -276,9 +304,9 @@ local function engine_control(_driver, _idx) break end - -- All Frame IDs for this EFI Engine are extended - if frame:isExtended() then - self.handle_EFI_packet(frame, _idx) + -- All Frame IDs for this EFI Engine are not extended + if not frame:isExtended() then + self.handle_EFI_packet(frame) end end if last_rpm_t > last_state_update_t then @@ -289,36 +317,79 @@ local function engine_control(_driver, _idx) end -- handle an EFI packet - function self.handle_EFI_packet(frame, idx) + function self.handle_EFI_packet(frame) local id = frame:id_signed() - if id == 0x100 then - rpm = get_uint16(frame, 0) - ignition_angle = get_uint16(frame, 2) * 0.1 - throttle_angle = get_uint16(frame, 4) * 0.1 - last_rpm_t = get_time_sec() - elseif id == 0x101 then - current_load = get_uint16(frame, 0) * 0.1 - target_load = get_uint16(frame, 2) * 0.1 - inj_time = get_uint16(frame, 4) - inj_ang = get_uint16(frame, 6) * 0.1 - elseif id == 0x102 then - -- unused fields - elseif id == 0x104 then - supply_voltage = get_uint16(frame, 0) * 0.1 - ecu_temp = get_uint16(frame, 2) * 0.1 - air_pressure = get_uint16(frame, 4) - fuel_consumption_lph = get_uint16(frame,6)*0.001 - if last_fuel_s > 0 then - local dt = now_s - last_fuel_s - local fuel_lps = fuel_consumption_lph / 3600.0 - fuel_total_l = fuel_total_l + fuel_lps * dt + if EFI_SP_MODEL:get() == MODEL_SP_275 then + -- updated telemetry for SP-275 ECU + if id == 0x100 then + rpm = get_uint16(frame, 0) + ignition_angle = get_uint16(frame, 2) * 0.1 + throttle_angle = get_uint16(frame, 4) * 0.1 + last_rpm_t = get_time_sec() + elseif id == 0x101 then + air_pressure = get_uint16(frame, 4) + elseif id == 0x102 then + inj_time = get_uint16(frame, 4) + -- inj_ang = get_uint16(frame, 2) * 0.1 + elseif id == 0x104 then + supply_voltage = get_uint16(frame, 0) * 0.1 + elseif id == 0x105 then + temps.cht = get_uint16(frame, 0) * 0.1 + temps.imt = get_uint16(frame, 2) * 0.1 + temps.egt = get_uint16(frame, 4) * 0.1 + temps.oilt = get_uint16(frame, 6) * 0.1 + elseif id == 0x107 then + sensor_error_flags = get_uint16(frame, 0) + thermal_limit_flags = get_uint16(frame, 2) + elseif id == 0x107 then + target_load = get_uint16(frame, 6) * 0.1 + elseif id == 0x10C then + temps.cht2 = get_uint16(frame, 4) * 0.1 + temps.egt2 = get_uint16(frame, 6) * 0.1 + elseif id == 0x10D then + current_load = get_uint16(frame, 2) * 0.1 + elseif id == 0x113 then + gen.amps = get_uint16(frame, 2) + elseif id == 0x2E0 then + starter_rpm = get_uint16(frame, 4) + elseif id == 0x10B then + fuel_consumption_lph = get_uint16(frame,6)*0.001 + if last_fuel_s > 0 then + local dt = now_s - last_fuel_s + local fuel_lps = fuel_consumption_lph / 3600.0 + fuel_total_l = fuel_total_l + fuel_lps * dt + end + last_fuel_s = now_s + end + else + -- original SkyPower driver + if id == 0x100 then + rpm = get_uint16(frame, 0) + ignition_angle = get_uint16(frame, 2) * 0.1 + throttle_angle = get_uint16(frame, 4) * 0.1 + last_rpm_t = get_time_sec() + elseif id == 0x101 then + current_load = get_uint16(frame, 0) * 0.1 + target_load = get_uint16(frame, 2) * 0.1 + inj_time = get_uint16(frame, 4) + -- inj_ang = get_uint16(frame, 6) * 0.1 + elseif id == 0x104 then + supply_voltage = get_uint16(frame, 0) * 0.1 + ecu_temp = get_uint16(frame, 2) * 0.1 + air_pressure = get_uint16(frame, 4) + fuel_consumption_lph = get_uint16(frame,6)*0.001 + if last_fuel_s > 0 then + local dt = now_s - last_fuel_s + local fuel_lps = fuel_consumption_lph / 3600.0 + fuel_total_l = fuel_total_l + fuel_lps * dt + end + last_fuel_s = now_s + elseif id == 0x105 then + temps.cht = get_uint16(frame, 0) * 0.1 + temps.imt = get_uint16(frame, 2) * 0.1 + temps.egt = get_uint16(frame, 4) * 0.1 + temps.oilt = get_uint16(frame, 6) * 0.1 end - last_fuel_s = now_s - elseif id == 0x105 then - temps.cht = get_uint16(frame, 0) * 0.1 - temps.imt = get_uint16(frame, 2) * 0.1 - temps.egt = get_uint16(frame, 4) * 0.1 - temps.oilt = get_uint16(frame, 6) * 0.1 end end @@ -344,7 +415,7 @@ local function engine_control(_driver, _idx) -- copy cylinder_state to efi_state efi_state:cylinder_status(cylinder_state) - last_efi_state_time = millis() + local last_efi_state_time = millis() efi_state:last_updated_ms(last_efi_state_time) @@ -368,6 +439,10 @@ local function engine_control(_driver, _idx) -- send an engine start command function self.send_engine_start() + if EFI_SP_MODEL:get() == MODEL_SP_275 then + -- the SP-275 needs a stop before a start will work + self.send_engine_stop() + end local msg = CANFrame() msg:id(FRM_505) msg:data(0,10) @@ -437,7 +512,7 @@ local function engine_control(_driver, _idx) if min_rpm > 0 and engine_started and rpm < min_rpm and allow_run_engine() then local now = get_time_sec() local dt = now - engine_start_t - if dt > 2.0 then + if EFI_SP_RST_TIME:get() > 0 and dt > EFI_SP_RST_TIME:get() then gcs:send_text(0, string.format("EFISP: re-starting engine")) self.send_engine_start() engine_start_t = get_time_sec() @@ -455,6 +530,9 @@ local function engine_control(_driver, _idx) -- update generator control function self.update_generator() + if EFI_SP_GEN_CTRL:get() == 0 then + return + end local gen_state = rc:get_aux_cached(EFI_SP_GEN_FN:get()) if gen_state == 0 and generator_started then generator_started = false @@ -504,6 +582,9 @@ local function engine_control(_driver, _idx) gcs:send_named_float('EFI_OILTMP', temps.oilt) gcs:send_named_float('EFI_TRLOAD', target_load) gcs:send_named_float('EFI_VOLTS', supply_voltage) + gcs:send_named_float('EFI_GEN_AMPS', gen.amps) + gcs:send_named_float('EFI_CHT2', temps.cht2) + gcs:send_named_float('EFI_STARTRPM', starter_rpm) end -- update custom logging @@ -517,18 +598,18 @@ local function engine_control(_driver, _idx) return end last_log_t = now - logger.write('EFSP','Thr,CLoad,TLoad,OilT,RPM,gRPM,gAmp,gCur', 'ffffffff', + logger.write('EFSP','Thr,CLoad,TLoad,OilT,RPM,gRPM,gAmp,gCur,SErr,TLim,STRPM', 'ffffffffHHH', last_throttle, current_load, target_load, temps.oilt, rpm, - gen.rpm, gen.amps, gen.batt_current) + gen.rpm, gen.amps, gen.batt_current, + sensor_error_flags, thermal_limit_flags, + starter_rpm) end -- return the instance return self -end -- end function engine_control(_driver, _idx) - -local engine1 = engine_control(driver1, 1) +end -- end function engine_control -local last_efi_state_time = 0.0 +local engine1 = engine_control(driver1) function update() now_s = get_time_sec() From 1e644d56a51806b63dcd68d5e6566ec0f10248fc Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 17 Dec 2023 15:57:13 +1100 Subject: [PATCH 0113/1335] mavlink: move forward to ardupilot/master --- modules/mavlink | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/mavlink b/modules/mavlink index 71af5c43fc24ff..130a836efbfef0 160000 --- a/modules/mavlink +++ b/modules/mavlink @@ -1 +1 @@ -Subproject commit 71af5c43fc24ffb237d3a93dc0c8358d67aa0cc0 +Subproject commit 130a836efbfef0eb3287a92cd5e187de7facdce2 From dee0ca2f3459d0f4a1d72f3f6f555fd22d208b49 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Sun, 17 Dec 2023 19:54:25 -0700 Subject: [PATCH 0114/1335] AP_ExternalARHS: Don't offer IMU by default * Since MicroStrain won't support >400Hz yet Signed-off-by: Ryan Friedman --- libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.cpp index 1abf9436355e03..5f2a066907bd04 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.cpp @@ -65,6 +65,11 @@ AP_ExternalAHRS_MicroStrain7::AP_ExternalAHRS_MicroStrain7(AP_ExternalAHRS *_fro AP_BoardConfig::allocation_error("MicroStrain7 failed to allocate ExternalAHRS update thread"); } + // don't offer IMU by default, at 100Hz it is too slow for many aircraft + set_default_sensors(uint16_t(AP_ExternalAHRS::AvailableSensor::GPS) | + uint16_t(AP_ExternalAHRS::AvailableSensor::BARO) | + uint16_t(AP_ExternalAHRS::AvailableSensor::COMPASS)); + hal.scheduler->delay(5000); GCS_SEND_TEXT(MAV_SEVERITY_INFO, "MicroStrain7 ExternalAHRS initialised"); } From 98aeade904296af06945b2da37a9606523b0bfa3 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Fri, 23 Jun 2023 21:15:14 +0100 Subject: [PATCH 0115/1335] AP_IOMCU: bdshot for iomcu prevent repeated rcout mode sets add ESC telemetry if compiled in add infrastructure to support propagating erpm and telemetry from iomcu add support to propagate bdmask to iomcu add support for EDT scale voltage and current correctly when reading EDT data ensure that telemetry data is reset reset ESC telemetry data to zero if stale ESC type and bdmask must be setup before the output mode --- libraries/AP_IOMCU/AP_IOMCU.cpp | 96 +++++++++++++++++++ libraries/AP_IOMCU/AP_IOMCU.h | 27 +++++- libraries/AP_IOMCU/iofirmware/iofirmware.cpp | 97 +++++++++++++++++++- libraries/AP_IOMCU/iofirmware/iofirmware.h | 18 +++- libraries/AP_IOMCU/iofirmware/ioprotocol.h | 26 ++++++ libraries/AP_IOMCU/iofirmware/wscript | 1 + 6 files changed, 253 insertions(+), 12 deletions(-) diff --git a/libraries/AP_IOMCU/AP_IOMCU.cpp b/libraries/AP_IOMCU/AP_IOMCU.cpp index 9045193bb2d3b1..2cf81c9165d599 100644 --- a/libraries/AP_IOMCU/AP_IOMCU.cpp +++ b/libraries/AP_IOMCU/AP_IOMCU.cpp @@ -113,6 +113,12 @@ void AP_IOMCU::thread_main(void) uart.begin(1500*1000, 128, 128); uart.set_unbuffered_writes(true); + AP_BLHeli* blh = AP_BLHeli::get_singleton(); + uint16_t erpm_period_ms = 10; // default 100Hz + if (blh && blh->get_telemetry_rate() > 0) { + erpm_period_ms = constrain_int16(1000 / blh->get_telemetry_rate(), 1, 1000); + } + trigger_event(IOEVENT_INIT); while (!do_shutdown) { @@ -308,6 +314,22 @@ void AP_IOMCU::thread_main(void) last_servo_read_ms = AP_HAL::millis(); } + if (AP_BoardConfig::io_dshot() && now - last_erpm_read_ms > erpm_period_ms) { + // read erpm at configured rate. A more efficient scheme might be to + // send erpm info back with the response from a PWM send, but that would + // require a reworking of the registers model + read_erpm(); + last_erpm_read_ms = AP_HAL::millis(); + } + + if (AP_BoardConfig::io_dshot() && now - last_telem_read_ms > 100) { + // read dshot telemetry at 10Hz + // needs to be at least 4Hz since each ESC updates at ~1Hz and we + // are reading 4 at a time + read_telem(); + last_telem_read_ms = AP_HAL::millis(); + } + if (now - last_safety_option_check_ms > 1000) { update_safety_options(); last_safety_option_check_ms = now; @@ -371,6 +393,66 @@ void AP_IOMCU::read_rc_input() } } +/* + read dshot erpm + */ +void AP_IOMCU::read_erpm() +{ + uint16_t *r = (uint16_t *)&dshot_erpm; + if (!read_registers(PAGE_RAW_DSHOT_ERPM, 0, sizeof(dshot_erpm)/2, r)) { + return; + } + uint8_t motor_poles = 14; + AP_BLHeli* blh = AP_BLHeli::get_singleton(); + if (blh) { + motor_poles = blh->get_motor_poles(); + } + for (uint8_t i = 0; i < IOMCU_MAX_CHANNELS/4; i++) { + for (uint8_t j = 0; j < 4; j++) { + const uint8_t esc_id = (i * 4 + j); + if (dshot_erpm.update_mask & 1U<temperature_cdeg[i]), + .voltage = float(telem->voltage_cvolts[i]) * 0.01, + .current = float(telem->current_camps[i]) * 0.01 + }; + update_telem_data(esc_group * 4 + i, t, telem->types[i]); + } + esc_group = (esc_group + 1) % 4; +} + /* read status registers */ @@ -841,6 +923,13 @@ void AP_IOMCU::set_dshot_period(uint16_t period_us, uint8_t drate) trigger_event(IOEVENT_SET_DSHOT_PERIOD); } +// set the dshot esc_type +void AP_IOMCU::set_dshot_esc_type(AP_HAL::RCOutput::DshotEscType dshot_esc_type) +{ + mode_out.esc_type = uint16_t(dshot_esc_type); + trigger_event(IOEVENT_SET_OUTPUT_MODE); +} + // set output mode void AP_IOMCU::set_telem_request_mask(uint32_t mask) { @@ -873,6 +962,13 @@ void AP_IOMCU::set_output_mode(uint16_t mask, uint16_t mode) trigger_event(IOEVENT_SET_OUTPUT_MODE); } +// set output mode +void AP_IOMCU::set_bidir_dshot_mask(uint16_t mask) +{ + mode_out.bdmask = mask; + trigger_event(IOEVENT_SET_OUTPUT_MODE); +} + AP_HAL::RCOutput::output_mode AP_IOMCU::get_output_mode(uint8_t& mask) const { mask = reg_status.rcout_mask; diff --git a/libraries/AP_IOMCU/AP_IOMCU.h b/libraries/AP_IOMCU/AP_IOMCU.h index 794844a950ab9b..041c565f48f193 100644 --- a/libraries/AP_IOMCU/AP_IOMCU.h +++ b/libraries/AP_IOMCU/AP_IOMCU.h @@ -13,11 +13,16 @@ #include "iofirmware/ioprotocol.h" #include #include +#include typedef uint32_t eventmask_t; typedef struct ch_thread thread_t; -class AP_IOMCU { +class AP_IOMCU +#ifdef HAL_WITH_ESC_TELEM + : public AP_ESC_Telem_Backend +#endif +{ public: AP_IOMCU(AP_HAL::UARTDriver &uart); @@ -102,6 +107,9 @@ class AP_IOMCU { // set output mode void set_output_mode(uint16_t mask, uint16_t mode); + // set bi-directional mask + void set_bidir_dshot_mask(uint16_t mask); + // get output mode AP_HAL::RCOutput::output_mode get_output_mode(uint8_t& mask) const; @@ -118,6 +126,9 @@ class AP_IOMCU { // set telem request mask void set_telem_request_mask(uint32_t mask); + // set the dshot esc_type + void set_dshot_esc_type(AP_HAL::RCOutput::DshotEscType dshot_esc_type); + // send a dshot command void send_dshot_command(uint8_t command, uint8_t chan, uint32_t command_timeout_ms, uint16_t repeat_count, bool priority); #endif @@ -192,6 +203,8 @@ class AP_IOMCU { uint32_t last_servo_read_ms; uint32_t last_safety_option_check_ms; uint32_t last_reg_read_ms; + uint32_t last_erpm_read_ms; + uint32_t last_telem_read_ms; // last value of safety options uint16_t last_safety_options = 0xFFFF; @@ -204,6 +217,8 @@ class AP_IOMCU { void send_servo_out(void); void read_rc_input(void); + void read_erpm(void); + void read_telem(void); void read_servo(void); void read_status(void); void discard_input(void); @@ -256,15 +271,17 @@ class AP_IOMCU { uint16_t rate; } dshot_rate; + // bi-directional dshot erpm values + struct page_dshot_erpm dshot_erpm; + struct page_dshot_telem dshot_telem[IOMCU_MAX_CHANNELS/4]; + uint8_t esc_group; + // queue of dshot commands that need sending ObjectBuffer dshot_command_queue{8}; struct page_GPIO GPIO; // output mode values - struct { - uint16_t mask; - uint16_t mode; - } mode_out; + struct page_mode_out mode_out; // IMU heater duty cycle uint8_t heater_duty_cycle; diff --git a/libraries/AP_IOMCU/iofirmware/iofirmware.cpp b/libraries/AP_IOMCU/iofirmware/iofirmware.cpp index 3d1cce6f62d1e9..2ff7db713b5e4b 100644 --- a/libraries/AP_IOMCU/iofirmware/iofirmware.cpp +++ b/libraries/AP_IOMCU/iofirmware/iofirmware.cpp @@ -135,8 +135,10 @@ static void dma_tx_end_cb(hal_uart_driver *uart) (void)uart->usart->DR; (void)uart->usart->DR; +#ifdef HAL_GPIO_LINE_GPIO108 TOGGLE_PIN_DEBUG(108); TOGGLE_PIN_DEBUG(108); +#endif chEvtSignalI(iomcu.thread_ctx, IOEVENT_TX_END); } @@ -416,8 +418,9 @@ void AP_IOMCU_FW::update() // immediate timeout here for lowest latency eventmask_t mask = chEvtWaitAnyTimeout(IOEVENT_PWM | IOEVENT_TX_END, TIME_IMMEDIATE); #endif - +#ifdef HAL_GPIO_LINE_GPIO107 TOGGLE_PIN_DEBUG(107); +#endif iomcu.reg_status.total_ticks++; if (mask) { @@ -482,12 +485,20 @@ void AP_IOMCU_FW::update() // turn amber off AMBER_SET(0); } + // update status page at 20Hz if (now - last_status_ms > 50) { last_status_ms = now; page_status_update(); } - +#ifdef HAL_WITH_BIDIR_DSHOT + // EDT updates are semt at ~1Hz per ESC, but we want to make sure + // that we don't delay updates unduly so sample at 5Hz + if (now - last_telem_ms > 200) { + last_telem_ms = now; + telem_update(); + } +#endif // run fast loop functions at 1Khz if (now_us - last_fast_loop_us >= 1000) { @@ -495,6 +506,9 @@ void AP_IOMCU_FW::update() heater_update(); rcin_update(); rcin_serial_update(); +#ifdef HAL_WITH_BIDIR_DSHOT + erpm_update(); +#endif } // run remaining functions at 100Hz @@ -521,7 +535,9 @@ void AP_IOMCU_FW::update() tx_dma_handle->unlock(); } #endif +#ifdef HAL_GPIO_LINE_GPIO107 TOGGLE_PIN_DEBUG(107); +#endif } void AP_IOMCU_FW::pwm_out_update() @@ -603,6 +619,44 @@ void AP_IOMCU_FW::rcin_update() } } +#ifdef HAL_WITH_BIDIR_DSHOT +void AP_IOMCU_FW::erpm_update() +{ + if (hal.rcout->new_erpm()) { + dshot_erpm.update_mask |= hal.rcout->read_erpm(dshot_erpm.erpm, IOMCU_MAX_CHANNELS); + } +} + +void AP_IOMCU_FW::telem_update() +{ + uint32_t now_ms = AP_HAL::millis(); + + for (uint8_t i = 0; i < IOMCU_MAX_CHANNELS/4; i++) { + for (uint8_t j = 0; j < 4; j++) { + const uint8_t esc_id = (i * 4 + j); + if (esc_id >= IOMCU_MAX_CHANNELS) { + continue; + } + dshot_telem[i].error_rate[j] = uint16_t(roundf(hal.rcout->get_erpm_error_rate(esc_id) * 100.0)); +#if HAL_WITH_ESC_TELEM + const volatile AP_ESC_Telem_Backend::TelemetryData& telem = esc_telem.get_telem_data(esc_id); + // if data is stale the set to zero to avoidn phantom data appearing in mavlink + if (now_ms - telem.last_update_ms > ESC_TELEM_DATA_TIMEOUT_MS) { + dshot_telem[i].voltage_cvolts[j] = 0; + dshot_telem[i].current_camps[j] = 0; + dshot_telem[i].temperature_cdeg[j] = 0; + continue; + } + dshot_telem[i].voltage_cvolts[j] = uint16_t(roundf(telem.voltage * 100)); + dshot_telem[i].current_camps[j] = uint16_t(roundf(telem.current * 100)); + dshot_telem[i].temperature_cdeg[j] = telem.temperature_cdeg; + dshot_telem[i].types[j] = telem.types; +#endif + } + } +} +#endif + void AP_IOMCU_FW::process_io_packet() { iomcu.reg_status.total_pkts++; @@ -701,6 +755,23 @@ bool AP_IOMCU_FW::handle_code_read() case PAGE_RAW_RCIN: COPY_PAGE(rc_input); break; +#ifdef HAL_WITH_BIDIR_DSHOT + case PAGE_RAW_DSHOT_ERPM: + COPY_PAGE(dshot_erpm); + break; + case PAGE_RAW_DSHOT_TELEM_1_4: + COPY_PAGE(dshot_telem[0]); + break; + case PAGE_RAW_DSHOT_TELEM_5_8: + COPY_PAGE(dshot_telem[1]); + break; + case PAGE_RAW_DSHOT_TELEM_9_12: + COPY_PAGE(dshot_telem[2]); + break; + case PAGE_RAW_DSHOT_TELEM_13_16: + COPY_PAGE(dshot_telem[3]); + break; +#endif case PAGE_STATUS: COPY_PAGE(reg_status); break; @@ -727,6 +798,16 @@ bool AP_IOMCU_FW::handle_code_read() memcpy(tx_io_packet.regs, values, sizeof(uint16_t)*tx_io_packet.count); tx_io_packet.crc = 0; tx_io_packet.crc = crc_crc8((const uint8_t *)&tx_io_packet, tx_io_packet.get_size()); + +#ifdef HAL_WITH_BIDIR_DSHOT + switch (rx_io_packet.page) { + case PAGE_RAW_DSHOT_ERPM: + memset(&dshot_erpm, 0, sizeof(dshot_erpm)); + break; + default: + break; + } +#endif return true; } @@ -814,6 +895,8 @@ bool AP_IOMCU_FW::handle_code_write() case PAGE_REG_SETUP_OUTPUT_MODE: mode_out.mask = rx_io_packet.regs[0]; mode_out.mode = rx_io_packet.regs[1]; + mode_out.bdmask = rx_io_packet.regs[2]; + mode_out.esc_type = rx_io_packet.regs[3]; break; case PAGE_REG_SETUP_HEATER_DUTY_CYCLE: @@ -1066,7 +1149,9 @@ void AP_IOMCU_FW::rcout_config_update(void) } // see if there is anything to do, we only support setting the mode for a particular channel once - if ((last_output_mode_mask & ~mode_out.mask) == mode_out.mask) { + if ((last_output_mode_mask & mode_out.mask) == mode_out.mask + && (last_output_bdmask & mode_out.bdmask) == mode_out.bdmask + && last_output_esc_type == mode_out.esc_type) { return; } @@ -1075,11 +1160,17 @@ void AP_IOMCU_FW::rcout_config_update(void) case AP_HAL::RCOutput::MODE_PWM_DSHOT300: #if defined(STM32F103xB) || defined(STM32F103x8) case AP_HAL::RCOutput::MODE_PWM_DSHOT600: +#endif +#ifdef HAL_WITH_BIDIR_DSHOT + hal.rcout->set_bidir_dshot_mask(mode_out.bdmask); + hal.rcout->set_dshot_esc_type(AP_HAL::RCOutput::DshotEscType(mode_out.esc_type)); #endif hal.rcout->set_output_mode(mode_out.mask, (AP_HAL::RCOutput::output_mode)mode_out.mode); // enabling dshot changes the memory allocation reg_status.freemem = hal.util->available_memory(); last_output_mode_mask |= mode_out.mask; + last_output_bdmask |= mode_out.bdmask; + last_output_esc_type = mode_out.esc_type; break; case AP_HAL::RCOutput::MODE_PWM_ONESHOT: case AP_HAL::RCOutput::MODE_PWM_ONESHOT125: diff --git a/libraries/AP_IOMCU/iofirmware/iofirmware.h b/libraries/AP_IOMCU/iofirmware/iofirmware.h index 62c8b12565b6e8..16227f39f7e656 100644 --- a/libraries/AP_IOMCU/iofirmware/iofirmware.h +++ b/libraries/AP_IOMCU/iofirmware/iofirmware.h @@ -4,6 +4,7 @@ #include #include #include +#include #include "hal.h" #include "ch.h" @@ -29,6 +30,8 @@ class AP_IOMCU_FW { void pwm_out_update(); void heater_update(); void rcin_update(); + void erpm_update(); + void telem_update(); bool handle_code_write(); bool handle_code_read(); @@ -112,12 +115,11 @@ class AP_IOMCU_FW { } rate; // output mode values - struct { - uint16_t mask; - uint16_t mode; - } mode_out; + struct page_mode_out mode_out; uint16_t last_output_mode_mask; + uint16_t last_output_bdmask; + uint16_t last_output_esc_type; // MIXER values struct page_mixing mixing; @@ -135,6 +137,14 @@ class AP_IOMCU_FW { void tx_dma_deallocate(ChibiOS::Shared_DMA *ctx); ChibiOS::Shared_DMA* tx_dma_handle; +#endif +#ifdef HAL_WITH_BIDIR_DSHOT + struct page_dshot_erpm dshot_erpm; + struct page_dshot_telem dshot_telem[IOMCU_MAX_CHANNELS/4]; + uint32_t last_telem_ms; +#if HAL_WITH_ESC_TELEM + AP_ESC_Telem esc_telem; +#endif #endif // true when override channel active diff --git a/libraries/AP_IOMCU/iofirmware/ioprotocol.h b/libraries/AP_IOMCU/iofirmware/ioprotocol.h index 21b0a4263a07c9..44c10d50542546 100644 --- a/libraries/AP_IOMCU/iofirmware/ioprotocol.h +++ b/libraries/AP_IOMCU/iofirmware/ioprotocol.h @@ -58,6 +58,11 @@ enum iopage { PAGE_MIXING = 200, PAGE_GPIO = 201, PAGE_DSHOT = 202, + PAGE_RAW_DSHOT_ERPM = 203, + PAGE_RAW_DSHOT_TELEM_1_4 = 204, + PAGE_RAW_DSHOT_TELEM_5_8 = 205, + PAGE_RAW_DSHOT_TELEM_9_12 = 206, + PAGE_RAW_DSHOT_TELEM_13_16 = 207, }; // setup page registers @@ -184,6 +189,13 @@ struct __attribute__((packed, aligned(2))) page_GPIO { uint8_t output_mask; }; +struct __attribute__((packed, aligned(2))) page_mode_out { + uint16_t mask; + uint16_t mode; + uint16_t bdmask; + uint16_t esc_type; +}; + struct __attribute__((packed, aligned(2))) page_dshot { uint16_t telem_mask; uint8_t command; @@ -192,3 +204,17 @@ struct __attribute__((packed, aligned(2))) page_dshot { uint8_t repeat_count; uint8_t priority; }; + +struct __attribute__((packed, aligned(2))) page_dshot_erpm { + uint16_t erpm[IOMCU_MAX_CHANNELS]; + uint32_t update_mask; +}; + +// separate telemetry packet because (a) it's too big otherwise and (b) slower update rate +struct __attribute__((packed, aligned(2))) page_dshot_telem { + uint16_t error_rate[4]; // as a centi-percentage + uint16_t voltage_cvolts[4]; + uint16_t current_camps[4]; + uint16_t temperature_cdeg[4]; + uint16_t types[4]; +}; diff --git a/libraries/AP_IOMCU/iofirmware/wscript b/libraries/AP_IOMCU/iofirmware/wscript index 7e051d72cbaefd..445b95c0e1ee0e 100644 --- a/libraries/AP_IOMCU/iofirmware/wscript +++ b/libraries/AP_IOMCU/iofirmware/wscript @@ -12,6 +12,7 @@ def build(bld): 'AP_Math', 'AP_RCProtocol', 'AP_BoardConfig', + 'AP_ESC_Telem', 'AP_SBusOut' ], exclude_src=[ From 6deff406e0fce001be61d9634765a2e0af751237 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Tue, 3 Oct 2023 20:25:00 +0100 Subject: [PATCH 0116/1335] AP_ESC_Telem: don't set up parameters on iofirmware add direct accessor for telemetry data to be used by iomcu don't update telemetry data if no data --- libraries/AP_ESC_Telem/AP_ESC_Telem.cpp | 4 +++- libraries/AP_ESC_Telem/AP_ESC_Telem.h | 5 +++++ 2 files changed, 8 insertions(+), 1 deletion(-) diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp index 0ebc163c2d27ed..d2b7e31b1488c5 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp @@ -49,7 +49,9 @@ AP_ESC_Telem::AP_ESC_Telem() AP_HAL::panic("Too many AP_ESC_Telem instances"); } _singleton = this; +#if !defined(IOMCU_FW) AP_Param::setup_object_defaults(this, var_info); +#endif } // return the average motor RPM @@ -416,7 +418,7 @@ void AP_ESC_Telem::update_telem_data(const uint8_t esc_index, const AP_ESC_Telem // can only get slightly more up-to-date information that perhaps they were expecting or might // read data that has just gone stale - both of these are safe and avoid the overhead of locking - if (esc_index >= ESC_TELEM_MAX_ESCS) { + if (esc_index >= ESC_TELEM_MAX_ESCS || data_mask == 0) { return; } diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem.h b/libraries/AP_ESC_Telem/AP_ESC_Telem.h index 503ef43299dfce..ae40ede5970792 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem.h +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem.h @@ -32,6 +32,11 @@ class AP_ESC_Telem { // get an individual ESC's raw rpm if available bool get_raw_rpm(uint8_t esc_index, float& rpm) const; + // get raw telemetry data, used by IOMCU + const volatile AP_ESC_Telem_Backend::TelemetryData& get_telem_data(uint8_t esc_index) const { + return _telem_data[esc_index]; + } + // return the average motor RPM float get_average_motor_rpm(uint32_t servo_channel_mask) const; From 9db7120c06818c09afa143e6454166b95cc2ef2f Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Fri, 6 Oct 2023 20:39:27 +0100 Subject: [PATCH 0117/1335] AP_BLHeli: add accessor for motor poles and telemetry rate --- libraries/AP_BLHeli/AP_BLHeli.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_BLHeli/AP_BLHeli.h b/libraries/AP_BLHeli/AP_BLHeli.h index ae583262fdaee3..35f1e5082263bf 100644 --- a/libraries/AP_BLHeli/AP_BLHeli.h +++ b/libraries/AP_BLHeli/AP_BLHeli.h @@ -54,6 +54,8 @@ class AP_BLHeli : public AP_ESC_Telem_Backend { } uint32_t get_bidir_dshot_mask() const { return channel_bidir_dshot_mask.get(); } + uint8_t get_motor_poles() const { return motor_poles.get(); } + uint16_t get_telemetry_rate() const { return telem_rate.get(); } static AP_BLHeli *get_singleton(void) { return _singleton; From 2a9c2fdf149ce2575ae056c57e79fb22493e776f Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Fri, 6 Oct 2023 20:36:09 +0100 Subject: [PATCH 0118/1335] AP_HAL: add methods to directly access erpm array from rcout --- libraries/AP_HAL/RCOutput.h | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/libraries/AP_HAL/RCOutput.h b/libraries/AP_HAL/RCOutput.h index bc360932268ecd..c4de0473a96f66 100644 --- a/libraries/AP_HAL/RCOutput.h +++ b/libraries/AP_HAL/RCOutput.h @@ -154,6 +154,11 @@ class AP_HAL::RCOutput { */ virtual uint16_t get_erpm(uint8_t chan) const { return 0; } virtual float get_erpm_error_rate(uint8_t chan) const { return 100.0f; } + /* + allow all erpm values to be read and for new updates to be detected - primarily for IOMCU + */ + virtual bool new_erpm() { return false; } + virtual uint32_t read_erpm(uint16_t* erpm, uint8_t len) { return 0; } /* enable PX4IO SBUS out at the given rate From e024f9fc8c2ea55d031e0eb2870a124ebf632205 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 8 Oct 2023 21:14:52 +0100 Subject: [PATCH 0119/1335] AP_Notify: ensure dshot LEDs work with EDT ESCs --- libraries/AP_Notify/DShotLED.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Notify/DShotLED.cpp b/libraries/AP_Notify/DShotLED.cpp index 798905a990e931..6b895b88bee6da 100644 --- a/libraries/AP_Notify/DShotLED.cpp +++ b/libraries/AP_Notify/DShotLED.cpp @@ -23,7 +23,8 @@ extern const AP_HAL::HAL& hal; bool DShotLED::hw_set_rgb(uint8_t red, uint8_t green, uint8_t blue) { // don't play the motor LEDs while flying - if (hal.util->get_soft_armed() || hal.rcout->get_dshot_esc_type() != AP_HAL::RCOutput::DSHOT_ESC_BLHELI) { + if (hal.util->get_soft_armed() || (hal.rcout->get_dshot_esc_type() != AP_HAL::RCOutput::DSHOT_ESC_BLHELI + && hal.rcout->get_dshot_esc_type() != AP_HAL::RCOutput::DSHOT_ESC_BLHELI_EDT)) { return false; } From 9f30d015610e912ce5cd7a783ac585b77b25b744 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 24 Sep 2023 14:09:23 +0100 Subject: [PATCH 0120/1335] AP_HAL_ChibiOS: bdshot for f103 iofirmware add support to tell if shared DMA channel is actually shared avoid starting and stopping the timer peripheral with bdshot ensure that rcout DMA allocation and deallocation happens entirely within the lock increase rcout thread working area for bdshot fix mode mask that is sent to the iomcu ensure iomcu rcout thread gets timeouts for callbacks control bdshot input and output line levels on f103 use input capture channel pairs to read rising and falling edges of telemetry on f103 reset channel pairs together on iomcu generalize the bdshot input path to support suitable buffer sizes for iomcu generalize DMAR reading of CCR registers to read two at a time on iomcu enable bi-directional dshot channels on PWM1-4 on iomcu add methods to directly access erpm values from rcout update erpm mask and esc telemetry correctly for firmware supporting dshot add support for propagating bdmask to iomcu dshot commands to all channels need to be aware of iomcu ensure esc type is propagated to iomcu cope with iomcu channel numbering when using EDT ensure pwm driver is reset properly for dshot commands on iomcu correctly reset pwm for dshot commands correctly mask off bdshot bits going to iomcu don't reset GPIO modes on disabled lines don't reset pwm_started when sharing DMA channels set thread name on iomcu rcout and reduce stack size on iomcu ensure that bdshot pulses with no response are handled correctly correctly setup DMA for input capture on f103 deal with out of order captured bytes when decoding bdshot telemetry ensure DMA sharing on f103 does not pull lines low only disable the timer peripheral when switching DMA channels on iomcu add support for waiting for _UP to finish before proceeding with dshot re-order iomcu dshot channels to let TIM4_UP go first ensure that a cascading event will always come when expected on rcout allow timeouts when using cascading dshot always rotate telemetry channel after trying to capture input cater for both in order and out-of-order bdshot telemetry packets cope with reversed packets when decoding bdshot telemetry ensure UP DMA channel is fully free on iomcu before starting next dshot cycle refactor rcout for iofirmware into separate file --- libraries/AP_HAL_ChibiOS/RCOutput.cpp | 84 +++-- libraries/AP_HAL_ChibiOS/RCOutput.h | 41 +- libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp | 147 ++++++-- .../AP_HAL_ChibiOS/RCOutput_iofirmware.cpp | 356 +++++++++++++++++- libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp | 22 +- .../hwdef/iomcu-dshot/hwdef.inc | 2 +- .../hwdef/iomcu-f103-dshot/hwdef.dat | 37 ++ .../hwdef/scripts/chibios_hwdef.py | 5 +- libraries/AP_HAL_ChibiOS/shared_dma.cpp | 5 + libraries/AP_HAL_ChibiOS/shared_dma.h | 1 + 10 files changed, 604 insertions(+), 96 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.cpp b/libraries/AP_HAL_ChibiOS/RCOutput.cpp index e703d362991052..e0539b01dd2f9d 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput.cpp @@ -336,8 +336,9 @@ void RCOutput::dshot_collect_dma_locks(uint64_t time_out_us, bool led_thread) continue; } + // dma handle will only be unlocked if the send was aborted if (group.dma_handle != nullptr && group.dma_handle->is_locked()) { - // calculate how long we have left + // if we have time left wait for the event const sysinterval_t wait_ticks = calc_ticks_remaining(group, time_out_us, led_thread ? LED_OUTPUT_PERIOD_US : _dshot_period_us); const eventmask_t mask = chEvtWaitOneTimeout(group.dshot_event_mask, wait_ticks); @@ -350,13 +351,11 @@ void RCOutput::dshot_collect_dma_locks(uint64_t time_out_us, bool led_thread) #ifdef HAL_WITH_BIDIR_DSHOT // if using input capture DMA then clean up if (group.bdshot.enabled) { - // the channel index only moves on with success - const uint8_t chan = mask ? group.bdshot.prev_telem_chan - : group.bdshot.curr_telem_chan; // only unlock if not shared - if (group.bdshot.ic_dma_handle[chan] != nullptr - && group.bdshot.ic_dma_handle[chan] != group.dma_handle) { - group.bdshot.ic_dma_handle[chan]->unlock(); + if (group.bdshot.curr_ic_dma_handle != nullptr + && group.bdshot.curr_ic_dma_handle != group.dma_handle) { + group.bdshot.curr_ic_dma_handle->unlock(); + group.bdshot.curr_ic_dma_handle = nullptr; } } #endif @@ -593,6 +592,11 @@ void RCOutput::set_dshot_esc_type(DshotEscType dshot_esc_type) DSHOT_BIT_1_TICKS = DSHOT_BIT_1_TICKS_DEFAULT; break; } +#if HAL_WITH_IO_MCU + if (AP_BoardConfig::io_dshot()) { + iomcu.set_dshot_esc_type(dshot_esc_type); + } +#endif } #endif // #if HAL_DSHOT_ENABLED @@ -1188,13 +1192,14 @@ void RCOutput::set_output_mode(uint32_t mask, const enum output_mode mode) } } #if HAL_WITH_IO_MCU + const uint16_t iomcu_mask = (mask & ((1U<= MODE_PWM_DSHOT150 && mode <= MODE_PWM_DSHOT600)) && - (mask & ((1U<is_shared()) { + /* Timer configured and started.*/ + group.pwm_drv->tim->CR1 = STM32_TIM_CR1_ARPE | STM32_TIM_CR1_URS | STM32_TIM_CR1_CEN; + group.pwm_drv->tim->DIER = group.pwm_drv->config->dier & ~STM32_TIM_DIER_IRQ_MASK; } #endif - chSysUnlock(); #if STM32_DMA_SUPPORTS_DMAMUX if (group.dma) { dmaSetRequestSource(group.dma, group.dma_up_channel); @@ -1501,6 +1518,7 @@ void RCOutput::dma_allocate(Shared_DMA *ctx) #endif } } + chSysUnlock(); } /* @@ -1508,21 +1526,23 @@ void RCOutput::dma_allocate(Shared_DMA *ctx) */ void RCOutput::dma_deallocate(Shared_DMA *ctx) { + chSysLock(); for (auto &group : pwm_group_list) { if (group.dma_handle == ctx && group.dma != nullptr) { - chSysLock(); -#if defined(IOMCU_FW) +#if defined(STM32F1) // leaving the peripheral running on IOMCU plays havoc with the UART that is - // also sharing this channel - if (group.pwm_started) { - pwmStop(group.pwm_drv); + // also sharing this channel, we only turn it off rather than resetting so + // that we don't have to worry about line modes etc + if (group.pwm_started && group.dma_handle->is_shared()) { + group.pwm_drv->tim->CR1 = 0; + group.pwm_drv->tim->DIER = 0; } #endif dmaStreamFreeI(group.dma); group.dma = nullptr; - chSysUnlock(); } } + chSysUnlock(); } #endif // AP_HAL_SHARED_DMA_ENABLED @@ -1588,7 +1608,7 @@ void RCOutput::fill_DMA_buffer_dshot(dmar_uint_t *buffer, uint8_t stride, uint16 void RCOutput::dshot_send(pwm_group &group, uint64_t time_out_us) { #if HAL_DSHOT_ENABLED - if (soft_serial_waiting() || (group.dshot_state != DshotState::IDLE && group.dshot_state != DshotState::RECV_COMPLETE)) { + if (soft_serial_waiting() || !is_dshot_send_allowed(group.dshot_state)) { // doing serial output or DMAR input, don't send DShot pulses return; } @@ -1601,7 +1621,7 @@ void RCOutput::dshot_send(pwm_group &group, uint64_t time_out_us) // if we are sharing UP channels then it might have taken a long time to get here, // if there's not enough time to actually send a pulse then cancel #if AP_HAL_SHARED_DMA_ENABLED - if (time_out_us > 0 && AP_HAL::micros64() + group.dshot_pulse_time_us > time_out_us) { + if (AP_HAL::micros64() + group.dshot_pulse_time_us > time_out_us) { group.dma_handle->unlock(); return; } @@ -1681,7 +1701,7 @@ void RCOutput::dshot_send(pwm_group &group, uint64_t time_out_us) } } - chEvtGetAndClearEvents(group.dshot_event_mask); + chEvtGetAndClearEvents(group.dshot_event_mask | DSHOT_CASCADE); // start sending the pulses out send_pulses_DMAR(group, DSHOT_BUFFER_LENGTH); #endif // HAL_DSHOT_ENABLED @@ -1700,7 +1720,7 @@ bool RCOutput::serial_led_send(pwm_group &group) } #if HAL_DSHOT_ENABLED - if (soft_serial_waiting() || (group.dshot_state != DshotState::IDLE && group.dshot_state != DshotState::RECV_COMPLETE) + if (soft_serial_waiting() || !is_dshot_send_allowed(group.dshot_state) || AP_HAL::micros64() - group.last_dmar_send_us < (group.dshot_pulse_time_us + 50)) { // doing serial output or DMAR input, don't send DShot pulses return false; @@ -1721,7 +1741,7 @@ bool RCOutput::serial_led_send(pwm_group &group) group.dshot_waiter = led_thread_ctx; - chEvtGetAndClearEvents(group.dshot_event_mask); + chEvtGetAndClearEvents(group.dshot_event_mask | DSHOT_CASCADE); // start sending the pulses out send_pulses_DMAR(group, group.dma_buffer_len); @@ -1766,10 +1786,18 @@ void RCOutput::send_pulses_DMAR(pwm_group &group, uint32_t buffer_length) #endif dmaStreamSetMode(group.dma, STM32_DMA_CR_CHSEL(group.dma_up_channel) | - STM32_DMA_CR_DIR_M2P | STM32_DMA_CR_PSIZE_WORD | -#if defined(IOMCU_FW) + STM32_DMA_CR_DIR_M2P | +#if defined(STM32F1) +#ifdef HAL_WITH_BIDIR_DSHOT + STM32_DMA_CR_PSIZE_HWORD | + STM32_DMA_CR_MSIZE_HWORD | +#else + STM32_DMA_CR_PSIZE_WORD | STM32_DMA_CR_MSIZE_BYTE | +#endif + #else + STM32_DMA_CR_PSIZE_WORD | STM32_DMA_CR_MSIZE_WORD | #endif STM32_DMA_CR_MINC | STM32_DMA_CR_PL(3) | @@ -1858,7 +1886,7 @@ void RCOutput::dma_cancel(pwm_group& group) } } chVTResetI(&group.dma_timeout); - chEvtGetAndClearEventsI(group.dshot_event_mask); + chEvtGetAndClearEventsI(group.dshot_event_mask | DSHOT_CASCADE); group.dshot_state = DshotState::IDLE; chSysUnlock(); diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.h b/libraries/AP_HAL_ChibiOS/RCOutput.h index 1fbd983944e5c0..d6c6c6a343d2f2 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.h +++ b/libraries/AP_HAL_ChibiOS/RCOutput.h @@ -25,10 +25,17 @@ #if HAL_USE_PWM == TRUE -#if defined(IOMCU_FW) +#if defined(STM32F1) +#ifdef HAL_WITH_BIDIR_DSHOT +typedef uint16_t dmar_uint_t; // save memory to allow dshot on IOMCU +typedef int16_t dmar_int_t; +#else typedef uint8_t dmar_uint_t; // save memory to allow dshot on IOMCU +typedef int8_t dmar_int_t; +#endif #else typedef uint32_t dmar_uint_t; +typedef int32_t dmar_int_t; #endif #define RCOU_DSHOT_TIMING_DEBUG 0 @@ -59,6 +66,11 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput float get_erpm_error_rate(uint8_t chan) const override { return 100.0f * float(_bdshot.erpm_errors[chan]) / (1 + _bdshot.erpm_errors[chan] + _bdshot.erpm_clean_frames[chan]); } + /* + allow all erpm values to be read and for new updates to be detected - primarily for IOMCU + */ + bool new_erpm() override { return _bdshot.update_mask != 0; } + uint32_t read_erpm(uint16_t* erpm, uint8_t len) override; #endif void set_output_mode(uint32_t mask, const enum output_mode mode) override; enum output_mode get_output_mode(uint32_t& mask) override; @@ -277,7 +289,8 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput SEND_START = 1, SEND_COMPLETE = 2, RECV_START = 3, - RECV_COMPLETE = 4 + RECV_COMPLETE = 4, + RECV_FAILED = 5 }; struct PACKED SerialLed { @@ -296,8 +309,11 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput static const uint16_t DSHOT_BUFFER_LENGTH = dshot_bit_length * 4 * sizeof(dmar_uint_t); static const uint16_t MIN_GCR_BIT_LEN = 7; static const uint16_t MAX_GCR_BIT_LEN = 22; + static const uint16_t TELEM_IC_SAMPLE = 16; static const uint16_t GCR_TELEMETRY_BIT_LEN = MAX_GCR_BIT_LEN; - static const uint16_t GCR_TELEMETRY_BUFFER_LEN = GCR_TELEMETRY_BIT_LEN*sizeof(uint32_t); + // input capture is expecting TELEM_IC_SAMPLE (16) ticks per transition (22) so the maximum + // value of the counter in CCR registers is 16*22 == 352, so must be 16-bit + static const uint16_t GCR_TELEMETRY_BUFFER_LEN = GCR_TELEMETRY_BIT_LEN*sizeof(dmar_uint_t); struct pwm_group { // only advanced timers can do high clocks needed for more than 400Hz @@ -315,6 +331,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput uint8_t stream_id; uint8_t channel; } dma_ch[4]; + bool shared_up_dma; // do we need to wait for TIMx_UP DMA to be finished after use #endif uint8_t alt_functions[4]; ioline_t pal_lines[4]; @@ -380,8 +397,9 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput uint8_t telem_tim_ch[4]; uint8_t curr_telem_chan; uint8_t prev_telem_chan; + Shared_DMA *curr_ic_dma_handle; // a shortcut to avoid logic errors involving the wrong lock uint16_t telempsc; - uint32_t dma_buffer_copy[GCR_TELEMETRY_BUFFER_LEN]; + dmar_uint_t dma_buffer_copy[GCR_TELEMETRY_BUFFER_LEN]; #if RCOU_DSHOT_TIMING_DEBUG uint16_t telem_rate[4]; uint16_t telem_err_rate[4]; @@ -525,6 +543,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput struct { uint32_t mask; uint16_t erpm[max_channels]; + volatile uint32_t update_mask; #ifdef HAL_WITH_BIDIR_DSHOT uint16_t erpm_errors[max_channels]; uint16_t erpm_clean_frames[max_channels]; @@ -593,6 +612,10 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput bool is_bidir_dshot_enabled() const { return _bdshot.mask != 0; } + static bool is_dshot_send_allowed(DshotState state) { + return state == DshotState::IDLE || state == DshotState::RECV_COMPLETE || state == DshotState::RECV_FAILED; + } + // are all the ESCs returning data bool group_escs_active(const pwm_group& group) const { return group.en_mask > 0 && (group.en_mask & _active_escs_mask) == group.en_mask; @@ -644,6 +667,8 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput uint16_t create_dshot_packet(const uint16_t value, bool telem_request, bool bidir_telem); void fill_DMA_buffer_dshot(dmar_uint_t *buffer, uint8_t stride, uint16_t packet, uint16_t clockmul); + // event to allow dshot cascading + static const eventmask_t DSHOT_CASCADE = EVENT_MASK(16); static const eventmask_t EVT_PWM_SEND = EVENT_MASK(11); static const eventmask_t EVT_PWM_SYNTHETIC_SEND = EVENT_MASK(13); @@ -672,7 +697,8 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput */ void bdshot_ic_dma_allocate(Shared_DMA *ctx); void bdshot_ic_dma_deallocate(Shared_DMA *ctx); - static uint32_t bdshot_decode_telemetry_packet(uint32_t* buffer, uint32_t count); + static uint32_t bdshot_decode_telemetry_packet(dmar_uint_t* buffer, uint32_t count); + static uint32_t bdshot_decode_telemetry_packet_f1(dmar_uint_t* buffer, uint32_t count, bool reversed); bool bdshot_decode_telemetry_from_erpm(uint16_t erpm, uint8_t chan); bool bdshot_decode_dshot_telemetry(pwm_group& group, uint8_t chan); static uint8_t bdshot_find_next_ic_channel(const pwm_group& group); @@ -681,8 +707,11 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput bool bdshot_setup_group_ic_DMA(pwm_group &group); void bdshot_prepare_for_next_pulse(pwm_group& group); static void bdshot_receive_pulses_DMAR(pwm_group* group); - static void bdshot_reset_pwm(pwm_group& group); + static void bdshot_receive_pulses_DMAR_f1(pwm_group* group); + static void bdshot_reset_pwm(pwm_group& group, uint8_t telem_channel); + static void bdshot_reset_pwm_f1(pwm_group& group, uint8_t telem_channel); static void bdshot_config_icu_dshot(stm32_tim_t* TIMx, uint8_t chan, uint8_t ccr_ch); + static void bdshot_config_icu_dshot_f1(stm32_tim_t* TIMx, uint8_t chan, uint8_t ccr_ch); static uint32_t bdshot_get_output_rate_hz(const enum output_mode mode); /* diff --git a/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp b/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp index 4a654c9610bb1d..8817e0217e646e 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp @@ -21,9 +21,20 @@ #include "hwdef/common/stm32_util.h" #include #include +#include + +#if HAL_WITH_IO_MCU +#include +extern AP_IOMCU iomcu; +#endif #ifdef HAL_WITH_BIDIR_DSHOT +#if defined(IOMCU_FW) +#undef INTERNAL_ERROR +#define INTERNAL_ERROR(x) do {} while (0) +#endif + using namespace ChibiOS; extern const AP_HAL::HAL& hal; @@ -35,14 +46,18 @@ extern const AP_HAL::HAL& hal; #define TOGGLE_PIN_CH_DEBUG(pin, channel) do {} while (0) #endif -#define TELEM_IC_SAMPLE 16 - /* * enable bi-directional telemetry request for a mask of channels. This is used * with DShot to get telemetry feedback */ void RCOutput::set_bidir_dshot_mask(uint32_t mask) { +#if HAL_WITH_IO_MCU + const uint32_t iomcu_mask = ((1U<> chan_offset); // we now need to reconfigure the DMA channels since they are affected by the value of the mask for (uint8_t i = 0; i < NUM_GROUPS; i++ ) { @@ -75,6 +90,7 @@ bool RCOutput::bdshot_setup_group_ic_DMA(pwm_group &group) // Return error return false; } + if (!group.bdshot.ic_dma_handle[i]) { // share up channel if required if (group.dma_ch[i].stream_id == group.dma_up_stream_id) { @@ -98,6 +114,11 @@ bool RCOutput::bdshot_setup_group_ic_DMA(pwm_group &group) if (group.chan[i] != CHAN_DISABLED && _bdshot.mask & group.ch_mask) { // bi-directional dshot requires less than MID2 speed and PUSHPULL in order to avoid noise on the line // when switching from output to input +#if defined(STM32F1) + // on F103 the line mode has to be managed manually + // PAL_MODE_STM32_ALTERNATE_PUSHPULL is 50Mhz, similar to the medieum speed on other MCUs + palSetLineMode(group.pal_lines[i], PAL_MODE_STM32_ALTERNATE_PUSHPULL); +#else palSetLineMode(group.pal_lines[i], PAL_MODE_ALTERNATE(group.alt_functions[i]) | PAL_STM32_OTYPE_PUSHPULL | PAL_STM32_PUPDR_PULLUP | #ifdef PAL_STM32_OSPEED_MID1 @@ -108,6 +129,7 @@ bool RCOutput::bdshot_setup_group_ic_DMA(pwm_group &group) #error "Cannot set bdshot line speed" #endif ); +#endif } if (!group.is_chan_enabled(i) || !(_bdshot.mask & (1 << group.chan[i]))) { @@ -166,13 +188,12 @@ bool RCOutput::bdshot_setup_group_ic_DMA(pwm_group &group) */ void RCOutput::bdshot_ic_dma_allocate(Shared_DMA *ctx) { + chSysLock(); for (uint8_t i = 0; i < NUM_GROUPS; i++ ) { pwm_group &group = pwm_group_list[i]; for (uint8_t icuch = 0; icuch < 4; icuch++) { if (group.bdshot.ic_dma_handle[icuch] == ctx && group.bdshot.ic_dma[icuch] == nullptr) { - chSysLock(); group.bdshot.ic_dma[icuch] = dmaStreamAllocI(group.dma_ch[icuch].stream_id, 10, bdshot_dma_ic_irq_callback, &group); - chSysUnlock(); #if STM32_DMA_SUPPORTS_DMAMUX if (group.bdshot.ic_dma[icuch]) { dmaSetRequestSource(group.bdshot.ic_dma[icuch], group.dma_ch[icuch].channel); @@ -181,6 +202,7 @@ void RCOutput::bdshot_ic_dma_allocate(Shared_DMA *ctx) } } } + chSysUnlock(); } /* @@ -188,23 +210,23 @@ void RCOutput::bdshot_ic_dma_allocate(Shared_DMA *ctx) */ void RCOutput::bdshot_ic_dma_deallocate(Shared_DMA *ctx) { + chSysLock(); for (uint8_t i = 0; i < NUM_GROUPS; i++ ) { pwm_group &group = pwm_group_list[i]; for (uint8_t icuch = 0; icuch < 4; icuch++) { if (group.bdshot.ic_dma_handle[icuch] == ctx && group.bdshot.ic_dma[icuch] != nullptr) { - chSysLock(); dmaStreamFreeI(group.bdshot.ic_dma[icuch]); group.bdshot.ic_dma[icuch] = nullptr; - chSysUnlock(); } } } + chSysUnlock(); } // setup bdshot for sending and receiving the next pulse void RCOutput::bdshot_prepare_for_next_pulse(pwm_group& group) { - // assume that we won't be able to get the input capture lock + // assume that we won't be able to get the input capture lock group.bdshot.enabled = false; uint32_t active_channels = group.ch_mask & group.en_mask; @@ -214,8 +236,10 @@ void RCOutput::bdshot_prepare_for_next_pulse(pwm_group& group) // no locking required group.bdshot.enabled = true; } else { - osalDbgAssert(!group.bdshot.ic_dma_handle[group.bdshot.curr_telem_chan]->is_locked(), "DMA handle is already locked"); - group.bdshot.ic_dma_handle[group.bdshot.curr_telem_chan]->lock(); + osalDbgAssert(!group.bdshot.curr_ic_dma_handle, "IC DMA handle has not been released"); + group.bdshot.curr_ic_dma_handle = group.bdshot.ic_dma_handle[group.bdshot.curr_telem_chan]; + osalDbgAssert(group.shared_up_dma || !group.bdshot.curr_ic_dma_handle->is_locked(), "IC DMA handle is already locked"); + group.bdshot.curr_ic_dma_handle->lock(); group.bdshot.enabled = true; } } @@ -236,31 +260,42 @@ void RCOutput::bdshot_prepare_for_next_pulse(pwm_group& group) _bdshot.erpm_errors[chan] = 0; _bdshot.erpm_last_stats_ms[chan] = now; } + } else if (group.dshot_state == DshotState::RECV_FAILED) { + _bdshot.erpm_errors[group.bdshot.curr_telem_chan]++; } if (group.bdshot.enabled) { if (group.pwm_started) { - bdshot_reset_pwm(group); - } else { + bdshot_reset_pwm(group, group.bdshot.prev_telem_chan); + } + else { pwmStart(group.pwm_drv, &group.pwm_cfg); + group.pwm_started = true; } - group.pwm_started = true; // we can be more precise for capture timer group.bdshot.telempsc = (uint16_t)(lrintf(((float)group.pwm_drv->clock / bdshot_get_output_rate_hz(group.current_mode) + 0.01f)/TELEM_IC_SAMPLE) - 1); } } -void RCOutput::bdshot_reset_pwm(pwm_group& group) +// reset pwm driver to output mode without resetting the clock or the peripheral +// the code here is the equivalent of pwmStart()/pwmStop() +void RCOutput::bdshot_reset_pwm(pwm_group& group, uint8_t telem_channel) { +#if defined(STM32F1) + bdshot_reset_pwm_f1(group, telem_channel); +#else + // on more capable MCUs we can do something very simple pwmStop(group.pwm_drv); pwmStart(group.pwm_drv, &group.pwm_cfg); +#endif } // see https://github.com/betaflight/betaflight/pull/8554#issuecomment-512507625 // called from the interrupt #pragma GCC push_options #pragma GCC optimize("O2") +#if !defined(STM32F1) void RCOutput::bdshot_receive_pulses_DMAR(pwm_group* group) { // make sure the transaction finishes or times out, this function takes a little time to run so the most @@ -268,13 +303,12 @@ void RCOutput::bdshot_receive_pulses_DMAR(pwm_group* group) // should be plenty chVTSetI(&group->dma_timeout, chTimeUS2I(group->dshot_pulse_send_time_us + 30U + 10U), bdshot_finish_dshot_gcr_transaction, group); - uint8_t curr_ch = group->bdshot.curr_telem_chan; group->pwm_drv->tim->CR1 = 0; - group->pwm_drv->tim->CCER = 0; // Configure Timer group->pwm_drv->tim->SR = 0; + group->pwm_drv->tim->CCER = 0; group->pwm_drv->tim->CCMR1 = 0; group->pwm_drv->tim->CCMR2 = 0; group->pwm_drv->tim->DIER = 0; @@ -286,6 +320,7 @@ void RCOutput::bdshot_receive_pulses_DMAR(pwm_group* group) //TOGGLE_PIN_CH_DEBUG(54, curr_ch); group->pwm_drv->tim->ARR = 0xFFFF; // count forever group->pwm_drv->tim->CNT = 0; + uint8_t curr_ch = group->bdshot.curr_telem_chan; // Initialise ICU channels bdshot_config_icu_dshot(group->pwm_drv->tim, curr_ch, group->bdshot.telem_tim_ch[curr_ch]); @@ -308,7 +343,9 @@ void RCOutput::bdshot_receive_pulses_DMAR(pwm_group* group) #endif dmaStreamSetMode(ic_dma, STM32_DMA_CR_CHSEL(group->dma_ch[curr_ch].channel) | - STM32_DMA_CR_DIR_P2M | STM32_DMA_CR_PSIZE_WORD | STM32_DMA_CR_MSIZE_WORD | + STM32_DMA_CR_DIR_P2M | + STM32_DMA_CR_PSIZE_WORD | + STM32_DMA_CR_MSIZE_WORD | STM32_DMA_CR_MINC | STM32_DMA_CR_PL(3) | STM32_DMA_CR_TEIE | STM32_DMA_CR_TCIE); @@ -424,6 +461,7 @@ void RCOutput::bdshot_config_icu_dshot(stm32_tim_t* TIMx, uint8_t chan, uint8_t break; } } +#endif /* unlock DMA channel after a bi-directional dshot transaction completes @@ -441,14 +479,21 @@ __RAMFUNC__ void RCOutput::bdshot_finish_dshot_gcr_transaction(virtual_timer_t* // or the input channel buffer const stm32_dma_stream_t *dma = group->has_shared_ic_up_dma() ? group->dma : group->bdshot.ic_dma[curr_telem_chan]; + osalDbgAssert(dma, "No DMA channel"); // record the transaction size before the stream is released dmaStreamDisable(dma); group->bdshot.dma_tx_size = MIN(uint16_t(GCR_TELEMETRY_BIT_LEN), GCR_TELEMETRY_BIT_LEN - dmaStreamGetTransactionSize(dma)); + stm32_cacheBufferInvalidate(group->dma_buffer, group->bdshot.dma_tx_size); - memcpy(group->bdshot.dma_buffer_copy, group->dma_buffer, sizeof(uint32_t) * group->bdshot.dma_tx_size); + memcpy(group->bdshot.dma_buffer_copy, group->dma_buffer, sizeof(dmar_uint_t) * group->bdshot.dma_tx_size); - group->dshot_state = DshotState::RECV_COMPLETE; + // although it should be possible to start the next DMAR transaction concurrently with receiving + // telemetry, in practice it seems to interfere with the DMA engine + if (group->shared_up_dma && group->bdshot.enabled) { + // next dshot pulse can go out now + chEvtSignalI(group->dshot_waiter, DSHOT_CASCADE); + } // if using input capture DMA and sharing the UP and CH channels then clean up // by assigning the source back to UP @@ -458,9 +503,17 @@ __RAMFUNC__ void RCOutput::bdshot_finish_dshot_gcr_transaction(virtual_timer_t* } #endif - // rotate to the next input channel group->bdshot.prev_telem_chan = group->bdshot.curr_telem_chan; + // rotate to the next input channel, we have to rotate even on failure otherwise + // we will not get data from active channels group->bdshot.curr_telem_chan = bdshot_find_next_ic_channel(*group); + + if (group->bdshot.dma_tx_size > 0) { + group->dshot_state = DshotState::RECV_COMPLETE; + } else { + group->dshot_state = DshotState::RECV_FAILED; + } + // tell the waiting process we've done the DMA chEvtSignalI(group->dshot_waiter, group->dshot_event_mask); #ifdef HAL_GPIO_LINE_GPIO56 @@ -479,7 +532,12 @@ bool RCOutput::bdshot_decode_dshot_telemetry(pwm_group& group, uint8_t chan) } // evaluate dshot telemetry +#if defined(STM32F1) + const bool reversed = (group.bdshot.telem_tim_ch[chan] & 1U) == 0; + group.bdshot.erpm[chan] = bdshot_decode_telemetry_packet_f1(group.bdshot.dma_buffer_copy, group.bdshot.dma_tx_size, reversed); +#else group.bdshot.erpm[chan] = bdshot_decode_telemetry_packet(group.bdshot.dma_buffer_copy, group.bdshot.dma_tx_size); +#endif group.dshot_state = DshotState::IDLE; @@ -496,7 +554,7 @@ bool RCOutput::bdshot_decode_dshot_telemetry(pwm_group& group, uint8_t chan) TOGGLE_PIN_DEBUG(57); #endif } - +#if !defined(IOMCU_FW) uint64_t now = AP_HAL::micros64(); if (chan == DEBUG_CHANNEL && (now - group.bdshot.last_print) > 1000000) { hal.console->printf("TELEM: %d <%d Hz, %.1f%% err>", group.bdshot.erpm[chan], group.bdshot.telem_rate[chan], @@ -511,6 +569,7 @@ bool RCOutput::bdshot_decode_dshot_telemetry(pwm_group& group, uint8_t chan) group.bdshot.telem_err_rate[chan] = 0; group.bdshot.last_print = now; } +#endif #endif return group.bdshot.erpm[chan] != 0xFFFF; } @@ -549,13 +608,19 @@ __RAMFUNC__ void RCOutput::dma_up_irq_callback(void *p, uint32_t flags) } dmaStreamDisable(group->dma); - if (group->in_serial_dma && irq.waiter) { + if (soft_serial_waiting()) { +#if HAL_SERIAL_ESC_COMM_ENABLED // tell the waiting process we've done the DMA chEvtSignalI(irq.waiter, serial_event_mask); +#endif } else if (!group->in_serial_dma && group->bdshot.enabled) { group->dshot_state = DshotState::SEND_COMPLETE; // sending is done, in 30us the ESC will send telemetry +#if defined(STM32F1) + bdshot_receive_pulses_DMAR_f1(group); +#else bdshot_receive_pulses_DMAR(group); +#endif } else { // non-bidir case, this prevents us ever having two dshot pulses too close together if (is_dshot_protocol(group->current_mode)) { @@ -604,20 +669,21 @@ uint32_t RCOutput::bdshot_get_output_rate_hz(const enum output_mode mode) } } -#define INVALID_ERPM 0xffffU +#define INVALID_ERPM 0xfffU // decode a telemetry packet from a GCR encoded stride buffer, take from betaflight decodeTelemetryPacket // see https://github.com/betaflight/betaflight/pull/8554#issuecomment-512507625 for a description of the protocol -uint32_t RCOutput::bdshot_decode_telemetry_packet(uint32_t* buffer, uint32_t count) +uint32_t RCOutput::bdshot_decode_telemetry_packet(dmar_uint_t* buffer, uint32_t count) { uint32_t value = 0; - uint32_t oldValue = buffer[0]; uint32_t bits = 0; uint32_t len; + dmar_uint_t oldValue = buffer[0]; + for (uint32_t i = 1; i <= count; i++) { if (i < count) { - int32_t diff = buffer[i] - oldValue; + dmar_int_t diff = buffer[i] - oldValue; if (bits >= 21U) { break; } @@ -631,6 +697,7 @@ uint32_t RCOutput::bdshot_decode_telemetry_packet(uint32_t* buffer, uint32_t cou oldValue = buffer[i]; bits += len; } + if (bits != 21U) { return INVALID_ERPM; } @@ -665,8 +732,16 @@ bool RCOutput::bdshot_decode_telemetry_from_erpm(uint16_t encodederpm, uint8_t c } // eRPM = m << e (see https://github.com/bird-sanctuary/extended-dshot-telemetry) - uint8_t expo = ((encodederpm & 0xfffffe00U) >> 9U) & 0xffU; - uint16_t value = (encodederpm & 0x000001ffU); + uint8_t expo = ((encodederpm & 0xfffffe00U) >> 9U) & 0xffU; // 3bits + uint16_t value = (encodederpm & 0x000001ffU); // 9bits +#if HAL_WITH_ESC_TELEM + uint8_t normalized_chan = chan; +#endif +#if HAL_WITH_IO_MCU + if (AP_BoardConfig::io_dshot()) { + normalized_chan = chan + chan_offset; + } +#endif if (!(value & 0x100U) && (_dshot_esc_type == DSHOT_ESC_BLHELI_EDT || _dshot_esc_type == DSHOT_ESC_BLHELI_EDT_S)) { switch (expo) { @@ -675,7 +750,7 @@ bool RCOutput::bdshot_decode_telemetry_from_erpm(uint16_t encodederpm, uint8_t c TelemetryData t { .temperature_cdeg = int16_t(value * 100) }; - update_telem_data(chan, t, AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE); + update_telem_data(normalized_chan, t, AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE); #endif return false; } @@ -685,7 +760,7 @@ bool RCOutput::bdshot_decode_telemetry_from_erpm(uint16_t encodederpm, uint8_t c TelemetryData t { .voltage = 0.25f * value }; - update_telem_data(chan, t, AP_ESC_Telem_Backend::TelemetryType::VOLTAGE); + update_telem_data(normalized_chan, t, AP_ESC_Telem_Backend::TelemetryType::VOLTAGE); #endif return false; } @@ -695,7 +770,7 @@ bool RCOutput::bdshot_decode_telemetry_from_erpm(uint16_t encodederpm, uint8_t c TelemetryData t { .current = float(value) }; - update_telem_data(chan, t, AP_ESC_Telem_Backend::TelemetryType::CURRENT); + update_telem_data(normalized_chan, t, AP_ESC_Telem_Backend::TelemetryType::CURRENT); #endif return false; } @@ -726,11 +801,21 @@ bool RCOutput::bdshot_decode_telemetry_from_erpm(uint16_t encodederpm, uint8_t c // update the ESC telemetry data if (erpm < INVALID_ERPM) { _bdshot.erpm[chan] = erpm; + _bdshot.update_mask |= 1U<is_system_initialized()) { + while (!hal.scheduler->is_system_initialized() || _dshot_period_us == 0) { hal.scheduler->delay_microseconds(1000); } rcout_thread_ctx = chThdGetSelfX(); + chRegSetThreadNameX(rcout_thread_ctx, rcout_thread_name); + + uint64_t last_cycle_run_us = 0; while (true) { chEvtWaitOne(EVT_PWM_SEND | EVT_PWM_SYNTHETIC_SEND); - + // start the clock + const uint64_t last_thread_run_us = AP_HAL::micros64(); // this is when the cycle is supposed to start if (_dshot_cycle == 0) { + last_cycle_run_us = AP_HAL::micros64(); // register a timer for the next tick if push() will not be providing it if (_dshot_rate != 1) { chVTSet(&_dshot_rate_timer, chTimeUS2I(_dshot_period_us), dshot_update_tick, this); } } - // main thread requested a new dshot send or we timed out - if we are not running - // as a multiple of loop rate then ignore EVT_PWM_SEND events to preserve periodicity - dshot_send_groups(0); + // if DMA sharing is in effect there can be quite a delay between the request to begin the cycle and + // actually sending out data - thus we need to work out how much time we have left to collect the locks + uint64_t time_out_us = (_dshot_cycle + 1) * _dshot_period_us + last_cycle_run_us; + if (!_dshot_rate) { + time_out_us = last_thread_run_us + _dshot_period_us; + } + + // DMA channel sharing on F10x is complicated. The allocations are + // TIM2_UP - (1,2) + // TIM4_UP - (1,7) + // TIM3_UP - (1,3) + // TIM2_CH2 - (1,7) - F103 only + // TIM4_CH3 - (1,5) - F103 only + // TIM3_CH4 - (1,3) - F103 only + // and (1,7) is also shared with USART2_TX + // locks have to be unlocked in reverse order, and shared CH locks do not need to be taken so the + // ordering that will work follows. This relies on recursive lock behaviour that allows us to relock + // a mutex without releasing it first: + // TIM4_UP - lock (shared) + // TIM4 - dshot send + // TIM4_CH3 - lock + // TIM2_UP - lock + // TIM2_CH2 - lock recursive (shared) + // TIM2 - dshot send + // TIM3_UP - lock + // [TIM3_CH4 - shared lock] + // TIM3 - dshot send + // [TIM3_CH4 - shared unlock] + // TIM3_UP - unlock + // TIM2_CH2 - unlock recursive (shared) + // TIM2_UP - unlock + // TIM4_CH3 - unlock + // TIM4_UP - unlock + + dshot_send_groups(time_out_us); #if AP_HAL_SHARED_DMA_ENABLED - dshot_collect_dma_locks(0); + dshot_collect_dma_locks(time_out_us); #endif if (_dshot_rate > 0) { _dshot_cycle = (_dshot_cycle + 1) % _dshot_rate; @@ -98,6 +134,296 @@ void RCOutput::rcout_thread() { } } +#if defined(HAL_WITH_BIDIR_DSHOT) && defined(STM32F1) +// reset pwm driver to output mode without resetting the clock or the peripheral +// the code here is the equivalent of pwmStart()/pwmStop() +void RCOutput::bdshot_reset_pwm_f1(pwm_group& group, uint8_t telem_channel) +{ + osalSysLock(); + + stm32_tim_t* TIMx = group.pwm_drv->tim; + // pwmStop sets these + TIMx->CR1 = 0; /* Timer disabled. */ + TIMx->DIER = 0; /* All IRQs disabled. */ + TIMx->SR = 0; /* Clear eventual pending IRQs. */ + TIMx->CNT = 0; + TIMx->CCR[0] = 0; /* Comparator 1 disabled. */ + TIMx->CCR[1] = 0; /* Comparator 2 disabled. */ + TIMx->CCR[2] = 0; /* Comparator 3 disabled. */ + TIMx->CCR[3] = 0; /* Comparator 4 disabled. */ + // at the point this is called we will have done input capture on two CC channels + // we need to switch those channels back to output and the default settings + // all other channels will not have been modified + switch (group.bdshot.telem_tim_ch[telem_channel]) { + case 0: // CC1 + case 1: // CC2 + MODIFY_REG(TIMx->CCER, TIM_CCER_CC2E | TIM_CCER_CC1E, 0); // disable CC so that it can be modified + MODIFY_REG(TIMx->CCMR1, (TIM_CCMR1_CC1S | TIM_CCMR1_IC1F | TIM_CCMR1_IC1PSC), + STM32_TIM_CCMR1_OC1M(6) | STM32_TIM_CCMR1_OC1PE); + MODIFY_REG(TIMx->CCMR1, (TIM_CCMR1_CC2S | TIM_CCMR1_IC2F | TIM_CCMR1_IC2PSC), + STM32_TIM_CCMR1_OC2M(6) | STM32_TIM_CCMR1_OC2PE); + MODIFY_REG(TIMx->CCER, (TIM_CCER_CC1P | TIM_CCER_CC2P), + (TIM_CCER_CC1P | TIM_CCER_CC2P | TIM_CCER_CC1E | TIM_CCER_CC2E)); + break; + case 2: // CC3 + case 3: // CC4 + MODIFY_REG(TIMx->CCER, TIM_CCER_CC3E | TIM_CCER_CC4E, 0); // disable CC so that it can be modified + MODIFY_REG(TIMx->CCMR2, (TIM_CCMR2_CC3S | TIM_CCMR2_IC3F | TIM_CCMR2_IC3PSC), + STM32_TIM_CCMR2_OC3M(6) | STM32_TIM_CCMR2_OC3PE); + MODIFY_REG(TIMx->CCMR2, (TIM_CCMR2_CC4S | TIM_CCMR2_IC4F | TIM_CCMR2_IC4PSC), + STM32_TIM_CCMR2_OC4M(6) | STM32_TIM_CCMR2_OC4PE); + MODIFY_REG(TIMx->CCER, (TIM_CCER_CC3P | TIM_CCER_CC4P), + (TIM_CCER_CC3P | TIM_CCER_CC4P | TIM_CCER_CC3E | TIM_CCER_CC4E)); + break; + default: + break; + } + // pwmStart sets these + uint32_t psc = (group.pwm_drv->clock / group.pwm_drv->config->frequency) - 1; + TIMx->PSC = psc; + TIMx->ARR = group.pwm_drv->period - 1; + TIMx->CR2 = group.pwm_drv->config->cr2; + TIMx->EGR = STM32_TIM_EGR_UG; /* Update event. */ + TIMx->SR = 0; /* Clear pending IRQs. */ + TIMx->DIER = group.pwm_drv->config->dier & /* DMA-related DIER settings. */ + ~STM32_TIM_DIER_IRQ_MASK; + if (group.pwm_drv->has_bdtr) { + TIMx->BDTR = group.pwm_drv->config->bdtr | STM32_TIM_BDTR_MOE; + } + + // we need to switch every output on the same input channel to avoid + // spurious line changes + for (uint8_t i = 0; i<4; i++) { + if (group.chan[i] == CHAN_DISABLED) { + continue; + } + if (group.bdshot.telem_tim_ch[telem_channel] == group.bdshot.telem_tim_ch[i]) { + palSetLineMode(group.pal_lines[i], PAL_MODE_STM32_ALTERNATE_PUSHPULL); + } + } + + /* Timer configured and started.*/ + TIMx->CR1 = STM32_TIM_CR1_ARPE | STM32_TIM_CR1_URS | STM32_TIM_CR1_CEN; + + osalSysUnlock(); +} + +// see https://github.com/betaflight/betaflight/pull/8554#issuecomment-512507625 +// called from the interrupt +void RCOutput::bdshot_receive_pulses_DMAR_f1(pwm_group* group) +{ + // make sure the transaction finishes or times out, this function takes a little time to run so the most + // accurate timing is from the beginning. the pulse time is slightly longer than we need so an extra 10U + // should be plenty + chVTSetI(&group->dma_timeout, chTimeUS2I(group->dshot_pulse_send_time_us + 30U + 10U), + bdshot_finish_dshot_gcr_transaction, group); + + group->pwm_drv->tim->CR1 = 0; + + // Configure Timer + group->pwm_drv->tim->SR = 0; + // do NOT set CCER to 0 here - this pulls the line low on F103 (at least) + // and since we are already doing bdshot the relevant options that are set for output + // also apply to input and bdshot_config_icu_dshot() will disable any channels that need + // disabling + group->pwm_drv->tim->DIER = 0; + group->pwm_drv->tim->CR2 = 0; + group->pwm_drv->tim->PSC = group->bdshot.telempsc; + + group->dshot_state = DshotState::RECV_START; + + //TOGGLE_PIN_CH_DEBUG(54, curr_ch); + group->pwm_drv->tim->ARR = 0xFFFF; // count forever + group->pwm_drv->tim->CNT = 0; + uint8_t curr_ch = group->bdshot.curr_telem_chan; + + // we need to switch every input on the same input channel to allow + // the ESCs to drive the lines + for (uint8_t i = 0; i<4; i++) { + if (group->chan[i] == CHAN_DISABLED) { + continue; + } + if (group->bdshot.telem_tim_ch[curr_ch] == group->bdshot.telem_tim_ch[i]) { + palSetLineMode(group->pal_lines[i], PAL_MODE_INPUT_PULLUP); + } + } + + // Initialise ICU channels + bdshot_config_icu_dshot_f1(group->pwm_drv->tim, curr_ch, group->bdshot.telem_tim_ch[curr_ch]); + + const stm32_dma_stream_t *ic_dma = + group->has_shared_ic_up_dma() ? group->dma : group->bdshot.ic_dma[curr_ch]; + + // Configure DMA + dmaStreamSetPeripheral(ic_dma, &(group->pwm_drv->tim->DMAR)); + dmaStreamSetMemory0(ic_dma, group->dma_buffer); + dmaStreamSetTransactionSize(ic_dma, GCR_TELEMETRY_BIT_LEN); + dmaStreamSetMode(ic_dma, + STM32_DMA_CR_CHSEL(group->dma_ch[curr_ch].channel) | + STM32_DMA_CR_DIR_P2M | + STM32_DMA_CR_PSIZE_HWORD | + STM32_DMA_CR_MSIZE_HWORD | + STM32_DMA_CR_MINC | STM32_DMA_CR_PL(3) | + STM32_DMA_CR_TEIE | STM32_DMA_CR_TCIE); + + // setup for transfers. 0x0D is the register + // address offset of the CCR registers in the timer peripheral + uint8_t telem_ch_pair = group->bdshot.telem_tim_ch[curr_ch] & ~1U; // round to the lowest of the channel pair + const uint8_t ccr_ofs = offsetof(stm32_tim_t, CCR)/4 + telem_ch_pair; + group->pwm_drv->tim->DCR = STM32_TIM_DCR_DBA(ccr_ofs) | STM32_TIM_DCR_DBL(1); // read two registers at a time + + // Start Timer + group->pwm_drv->tim->EGR |= STM32_TIM_EGR_UG; + group->pwm_drv->tim->SR = 0; + group->pwm_drv->tim->CR1 = TIM_CR1_ARPE | STM32_TIM_CR1_URS | STM32_TIM_CR1_UDIS | STM32_TIM_CR1_CEN; + dmaStreamEnable(ic_dma); +} + +void RCOutput::bdshot_config_icu_dshot_f1(stm32_tim_t* TIMx, uint8_t chan, uint8_t ccr_ch) +{ + // F103 does not support both edges input capture so we need to set up two channels + // both pointing at the same input to capture the data. The triggered channel + // needs to handle the second edge - so rising or falling - so that we get an + // even number of half-words in the DMA buffer + switch(ccr_ch) { + case 0: + case 1: { + // Disable the IC1 and IC2: Reset the CCxE Bit + MODIFY_REG(TIMx->CCER, TIM_CCER_CC1E | TIM_CCER_CC2E, 0); + // Select the Input and set the filter and the prescaler value + if (chan == 0) { // TI1 + MODIFY_REG(TIMx->CCMR1, + (TIM_CCMR1_CC1S | TIM_CCMR1_IC1F | TIM_CCMR1_IC1PSC), + (TIM_CCMR1_CC1S_0 | TIM_CCMR1_IC1F_1));// 4 samples per output transition + MODIFY_REG(TIMx->CCMR1, + (TIM_CCMR1_CC2S | TIM_CCMR1_IC2F | TIM_CCMR1_IC2PSC), + (TIM_CCMR1_CC2S_1 | TIM_CCMR1_IC2F_1)); + } else { // TI2 + MODIFY_REG(TIMx->CCMR1, + (TIM_CCMR1_CC1S | TIM_CCMR1_IC1F | TIM_CCMR1_IC1PSC), + (TIM_CCMR1_CC1S_1 | TIM_CCMR1_IC1F_1)); + MODIFY_REG(TIMx->CCMR1, + (TIM_CCMR1_CC2S | TIM_CCMR1_IC2F | TIM_CCMR1_IC2PSC), + (TIM_CCMR1_CC2S_0 | TIM_CCMR1_IC2F_1)); + } + if (ccr_ch == 0) { + // Select the Polarity as falling on IC2 and rising on IC1 + MODIFY_REG(TIMx->CCER, TIM_CCER_CC1P | TIM_CCER_CC2P, TIM_CCER_CC2P | TIM_CCER_CC1E | TIM_CCER_CC2E); + MODIFY_REG(TIMx->DIER, TIM_DIER_CC1DE | TIM_DIER_CC2DE, TIM_DIER_CC1DE); + } else { + // Select the Polarity as falling on IC1 and rising on IC2 + MODIFY_REG(TIMx->CCER, TIM_CCER_CC1P | TIM_CCER_CC2P, TIM_CCER_CC1P | TIM_CCER_CC1E | TIM_CCER_CC2E); + MODIFY_REG(TIMx->DIER, TIM_DIER_CC1DE | TIM_DIER_CC2DE, TIM_DIER_CC2DE); + } + break; + } + case 2: + case 3: { + MODIFY_REG(TIMx->CCER, TIM_CCER_CC3E | TIM_CCER_CC4E, 0); + // Select the Input and set the filter and the prescaler value + if (chan == 2) { // TI3 + MODIFY_REG(TIMx->CCMR2, + (TIM_CCMR2_CC3S | TIM_CCMR2_IC3F | TIM_CCMR2_IC3PSC), + (TIM_CCMR2_CC3S_0 | TIM_CCMR2_IC3F_1)); + MODIFY_REG(TIMx->CCMR2, + (TIM_CCMR2_CC4S | TIM_CCMR2_IC4F | TIM_CCMR2_IC4PSC), + (TIM_CCMR2_CC4S_1 | TIM_CCMR2_IC4F_1)); + } else { // TI4 + MODIFY_REG(TIMx->CCMR2, + (TIM_CCMR2_CC3S | TIM_CCMR2_IC3F | TIM_CCMR2_IC3PSC), + (TIM_CCMR2_CC3S_1 | TIM_CCMR2_IC3F_1)); + MODIFY_REG(TIMx->CCMR2, + (TIM_CCMR2_CC4S | TIM_CCMR2_IC4F | TIM_CCMR2_IC4PSC), + (TIM_CCMR2_CC4S_0 | TIM_CCMR2_IC4F_1)); + } + if (ccr_ch == 2) { + // Select the Polarity as falling on IC4 and rising on IC3 + MODIFY_REG(TIMx->CCER, TIM_CCER_CC3P | TIM_CCER_CC4P, TIM_CCER_CC4P | TIM_CCER_CC3E | TIM_CCER_CC4E); + MODIFY_REG(TIMx->DIER, TIM_DIER_CC3DE | TIM_DIER_CC4DE, TIM_DIER_CC3DE); + } else { + // Select the Polarity as falling on IC3 and rising on IC4 + MODIFY_REG(TIMx->CCER, TIM_CCER_CC3P | TIM_CCER_CC4P, TIM_CCER_CC3P | TIM_CCER_CC3E | TIM_CCER_CC4E); + MODIFY_REG(TIMx->DIER, TIM_DIER_CC3DE | TIM_DIER_CC4DE, TIM_DIER_CC4DE); + } + break; + + } + default: + break; + } +} + +#define INVALID_ERPM 0xfffU + +// decode a telemetry packet from a GCR encoded stride buffer, take from betaflight decodeTelemetryPacket +// see https://github.com/betaflight/betaflight/pull/8554#issuecomment-512507625 for a description of the protocol +uint32_t RCOutput::bdshot_decode_telemetry_packet_f1(dmar_uint_t* buffer, uint32_t count, bool reversed) +{ + if (!reversed) { + return bdshot_decode_telemetry_packet(buffer, count); + } + + uint32_t value = 0; + uint32_t bits = 0; + uint32_t len; + + // on F103 we are reading one edge with ICn and the other with ICn+1, the DMA architecture only + // allows to trigger on a single register dictated by the DMA input capture channel being used. + // even though we are reading multiple registers per transfer we always cannot trigger on one or other + // of the registers and if the one we trigger on is the one that is numerically first each register + // pair that we read will be swapped in time. in this case we trigger on ICn and then read CCRn and CCRn+1 + // giving us the new value of ICn and the old value of ICn+1. in order to avoid reading garbage on the + // first read we trigger ICn on the rising edge. this gives us all the data but with each pair of bytes + // transposed. we thus need to untranspose as we decode + dmar_uint_t oldValue = buffer[1]; + + for (int32_t i = 0; i <= count+1; ) { + if (i < count) { + dmar_int_t diff = buffer[i] - oldValue; + if (bits >= 21U) { + break; + } + len = (diff + TELEM_IC_SAMPLE/2U) / TELEM_IC_SAMPLE; + } else { + len = 21U - bits; + } + + value <<= len; + value |= 1U << (len - 1U); + oldValue = buffer[i]; + bits += len; + + i += (i%2 ? -1 : 3); + } + + + if (bits != 21U) { + return INVALID_ERPM; + } + + static const uint32_t decode[32] = { + 0, 0, 0, 0, 0, 0, 0, 0, 0, 9, 10, 11, 0, 13, 14, 15, + 0, 0, 2, 3, 0, 5, 6, 7, 0, 0, 8, 1, 0, 4, 12, 0 }; + + uint32_t decodedValue = decode[value & 0x1fU]; + decodedValue |= decode[(value >> 5U) & 0x1fU] << 4U; + decodedValue |= decode[(value >> 10U) & 0x1fU] << 8U; + decodedValue |= decode[(value >> 15U) & 0x1fU] << 12U; + + uint32_t csum = decodedValue; + csum = csum ^ (csum >> 8U); // xor bytes + csum = csum ^ (csum >> 4U); // xor nibbles + + if ((csum & 0xfU) != 0xfU) { + return INVALID_ERPM; + } + decodedValue >>= 4; + + return decodedValue; +} + +#endif // HAL_WITH_BIDIR_DSHOT && STM32F1 + #endif // HAL_USE_PWM #endif // IOMCU_FW && HAL_DSHOT_ENABLED diff --git a/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp b/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp index db368a9cbfbb1a..52c801e985f7c8 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp @@ -39,7 +39,7 @@ bool RCOutput::dshot_send_command(pwm_group& group, uint8_t command, uint8_t cha return false; } - if (soft_serial_waiting() || (group.dshot_state != DshotState::IDLE && group.dshot_state != DshotState::RECV_COMPLETE)) { + if (soft_serial_waiting() || !is_dshot_send_allowed(group.dshot_state)) { // doing serial output or DMAR input, don't send DShot pulses return false; } @@ -57,18 +57,8 @@ bool RCOutput::dshot_send_command(pwm_group& group, uint8_t command, uint8_t cha group.dshot_waiter = rcout_thread_ctx; bool bdshot_telem = false; #ifdef HAL_WITH_BIDIR_DSHOT - uint32_t active_channels = group.ch_mask & group.en_mask; - // no need to get the input capture lock - group.bdshot.enabled = false; - if ((_bdshot.mask & active_channels) == active_channels) { - bdshot_telem = true; - // it's not clear why this is required, but without it we get no output - if (group.pwm_started) { - pwmStop(group.pwm_drv); - } - pwmStart(group.pwm_drv, &group.pwm_cfg); - group.pwm_started = true; - } + bdshot_prepare_for_next_pulse(group); + bdshot_telem = group.bdshot.enabled; #endif memset((uint8_t *)group.dma_buffer, 0, DSHOT_BUFFER_LENGTH); @@ -121,7 +111,11 @@ void RCOutput::send_dshot_command(uint8_t command, uint8_t chan, uint32_t comman DshotCommandPacket pkt; pkt.command = command; - pkt.chan = chan - chan_offset; + if (chan != ALL_CHANNELS) { + pkt.chan = chan - chan_offset; + } else { + pkt.chan = ALL_CHANNELS; + } if (command_timeout_ms == 0) { pkt.cycle = MAX(10, repeat_count); } else { diff --git a/libraries/AP_HAL_ChibiOS/hwdef/iomcu-dshot/hwdef.inc b/libraries/AP_HAL_ChibiOS/hwdef/iomcu-dshot/hwdef.inc index 5f6404aa15dc71..b51e0b156d951a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/iomcu-dshot/hwdef.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/iomcu-dshot/hwdef.inc @@ -16,7 +16,7 @@ undef AP_HAL_SHARED_DMA_ENABLED define STM32_TIM_TIM2_UP_DMA_STREAM STM32_DMA_STREAM_ID(1, 2) define STM32_TIM_TIM2_UP_DMA_CHAN 1 -# TIM4_UP (PWM 3/4) cannot be used with sharing as channels used by high speed USART2 RX/TX +# TIM4_UP (PWM 3/4) cannot be used without sharing as channels used by high speed USART2 RX/TX define AP_HAL_SHARED_DMA_ENABLED 1 define STM32_TIM_TIM4_UP_DMA_STREAM STM32_DMA_STREAM_ID(1, 7) define STM32_TIM_TIM4_UP_DMA_CHAN 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/iomcu-f103-dshot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/iomcu-f103-dshot/hwdef.dat index 10f3b2a2f3f65c..9f885359fe2ddb 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/iomcu-f103-dshot/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/iomcu-f103-dshot/hwdef.dat @@ -12,3 +12,40 @@ DMA_NOMAP 1 # only four timers on F103xB so use TIM1 for system timer STM32_ST_USE_TIMER 1 + +define HAL_WITH_ESC_TELEM 1 + +undef PA0 PA1 PB8 PB9 + +# the order is important here as it determines the order that timers are used to sending dshot +# TIM4 needs to go first so that TIM4_UP can be freed up to be used by input capture for TIM2 +PB8 TIM4_CH3 TIM4 PWM(3) GPIO(103) BIDIR +PB9 TIM4_CH4 TIM4 PWM(4) GPIO(104) +PA0 TIM2_CH1 TIM2 PWM(1) GPIO(101) +PA1 TIM2_CH2 TIM2 PWM(2) GPIO(102) BIDIR # DMA channel 7, shared with TIM4_UP and USART2_TX + +# currently no support for having mixed outputs on the same timer +# PB1 TIM3_CH4 TIM3 PWM(8) GPIO(108) BIDIR # DMA channel 3, shared with TIM3_UP + +# TIM2_UP - (1,2) +# TIM4_UP - (1,7) +# TIM3_UP - (1,3) + +# TIM2_CH2 (PWM 1/2) +define STM32_TIM_TIM2_CH2_DMA_STREAM STM32_DMA_STREAM_ID(1, 7) +define STM32_TIM_TIM2_CH2_DMA_CHAN 1 + +# TIM4_CH3 (PWM 3/4) +define STM32_TIM_TIM4_CH3_DMA_STREAM STM32_DMA_STREAM_ID(1, 5) +define STM32_TIM_TIM4_CH3_DMA_CHAN 1 + +# TIM3_CH4 (PWM 7-8) +define STM32_TIM_TIM3_CH4_DMA_STREAM STM32_DMA_STREAM_ID(1, 3) +define STM32_TIM_TIM3_CH4_DMA_CHAN 1 + +define HAL_TIM4_UP_SHARED 1 +undef SHARED_DMA_MASK +define SHARED_DMA_MASK (1U< Date: Thu, 19 Oct 2023 17:19:37 +0100 Subject: [PATCH 0121/1335] AP_HAL_ChibiOS: utility to print out bdshot encoded data --- .../hwdef/scripts/bdshot_encoder.py | 113 ++++++++++++++++++ 1 file changed, 113 insertions(+) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/scripts/bdshot_encoder.py diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/bdshot_encoder.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/bdshot_encoder.py new file mode 100644 index 00000000000000..4c1877e8b2407b --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/bdshot_encoder.py @@ -0,0 +1,113 @@ +#!/usr/bin/env python + +""" +script to encode a telemetry value using dshot and gcr and then display in binary and ascii art +see https://github.com/betaflight/betaflight/pull/8554#issuecomment-512507625 +""" + +import argparse + +parser = argparse.ArgumentParser("bdshot_encoder.py") +parser.add_argument('value', help='Value to encode') + +args = parser.parse_args() + +def dshot_encode(value): + packet = (value << 1) + + # compute checksum + csum = 0 + csum_data = packet + for i in range(3): + csum ^= csum_data + csum_data >>= 4 + + csum = ~csum + csum &= 0xF + packet = (packet << 4) | csum + + return packet + +def rll_encode(value): + old_bit = 0 + rll_value = 0 + + for i in range(1, 21): + if value & 1: + new_bit = (1 ^ old_bit) + else: + new_bit = old_bit + value >>= 1 + rll_value |= new_bit << i + old_bit = new_bit + return rll_value + +def gcr_encode(value): + expo = 0 + + if value: + while value & 1 == 0: + value >>= 1 + expo = expo + 1 + + value = (value & 0x1FF) | (expo << 9) + value = dshot_encode(value) + + nibble_map = [0x19, 0x1b, 0x12, 0x13, 0x1d, 0x15, 0x16, 0x17, 0x1a, 0x09, 0x0a, 0x0b, 0x1e, 0x0d, 0x0e, 0x0f ] + + new_value = 0 + for i in range(4): + new_value |= (nibble_map[value & 0xF] << ((3-i) * 5)) + value >> 4 + + return rll_encode(new_value) + +def print_signal(value): + old_bit = 0 + print("_ ", sep='', end='') + for i in range(21): + bit = (value>>(20-i)) & 1 + if bit != old_bit: + print(' ', sep='', end='') + if bit: + print('_', sep='', end='') + else: + print(' ', sep='', end='') + old_bit = bit + print(" _", sep='', end='') + print('') + + print(" |", sep='', end='') + for i in range(21): + bit = (value>>(20-i)) & 1 + if bit != old_bit: + print('|', sep='', end='') + print(' ', sep='', end='') + old_bit = bit + print("| ", sep='', end='') + print('') + + print(" |", sep='', end='') + for i in range(21): + bit = (value>>(20-i)) & 1 + if bit != old_bit: + print('|', sep='', end='') + if bit == 0: + print("_", sep='', end='') + else: + print(' ', sep='', end='') + old_bit = bit + print("| ", sep='', end='') + print('') + +if args.value.startswith("0b"): + value = int(args.value[2:], 2) +elif args.value.startswith("0x"): + value = int(args.value[2:], 16) +else: + value = int(args.value) + +encoded_value = gcr_encode(value) +print("0b{:020b}".format(encoded_value)) +print_signal(encoded_value) + From 153c5181cb46f0e884396c65183f8477247ca105 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Mon, 23 Oct 2023 14:36:02 +0100 Subject: [PATCH 0122/1335] AP_IOMCU: reset erpm to zero on timeout remove unneeded packed attribute reset the PWM status after channels have been enabled or disabled --- libraries/AP_IOMCU/iofirmware/iofirmware.cpp | 11 ++++++++++- libraries/AP_IOMCU/iofirmware/iofirmware.h | 1 + libraries/AP_IOMCU/iofirmware/ioprotocol.h | 8 ++++---- 3 files changed, 15 insertions(+), 5 deletions(-) diff --git a/libraries/AP_IOMCU/iofirmware/iofirmware.cpp b/libraries/AP_IOMCU/iofirmware/iofirmware.cpp index 2ff7db713b5e4b..87e2054e10a27c 100644 --- a/libraries/AP_IOMCU/iofirmware/iofirmware.cpp +++ b/libraries/AP_IOMCU/iofirmware/iofirmware.cpp @@ -622,8 +622,13 @@ void AP_IOMCU_FW::rcin_update() #ifdef HAL_WITH_BIDIR_DSHOT void AP_IOMCU_FW::erpm_update() { + uint32_t now_us = AP_HAL::micros(); + if (hal.rcout->new_erpm()) { dshot_erpm.update_mask |= hal.rcout->read_erpm(dshot_erpm.erpm, IOMCU_MAX_CHANNELS); + last_erpm_us = now_us; + } else if (now_us - last_erpm_us > ESC_RPM_DATA_TIMEOUT_US) { + dshot_erpm.update_mask = 0; } } @@ -640,7 +645,7 @@ void AP_IOMCU_FW::telem_update() dshot_telem[i].error_rate[j] = uint16_t(roundf(hal.rcout->get_erpm_error_rate(esc_id) * 100.0)); #if HAL_WITH_ESC_TELEM const volatile AP_ESC_Telem_Backend::TelemetryData& telem = esc_telem.get_telem_data(esc_id); - // if data is stale the set to zero to avoidn phantom data appearing in mavlink + // if data is stale then set to zero to avoid phantom data appearing in mavlink if (now_ms - telem.last_update_ms > ESC_TELEM_DATA_TIMEOUT_MS) { dshot_telem[i].voltage_cvolts[j] = 0; dshot_telem[i].current_camps[j] = 0; @@ -1146,6 +1151,10 @@ void AP_IOMCU_FW::rcout_config_update(void) } } last_channel_mask = reg_setup.channel_mask; + // channel enablement will affect the reported output mode + uint32_t output_mask = 0; + reg_status.rcout_mode = hal.rcout->get_output_mode(output_mask); + reg_status.rcout_mask = uint8_t(0xFF & output_mask); } // see if there is anything to do, we only support setting the mode for a particular channel once diff --git a/libraries/AP_IOMCU/iofirmware/iofirmware.h b/libraries/AP_IOMCU/iofirmware/iofirmware.h index 16227f39f7e656..ebc4f1713824cd 100644 --- a/libraries/AP_IOMCU/iofirmware/iofirmware.h +++ b/libraries/AP_IOMCU/iofirmware/iofirmware.h @@ -140,6 +140,7 @@ class AP_IOMCU_FW { #endif #ifdef HAL_WITH_BIDIR_DSHOT struct page_dshot_erpm dshot_erpm; + uint32_t last_erpm_us; struct page_dshot_telem dshot_telem[IOMCU_MAX_CHANNELS/4]; uint32_t last_telem_ms; #if HAL_WITH_ESC_TELEM diff --git a/libraries/AP_IOMCU/iofirmware/ioprotocol.h b/libraries/AP_IOMCU/iofirmware/ioprotocol.h index 44c10d50542546..b79f562fb190d3 100644 --- a/libraries/AP_IOMCU/iofirmware/ioprotocol.h +++ b/libraries/AP_IOMCU/iofirmware/ioprotocol.h @@ -189,14 +189,14 @@ struct __attribute__((packed, aligned(2))) page_GPIO { uint8_t output_mask; }; -struct __attribute__((packed, aligned(2))) page_mode_out { +struct page_mode_out { uint16_t mask; uint16_t mode; uint16_t bdmask; uint16_t esc_type; }; -struct __attribute__((packed, aligned(2))) page_dshot { +struct page_dshot { uint16_t telem_mask; uint8_t command; uint8_t chan; @@ -205,13 +205,13 @@ struct __attribute__((packed, aligned(2))) page_dshot { uint8_t priority; }; -struct __attribute__((packed, aligned(2))) page_dshot_erpm { +struct page_dshot_erpm { uint16_t erpm[IOMCU_MAX_CHANNELS]; uint32_t update_mask; }; // separate telemetry packet because (a) it's too big otherwise and (b) slower update rate -struct __attribute__((packed, aligned(2))) page_dshot_telem { +struct page_dshot_telem { uint16_t error_rate[4]; // as a centi-percentage uint16_t voltage_cvolts[4]; uint16_t current_camps[4]; From 8c03c9e4bf81c48298da98f7e7b3fdaaacc1dfcf Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 19 Oct 2023 16:22:08 +0100 Subject: [PATCH 0123/1335] AP_HAL_ChibiOS: cache values of io_dshot() and io_enabled() enabled shared_up_dma to be fully compiled out address some minor review comments --- libraries/AP_HAL_ChibiOS/RCOutput.cpp | 54 ++++++++++--------- libraries/AP_HAL_ChibiOS/RCOutput.h | 13 +++++ libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp | 23 +++++--- .../AP_HAL_ChibiOS/RCOutput_iofirmware.cpp | 2 +- libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp | 2 +- .../hwdef/iomcu-f103-dshot/hwdef.dat | 3 +- .../hwdef/scripts/chibios_hwdef.py | 18 ++++++- .../hwdef/scripts/defaults_iofirmware.h | 13 +++++ 8 files changed, 90 insertions(+), 38 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.cpp b/libraries/AP_HAL_ChibiOS/RCOutput.cpp index e0539b01dd2f9d..d8c5a218a20030 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput.cpp @@ -100,6 +100,10 @@ void RCOutput::init() if (AP_BoardConfig::io_enabled()) { // with IOMCU the local (FMU) channels start at 8 chan_offset = 8; + iomcu_enabled = true; + } + if (AP_BoardConfig::io_dshot()) { + iomcu_dshot = true; } #endif @@ -144,7 +148,7 @@ void RCOutput::init() } #if HAL_WITH_IO_MCU - if (AP_BoardConfig::io_enabled()) { + if (iomcu_enabled) { iomcu.init(); } #endif @@ -442,7 +446,7 @@ void RCOutput::set_freq_group(pwm_group &group) void RCOutput::set_freq(uint32_t chmask, uint16_t freq_hz) { #if HAL_WITH_IO_MCU - if (AP_BoardConfig::io_enabled()) { + if (iomcu_enabled) { // change frequency on IOMCU uint16_t io_chmask = chmask & 0xFF; if (io_chmask) { @@ -499,7 +503,7 @@ void RCOutput::set_freq(uint32_t chmask, uint16_t freq_hz) void RCOutput::set_default_rate(uint16_t freq_hz) { #if HAL_WITH_IO_MCU - if (AP_BoardConfig::io_enabled()) { + if (iomcu_enabled) { iomcu.set_default_rate(freq_hz); } #endif @@ -526,7 +530,7 @@ void RCOutput::set_dshot_rate(uint8_t dshot_rate, uint16_t loop_rate_hz) _dshot_period_us = 1000UL; _dshot_rate = 0; #if HAL_WITH_IO_MCU - if (AP_BoardConfig::io_dshot()) { + if (iomcu_dshot) { iomcu.set_dshot_period(1000UL, 0); } #endif @@ -542,7 +546,7 @@ void RCOutput::set_dshot_rate(uint8_t dshot_rate, uint16_t loop_rate_hz) #if HAL_WITH_IO_MCU // this is not strictly neccessary since the iomcu could run at a different rate, // but there is only one parameter to control this - if (AP_BoardConfig::io_dshot()) { + if (iomcu_dshot) { iomcu.set_dshot_period(1000UL, 0); } #endif @@ -566,7 +570,7 @@ void RCOutput::set_dshot_rate(uint8_t dshot_rate, uint16_t loop_rate_hz) } _dshot_period_us = 1000000UL / drate; #if HAL_WITH_IO_MCU - if (AP_BoardConfig::io_dshot()) { + if (iomcu_dshot) { iomcu.set_dshot_period(_dshot_period_us, _dshot_rate); } #endif @@ -593,7 +597,7 @@ void RCOutput::set_dshot_esc_type(DshotEscType dshot_esc_type) break; } #if HAL_WITH_IO_MCU - if (AP_BoardConfig::io_dshot()) { + if (iomcu_dshot) { iomcu.set_dshot_esc_type(dshot_esc_type); } #endif @@ -670,7 +674,7 @@ uint16_t RCOutput::get_freq(uint8_t chan) void RCOutput::enable_ch(uint8_t chan) { #if HAL_WITH_IO_MCU - if (chan < chan_offset && AP_BoardConfig::io_enabled()) { + if (chan < chan_offset && iomcu_enabled) { iomcu.enable_ch(chan); return; } @@ -686,7 +690,7 @@ void RCOutput::enable_ch(uint8_t chan) void RCOutput::disable_ch(uint8_t chan) { #if HAL_WITH_IO_MCU - if (chan < chan_offset && AP_BoardConfig::io_enabled()) { + if (chan < chan_offset && iomcu_enabled) { iomcu.disable_ch(chan); return; } @@ -717,7 +721,7 @@ void RCOutput::write(uint8_t chan, uint16_t period_us) #if HAL_WITH_IO_MCU // handle IO MCU channels - if (AP_BoardConfig::io_enabled()) { + if (iomcu_enabled) { iomcu.write_channel(chan, period_us); } #endif @@ -1198,7 +1202,7 @@ void RCOutput::set_output_mode(uint32_t mask, const enum output_mode mode) mode == MODE_PWM_BRUSHED || (mode >= MODE_PWM_DSHOT150 && mode <= MODE_PWM_DSHOT600)) && iomcu_mask && - AP_BoardConfig::io_enabled()) { + iomcu_enabled) { iomcu.set_output_mode(iomcu_mask, mode); return; } @@ -1234,7 +1238,7 @@ RCOutput::output_mode RCOutput::get_output_mode(uint32_t& mask) void RCOutput::set_telem_request_mask(uint32_t mask) { #if HAL_WITH_IO_MCU - if (AP_BoardConfig::io_dshot() && (mask & ((1U<is_shared()) { @@ -1516,9 +1520,9 @@ void RCOutput::dma_allocate(Shared_DMA *ctx) dmaSetRequestSource(group.dma, group.dma_up_channel); } #endif + chSysUnlock(); } } - chSysUnlock(); } /* @@ -1526,9 +1530,9 @@ void RCOutput::dma_allocate(Shared_DMA *ctx) */ void RCOutput::dma_deallocate(Shared_DMA *ctx) { - chSysLock(); for (auto &group : pwm_group_list) { if (group.dma_handle == ctx && group.dma != nullptr) { + chSysLock(); #if defined(STM32F1) // leaving the peripheral running on IOMCU plays havoc with the UART that is // also sharing this channel, we only turn it off rather than resetting so @@ -1540,9 +1544,9 @@ void RCOutput::dma_deallocate(Shared_DMA *ctx) #endif dmaStreamFreeI(group.dma); group.dma = nullptr; + chSysUnlock(); } } - chSysUnlock(); } #endif // AP_HAL_SHARED_DMA_ENABLED @@ -2229,7 +2233,7 @@ void RCOutput::serial_end(void) AP_HAL::Util::safety_state RCOutput::_safety_switch_state(void) { #if HAL_WITH_IO_MCU - if (AP_BoardConfig::io_enabled()) { + if (iomcu_enabled) { safety_state = iomcu.get_safety_switch_state(); } #endif @@ -2245,7 +2249,7 @@ AP_HAL::Util::safety_state RCOutput::_safety_switch_state(void) bool RCOutput::force_safety_on(void) { #if HAL_WITH_IO_MCU - if (AP_BoardConfig::io_enabled()) { + if (iomcu_enabled) { return iomcu.force_safety_on(); } #endif @@ -2259,7 +2263,7 @@ bool RCOutput::force_safety_on(void) void RCOutput::force_safety_off(void) { #if HAL_WITH_IO_MCU - if (AP_BoardConfig::io_enabled()) { + if (iomcu_enabled) { iomcu.force_safety_off(); return; } @@ -2327,7 +2331,7 @@ void RCOutput::safety_update(void) void RCOutput::set_failsafe_pwm(uint32_t chmask, uint16_t period_us) { #if HAL_WITH_IO_MCU - if (AP_BoardConfig::io_enabled()) { + if (iomcu_enabled) { iomcu.set_failsafe_pwm(chmask, period_us); } #endif diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.h b/libraries/AP_HAL_ChibiOS/RCOutput.h index d6c6c6a343d2f2..0b0a41b8115124 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.h +++ b/libraries/AP_HAL_ChibiOS/RCOutput.h @@ -331,7 +331,9 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput uint8_t stream_id; uint8_t channel; } dma_ch[4]; +#ifdef HAL_TIM_UP_SHARED bool shared_up_dma; // do we need to wait for TIMx_UP DMA to be finished after use +#endif #endif uint8_t alt_functions[4]; ioline_t pal_lines[4]; @@ -517,6 +519,13 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput static pwm_group pwm_group_list[]; static const uint8_t NUM_GROUPS; +#if HAL_WITH_IO_MCU + // cached values of AP_BoardConfig::io_enabled() and AP_BoardConfig::io_dshot() + // in case the user changes them + bool iomcu_enabled; + bool iomcu_dshot; +#endif + // offset of first local channel uint8_t chan_offset; @@ -668,7 +677,11 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput void fill_DMA_buffer_dshot(dmar_uint_t *buffer, uint8_t stride, uint16_t packet, uint16_t clockmul); // event to allow dshot cascading +#if defined(HAL_TIM_UP_SHARED) static const eventmask_t DSHOT_CASCADE = EVENT_MASK(16); +#else + static const eventmask_t DSHOT_CASCADE = 0; +#endif static const eventmask_t EVT_PWM_SEND = EVENT_MASK(11); static const eventmask_t EVT_PWM_SYNTHETIC_SEND = EVENT_MASK(13); diff --git a/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp b/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp index 8817e0217e646e..43664570eb11c5 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp @@ -54,7 +54,7 @@ void RCOutput::set_bidir_dshot_mask(uint32_t mask) { #if HAL_WITH_IO_MCU const uint32_t iomcu_mask = ((1U<is_locked(), "IC DMA handle is already locked"); +#else + osalDbgAssert(!group.bdshot.curr_ic_dma_handle->is_locked(), "IC DMA handle is already locked"); +#endif group.bdshot.curr_ic_dma_handle->lock(); group.bdshot.enabled = true; } @@ -461,7 +465,7 @@ void RCOutput::bdshot_config_icu_dshot(stm32_tim_t* TIMx, uint8_t chan, uint8_t break; } } -#endif +#endif // !defined(STM32F1) /* unlock DMA channel after a bi-directional dshot transaction completes @@ -488,13 +492,14 @@ __RAMFUNC__ void RCOutput::bdshot_finish_dshot_gcr_transaction(virtual_timer_t* stm32_cacheBufferInvalidate(group->dma_buffer, group->bdshot.dma_tx_size); memcpy(group->bdshot.dma_buffer_copy, group->dma_buffer, sizeof(dmar_uint_t) * group->bdshot.dma_tx_size); +#ifdef HAL_TIM_UP_SHARED // although it should be possible to start the next DMAR transaction concurrently with receiving // telemetry, in practice it seems to interfere with the DMA engine if (group->shared_up_dma && group->bdshot.enabled) { // next dshot pulse can go out now chEvtSignalI(group->dshot_waiter, DSHOT_CASCADE); } - +#endif // if using input capture DMA and sharing the UP and CH channels then clean up // by assigning the source back to UP #if STM32_DMA_SUPPORTS_DMAMUX @@ -508,6 +513,8 @@ __RAMFUNC__ void RCOutput::bdshot_finish_dshot_gcr_transaction(virtual_timer_t* // we will not get data from active channels group->bdshot.curr_telem_chan = bdshot_find_next_ic_channel(*group); + // dshot commands are issued without a response coming back, this allows + // us to handle the next packet correctly without it looking like a failure if (group->bdshot.dma_tx_size > 0) { group->dshot_state = DshotState::RECV_COMPLETE; } else { @@ -738,7 +745,7 @@ bool RCOutput::bdshot_decode_telemetry_from_erpm(uint16_t encodederpm, uint8_t c uint8_t normalized_chan = chan; #endif #if HAL_WITH_IO_MCU - if (AP_BoardConfig::io_dshot()) { + if (iomcu_dshot) { normalized_chan = chan + chan_offset; } #endif diff --git a/libraries/AP_HAL_ChibiOS/RCOutput_iofirmware.cpp b/libraries/AP_HAL_ChibiOS/RCOutput_iofirmware.cpp index e45ce3c363511f..994485e4e91e15 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput_iofirmware.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput_iofirmware.cpp @@ -68,7 +68,7 @@ void RCOutput::dshot_send_trampoline(void *p) */ void RCOutput::rcout_thread() { // don't start outputting until fully configured - while (!hal.scheduler->is_system_initialized() || _dshot_period_us == 0) { + while (!hal.scheduler->is_system_initialized()) { hal.scheduler->delay_microseconds(1000); } diff --git a/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp b/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp index 52c801e985f7c8..c8ca5156fb7ce2 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp @@ -100,7 +100,7 @@ void RCOutput::send_dshot_command(uint8_t command, uint8_t chan, uint32_t comman // not an FMU channel if (chan < chan_offset || chan == ALL_CHANNELS) { #if HAL_WITH_IO_MCU - if (AP_BoardConfig::io_dshot()) { + if (iomcu_dshot) { iomcu.send_dshot_command(command, chan, command_timeout_ms, repeat_count, priority); } #endif diff --git a/libraries/AP_HAL_ChibiOS/hwdef/iomcu-f103-dshot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/iomcu-f103-dshot/hwdef.dat index 9f885359fe2ddb..10b71b35a9a0ad 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/iomcu-f103-dshot/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/iomcu-f103-dshot/hwdef.dat @@ -19,7 +19,7 @@ undef PA0 PA1 PB8 PB9 # the order is important here as it determines the order that timers are used to sending dshot # TIM4 needs to go first so that TIM4_UP can be freed up to be used by input capture for TIM2 -PB8 TIM4_CH3 TIM4 PWM(3) GPIO(103) BIDIR +PB8 TIM4_CH3 TIM4 PWM(3) GPIO(103) BIDIR UP_SHARED PB9 TIM4_CH4 TIM4 PWM(4) GPIO(104) PA0 TIM2_CH1 TIM2 PWM(1) GPIO(101) PA1 TIM2_CH2 TIM2 PWM(2) GPIO(102) BIDIR # DMA channel 7, shared with TIM4_UP and USART2_TX @@ -43,7 +43,6 @@ define STM32_TIM_TIM4_CH3_DMA_CHAN 1 define STM32_TIM_TIM3_CH4_DMA_STREAM STM32_DMA_STREAM_ID(1, 3) define STM32_TIM_TIM3_CH4_DMA_CHAN 1 -define HAL_TIM4_UP_SHARED 1 undef SHARED_DMA_MASK define SHARED_DMA_MASK (1U< Date: Mon, 13 Nov 2023 19:58:36 +0000 Subject: [PATCH 0124/1335] AP_IOMCU: constrain PWM channels to 8, telem channels to 4 and RC channels to 16 make ADC readings interrupt driven turn off iomcu updates when debugging allow for correct number of telemetry channels cycle between vservo and vrssi when reading adc build adc with O2 --- libraries/AP_IOMCU/AP_IOMCU.cpp | 18 +++++++++--------- libraries/AP_IOMCU/AP_IOMCU.h | 2 +- libraries/AP_IOMCU/iofirmware/iofirmware.cpp | 20 ++++++++------------ libraries/AP_IOMCU/iofirmware/iofirmware.h | 2 +- libraries/AP_IOMCU/iofirmware/ioprotocol.h | 9 ++++++--- 5 files changed, 25 insertions(+), 26 deletions(-) diff --git a/libraries/AP_IOMCU/AP_IOMCU.cpp b/libraries/AP_IOMCU/AP_IOMCU.cpp index 2cf81c9165d599..b996aefbe4cba2 100644 --- a/libraries/AP_IOMCU/AP_IOMCU.cpp +++ b/libraries/AP_IOMCU/AP_IOMCU.cpp @@ -78,12 +78,16 @@ void AP_IOMCU::init(void) uart.begin(1500*1000, 128, 128); uart.set_unbuffered_writes(true); +#if IOMCU_DEBUG_ENABLE + crc_is_ok = true; +#else AP_BoardConfig *boardconfig = AP_BoardConfig::get_singleton(); if ((!boardconfig || boardconfig->io_enabled() == 1) && !hal.util->was_watchdog_reset()) { check_crc(); } else { crc_is_ok = true; } +#endif if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_IOMCU::thread_main, void), "IOMCU", 1024, AP_HAL::Scheduler::PRIORITY_BOOST, 1)) { @@ -407,7 +411,7 @@ void AP_IOMCU::read_erpm() if (blh) { motor_poles = blh->get_motor_poles(); } - for (uint8_t i = 0; i < IOMCU_MAX_CHANNELS/4; i++) { + for (uint8_t i = 0; i < IOMCU_MAX_TELEM_CHANNELS/4; i++) { for (uint8_t j = 0; j < 4; j++) { const uint8_t esc_id = (i * 4 + j); if (dshot_erpm.update_mask & 1U< 4 case 1: page = PAGE_RAW_DSHOT_TELEM_5_8; break; - case 2: - page = PAGE_RAW_DSHOT_TELEM_9_12; - break; - case 3: - page = PAGE_RAW_DSHOT_TELEM_13_16; - break; +#endif default: break; } @@ -450,7 +450,7 @@ void AP_IOMCU::read_telem() }; update_telem_data(esc_group * 4 + i, t, telem->types[i]); } - esc_group = (esc_group + 1) % 4; + esc_group = (esc_group + 1) % (IOMCU_MAX_TELEM_CHANNELS / 4); } /* @@ -874,7 +874,7 @@ bool AP_IOMCU::enable_sbus_out(uint16_t rate_hz) bool AP_IOMCU::check_rcinput(uint32_t &last_frame_us, uint8_t &num_channels, uint16_t *channels, uint8_t max_chan) { if (last_frame_us != uint32_t(rc_last_input_ms * 1000U)) { - num_channels = MIN(MIN(rc_input.count, IOMCU_MAX_CHANNELS), max_chan); + num_channels = MIN(MIN(rc_input.count, IOMCU_MAX_RC_CHANNELS), max_chan); memcpy(channels, rc_input.pwm, num_channels*2); last_frame_us = uint32_t(rc_last_input_ms * 1000U); return true; diff --git a/libraries/AP_IOMCU/AP_IOMCU.h b/libraries/AP_IOMCU/AP_IOMCU.h index 041c565f48f193..1c976d2d7399b7 100644 --- a/libraries/AP_IOMCU/AP_IOMCU.h +++ b/libraries/AP_IOMCU/AP_IOMCU.h @@ -273,7 +273,7 @@ class AP_IOMCU // bi-directional dshot erpm values struct page_dshot_erpm dshot_erpm; - struct page_dshot_telem dshot_telem[IOMCU_MAX_CHANNELS/4]; + struct page_dshot_telem dshot_telem[IOMCU_MAX_TELEM_CHANNELS/4]; uint8_t esc_group; // queue of dshot commands that need sending diff --git a/libraries/AP_IOMCU/iofirmware/iofirmware.cpp b/libraries/AP_IOMCU/iofirmware/iofirmware.cpp index 87e2054e10a27c..76b9c11b41af88 100644 --- a/libraries/AP_IOMCU/iofirmware/iofirmware.cpp +++ b/libraries/AP_IOMCU/iofirmware/iofirmware.cpp @@ -468,7 +468,7 @@ void AP_IOMCU_FW::update() now - sbus_last_ms >= sbus_interval_ms) { // output a new SBUS frame sbus_last_ms = now; - sbus_out_write(reg_servo.pwm, IOMCU_MAX_CHANNELS); + sbus_out_write(reg_servo.pwm, IOMCU_MAX_RC_CHANNELS); } // handle FMU failsafe if (now - fmu_data_received_time > 200) { @@ -583,7 +583,7 @@ void AP_IOMCU_FW::rcin_update() const auto &rc = AP::RC(); rc_input.count = hal.rcin->num_channels(); rc_input.flags_rc_ok = true; - hal.rcin->read(rc_input.pwm, IOMCU_MAX_CHANNELS); + hal.rcin->read(rc_input.pwm, IOMCU_MAX_RC_CHANNELS); rc_last_input_ms = last_ms; rc_input.rc_protocol = (uint16_t)rc.protocol_detected(); rc_input.rssi = rc.get_RSSI(); @@ -606,7 +606,7 @@ void AP_IOMCU_FW::rcin_update() if (mixing.enabled && mixing.rc_chan_override > 0 && rc_input.flags_rc_ok && - mixing.rc_chan_override <= IOMCU_MAX_CHANNELS) { + mixing.rc_chan_override <= IOMCU_MAX_RC_CHANNELS) { override_active = (rc_input.pwm[mixing.rc_chan_override-1] >= 1750); } else { override_active = false; @@ -625,7 +625,7 @@ void AP_IOMCU_FW::erpm_update() uint32_t now_us = AP_HAL::micros(); if (hal.rcout->new_erpm()) { - dshot_erpm.update_mask |= hal.rcout->read_erpm(dshot_erpm.erpm, IOMCU_MAX_CHANNELS); + dshot_erpm.update_mask |= hal.rcout->read_erpm(dshot_erpm.erpm, IOMCU_MAX_TELEM_CHANNELS); last_erpm_us = now_us; } else if (now_us - last_erpm_us > ESC_RPM_DATA_TIMEOUT_US) { dshot_erpm.update_mask = 0; @@ -636,10 +636,10 @@ void AP_IOMCU_FW::telem_update() { uint32_t now_ms = AP_HAL::millis(); - for (uint8_t i = 0; i < IOMCU_MAX_CHANNELS/4; i++) { + for (uint8_t i = 0; i < IOMCU_MAX_TELEM_CHANNELS/4; i++) { for (uint8_t j = 0; j < 4; j++) { const uint8_t esc_id = (i * 4 + j); - if (esc_id >= IOMCU_MAX_CHANNELS) { + if (esc_id >= IOMCU_MAX_TELEM_CHANNELS) { continue; } dshot_telem[i].error_rate[j] = uint16_t(roundf(hal.rcout->get_erpm_error_rate(esc_id) * 100.0)); @@ -767,15 +767,11 @@ bool AP_IOMCU_FW::handle_code_read() case PAGE_RAW_DSHOT_TELEM_1_4: COPY_PAGE(dshot_telem[0]); break; +#if IOMCU_MAX_TELEM_CHANNELS > 4 case PAGE_RAW_DSHOT_TELEM_5_8: COPY_PAGE(dshot_telem[1]); break; - case PAGE_RAW_DSHOT_TELEM_9_12: - COPY_PAGE(dshot_telem[2]); - break; - case PAGE_RAW_DSHOT_TELEM_13_16: - COPY_PAGE(dshot_telem[3]); - break; +#endif #endif case PAGE_STATUS: COPY_PAGE(reg_status); diff --git a/libraries/AP_IOMCU/iofirmware/iofirmware.h b/libraries/AP_IOMCU/iofirmware/iofirmware.h index ebc4f1713824cd..824a2238e4220c 100644 --- a/libraries/AP_IOMCU/iofirmware/iofirmware.h +++ b/libraries/AP_IOMCU/iofirmware/iofirmware.h @@ -141,7 +141,7 @@ class AP_IOMCU_FW { #ifdef HAL_WITH_BIDIR_DSHOT struct page_dshot_erpm dshot_erpm; uint32_t last_erpm_us; - struct page_dshot_telem dshot_telem[IOMCU_MAX_CHANNELS/4]; + struct page_dshot_telem dshot_telem[IOMCU_MAX_TELEM_CHANNELS/4]; uint32_t last_telem_ms; #if HAL_WITH_ESC_TELEM AP_ESC_Telem esc_telem; diff --git a/libraries/AP_IOMCU/iofirmware/ioprotocol.h b/libraries/AP_IOMCU/iofirmware/ioprotocol.h index b79f562fb190d3..01a29b15ff5f28 100644 --- a/libraries/AP_IOMCU/iofirmware/ioprotocol.h +++ b/libraries/AP_IOMCU/iofirmware/ioprotocol.h @@ -9,7 +9,9 @@ // 22 is enough for the rc_input page in one transfer #define PKT_MAX_REGS 22 -#define IOMCU_MAX_CHANNELS 16 +#define IOMCU_MAX_RC_CHANNELS 16 +#define IOMCU_MAX_CHANNELS 8 +#define IOMCU_MAX_TELEM_CHANNELS 4 //#define IOMCU_DEBUG @@ -136,6 +138,7 @@ struct page_reg_status { uint8_t err_write; uint8_t err_uart; uint8_t err_lock; + uint8_t spare; }; struct page_rc_input { @@ -143,7 +146,7 @@ struct page_rc_input { uint8_t flags_failsafe:1; uint8_t flags_rc_ok:1; uint8_t rc_protocol; - uint16_t pwm[IOMCU_MAX_CHANNELS]; + uint16_t pwm[IOMCU_MAX_RC_CHANNELS]; int16_t rssi; }; @@ -206,7 +209,7 @@ struct page_dshot { }; struct page_dshot_erpm { - uint16_t erpm[IOMCU_MAX_CHANNELS]; + uint16_t erpm[IOMCU_MAX_TELEM_CHANNELS]; uint32_t update_mask; }; From 2415c2998b278c6aa27ebe6f681880843ccf3a12 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 16 Nov 2023 16:27:16 +0000 Subject: [PATCH 0125/1335] AP_HAL_ChibiOS: allow dshot to be used even if bdshot was specified. correct zero handling in bdshot decoding --- libraries/AP_HAL_ChibiOS/RCOutput.cpp | 12 +++++---- libraries/AP_HAL_ChibiOS/RCOutput.h | 5 +++- libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp | 26 ++++++++++++------- .../AP_HAL_ChibiOS/RCOutput_iofirmware.cpp | 2 -- 4 files changed, 28 insertions(+), 17 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.cpp b/libraries/AP_HAL_ChibiOS/RCOutput.cpp index d8c5a218a20030..1817c3e6813eb9 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput.cpp @@ -16,6 +16,7 @@ * Bi-directional dshot based on Betaflight, code by Andy Piper and Siddharth Bharat Purohit * * There really is no dshot reference. For information try these resources: + * https://brushlesswhoop.com/dshot-and-bidirectional-dshot/ * https://blck.mn/2016/11/dshot-the-new-kid-on-the-block/ * https://www.swallenhardware.io/battlebots/2019/4/20/a-developers-guide-to-dshot-escs */ @@ -981,10 +982,11 @@ bool RCOutput::setup_group_DMA(pwm_group &group, uint32_t bitrate, uint32_t bit_ #ifdef HAL_WITH_BIDIR_DSHOT // configure input capture DMA if required - if (is_bidir_dshot_enabled()) { + if (is_bidir_dshot_enabled(group)) { if (!bdshot_setup_group_ic_DMA(group)) { - group.dma_handle->unlock(); - return false; + _bdshot.mask &= ~group.ch_mask; // only use dshot on this group + _bdshot.disabled_mask |= group.ch_mask; + active_high = true; } } #endif @@ -1115,7 +1117,7 @@ void RCOutput::set_group_mode(pwm_group &group) case MODE_PWM_DSHOT150 ... MODE_PWM_DSHOT1200: { #if HAL_DSHOT_ENABLED const uint32_t rate = protocol_bitrate(group.current_mode); - bool active_high = is_bidir_dshot_enabled() ? false : true; + bool active_high = is_bidir_dshot_enabled(group) ? false : true; bool at_least_freq = false; // calculate min time between pulses const uint32_t pulse_send_time_us = 1000000UL * dshot_bit_length / rate; @@ -1131,7 +1133,7 @@ void RCOutput::set_group_mode(pwm_group &group) group.current_mode = MODE_PWM_NORMAL; break; } - if (is_bidir_dshot_enabled()) { + if (is_bidir_dshot_enabled(group)) { group.dshot_pulse_send_time_us = pulse_send_time_us; // to all intents and purposes the pulse time of send and receive are the same group.dshot_pulse_time_us = pulse_send_time_us + pulse_send_time_us + 30; diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.h b/libraries/AP_HAL_ChibiOS/RCOutput.h index 0b0a41b8115124..037e656984d9f9 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.h +++ b/libraries/AP_HAL_ChibiOS/RCOutput.h @@ -314,6 +314,8 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput // input capture is expecting TELEM_IC_SAMPLE (16) ticks per transition (22) so the maximum // value of the counter in CCR registers is 16*22 == 352, so must be 16-bit static const uint16_t GCR_TELEMETRY_BUFFER_LEN = GCR_TELEMETRY_BIT_LEN*sizeof(dmar_uint_t); + static const uint16_t INVALID_ERPM = 0xffffU; + static const uint16_t ZERO_ERPM = 0x0fffU; struct pwm_group { // only advanced timers can do high clocks needed for more than 400Hz @@ -551,6 +553,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput // handling of bi-directional dshot struct { uint32_t mask; + uint32_t disabled_mask; // record of channels that were tried, but failed uint16_t erpm[max_channels]; volatile uint32_t update_mask; #ifdef HAL_WITH_BIDIR_DSHOT @@ -619,7 +622,7 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput volatile bool _initialised; - bool is_bidir_dshot_enabled() const { return _bdshot.mask != 0; } + bool is_bidir_dshot_enabled(const pwm_group& group) const { return (_bdshot.mask & group.ch_mask) != 0; } static bool is_dshot_send_allowed(DshotState state) { return state == DshotState::IDLE || state == DshotState::RECV_COMPLETE || state == DshotState::RECV_FAILED; diff --git a/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp b/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp index 43664570eb11c5..31a7d7f4c6cb65 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp @@ -58,11 +58,12 @@ void RCOutput::set_bidir_dshot_mask(uint32_t mask) iomcu.set_bidir_dshot_mask(mask & iomcu_mask); } #endif - _bdshot.mask = (mask >> chan_offset); + const uint32_t local_mask = (mask >> chan_offset) & ~_bdshot.disabled_mask; + _bdshot.mask = local_mask; // we now need to reconfigure the DMA channels since they are affected by the value of the mask for (uint8_t i = 0; i < NUM_GROUPS; i++ ) { pwm_group &group = pwm_group_list[i]; - if (((group.ch_mask << chan_offset) & mask) == 0) { + if ((group.ch_mask & local_mask) == 0) { // this group is not affected continue; } @@ -101,7 +102,7 @@ bool RCOutput::bdshot_setup_group_ic_DMA(pwm_group &group) FUNCTOR_BIND_MEMBER(&RCOutput::bdshot_ic_dma_deallocate, void, Shared_DMA *)); } if (!group.bdshot.ic_dma_handle[i]) { - return false; + goto ic_dma_fail; } } } @@ -149,11 +150,11 @@ bool RCOutput::bdshot_setup_group_ic_DMA(pwm_group &group) if (!group.dma_ch[curr_chan].have_dma) { // We can't find a DMA channel to use so // return error - return false; + goto ic_dma_fail; } if (group.bdshot.ic_dma_handle[i]) { INTERNAL_ERROR(AP_InternalError::error_t::dma_fail); - return false; + goto ic_dma_fail; } // share up channel if required if (group.dma_ch[curr_chan].stream_id == group.dma_up_stream_id) { @@ -165,7 +166,7 @@ bool RCOutput::bdshot_setup_group_ic_DMA(pwm_group &group) FUNCTOR_BIND_MEMBER(&RCOutput::bdshot_ic_dma_deallocate, void, Shared_DMA *)); } if (!group.bdshot.ic_dma_handle[i]) { - return false; + goto ic_dma_fail; } group.bdshot.telem_tim_ch[i] = curr_chan; group.dma_ch[i] = group.dma_ch[curr_chan]; @@ -181,6 +182,15 @@ bool RCOutput::bdshot_setup_group_ic_DMA(pwm_group &group) } return true; + +ic_dma_fail: + for (uint8_t i = 0; i < 4; i++) { + if (group.bdshot.ic_dma_handle[i] != group.dma_handle) { + delete group.bdshot.ic_dma_handle[i]; + } + group.bdshot.ic_dma_handle[i] = nullptr; + } + return false; } /* @@ -676,8 +686,6 @@ uint32_t RCOutput::bdshot_get_output_rate_hz(const enum output_mode mode) } } -#define INVALID_ERPM 0xfffU - // decode a telemetry packet from a GCR encoded stride buffer, take from betaflight decodeTelemetryPacket // see https://github.com/betaflight/betaflight/pull/8554#issuecomment-512507625 for a description of the protocol uint32_t RCOutput::bdshot_decode_telemetry_packet(dmar_uint_t* buffer, uint32_t count) @@ -801,7 +809,7 @@ bool RCOutput::bdshot_decode_telemetry_from_erpm(uint16_t encodederpm, uint8_t c erpm = (1000000U * 60U / 100U + erpm / 2U) / erpm; - if (encodederpm == 0x0fff) { // the special 0 encoding + if (encodederpm == ZERO_ERPM) { // the special 0 encoding erpm = 0; } diff --git a/libraries/AP_HAL_ChibiOS/RCOutput_iofirmware.cpp b/libraries/AP_HAL_ChibiOS/RCOutput_iofirmware.cpp index 994485e4e91e15..c8d535dc5b4559 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput_iofirmware.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput_iofirmware.cpp @@ -353,8 +353,6 @@ void RCOutput::bdshot_config_icu_dshot_f1(stm32_tim_t* TIMx, uint8_t chan, uint8 } } -#define INVALID_ERPM 0xfffU - // decode a telemetry packet from a GCR encoded stride buffer, take from betaflight decodeTelemetryPacket // see https://github.com/betaflight/betaflight/pull/8554#issuecomment-512507625 for a description of the protocol uint32_t RCOutput::bdshot_decode_telemetry_packet_f1(dmar_uint_t* buffer, uint32_t count, bool reversed) From a8772ef5a2af47f2c89693809b2caad1d7b68da8 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 16 Nov 2023 17:44:00 +0000 Subject: [PATCH 0126/1335] AP_HAL: allow bdshot iomcu on non-bdshot fmu --- libraries/AP_HAL/AP_HAL_Boards.h | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL/AP_HAL_Boards.h b/libraries/AP_HAL/AP_HAL_Boards.h index a6ef45740f161b..4831aeaf91840c 100644 --- a/libraries/AP_HAL/AP_HAL_Boards.h +++ b/libraries/AP_HAL/AP_HAL_Boards.h @@ -170,8 +170,12 @@ #define HAL_WITH_IO_MCU 0 #endif +#ifndef HAL_WITH_IO_MCU_BIDIR_DSHOT +#define HAL_WITH_IO_MCU_BIDIR_DSHOT 0 +#endif + #ifndef HAL_WITH_IO_MCU_DSHOT -#define HAL_WITH_IO_MCU_DSHOT 0 +#define HAL_WITH_IO_MCU_DSHOT HAL_WITH_IO_MCU_BIDIR_DSHOT #endif // this is used as a general mechanism to make a 'small' build by From 6dec0c2da5d98934a28c66327bb3e438d826dcf3 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 16 Nov 2023 17:44:41 +0000 Subject: [PATCH 0127/1335] AP_BLHeli: allow bdshot iomcu on non-bdshot fmu --- libraries/AP_BLHeli/AP_BLHeli.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/libraries/AP_BLHeli/AP_BLHeli.cpp b/libraries/AP_BLHeli/AP_BLHeli.cpp index 66577622a7cd40..6d944f221bef88 100644 --- a/libraries/AP_BLHeli/AP_BLHeli.cpp +++ b/libraries/AP_BLHeli/AP_BLHeli.cpp @@ -134,7 +134,7 @@ const AP_Param::GroupInfo AP_BLHeli::var_info[] = { // @RebootRequired: True AP_GROUPINFO("3DMASK", 10, AP_BLHeli, channel_reversible_mask, 0), -#ifdef HAL_WITH_BIDIR_DSHOT +#if defined(HAL_WITH_BIDIR_DSHOT) || HAL_WITH_IO_MCU_BIDIR_DSHOT // @Param: BDMASK // @DisplayName: BLHeli bitmask of bi-directional dshot channels // @Description: Mask of channels which support bi-directional dshot. This is used for ESCs which have firmware that supports bi-directional dshot allowing fast rpm telemetry values to be returned for the harmonic notch. @@ -1409,6 +1409,8 @@ void AP_BLHeli::init(uint32_t mask, AP_HAL::RCOutput::output_mode otype) #ifdef HAL_WITH_BIDIR_DSHOT // possibly enable bi-directional dshot hal.rcout->set_motor_poles(motor_poles); +#endif +#if defined(HAL_WITH_BIDIR_DSHOT) || HAL_WITH_IO_MCU_BIDIR_DSHOT hal.rcout->set_bidir_dshot_mask(uint32_t(channel_bidir_dshot_mask.get()) & digital_mask); #endif // add motors from channel mask From 92ef809e3b357c626d8e7fde8990d0279f1b3c71 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 16 Nov 2023 17:44:55 +0000 Subject: [PATCH 0128/1335] AP_IOMCU: allow bdshot iomcu on non-bdshot fmu --- libraries/AP_IOMCU/AP_IOMCU.cpp | 9 ++++++--- libraries/AP_IOMCU/AP_IOMCU.h | 3 ++- 2 files changed, 8 insertions(+), 4 deletions(-) diff --git a/libraries/AP_IOMCU/AP_IOMCU.cpp b/libraries/AP_IOMCU/AP_IOMCU.cpp index b996aefbe4cba2..6be77ef637fbb6 100644 --- a/libraries/AP_IOMCU/AP_IOMCU.cpp +++ b/libraries/AP_IOMCU/AP_IOMCU.cpp @@ -117,12 +117,13 @@ void AP_IOMCU::thread_main(void) uart.begin(1500*1000, 128, 128); uart.set_unbuffered_writes(true); +#if HAL_WITH_IO_MCU_BIDIR_DSHOT AP_BLHeli* blh = AP_BLHeli::get_singleton(); uint16_t erpm_period_ms = 10; // default 100Hz if (blh && blh->get_telemetry_rate() > 0) { erpm_period_ms = constrain_int16(1000 / blh->get_telemetry_rate(), 1, 1000); } - +#endif trigger_event(IOEVENT_INIT); while (!do_shutdown) { @@ -317,7 +318,7 @@ void AP_IOMCU::thread_main(void) read_servo(); last_servo_read_ms = AP_HAL::millis(); } - +#if HAL_WITH_IO_MCU_BIDIR_DSHOT if (AP_BoardConfig::io_dshot() && now - last_erpm_read_ms > erpm_period_ms) { // read erpm at configured rate. A more efficient scheme might be to // send erpm info back with the response from a PWM send, but that would @@ -333,7 +334,7 @@ void AP_IOMCU::thread_main(void) read_telem(); last_telem_read_ms = AP_HAL::millis(); } - +#endif if (now - last_safety_option_check_ms > 1000) { update_safety_options(); last_safety_option_check_ms = now; @@ -397,6 +398,7 @@ void AP_IOMCU::read_rc_input() } } +#if HAL_WITH_IO_MCU_BIDIR_DSHOT /* read dshot erpm */ @@ -452,6 +454,7 @@ void AP_IOMCU::read_telem() } esc_group = (esc_group + 1) % (IOMCU_MAX_TELEM_CHANNELS / 4); } +#endif /* read status registers diff --git a/libraries/AP_IOMCU/AP_IOMCU.h b/libraries/AP_IOMCU/AP_IOMCU.h index 1c976d2d7399b7..24d19c32c344d0 100644 --- a/libraries/AP_IOMCU/AP_IOMCU.h +++ b/libraries/AP_IOMCU/AP_IOMCU.h @@ -271,11 +271,12 @@ class AP_IOMCU uint16_t rate; } dshot_rate; +#if HAL_WITH_IO_MCU_BIDIR_DSHOT // bi-directional dshot erpm values struct page_dshot_erpm dshot_erpm; struct page_dshot_telem dshot_telem[IOMCU_MAX_TELEM_CHANNELS/4]; uint8_t esc_group; - +#endif // queue of dshot commands that need sending ObjectBuffer dshot_command_queue{8}; From d2a48148dd3ad885a7a56eb22030bc5c4a2bdea3 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 16 Nov 2023 17:44:26 +0000 Subject: [PATCH 0129/1335] AP_HAL_ChibiOS: allow bdshot iomcu on non-bdshot fmu --- libraries/AP_HAL_ChibiOS/RCOutput.h | 3 +-- libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp | 24 +++++++++++-------- .../AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat | 2 +- .../AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef.dat | 2 +- 4 files changed, 17 insertions(+), 14 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/RCOutput.h b/libraries/AP_HAL_ChibiOS/RCOutput.h index 037e656984d9f9..8fbfa6615b81f2 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput.h +++ b/libraries/AP_HAL_ChibiOS/RCOutput.h @@ -164,14 +164,13 @@ class ChibiOS::RCOutput : public AP_HAL::RCOutput */ void set_telem_request_mask(uint32_t mask) override; -#ifdef HAL_WITH_BIDIR_DSHOT /* enable bi-directional telemetry request for a mask of channels. This is used with Dshot to get telemetry feedback The mask uses servo channel numbering */ void set_bidir_dshot_mask(uint32_t mask) override; - +#ifdef HAL_WITH_BIDIR_DSHOT void set_motor_poles(uint8_t poles) override { _bdshot.motor_poles = poles; } #endif diff --git a/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp b/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp index 31a7d7f4c6cb65..d8fd73fc8f7529 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput_bdshot.cpp @@ -28,8 +28,6 @@ extern AP_IOMCU iomcu; #endif -#ifdef HAL_WITH_BIDIR_DSHOT - #if defined(IOMCU_FW) #undef INTERNAL_ERROR #define INTERNAL_ERROR(x) do {} while (0) @@ -39,25 +37,20 @@ using namespace ChibiOS; extern const AP_HAL::HAL& hal; -#if RCOU_DSHOT_TIMING_DEBUG -#define DEBUG_CHANNEL 1 -#define TOGGLE_PIN_CH_DEBUG(pin, channel) do { if (channel == DEBUG_CHANNEL) palToggleLine(HAL_GPIO_LINE_GPIO ## pin); } while (0) -#else -#define TOGGLE_PIN_CH_DEBUG(pin, channel) do {} while (0) -#endif - +#if HAL_USE_PWM /* * enable bi-directional telemetry request for a mask of channels. This is used * with DShot to get telemetry feedback */ void RCOutput::set_bidir_dshot_mask(uint32_t mask) { -#if HAL_WITH_IO_MCU +#if HAL_WITH_IO_MCU_BIDIR_DSHOT const uint32_t iomcu_mask = ((1U<> chan_offset) & ~_bdshot.disabled_mask; _bdshot.mask = local_mask; // we now need to reconfigure the DMA channels since they are affected by the value of the mask @@ -69,7 +62,18 @@ void RCOutput::set_bidir_dshot_mask(uint32_t mask) } set_group_mode(group); } +#endif } +#endif // HAL_USE_PWM + +#ifdef HAL_WITH_BIDIR_DSHOT + +#if RCOU_DSHOT_TIMING_DEBUG +#define DEBUG_CHANNEL 1 +#define TOGGLE_PIN_CH_DEBUG(pin, channel) do { if (channel == DEBUG_CHANNEL) palToggleLine(HAL_GPIO_LINE_GPIO ## pin); } while (0) +#else +#define TOGGLE_PIN_CH_DEBUG(pin, channel) do {} while (0) +#endif bool RCOutput::bdshot_setup_group_ic_DMA(pwm_group &group) { diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat index 3103a5c72c75b1..a4b8e930d0f682 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat @@ -257,4 +257,4 @@ define HAL_OS_FATFS_IO 1 ROMFS io_firmware.bin Tools/IO_Firmware/iofirmware_f103_lowpolh.bin # enable support for dshot on iomcu ROMFS io_firmware_dshot.bin Tools/IO_Firmware/iofirmware_f103_dshot_lowpolh.bin -define HAL_WITH_IO_MCU_DSHOT 1 +define HAL_WITH_IO_MCU_BIDIR_DSHOT 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef.dat index 1419ab5aa2e053..a67d7f9ab062f5 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X/hwdef.dat @@ -379,4 +379,4 @@ env BUILD_ABIN True # enable support for dshot on iomcu ROMFS io_firmware_dshot.bin Tools/IO_Firmware/iofirmware_f103_dshot_lowpolh.bin -define HAL_WITH_IO_MCU_DSHOT 1 +define HAL_WITH_IO_MCU_BIDIR_DSHOT 1 From 5d9f9db2fed3d108c22c08e4a22a06b01c046b21 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Wed, 22 Nov 2023 09:23:21 +0000 Subject: [PATCH 0130/1335] AP_IOMCU: treat register_write() as a successful interaction --- libraries/AP_IOMCU/AP_IOMCU.cpp | 11 +++++++---- libraries/AP_IOMCU/AP_IOMCU.h | 2 +- 2 files changed, 8 insertions(+), 5 deletions(-) diff --git a/libraries/AP_IOMCU/AP_IOMCU.cpp b/libraries/AP_IOMCU/AP_IOMCU.cpp index 6be77ef637fbb6..b77f4f94c9d006 100644 --- a/libraries/AP_IOMCU/AP_IOMCU.cpp +++ b/libraries/AP_IOMCU/AP_IOMCU.cpp @@ -129,9 +129,9 @@ void AP_IOMCU::thread_main(void) while (!do_shutdown) { // check if we have lost contact with the IOMCU const uint32_t now_ms = AP_HAL::millis(); - if (last_reg_read_ms != 0 && now_ms - last_reg_read_ms > 1000U) { + if (last_reg_access_ms != 0 && now_ms - last_reg_access_ms > 1000) { INTERNAL_ERROR(AP_InternalError::error_t::iomcu_reset); - last_reg_read_ms = 0; + last_reg_access_ms = 0; } eventmask_t mask = chEvtWaitAnyTimeout(~0, chTimeMS2I(10)); @@ -682,7 +682,7 @@ bool AP_IOMCU::read_registers(uint8_t page, uint8_t offset, uint8_t count, uint1 total_errors += protocol_fail_count; protocol_fail_count = 0; protocol_count++; - last_reg_read_ms = AP_HAL::millis(); + last_reg_access_ms = AP_HAL::millis(); return true; } @@ -758,6 +758,9 @@ bool AP_IOMCU::write_registers(uint8_t page, uint8_t offset, uint8_t count, cons total_errors += protocol_fail_count; protocol_fail_count = 0; protocol_count++; + + last_reg_access_ms = AP_HAL::millis(); + return true; } @@ -1079,7 +1082,7 @@ bool AP_IOMCU::check_crc(void) write_registers(PAGE_SETUP, PAGE_REG_SETUP_REBOOT_BL, 1, &magic); // avoid internal error on fw upload delay - last_reg_read_ms = 0; + last_reg_access_ms = 0; if (!upload_fw()) { AP_ROMFS::free(fw); diff --git a/libraries/AP_IOMCU/AP_IOMCU.h b/libraries/AP_IOMCU/AP_IOMCU.h index 24d19c32c344d0..253b1b9890b457 100644 --- a/libraries/AP_IOMCU/AP_IOMCU.h +++ b/libraries/AP_IOMCU/AP_IOMCU.h @@ -202,7 +202,7 @@ class AP_IOMCU uint32_t last_rc_read_ms; uint32_t last_servo_read_ms; uint32_t last_safety_option_check_ms; - uint32_t last_reg_read_ms; + uint32_t last_reg_access_ms; uint32_t last_erpm_read_ms; uint32_t last_telem_read_ms; From 1fb62054397779bfb3a2a83f8e33d96531caf53d Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sat, 25 Nov 2023 15:47:55 +0000 Subject: [PATCH 0131/1335] AP_IOMCU: always run iofirmware loop at 1Khz to avoid uart races don't look for multiple pages on single-page packets --- libraries/AP_IOMCU/iofirmware/iofirmware.cpp | 29 +++++++------------- 1 file changed, 10 insertions(+), 19 deletions(-) diff --git a/libraries/AP_IOMCU/iofirmware/iofirmware.cpp b/libraries/AP_IOMCU/iofirmware/iofirmware.cpp index 76b9c11b41af88..55e67dd9978df0 100644 --- a/libraries/AP_IOMCU/iofirmware/iofirmware.cpp +++ b/libraries/AP_IOMCU/iofirmware/iofirmware.cpp @@ -411,13 +411,7 @@ static void stackCheck(uint16_t& mstack, uint16_t& pstack) { */ void AP_IOMCU_FW::update() { -#if CH_CFG_ST_FREQUENCY == 1000000 eventmask_t mask = chEvtWaitAnyTimeout(IOEVENT_PWM | IOEVENT_TX_END | IOEVENT_TX_BEGIN, TIME_US2I(1000)); -#else - // we are not running any other threads, so we can use an - // immediate timeout here for lowest latency - eventmask_t mask = chEvtWaitAnyTimeout(IOEVENT_PWM | IOEVENT_TX_END, TIME_IMMEDIATE); -#endif #ifdef HAL_GPIO_LINE_GPIO107 TOGGLE_PIN_DEBUG(107); #endif @@ -948,18 +942,17 @@ bool AP_IOMCU_FW::handle_code_write() // no input when override is active break; } - /* copy channel data */ - uint16_t i = 0, offset = rx_io_packet.offset, num_values = rx_io_packet.count; - if (offset + num_values > sizeof(reg_direct_pwm.pwm)/2) { + if (rx_io_packet.count != sizeof(reg_direct_pwm.pwm)/2) { return false; } - while ((offset < IOMCU_MAX_CHANNELS) && (num_values > 0)) { + /* copy channel data */ + uint16_t i = 0, num_values = rx_io_packet.count; + while ((i < IOMCU_MAX_CHANNELS) && (num_values > 0)) { /* XXX range-check value? */ if (rx_io_packet.regs[i] != PWM_IGNORE_THIS_CHANNEL) { - reg_direct_pwm.pwm[offset] = rx_io_packet.regs[i]; + reg_direct_pwm.pwm[i] = rx_io_packet.regs[i]; } - offset++; num_values--; i++; } @@ -968,7 +961,7 @@ bool AP_IOMCU_FW::handle_code_write() break; } - case PAGE_MIXING: { + case PAGE_MIXING: { // multi-packet message uint16_t offset = rx_io_packet.offset, num_values = rx_io_packet.count; if (offset + num_values > sizeof(mixing)/2) { return false; @@ -978,11 +971,10 @@ bool AP_IOMCU_FW::handle_code_write() } case PAGE_FAILSAFE_PWM: { - uint16_t offset = rx_io_packet.offset, num_values = rx_io_packet.count; - if (offset + num_values > sizeof(reg_failsafe_pwm.pwm)/2) { + if (rx_io_packet.count != sizeof(reg_failsafe_pwm.pwm)/2) { return false; } - memcpy((®_failsafe_pwm.pwm[0])+offset, &rx_io_packet.regs[0], num_values*2); + memcpy((®_failsafe_pwm.pwm[0]), &rx_io_packet.regs[0], rx_io_packet.count*2); break; } @@ -994,11 +986,10 @@ bool AP_IOMCU_FW::handle_code_write() break; case PAGE_DSHOT: { - uint16_t offset = rx_io_packet.offset, num_values = rx_io_packet.count; - if (offset + num_values > sizeof(dshot)/2) { + if (rx_io_packet.count != sizeof(dshot)/2) { return false; } - memcpy(((uint16_t *)&dshot)+offset, &rx_io_packet.regs[0], num_values*2); + memcpy(((uint16_t *)&dshot)+rx_io_packet.offset, &rx_io_packet.regs[0], rx_io_packet.count*2); if(dshot.telem_mask) { hal.rcout->set_telem_request_mask(dshot.telem_mask); } From ea76c0bd0194b14b6e223392db101bc07baa4f0e Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sat, 16 Dec 2023 11:25:43 +0000 Subject: [PATCH 0132/1335] AP_HAL_ChibiOS: ensure dshot commands are send to all FMU channels when IOMCU is present --- libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp b/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp index c8ca5156fb7ce2..dc6824256a1322 100644 --- a/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp +++ b/libraries/AP_HAL_ChibiOS/RCOutput_serial.cpp @@ -151,7 +151,7 @@ void RCOutput::update_channel_masks() { } #if HAL_PWM_COUNT > 0 - for (uint8_t i=0; i Date: Mon, 11 Dec 2023 09:58:54 +0000 Subject: [PATCH 0133/1335] IO_Firmware: iofirmware for bdshot on f103. --- .../IO_Firmware/iofirmware_dshot_highpolh.bin | Bin 46996 -> 47164 bytes .../IO_Firmware/iofirmware_dshot_lowpolh.bin | Bin 46996 -> 47164 bytes .../iofirmware_f103_8MHz_highpolh.bin | Bin 40544 -> 40592 bytes .../iofirmware_f103_8MHz_lowpolh.bin | Bin 40544 -> 40592 bytes .../iofirmware_f103_dshot_highpolh.bin | Bin 46988 -> 52668 bytes .../iofirmware_f103_dshot_lowpolh.bin | Bin 46988 -> 52668 bytes .../IO_Firmware/iofirmware_f103_highpolh.bin | Bin 40544 -> 40592 bytes Tools/IO_Firmware/iofirmware_f103_lowpolh.bin | Bin 40544 -> 40592 bytes Tools/IO_Firmware/iofirmware_highpolh.bin | Bin 40544 -> 40592 bytes Tools/IO_Firmware/iofirmware_lowpolh.bin | Bin 40544 -> 40592 bytes 10 files changed, 0 insertions(+), 0 deletions(-) diff --git a/Tools/IO_Firmware/iofirmware_dshot_highpolh.bin b/Tools/IO_Firmware/iofirmware_dshot_highpolh.bin index 362fdf5ffa84648396d91b15c7e082d563589c74..817ba4fed0b98f46bc0e55683f6e77310ada1350 100755 GIT binary patch delta 12736 zcmaKS3tUvy_W#~zhG9^UK_2oDnTIHd*bJzlrVc|M1XM(`o38>*8=qljnQ5S?VOoJ3 z3N?#LyINK}q$Hid!qRTuJNW3L=1nV`kn$c>nlmsk|L-2Oy8q9;KR%!DtbNv6d!7AU zd+l{7`?qjR5=InKqKzFy)XiB$9SfA-q4Pn9g8yfPmX?kfmN}`8s8<1dfm1*S;KPVI z0!Rc>fmy&3U;{8!`=3_0Mcqe4z3p)6jii3@yNNnrFHw&N-S$!GjVDUY{{2dmh`N0e z%w)jKOSLQMzx;h1E<3#0iw%>kOR|I`xo6aq$6J8C9I_a!~0zR^2an#QXJx z@J`tkL`yV8t^SoyA92d<%8 z*domvp+uOoM6J_Hg~FV?Nb4NyT&r4YV-Z0^17^v@a3!zkR#36Vww_H5N)LEkzLrM} zoRb31n?doxWJZX#Nv_nKZdF=Nx2n>pl))|s#q@txjuV^Y#vDQV-lY}K$&Ep*U;nVg zA53NPk0z2Z+OE=P-!4owOx92Jm41;u&YB*rNTrWmoKJG%L|^GD%jy3}R$~Zyh~CZ8 z5%qq6XsDU^Q}aGG(JsND=hxX~f8D@ojj~&7mo>U%Yoknbb~!}nBR0xPl)`mnaHFi& zwXmq*sf&2M68Q(6hSy6{io5Ge4m6`2}reJ#T+VW|2hc9^bU<8-%^}O+g@)cd*`y1tNP5J4hA-}F@tx`Oh zu&IhjtT3QubOMno3-3+HY8KWC(nN(C&wncIE7N6_<+b+r5&xoY}>bYjqoN}X9YPNZ0VrJ*qe9}mH18cNiU0I5JSumso^ z`=98(!@GKi9{(>oe+91`*aEBuqT_mPgrdyt1%L``dpox)e02Oo=c()~5SiRMp{hMdKAsSCq(UwY;?IC2l#n+xJ3keG*g*Ut{t8_({ zj^=Zi2SImECPI^JH~C6N&pL-eoIJi{=Bf%h#1E-qv;2c86?H1* z1;+7Sy3;tuk(srz__N|DYo+{>rcy4^wk$tW!{?|Hb2Q9B4V$2E)ozx*HyPN*0a003 zbs>&T#nezKKdSxNVQ-~|#@4BZKInW%5Ps1{ciu>a| z#l|zsKa<@?iG4RC|w84>}=n1-FYoNc&9;e#>j+iw_>vX+@7Sucz*(-hmX*vZ@azS*c{`@>%rm zPafyhE{$H16&aK_8+(CoXhM3O0(&W3$LhipXcoH~o*ZJ5k65nR&3{^daWadG(1+~k zCUKXW3;!etklDi#gMu$Z(DWw(k#4h>Bl4mbb}6;KQen5Yx?KL+NRzkVSE)OXY4?@N zSwLh1?O>-P;iA9qnKl}1XX2i!)l8-3SG zbTgM2q(a5ayp3MB%Db~3K976u7I<;Y12+3Frn8X?6YjlmUzVn>QT|1@$Ep;AC9NW= z8Doe!l1yY67VK(uL-y@=1Jlan+d7&gNP)s;l-Orc!_2pJ&y4V0%p7=O_~w*yCG-@icL6%l%WSKEdk-=UOY$6RZVg@@QSla$ZScz4UlRIm$NhQn<^@5^`(vTv`;Pqq#dFDyS<2uZGbwt-UHE4vX$rNTUwgg<@`|U*! zcf*3t_H(}3SL*r1>w!#3)qm#RV(~Gf(2Pf7V&j@HWW4qHb!4!Q=s&F->raVw`Ga=_ zo~rS)CtJ(q4|VKNOn4AilO z`Dl`wWPgDSv)a$$e16Z8cV=rA)kRsuF}Zt|RiyVgdL6;1EKSR@HvNylZMqd%+p(^|aORvWL$^=D zh!!<^yURu5EX}g*oIDV^eG)QTvL#{}k@ZLIE0}^NSv|w!40WAb`n#b^XF1!Q=W!mB z`5a9|lt-lgXiBenySJL0<8i*_=5j-K*qt+C&q^L=gd}aR=lsumcrzYEGmc?EG3=OS z*-WJ`S+qW40QbU6UA#L7aUgKd>Gh&)s{S4oFIA}7CcV+m7*r(xsH2jF9o0t+<$^^B z!A}n(>I#&Nb!p)QCq0vQ=Tyr(P0SK_rdoc1b?FUs6N@p#1nf>l2*~+otK>~A%P@+r zV;c=I(F;s{E+3X>(8kE=X{k5M`j>Rwl)~>XtjV_>mMzR?7+_eJ7a(dxg5Yx96GVEh zGpxF?V_iO}QMOG|LI*o_26GxreYUPqcGRyuEWc}FNrT7eI+~vflj*qD8anP$jc-D~ z7A0Z{A+c6Ir}b|xlMkBMj=}SS)FXV_1)tZOg(}<6(#BD83UdvP5+DqVO%mQQvCLS# z-@RR1ES+{LC9^fL2}2K{yDh;)tEuZZrC&ziWR;}q>6f7uRg%!7H3)kD3~jVZn!~<~ zjgH}Z$LfiCB&Z$q5b7qjO4-j>(Gn{C!W2V1^hc%`nwpi>ty}A#8IYx(Oyd0;g2V{e zOYZjNt$Mi;wYUZT=B7JuuiQ!rx5lmVHzc;+N<}2XLtFOp&=_HO533p)Hb&b6H@Gk% zPk;|VXtJkC4o~XsDnfhx?#P;s&Vt|0@=HTxW>B6&j{rvh3y!XE<{5hL#PB4gx8B#B zqu�O8D}Ez^@*8ipf6Gg>GW_H zOFeO7Viv($ubRwq$v8oJsb_!Q0qET5@e!?Fol~rISZLO|o@;qWz`qFo0WZG}bq8j} z=?Ma8>o{L&lBd_siPpjT{c?rYr~Ne|NDueKF4%{9pZ;!d7i%9DYRv4pwxA6Bcfk+$ zwvb4Fcf~GDu}Pm2HJ^Zd(2@qCHUriMHacM|)iGN_M5y^wc*bmK!?WmD?8D*J!F&@Xw#sRW-TKt@UhEn|ER->xhxwV_r`%TG~Jju91vToSCSGe6_Kw3?+FP4ok{+GwDa>{a|usXb~8r2)@&^UX*P>?=dVomN*utcEpXhEPz0FFKM#T*5R#X{nDL6@#Q{zNB zQYF3b(hT=$*ZMe{Q*0yIwWQQVdmGFKLno1lL~&EkPbWlOCx~Rd$Jy@D*4utoo2R4P z)}Xcp#--HtY4M$+Y%_=KxAJ}Yt}C?qZR=hOZ6?|j8`ZiUBmIarFg~SDDTa!HE!cBy zsT!5^8G9r-!iUR@Y(w%Gn#n#+{>xyMD@W{h&UN+Ot=iM4#2!wK-A=dMXAc#_!B=#; zoemF68focgL`CaST(ZeY%i~9DH;wE=?-(l`HI9yCr$@C9Jzz|$x6AvcCsxP7mA~kY zgL^&#=bmCqX(Vb58f3(ZJIJn$9y)%?F{~;Z?CFJE-r>6xT3Jd_k!xP6uJ$-zLT!!h z2;R$Udz_MoyZj9-aA>YsU7dofQX#k!2v-r$F8%^`JX}!Z(uyOq278@^a-2%~hez2yk|?BuJ-wUa zhetu3+)MGRxP6^Q(RwZT`ag)u6 zI*E2h9XLFv)Bs)tt#S&CdCD=k-Ti^I-&Hsqy=6dXS7lWlBT zdJ27*J)f@Y*TCO-M^J2IAEgf&a0vQ*m)!;5O+C&yb}L;cO#YOGO*Td>IFgTk_fI^~ z&_7lw4nqG!j7y11da(A9$;p&H#8`$+DEYK@M&^?O{gizBqGK-F!BKja(Hp4;J*3O)%qbdKCGsG@u zoGTT-(Q=nFu#4Pu7*h&I3*~YqQQgj8Y)tENHhHx|y;^;sJ{U_E)Xsd+N$Kk>>!C^Pwb6a&H1KivI&1E*?|}0f<;|KxxtMbr?DA$l z<_#tC5ihmNC%sfyZ%3M-+1xj+5i}nuk3zW~lyJ&gA39|qLA)O4f5Q2&#>+R2;Ueb? zyv)we)-9WZIHlJ|<<}Vv{vt1z;)pCo3urR4s4wyO=ZaM!O}e9*Z)=u!7^~&YxwL(U zPcVG7Qrhb>h$bv}nyHjtc3pE!T1wP%osZa0^q->a2z%PF^1OVE<;~I25>_-Paoo@b z(x9&EcIrHetV`DL$g0jl$?T`L@qNWZz+!Rel#Sxh470eU3ia3ZINy@XpUPs^l4 zcz5p7{;eufk-klCH+y5+=g-OG$kl;@w3q1~4))<*Yy}(h@KidPJ^ye#y@ypJ*^$NQ zBgynvHtLZ?gCIr7RO^4QP2^!V*EcO8>QJ=aALB-VU)YvMvgv+y{*mO=x*mg=gs4c7 zsgVBKb2pPu8gy6*+*@=zKfz7(w()Z$n|v=QaYMXKqO8HyQQL5dGiq#QEF(92z~`QW z?S6jd>ZB1H8}ut%@S;zF$sY@>N2G3O zHX;na(Op@M8d{;yUi79_O!JKRMKR z@kX}c(NVJ!Gj%Ix$Oi3uD-yCJEambMqkjX{5uK3mao0_!$^Le`Qc>GkbZf33DV?HI zFhiE`YLpe*tyBkFZ}u3EQaJc|BiyUtrg4R&vLjqbya zcUKrzMp~-uMDN=ksF+L8{@f+7C*cigTS^TiiFZu7tH`tiR7SRdpjmLB}ksW_5nYvlWV+KU>5!Pkiy|IXGv+4qF zHj=ty?KIH0*)F@;$JT^&1-27EZwqmJ29|xX~}oFl`E+f zcSq-f*Otfm75jY2E;^gdUwTi$({fX*p61(d!OD&no8?BMzo-%ih=ywAIGR8&@LA$* zoY~#&%tIciM0-vyGZu!YwNb_MmNjh(MWa+*xH$8cHORUsbMlHN%sxWUrOaZM-YY}~ zM?D20qxNwctB|^SzLVF!xp2NGA;3=cLZ_l@LBYzX>q4N)egs1sY#*3BS`H>x>ggz- z#5R2PI6};~3yp$Q>egY|@F|_5_c%8-B(48Oc55QXEqb?L7I&6KJHS z%lSf&`R3nOZK`>zW8D+gZI;07>lVe-i{_h-q;KRVjrrz3R!3de(!lVBU@_^L;QQy2 zJvHCpvtIw}eFJms`s;m#FYv?)mxaaZANOhZOh9M)3T^%T7l`p0W%63$XT2zse9}eR zeY=QsjvZZQnp@<6ZS9^K-m3^ZPjf|_`Mkrm&^LKc&HI=lZ%!%O?c98{BE3+Y>4@yJ z>3VSgIcAT`}tuJ%Ud42sLJRgmf#jF+R2c3 z?}3V~hFkOdt}FOzaM!z|dgS*YuA+Ir3+v9XVIJ0EoQjjOrfuRo6` zpY}tv+c~@QT?b29@le2JBu4K}R}R~?B6@!G)J;`;<+xm*j+0N~1scCGLi~;fqNBQM zOGNVzE00$1S^r-3jrxD$gw%2|)}dC0P_ z{iK502a4aYpq0S|#h#xrIDCJk)b-8kn-Pr<7Ry#dT4z}CX%)Gvo7y6IniiC#*uuq< zbP^{wFI#c*&VWvZ|3(BvN@U6Sw|Y&T!n(PN=js&)l_K)>(#P;o$|{Ym4mp*QRX$my z%xAJ7o$2P67|94pfh|9Md?6BhxC-!4Wg-HQf!2xBv@5n$;l{PB))LU%@91+eFZ;H3x*+`<_vTSO z-!q_8`~c*FssMSILbm-7De-b^IFGw?#El}pf9Uxt{e;Emk1D8j)6qU7e)RedLAv6af`l2Do^`+D$P#(V z?xc~2$|n&D+mZ0*r@=$64a#_gR6x8XaDaFxNo2(^It=KCMp8ksbTCS>kQtgoSuUO~>&oD!? zXV}1ool$3MUX+!Z7iE9#5A}WGjx_YqD%zHRIyZf6i)sciAr z^*#;uAeK4kaem}c;!{5lZfB;QlQ#!xc@$iM{ARd#(Yw#s_p9zl9&hLq(NRTil^BS| z7q|3A)dT%ox~L&-wHnv$xZ`Z+YD@5~ zdW}s}m-ehuoLgPE#9ZxmRx!uwZQiQZ8~t)bxO5RXb6%;v)oir93+1QLZA(EaL=~ zwj*TUQ9+N0L zS9>)ELt~ztEv?Uyol89~=L0U?T0y+Btk>3epUAdjXpsgROOR5I3DV?aaB1x0r?;n$ z?cyP&DL2}?Nr}@F6OO(N1_WvCF*PpSOKgPjSf{uuKvW*^IVebryU1Xb7?Kf(>E6eR z)~0DTxxRC#xrL4MQ1h|R*f(pJ2fpN~oGFZ!9c{kK^PSG;S)PAvHH04Hno*S!jL%HH}Hlg6bf>MvN_i|H&Ejapg ztFTQk#*3;f^NKEKkw7HZ;&7a4DJFHJCBM!eInu}$+1c8u615oi zYn>D^i;Vc*FGF^Y=$uq7Nc+38rROjKv7NFrqC4LP$J#|xI%|Uq6R9esKhX|vV&cY4 zcZ+}DID>{T-KL57&D#`QFuaMoQ^jPD^PGpLay`z$4fp-d`|1uavSG^ayv92`O~bt3 zc^}>3sT!95&O3C6=l*p4@4UC}@NRy(13Y4gV7E4{p%1VnMazWOn%Fl*pW>l>^TdF2 zX!vb_D2X|w_Uh(6G>Ef^Mlh4nD=8O+uot&xdlfmim(#j+dno^0Q~xTgLyx3TGyf2D zifw!T?S55wCzo>lmS8rvctW2)9&0xhhtV+p+&dikcbdBMXiISI2iy8lx}Moy_|A|2 zkHfF{cer}CfBQed+pyzt`atckJH{z#6N@jsi)v?~%r&#l=qXv!ui)fYjYJSOD!b1b3278wiw^A`g6#zeg;foZ;E5pgn=XZ3$coJGad25Ko3!gFuO#eV z&_{U!SN0h1-DlLz0YyZ z3wzJpIIMmZ%*rX-$|nW7TUdFpT3!?s>0)yFxKy_AwpFc8~v7^lR0mFGl-9$ z7Q+z^Os$0<%bdAPkv4N7&xbXJ)J}W*If|uydS3#5UEbf={k)vx{oSztF_f?EUya|{ z?<^ChoM2zPvs5?|#*+RzHf?ne(f#He>8h+I!<83tOI4(G`gDxAf5>%TBHIEoI-Co< z8U|N5H2Pe^7k?Yvh3(^ZPj=^7Dt0($un+$_dvt6MEr}OtMTc`xk5M9NDtwgTr_yiE zpJYxOZ-pruZ+$r45acA>l%cvB<= z>ivHb%twVa0B_Vm;CC~gLGRWd^%smFkOPdl zgTw+9?kdbeIS-f(=zv%t9=I#ti}HS88&C?=0rkLLc{9qbC3rdLdEf+a3OEhi)w$d7 zRa2n{#MmPX`zjw>WEExrcptd77Twy2Jq-Ba7MBRB z1C0l|fk{Yqz6jckTit$6AIIpU><5Gb)m98FU;~Z=KHyz_4vPupQ^08}$x}C@U|R!4 z7}&BB%Nn#CitV76p&SHydKnfL^jtvRax5tDTxiUBJYN7V16P3{=v@PC1)f;=_?joN zHrS(8YiE>if)bFr8La}HzZLrn<=KD@%X|xXvx+b|crHab8kFB#PlNX&o_UUN6nJBR z6VTtVg^j2l5?Ti{ZvuQ5m4lW72icP9?FCa`zz`K*Ze*r%NZGgln+fe()n2a|uI>0Jm zKClFs1*8Irzy@HUk&s`S{%Ev0l*cu*4!=C)*ep*0MJGKTNMxptMknVoq5gd@yvJg+X{+0L*XXycf+$z+CCYuEZS_0vKEE@; z*KezlC>y2`Wmqb@*-@8A|LN=Xj>|_ZWV8K}gV&*y*%3HBaK=X_*_9_Hd1z^}tCfnE znbj{~%z_3&_@L}Eq9!V$RNf)i2_b6E6HgN*=dV=|bpi0$P|8;a6%Tc`>m@7QHOsUa|MZ&Y$A(m$?nHHs3$$|%t9N;Ap-SzB}`vXf=wr|*s zfyo2Hr6011j&tI{**`EkAa~AS^=YX}^;MhP^i`W8iHb?=+Q9HZ>!c|2X=(HvLHyjM zHeZlN4`P0UhQwqT%cWUHq91QpXfqxZCF)YNGrYyUlE+!wtu|B9>f(GdJId@W?qstE z{h?4Dh!J9Rb2UU+4GoyNWs+f#U3yYWq6ar_)MPy9SiL9YHIw3UXzG`i%@2x9UuHE) zPa0LW!_sT&v<5!r!D%HTrIp@Ew~FHevQ@T(pFcI)rKy85LzwAq3l$kV6fjgVi_gy> z_GLgsB zzE^HSu(c(Aco>r|1 zn?uO$B;q5!>pCK72gO<&Bho`HEtu1xu5Q$C@|6D|LYO`FEAQ`4m@f_O~ z7+yGTBsSUzqO^jR0PCZ$!9cf0{vH#+=e*E|)cqf1Zh-d>pb_u_o_;7h6lLD_ASh}7 zWBweX3F}q((Lz^E>#yT|HhPNl~WIt$Ooojjk5OF zH;k5st4mDxn=fEB1kD90S13F!J!bS4zv|9ul@-XuDKe@reDLTepA|qqS!HRJG~76^ zwOrEA$w?=ZgBochpVx9}lu=pYl{4GPT2%pWC9IN8;;zZ=KG7lwvPw0J41)g z+VFAG&*p&ldK&%t<0Trk+2ee&`|X>(vnyauc78m~LPg^C%GrLC?`}eRy~^fNidS3I zds;ot2DeJEBg+$&!P!!=||9YH!iEOKsgH{mnq*w&GW=xd_Yf7B%cl za3gJITSKC0Jo_YMvTmZA56A9_GW(}`i;uds<|wm4<1Hq+DXeLUNqcuM{-~n0eYbTmA2=T_fwMBU1vi4THG#}mc z8-*urXmem1U$}rC-@q5L951$V86%DBr{^j#<*;FeeQ$1R<(lxWe{St_{9=6>Hbt4F z)_R%um`V;u*h$2~nf}*9m+elDvv@ml=)7F2m08Z!W?Jaj-O0+)yCCmx|1Kdwr2cW1 z*4mcbiDsGQX7knG)c?DAtE4v8!+z_f@*lUN0?8l#iZjk7^MfqobF$Oqfo!x}Gs-T6QPvEW4zo znwDJNN@mGiwL6)&b~uyW${qxtnSXUN%t;lWu2#tV|9t_(S=_qtpzH5;<-C(5>fmcv_Q zTJ@GAJ(?VmmZ&fuXu|jUOt`rj#wU7em#TUXmM!pGylw{Sh5-icq`Gofkda*)J|@;+ z9AYmu4Ya~S)wQ%WJ!Eo)o+M{2)|yj7<4Lfa1GZNwysuT`4U(%3l&9|#eHJ1*dix{U=3ZOJHnKunLP zpO#AJgk)ck)`D%+4{y03S&a8X>e^o_)SbT|EdjTmeoTuJgU@i0C{wd!yC9YJaMM~c zL}D5P*V@Tx=|dJko9 zQSIVGJP2dwQFNa>tx*v62W_;1Kg)gC8(KqZ*1!^JmX?a6-CpU6w4f|Ssv^bqqcVYr z*N*<$_!)%zfqJ5pqoJWbDTv1jOcLf;rH)u;@;`5t?lEtjj^1K=UHAaObXdB_`ClKF zZn39z`rtK@)AHQ5a%mPep2dH14gY4m%aYSaGC&@n8%;9>Ol5mR{iLDAx*A{BNQZ$GSoD9Zydm7qcB zGp0?l(N|)117X}dULJc91S_%hU;K>s7KW+l<@YvAKqt7 z+xUM@lqFD>|%Yk08dh6q?Mznfz$f6(1D}d#x}(f7=>%`M5t|^DO%lX{?&|Cs$lUGrGFy6N>bi+GGM!84v$jf) ztGyhr6G2?k{X_Prkh=o8njX1#(bur_C@n$EZkgmQy3vleI@1=Rt(JDHy%sq3qG3vR z`qqW{v@^%A}i>xm)nK7S&|M{olz&?rIUZpi(pRui}X)y)#!A3gdH1g z4dA;qrcFwc<;u-OpJ6BBa8?)-N&Bd{1PW`9vY*FjCmrjo+SKKI-#s9;%h~Q;y2&?HZvOm!lcLM{dKYQ% znVunf;&8QPUC#4eO|_&f&aBcznS~FiSj3)qpLsElX+B+-88U;()(HR9N{db%P@wUB< zM5%(0Gr*b}S=fY;ijR)LVve)43F@KmLquf@0)vZqoT7(&cgBh*yu9G>0HSUJ>_9Fg zu7ip|6+rypn*cRn0Dc61;?$q0zXxsV50!x`U$nt<0^lnrY9;U!WK!5O@tW}pq)vF6 zL}@cXuBd**%n=!JSsj)U=||KdSqgEq%i}b5Da80rZ935m!@PT(Dv2GAR~Ke>CRhVB zL*W>gc23s@rj`aNM7M|P0%jO2AFe@)0`ZVS9E^F8i4(ik2oQME!fo+QJEFdltq>iO z!O|NwafzsICl0W&P=Y5?xH5bzOoh^1c{v78(}OHL7r^UCO1>;P-j~gpxUew8r8bXE zkLcO<@<|G@(j#|_B{Feccdtc%w`5G(m{bL>tp;7p^ucP~>X>w0R>p&~YrcDq=uS&} z4g8K+W$1R!>Ty@O8X~$oz@J4T!_#!BsGAjzQ6B2nq{zgSu8=f!>To<)cZa8krT(+m-8Ewg0qY1sE7#F}`xX$6*v$vA)&Y3xg9;cgReXd=80ngnrIQIV7|E82WmdWCd3 z_p+p?G;}-5c`A|?)NOytNpT33%$p|Xlg{k(hD|*A9P%+ZwVGDtCzm0m$1ChoQx6q3 z*b$R9C-hHh0?kk6xf?4e;grQZb519zxIE|Aaz6Uu5|-Lmx`!+nS{<2CK9oi#oP=1;F9T#Z@kyITmJ3 z)8t~d>xWj#c0L<`0aZV%p^MlT&&Gtfus4+PoI&h#?^9taOAqvz)?DT};d#<-g$= z!tTUCv!6K}2YVZfUi2~|nd(I`;g93B?@Mb9Ez*-DGYx0dN@hwx@^_+{s%4^{ITlTz z>sj>T#q?X2k)zRdcG7WoYUMF^ny=?kO_x(HQFZ^GpnXC1|F)`g1@RxO8EKCN%&}NE zaEIr#lv|Y8>Q%<2JDtrea!L3gJ}uQViSiJTvz{nVu4hjz856ys*?@@nR9BT1hG+=I z?+dd?%pAKH5-DrKuhuH`QJ1-dl^t3#l+I;mmW+Gy;7Wa(wWHWEN7AWxNrw&58G`<= z?t9LRTeAno+7CG7vbv6v`O8MN}{i2J9EP18(Y^lvf7-{G=zPd6Pj_vpv?r`g=Fqr3Xy5OiydsBg=vVYZ1iVh9}_$ zWf(cY95DS`X%<_sO#i5NCsxc*wKTM$*OG6-9D3*UlB@mU3|wACln4uZT4#s`B|#4Z zr?Z92g4w^9`A3Fy{(0%EaDTUZEXn4o%A=y{A@4>j9}#j4EN*!PO=Mp!f25E}r`xnN z-^M3)sCk%KVLqETz})G4vFqtua#?~{RkR}QzGa|gd0NWKGtzMb?0Y%4@4pn`vZ$Pn zm?>%%jgX1$-QP;D@7FKz=zZ-}vpkP>$lRf~1b;7k>9m3NVR7T70Ag>TW4%WI)O=C; z6khU;&S1G#+8#C{QQzB$LT^$3pvC~RaectlOj22U2?;o^ z${+07Tm6O4@f6Z82{)|Gw*m&m7T*$NGSOd_bc+UzS|xXQ9>=))3%C7z7nu#IyQBi* zW4R)ceB!1KZ#NMyvbnjjg8w8nrPSMN`RfDhJYy7a{(*V; zM+T2xX4mFjNjUF4_~J#WM*SMDxKZX^()(&6ZggRt$Nt&$L-PnL>I`(!8T>-$lHNXE zMgr-sz0%VR`nbWaB`Q7A1H^1cXMIf-o)j#UP%f8x+c=B?* zPrIBibR2-evYM6ie9j;v$rpSQ8;}+n+@(&xEM3uZ9F=? z@1ppK%H=n?ORZFMJ@2%1ysFb_>-fm@zT>Qn+J~9{x3%}AG2K(Gx!$VjX}8_;V=Jr5 z3n{#%E|F%c%cWZ+-WFsoOD0iL^NN-C`1Zlp48$y!Nk1Brjs>QN7U=8FYV+#@rt^GI zb&$d=xMg!UAEwtoLOQW`CMu<~V@cG{_P5cdzmX~BdV#xSJol})eo{8bVsBOMLgQM zfM_PbYCxW3*&Q5-kD3$VAO-Q;?yaaq(oait9%m`C6a)!UvdiOCd(erRj5?2T78`i? zG!B7;LvRm_+X9XtR`k4#=)Z0LqR0ODG0bmP6y8u-&o7vX`GEm)$=j@MAS2_=vYs=n z)9GN#^1~TyO?|~0 z^T!o_-bu%Mjrks54!I#*bxlX^gxB8etZq#=|Af>Cf=B}o9Gegr+R-a7A4eHUt>j2d zc&H_FCBw~(=%*k%Z^bb`R{hQ9jr-(Pp)!)7j>!a`?*TndT+N+X@L%5ry^PGv(&- z7Mr9dFRa`rMa+6z+MA`Y#?+12@V1Fw_KZ?DzZJSelB;$|zUuE9`bB-(*iS8Y>{SS5 z^q>K=^`)nvVIB7EUef8DikHb-d^NpKPkRss9K?q|j~sT(gTyD2{?^+_+w&6(DsWeL_!=lAT@wcC1{9&chp){POq zX=3Je>Hy!4rdpMa#tqQlZGKekf-VNOeqE;jwXMBTogn_$)#)71zFQX^@s4|CgKl{o zPRs+@w5HSfp_}J{=p@}DqW`)1J{+~m%?vMW5)3YO_=O1C$S%GR^JGm&Q)u>WC9N^7 zb`V(`((l~)aRcvHhZO3|wCteIGEO8kcGQ?T4M~EcB<=o(kvc{V=1$Yng@qx#(ERu7BC)(_C zZk1%>O3CGHfai-xbauOg*X4O)&64x89*MP(m@j3B8)i$+qaK&@eV3*{FkfHM+t;^8 zCEGA)q{4O*#Q5V#P##BY!JaPIo|xz6@mXwESkLApPEU9)#!>(vPkLO5tL8o%Av_W( zJv_iHukku4h)dlhLSY`98inOB6s=v6tZB_CfiVvgZv6JkD^|}5no~kE=@lxw; zZ~4Uz#HEh)3+QH+@lv8Ne;|A7rCXeAdimpFE4qWMi!DN0QybCo$t*j?|CL3K&IO63 zY$y2%eE7B8Ix}AUZh^@V%FdQuI1H7XP@QRm3 zz1|34hD9wl<=6X~1I-~Vl5?V4VOC?>$GIu|r{tX6>60osH+4+23SzZ8L)?S~Sl1yr zmv!ai{{M}e#&^`!6~$1++ClL2pRt?8oBN7+o9EzWeRA^@{L+$u!Xjv_te2(0;d%Hc z6OS{ZvFsP#mk)U%ja9$!njZ30jfa2X{pBG~(b)70@1uvj&J*@uc<(*r-8*p|JfaI` ztYjVTvOZf@2;yh#g)JxWFmCIV0b}uz;7NeUNy6H?;;of*AZHPkkU+-gQC_u{#k`u) zBgnbEoNcde4=hJr@H^-oawMK6@NX5-EV}f7pZs+17Yi;QKbT!9eY_tR?tQG&ZW}^} z@aNv?$bYEnTgT!D*Ufy*kJ4}0g6-e>@Gtr^_8=9(roH~Z;Dzm2MUT|&*fB{?gV?#9 zSG@=hqlt9~-;z;*1hS9WB~D%`A2EcVQnK_bmVgzyTZ9f=9F&lsjQIUj`QN>Gm5N>4 zrDLD&QVU>S*=6En_}lMsa_a4#r^hRXuwn05IOmmjYUD?cp{x9U ze*S=uA}c?c^N4{Y@L3wwAUKLlLc82JXF0D^4rTw`uN6Rq_h$N)e?gRwLAn=g;d^Nc z6&@3YvX9>zA*hD3OYdnp>3Hwba6W%)F&(+Up<4K{v?o@`lAc(c4sV zwEPP0i?XB+ul6xhN8Iuzl5Ie0JN|c%ORRAPL89MPOqLDq!uD5(C!^zQYHoMF$1-Z3 z8NaTZmPMQC?sjKhw?QOH3VdJSr_#^P@h(oA?hlbQ-Tz`v(gQ+HIo_7FBwTI%<}~|f zjY*i;&9n!<^eT?W|8Uhg4(jOagO6jN!0ZH~+y+#jybst9R0HJUUqvEOE(2V^HsBC2 z&V>KQ1YHMg1loXNmh)j|Ve>Si+=c%M<+zCQW#Afc<2QU>=fZOr5NO7~ZvxRk3=j+S zy_w7Pl>?I@2h2tNGr)r1$YrCP11vL>LgmWeR79e|WPmHR8vJ#@|F6_W@DL^{Cj$SM zQtMGa4www|DRm9yL|___+QTpGt=fr)T|fn}57-Y>0|$Y=#T|$f3Csqb z0X71~KwtX`lvB&_a?pLi4qzv+3+R*SQ+(nK$N_V=;-?b6yrlM{JFgpjs0REfYM${DpG0#C3_?;X(^hrsftZ()}Q&*zb zd@LIfxEiVg6$O~ABJ={B!DX!i^cv_7Km+ojF4U)j?!W~u8+6+$Yo5dVPR@f}fH@l-9m4Z2l)nPDt-wFFf;IrbxmbPB>|!Va zx)0b7R0Ch3-9gYp08?2D=Cng-@@5E>z@R{FTcH`s4L}$y`v=t5gWrW`2g(~k`E@jg zQ(lJ-ccEMXL_+@B7IwutA~5h3*ek#{PCL4E06r|Rc6;HWZSYK`&=M9O255jtAR5?( z76V^}hJY1_1+N~|0sc6YD?l}Po{VxLFb%kjzRrN(3@kw34m_VkITdv?fNVT317@Q< zcP6}FH7dtJumRKt2=v$0&DoBQU&CGpHUfRi-VXU2c(#JNfJn#%<9Q$F0rk8;U_JON zcc2eo=j%`ubvE!%0(0|LZBrK@^E8Cw5ln&l}^A$`d9cqsLFdLO#fP(S+D z7Ga}$%URzI!TkFiVjCShy<3;E0E2(EAZ*8=qljnQ5S?VOoJ3 z3N?#LyINK}q$Hid!qRTuJNW3L=1nV`kn$c>nlmsk|L-2Oy8q9;KR%!DtbNv6d!7AU zd+l{7`?qjR5=InKqKzFy)XiB$9SfA-q4Pn9g8yfPmX?kfmN}`8s8<1dfm1*S;KPVI z0!Rc>fmy&3U;{8!`=3_0Mcqe4z3p)6jii3@yNNnrFHw&N-S$!GjVDUY{{2dmh`N0e z%w)jKOSLQMzx;h1E<3#0iw%>kOR|I`xo6aq$6J8C9I_a!~0zR^2an#QXJx z@J`tkL`yV8t^SoyA92d<%8 z*domvp+uOoM6J_Hg~FV?Nb4NyT&r4YV-Z0^17^v@a3!zkR#36Vww_H5N)LEkzLrM} zoRb31n?doxWJZX#Nv_nKZdF=Nx2n>pl))|s#q@txjuV^Y#vDQV-lY}K$&Ep*U;nVg zA53NPk0z2Z+OE=P-!4owOx92Jm41;u&YB*rNTrWmoKJG%L|^GD%jy3}R$~Zyh~CZ8 z5%qq6XsDU^Q}aGG(JsND=hxX~f8D@ojj~&7mo>U%Yoknbb~!}nBR0xPl)`mnaHFi& zwXmq*sf&2M68Q(6hSy6{io5Ge4m6`2}reJ#T+VW|2hc9^bU<8-%^}O+g@)cd*`y1tNP5J4hA-}F@tx`Oh zu&IhjtT3QubOMno3-3+HY8KWC(nN(C&wncIE7N6_<+b+r5&xoY}>bYjqoN}X9YPNZ0VrJ*qe9}mH18cNiU0I5JSumso^ z`=98(!@GKi9{(>oe+91`*aEBuqT_mPgrdyt1%L``dpox)e02Oo=c()~5SiRMp{hMdKAsSCq(UwY;?IC2l#n+xJ3keG*g*Ut{t8_({ zj^=Zi2SImECPI^JH~C6N&pL-eoIJi{=Bf%h#1E-qv;2c86?H1* z1;+7Sy3;tuk(srz__N|DYo+{>rcy4^wk$tW!{?|Hb2Q9B4V$2E)ozx*HyPN*0a003 zbs>&T#nezKKdSxNVQ-~|#@4BZKInW%5Ps1{ciu>a| z#l|zsKa<@?iG4RC|w84>}=n1-FYoNc&9;e#>j+iw_>vX+@7Sucz*(-hmX*vZ@azS*c{`@>%rm zPafyhE{$H16&aK_8+(CoXhM3O0(&W3$LhipXcoH~o*ZJ5k65nR&3{^daWadG(1+~k zCUKXW3;!etklDi#gMu$Z(DWw(k#4h>Bl4mbb}6;KQen5Yx?KL+NRzkVSE)OXY4?@N zSwLh1?O>-P;iA9qnKl}1XX2i!)l8-3SG zbTgM2q(a5ayp3MB%Db~3K976u7I<;Y12+3Frn8X?6YjlmUzVn>QT|1@$Ep;AC9NW= z8Doe!l1yY67VK(uL-y@=1Jlan+d7&gNP)s;l-Orc!_2pJ&y4V0%p7=O_~w*yCG-@icL6%l%WSKEdk-=UOY$6RZVg@@QSla$ZScz4UlRIm$NhQn<^@5^`(vTv`;Pqq#dFDyS<2uZGbwt-UHE4vX$rNTUwgg<@`|U*! zcf*3t_H(}3SL*r1>w!#3)qm#RV(~Gf(2Pf7V&j@HWW4qHb!4!Q=s&F->raVw`Ga=_ zo~rS)CtJ(q4|VKNOn4AilO z`Dl`wWPgDSv)a$$e16Z8cV=rA)kRsuF}Zt|RiyVgdL6;1EKSR@HvNylZMqd%+p(^|aORvWL$^=D zh!!<^yURu5EX}g*oIDV^eG)QTvL#{}k@ZLIE0}^NSv|w!40WAb`n#b^XF1!Q=W!mB z`5a9|lt-lgXiBenySJL0<8i*_=5j-K*qt+C&q^L=gd}aR=lsumcrzYEGmc?EG3=OS z*-WJ`S+qW40QbU6UA#L7aUgKd>Gh&)s{S4oFIA}7CjGD=qmJr`{%v`Orbzx#N2OF| z(+?QR6&4{BKRt}7D^NDprG*om_)OlNQ!Vc_F-zc?YWW4$r8m$`EXEKMusao@Am^X0 zk~gs|!zj9rZ8XG0FEI7Fd{~}A8zZNurQR&-U($6`3ctUwCf{~gwlJGvfMH!;fT$4( zg3NVK5b3$ju54IZQGXnrb8rsG;` z=(tNYz6t$Wl!z&W#9H~B*1x$-K4@Y)2G0vpkML<1d|q!Bs%$??8%N10%r!VlfG{jJ zNqEP^GGq0A_jYZublRzu%+|yv3_XDEwgeNcrmo+Vei?z2Rg$WwUxrpxNkWg-An5%w zw9zVQ4*N1TI)>{Vt0(G_pmxwhsGHa-Wj|jg7h%;uiRuo9?{5aw{d=8n?>dkl1=F6%h#!aoNj5V}#*7tZHc3 z7;O*S;lhMG0loks%AO`UJgK*<2=Vp1BWpT33w}GxFAtHKL3s*20vY`;IKsl2XXw2X z!;_TWdS7#neov$+;mZpGzk=i`Ci_Six{2Z6SUTRzg_@eFuGo^&pvEO+=TUXFuf*7z zxET5iE00U2RqRyU)ATk=jsKN)vU`SwPMz(#mRqRxIQx2hL~S+I>%`;m1wY)|LL&X$6}vFSCVfiOd;;=8OB#sU3|Jf3=!C6Q$7~4^q2^EFA=4FW`z9#u zLh^LkfGf#Z)|T)zJ;oLe&!S(k4~JI=^G%f4DyJ!yD@Br!Z70%5wmLBuHg+Yxfx#Lx zA|v=6H=V4uwLtS*;My3xkd==}7*>s)ul{{l%ovtO-Tcn5SuUQwS>9&cjH5lpMjAqn zvg;%Caqk&ekSMfWg_NXzG20Yu%HzPf;ub4=s z?6T<|I-dn3Mbo7$A!%sP*lwe^fW$}pN-MhP0U}Lf3zOn~qPvOoHY-gU6*I6~QDwBH z;6zbQjT7lemGr(#Gu)?L>*H)rv5jQcl2RA#Z7>@QokSuM#f?2boe*`MAd>YSXS+vR zZ~Iwoo{n-`gW47tmr~cK#dnIb%^b4d%J=2FuF&eYt$QuBnP^jNRO@z(^ds89_>?-O z7%B#~V9&LsYE;r^?2+UMA1*Vp4as9@Ci^(~FN0OC9I@Lu*VT8oYEPdMdpI?AJKb`h zJyZ+_U(xAyIy@|Cq@|w`6|F~c*(N6~j~}hwG_nu9W2|)4I69J@9@RedfHAG!F7KP3 zSRDtK{-Qe$Zu$tEe2Oilk*GCjkP$2HAiFkt==dqeu&QjZrx$X0hwoBoWhq5Pu6e1t z+T(l)wKcXQcrUN*aY`QU`ZutQd!L;@J%DI)fqcLp)(SyO05ebtQ~`~E9VqTcv^#*} zK%(6Y`aoaQ1ycM`2hUfa0xVAv;{A_&DFuW0q~!@-Ba|T8O7ng(mgUY z1Wz?u-&?J)Mj^aWNs}=|3TZ`;79l_sLVzx-f97HB#XOZ1>oQt3oa4Uwffy>C`d_}swFN+-Wa6yqvD~`+>>~#{#aVqH_9%cJT zqL2>u^lpkD9vzW6B10unkI|4gB}8jjm6&D7&Axqdb(6f=NDNIp#)O+ZVC->@f!oql zFV_*NvlIO3BsL~fp8?tQ81(Z>k9M*`dbT?zDW9F`KrWCE6apncB~S%40(OAUSU6^t&lsP%Ln!kZyE}XLq0=RhT@#6#&mv!8 zzoN_sq!siEY*c=xMBb|}TQ_!I|8+<6;V{ZjgAW}aMy4GX$28+AOt+8*Q%T|{Drq_} z{1dq@K=c)Za6=2j{`$H{DQ>ltH3*_*V7!qSp2r*E;^i8^|Uou3#(ZM7W}b140u zrKkRluCEQYoTBu2?d7xth2K?AwzM>-%XygvrAOn+9$qbEDRPCZv|P0<4m;=Bke4P> zaQL)Owy|mHDfD6Xe7de*1ApfoL9vZ}ls;s@A?Wj6b{Bj%^*H0$t#q9*`BN4)*%-0l zNIv@AKk-0A|5&9s2>lN+E+s1I!P-YACsX4!U!lj@ww(FMFgkLI=!0z83t2dz*tPwIlwc( zdq6E~pA|v3vc3=M=o*&zU@TowJM%#&rLVKBhbFPtM)#f5z{lO|thvL!1I}xdH){&z zV$Nx>%bWR_HmLlwKc|UuQJ5gW;ty$h- ztd=+D()Jxb!SK~eX|Ky5ny}z$rc!#@b}kWw^YSs4H%CWH zSkausaYGwOgSxKUsq-kZE?L7Pt2zrMv!B|=_Z1HTi^ZW+Hi|jkV257{8;_faKsj&BIFuWci4b#WMN+s<*pTqXj7*65-WHme5g~#gDr>oFDn0 z9GNW65zXT1R`O*)MvrqTn>kk(U4^J51baRop?%T6qSB7x`O#sdF6Baft(KL}4GtZC zVfCbrX4)mVV>)-Zk9ABgz^t(PxzSULuN>=G_qg8$#M}#OyKdf6bO|>hGsbjoa{Fb~ zcDZk14vq6=WtTT9H{eOj<(xwrG&m#7mOvuJ8xI%CM_A0fFN4RzwZ|=QwQiB0GU6JN zrjTYb*SuJ2WHIv-XgkZAzhOWN+-|6Qm#ooTkcm;*N!#g|Q}Pb>-TctRo8~BMU}pFV zx>I32Et3-A-MLHqx2i}*`Zl@U?2T!kKPQhPR|g8xUZ#6E*oS+u6>QAIQ|V;({KN6| z9#)N{M;4=xB-3Bns7DeFf)pWBt^d6?k%!q_-?W6NL(zJFj2i)dVOt)_ru*6XN0L+P zdJJL`q9R46Li%gZ-HbkI&|xKTZ_(}i1UJ&##?O&-^1YzMP4PB~vIbX2ZNp{GsIir? zjNI%2pL-6r`}vuxlSXW8(64Nfj~Rp0PGaSJnCle6d)R@zVSx`H#R5qU#nOs_(W~rg z-m{dk`3n*ePie`WkTJ8KO3= zWBnc-k-DMTh%o#{cV#t}qcIA$snK zoWFMcnq{tdWT>V$-kyKXv7_P5)WirUVi zTXX$L=@gxU8M1^|qpa9&r8?Mpv&VRp!oklYZ#w8u?Q&(inhMe|Hff>GlJ36Sb>1Rs zuzR~}bRTxSyTY(C(o$t7df)ay#ax2+=Qha|`Ax{jH_5MQo8&U>vyPBPws_I-G52?C z>g(Huz=17g@+2ck2x%~hR7WvO*w;q=%HXsUpnM3nTYT(jiY89vP1CZ!Es7e@qC(_` zFl4c;MldSB-0eKud9HON>s}Nab*8(rzFeNCZHp4d(qY-xe^B_h^yyOEDwBU<;}@Go zTU_Dr5JeWB<}23lYWSi&K^o%ecJAmD#KZCpqftys-V>hMPH0o>NE57QE2OX^Y~Nz7 zcgpx?i=X%MXD%$m#t`<+;)i{H$$v+_!Nxqch)!T{Jf@?G?D%8J)Xh2`Ga!6V?_iGiI< zOTNpkTuG(4J31GL~~rwU5(Sh1AvaoxJwVh4VcL0d}evIu%_D3RXs47XnrGBN*CX`@rPU zaxl44Pe=JAw&C-~5n{ewXcVMUw+_pOPw5oB$GNE?Y5g~{TN8P|x>LB>$KtqCkHmd% z=SfJONFy~}&KG*jH~+qBQ_Wi)>z=4?vjk>ewqVL5lP=os+eM^v?C3Jn+#&~TYxmUfUPah>x+~($=N+zvzR7!P-p3Sqb4%H7=jNjo z>4oAuc)&3~&e@&sI#|kzhXO7mL3($(a@ejF(etCHZmQZV$L0EToO}{5(D;oJ z;&(I<i>xoQYR8-!Ru1+x^G<+-*k`QglApF)l_$7CDv4> z+xdFuANRx=>*gw+vsWBcipbkbAHzo}t2DMc z?Cx2blmh02LqtC^>?AzMu zg7k0Pn@9DOBMd`oSR7YdE*ERgBZ#ml40N4 zc~zQ>*rZ+P3c{zQZN@VWL@9%RjF^nt-#Oe)70eeKeMOp3EQZ;QhB`!@JoY<}*v?Qr zT~w3`(ziW|T?vStri+5~_nvK#!tM;?5eJAC?J)~o%KOiIGu}Kj;K7^vI8pQ9PhID6 zuJUka=*;#JOR-x0#hqdWPC~WpD{AY>&=gVOJ%ZiN56L#5@uX_ z*8PqnOXMlLlSUpYpF}8ZN8+28n@~pU(uN>i5M`aag2}JpU`xf9g?iBO&2&hgp+4*N z>&tK&`zF0>iM>R}DH39k(rz-UI(_8u>xw`>JA%rm3>7(OGrjzOC@S;D7 zd!>b;UTI@GKakHl6!5csTl(m!4kmO4t49wD(*wLZ2hzPmQ`GAMcp`>a14Oqo)6+N3 z4;wLF)LPxndQWA$zv3awL#YMGWg%}MxCj7QC4bRl>N0o)c1)y($Gh%Y~QC6O6Wl&M(s<_+WIy4#<7pM zok4h|vc+H5`!v{tSmvO|`H@G7PyRf(otbt{-W;UmQE&zFo8jU`?>=MSueu+3yrEA- zM-{nMVjvn{;4X}UFID8V`BGlfwmu{>;@_qp{KC zfP@>(W3?`{|Ww)RG$0=}xaodQc+6F+!i*NS?>(qx>;Z|BhiZs*foJkdtS z85WR)-k9^z7O4d9l{3J8YQ-kStHtMOw2cGO~jLK_M(*u@O?L^Uvj}hFJ^5~F9 zxr!{aj1yGajy#hF9Uz|}Qs#HBEUJyj&rd(1AzH=n|M<{k3{U5C%szT*fojcBZ*kDm zkp;;vV|}(XJ!gnS%r56}S6p?9s9THo;PXW2(Oj$S9PWu1UCvQ5l0UM`xdgs51zW4F zlgkEqOrq>u?bR3zjd^mmv_406F7>#a54dz|1@X$VUR&RNBHNCkMH*}@K}tC$NRyAj zrLm8n-kv(Pi-(k^+-UD6B~DLFIQlXe5Tv!o)VOdju@S;!o#LthQF*}Updc;oB7;?8 zNJbo{dmk%Wo2J?1`p%)|7Bh98_>!k`rZ8G|wD~H}cRHVEInT_e)7Xd4 zqzY~gyZOv@PX4v-gMqr9@alzDA+xcS82Dh`_c{OH93@`;cMm)8>{{W0&zXMxVjm;; z53m>4Pet!Zy7aFRHT4E4rLT9?8+GO4NLED^cwr;FF?=!*QminADAy{5pT+NF!Th zXKSZQ)MD7LbyCDEGU9u`4B0uNb5gY+?eEH#p2GyhcFN9(?tB{@YZp!FtPL(qq^gkq zL_55Ri5oZFE&hGu3>w08nf ziih&e69dkn;kN;zB<7IXtDE=GAkHEh!AwT4q+ArjUfi1PRpi`WPV3g~q5N}A{j0DJ zJ(5Dr{6o+ww(a@1`&HqcT*~!Zg4x*O34Q)}tld-`M#K1X?{MVbY3k0SEy1-PZ0kqq zdS-j!J3s!v4!`2x;_BJ{?f(RC!;Z)41GT^I7^kF7EWY%TPbCyC)cWmIP@yt}^<&>~ z@)H{p#!oOs)|IXWO2rUW z0Q>-o(<;KamBkgKIeER}x%k{LqLnZ{yuP~biI0?76_4S=CxXy#x)gdLD>A>w!DYE@ z(ypVtlCXP0ALR*L*<-wSpOw2OaP9}Y$8vIgcM>Oq_ISyRJv(VGySC?VoLBSO3>7zI z4`F@wKF2vP>^*arv*7g`s^w^j{|WZs8wKn2_XMgr1w&2Oapn6S<(SahW! zvJw&=4SeWPWS(gyNsZx_HcHjD$}l#kvL@*e#PEn~qpCB1dzbejH$R>8h>@82C=II@ z+6yg0hcao#QZ73X#wNU}7eE%gIj!G)CyDx7X!nAB`evr83XfO9SiiT12vuQh^jmsP z=DhXIAU=Lt3`aOHwHAIXbLKKd+RTMKAJ!OBJMHb~D3&cf6{cvs_2rDT+k|}9{)(c-e92LKf=xJJ5n8+1rUPI3yqH4NrL{Q+ z4K$~20`>qf-;Dof1NNhQ5O^P`2Jq3u`?o)psMi2K7U+T21F0xK1G*8|26O-~vJ>yl zE$|cZVH^MC$`OEa5D*GP{E5$HCOnSiDp6}Ve@+vGpW$Fm^^N^$)-2wX+^H0U#+&7c>6T_~Riy<30O zUoe6|4lw2p5(`kct1t`YJYY7U17d-A;I4cx%KL$BKq*iM)B|_r%_z5);N_s_ffK+f z;52Yo=WfGSO@$s1Ys1g4z+PY*&<#vNtLZ~T?LtM4XtwJ8;DRxbj0aM=29N>d0JDMl zKpwCNSOTm7+ELR7R{VetlsUQqZt-q&A|Q(eq5&Q7zt;5e*(6eZVm1bQ9{L7w#X3CO zfNJ*Z`{N2az;yw!52Ja&|1z}*vL(P8;QxAM2jnhbMJ@&h_+R#HkR8t@i`C;7Vhn)) zrMMBYExU^oc;FTFa*>VZX%K^OQBJr?j`(VaC*Na+gft9)#cRhR+bec;+!bZaB_ zFyMzYo5f~V2@U<4T^`Ne5) zg_9sW55{cJ`G7zbcQ*?0*@59g16@G$_CIz|Ii5G-IR|tXa02Ce(D9rH%tCoK5P|vu zFTuu(7$x8`c=LfgVAjfID<6NF-K=>y@yO>GT;MqH1@JX+2515P1^fuK0TQQdL+u-5 zGTy}K0IPucz!G2})F+pUF_ s_&>DI$FqKQk*cO+2qurQ5p@>fTz~dN-4_U`$9(jqaJxSfKHmBN0Gap5(f|Me delta 12553 zcmaKS4P2B}_W!-lyf7%jD5AWG%!?>EV#DAIW+n_eys4;VS-vc&*rs$H2xbti+U<~^j*pu@obHP)1GA2~du`Up`q0UbbW z9Z}5!a^E7VwZJxDA5aIJ1Fiv6HNWkJ_gI29Ew$V4ngX}%BC6$kh-xorOWpRn&u>o( z2;6KUs`|-96`781w$Rz zvjql^oL5f>ACyBzG(=5QsypO5Awy2 zO=JHKT0=*(T=lyldBU?xR9c-_EIgYNZhh7|$Ep%5SyMl9Qz+UI(mRHpe?Qa_Ojfh;I^ zTrPiCxs;_-<6VU&xn*~Kxn%6;ke<|$*!~UcwOJ3^R_+de&8)l}k^ZH1PssAyvE_J5>Et*MZVM!Bm!pw3AesE#XNEKSk%p42F%nF>-#LqT0>q1r59%CTl_TsUIaZN(uXN7_|QP>r#j$L()XoSNB_H(E`TKuIU@>jKrSn(TjPp8pF z&Lre^3h@`;^&F9O{o-v6Loy?*&6v}#r848r)Cy@xKN6cH{;` zB&uliFl@A;L}ddl1=hx3gMn_2{w>CW&v_9KsrSFg+yL+IKm(uvo_;7h5M|!>ASh}5 zeZfqkjqFzV(IU?Q=YPigZ0tn$%b$?ex`I1SEVDpjb~Wh=D5ZPF>rAC8JlWEq^zBT&?k=tfMuWvQ`I}#+}kq^v+8f2}n zuNxr^)|8s>H(kJL2-*u$o=|jJdd%b}e$|=lloiUvi85*^dhqBcpA|wsS!G$3G}tuT zSs@u_=4O%!p$#;e&ufJ=+@!P;c0n2nn~B!Z9ham7(+{MkI7`uDfpH>~FUC$QdNBSI zsxL-)jB{3IN!h8g2y2z}hPp~B*EHvyufh8ClXhZ(hN0mVzbe>Vl4~D3IUq_uDgCsR zXiCfWxu>?Pb;+5}=5ULgqbzDwpvz5CmWi;510#y2>RdNduMQ9=x<_V_B{D-hG)N zu|cMT2H3R00i78;{(a9Po?4mXG_gI|Bz! zU-xm!&z9i#x*GlQ<3(DH#piyq^X;46vnyauwtqa?N=4#TJh97(?zGZ8y|?0TrKe_;oS zxz<$ttBUV@Y(UuH;B%-r{hNv}S!!5Ls_U4$a?TW zN`;iIqb5NN5;md4UWypLC|d`ie*aO#Vwir)b*5PzWbJ0z& z;ds(TG=*gFg$wTT4SXRh@M0U6G0}ux2Cf2A4H{I`^X5h;*MxWdv$MzXi*@DL6y=ge zr?BicmmVJCAVcO)3%VY$WM^uE)z6hnXXjC!%zCb7j+KtunW`GG1M)$R?~;N=8kAsl z)->mhv&gJBo38$<{@+cTC5@>L_FE@a6lr#w`=i_RX+4c@ppo1~&{fYb%(TA z+nmQ+$*gl$>`dit`IFAtJEa=sCy3sWN14n@4_2a@R&JI)C!3`+M%iJ}zA%a!CN%4& z{i`OSyGuxztWoLHm!q@%t!7gb4%ZnEyQJ09`)XOr1?K?P6d6*avs}(QTZ|(sTUGLF z1rn@~hf8><5|r#w$z(m`lx2qFm%pW?=1ZI=J;yJ%8q)g4D!9~@Gi|k!rg6VS8ijZx*$oK%J8!W#pMdA$(VgVS+)tZ0^VYd z&0sy!rO6R#ks9NHCVa0?gPWUbdZMd#vAX+U*#y7E>!zY^5Mb1eudVQen%JemBjb&x z0gf_rpUZr^Z1ZtPD`@RM79{zJM~?DFMw7|*YwkfdI%+g6WXqzWXBhjPb@Cw=)R7?y zOTaX4K602t zC_@V0oOVy-bt<0kxFD^A!c%lKL4iPNo$0hxD3IY+#|0eCADVN{zmiF{5!O&FXeDBj zPG|SlKESdxtSIk)wBFTJ<40T-#n@4p$^zYP96e+_P7L^>O;Ul$=l)j0u``p3=^fma zqpZ8?r^Nd|(ga@Qt>)M+v}`loMogmoTCF`Tjhcz@feX zX{l^xc+LfBHP|M@;N}aG)pS3+w)LeV{rL;hB5->dMmDQ3_$&{JF*ix}3sPAZH={XA zB<7KDtv#);W06ivt7rP$2G4)`x%xHdS{L}-=Ow;~6A>a3v0qzJPxp?lW{c45ukBo5 zYR7w_kc)T`Eo2QPJR4WGXU3vlZ#e zH2aULBqDxuw5N+_5cG!_h)Ry;#=4YH9xX6Qm}!&R;+Z+7*}tLRtmy(flFDy}K8ACZ=Jam&3w zi>=PQyFOn*o!qi8lu1|E4Sl3ysTS>+Y)E{sH`d5oe<(a6g`3#pL&ju>D7|WVDp_n4$Q-)9xV} zjivW>yGPKp;Yq1+BVIuhU9?FUU}8^2>-@Fe&E_@-6(d|W zno>O85ty#AD8)}ZG2Zz1^*Ry6MV&w7dx^FTJ{q3*

4EoIr${;tY^M?f$koy2~p*E`1VhjGw6TL9eKK%qy@#S#X
ziAv;U;Oq%zHoWpk@A{po8r-5pCn2)J-UhitNSH3^ap4($0=_!+x4a?DZFrIXfvp&k
zNsq8&BW%HZ&&IV#DY87dg&49NL>$bD;-YD9Rvq^)W_a?*^x(PeG)-ln1j#hu@;E5L
z_Kh?ISHi=newoW8%;hxp?Z^;e^-=coNZt5j?Nu8(-0yq)q<6Smy^A*lq{}Uz-)~fQ
zxL@xe_5M?`L|+0fxU9o{zN4{*lqXo!+8B%Q0Tqkc6OWvve`X=Zv9yv+HOAAOtjMUR
zud)636>7gQhR{B_9rD|g<@CV&Wkh_LwZuO{Q(2fP5;~7H4eL9k!)RGRVk7-Ty_X&!
zVj^2%idFb^5OEvZYZ@J;?2sKc+7oe>$*0Cx=qRPQ(4!uqaA_3orbK%cbD5I$iFLi2
z{ieuoC-twk@_qP%C&aejy4Osbuv6_+)9$QdB?%!>Z+NEKl<=|%wg9be9rX$cyRFo;
zI~)CAzV@)XgmE;R{X605Av(_tONaYKPw(Bz%3kG;P-^UOhkANdQcEcKQEeS=nZ%Zk
zG6(KK!?QlRT)$29nzlZakdy(%C`0xxaz;*
zR7kY%X&@>!e4G*1)W9Og4pV+~3>I^oWsKDfd>
zQ6hoDlO-y<5pu=T=MXaH6JY
zPJ5CqSUV7oadG<;T}XOas8aO$s6KeA(fZ*kBq|UUDaHPn2bnmoQ-d&pr!KtKfQ%!W
zD>+KhB^j;Vu@jew>2%{58wDkJI)y94x56YS&6Ss9@H8{j$}EWwH={a~`GnX&`HDU`DJLpSM9rgf)s|yCu6uwMeCjkIZ1DI~@eQ4wPNmrIs8SpR
zNcB=(AB&%*FK%Q5u!VMZ$}O*$D;flgc~Gn+5u9As_pzw~Q#$F;`%W^{g%Fc1eQdD+
za{jR~ob;M-oH}a1m=H$&ANdrQQjJm^##$a}8mTm;1jl
zk%Ge){J?ScN@^lq%^Fg*fm``IA6EQ$oZU?wIxqlk7;>Zsd>?hXA7_R%t#H83rllF_
zNLG|Kkm_pRNlTzKpZz7>E{OKp*D_WM^aAruiKa2N(NohY9mG~ldy})K#R`QdYKLd-
zfh%WUOwSQ6d)e?AZ_{n;SfX
zu=EP)aPMI$Pig5^mitsREv()8l$+uZDxE!9&L^EYW)B*7@;PK>aB4NKC`c_wVvkoi
zq{c2PtaBhTZA$8$(g<3R$}>1NP{JvTd*+;8QgeCEui+cS&mXWr-N&ZPZ1_os%|I
zl{_d)PP3SFbF3wzk0L*ixdp2*VSYqxOHx-<`052|Jh?GQ5Lfy(Nh_y+j@$`p2*H^V
zJNL~~+^yVUgJh$y+-0788ODS%yq}xw9v2Pa3W*={^lR+^2Al{K@zk5<-5L
z<+#xOL?W!gwumjKk&;u}AF%D&Sp(nk9d!BoC)rFROB!_f&C(HLaLQTf2y$MZn;D?y}N?;c{%@ZYVri}@2m;Q
zk9o|sP~Uf(@3fRxoa|JTbLn<>6N_FH)sIh0^)#Y71mvzIs*`KkQ;SB%u4^(PB0kko
zWrHCaBk=pebP_kyp+GuiRn*lQr6J}rm$0!ziw4qJ?98IkPaa%u$gs7QxMoUv%?|0X
zF*Zvu{MmcYopozQ-+0GKgZEi%?5u+|Y
zIOPoHo9nyPtZ<+&b&Q4gt@E87RW-S}3HDhUZ@KA2z5zCX$To|(97=>jIPxEpRQ0HT
zv%`I@?Lv!*r7w<#>s_%pjDF9yERG*D#S@BsT547_UAKnX-~)05vAwgy{dSvRIU?OO
z8ZD-T%FtvNp{H9+@#rZ_5Pxc5;$ltL4D%Oqqpe#?RM_IW=jJQEFZhFWlWl%3m-c73
zpVLwq>tjuz4_LBQPxrH2>oNsjnmBgRs_k>Dk<=Y`(ICGjhxCBSmKbOadt^yiNDYFx
z+wdgZpp3)%Sc0c~D@|wfmKYxOYsZQis}@JpcU$sJm_zrRUh=d)oPoRb
z>2!;Z7TEd34zvuiC@p96`&ioDFLpeAOD;-!Aze1-rA)h^AaZ8C4fEg?wZD4X2ZF(_e-6igiTbd+Mm
zPfZu4PvIrsXpglRi?GY3tSLI5`<({Ux=Ydnb@(Jzn{cm}x#eLa67#(SiM$0o&qQjx
z?xxP9dw+Yrv}S+nORH*brvzo)N})MdlI}T8m!#wBq*COg*F6ROlyND%^{UF
zmym|zs{GEOyVYCx98clBQgFlCcq_PHe90|ACKH2XDYt0w@D*~G?{SQ)w{SZ!V1dP$
zzC$V`{?;oJDIi|z^79h$BAb;LU$oiT?!Mu>h|dcbkrpiuO}R~FubNlimdP3(%>3j>
z>{LFic6Z$|D5cq2!(Sil;CZ9q^PjbP7WySr*6c#2vDlL44DZDic{Yh>pv|{r!PQP;
zc+>HkQ*iJh-f|LsSy!4a4tqTh2Zt5OncI2(xd)62OF6E1QypYz+!T51fEW4cL&d$G
z>$V-zM@FAP=FsI|NjmS>|KdgIfaWz^abqkyr1v#MT<^g;kNTteho+%6)EVjcGx&wh
zrQLnJj5N|+N4tADduDm`qZgz`I1~OWH+wq#<1^1I22PJYSXgFs-Fr+3VUmjiSc
z@uYCQPdnT%wC#t%vIEO!`=3Exk}vpp)+av_Zo!Zr@l;J~+CwensU${fTDJTi-#*xyA(+K-=|^MAv5?G&LPPCYT|r&&
z6rK;N4pmwNuWZ)F!}R(`NGf*EM5T0g6p8uS@iyA@w(&27bw~-6uk_0#Z~LVQqOF7K
zUqKzO;RjuL5l$$+&8mxtNW(AwMqFME*qNZI2hV05Y^P;TWhhA8u~em`Xkc1
zVjk^WKr|CWJu9$}rcoZ)6h3=@%~x8WEZ-;^a%RhHPxzXHeHUE}~|hDc;|j~i8O3U?G%{HqqS
zQ*Sj{zAlmuRQ1yGsdA)pv;R${bf6%ltM1cOI$9OijKtw#qij4i^lt8@qgr&L)mweK
zukod_PnX<*)NX6-Ho!#OEr^x7*q400WBjpcVl5hLySv3#k***9F%^j5?+Nv_@|1!%sj?-lcDLobco
zwMQwG(}PCL)|bA*`Zd_Mdq}%`5?&^64$yW#J?%pna1fvWd~(<=4-%h9`PT{_NbWQz
zHiY_Fu6At~w(hZ2C-s(XC0qsFG;esyT50zuHMqs^mrp1
zux6z2O(V0c(F6yyHP)!@G@*~-ZquV04|FlIwQJ@CUEACp)d}K{9qsNh?7KCwL*DT&
zuh%b4z=^p(haPBmf9U0TAUa;ZfEa#mx(`RK_A=uO8w8_=9e!a5ZD1E)hxHUQ7%j2{7?8vUoN!-4uJdC9fK%Vrt3Rlg&
zc0zb0Qg*nHMSehWP!Jb;$q=Qbe|ij-yP4_Nrl|kq`PQl8J(L_q%VQ_m3v2U&ntfGI
z2xBDYZ9n!n+qY-n^T{kf#s8s2
zj?M*%rL8Lz4xD1A)-6_S0{;k$TR)Xb?B(^bf@drH!+KnPUt|AV|BA40Ywh9O#EPATwj8EQuSt!NU8}n6*utjHywJ0-_mV4cQ_KD7JQ5X&u_W|C~
z0Von>F|Rkkmtj#$%msA;mJmyLv*aGGWOS)bfE5x=xFxTqK!tLkKF
zaCkoc!Nlht(op^j@5_h0@P?{ic#RKv>W0I=@c#6Wr)+5ah4;}zUi%5hFTD32^6s6u
z4j$2mF;=<;cUk{U%LMT=_QIwUco@BTVxLj?Nbn>;JsGKZqAlhw}w=pF6y3wJ-(
z>b4A^1Nd|IbQC;P^{r!x{cESa7D(wgY~I#y{rPwOsk@PiV3S|}2Y8X&R?s80+qR9D
z(@=J9`&9+OVKlDx;9D{(kP!AUyTr*W6+;K`Q%aV3#TvX!e~Zw*3qz9%QW3wOs`#6N
zSE<>x9eVcZ4vhfjl^teI2EY9tC#T--dU|}<05<3yE9boO&H?$+V2kW|D6;M^JeayspK6QL)ZsJpJqS5Ywq(C
ziVpx0kl5rZ1NPv`s#HY@>|A2@Dt$N^$kp|^Kk>;j&bJU#W2pHyrSR?pSzA?&DFD^*
zh=mchjGsT?qsT5u;k{{r6<-k5W039!
zoBv*hQjN!?f$Zb=h6?I|?9zKWPTJnPG?>rdYD`BSaHs};EaQn~vXmzl7QhEtwovUn)ux@t<6^u7i3y?5sI~yRP~Hpd1F8Y?@NZW#Q7r*H
zz!u;TFxrg&$pl>ktOr_v5|;bnoT8@5M70C|8Om`H<;%b|;Kr}`yv~E?4j{yWf8qpU
zfjA%@=y@}j>nVq%LJpXP`e%T7zmm&AITu)BAw{a?zp98vg9!jvY9;t
z3-G^eddo8y4zO}Ah6ZrC^?2S4RI_a#k1w)=dlI-a5Bkji-#x{lE*_Ww{9kXhqy8i?
zIvaBX{4dQmqi#z!S*%hl#OeY6OE4XEQ-K+|7zXga!HfXWH^unRC}prb>0-huL0z?NnB_g2t)AS@57
z51LZ~ML_og`+#cTE3`WZdI(@@Tj9)B2u;`sfl?S0sC_duL%AM^gk}GL`a1AC@a#f)
zJt)79#&OE)(BTf0cLC9mzqW~8u?-Cgc?I?g@Qu@oE?s~>3#r*!bZ84aQyH{`#YX~K
zAR34TcA!PySD_(b1LDD}19gEv8s%M}T0BocIT@G?Tt;7Kz;6QPp>G$SPokWTx~V`8
zo|gbKP@Xjn-me;!qaj!iY6k@RpViIXijH5yUI*3#J@|WeWc#-|Sc79yIXBa0C0)zt^U??yGFae3cL|_u9
zEcVE|;|^9~c7P_p4x9t(fPKI=;2N;dNJtWn<{qW1xWzVW9ogeQa9
J2Y-I+{{iC1Je2?d

diff --git a/Tools/IO_Firmware/iofirmware_f103_8MHz_highpolh.bin b/Tools/IO_Firmware/iofirmware_f103_8MHz_highpolh.bin
index a17db83ef58c18393e242a2a57a0747707953492..04a25723c84407f7d52dda07a0c8dde5e9cf4526 100755
GIT binary patch
delta 8716
zcmaKx3tUvyzQ@ttVDTq5>fj1$g9v7!Tu=vzy9%l>+YD4nVN${83UGq
zz2H+&`3g}sfSaHVs5TL$9z=uf1O8YDui!57aJeq4TW;U|{!rDjt;mo|l$#)D?!IC7
z%7`G!8xx5#u5=mIdU+~EFG(q0WV`yrM>yO{@wnta#eeEai|pHHBzZ_~e4B%c;cfk=
z^#6m+Q~V!B`-b#apCrn98PQGm=;neid%UknIl}eO;VEi5+0wo>LcdSg2=ABZN_NP5
zwSOm_yG*GM6|;o78Ns%>wsf1PxSfTmA|`a|_uEqCic5vI5c#uJ)Q}^6Z_byln~8B$
zy+>&B{j50sWZhH`ahT+Gn%p`o742=@PEv+hJwz?rty(nUjE3lln#K}u8oORebnj!7
zGRx~FZ~cI2)l#RfUQ+9$Y}FFc*GqnSg|%9eLkrZC!PSyd-^6D0n;OjX#5Z5DLA}qMOA{5JZ!eQ}n7k9u-Ih%}+#xd*-<~mOOcl=wG%VC-aM+%QWzquE6;IDg#BfA9
zZE`ycA0Cm4iMrD5JOJ%9aXa_0{;7XU3DN%<}B@a_f2HmSQ5lm8EJLZ6xB6tTD#q24TG*
zPLL^a|36toClqH^)tiL;1S-D9oNBF|R5|rTIVqGV-v*n(T5ufH>HbKJq5EFn
zBWaI()X#x@mq0Bj1@n4*Wmw>t!f|8twPTesFF*>W~%Y7D=bfD;-ojmuN`q8<{nZ?A&iXi!eW8
zTh6cz{Rc&-CDcgg&65|noqb&D(Ai0IGx+RD_prBGKj>aFamZ67Ei}b+$vviVjzpHy
z|1sYpJe%PTYS@BQn=VJXW;U>o`-j-C>iryBa;c$6TCBU}sBfl*>gK72KIp1ClAv)O
zC^ri_g%_V#MVS26Qlq);r{Rg&x&3WLQm*Oi6`x6WOyW<;_cyNHl3UvG>phuqY?TaU
zZiDZ6^FMx?^lRTmTXOeX?Dr3y8qhOeuB<4CCw^GyHKuPKaoByzk7f8iHYMlO#0OU2
z!(Ev^Kebq|v$~!09+v;qJ#GS;R(xubjf$%~6iZJ0p-Kkl)FpiM)fiB+B6L`v~Lm~jjnrbhpa4!zwO|K{9bppgSUkj{=m^2
zamDgHOyNAKSdYkQ$u1sTPr}wF`&?6IZ9I|J!!U^
zf0oH+)t5=5Q{)i~>%*Ib7#fk@^z>93YV3+|>9&G+qb*+=t#4YvGs$dMRu{zcto&}c
zt?$Gm(20Sv`hQuGtXQmEK1eW{n?_Fi`E*oQnY@HZ+lYkeD`m56>8oD1OliPoHv@&D
zO{3@$>4=F=ER&u>6=QM7txsrVsOTy45h+%4-T^z(p3<|4ha1YISUu9s`z;3=&N~8<
zf^BCUek>)(-#*-WdBypx_EM2tXh}9Jq$<;Hr5>SL#xA_m;8~Pl~5qMcPSFtsh^S-*(K*
z<_AA+t~LkM=UP;kd1%<>=HXS)SKi8u^$;6B;+d+=ktL5>>sV!QG@5ZQIBZxohK_eD
zvz!c8SiPt1#XOW_e*S~cM4!6TUiDG7z0wDI78?@i)9pwxsr%`$q}lT!2D^7;KK57|
zRnxphMz8=6XPxkzeJLN&jEu(yhX|4*kw~{w*M{hyO2tGM57p2^uXuV`YowF9eqG+_
zC5_E%B5&iw;PH)GUnA9|U?(R;9MRs0z2bK8d1F))jyV=ALtWgOkq
zC`smf!KJMm?c=|0ly5I6n!wE;D6o_*A
z7$-F)i^LL+$k|h}@jM2!Mv|wxolm3fy;Yq1hFhf!xAV5d2fXN^&PqfTTG?IknXX*-
zQ`}COi>K$f{F4F_yTeD}DrOnbkdJL-#?uu#D}P29m@3|;0*n1Y+6TuSys-D%MMxgz
zyEjV@@!dAw=~I}9*Adov-0X@pEJ$lq@Q1R3C1}kaCQY_*7yh7jcn
z=%(_Cfdo4hRO~+q3?P=`SB*!ibF?&;eL5&aK;pGQk;1!X)?YVk=qu<-y_)FM<^87gOYoVj5NAE?m!PvM
z#MFm6gAnSSpwlYE6YNc$R>S?8iimOqSY(n_6*QXTtBAD2|<(y#YUR3#}VlW^}U
zjWq~GWV<|h)o3$tg&(N?mg
zR#K1cI;dw1v&zMM7oylAV}^ibh{Ho+jpP^E-9a3^L-z-tZf&2}ygF#RpVirRry};HPUKZ4c
zN`EnIqjUpX7dAWKz)_;)4Icpc@4!4*$ELKFsdIJtr3b2}Bud@gZu=E&{)>(v_w`l+Izh%uyaA-a#LZu+PmyXaT!x
zetq8bzC^bGWP&?~@t7g=KrAQ%#h@D0gIsT-+X-@2M3)08_rg>HllveK?ytkgTTXOJ
zuoFJ#*`-K**fV(H$iAn^RaQ2^H>*5sT3B+_f_7V2QkgDzfkK?prVtmikf;dz_Kw&R
zU;Sg4miZl1Lj4nR0~O-S52?X-s>$}=TA3{b5ndr$a4-_Y0klK1X&;t6oFz;4e9|OWeKh0
zqs&KpCmtCe<(?5As+)tvO>vlHaOfTS0?f}1uw6$1oyQ=(*udy#)!08PNmV`^dEd`y
z*pBGW68zl{9SYG}p%52>0ToiY%Iay=Sch2yu#AIUa_crrewARg3<$T5g~idSvr3gX
z1nYAxW2=;~)Spq7D8vS~cl3Cygoe?T^hfsQ7$>!{*T(AUId**PAo^ix-PjaL14~1m
zXr(m1RP&@!=A~^<7GFr|bOy0W6O5Wh^z5&GZ%m*`vIYD(+-I97q^l;KK~+7LQLK5w
zP)uD->==5VCB&M8Zs9FdW$hnvtg3&Q+&U1=_A|Xe@f~h%w&m`gA3`Gkt(xwUndIl5%wz4^l7X5H6Wt%GcvWHCOpt)DaUj
zIB@+3Q=paGg)Tiap6gP%ht2!A^@f_}j+
zrp}<>GyRNc`YW3~!)X7meP>Syc^0!tjYXUZ`3g{4X#y1sKFWc3DfdwfsQ??GWxEU0ry(v~{vw`E?$AY1Ea|JkN}Y
zg{SX1aPC;`c^RcK_Y5z6u8EzNC!X%OcaN9dfcEfq@NgE|ZI4ey;eae^`c(^s8jSZuw^>F*Y-jm;)zm@}S!$DW&`*Z%`wa;}*oqe22F
z-KGkYwWiq=U3p826~sMfu?nl!vqN+C(mQNS+BkZbtw|e6FR?>u{yty2uR4layaZwR
zwaY|wvD&mjitjStldiGmv=FRP#oVD@KbWXd(SR2=7Cm>U{}I#XmwYQsXWh=wD$`la
z9BiLQ*qXUo%MZG2X&OEU{XoX@8Zj<>GjTcp8|T3vP3Q2A>3La>gXE7S#O7NPvb_fH
z?dnP%X57x7tN0vb7v{#IQdN2kJJaPbN2
za?W#Qh2R_@%ed`HF(F=TcYetV(`&W70k;3bG%TO^SKkuZWbB`v)G%=^FDHv_dUhyY
zoR2;`(%1Qsx>5}vxi!5cYgufG%XyMHp55Mc#H(iO=8dG++0l7=-=_BJ)9OkZr854~
z@Pw`nlWY{bJTG0XSdD3qHVNX7F6_x2?CJT#464qR6^0k0Dv05o40_Dv)OX5?O_g-K
zVIeU-Xt?KaIh)v<^X>F+%;&i<`WlOVE@EV6M|DWXZ6!TsS<^yf%{cPn31;_>qb!MU
zD}wkQwiz|LFo*4aE-9!0qsK>1_S<)`8dD&G;(FHl+#-dFKL<8%L5SVA!&H$hPEQ#k
zlGt{qcgL`ju~z+hK0~Ou?Cb&?Y;EDzcBg;4Aim{pcN#hnK*cWTw{+X<(=s@wSK=mWITJ*BYF_qo|LG@)@;-{-gWUTMSuUIGc3yK=-cn-Qo>NtZ0=sREJ+^68HNV-u
z?6Eyv)%csOy2tiJ)sO7P3g6-Pe@i*plQN`A{$6jXhkI-Ts{Gz#16OXOqu9Qc%Z0)3
zF^^TB1dQ_GYfm!*5r8!Vii2SAWLE{7j4L0vzuEA}6ulrSE4J
zQVll|wGc}VC(3z}H%oglxyzATyDjA}z8=62>#A&g=1K_@$XFW7PyX6$Hf!x0{l=o1
zJeg;xSF>N&KGo;<+tMdq3ZQfZOIhbD)T>LEuIoqXOKja=zVPB-r6RWB{{}Yc<-fzG
zUH>5+ReEXtcsZTIG@Gt?6u?1SSo-TGf#Mw6`s&|ty=WgQ;DqwP{y7()WF6*W;bsdL
z?{0pTiy>Q%$p@c>^7WR{3LZgrGgWr9nj-Od|`Rd6|+J(`#PZT73-b9`}BLZ^9w%JLWgCQmAOo`^y_5zE?T
zp+Zt{=0gWho5MEee9SXFwRIX7Z)|;ni!ZlEa`CWRL~h%IvrFx^C~j-t)|K@5YhC`Y
zzV?e^G3wgM*5oF8@e*@zm&@vMqaL|aY>!v9Jj|^8Jw0vv44TK@-~Je`wc987A3!cd
zjP)TUi4RWj_ASVaKfr=^gkV6UcNlO@+mRfacZw)4z_S-2Nrt1VEO9Qpi(s$!Wnbln>vdm>>8aUe#5Jbtx~%KEx9j@puIFJ7e`77K
z2j5tYcPiDJ9|*^M*(Yz#qHi<*yss2-QTP~NdNa>JQ+7RpB0=<%M7a`dg1#AS1=|7X
z`K^n=cXdFYBFZI@hZtqT-hnozr1S|t9!5Xj*^kxp4_`5zS8IJ{IfP@}m
zAbWk6Kwkrv0W*jO<3Mlv`_Rk5K07XlKrN^Py$&~^Yd2!3A#Z|9;4-)hdVSVRCdyr4
zYCH-9`#>Go0G5EuK#z3Ibc{j|ZFocq*u8)X*fqHLgCL*S8xGNsW=INJP=N~$
zb&D`Pc;SEo1>pboctNUw2Ka+Y_ys{~S@c_fO^sWQW`Xh*`1=p?<|^b~iRy6QvH{hj
z^dRVAuqlwf8#;yb0xsS)$m6iR58B|bSjB{bA^tI|5mUfEEC?-R5HPctf;a7|wHT{4
zXa+2wf?7}qE`m0&ArnnSdJt&9y%sVJwoA}mU_11ykT<|hFz!Wk8Mbkt5_$>FO%vBiTapWEJ<{dWhfJM0A
W!xkR+gnBdm!7Aa75BuTZtN#b~On2)5

delta 8739
zcmaKx3tUvyzQ@vnK6P6PvxQJlLGNEDk`O(?8zYNK`ql3
zp5wEFny0i<0Xavi2~w===Dna;pxM!mIucnM6=(Ap=l&Ltvimt*KA-RW*Z!~ndjHpd
zt-aY{6|R3GOtMg-&haD4NhYG)Ih81BuRM=*F7%Jn{?hNCvvyAMpVhpdC(tYwK6euRjS&-p7Zxpyq
z3n$78@kBYaVi^r|b9EKloJz5Zz0ofr{1Q^Tq`|3!r+pA7yE0Rf`xhs)+o%}S?wRWO
zJDsceF{AzcJ+Hq{lyx$qPIu`c%$tqruUGmy9@$()M<-j-zgFn5vakVb>0EYj!0N$f
zVcs&OMk`u`c{zUOdFJ_MS8*K+b`Os=YxkNn<%-Mu%>MEP)l|1pN->m3sRj}{uFgf9
z_P{b(lc=8NB6>?syWXibQE^>6*OQDr}^=EcStE(73y7Ukel{a?U2Ge>!fro+dD8IHQk`Ho|Lw#ldE{=y_1VXO82?O
z|5zC5m7}s6AD%YUNk-54ek|_iMk-G0I3;b>4@f@SB8xxNDbt;7nGrOhnwJEgOz;>U
zyy4L)DO-Ql)%7yby(5+Do%U^y-jPlcmDOo~9jS8Sv~OT39xr-_NJMuuV51bFPa^VG
zJ)z=H?X1ybOo2*WBI)(=)~*4SHd0NsyyF%rQQLn?jWorOpFpbfD~s04O<#s?I7!4(
zi$~-5P$Ir-nGl*@FRVYiUJzr2J-(_CxcFAn5rj2JBQO!cTKbpw5{OQ1l532TK9-7k?J^Tp^O5q-7(&JR
zv+Mms?>5pynUYRittH9{paob#!9R6Gd6g^FzvnsVxo%dkjOvw-+xbK12HH_R798xg
z$>^=`-;kv3?fgul3G5klrt_%nw^^GP5?f$ja)Pu~=HIo!Qv@<>I8e0!D>KUYqO{$f~84|Od_W$luX(y%3%i-=i-=(0GhDen^4_sfb0}bn
z{&sw-nTqk9ip6`-S&HV(>fJV{JsJadOYzHDWn(+MG%~~nTlV$V<-(~AwD6r
zhRyJqG&H<(6uMo9aOj@oB4&4vHt8`C7jYRo>f@iuhr%Os!yuw=M3lz-V(-s1T=L5e
zozV1TimI|knyKAqmYcjpwamYMhg6ICoMRxP;c#n|)oBlo#g|A6wA3Jo9>PYXn9q>W
z#syj!dH$xnVareOdO&gq)Dg`N81ceAxfVQe+d5mFGzZo68;vI|vkdVom}8)k{X%(b
zgX*cae+t$~-4i7ISME+|vGGcNYrDqA`@$=KXzL5^V&x8a@(xL@Rhah16`dSjM}|K$
z-Q&9dvfT-hX4lrmbWR@C%FO4>=bP!c-3iLDU9k74`?t|cqy-+4W?Okl=T>yJn!D6wcz
zrDTrK{YYhd;zH{xr6rT)VN>cxH40DCuqBNXQmIzg9SIBOn|CMZ%)6u|n#Md{OlF?H
zdUpaZ%%8O8{_#hUCc3&j%4BAGbRTl*zD?5SWRrAGFFPq(bAyD?NsZd+Ka@vySINs8
z%t1-%D^b^~ZE=Qr9GV%uHPR!}J1SXxgUx4p+JlaTkp(?P&eP0(1<_~SM6hHj(W(&)|!qL)q=5j|OZQIu%Fg}-ARw1ct4ojp)
zh};%uhm!>uysFrbLq`RyH8e<)dY|8yp^Bywsa~Ibf3j>NWC`K{8{_92mW=41WSCJF
zYCa_`QT3c48xe;1woXD`00`4gtSD*sHL&OX#zce}eCmqh+?)7je#6Owp`fwe$v3))
zUwy<2g&7QGk87)0yTpSOuX12
zWkcOB)YO=7rJ|3cL3+G{^Ds423@kmsuOLsmH|}u#FPv72&6rZ9Ht}V1+SS#(PrKs^9?m^+)W$3OutS7&+Or<@oOUka{&qg-frU;~3lPlj6V+pO(Gtv2<)ZfzIT9e8q4+il%N
z?gbeH9|IeqetOm&K46>^s>*?>1Cu-w6=Le6fk|qULQH(5)(P4HN$Nm_Sn4F=#jg0`
zcu_8kw-E7bo_=7-jkl<<192gnU*fYA8yfz?7Zu)W(5fHk8(wh~33!_x
zc@P!6jlj;oqEH`1sh%B-h;)%3#uyH>D-k1TKBIdh`2h
zWM+SyNeVF<7a>8+aj0?l`LEcW&}kl!d`f*KM&-Y2VZ|-d9d^vf6tv0T6?xly
z*H1wod0!V`tTe^f%wLIk9!boXB_#G^-$y<(lu2rnA!WFh;2lIhQ6aiNlDCc{f_Q+<
z8aJWfU58$)Nzo?yJ*Q3f%T9an|Ky;g0QCK@j$tXol8dDM>3-RPh&$1U
zZSQ|ds`-pQKHGgW{hwyJ4!z^E%x8NMmWyf!^GMo$seN&$g|6B|mUxKgS
zBT9_K5Vb&+{}Df~9`N(eV?p6K;*S(x2Jk33mEC
z+ZU~&Rm>V4L_e&!7M(%qz>2X?v{5>#BKXNrncK*YG;w)GmtDu^#)c0103&Zy({*_?GtEf
zMbuQ8K=)U~BseME!eWyCiU#YGT7(IKok^xn`>M{#_|5I;w2yU=dp3QvWxTLUN+vE3
z@|Wo2JMI0tt>$-IrNb(K-A_%LaIJ%v9n-DVLHkSBe=7S`x0Qdll?qnhu{G1m2LCII
zC_|pX2O6*rybDfL#7zIEz@+p6?B=t+%s4^L@+0H}K3i&$Eb9D(n$`IUY+T00m^&&=
z2I22$`}Ig6i>I&XeN9|1bf@zZcv`A-F?pC|!TnNotG*@X`ZCL6S)O!Li!qLc1U=%2C)hv+XehYoHs%J?Bu#Or(i*s){W&Cj#I
zS=E6bSAEi|_Gqa;BY9hFwti)Tc&J^C3%!yG;x^VkYnEH7Uc1UG{v76Q_R}BJCz;pm
z2x@0jX9v>?lO6%)d>0vItaI1{or0;M
zc??UKGm$p1qB$B(3qIt0qc=qQ`%Z143cabec}$e`j${yZzSE%3g>w(*spfl{i_Lyu2iPTO@U@Je@{SIR9CH7
zSt4Cg7fI9co#+aQ?!C+MqrzeT2A9O|^k?zL=-MR5?eaU~Z}uwl-%^V=a+Q?_5vTpf
zYW85B5lu(UpOo==r|};3I=n$=4l(uI;`W(+6O@$>dq|fo1@BCLbK>SqR-zFefh9EJ
zj%HRkxYIi9OC1(}obs}q7FP-vd%nZ|Jv%%9Tp(Y<=y&0YmGLiomB|uuT6R%g{2E?Q
zIy;dpy6=HI*nzCE^d!5GrSbZqqo!PC
zrIGHTKi5B@Zin;98GUBH>e?!}KKdkxHyt>EyI9^cqjW>MR#xejM^+Kt;T-y&!yeit
zJE^zQiMoX(^kMydo5TJC`{y$ScqgCmY%nf5SovSj@5`yjk6|dPawRWT(E0r$#{2VOMvKDvLI0)^oR_;<8V&&Cs=nm^$ns9fJ5*XNP@4
zCq?+CVr&=B^K6em-qLOhUs!B*rirhh)@Rx~?AlJvdSRgH`ih>)BH^Q5%suCX!ie6d
zv(Iu?D~kCzSk%Im9&bsdGlcPyt;JP-xy!zdl`Z_6@Z><2nfoIbPc1s`|1Zh6EY~a~
z*EACyzbl%L@=vqe!%j2T#V=9|D_p!(u>jf5w#tfIps@N=ei=No`V1GF^W)sZaFb32L{5x(6_@k(
z(Lr2ARDzKlN|y7iJXZL8TDKwB_Gqp>zs=`$U>7Mz??;VNsk$zCc_H_d(qTYc&ec{HxJt;Qh9~f-q
z3*SOFb^SkSNrhwmL^%$km{+g5NW8(l6@IS?lu9hH;9LB*6^s;cFBxX}oQvC*LtJbv
zjN{_J3t!`6`iA%9(VrmEv0=P|N0MbMswhhS=wql>75Q+J%|#=IUHiBv&dBkl;;Q*A
z^FH(5INId2->A+{fXP=y<9q7#VZIy9{Z4z~(8H*avvs3iceSV4(TyK-nlYxs7o4dul&2Q1u?C$1BuG9XxTle&zyY2t}=bsg|sCEI{Q=I0;J9-mOcUWt2
z9IitaREJJ7viin~9;uH?DFdjGQI
zhsU%+iXW~^U2O7Je@tN3Rvmr|x29>cj}v8>H&OQ?q{whVl_k%EHGy95&F*a-ArNoo
zw@u5%Q`^27#OHx`B_DHP2FogfU-zPL&X_ks@w>SDcW3vnwfndEjiu0MY+r-lbK6(r
z#EE+IgrM|hx8Ho4RQUDk|^hbWk|0C&w+J-^#0{c
zBFY$W7i55gAml0hmkn|%mV$7ufTdp68e0xe{Cem%$Bi
z3p9himbqPD`aEvX_3RBcq+lpgfj|R-L7znv(yf5^AOtcT{NEl#K^FsBVe|j>AObdb
zVbk_lZ+1f0ZX^Xt2b2^KeGMleJq=`lSzs>60y&`1MiKv8IwB2g0H%ScUP2)IY%`F~
z0<%CM(12jjlOIXQ9y}Zbo4^~O3{--?3N9es_9EsLvL1ZKG$mdIS&2mXB8W*qX|M@Y
zg2f;MoCEI2ckt4^+`=spjm|dvKYBb@Goj`84O)clpkheQa~lB0#@)DxSN9=j{IeiNej^n$eq9)
z>2^p3INLPXLaODf=b}RG_JYVBO
zfNX-i0WO0a>+Dc~FJ!0_S)o29pozjLXTY(!}x%(kwWzY=nLf;C?
zptt@B<-z%N*cr%c<86Uit5&R9{Q~RQ^K?$y-*HL91?>*F3+{t<-~@_eMA;vBf+4-K
zuN!@lMDr4&33wGzBMWjcWDevq5QX$&R<`$VF*{#}1*if?Kp8jywt#iu9LUuZGUff>
z2D%%^-f6aFUqSH670v>RhMo9);B@x%z%3B{9sZkj6${_*@AArFd_OzHrtgmv!c^?7
T{h!i2mT{n3NL4Y~%$s_%K|w>)
zLO1>|ivGh_SIrCrZc-AIP*Qp?6#g$}ns&2^)b1g{IXuSs|2B`Z|L6AS^ZCwNXYIAu
zew@A6+2?TcypUHZL}yW=%?KdM6bn%vpG=g#z4AKr#jrn$?$5u!-nJ(?aF*r}QAUI1
zU?2DxRK7x#4d6Ct2dd3PsRL19$Kc-w;SJnF9WK{r^~fE2-W{%5z6}*}iE=aKtUb4E
z9vR_8c`J@6V@sFQAP;w?=piY^%WQYQ_;9;RDV~&kr}|DiZI*rgj3f`tjc>P8F|2*y
z)PcXVxr_f`w1410^=YE4ml5p@w;nEev&Z`zm7|;w?e3zci!JM4BMkV6jq-enu40Eh
z*Z6kPdCQf$5HU-bml0r{XPs|#7k98wRrsVX-2rQ=Tydq)8Yq9Zit2NuZ%z5qO%pMU
zsdo!WZq16-P0>zs6GuochtZ|AP|?=T?IdM{#Z3%idsK@jozoC4QPUXWNnYCWh0n-9_y*%k#of`F&
z5pv6ciae=WQ!jn5V;>9{JoS5%y0Tc>sZFflo%2b|7AY-skNas$q<4n8GUma#h1wITlo?N|GRw0!$SoHQTZ@VKmn>D&SOXD{WsNf=HwYU9
zagt1l>wjbstx%jW`lVDn!KDOk|!GYdNRn+7Rt=o#jIzp-JHY>rj$k+#E`sYDmlGv3v%B0H7>
zB_j?t=r+*qSv%5@{J`~!J_uJ-b|;p~TYSjtX7~C?NiZy$>{oSEa?@p-+Zq~iM+9A?
z)J1EgOC~pQjBAr!wn2s%)L?5J|K5cSXhT+*TO^$^t+Lagc|=3n-pH)6XXk$HUWD}#
z({he&92gvxmQW*IG)+l&Ir=%(A#;-EW$@KA-_6!$d9P>B#G+1-w8$9UE%zEH*b`aG
zz{k9caBoK1seUU;t=b&vhDpyp92jW3uJf^P&87MxX^Hkndwnz2S2s`7_rp-t5d@uc
zL)GCDyswSjP%qcePkEX8z78}N0eKJX1UM>BoE40cj-lA3(*pMgHU=Ht^$Ve=;
zb;_#b)>Co$lBlB*g6JjWKx4BX8yO?&;H3G@c*~v{@7+okd)57-
zy>u60`i;buj#WPvV7qIgk^Kz3HBAEz>7RsKqwU$-fvXDQ@7Q^e-`cLW^SHlwDZ
zg(_rLpQ>wC-k>u4=LQl2AN54*F)3e7_cpDhCwZdE!e*d_Int*jN2*24F`6>zNt4a=
zlT0?dzDydMA`f3wAJ!y9)A0FCPfw#EhVBeE-&zoFu;xo+bxkXIC7Jcwnu2&>Eym^-VkPTK3sud*8#9FGkX~
zeI1h1+SHO#NnL$ZBGp3V>t+WQ>S>dAMP__J7M6p!>4VJj>C@yEgSB8K6(_KJ{u-)e
zE`NW^4b%J*!>_F_QOj@$Kq5dMxPiyPb<@o5(q-zNN6IeTDPDFRWv4;4ZenSE`w0_U
z81T5M+BB#>*Q~nAQ^Rf-Pp^Wm^2f{=H?i>pUa8s?QSzv@j#UOkp&R!DLPu0%>iDoS
z%gIoM#dG>TtV220=fC($^r}1SQ6FjDC%va*F@b(wJ&qKMdVm&Nnmr$=w|Pe7;~7gM
zYnr#p2sYr6tW)lDuH++|k%@S~A%o;dB*Nv;wj=weQZdoVQ#JIEYwm8A8tJrlK)3h&
zlE&t>5qEH6aQjNFtC4C_@FXWh9M#c?XT_a>i-yQ19COT;q#DUDH6Wu=lEXV9(lEBE
zQIbse14`RA*(QG3D7C`5pTW|USxLn~&PM6c4$i|oG@00wg9B_Nsf^$J6M0UlSL;;#Mic<+vm92`_r6wGdH-UiLJ6uDe!i
zipwE$^70&~Z_=Q|p7c?;nwbYTTKzzj*7vZiX=s%
zU%Dc}ZA#^j$`~U4{R3W?*NDRTckM8uTnXJ+9_L5!*k;m!loDyLiJ85=ERlAy3qg9i
zmDz)WRR>~m*yHxEilwd0dq@=B#1e)CyDu{JyIv-xvNc0|{mryGU`AYC=L50LzVc_6
zE3;f~S?tH8P3+K+AcYwlGL=;gG4`|O73Tq^v
zh@JuBTpn^D;A~rm?ZH?4Y#)%Q$&iKM{1I{&k1HScS;)9xp9pz(y-VB@QW#(|e0Ejf
zZwMK(DROZd3)1Tavh|^J1|2+3l)U4EA)kDkDDOi0
zyj}WT=yVy~z)WHP6x2spzmZeCYdYu@W#ws%uNdqfLzH=J>ByPX$SOvL4SUe3N^m;j
zyOzD`nIN}(dcWGu>A2w}6&_QQMOP%=Pngs3&{?W9Y^C()($_~(DwKJ#H^M)mPL}fc
zhj<@SjV`BZc42fHHL)P0ZgfGHc9mQ-bW!cw_8c7O`5YZxa-;V+<2#8cW6WMejnzfq
z7h1Z?7)Hyf%mXo?2o!^AP!DoF
ziFOyrRS|6tq}&5b2~6pSI=H?GA5S^aD#0%JTx3@wbfM4SZ6y1?CRbV61mCRk(CMMc
zk?9@Q(4;bLK)OPl+O80nu)xT0+m6nd5^vpOSeE&nQ$u_ca{UzI%MYpEdz#Vu&N`Vj
z5b0kbnsI6p#1&5MDp*z&#CKXf6U($;XDCGPcB8fDA;CT7IUSghZ_p-x+v9EXUHv`!
z$orauvCEMij^dRJw@yKDP
zKH@Vv1EhmYkOlHU5hw=LpdRp9me4ys%Y3$X;g<1P?w#@B+PNs)9E(K;hrX#V!1~+>
z+f4-MIsxgyhD1H9#>2IeROQ2wkNup6?Tq>)!PoWBt`IF13ULt_Tp^XKEbbPKWrSrA
zwsC+{ZrN_muM#Zg!C{v1u-Ln_7O4^^WL>U#e3cTG`g6(>h1kIMjh%>{&@i@=e$U<<
z=b%>h+IStkz)p@2rtg>5jZdM}uQc$9HcI15HBTC39zh++;tMHV4u3Xzl0nmmk^R}{
zjY%{~md@`(E88+@zH0J0G}UVv!L$wsT2mSt@1m5k(1gFB3zZ3XgmK=T36@UBlFnHC
zrgd~WLY?FnyK#KhSYe-(NZeX8ml@+a9i-bUrQ6E_uYv5_sR`r0>fm*Uc3b^nz1{Vn
z>Q;AqX}Z1K;PoYYZd!@&{RQ}Nvydn=zz*;sxKJ88{e6Lr8t2Jw&QP+uGY0!qOF8N+
zDOZd6AoWrX;gb2Jd^tf>bCthh9Wz3M1J}PZ`dPSL=+-mixh|EvS-dQ=(0)_(tN%wj
z!Gcr$sf|rYHQ}{mMQS8c_*<#r^fPujbte6m>1IaJU)Y?P2HQ6syLwZ|vsg`PY~oDF
zSAfz&6R245K@RjKBaP+c>VyjZ3Wv@b30lrI8Y^Y`K~wXkXJ-h}Lb!O9PL#J)%O5n*
zPT@Yv)rDtE+osr*U*^G=MqWG1>&%QRJbT}cL&+NVtBA&2Gd*;~@r=Lktr!`9U}f_b-Z^#Z6yGBESok=%D
z%|@o5JCT0Fo|~)F{R^LYZWtpX1N|o7p$em=rr8)(`J)sghLzWVTaRvy*_tcw->c|2*Su4SBdCkwQ0eMZ!+JJZm{OGKG)Rk9U0GC#Juo_iPQ0S
z92UPfUcd{e`&BtknctH@t9MD@jvBnwt1Ee$aXEgf;%ksyniqpcRr90id6qQae_U{v
zED0}L0dviBW0eTXbFze>Dum5&@&)U3EO2H8;v68$xZ_T-AYSZne9j8z*9P$pSpSM;
zSRVIh?-JP*JU_drK5iY4lf^baI~;G-$DbYT?f5`lsfLf-GQT8ic}$7Zahlnm-O+vi
zt7hvLjHWl)@dY~XrjF{f>Pi}^GW^`|gti@vYz(`)V7^+h2Fo6O62$MFcqVtUrx%XU
ztGZTI=wFDeAo`;j^n}x)>yi~4E9pf2B4T*ZaNq89G_f}q+UVby*K?utH5T<;_~^{e
z>cEUUN_xV)wuQ)=aURAU%V@0w!BW0LKVmch2og+%dTXY-v3Zdfi^XXRD+QTdz4&M$z
z{EMr@q3@)~;`r{=#mgQ_CX~(W_K?G4yDM3IC8fiW*xun7(5c%XSZ=Q9i4}>}b`X71
z<8UX4)6Way!t>$HB6Fl4Qe@%@lg0LDtWlhUc7drDt@6s1ie?I9CHozB`IRom7Pe#2
zTf#RgHgfS#Tnt)rCh&^nSF+eDBvv;QJs)?$N&eB5ud6fc+a()mF-u$eykZxuV_5Cd
zSspv3At5H@+aji47Dm(9v}KcM8{56?HG!@#9rXNI$^%cgZo)dNvp$bs)AE-G&NxMs
ztq8#Q-d;YAGuxrEr_FTsFn!
zxZ&cj11`thsxk!Zu{HMErdQScYWuv`_H;Lqb2mfRhz8(LJV3S||Cu~6*-ltLU~~Ol#7qDj&QMPi5u&pQLL(fC`a_d+H&meo4Dm!ZMPakp}
zpY*KPta;W#YXOcgL`$)q;JPq-*pRvpdlF8M%U-w~Fw?6p$1UV4xE#qI%cFmt{c6};
zZyc2{XdX~m{^H-{Nd?anQRpCIS%)k{ND9b&Xy;{f*_NCSd8MbeP3Pi`ZBKCV`L+ly
z9`=Zc?R#-{sofsQZ5`XYiynWi+yB+qepW0&Tf5lW+++_PF$Y(0
zYIYm&8{Pf8y!&@w_wUEMpNBo{jdl1v^u`*zQ>os3PdMStK6-ODeT(_#eW8er#FzTg
z+j)ALvik{y1W`{C;R
zp%{2udN>UII5-L3eZad2HJrW^tH_W`t<8KTi*sc5DLOTUs*VG6Nri>
zHsypz3hqHyn2C~iDjIq$_`jV>fNdK01OH#ACZn7J575`}ap)?b0lwXKTTjsfTx5Wy
zU^!R?)`In*ud;vKZ~Ek9+!l}l5_*Y-?DJg;eJxlHOdtwO0Da}}LN5pVZTLA1YC#?7
zbGQXPXcMLy@;0~vu7c~J&u8rvqTCIp#UmKl59+{1uoPScI+SZ>U>165$1PI8?g3Q5
zrooRd@CQLa2SPzOhyoKpG>8S0K?0x%<_r9Rq8Ak;Z=|ntVbG&MI52@fSgk`yLkdO*
zDxSee0e7s$^<}VwY4%ODDP|!wh?Axn~CNIHlS%w`5E`xRu
z{Q~}JosLNXb>K2+09Sx&5pn{`cVu9#K|c&x0>YvDgHUi4e%HZm&}72rDPE0_g67G)a9G_Vc&Mo1^nK=+082Unrr{uAnhmi5S#umu4fn6-Mv>NPL3
z&-c&Hc=>I7wK_$Vejo_wK^PbfqQFF82JyYJuN!?SB>|}?1METi*ajH}xr1MW1n9fj
zmIH51sMv*-1a5)L;3}vECEyUa2NoL%dFh?s20DHqKMSN4+CsBdxNH;+yYRumhvnK6P6PvxQJlLGNEDk`O(tSms(gO5yG
zc#h8wYM#_v5CP=Zeo9BXJfo4ZL>PTd5RGiIYocmim%I@cO`Fy_fU;DrQ>-}H<
zwf1JGMY!>aFtLCVb+#{2PBanat|>%Gd*ubBbD)2c_E&!YoVjbF-^}I%L^Jy9M57EljvgLdHd8c}ZX|9vIAf%7QC<6nZ4`75pI(xcfIbngsP!C(%oC*z^vyiHd96xt^qtG&zYbY?oWk^FAI#O;prKT&eMvlBhq#Eag?!
zN&ex(rqxJY`Z_5z++ePeT*K=mb-2P*BN3#Ag_B`5k{qd#;Wd&HQV*$u91H0M83pMR
zUdJK^O!ejU?v#?XD%88iAUEx++9`#4)JbVtwr_xcN}54sIVEjXCspyzdnFZ#l`;>Gh1abK00HllZ+nod|B+zjZ~c4aa!7{cTGCiB8xlRDbt;5nI1U4nwJC~OmH6-
zwBhk-DNBFN+4&05y(5+D9ky+c-;qucmBnG(j#N2u*fy|a_m{nbC89g#zflU;ClYz9
zo>1|pcGl=VI$xzOk@R|bYnN-Kl~hwL?|6ZfpzS}oMw)EMizn52l|}31rY}P_oFZar
zfqUb)5F)-?Fg_%$URZZ-ogl^tdwo>F#s^yph*~(6XSsm<|1S6{B;tvDMX>lCxvy1g
z0x}3`i6hS9*N)SY)+0Q>?4x8qb7QW|d|4{i?};ywhIv$#RVGy?dzkBT1@k58y|ja|
z1L{hokh3MyD8nbM#L1_c4kxTZ8jgtw($c@Y7f*C*lU!qz^f6S-ZI_v-nvaxs#t(#{V$7toIKG2l?I
zO?q#A|A8cJZ|7wYO+e46GaSdPzs=g*;Fx^d;*+GUGVh)ho+6Nu`|7ppN+j70KCJ^<
z1eq%2z;~avy1NH<>=6ALS@~CGbB5Nmx|0p%Tgug_bP`Q{6*LW!S*Vqw3{GO_RbwkG`1dL)FV(AlUOT_H6&y?Z2#&~X(uMn&F1bp&ndsn4>j^l?9K8${PGjE
z&ek|=y@lbj?zZ33JMK{32J~Vf7Ba~o-Pusg{jwB$r$#aw#5HC(+j<$nL14aNIn^B?X#;o0kK*K+s3X*No=
z`mgRxasAa`%ZdIh%yaOJ^(W#UnLH177qXmKs8O37w&{;QxWo7NF~ki*dg4gW9157C
zznz$3rea*DV$oi7mZEvHdXLp%i^9NNl6|vRTG>udjSR7eo$?$dCt{O>eeY@TtahA<
zyfF8k($
zjBk26Syfph&Cu>Q%T1o5TIN^3Q>w*$&Nh%yaJbdV>ePqF<4UCYT51qPcVQz^%zN-C
z<9scQJbqK&wC2ToJ|sD=bwslhM!axOZULUSZJo7FnvH7ujlz?b6%6*xpKYKK{X%$a
z1M8`_e=^od-4i7IR_uvyvGPiOYrDqE`@$=KWbF&?V&zVF@=i&uRhah07M&VaM}|E&
z&HaYo(mnAJX6M#LbapP)%FGwa=b7o)J@LxW-LQAB`;XC6r1|aqiH%V$krSz7*QYumJi}gaaiPO3Zq0CK`k+)L0%u`U>yJt$D6w#0
zrDP7*{YYhdV?*jHrNxuvp_A)IHVRME(8Z18Q>a$g9SQU2nfJu&%)6zcfr&5&1nu&=U!i)+K0(!d$`@Sw3%pY21$-emI%@&q_g`=hK%;ktm-*IHX;o1ZJmfbe-NsjP*KwEV_+}(jt&nsc-Ixjx;635{Dy-ELqTJ?n`d+q
zzxs$53N;wYp43*edf!O8hB^BMrG|QZY2^dRt0cn|Cf8})TjcPfo~6G~jJg@y;d6>YENPq@?|
zWkKC9#MGE)p`y3FL3*--b1^lO4J^&yH$PXqFZM|NachILvAe*O##E8S1|!Jz)*SLB
z=D1eM%W&A9L*M(FICq(A7cOwv6zzNsN*}9DM07(hdm28|T`CKu!t6Z%gndx5cT(@Z
zU&&(q>q~G3O`lw)Ht}V1*wod$PkUnXAI&*=%*reKutS7&*fJmYoOVv)fp$LV6Y#?u
z@IfB%x#$Un-OCvu^`*^heei5a=evo|5i!{pC~A
zk8H%yNP3lJ4h@Vv9^UUdu6MM?H!W_`{SuFzo%cnb$pz(kmebO*Ztc#_M`D{b_h*MA
zuTpNx@nO)U}X5Rn)89DD`Il)=Z+im`3Y4
z{$;x}@7kNhg{Zk1Z&r>pFIu{plArL*i}Gs1njcKUC52yF*>Y`Q@
zzUCV3e&6trFPa4YmXR$>kc)9FT&ELml(J`a2Ko-$qI*fWTUsFu+f3;ywk2qm_nM!bAvSbWg6BsaG(lxWC^v5)ZX~tAiC-&`_IdlXI*K5Y?=u)qci<&N~{=0P}F8zE?jx7AX
zH#XB4qBO?36BWFTz|OCtP#;LCo*fF0aFQRv7>=;3;lpVjqlRsnr}`6h4X6XPhl%nA
zqzFm@afOorHPC~*;3qEKu!A7;FxqwCR6mr#vk|z;iCPJMf=wxFHfVy9@WxW~U|_M*
zVuW2mWze*s)QGGOb5QbWwQrU}jBQtlbJ>`Pu>AZ^W0|LBFdTAgXNq=EVzG}xT=AId
zJg4f-@2{4b{ctiV#3)>c1TovL#u4bZd{2C**){33`f9d9bZOU{aV)}$Tcp`-n32h7
zlfNWW=F&-UG8ptteIERC
z5p;YBzJ8A=F%m=Md{y2@{Lp&H*9&9!@nCO9o=xoUcx+XOPgg0#*}$Vps&q3sn+BRj
zn!FJMRCc*(b8JbqV2bq*Hbp^my-RJ9EVwFbiesaymC$^CMp>p1zhKA4O~6jLJBNelr$b~eBRW#WW$9fu9h(yqGVlY8
z>{YKFF*I40#n<6$wmW8?+k`V{s#oL6>@g$Yxb4xCvZQdpiQen+D-1wVV@{AlT^T`>5gKMzS
z{2vFe4>8L-Xe*6AFKx^!e3(DUpdD$NXD$>SbWeQ$6%x|Hg*D?Q`RW8P*x
z`!Ri*dCm%_Ha2Be5Pis&&zeF{va(qkxZUMhW1LI%{ktt)W{((L<0Lof5nwKKk&(ta
zyDh*Wm>QZ#v-sH)Xag&ntQha92LKGT(_3Cx(LFk@0*C&$(rW`
zDjM?Mm%d?cbNx_0c*2ZzaxHT&oaL)wRkUA
zS$Gg}*nX^L59b=ubmY8=>7RER?^Dks8+7JiQ_o#)zu6~VS!uTgcgd3R=Hxp&cJ?GC
z8sQOGLL+WyX1Sd^t=+c7Uf_pQUY6bBOyOcLcG$jW=jNRc;7b_wE?luP?p4n+SprVW
zE~<-L&Fe{HN9T{gSH_F;$9U3@RTdR&kZ^-rnW;e2vNpPQ$;z7npFJ_+J2J5Jy(miydD-QcbjRk~#nRYZ3r
zo4#kag>=bI=`D1EZUG5-RR6$gxBbBW`CLBU%*Q_;go{q*^I?Nu>8$a~Zc)v#fA0R`>kaArhvLZ(G@~U&=nw`ylS!VgXq>`R=`oAyukV
z+)UQx-X=08x=te!W2%^z-eDWjsjuRx;m~y0)SV;CqD-1~+^wj%^ph+zbnU^W4qI@C
zApX_SVH@8`5x%Jy)5Y^V+QX5zq}##=7MmTZ;(FBjTziL2+o@S63^3hT-cwlwe6)+X
zWuH_S(fc&^S@tSLF&_tuT(H9ZEva<6Fix_zILohe*|xE=1%DHs9>6kke&phrg(v*}
zE%}t?n1!U8W}@SFMe{NKftGvN8Rop`Wm>=r7cEiDhqi>>TQt+NLDX-&m5OU6-N@t@4E!0TGgOYl2q=}R8!)7xkuI&W#D?I%TCS!D0K}!Cwm;w%OGiQDKj+
zp;tGpx`f@#^~`wZ*PNQ(oTsW!|El{(uTEcG`>XDQUfuBOhF^7udv*TRw~jN@idSd}
z`)tK>;o)&MdgZ6yCFqf=QkKGBe!l1ulK+#XvfvgdtooE+2G6cK%f;rrShrBzq*DNq
z6Ju`0mAw6QAXgEUU?hi=#KJRP~sCm&*la61DWrdXZrp2Sg~M@H|;LnGe3E~BauGR53Ja+b^t}xJNTzBT=*9#
z#b*2)gROY!Tj-{&`zI}_u&S8eo;tmm&qi~g6Aw14i_J^SZw`@jGBXGJZlozM0br@HWt
z-on#e)><6##8cRocsGS3&+=P-;g;z`L|7^-9kxXdS<cNu)O`raGF(t)NpoRMpx1k`
z`&)+##EbcE({l05wr>XVdEi~i!(5ob(u$z%o)pd*{YD6W7j^&c>i)HK|2Ds|1p4$H
ztMPk&$10pSk#C+9lwR!4o6ph;HgV^FDZ(O%GQ7fVmyV{t{1j2X1~g9-dy}<_O4?!vbXh0C?vuHxP74RMeLxzF>-GfNzqCqQc
z{=XiC!{#1r+MejmF6i2gBwuNVlH#GS;Y6gTf^;ww%mJAo8}!*I;(kkqr(zAjR1n!q
zFl3)?I?|b7CI|o;5CnSiBM8}xheKc!cmtGyO3+uqMWowa#=Jt-gU^_z#4|rLfhb=F
z(eWq^Hi1g82&9Aazzz9!Ub>gtSbwE~1O^`Ri6_Aa*Lg+Sude~oI!3=wb4;r)zjR3w=+E8UHaA7O
z#3tnK1qZ<)a1_*o^gMJQw1Q)JZi5U5A0mAPWFuV(Sp_U$AnH>EVwL{v0KxKWKfgD_e*;tLm0hORHBMj*w$ZJNqaHKPlPKUe#
zn!!EjTR|E0mOr69xUd#G19@${EiiNC@|CMzVjX**%})J0E@`-+-39l+1JDi}KyjQX
z`vVU!xL5Xdqc4(ZUO_YguOVt=LJoq=hFl6FkzT~g_Wdn-*LGNdDsU8(frDTRSPRaB
z96ceE-~Vl(dvNTXVO#d+2c25($fs!7fzJmHM^6u20?^-KzgbtYumgTh>yP03*K`u_mCgqkA&

diff --git a/Tools/IO_Firmware/iofirmware_f103_dshot_highpolh.bin b/Tools/IO_Firmware/iofirmware_f103_dshot_highpolh.bin
index dcdc39f66d8b805e0bb85effbaf9bd894a20623d..c23f39a50f8c81fa437079fcb4bdc0e16e857989 100755
GIT binary patch
delta 22408
zcmcJ1d0dp${{MNNSr`yy5L7m079|9=8BoNn#z7ud#jUPs*5FcuqTtpw%LWw<%?f+4
zaH(*+S6f-6D;7aXr7ic)xD;lK<*iA$^?gui4l@k%d!GTib${Rc`|ro=^`3K{b3SK3
z=kxiT&pC&^|HHp?NH&4UiDt|wqMDaSR43*T)v$i|YxwU#`0ug%=)MUF_n!KYsICCq
zM?^IqxDR;rI8i+f90BTq3&7Vv2QXXn$6Q#BJCWx1IbZo;--Ng!yI&=$d)^?b7vcW=
z(Y{~S?=uAt89b4wPGu6+2f4`d<+`=pSHY?v>1lV6w8wLN5${}mC{Qf3RUrO~U6?Ak8NldXTb$Oj7
zGe>9YXRD;+-9A@!uSVdcKf75tnHR4RRMLTN@!p{iWi-bU%{^L7IDn`*6A9)__lFWq
z0j5fEy`2VYW9Br|9*v!DMz!$Z+_Q
zDAD{&D$NqNwv5d+$yT|pwNT#m{W_U7dTnLKW%{YHh1%!I
z(pumvZoEwGT6xavQ7@Xynh?SjHcjK4|q0+8*~UNUCpt+FX4!nd@vN;@Z@
zt8L?#lo)Q-wiX7or$_VF=hl>G7zLk8=nj(p>GruMct%rxknI|+)SqnU`Rw#jt=DL&
zjFC(N$t94C^jt5wM$7zRi3q!ZurSZ{ZEw>O{rB77riYVn?BFKJ$A9c-{E0rBClT3=
zk{jD@Z0|&?Sp^9>Z&st#KG$>J)6`VZW
zBJz%j1mtsrq`mG_F{RXK$wHWcaMB+4vCa4tLR<1%=y~AN{Nl!>gugkW
z`YO?3QNH60>-XE0Z#k9y{z_%Fb9lf1xbhXJs^8zEJl;oRLkqrt-J7#GpRIu<
zN?VukW*=jmi8NJonPG~+bG(S1*H#vRt&Dr`OG<6{utgTatd`sZxK*gq075G{+jY#SKF(G?L*-&d0Ei+s!
ze4myYr62P;w`|y6R_D2OTb7vGBtxFNKpUKL8pkcWQRsf(&je9+w&B&#+wGJ#)QuM~(TC^u;K_G-Bfio~?R?L5bcM0!T_Ma>xf
zk(;&L?u!>fvQ*ML9-R;`7_=(s0}qE8)y#2HlvlJwN6cs3@o@+_mgyo$dW=?_osLVn
z6tz5Y^3~}%>iT9nF7A+3E`&)MS+t{^wqSG&DI@`tc!R1buk)3(3OX^4OX8&vz7#(3
zd|&GW@}!^
z_2`1ijA>S7$4YKdA*YjBFVrrva+4}ERO2f^A7XDeg-Kkcc_$p2;)v~WdYf##8_@UVSmx5%~Qlnx9KYmv0l-Z|g
zDpD{_;1aDsbrP)=bZThd_sRb6KbDhd9hbFe4R5o~U%SVg>wrErA4Q|)6S?E`xQ0tR
zP47ZQQt`z?r-t&V&RyE$)D&9pL^wL|F0GjMtm8B_fo`htpn12W-Z>o0{DgDZoV-r=
zvOd*>wG%9&IN6#YTrE6bf*6Zx+dz|Ttj)>R)8I}6K`g;QFC<$Zcb20y+iR=)7dTVg
z*c>KZyEc%nXV%THsiW%VW0W-W$xoSGnBT7%!y1Y+qDnB2Bzm^Ee$H&UkZ7$e9+9wlI5TEx8uc_xpWR#(w|(kNaWHDR(mWw^b}JoqYGzfb!Z_vf{ZKNUmSre|3q
zc}h~v??Zn+3oT4KEl!TT)0UfJfF?{0$xs$98i=&0_c-k&tX|L4>6&G?iEOJAISfDV
zWXry|o{Uxq!E^Rw(#x?JZuqDDh1x)SvUNXwQ@g0}dy~w{LzQInmz$^>chfPT@zHvW
z$vU|(1We53J~3Mz2>I0&|D=+u-Y#}
zuXxp*f3ZA=(?(k()}TvQS7!7&`#4jvXI()0mA(zf5M7ygpJpVtUHr4=VO!;Y$?<@r
zHh^@TECG)|&(DfGXb!ZKX;2=(mrLoa6rU@ZVzBPzq)oj{^uZr@EkKDny{1uLVX0Q5
zPgNMp;J9`u*vd<4Z3|W1EAQwbM7q;`8S=M1>bxyc(~1p(IU}cq-hXdY{$-kp;G{%-
z>t)(w1VLgveA82IN7Z$0v5miYnWiE>C~;b=3f;7~o5bfiD3s{?{h@zqg`R4j2;no3
z&ovBs3(dUO=lUMi?aT3Ve^}2vpR0`8{++qw5+j}dkk6%{Y^F@W4u(jPey*R5#C-*y
z^CwP4hFf|Vm8XZTFE$AeLA$SjfPSihg}>R$DmWb#d=q1X5yXt6CQe$3tw@Vuv6JOp
zs0_!c!FZhRol7KlZz&y(@k{Md
zf
zau)vL^Rd0t@(7V`5x>@tRG7iK=8HbPF=*E&c~`^c)ASXiICbkr`c`iBx8@plG+FZK)otwcXjmUv;
zp#80*h(=vMBzH(wNM?ZalXpm#MhKAp>DB0YU2v9WWPmi?C)&rv_z5+i5YH4#ciZi-lWN6bQ{G`bfnVZn(mvho9}PW5lj
z^Wz1j6wwQ@vOF=L2it=#d8mahO6lt=J6#laFsio8ZTs~S+pBT?9H#x(aPpPKu5;VW`G7ATz
z`N&6fV{#ZpqGcz&OQY!6OL%Fs?}z*|8s8GvmmoapC#*weF*)%%g58gGno634ge=(y
zH%IGE&`KmcjD+|5#wsL+shg3=J#^l9LeG=0S;aJD)t4>ajPys|lhcmrC;^X6WAdIEr(eW?wi#`?26NKR^>G>WmQ`K0G1QkHR
zG@`Och%Ze@NO;q$5mdkRq6xjY4C*rD^JQ~O>25;lta_O0TP>hcpD{=1IO}7=J{sE6CeiOUjc4HOxx*fF?p0e<
zsKQUEdF7`>6*9KC-qcDG@3M2FzX>Rz+$?ibZ8x!S9l`PyoJ`^snN7+Cx!jnV+U{_R
zBJu>S$X^;Tv*{jdun{aQbhc$wfVpYEm5Y3jmd*QGX|^?8@qg@{cR*=w3N7Fx->2oF
z@>!?pOIj}Jx!U7!Pt(KN=W4^CbsaVmDYLhQRx*1H2^q^q0CHd0C&UU`2q8{|DwPsx
zVy`JZwaFwzXq7^KT4BU>>*_^8*~=}4sC3Geuh9BjFMGVM1KpgkM3L!r9dT>&f3*D7
zQcA;1ATD;4JYPx3=#5$E2?!aPC9Hw8NV;G08O$`UWDa4J+S`LNmX0yi;0>Z0m#iVls!>4FTCb=e9t9zXD@W}_Q
zT+%@Z6-j{v{|Xg%C8rLq?mkZm$rL7J5$Uk_Npez&%_{3$?Ak64o;dn
znR!_g8JKUt&s?SnM)=)pe)o4YqHR%(_-2Y?xr(h)tU8Ds$^!u~TqmVN*%PBh&W
zE~;n9#gi%F;#ZT};tj^M2JCm|jjxG^lC!@jUg&kb@6!mWjVCV>6|)%{G`+4mpZH5k
zobt@y!4Ll-Mok_S)$6JRmAY{>g8D3r625y~Px{39lh@k1yCZWng5IJA8z>)6G*v(~
zuo>jdaP2?|a2=2UG6K>XI1hZv+z6s+VPWA!69Gto9p4&YFXU1g@F{2({sRXC{l@tK
z4DLbefz^A=oOpL?piL>o^&9I|jU`B5QXe-bE-%^Qw#Mb0)UGI|OpFle9e34gSb?EcXrP}nHwc2{BVT~D)nlp&(~f{vQRd0j4a+Kv2$075
zIGDH%)>k+5(FRB7+QvIeJqhVz@82rCA$iN%r3;*2u5sr555iDdCj$L~`A?_%FH`2XbpUFe&d
zX(Q4+I7FJ`n}XjQ|8J%*75;QzYEEkQl*}m0l$&6PU^gLc;t}#d65lr+JgI>SR=ep&dkQ1)aTk<;3
z+cv=JW+eI+I?l+fYzAYmYX;=7x~5P|q#ifI=aDh7+4?NR&5K2MUiNA;<p;-2R%GD$`b2WcYUsx-euF~_fu+MI{oKVn#1N&DdroSOKeU>V6L#aG%&C1
zSfX~s-IGmJY<}gUtJ$Pqif`8S_rYcJZS?0vRTeI8pSpNxfMj9Y&8Evp#zv_*R{UjZ
z^F*ceg}2ukASE;eND~2d1Fat{1PGz9It@oZz3Y_=yUZ0$ykL$QE2JXiDX;kbwCo`P
z(t0l!ciTzgIg=tnoDsnVWk6hT8l`l1lX&*7RlMaN
zV%*&o{P$k*ox4ZLmD20I;x~84z;mRxuJ`UaoE+Wh7U#}956@b6U5xod7F5?=_hVXu
zEJzEDbJaYLYh@YWN(Ph0jTY=&nFdJr@4V-5f&L#5?^D@!pISxz}a!
ziRBrZAvLTn{c)ZD5Z}#+i->^AG{9(>%XosUNFrWeIMV
z)i)ErOM5-8yl!&KX-F+e;rG*QqUFB!V}rcw%*J=jKa1nR$XITElq)38sF1rjV^9<&~Rf74bJDf_G}7+2xYueFBq}z
zxom~>XZnM)aSc(?dWA4V2+n1_p)a~ZZL_pt<^V@B^p*;2`|CWvc6?{i_4m*(u#spA
z!3XKDPF8z$LVS~2S5Cv52MHDFM8v9I*I#G_EhIAOU^iTY0^4*FpDg+o
zkF?38J>7a7ITflOC>W8W5Hf{h9wqEpv#Mp%9o^c(w}SZ>l7%@1+@w(#&1?)`>)?am>EJ`gUEPr0>447G6YJjF^G;W$4Kp=#@I}t}
zNv*6u^u8Dt{*v%XZPz8lekWdE5}u+q#=5unsB-E&J-0Ezjm$m(%iVgS$Cnml{t(v9
z>|Jya{PBf1
ztvl&119kyvGHF_q$S>95v@=4yV`-x8Q6ot#b}&VMo4}1p$(@{s6N|1r4;}ANs31*)
zmc<@zSMftb13dh#i?s?jf2))}JXasvLeFW!D3>@d#+PuRc8L7|9Y%bvOTOK35gv1y
zuGT2rTt`q^3w(#oJ1BqTN0?++8=iU_=7b8hu4{(;jmhWFDH{N7I@WcjY)sXUbR_EsMZ$?|crQ_b4W{F;-5Mr!DgcYmHg%#TCxIS!3T%!^?>_up>++>+IR^db@0JU`OyE{7rd#yohK
zkoXh_n+qG#U5>}BBypyFs?{jWT{AJq40Ub1*ziCMw^jW7fh0c7Ck8z@I^-><87nY6
zC)H|N<8`%*Gaigg-R0zr54yMYT&|55SS;pi3onKGI8E^6Mr>oHXIV=w6ymTHE!&J4
zSqLn;C_eMxC@w;L{lPnJGq8~Rq}n&$%k**MIh+s$T$RHX`ZyPD4XcUX-GcKxbtBUa
z*l^3X8r?G2FnbAhA(3q9ud44lZwrB$ywD&|)E5OeO%R|aJrZjUbg;o%nEne+@1-a8
zMH7TrbC(@-Ie)p)g(>W)}$+HrL&A-Y3K3#y|V$!<2LM^K9|$`
zKmPRq3-IiDz
zY3gIhx>m+$^3z9M3dugw9vp0_f6%?Rm+#uMa$#(kKlL-|O8Y^i=DW_U-*3L{Ff?-7
z9jiHaaL1su9m|&&MW*FHY-sG8At7TYv=(D)8Qwft$WK=a!!CvAvRsj84?4s`^vhy~
zQm*}~t+q2=*1^e?c6s8j{@y4xOE9);3T0BXm(v@!)~;R?C37pfbZrX07RBh>6pED(
z7o#Ayc*}9g_&4|SKg7|mG&1y`k1VbcDb{OyiR=<6G&Ps#_1`2QX^Ldh
zpvPr7i-DUt47@rP%FA~>pWloVf6kALP8d_3{zSV%sk(SPBCTB^I}HZByq%NzTu+MH
zWm?FE-4jHd8y(X}jA-U2g{7_mGFQs76=kCCNxS1~i>`Vs@&vReW6
z+pHeTjgsVkbcHY{!0Lwyx{*3R;J&%;i4b{Wc?(K+Y~Tls^|m>gw!fEb;lDi7BL
ziajn}_clROH@HI{9CRuaSD}=L_Tn;BzyVx_+LtL*P(j_}`WFm6kC*G6it@fH2|m(a
zCAM29`s*16C(+Fma02SQ{_sg>-~E`S^NDID@bp%q@&Z!5Z6E3qEGQr_pL&~Uu^25a
z^s-t$p@p`p@3fC-tsBK92DEZI)`ss8w^u_Fw>S*w*mFHqHEfYb<9F9wGJdXIfuqI^
zvDa#qiDRxZirO9$|Fa|TE`CCrf91A#esrqP2d4f$_|W-~E#~2o==f;g*Z_ON)W5quMIpF@O*+@s)e;0soLQG#u&XqsjoWoO+L)1z)+Y;I(01x?3H4sS9FoR$MCyaE=e
zD+){d050qDr_2gF+M|vaSo=o#7+(!ratV2D`mo^EAdl>J1>LB<
zR;zQ%ZeN3OGO_Sl!8saUt>`+lDLws$xb&e&+lcN6C}TU!3Wug3q6WHSzD#m@y{-Z`
zFPx^27!5*F@}Y>C9fWJSd9M+b$dgH5y!$PUDUXa|B6@eN|6~wmg1d?wsAP
z(s84!gn3yf+5@4qKqG_FB8Sp)v6g=>VQKy-rmRe~TZ>d~8{ZStMnWdoNu}M?9FTBD
z*>1+BWqK7?$;D5A7Enm!@fmhmyi8nXm&Z@M%1gsMvO^^PA%ENzT2-}u6qlg7TGbKA
z^9k~+GLe_$pop(okj`C>&9~_a!O;n6~-*MDw5d0cvp3l|uZgGZTE1xurt0bt|
z=d_gLO&>Y>3LI;HPWZt2idC0$%)=)=7aW8Z#AEV4(~Wp>jCC@%SX^q=+6qZuvCp@P
z{!ag49?s4CJDw@6A!F}oh5cHlp<&ox958DxmD4Tnk@|N!xR3w`_E+BpyE$~gkPuZ9
z(e>|fWCx#2+xnDQb#=#9&UnClrYTY=r)J|eY#o?lTAYF3cGx`MC8E!&u$f_UZii;i
zgp%Qo!O$YUrPdOrJl-gJ6*Ik0#iLAX*mkUlKyp5bElZGA4;2U85a${y4`WYN4@Woj
zZCHMAUN7o#<$(SCYTv2TW70-h^o93XzbwdEt(SbVOO`fpMApvPWyGfPx!(5|o+lYp
z1Qi(0)R_NPxV;R8v*MB)s)}$K#`D*QS#{d{MGi%gx9zOJSQL1z;9Co$@w)qHTKfz2
zxz0Cbk=?aHH8XM4B7R;l%2r$-o*6!ySSMH;soHc8k$aTC5|11rTvejhyj6R=mTNZ$
z<7!P_c++2mw*)SA2`Q<4jgsq!YG0d0;yWCCJ0Hfkzt3xF7|~K4DQ;w%J=5xo>w_V(
z2Nmuqx>hjXnwvaU5G_nd%cbFNPG`C`*pOzsb@1L}McTq8)(ZuQYQADRM}wP}T1HvQ
zR^Vo+Cdz8Y{eUQo*EO5A+>FBs16zM11qZc5dMJev!j9_18u>IXk-sYQOGY*T=X$)Z
zNjRmh(p-jsE`d(L$(}TCYM05HrN5RW7qD9lpBl7~p0;0migJpxqpge9Km}OERDfnI
zbP`wz;~YD>=&SGBxO6ISR|Sl~hQXJx5n@{9<~`AEvXHgVBfkRAG)a3)8ZbAXuwxnW
z<T)t;bdDHQoCA`jXnJt}Vs2?WT~tHk0h}FHN>v&ZN(2Zm8+jKQ=_S
zaUl_42}zHJ&00bZ)qYOPIApGl3R1TX3b|0by)A6$MthpX$rhWqnu}@dLX^2p7N%(%
z1nLh#jmm0J`9XZUV#s=7TGnY=Mgpw}ts)+-BNqDkdlcsqGtE
zPRJK@R292~i0OxFI~_#-2JX*dY`Ezp`oew{
zgE0^`>Dc7M97&56?6?J_fPHXBHA%GC(J!hLw!R7=$gp%Dq=vfv)HdDdOO)AlMPHgO
z28_CLg{Er1#QA5uu%AxUa?+i&1S@@^IuxqLSBA&lW*i|m{Ts&_D4udVsEypT5Af@6
z{f@qjlPQV+r@hDJ!ex?5Tm?CoFd9pjcuBc5OOvWsa5!bHK*s7s>$vdiH-I#?&4or+QxP6Z`YhZSr
z)W!;`GRoU`U^{T#@b3ct5c*iOb-!t;<(!kPX?{#z=b6U>gmU44FeZ0L^^4SCIo_4J
zg{d8Z)A+=_O%SU3I`cTk4O`KIx~fp-?Ej##11igJ7_0%4m_z1q$VitzKZEXVnDMTcCW?2swD9ADp5>>_s{W}3Iwm#DUXN$=M%
zrE`#-)89)ggVj2me1vc^7&tT%Y&y~|3gYR$#36Q0$CROEMPb+hvt(h|%Ou03P-HKo
z{5)>5{7z+uT~H&mPpLUlv5q*aYfQQEuT2s0~R)MlN233?AR3T=`#H+5w*^1
zOCLlMn(QLYQlna$edcgfE7`(&<+T0PS*%}<&3c<=l7RLMnY<&Dx6gM(9HQBVr-~nT
zes(ip>d^j5h32pd1-Q2fCAOM?L&2{g%VzG?fhQ{iRmwz_Jh+(qA-27rI=N&yt|Vu_
zxyU)L*XMhE7hW|z$&5*^JQ5d^^DQkd5hR3o44mWhzNXTHvQ+`$G1)4=Tk(1W<&Y}^)yAh_!<_>W)hDkm}
zK!+^gI|rBIaP}=G(ljt(PwXJjecoX!ATOkE1#Ah+K~>7bayn~|q>sGXS2*L@K_2<7{U@!oQK7$W
z!(HSOBOcFS@#%f6Djz!c3jcJb)(;c*L@e0sON_O{@Frvx5x)!`VSf(Kg+Qmin8vEh
zu3QpnVGp|wS5k}X4~i4?GQkl;6g#nC1+sJg)JA5em;251u=9ZB+Yuv6jJMm475$r|
z578ejng^lrlxcyb0_s9o0~3|Y-)6#)lm60k5^VRR`ZBFH2)G4Wt$eyRtcGn2$9wd`
zSf~-9*)k~>`*J2V*bAU)1E>_t)(_JZXp(SUMg^L|ztQkET*qOxB+`Q40!dTHHk|dO
zqMPFnHt{(NsD`l97hKf2#106EejBRgxEYfaW_ll{Q!y=A2y(F5&_5T*Cq*Rw0S8HZ
z09O?4upkzIsRtVMvmV&o;|la>VSd6lDuaD}u5Sam8A0Ob+iU1a4VQF;{et%?JFd`$
z+8}I~7i#fF$*5@GrTm-
zW9J31L?86&3zaY>QP)fy>KX)!!(9$K0d=L@d{J4{wF`&EkIbX4J-ssNUp_ANI8}4B
zvC=Gau+!kL42PZX;grean(F)2S%V^3HOn-0xCCoAC=#2|Iu)mAH?fl~ybm~m-?w09
zU^WU~TIgnZ>@qYsgTByDFRrhKzE8&HfWec|!v)(If#BdkeZ8e)m~7bScM!Q~6qm%*
z1|=?;>@%C%WQt%$acQ6VUsn-t2p@N>eaMgy_cOgiI#fj7`jQ}TSBJ|2zjqEBr*VX4
ze{j204?_$2;P$LAxCVt3%Ml*=sOM9y`h(jo$t+Zrh7d!Etxc`p(H0gagU%9?$T>)0
zaUV$JswtF$x
zh>yH-Jy-sdb0GF*f9wjcO3#;n?UbW;Dr>81OjvaL%tP(7RPwH&qvc(6#c7Y!$tr!k
z_As~`Ylz0b5CdWR!42wmL3WI;Fmd`Tuxi$sV2rWBYr$FSC|b
zvnK=9dR;Np+Mrp(HbZ^a+u5ZJ7S~~CmX{7Yx#Nt`ASC4^XJ5nl
z#;4VZ`HHSRTfWTC>(tEUrS_g4*K8ONLXEf)E=;pQaaV^zRn~sj5FROX5T#B?_N&XB
zyU+I-M2XM!jT>}YlJFG_9-&4q8E=3(cuy$a!h{+xI&rQw`k#@RNd2v|$2AJstBnBy
zmslnYw;S~JIIU$Y=?V@Y^)+(^**=-nN@WKUg~fsmpVG&aNjsMD87F@6v?h2a?~%{C
z;x}iolMZG(Qe7r0c0$Q+ldbdh>3jovAYYgfak)Tmxna@gFJHEN`LX3Umg`r%K;=d*
z(Q=i?o;Ivize?X(wm`q^MgcP)q)ArUjr<$70)3|~Ev?g@b|YWEDy=gY1hPU-ix;s4
zL#^zk6JBLZJBF}BR&Lr2xJ#_pRxP*W=j-yBe~I4~al;}jjCw*>v&0&`I<1qWEnk8C
zZlDlDaBx=DUP4I6LPeixT46_}w9iu>k0@03>U7&}$4(uL;1I?T_Wd-(UG-tnyN_tjftHjJ_(u-m7Vqt>VYB7R#2M^QXzf
zepe?umw&E+Pv}c0UvSQrFGIKFE8NY?~lmag96xC4)Y&5$gnPW+)q!p*W)>$zHpwlH4Chf7B-8u
zg?iX31}9%AxK@k7+3?f~ec{!DoC0RS$jN6`s*(QR2+MqIKv`&*g&oi>qGO2cKW3A~
z&8qz>c2kj0!f-|s9fjg~j0QRd7?DBpU*Q?p?AD-}Lpfh	k2Qats)Tm7sP$2}gu1vqy%ETM;Dj7EV
zpAb`8M|k!}elca!laKo4RKOqP)JK1mQ-2UsJj4_;Br^WaT%T*nJETbs{=n36g|H7&
zKN$9`O5D;8r%FN7K;rt1EYEsemwGSXjDv#aHzL?>#wY#WiqLkE$@DP48SI~}*NZ%^
zOiyBg)^Fru`pRw(vt}_}7Ai-TOuDa!=pJb6$k@FgJW74w*DoNbycF}4+tY>Y~`f=0j!7ih#s%Nu-zRD(b+
zEU76eFkyTBR*xucDD!9f(`E6AjWOXv+zA5F$~#J6qEX>B5iYi05#QK2YPj3=ad&gA
zx{*sBocN1ls-~OO|BCqi#>MK67y2#+@VLO}apB%t?xwgg9#=unng;!K%4yTF4KeRX#jXO`c4BPkGuEl^0
z#jLO2ePoX9Bg$#~7t&q6Sl&<4>xxAuv8-vmCU>ylTs>SMcTTZuC1T2x=0b0Llo}eC
zFAgEpwVuY;qzc;2s1ROA`OaFbF4y|rv4YF>m`^6Hq}25$q$_R~x1!gGxCTGP
zDm_RR(md($c`p3Z3F9%#=bz4S;d_kB!negUkDB
z8*_f#^4iF5*Vx{On&nnLyZI*3vwO|WxEETC;qbUFi*G*mDBt?InDF>R%F_s5I8uE6
z@oZVQ>n-ud<74^3FNs68rtqf@i^A4jW9naI>0;uzF*&(Om~FU(FRk`wkY>K_`PKL!=-c`;uFN>PiVPFaVLIN;$QLW5-;HQN3s2hNY-qn
zZK|^53!;koLKJLMxu?Z#wrKtZD!yck8orxK&b~OJVv}by=*E8`{@oT~bh++yLq1^C
z6WtuN1(z$?6PV?4ZR}33;iVTndD0UY{?*+s*MmL9jaW5xBT9^%GJGVih<_o@*|vSa
z`}wx{eE3K)Vf$S+7OAS2WkPB8vF8AI@z+$1BKyKF_lJ#cYW^+kA{B`>l9)rAo$0}aaDt@!$UH0`-
z>0LuEqoSPv{!5K1d{kXq=|OHN3-kZenWNcq78gEBe16v)KPe0D54yE$&v5p5Z2T##
z=6PdylFFIbBeof*#OI!TX2?X;ghjIyt)s*VWp@Sr`?KzmGMIqacVCAT_t*9C+pVMO
zj_w}9@%Ya&wR=7cVo%*?zeZG%uZi2A`kaL>-n*97{o}o#;}+GCrz4|_y>CWO6~40?
zW^vLg?+xp;S?$gU0q=b5qrhI
z^KkxNAt)F{i0G)$i_`bVu)xLpk20rsznMAa=bvEC`_KPH`K#;0v+%BcVXBfP3T+VI
zcp+)judY1^B^r57l=YgmoV{7b1#J9RAMi<*%?qP7zq$(WcJkju&w=P5lYg%7n*2oO
z$`n?}mdX{gp6J29{^?QR)g_TG_V9Xr@lNb50>IEMTB6yAv0?eB>es&|QvNJDXc
z)#{Pyc>IT;{cC&;h**{g;~xo=a(w@@2)KOO%;LE0%EIGo|{H+!u3%ATrrd0?!2
zcXxLBc46>E9>u*Ze)r;^1~R|vrEG45xcj9$IGI@Ul9szAUV3RP_k!qsX=Gw~H;;Wf
z@4tWE_m%}u1T^L7oxIMfnNS2!T=N-RbY@k0`OYDG5nI71fJ&{n{pAE6&Kob!QgykW
z22a6<`(+(pr4>h24QEbD)iYvqRs8VRkN}c#b97DiudlGd!G7vBt=L-?#h=uQQAc!<
zCqeOXEeBoQ=X$D%kO6;@c+Zi^L*DtCsJ;S4AH;)4vX#~Nysj17j>PfRT5;%6T?Px0
z>PHAqR;zS_aU-nPb=@Zy>@~rMW=6`z!H1y86)VKgZt}x%gyremZCjyF9rAE`f;*{W
z@DR)AsuUkPI)>{Kj~t!G%@Dsns?Wj;5`?evD4|kWP{wie&tc#|3#4K8g4MFL1h~nPTlbDk;ZW*W(RQk
znTOZ4O>`WaiKoJ0$N#DdewWBO6ZpjY$49GvZS4Q}1s~T3KB7*HR((A1A>iZmz{mO%
z4+L$)#OqJ><%vR@&>u%MO0BA1g+B7RmD&J2HS)k!!F9n6gnJuq5ZwQPI|6RIo3#S}
z`wIRa&Jx0E{Bo}f5Aw$K;>?)#x`ujsUBTX7*DAb@o73Os^^JD)6p@0?aC%uW5kL6L
zgZvq-828syq0{xAmuS0O+i6t|87Kb|7jtkrbQ8GKbtI%$%3x+Z(YM^1jM44n$DFttuNrQ>WBczqU;snTbOXJ46bo1F)`{{`=5;{Uw?
z7l6+I2XF=WPui;p`wqAX{0wveT|hU$Wx+5G1OkJBP+%Ak35*1^S=dpJfoD8m1SSDf
zfEmC{ARWj8W&`tpdw~0Zr9eKg5-0%H0PBEFz(7X~xQ`-ipwe66-v;aicKgF^|BgI@
zfD=F?@B!cet^ikofy`J&1O7(5BKiREBA$b*00!a$;U5fy0>ge6{u%r~0IX7xa7Wtk
z^PjaEgRrr{cOd$IRZ0t*uR-$zFi`MLgx$pV&p^lT!lxj71~3yy2eN?KfNdUr1`>DY
z{M$cs0lFCoh2?fEkPrWCxZS`!;65M{VfVltNMFAgixzMI4gGi>?m+w%_`d_L0!M%o
zi!uJE;29toxrC_30D(X#FbS9f48+faf9X*a4)-1)9moP^0|PVz74Mh}Ivjq_0M-B_
zfk0p@@By$5X&zmI@qZMa7eRaqcpaz#>VXEJ5qJ;y0Js1+fUCgQz<0n8z)j$1U>)+=
z3G4SvR{Zz;W*~0n3XELiL+AwH
zzZJ|qj70$i7J!D~zZ5(PaZ`XFR)Kc)|4p|rYj*nldyPS?LGX_mpR`GnmMccR`G_rW
z9k|m5OoEN*Q{ZRd)Z@78{~X2vI09?<5x5O--vbW7A|ALElMHSaZdtOc|Mwt$1Kblp
z4PXS_3}78FcrVhkFu0*vf8<`<9wiplY(y&7qY{i589t5gdK@yJ!gqQRCIsAlz*YDU
zz+EF^2ExrpW-9^4y>=tr0QV~ViYKjS6r_6HAY!>OT-;VaCO;7EW{n@jIskuzfgwN$
z`{@7U;mZ2`3b;xjp#PgWYzA`u-*ULY{r>gKi#BaUDRdF7
zKU~KP7%%ug1B_VI-RPPN2oHT8T?%&}!r5uYOt>7r*{#@9@V^dB0e#2wqOK-x_}EGe
z3&40rAY277vQm7Y<{8_2hmh(ZO2Tr#0$c^Y2EGGMfo#kHtZ?81;3mQ@z*PW0!~Z(s
zC&AwZe>dO-enwtb5&i?P4tXnpEAZpBmP!F^Li|=B5dOjQu|gUUnFXTH;5q=F8yF)(
z9(@s0?=WTrun*`T5E2M~7w`en4Td`fbmQUHurS~P%MW-O;oDwD9>9s0(6xwjAp8n&
z&)U^%i~cOO)jlv`I`+OZfpj1nm
zH?Rr#09bAyq`39pwKi$|8=*O;pW#!@;y0(G4Eq!Q9m^&5`7xvM4`2KKdJ{Nu5mV9d
z5BzJ6zY~>s<}FhM+cC>Heqg3z&i47A`&)@vUY`%7iXHWLhlXQAEa#N{bexnBVROa2!8e*l(-!r=e_

delta 17314
zcmajG3tUvy+CRSbo(lsajG%~sG8aTHYQx|KwR9Y0b5l{WGPM)rr7@AFvJRCscq`O2
zY-0nKJWSc`Fy^!)?Vvb
z_h&uNv!1m$wo~@nAMEH#hG>QlBdWIxiK?rBs22BzqY#cj`rUY`ddujv2e%(0s#Aaq
z7}`Ws`M~lwh-wwE4cHH~01n_6V20-3YoRqhi!yiDe5!HF=;Vl(wxhOPM70Is_f1=V
ze|n24JYtiPs6NXfs^R&la#LeD^Iftt@Jw=Bw*+^H-TB%Lpcc7+JW(QY=?o+-ZrIFKA`-Yo#LNR%w=zq>r;Jbw#%;rzYj;
zXM_lENdd90Tf;FzqnoCa*(nMxMBpXYjI$q;3i=IHn*
zq7!U$jOvy;X@jPqnGSDY!5V>Kc7|kktjdfoRkxV#95&jeX;Jgzc=PY=jKF&iNgE8|
z1t&UX+3$E|`nt~h6UVpGl0X#7vO~DE){P;2$STys6nyI>t#r_d>pEwvo8(+T^!X1-
zC5Fo(As31MU8%ul2#AXAccnU_ZV8A=#2N@C>PaE3Sxu`euh=Tdt|){lOhhN6D7mGOtuwDh-u3TlJ0oN=VTxjt
zIifX37ya}UcbadJ)rRlnU)7qpwBi$3$rZpJU
z>Gaig#3pR0jA$R1PJ}I$#Qwjkb9)^Z2HiqBpIeK
z!Wp-WV>EP7{Mnco+kGR5N&z$j8-Z0RkZuS!4gYscK{`#-_lC0G@NT;6DEHsM7eIgD
z(O#NF#3@}pLelk?wU}s!_H^7}bMJHhHST$-Q^XfPCS6U|8%}U4OH#HwbiuWy^Agd?
z%GBvQzdP=Vj7;=w7UJ9ahO_k#4{LKplGP3C8#JhNDpPbP@a&!h(rG5lm5t_5d#1$R
zbHJR?D(iY}dyOH&r`?O4vI;PYj7hiMp7`;J3iMC5
zv#M4aW}NHXDy0`gXWSRt$_%Fyyj4mwDlLS+ASHwMhwGSa-$?sr?aR$}u0e^%3{%kg
zN{9>F?MWXq`bxydIUnGs#tt4(gJl^3s&7MTu@g+LxA_}`6ZO;bPfA(Fypn*J?^Elh
z7S1cB`((b-)}=ssDt-vREH*xShR$^@8=_)S#*J&Vr8f-MuQB@7h%Lf`&NTjbZFLpp
zxLWM#Hffsi+iN2V)>K7VYQYZY%08EF8yvhNcCanWc=B4#&3+44SM4y{Zg2l+NH5!5
zF008UXz!%q&|UfKKN`@RAHTdNm(l-@(VZkD#ddq;N7;9{=y!s(y#LW6tpo4jgWXklEb)yY>3(JF#M
zgRdDflF{;~hGY&5kq(=Gv77#6VIp(~`0zNLt-?=IzIRmKmGM&md`&J&hcw%yGX}=U
zWS&BN9pX|8?c5oZIQefS&fZnx>|G_!q6AexkTpJ~bvrF`E?UsY;vHBk@WKKkNyEl?M%7w$`#|W2coFI60bU~xzV@D!f-p$R)dHZ?#Zph7p1j3?a~5N6PAWA9j_i5
zXIp>?4@;-54RA2Jeudy9O^-mLoYU!~mHgFqo0Im1R({9XryPZ*YV5dbNuyJ6JIrh9
zlI$euZ!;sW#4oMM&9sEL7Bh3p7@f>=reVH?8B>$18o3Shk@lZV(E?+O%(OTg+RG+z
zGRrl`<+}*}aIBLw#wKi-CTXi?hj}2X&7T=8gfdrAM($$dGRwf$%NE*{dL*U&-LY5N
ziV}+kG)a~WeFr1kZcev1NlT{6M^3Y+w6pgzBbT&~pU&v?L8)t-Z>h=ETee9{wC!cI
zn9MT&$(meRn11Oj{j&EWPW1LNhL>5G{X3D%>|7`Pi>#AQ8Dw=r%fdu9{l0eH%pV(|
z!Xe0Md7~vUf7Wuu%Qu>h4wxUaduwF&O7E&=*%zEKGmCC}9?P`#6hSA7Zogp7wCK1?
zWv45VRiavTcZV`9s6g{)3h4W~XtW%3$_nG~OPgKQa286e&t{>FM7lOV0|EY2aebqt
zY1<=_Ha2skSp<_M7^9ohthsTOSWDr`5o^=T8FDV&Qd7nVp&lB_EIZKyF}fi(bhtA(!3eSO8^YINsU|Gu|_^k
zGkUzi7-O$8_rF9p(WU?u?5wusS1atyw~o+42BWe5?o|GWwS@?~_}4Y}45%;~U<68r
z%!;+rIRg<){C{Z%r5K`4JL%A^O(aRdh0mmXCI|oZFwL0;C>E@AqK*&O#zs>@sR^_G
zl$?uzJlO5o$&c5j&Zhge#Xa;2Bb@VJkXEAC({)Uy0?n;7o|GzBl4h}AfMM`~x%AvC
zg^V`d5{rf2345;F*|Y2Sd7cW%x!7YuN9bPW>$O9f3jV*ekK4-rLyg-V4I#v}wQ?)O
z_*TiP+W{R&CP8&UPOg=##(?;P1pQac2>C&C3~}A%5GDHbp(f%YEj7RX!u3tYPMCel
z^J?u$X-u))Qp*LYDwtZ(UL+9nXo&s3(pRv0C#4m|0WsbES3Q@{
z(^Si20r8wfS9b~wZX!f^Y<<<+gT)r1*q1&^FvB0yr>@GW4OD5|*i6$;bklC!kx0rh
z%sEyD3?i8rq5d!(bGegNd(d+oVL%l9J=Q^p5ay;s+>d=gbwQu--KQjx8Y;7xJgBeZ
zLGj+9kF(KyIdEF1Y8p^z)b0Uqn{TS0-XoQ1@^pKoS2PfT_}ZXh@U=v}M|w@OM=BYx
zMw+E#gppoFp|T*hM47M5qlY9Se1GJxc1v+a9GXs4w0=WVb}Y4Zc!@2pmpmD~Ir3b+
zbd%qhq-Q$#kCPJnv*tSKCQUzICw1_blg2XN@&kq^4n2?&_C3sarY&w(_SBnOqpH0(
zh1hA84c3-J(i8lQ;e++xmiFh=9MOWCpC-b~o|yW!t{1GNLEf1o2aOh``B#T$gl&FS
z-t|kxAt}zte?EMI_GVOajKoa3-oQ+{+z^=_(JqGp#g1x}E@;9XTcsgJJ|TI*0QG2v
zi&ebkVC!0b6;_Rv^7!@1@hmdmOE$7GM*iDm-2$z5o!Mh&grQzdNmdKatxc-J^>y(T
z+0D!WB5d|6@`gYIF#D;n2(5cWl6y((Kuk&&w4%BxVtPb=WS&xZ&mWPm;grHVevO{h
zh39LADg{qBKX*hz4`DM=ZH*?HB!sajJnFho^lBYb%?RIk_^l&+GNrJV=ToN4R0^Fw
zZAExN|3XzBNeyouzzspI=Y1h`1h0=oQCbac-_YBK+E*AttE5${fl=3QO@%!eJPYue
z)C9Rg_|easQU~6v5Wew4o-a%f
zPj#noaJZm%S2Ijf^(0oP=-ykp4>Z4b(^ER7Y3wGt;f0hUy=0v~8`J&EV_QLY0CcgzArRqf_wa>TEz^z@6&6C^N%vq8iC&;AZ{K`=)-g
zQnsv2&XM#YI}wHjc=2{Ss=M^AcdrK(wLrS*ojuwk%)S}jNT7Yw?4kNRp~_KUUN{`r2<rc+s!ns5wlMJWf?pK)erRgZ+#~g{?mx=HQ%Ja&B)uagAY$
zb<92@S_wd0D87o|=108suDdBbDX~$n^j5s~b<~
zaM))kWr&{$n|zwZDaiSUFDhkUYn0~m1{exBRrjRP-?x14O4A9A?L}-Rp(T}m+S@Fc
z1@b{NQaEOeQkdaZk5src3el0(QX9%27;Bo4)fCnqGF{$j8o1X&#ZZZRQ2iduZZqSc
z-U~+KbJk)pBU7{B7#YMxwnMmdPE{*~3chIE5GBpq70Q>7%j#d^IV};A$BoX%@c71Y
z`N@89n0q$o7oTzW+o9YUR&9@E41RH-J8UPz#Uef4;}Zh`UN>IH{^8}h@xvl^p}J#7
zaP}sr%_ojDK0Q8+>1$$j)Q=}y
zbk%@e(kk(rCnhUvk76qv?jeO5PG3T0
zM_qrSX#?y)3COP?6o6WQL_p#I8o&Vj3j9XHNTT@}VOu|FR-iTk*Z?~$+m~%HGyD&eLTw5`=ygA;S_~*(*_1ppxhS*5V@WPNq=_q03Nh}0
zX!I)uoljRtv!4+Wi(K8H|51#3vRSMlUZwe<9CUggj!@Toa!V3;*zAaS>mnDOx$MB^TDcvFj
z_84@Kx({hbsi2sKfzkm>SVQ<$E!2-h^GKdGHw$4_)5JU?%neMy?*qZ#;y@PSMZw?c
zf$@1ZBIF|=0v8yE-|XP8DKHlC`vPMN#}6Gv2(
zrzn%RAWo;c86oAb-##O%tZ?2qd0v!KFdT(wX}ygibX7Ei__rpvjZp~uyStrA!Pl%5
zlt+}pkIhn3e=dX@fD?QScK+sWIroZrYb(o{6H>V>q|EQ;-uW!b}E
zPS^tc=4@(LJQHaAD0?O&R|@ZX-^e+QaI&}Y%bb7Flr^5lH*?cuVeUYY@WgDd*cIT<
z7R2eg#T`;?JzFR%VGFZMR4pqpNiPoEJcU6D<+EMKcxB-@dAGPi;!TB`h*h*Jy?Ngq
z^cXf)YK)z3WZ3cmKYhkA_UD$y
zu$e1Z_JW_UoR!2T9B+JYRvyD9_<3RWX7+-QuPjbs%Z@i5DBi`ef|t*m^EV9gzr6f`
zIa?7~E2>P}st+~~3xzjYe)D{fcm3AC~9HxHRZ3wOK@l{Io2uW{fdeNFIG?C;Yfr(H>
zO(!emT`_;>zgsZOmfC!J%rW!t4yA_(Ldzf=03tlHThSfik*d~V*?Y}hj^CZ6br1w}
zWa>X#Wh>9booPtO*xG842EdI^`w*GBqZO);RBq_`CYt_*vaXnwytF{Wq(xp*ACg_^
ziOVl7C|7e~7F~8&$?42pIky~Y+c9e{jsEJe=Bm+%Y~>|Wn3-mJPz
zjdI%+i%ej8Nv$moX|17NT3N!l)+(Z*L*>H5ZatR)LBJHqg+li)&d?`_N@`MY5nT9m
zI*Iyn>a2`5hd44}9&DAK(=>YTxUQDO1?Tk-oR>9aGGV%#Y6Ut#by`ZRT30Qp+xl@^
zbBOJ{HTRv)aQ0jSab+>ZMAkW-$b~;3Bvnm*aYR5?c-aygSLdk|Orfe4s#54Vr-~af
zeHAw%-^8t}LnmJ77WYY8r3EmA%RLAU3Y_3biqWo2-`vWK7*8(SdPi5W^Q4jaq
z1a9t9R`{DoUuFZj`fp1I7b>_sZmTq{ZjV@b)9_CKfhbFN^^2fITXP&lrsGvt%?HG2--}5eBC=zIfStVu;SRg=6~X|)rc=j
zBTeHk)i)+m4tW_|p=~>z`JsyqKjva1(=R=f)8$~itS`~?n(tUwo(&AI<|`geD5$)0
ztm}m*LoeY-yRgxF^OnrZ-bAJ$(X-m8Ds1%nZk>3Xo+E=tUj65Erx<$9m2}Qc=19V(
z8V*%Tb!z^~qe-b{=o0Og1+Ysi+o&CnHg7d{owg}ByQHeLOX1bk(gJ=|$#TtehFE)N
zv%;l<2$NtLq?BE^tdpKI!26IbqZ0i{iB84}zw^XG^dVj7#;bCvCl^&XL9d_pZkN>R
zOA;~2QHYsvMp|3D>b7la9%t0ex2zHZ4E&>o>!l78-&PuDyKV}eS6{s#O(ItlSYbXK
z>QBx37u?4^`#yES>z@Y?J63uU7K+x@6&A7|$6J1oQa+nh62Dx*C0HW3Ma!zWML8=R
zywtz;h>Junvu~5s)kGWWik8W4`<^-2DeE8V3h&2$I1gtHxe$dt_hQM!LYXee2oI5c
zM^9%yljC;0Xd&rS?Gr5-+^pqe3eC_%Pbep5nwdo<6CgL5niXG=&}$Mm1ZU2#yNlq
zP^VD_7|da3j`*>jByAd|;hAndXTH<>_}Y3v10ThZUlig@cCCXRLgB+44A?vMaIDTSZnre6wnds_-Hlm4jBP-K+Da4Z+UeFj
zNm2+5g+tN`%@MQSzOZm%{&|U1wo7vi2;07s=G1M>F$o`6(nAEjUSDBA9+_W&Gstq@
zOmBfF;NDjz4C>ZAPV3rI2^uRI5i<^6r(M>QQjOuHR1KH$a|pLuN%~xe(yQpwmlZ(V
zr-A{V@6I09*hPw-J!ekPlpW!}Sdz%@eVp%DVuUt0iklq^UL73>}f00Ed!?E+^w6x^h`rd?x$cu
zO8bp-|MK*Lde15s^dqh{>kPKkA~yX~?@h6&WA=ay`yQ8E*63MtYknx%GFL0(b%pFd
z;w>;awrH^<-|03SrMLYH$U9DEga-FqR1aPE{{O9(^3T_ivhij>VKw2$B&@J}`PW|s!Mqj||mHFsNwmZ55rO2-&Xa3sXfI}jn*c@_Hdw3WPR
zl6jb&&R3jY-Asi@Li<)J2O4l-YX-+?83-C!M+RMabT+PW!I=vT8_fzko^32pr$EF8
zL|x$YnA)6nNGxeh26wI3bU=ee#AR2)T>(LwEUB82|GHoN-gDu)(O6@Cs*`1Bp8r8Q
zR^4;2GO7rMZNK{L?(7Awk!C%|F4F+guJUfv|E9&@37TzA_mEGDZ{j9lcYtX^Q
zy&Ph0O)tB=^n^69?)2E4oSz*%GMXyR_yT&36JN%glO29>x;qwT*c!9Kam5l_53{ip
zo1xn;zUg7PL((;afiq_AjGgKt%*pG<40N>!VyE>7DWQ5u9Ib7AL-0}vPKWn#Ek{!B
zx$L+?M+$XBWe-)bEifyob+=|E!F!Q4l{lFjAJ3=iHq?^C`=5xn?ZF!mh9@I_kSexJ
z;%0E6T`@0igSol7`SjQipf^o-d@PSQGSS>C($CiS&@FP$j9vqcNvh>$=kM(dh4BIV
z3dV;V#>cq^_KmbhN{3OSV~pKWuJW+Hgborp+D>ZhrnZo@i>xbwjFZ&0Obug884ZoT
zfXGvF?XnaZ|Cn8#GUgJ!)RyfeDNBNR7p3aj)x(%H)umcjD9fhFFUfdDkbxql{{9^1
zT%u>gEq2G?Y-WsNA+Do;+!JTsQ
zv1RHIR@mf0B7aZWcxFETc$wC=fb=x=W;@?Iqhlc(`ev1yosp>{+HpLQ?N}{ax!tTi
zUoCaCk)~rVCNjifmu_DP_b?cB1dcmIM-MlQD?z4_qBYqoH=0$K)~sYQwwn*P4&kbC
z7Fo3-x}KVq)?EB{21J()hB|>yzX8sqPQOui(Q(>y5?(!JR?cO;u`
z_BY^8tsL5PzU9o)3zD_%gcRQPNXf90szoQIHcgzxj2CKgC4P7%PhQtCR`{u3=qM8mzSjv-3k_=9=
zAEejbPJbkj9&Tr}Pn0trnK!<}#zrdaRXGFf37O-hXku@s?E0JIqI4MNs|sH#WD?!t
z({=DWw;ET1S=DjVuy<~TnXmVjAt^uG>4iSMPbLjs(a~+X`SsIl8uoO(@JvHzc4SdU
zHdFeo>88{8jdVc@6Qgg?d^^0!G9B-HY)M6ATixI(-{xF}hx
zcQ%Ad5p`!8+8V-LrhYxk_X@X}Vu43noJiM}eR+3C&&uh@djLUqn|9L4q-6kIhf
zSZ3Hs@~Gg68(IWAX1DuF{Wj@CLm*vd*Oh;3Iu|nV;zennW&^I5Qn+o>yBZ?APJ{G#J)dg^!)H`>43ed2PwH>fgPfZl71yCB(KGn979mfUwVA#@j`4YC&TAip6p=4|2#nG)|W3#$a^u=vf5O@l<>2j*4S#%mfTefp8FWx
zqr5lVOTDpe2KthT-U`vf0X+hSV1l-D2{TsL?UqtX6kVrRV0h}#32f?Xt+0Qz_2yW|
zPvwpEJ6G3(EP6Jw2ZMQ
zaR2S>IU(XA{Fy6GZLr|Rz^_4}k=4|%uwVXAyjFsRZ7H^FFe_p8bZFK{Gc^cFR!b~b
z4V@=BmMy>8E24*Dp{u1|4cSKr6~goMZ6D|v@p9(1?Z-(Tt!cN%uuON@+(4)gzdZ>eDJ!pfo2FIw%
zCPSf|8)~^{X3Fx_b#T@%Yc%(Fbc>AN(wwrK?$VyeEh$j?G|y$Pv7yf{I~kr-m{fGx
zB6qD-{sfn}W)_TGxL8&h8u8+`(!iug*$w(b(#lG@C>P*8imo?stnlAB`%UDgLR7%8
z?p}vHJWkLNeL$?j{UyN_AK4ZVH38J2A!+9@%vARO24Xy^}m|P0sG|gm07AFhZ=RVQpzi?fr
zuZ#>C2QRe^3$0V=j8o75K38W3QmzMYQu($e|BklSppBgq~+99dJP@O|~)_&L(h#cU!
zpOXhm{maLUQ;hx@ehkWbr`*$V=}c?8=G*Hm_0bD~ekq|42T*espLjh`>k606HP4-j&5P?pTT>$caJe?g
z`F?9h$$etChrf4i+%TW`sZR+*-zPTuD&rwtWTl-U46V>D&hzmr)}B;SvvqD8KY86`
zdd>0jy0{3R817^A+0Wp@x7FIlzqig5;}b_5QMag@vR{;Q^Xn^@n(BSx&tBfQt}0l*
zu8rUDO2WW!Pa58-$X%82S}8sBn$q6JA9-b1j8_czv^A((n9Tm^zdI&s+~|MOXZ-K4
z%v1leuE%}C;zgEE9OvcdzM4GTC;r2`yjlN5ChVs@rOZB`_<@&R@-mb3j}bToZb6-?
z`8}_`B=?F2H=k6c!;o7&d_h%OoKM{6X^SuIR5AO^PhnGB$9pBJBQUtlRWZqVxId!a
z0j7}A46#~sV+X)X-TOZ2Ja{V>@&=@5t7h6x;Xq91;8!t_$OcIQ;`*aKTp=}SruXNZ
z%VIck&jh?~~YiyoTyL?DBc#MU5%RS%M4sYqBkTM|DBxW!txwu0rZEbFQ4%n_+2VE}(*
z{UT;ApSWRcvQI4c2A`3a3=Ikif?k(kuulQ3@YpdGZe4b_@GoqL!(6qy`I-%;D4+O=
z`v<3r(y!VFy2j7=jt#|3BY)q*Ed!Y7ycAVtw43S^-hz@@7#u-r+coEA8|MdOr
z9LW8MWmtWLKe^GwE*QWoU+bX3&DTC0>JgW9$JQ^jumx?`iJo3FSA9JA&u7#Sy-~z$_k}^F8D2XWx;_o{O^nZ&I%9l1FDBIdHg-qiFnXkgx?hY
z$!aY#nBRh5CEtkOF8*S*HsNPq8J_I;3@ZF~8^ZBM)<5ec{^i5kg26;>nW)S=fu|;)
z^Tk^xG8_3#TjJSM0sg?2xJN$?2+p27a4zzkChzPE{S8k
zO1MfTF~iG1kx1eMUueE0zTnBJhsN_32`^)vpYllJV!yQoyP;A4Mh2r?5rvnb~fYd@;KsiXXRivW;e{nq+wL_CEpoJ}n@QZmmFXd(tlSrX{sj{h4;QH!ZHU=FhaY
z-ZXXVzCY7G=}l9%9{w}!!`?LC@zXtNk!bjx-o%^7+fVT9wij5e=F8ijV1GTqcWgUO
zzYe@PIbsZ6WX%EakjbaN)kvlY48
ze_-3r9?p_1#zfzhW&DGGYy0L1A9_NwX^E_X{KOrT!~XhgT)iWP36}1e5NmH=cOA_d
z*!a=T2!_S~C>`JRuQ2+2d+HASi^L9o^X_kG>XNt0Y2Uwj>l@}p{@_1{#FzU&j-SX~
zwHT%`g2n%nWzw`xXDo-8HbNm3Q7^lfB&AI&wD?CCN6pZ9U6q~Gt*$^zL#n6^}hF%qWI-eL|@oHQArCa
z-sg|(Hx3iUYNX;xB%Tyswp7y>z_o_}2$H#Z_E*p5cdll*s&@pYT!o)cyE=+mju?vtf@pgj1bgk??Lq%8<$i
zB7Epc=I-PEaI&N2mx8hsM~i}^5`+}(4Sg%1#ABN^{N9gpgL7vX#NYg=xPSJM==IF{
ze$%2?5n&WR`{TqRl$;vvKS-x5RW5Z%#>{p}J&Onf`1K!WFe?7&$MJ(Z+y^$)cFIE&
zJ?q^CIjgz;=U6nio4@h#Lw%JO)D8sk{iU_Px;H$(-BvkeS<*m&aIN=RS)DSmO|_=wlOAgX&o(F6WKV}VkQPt#!D
z)0oVv2lKi^x?GwfG!5ontyAgx!`nrzZ15ZRl$FCos9{I+r2%`
zK?^LW-Cjmdw3X6uJSYo@JNS)XO;UZ?
z_wgV;KI!{d{psJr*3breN_Bi%X3Oi%BO0Yv)uh54FS
z7s9~^Z+Pe^l-d-;oks}#>;dtg-KsplIJ%n%5mGnaR&IxKj&NHZCUpIfK`N6C%@x^YY8n+lVUE+#vgFv#Cc!)=B
zygTB(ZW^}TijlS5`l2}dHX)z8-jubQE;}!r<114c()wpk^Ux4d(rPDlyg9QK#1%?9|z*t}c&{r3w>x&P~1s(7R@=Jlm
zchN27h)uN|2~Ppf-jy*51#$q|sppaY67YX_Y8}$n15<(jSEp7X|2`lG=Ji_KFdyOD2=@a^5#Nij
zue{0N;PuKeXle-?NcCw&%o-bQ?OH5x~_
z7uW`D2X+H}G<_YnO`QQkU=z>+EC(J2z5)iJ*A5gq(~BF^(GkE8FvwQ`p+J9N05Av`
z0%(C$U=)x6j0GkD_W_@wu8Y7W;M7B8KK)UB1<*$NdUqZ1F5m{>0{#=PZ+RG_1D;=i
zkph%%9lkdK2PgBMwu!b=NInB}J%axI?LSvF7I_nZ9N_=e7Ynza_
zrGz}L>c0?^0Q@Jy*~ohUcz7|!0sJSrb;w%}jC~xmz`xV+ai4Ft&0dbGte8$<=u_w)
z@OA~Js1ikiui%Y&8{sbqZvda+YM*%?%z|(mJT&y#z?LVm_Yr;tTmn{sZXIw2@#QaL
zY7yT8Yy-9f&p!(wFQ=U3tK3L<7!@@kVK?Fzfi27MzrF}R1GHsWbc9P+p(68{UFL&4T3e`Duk!jp=XGH1`G##-#~r~(iLmLm58rHI`ub=r6J8j
zg}V`d8yE%pU)J*TP9?_-eFaPl(B0!lm2P0bEBu?MHrtxkLq1iZo8bH5Kq@c_$N+Yu
z$dFgjMW7j&fV38bZlvFb_}d6m@tuQsJ}?8gin_i+`Xyj7>UQJ%4C1qq_W-aI-%kM#
zBmT%t$ijojybpw*Av^`JjI3`(qx;RpS7d^aOx5RL+!7U5o+2DH%n
zfK^C;b`$CVw!emsBJUK^&j1gUFDrlY@4W7dzm1lk!1Mt9fhZsr7zQK(X@CJ358N9J
z`H#MMYvQ_E3!{|5{WeTe`7

diff --git a/Tools/IO_Firmware/iofirmware_f103_dshot_lowpolh.bin b/Tools/IO_Firmware/iofirmware_f103_dshot_lowpolh.bin
index 76b5c6d9742bb05bb54ff0735e654fff55e46682..30603776fedbc6e4731a62951df9771143ed338d 100755
GIT binary patch
delta 22408
zcmcJ1d0dp${{MNNSr`yy5L7m079|9=8BoNn#z7ud#jUPs*5FcuqTtpw%LWw<%?f+4
zaH(*+S6f-6D;7aXr7ic)xD;lK<*iA$^?gui4l@k%d!GTib${Rc`|ro=^`3K{b3SKz
z&hq(u&gXm{_Wlq5&LP2-`9NQgMAa?hU|WosP1`#s9r?)
z^GExBS-;N|JY?`hqB@mHR3GG`%9rcba$g0jf~2S2LDD9VIDg2j`-7y_c$nuImOE_r
zYi8M(3#mN1ETh}WNiVvG<_`TsT9CBhEFtWj=PHSYsEJDTGr5iw4NKEpB`TKwuOOn4
zfUmUTtsxVF0;RLPz0N>somWf8<>fVoQXXh^nBB~5Q4YTiUfb0$v5-nrAb>ri);+)V~NF3Y!
zLw;YKsVwnmsKI6$9Xo54Wn{-sGNP#T=}5U!8!yNY
z@zRyfqviKEar#oKPpP1zQ%GWpU8&3K
zESWhvQ$JfJ9q;zJs(Up8C;i#Y(#gDdg`koSbc^>6eJG
zXbP}YitFt(SQ|5^nf7SxRIN?6HdCUt({QaqXr^++BD7?5GgWC@MSa-pC|0hV>f_WX
zmzyFN4mOli`EWapj}!NV#n|Fg)Q#12k0!f;bu&DBhs1G*0@B*HC5Pp!8%@8SNkWCg
zmqdx?Us^foVb5v0#}J%-u3eUP)FabZw=amD+{8)(!%>!x6cU=A3J?Rfp&l;#ODAb!
zosZqwKCif5F7VP@UiBP>kZf%&lv%H>skCKmu1U7ab*+W+uJ6~$tkG*LGcMCljV;tZ
zPnOn#SaIWJYS+qhUXOawT-JmXuDFpjv9~grL&*4>G%oKzn*LZ+&h}d4^H&xrFW@>7Q<&Yl3GqMJ$w<%jl54cgpO%QU3rGv|T;KLKEzy6!{cUezpvw0Gc
z-6*-S?Z);_yfy0}A?M9%ytU8uocA=f7_J2bTp{}7wASEr9r7Nh)kJM;^tlcrT1yy_
zKM8MFT)%y@T#zTITIC7y)^C5}r9Ul|EuV*NSlswYLcaaegu5N#nhI(#$h+De8MC>9
z%9<6@-CS@xr?A{s$ab1bk>~uXsy$dHlkQeLZH{jmEDRrivT67jWqU41;!0_frj#Z(
z+g1^I$3z11xk1ui_oKic{4e?@=D_qp{%)zJKH;C#PepvxI8m
z2F+@wF)54%6xZ*-D4b8+UQHyiWN>RrB9W>}CMV`N_|3d@w@iiSPfCb}uP$!9fcTk`
zj}s03dCJ6Fj&qEPCtY6_Ye&u}q&$H`CTBwa^}=M(M7zPCKwUFF0sSCaU{4((>nKUPN_dB6G|*N?;#Cu^U{$veWy
zQ|17BGUXGOrAIU!qe|@#bC=^X=7HB7&~G_SQTa@!O7{jBiD*$s!P#}yGKOZv~l6i
z?PZ+4imuT7x1yB3&CJ*ol4YOf;a~%ww$WK*P3ZWO81Wm**nUHTB~T8
z;bP(YwA3j5nAf>w!}hW|&#l|C#MCAk>f8m|;FKFbrr#R0e0$kJv#s;Q8!`RM|>cTgA
zN&MH2lHX-aq2fc4qr$&NM#~>EG*qmNjA63!tw?jiXKuMhB|YQS)a<998o1=0_?2s~
zV6s)xG4Fsp^vh0NRBhse?!F{hwV{y-{Nj40Kr}(QL9@44%XLsBrVVcAIZh
zxRgs#%M&MGot~qvZ>Hno4q4?wn52*~xmss{YkEAf%=Ga%_!qTCIh!HSee%Z6{;4
z=7n63E~w0yW>t2qbj`{dRE__|L3E%|PqQAU
z6>9Fe)K$@oQV>
z%;t27{xMl%t;|TY+A3&@wzZHIf)p>R%s^2sdrGthr5#5cirs%{NLDR1DrWHGXSGh5
zeVV4C1k(gA(F$}Y(ON;LhW0(5?0^1aJBikDS&P>2HtYPgd(62G=u`92GvS*cQ%%@=f<+W3TN8w(_N8j3TbO0bS3dbYTJ&TP4mXss;d
zq_^EHlvxj<1rndn7<6>XWlA-NqRuBOu2xWo!E$@1tQ27dSf%*PsEBbo=wsTH1vQE2
z<3sAc5#5UsC17D%jVX{1BxV_9g_$u4KPx~16=e3PL6+_vk
zXIUY6N>a`5Q-3}SElfHsPL93PmYZULCQJ>ec0v>^ppA~n|9B3!gpge#tm(p1&K36iuWZlb2n|hh(Lp<(UfD(OrO{2cT
zO0CA2sxX(qaqUpBm6z1o7OJ{e-qAydbf^0=H)Y!M!Uc3%Mj{Zs=>f3uf$a5_5pCguh+h!saooU{^0kru;Z
zC#$>0eRDD*KGzLzpHiZd=617jIEeKRShz
zCif_E6xk6LMV2zN@h7#3NMD^DX#TroqUuh>(HQL*>eC_!v@4MwoL57iQyE2b$i*7E
zN0jOHSWb87V+S9ciSrgqzf?`PiwpFVxGmyteQdxoW6;;9>3s1`{jf+g*BmuBt=#jg
z)a5Mv#ph#Zr{xhM-6DRiAE_{db;*eH3R5gBl9lfjxc2v+)MzLb_{h_J}iVj}!l7p{q{7Kq2iKdEBcX?!v8k5BT
z#VF1nqq~1n&rY-3&Pm1|jU}}a27r21&hF~y&1ntXD@2O#Rb)m&gmI@B+Y78-O64BX
zWWoEljv^X${gB)tSs|GL(ofzYSsEcg`lnZ;=XJqZnvnt0bf0J+6XPe;d_q(cQD7p%
z6(~IZrj++&HCN6_Z5}Z=u16LieJBpP}@
zf|Nl>(bRA{t&p6j+Li)@dqf5(=_n
zAKVF2(BuGv|WSa*i%I$peT&l;}^sXj|l8is5r8bG3i5umdbe4*Rz)p}RE0hZ)F%PRciHeVp*MTsWibu!4#4q|(G*1wQtEA_9xJ*@JISNz&
z1=EPi9wELoAtB*SuSQV)Hi{;U;xeeqjL($bC-jv#?s+VVnT0?7OnMB&%
ztG1}ng`d##%1?kJ6Hr3AS>~qNZerm&g5@hXnZzqHo0JQ3xiK}h
z-QgBR>N;BUo7IY|E$sbJKn+7x^A7oAB)vrf~Ov|Q42wZ{>jriZo9)rLXqIt>1q+1o-ZnZ1UDjAb(bxi9P!Vg)UP5T`xWD+8@N+Cb3Fygv(^`fBc-a9Z7XD|}P>T@+Ufr%m9gb;itBU~6P
zD1}I@WK67dR6J+6q5RnEa~<`FuNlYbzV*u6)8*XB<7GtZ!rZeH5E<=us_K2NV<6kw
zBf5=IvF~{=-wc{Z^tv_N$pdCp(|&Wy%^-a^><45Fk^U|wC*5It$!idnk+CCH(m6MG
zl1R0vj+rb7nT(UdLW5jLtMj>*dKHjzv%KoMb2?aLI7Ye6OQZm=W@S8byq=-)C!2<9
z-mitNMx!0sm&ShOJ;!M-VX;Ao%^|F0iI;Ua6{?ne*z9#1IG>O>vCphtXQ;;142LUlcCwqbRXeO9+;Vi2cfeL@ol
zCrzEqqU;qJSZpB9LZ%5u_`_@d@OLz#ZBdN)W{P6Ezx40Q5k03FWC118{lPTfiSCiV}4aT$voOkDquZf3}v%e=^=ykpC(+H`JCod8evl$vRy{#78mx^Xm;`YekQo_k$S`o#H@*V?+fBXcx@-l7H@C?8HV
zRX{bc8RX3f?LY}|9gqMr0@4~d4}8kP2%>3WY2ic@0Z4!y&l+Ga%DQFh{0~Z7R
z#`yqD?m_E;)qBjGcz0@`O)16o8|zh#B`9A~A2%m1FWKU@#^s#WL|Fo)TC!%PNZq
zkjDBrn79qrS2y(021qG356tsYk=I`w>b=JroPApJWqyDZN)1*SZU-te7{vo#7c|IH
zbdVX_Sx1?e7>yTYFP!=r?r(A;teC_mmPay+Gs+OA*3ZZ!lEpV2zf1kUi+$4&|C9fB
zp>JxYjY#tl5NVEY3Vw6^znQ*N#M6DLIjPxGGNUY0a;9WY&5g1U>2@!p8jXB~v=ch@
z^LUN9#vFM^Fwt8Kdi^?|>y~>$PPj&I
z$?H6C+W@PZk?33KI3u&N8H~NI8IZ&3nnEp+dfZ5#N5;fv>$8wIFBZdj*{jWzOMmW(
z%GPAD=TE({IhyPp^zhs$ODvRKCTm`Lmo1y$FR6j$^q)&<4qHp5SZ{1Cu{9NewZhiY
zz`C+yi`tQQPc~7p^_7dEW{Z9)p4rgfhmfte(Vr7lS-7};>f)gRl7$^Nn=Ydmo2BMh
z@t3L16P3~z-d<;bl+X|$O$5{pw0^J%CmuZ6}HAz>!p(I{hIY!O`g{EckNzS$U7Ev$w8tMg$j>0dc`;l+xWz;@P`a
z@s@vxad%hn-+RS(?j9vqO0V~d-`pL8$dTT<-n-{;atx&)Udwv=XL%=d^aO5A_6MY0Ha|c;|X3@f=}$p(D0}2;;2jmzpzQ1n>n1%
z^wn82lQ@2HuXs4?9lpn2w>Wzv&o}po_T16@L`U7PxtScV>Jd$Ip5dE4qJ2(0U+SoH
z&pFKTU%AD~xewqqeQwb`w*rwmxA@$=`}u=zQJS}%U*r}y&i|3$(p`7|f>GR5w`+ti
zOK`iazM1%4+Us%Ub(338LuyG1zn^9kWoPk2hBP-eJ)^qEPn8X->D}V#g#wCy(aSR8
z{TU;Xfg8O4rFe^!ACJnkO_XcFSUH5rqLOnf6xQUusF-Z0HFm284;(FN;>b%)bO9@GZ
zfdC?*gsMVWJ+L{4mf#wX#c{F6v9KJc;J)X%{*d2lrwfe^)3`xt&4?6dFf;c|grq+-
zJyx6{)sr}ARYQj6lCAQtJr9ej`$h#C8{}PQHojy2SsZ^~wC!i-elYNmu`f5twqA(3
zP|FUg6-{N&`bAh%$k>BT!A1iO?b8LIUk}NVb?qq>aa86K)K}G~W!L-S@~ih3sf8e`
zE-lC+>pHXHaQZEW`W2OH&}1#`pADql+6IG~8H2gY&trJ)6QHLK*MW
z3r6gFE?Xh}nf~BxTtif}ULgz-f^*qu=!>pU+bnIEIlz$&y`=&N|2ogF9p71W{Uh`X
zY$TdO@Im^kll5Mm5Z|QMmDBL%K|)13xm28Sv^|)=SW7ylbMuL;J(nn?k+3tU>bM+rODtZJEbN4K`{tziCzWMNJLH>p&3%hUDi
zV!U(vX99c%!p0$|WW;Tbfb@0LObnqeLu5L*0bUD+=A06^fbdPoMI$)=J#U=Mga)sii``2i886xcM4T=sG&MrC#
z{`kV1)}3^h0jGd8nKZ3Q4sF5TVJD8%sP2k3)fo~w^-q31MVluMi!<4d?uJH&o~4kJF-CEsp@
zNRPQpS8Eh*t|KU|1+l~C9h5)vBTTZZ4Ntudb3zcCi__*=lj#Sqed6Fo2X<8#%O&bQ
zK*QBnaUCs3QEtiw8h&J3r)_4Ykfd8;-6r|C$_#bRZn|Zr*t;~!_UKH%x#7vnbQ<|C
zMkbZ?meOr=KfqlE+rEFD+<21-!4n&pRYS_#S)H51zZq@)mX3RGnk9OTLWr>r5mu}&
z7gnS{;t=WJsYAPtg~ms>+Q0^fgQnv_}3PLMJc4I*jtZTrm+n_
z8tdR;LgG^#Y%Od^cR3!jlEj(zsaB&fcg@5cGt{;5V#5P5+*a}P2a@2o=~|Ks0ZA!Bu|{MLQu*h`_AyQ4_`$F&4os;WZ~EQ`g;iQZ#Y*(=T64$^g|xH$cm
z*lmfmk)}R|tZQYACO>`DrI73+?ZLr@`Ul;6d-<+CD;LIw`Aa{OuCyOSX};^s`u*nH
z4nrfS-LaZ;2X_og+p&CkQDj>F!-mGb6%sObLTfROmf_8Vh5U4-FzixzE~^!F_FzCP
zM87O%DCOF(+G;z~WgVPMX_qJd>K~0#vjk(ircfqDdpW&vYwhYaQ8KrpOV_60Ytf9p
zO`%x%a4{NUo3|WJCg+Ms`*vc7!N0km{~?clrIBI$d}MKrNU>krOJtWop{cnKvz~2IP@d**I0K5zQv4rDUeS
zY2?xrZ%cn|ua_JbXlcptL)~jy=t)Bhtunw0Pz2MyA=KPLj~gC*v?Bo;Z89z~bF
zaK5mpU@XR@(wjD_u8ZWANKcoTV>E?ti>_s{@)nqp#E9idkODt?evB-oyNa11*OwUJ
zmfZ@lFE5HR%k5(YqGMAd>)|H-Tq_^{v*UUZr|oe)i~Tgn&-a(+f8o?Z)5W=?m&6}*
z=!!gRpc4$zxA8L1N?p;kwP9(~9_s7ZvvyY3dmd)t-eo9rM(1EGY~>F+V{(+`0b+EH
zsytj1DE7E?-P;6B-QW&+aL}nxxI!rp?S(T`zyUZz?aLG@sG#m~{R@Vk$IJCjMR{MB
z1Rv?|5<9IE{q+okljvp&xB+!ufB2-c&p&4Ae4<(jJiV2uyns}1+lRgc3knF#r`{%7
zY(`59y{wi`XrZm@JMAM{>qc>j0j->ly~B6N+p8goTO0-q?75z*8n(%!@w;m-89&#q
zz*Xah*lV@Q#4%SHMQsm>|Jf0E7eArRzjIqWKRQ(y15^JPeCT}07W42(41Bb2Y=Avs
zYoaxD7S89oB?T91D>MFP?!cTDTCO_BXKRZfS~cx!67wR>`>Dwo+{9^#mQVbf=a$Q8
zKh`0a)wy@vUJ^+5Rcd9TK8JrH+6v`lpB48vvY0JPcH4vnsd>W5quLdoI`|&+@s)e;0soLQG#u&XqsjoWoN?`)1z)+Y;I(01x?3F4sS9FoR$MC
zyaE=eD+){d03jRlr_2gF-bWoTu=g9~V|=wL{R`$5wZka<;Af9$FpqRqKLX2!Ad}*K
zD%h9kvtCz?`|{0ulPb;Y;DeQSNgVP}#FRZS(^Y$`8uml+Y>(!ratV2D`mo^EAdl>J
z1>LB`+lDLws$xb&e&+lcN6C}TU!3Wug3q6WHSzD#m@
zy{-Z`FPx^27!5*F@}Y>C9fWJSd9M+j$dgH5y!$PUDUXa|B6@eN|7H+og1)$f2}ctmU6eSeieIDJv80)*_YL#`nauk&p>?QfW6e
z2P9lkwwrNinO?=226$e(wGR#j~u#U-e&
zR&@mOe1iO{OyngwDB^1tq;nTz-Ft5H2S=oF6BXm$cN}#Z1i!|a=X3SETbyCo$|ud@
zDhYb_IW6UQ(?^cJ2FKc;6FzXhV%6mw^YBT}1qa~`;<0$2=|;Xd#yXi>EH1TbZH1(-
z+2>nD|DgXc5BKK%1J9J!kg<2P!hS8&&@h}Y4wyBU%ITK(Nc}q*vv3F
zw?ngMLdkH)U}zEFQfmoQ9&Z%Aik04{;!&nGY&%v&AUU7JktIm0hl&GkhWa=?CmweQsFv1p?#`ojCHUl!!7)=NIwB}*GPB74u-WyGfPx!(6T
zo+lYp1RWU8)R_O)xV;RGv*wZ;s*2zYF4@U4Z>c-?(8
zt^JMqT<4pz$nM&pnwhw25kD^&Wh<@^&kUbUtP`w_RBgJ4$UVwmiAN3*t}0P$-l{!b
z%e9+>;aZay-t-sYErCm2LP~01qvZOb+Sg{0_znl(&WG{s@AFz3MzmB%iW`|`&$RmD
z`e2CcL4|vYt`*F;<|dC7L<Chua8Ns>hf)|J?5Iwxkx%0i`KvO&WMmU?
zuE*<|gj?z=&1DGa66h41>`C*ccA2bM`fEvY0rO(`)S!j*wEfyslvA7?ZC$hmD!?kH
z0yJZzlfX(C=h)RnUw_|*)2X~&6)*w^24BKPh-sCZ_e8hJLe@f${0cnNB<(F}z}kGm
zj%~=7KMVg2J99E&ZVaT><0|%=ZvB0INo`fvmg3rWQ%GK$N%r`cCfhA%(&scc)O70~
z8=~8|kO;7Zq({SMEg^?$Kc{6JDpyAZsoMsHT&UgN7B+OFJx$_di%ne3#Wdy+Wp0y&
zY1#&X`a@8ovl?`M5Z|sCvR;^$b()ruKr2$Kh==Qlg?>IcE6|!i71f-FNJBbG2H8q#
z`{tGt@&z4L#V#RY`k~rR2hqO)AG$Z-Gs#aC?D>y=E*sMVC#X<0`+x+I&&Xx|lESZi_8wBn-A{o8h!2%~
z8{Ni-gxQ%xL-@sWUERwAk`L8B0e-wqxXby+_dHbltdk_(-MR72wNBoCtZU1Ln@*xH
z>{l@u17VAfEk3M~v{=CoFCYc%gFC88qQ#DJQKhi`RRBSTt@|J~)a|FX=|*3o%&sf?
z(sVIk)RikVRr@9GKjVe{bfT7%?xZEy=?m4NP&K|XJoYx@2)XIsIL<)vl-ogVM}iS$ZwZnf~pKj$>t8i?=Y{&qO{vCCJECZ
zOxdN*{@x4DD>y@AU5YG~rTvWCusr{;m${p9&peLvy1M9~_{yunx+{26bRAshbzGIE2zpSZ{LCAz;(mF8~8)&W6{?Arlpp1PPV7{F?pS59t#l4g#*Hv+#S^~QiJ7q
zSLzm~b_7o26ZbYjsOsy?;~Y0^MGNW0a3I<6
zcfX?TbN$KpxwANs-3-_UR+9oVRiO-9Q9kaGMLz5_oT4pb)I=tzBM>U>y~$NYhyQ$ZsX+N($OU?D?4hRH3wdW
zHn?q2QH+_lvlRi>X-m1~WE$6DsCi75u;JT>;odHA{sHd(?ow6aq
zNVv<>8l@=5vmy|-3Dv9Z+@J_QKg)8QPgiuv70M2ovdi)HO~o#92Xdx)Yki4o`T>6EG_lhO7ABOob3S%o484e4j)cziuQDwewK({
z=e4B|A_+})k!GpUEzLf2IJ%W=VWV=|{^~3?F2`oQO*2VAdxlKjk;&WVJ0cFzY{OH<
z4?91*88CHdf2TroScd}K+k_HZO~9exS5Rd$_v*kWD+681M3+2p%>59@-cOxevK%hS
z*>5g#j_dXLUf+eUnx16FBv&4Zi^=(x7MF;WR7Gc#eVw&O(-W>@DQ>tw4U$e4E6B${
zEg94~an>yM9TBPAW*+KTNFxq6bl6D9V8>H_RpEZ{o_m*Q~tZ6?w*uwYN@Akcl@VLKo%q;Cgo3ClrO%ENLxYmcOlyxP||fa}7Oh*%AP{)eyv%<;^ff{5PqFeM>q;g-PI901y^i7B@Uiht!?nk$1XgOR
z_MWEFTx6>8QAO8o82(;>m3N^btY1uUao}_B1;gMH+#x5WH1NG^wav9S&vVNn=5OYb
zeF-?Ly7^v}eOZybeOtgN$Uxry1?|*aY^XH1!2wwH-aR#P{pFiUYQ|A{>CXO}R@$i0
z-?qUQxx|Q%XR!J7KGu~FoqL6UI#cV1340&Uf?g)LVu)fl7OX*b&!5`J%=B`X6^)dm4xpw-H!Yr|^T!En4s
zFN}p65t=QNVsS2KQiFW~RBZs2g4z0EngUG{++|dt8T=a!Z-YAy>m`vE{FX?XI=11i
zCl$jSf3S(qSwJ;}-M+w4=MuXhAo^|Smg8njQkdy|m`=sCU?IrCRzv?SsN$xyKdg(Zc+MXLJVV`dr@zax;R&&$rjmlNv7R2>S)^Q+8aT
z3$;NwE-%#L8zrNneV6icdR}ujYL7YKD$ym*ItI#Pv`q6MJzvbmDY1@e^vvk0VbzBc
zsg2ziz!H7Xr!Q2(ltf)Kaj9z%C@yz7=mgZ2Zu3QDQP(b97C$nNy7u(Sq<{Ii)ZkG3;f|hK`nZ(G{mXQYY*5
z@!G@SZtO)g{*4$2+Ydab+XdM%y28ZiufVEVXM!=t2D9aP{qnT^n87-aBvDtAH_;m4
zzZN^RrZQuyAp5Pyr#zoK`);_HZ5<{!LEgc9!qUJ{F5{LGHgyA>NJu%|Z2Y7_T`#ki
zR7oE7*8vW16OqBlC+2b08>ea>o
zflDkChT9GLdfe7BmUIOdkouarf^45mYNfIRiNa#RhDYgR%A_5u_>2?3__QW?Chw8Y
zy5cuyu$vBMJ5pUHDt1H3yvf%2`gFblJ&-TVh`3y!x7@Jk^OrAMzWmto8_V@8UZ8R#
zmuR`l<4haYs$Zq=EL)&ocB6oq57H#7>_+|#TYzx;BH!3I`7P1633TJ;+>NpPYwxKvwa8z@k+e4xPZ
zd#GA)uD^qCI?_64{jP(=PY-oH!w#8fhpdaoiYC8FMP54PV=_@Mq-XQeA#70@^IBi0
zD`Zo1vEX=nsVdB(vlXg37OE~5$lC)IVfnhkhelp3xMa~4UMyIE-_umR?qb0U%XEd1
zk>p~512N<*1HV5aZx0G!b2-d^)(mKMkKk|zyo1T2sFQ)?jAg4b1qn!GKnBpO(m?4qzcNY3wOWq+(YVZf9jw^(H
zkov)}XH~*WJDe&7O#_MRH?lnIab4=Yd@~LTn%{_EyBVMKdn-cQMJCh3{ARF!wq7st
zxH3J71zNw6i|H%7J
z4F@}d^U}xN%uvLtJWL`8A&OdOEwbg6q$b}RbR5j$0H80Z9
zbDyV&Ey|koy11>+o4KpL1iizT5YzNr^u^kzsa*Xu4c6Rf2#P<`6r_=NJ^u(_&Ydz~
z+CK7aZrB9vc^uc{8i5w&t-+W?JdJfFP*~DV`CM=LZHf@s
z_xSK}Yg=cQdtB!|qG5g1D35EmSBZ-tk87v5BpQb+S$=x}$4XPzLXT)&-=bu<^yQbu
zqz!i^uqaOgsyTq*e?!QLTcN5?dn^n-=pNTMJ)Aym1M|H;d09NT!8F|C>Nu-zRD(b+
zEU76eFyVOpR*xucDDzkP(`E6AjWOXv+zA5F$~#J6qEX>%A~?2R5#QK2YPj3=ad&gA
zx{*sBocN1ls-~Ou|BCqi#>MK67y29ncsMY6T<}}V-4r**<0|M`)1Y6K49okmeD0(N
zj@rxogUZs;tQL$%H6JCs2K5x4&$)TBi{8$!o42X7Eg0@e!Gf0XWdbmLDoMP8X#FQt^h2HomH8ikT
z98#!jJ&mtP6||etA$%d_J8QAJTf
z*|KieTjGt!$MS<;5{GO};ZGeFg{`~B)W68e#l&%Aa&nWf+TesQt@dW+uy|GEa?45_
zfR~FMTf-i_&$|*@Y^uTJ&y#m7BsZ3q(kb}PV=A=HZ0|$JU1(sR2iy#r7v6*=s9p
zQ>3TRfvdH~tIp@3sh|%XOz4@&U7+
z=;oj;xLnDez$}+*V|RKDFTLo=lb*ozukLoa9_%S@#IC6uQDWqj;UnQ9{)ISa+xCIz
z=iBD<;UmR_?RVK&rm9|+38mS`J_o=Te@)eBvM=p&f7nL$T*3??A<+&3V_{e3*Tn5lea=!B?_JCK{_)<=;YD@i>B#6}@0-z6h3~9}
zS)8=Wd&4?yR=YDo!1q2_lvkdzA9F1d+u`#p(NFSmNUSM_JIj-^>E@^G~qg{pbIp{MGg0Swz>qFjdJ4g*J$9
zypS~NSJxh-5{*13%6iRO&c0cO12+Dv5BMaj=7rIkUtIo*6M1(l)Puvk`B%szM*OWkvDDhob5n8X5i
zUohd&b3BT_e@IZ=fc@eVaq!_-?oo04;l!D*;`x|6E&5RHF>`>Ry0kIocx`-SNiC7y
zaK{NVg#U5!6XaL@>{Uag+_x#?Tj&k*Pse{ykamg(4rlns%^oZMczFKc^s`~Rx!r?i
zg>A!!zhe4}v5}0N9SOdr=Sx%_>Hy=MR;r#$q%d*oi$*R;eDlTV5&!CbWlvSRJTTV1
zyE{95yD<17kLF$$zkBgd1C`(PQZ_e2-2KuWoJ_2FNz2_5FTFIDdqMQRG%~Tgo5wkw
z_xqpseanJR1T^IsoxIMfnNS4KT=N+?IKU=QDt`EDC;-X0Il3nM*H_r&;5_x3R_v{c;!kSDs3W?_
zlc4yxmV>VDb3N5W$UwYEyywW|A@6)mR9}Ij58}Zi*~)4>Ue}6kN8a*|#3DQ@2lu)TGXyZ7>=P+=f1=28k!D?CBg5}Jh
z$R>NYyU0rV<=iDJ?9lM)*SloRqab*2(w{H0NNaHvYvjaH&
z%){&2COVGI#HYex$N#DdewWBO6ZpjY$49GvZR~&e1rOH;9->Z+R((A1AmHKjz{C0z
z4+L$)!s{>f<%vR@(4R*%O0BA1g)#EEmD&J&YUDwvLg+#mi10STAcX&ea0J43H+u{G
z?<>TAz`qD%J$|`Yg%9$^_2SN$_PU08dR@WZUe_vo9XF@{o!2+oF;YYdI>YH@#YFtz
zFAwr(v|`*}Q-w~~dtRdLa&4zoHDsLpOE~Jt(%@-0VOCsQ0HKY8vpV4f#35<_x|nCY?0NJ6)5#;v*+NR)$UmSD0ESoYHZ&DJG(t0em+T
zJljlEV-X(@7=cN^!lEM0n*6noYG%%TFnvMVg9}#{u3V!jSi50k{@Ud$H;_3+8YF8T
zT3@twIq?HqhyUb09Sykz(8fJqJelLz9RYn@FJf>r~n4?0udh!gaX5Um;M>zKLD&#kqAfH
z@bjO&8iTa4z;__}e|1U=ny*3g12E9=PNdz$^UpxX@6x9reFiWSNC&cj*??^xeg+D6
z=lnZ9a{-1K2!-W#ERc`*Y=qswJm5Yc5^47!94KGE7@HPw01f?k9pOO!6~w;-t^!AZ
z6N@qbrw|z+7`cR~#sGmpC@=|_0u1EOLwxB`G>-5dARWj8W&;B>10C;}3p!kW&j8i{
zBY{9*EARoZ4P_o(g86?GkrzRH3V0o;0qTJUpb>Zv_yD*7IDo6b*T8qc55P^}XJ8%b
z*$M0hHuYmGLRSAk=MEr#0(cQP0*qx_{rB5`fNzjeRnJX}JjSpcE
zfdAGo_b@gE5Lf^jhX2y=B;-v2epm(C)&Do$!mQcp^Y1kVu@^#o%=n~DnzURo>di-N
zf$PAXHeeBK#Fzp<1E(H`um5wH2jB>-;YScQAbbxv0E>9wRxC1vS@5!CuK)L-d;`K0
zKn-97-3(wIFnBM@vowUES%2hS+a4tr)of%c)}s@Q7!^K^=XzW+pTcu`5f%i(eZW=3
z47XB4D*-5_GQFDSeMo1w88Z=bcxGO)rx1S~m;(Ba=S5vj-0-oL
zm==KXj6j46U}UBEK+Q9@_YR@dL9~SJeg(J+d<}dDoC4XH1K8of2f$6FT|lS+en$Lt
z)jK09O#l*IFtCunGBFfk4Cu&&LjFKxP(*K11jLcy3^h
z2zm5HEWN{65x_p6e?mwg;$6T8C^s146wr-FSi{nQ3#>liX{2v^8Fc_BUc%5K&w=zS
zz&&eMuPyqs*jD?%gy}f@&IHndY+x>MFK|Dw46p)4z(#*4K2rD6)P1#h4WI!y0n`95
z0=t1tzz4u`10lt&|L(O(<39+^IsFWuY8Jma9c9>`@b6qMu`iAljeq#s_t%@ik&9T0
zhJWB+bNrpC#4~T1BG`#p#_GLH{@mY6#Pa%lAXV(BzdJM>2Vyy=?5E@8oH(;S
mOq})Brr)R%>hFqR$8(#zdORI#kx+tx(gj
ztsT5|D6`bExJZeLQ0htjsx#xI7qj!GU7UohJu2=!H|G1V0m}3K-t&F@e*al(ul20^
zv!3T!&srSYDSPdAc622}G{c7x)!T(c)m1=Li+jUS2uC3OZoE{zWpvtu+Yb@dDZm8`
zZ6d0CVEG$FwF=k<><3x^2kEjbnY(K~)wpGJa>Ps9QQIz}+Jf+3OKLWqW@{c@71X!;5z(NqBU4(4x0
zj1E%?hy2}6m9Wgmr$s&yaSjw0fb)P|#=jF;pbHVk9VcqmM3NX2qhku=tkztbP5y}U
z5$e%tv~H#_w#u4IT4@ccCWC&>tpQa5aYcXxV=cd^Od-OA!~7EUJhno~f37yim9g`d
zs6*JWhQFEXO23Ft_*Qk%lbce27?r4;U@
zG_sf#PP;YS1!-hdKzutevT%o`SgyFZ(-JRV(8}o7N=3%4(kvrMA7@wUif&g22DXT9p1o#H3Gxz49V_Tl^I>CZZX|CY_v<$qUOi(=HJ>Gf%hDeHW7WzWb{&^B)+LOM#yBs6vZZU
zN^5^EX4JmcnBn1_GnuuLQDa*xWnOuL$X#Oyh-ZZgE;rHdPgpBu81j*7AdF!2$T<4V
zpvmao=Ir5LIF-Hen()t@F}?A3!;d=Ey>VZ76GqSI=(JZ#({=r(wMltKx+knnYcQzO
z>8tCAP1sNw(LOGn2wN)0r%!OO6(=fKVG6rFR-O9Hzlesdv$mW;?vcu~=|k_zRip~v
zk()Y=c4#pno!KN**ycVY>7p{~TMOeY?cj*>Qk9`5cdL{XMN&<|`;|nm;pAGAWSGJT
zXWTN5(a=HhXJcY)_l+Pb1<(v^1XiU$x*^;&{NFJJ=`>B>8_IgayXmf@+X9z?zk&5GSRbHh;Qc`&elIXtj!fkRyV9~(4f+(OwpadvwIRqr;>RZ{&_CJE
zs#P>v=IJ+lnmY
zAuepUCw(e1M-CJ9t11mSqH}z746xPB6LN=5Gv6)KAMlDPArSH?Gl^-Y{Ih#^_fgwg?M4)A+-+)m4<^
zYO$x=q-n-)uZ<{JQx#>Y1v{K8`&_zhaPW@U!L}^p$!j?``z>5uwZm+?z5Syhy=-&2
ztR|PBy_1GRcjd4DXh3g%{PLPyM*kZ|cao44+wGMfW#8eV-wD?8{zr?n8tm~o-EUs&
znMoGo-||t8g%OBXv3TP(DvSt$ARGdru)2!T*Gd-64rf4Y@~U;Ag>j`;Ctoo{s|X4W
zzGlcsM$4ZXk~uI$I&A*gZu*0TiO?P3!{ctzK
zFm6QJB(Gc(BHZz5>bFT>8ko#=_?2rfg0n(|e*Qk?6jWs0aSah)d3us$b%qw`w&U>$
zOcsAR{=THKUfMr*kU@1-wo{1-R)F6
zOBIkZbB*WY7N(ECbZ?=$sZE-z+i8(=(Sk-6@4#At7Zw;v8aBo=s@9_02eP+HB|65)
z3X$wu#Q66T(o7{f5Jml&c-3jmjlNA5hTDm@8bq{kPi`f?D6QRTmlmL!urz$>c=gaY
z+X75@SUPQOfP>NXD+DKLdIS>XoK7dL)$@l(~vBau*|)Sq8RVw$P^3BPs1~j=j=W
zlvp&NNwQ?+2=J$h>l-Ca
z+a8Iuv6&mqBA6_}7~Py^&5f(XS_)T=Ses_fkaOvlnleTR_0Uje*@=coN@-B|@?R##
zax;zd>(ecVf_*t8EmC8Mlmr53CdBFt)IJr}9UvEkxMGzplAwK!wo&BTzDA
zR;-oI8Hixw|EU?2Vu(8Jq(iqhkt78dK9lm99Q@bAG-n#1Sg_KGIzC(*8%+tNCd~R%
zaxMb$V7F%{KVF+Uo9^2d_s}bhaL#{0T8Umy*D;w2G`G@tQmSA{n#FzrhQSBs(sQpA
zGTL}cEEakv?741d&#vF+c`795Vvh+Op?jIH*A8VW_zj<7F#D9}
z)!LKNm}0rhM~E=Qa{5ANzpnfyv%8sSB4ll9A^^zxpH%FeU
zmu~VKlk`jn|8Y`cf7V!c3;a?)7lTYkXs#GwZ=!u|y_o@tAll|A+5)~IUl
zO(Aw#WrMZlkn{vUWB6eGx263#HAl4I=BJ79vL~j#t?LCVX^?m3$U&n;Y5vvW8DX2B
zm3RGIaY%|Y@}Cc%puHKD93wH4t~W4~E;mG`N3_dfK(V75r3;#H$5v^GkxxioFhD(8
z;bIkUIoP_EUxZa-r96Ipay*O7_mYiljFJB~S+_vzU1#>#8DXebQp;|IuMhR1+A!VikKdeADO2V-t$M~YdEFwj$fl^
zb>aD%p-REi&CeZ?&_mcvR9mBoCJA9I3Xi%j6unxv>-Y9l`4(QIu9g+c)&~q4pJq&?;%wYGBm$TT@{V2G0V#
zCN)8>5PtCUrqqG=Dui$Rkmn22OIgUMN+YxLq_o!9GdFf=t!_tLLzl;P=R7@H#uW@G
zmFZwh>VAddU901(Q^!qNYm^5Iei=;K8JCg%#U+-WP)lWb3gLCwAHRchgQrgwm{nV4
z&T3WRh-y5lst*w|c|}?xYij0`(~PXVnV*+doGh2aNCR+2m`0~lUa-+Dw?|7%VTnn-
zKys>K73DSa=hA*qzoV{%!W13RnrxC~Qi$L}L0at8^(5V1sRjjipB+C6+>R?D>GL`B#0WD8OKg!oqA7$B?Ym#%bFE>p$v
z=SIH3_G{*6j*5**I}Ux3OY`J*HglGw#|bj&IKOh#3ONzp3-Gr`6|je}^rPzrQb{rD
zx|A&|lXE1!$WDY|0bYKO4ut&zeA+#4v3W=Mv-fZ@Awsc_$y2pVLxDWt>I9+^BKc%P
zTG~#?JJlaEYQl`p^wE>vTB&N*T4}vuEo>NUpjOKf{sn{X-lM+Sm;GX`w|~B0ba|J&
z9G)-d{&A~K=@+Z~q&akYkr2p)GlTbwU;En{NOdNshMR;vzzCH-zTMEqe(K|QWQ=2X
z`uKAh2DZk_%Z<9>8~kY;!)dsdU$RUAabas#3${}3K(0ThpY}Ej
zW`TUrj1-O;qZDSi)gu)yjY4!}wbX|42gaHvWHp7ghfJ4ung;H*P%%{E9#p@_vfIo!
zsP}@=_?)#^%*fO%I7S9>k?jyJom16Hp@J_OH$+MEc7^ig~R8G~OO=nmV-aIr{__xQv>fY*)JvA=tHZv3!_U8wHZ
z5uClrY4eFAjZcpcWBQs{oi$NTTjMJx{FYK{$ZobvyJn55Pk}PrXq7^@&6~o>gbCfj;xO;Lmhgf@nr};$!ez-|=`nmMMM}2_
zfjtHtr0zr7Q7R~=VW4!t64nsDRSWea(L9o8&CNoX)ig1W2y+7y@cTgUw>Xf6cv0|o
zdSHB>jR^S&h`M)ZD&vy3+j2{<`E*PD!6i##-^rNN^)aaiYRj4m1x_$bYA0H?B
zlhQ5&To^W~*3d1^f-+FomuZRM^&n#w8J<|6&tEIm&Pv1t?&;R%$%H(AT!AKk7`}IQ
zCl)3atN~qI$uO8hRKDzmtwmYoZZ_&;q5qA2%D`fjeI`>rBH$0oKYhGZjp-DS*~AeQ
zpZbnG?>(|eSDl42fPM#N~6bwfpT3T?AeOwx-3H&0=ZLiudhFK}vmc8KTD`zFK3CA1Xo0Z3~34UIfy_vn><133(*s|k|2a0zwtl;JI=KKYN{HK>c
zFlQ?wYrMSqfd%YGUcUB$)ohuUPkQhgyV=ti{?IUHqF4M~%ICbI$vqXnVb(C4fOJh=5i?haWI1*!-KiV`zA
zegM@45C7BLdF%=|Z+h6ko^ta~Kddt}E+#5Jpk0EyAK*n`4SISZg2p()vQ0
z{@LTO9YNprq&2r1E_a${m)e3MyV8y$ki*n3yA7cgKE6t+9wF%sO)pw=g(i|*Brp-G
zsOe;-yesCf{C5k6*;1QNk2z-k&7t%VL1-C-13-jFb}PCgJW|yO-APATOxlri-*%|r-QAte-E`kf6
zPA5@cPMwv}<`73F%!94cbDBo)9oN;8xZu40j`OmnOeRcsQ>{P;s7_01RqLuHbz47f
zYYwrUx8}an8P1+-Ag(N?n8-S(6S?p^grus;FOCSv3NKq?f+6=@b5yJ|KCB1bh^r_4nBI@CO
zo50Oo$_jt+=*w&%SN~<{;6eqL$8D9S)$Q>r$6=?s^=0he9$m_eUCVvy?Gir;KRqUs
zo5z{Budb6X`sa6xR%uSoDTg9>hEk^gtyNK=8bO;0kgt13Du*z(09G8k*Zg;Uwi@w8
zX{2fVrTWH1${{anmm({p6-$gBUH?i54MxsuMg$s9@8
zRKuZ4sZPybc{C}t3|*q#vH*5zWgE5Q(dMnjuG2OJXO~o!b}78NT3W!5Dp{_1&Jb(w
zY*x5b5MdH5gOsxCmUYr|26!K`WmKXcDbdMT;Wz&Kl62d314&=zpceEhju}2?`q-k?
zbcvpO*QHQBmiSJmianMhy;V>9Z38X=fTD?Ax)o0^-HM
zdW1+%xFF5fC_IcSEc+y4yUf4912^BW<|zCxVW-C&GEb96eQ0+uNue(LDCqU`-tCfF
zeMuq)ISMfo&PZ!(SKYQv&Et%^`Ic2efPsIsaJ|%F;@e8&Y}ZY}^XjV?q)Fsz0xQgi
zL;a~)|A70rXWyqTc>VL>VaG~O!a~uyy23*C<9N&WQp#tOO5&F*xCBcCw`f^4ws=UyzCSSZs48Q~$a
z@962wXL8(*7cC@xs(qp*gPXN{OraTiXgvSYV+qVke#c`*Hc{fgek>{SQ>Piba$sSW
z#kAZncJa)@ArDnKnT$t0t9%z4QaG9mPCdy8Hv)_%e0&Q|H^S?56kQggqSCAc+&Bj?
z0qQi$0E0Q~%n?7-lcY_8X
z=#mKi>hjqyMp-tR?k};!PNI@SCOp%v=ZrXi$qHn`;_g2$5`IQqRKfbi&*1?4)o=oS
z|By>^c;bE~@s{ZN`1L1o&!cXkRtn`K*~$!?Mv~JC$vvIYZA!7QEdV9&TuQ)bm<5+ZFTdoW$s0$;~+m
z`wm*txXpaqVQ68r*~=JDxT{}w_QHkbL$XVk7+U&xFEVvhyA?-Bbz6U~G)Kt|JU?(c
ztrd0pFcDUwe=H$NVmdE1+
z9SZhoG^6iOC>AfV1{qZt~`nfpE?M_JrT=u-S^FP9e;4~koe@`)j2PBDwL{o
z@5W|#DrAQsu@`nSvVgdezq(j!E34dC7mn2##_g77)wW1;th+Jmhp`QaP+Mt2T|3>H
zCrJu{p>RlAp*dpK+ZPrt%s(%Y%64gv0b$#B(ww@DIVR!bN_vQ(*Xt_`$RqO$a0Xe<
zo9Qj^1l;?|ghAb!$7x+#DnVl$J;yQmQeWl&aw}eh%SQD@mX0Pl%m;3Yp8X`71EKdbjBAd
zt3&wsLRIxZO(^dZAMsT3^^Xs+nV@PowGWQ|lTumbRHvev*60%*0n%F|JqQzhd+rP;
zfwrp2o$I`^ZKR`D^Rx=84DebF;{(V!Hx2H_s$qZcwJDT%siPxMsZJ2%XH1
z?g(y+8{TV96$Us3?itzyhG~$G{?f4|;qjrEu=qe~h&^p(x@EvLoV#`Nm!4^;$^8^8
zNNK-u?q8l>Q14mgf_}ucW}U&7TEwP*>b)rzb<7@+Vc+AD%NjjvZp{xRTjpwIysnV_
zTf7A(#}+Mi3qfc)y-6hB(!gpa-abRwq|gQmVuywb!5<$M`z<27o54ku+glrtQyQ
zVl#C6#Wy`HcSyQsFmT4qov~A0ggJTLn1QYqLF}}CFC|nDiKDfxZwOur!RhcmuH{I|
zJ(nF<=t!ZCsO+H%wgqM-weHreBzP~frV=M}fdewmoMkbnjMf%D59=b*DnbB*YF-f)D?EJl*p)fvR
zU%~j0!}vJYz`l|8Na-+Ybd0fE%2giLm(W2XN83q_-P9J6c9C@@ka3c_mZ@QEDWjp$
z7Z7<$u3eTQ;~%rjQ^s7Pm)f$OBxOl3@1j&)yLuRtrn*$?3T4?e`6U_82r^Kl)Zd@O
zoJ;gPnPeIwl_tmz9!PkX8MH@H(y
zKDJC9!U~%_NaXJ+8_&$=A1~9|7LcB%-fZW4XLKxNL*J}YvokVvL_3ZrvK^~sE4Q1q
z=c}cTHqvy=#YBcU?9%Nk;T{H~j=*t;=;+~waV5w!QnV&}0;JatyJ=0?L$4R~2lG_dtO?jw%LnolYlUX#d`oef*3
zkrbDM?PR0b&d=G?a~LU#7+R>cO)YI}6V;LZ$~Kf=URrFKp2?S_a+)V)xHHSXxg*(h
zv%i7S?J0*goo_j_^nzqa9q=(xX?GxpUN9K+1u(6Q}dsWT=dqU
zuku!RL`SXaVDTg_QkLDpM5jF|cLgS6T>aS2i15caL;g0Yf`nSWm57yi8CQsx2p1)5
z_0EP+DWdL7Lt8_*%ha!D`Cj2RbF3u)eLmrHb~fCG{CiEBX0W{`S1KBnpbqnWUaT0KmG;Un$CewY&wb&Xf`&`u14GGwQ=;h6J73wA(=ZHwnNxe
za(T|UFxu&PCi+~(+#!qJ>m=!~+c!8_JDraXC(&00H9Ot8;1yetS*Xt0j-%K$Lw}rsoy4jXb7as?7H%AP3J-eUc4yn(`>-?QVO?CdRIe)m)zit
zG4Gpyb|lv$&%jJNg_Xbsl3($LQaTg@pYlhNJ8FK;Z(3oj<
z5q6FFX^j5ca~I%Uh{q#@Hdx)~9cHc&8jL#Fk9X7CyIpYnz@eY=!KHBBMSLk-?=pVz
zInSQn?MsgjJzj{70(;8bX+LF6!!E+y@
zdzANvd#N|J%|Kr=(OV&UIG{(s5KPc^E@8&%y4_MriK6TD3JgyjI)P1ntrhliy`~ypu+fy^v2UVYg6=edhNV7R>`qm*#oQVY|NDp@$R8#
zp>|5A$B>je_BT7aYQkk<^;02*tOspy*5DXb
z*<>h`b3-ln%uHFnx(?3zWsTYiBay-Egtq0hzFoRvB3Md}$U*
z|K9OMaF5XAE434-8;ahw@d3&QVv&N|f^8Aby}{MM9Ft2SoTizK$l_!{``jnG{1>k4
z^p$Zz&c2?s&^RvJMP#p-H%{&RH@^M}w!Ke0>*=&vsGI~d7^sM**ODn*9B$5GTKQ&k
zt6-cnI?DWC`IzL@TqF0+BZ0Jm_R{ix9`;s0bEIAW%@05EwE}dy@*L-`Oh1{=BLTqqt8mK$74IV%{xAw?oDEboKMMi0i}=K8
zs9WA1uI>4HC;%&be?V*w$gu^e7wrD*AD*P1vKl-Xh~+N#?mY4$5g2%ku}KJ13YTk>
zobR`Gl-wtFd-!|T#trj{pZb(A^nGHZuQDFeMONAw!q5uc;yfR}V(m#KHCyMl@srn0
zrq>)VuZxTDiQzs*pZyFjd|Rz;{Cn$6F+Op`5p|2YDf>k^H^07esj1#4{^aF->#Bm~
z>)QAYuOti%_oU&SiriHRua(k6uPN#*O|bea8Rx
z$~^VY>w4TLEM8>!#BpAJ?yJeeed6D|%bWF2WWs*hQ_Ae~i640BB`-5c{}_Qo;1<-G
zn&0#4OLDJhaPvu3It;nh!xvPg#red2p0@bXP8GAy{1i6Db-Y)iIs${+Tosd?hx;Sy
z9bgI>%@C_KH+BHL)V=SM&V#pNA#Xr>wrZyB6b{664t@~>iENN0Ag({!!xd7KW_o|l
zxh#ew_e`*B1!5`^X3chsHn*Xf#*&fZ7AxE-^;w*@0`22rQ{YI6MG`9lshnF}CCP+^
zl3Q$oz|O)Jzv!WPPXsbJNo);LSoI(&mWqUxvnBD9fLp9}Yb#jp%Cery&K!|i5(e-`
z)-Ph_@`)S9Ci}#4Z}1s;$q{
zxW9L*DE+E^plke$@7PexH1hXt96Z1ywg+nOXU9p-&Jg)UkLchRZ=4ZTffuoi@OR%&
z&Vk$ySccU{_>&t=?1BNj^0f{c+3O#HbAH_BCCZgZJ`}~jv$;U#5hecj&8aN&8Xx!iICl32zWDW5ChXrx%OxZ;!waVy
z!CZJwAT0Ig7t(m`kcB0St*lV$=YrpIR~8&d!~eSYudMJ8KcIRjlgHmvornj$MfgqO
zpRCq0gZVA^Rq~Da?cy(1YZHF*mEp;b&!EC@w;>#FWc{;F;$J?jEf`GHmWj%|6L@O!
zIbXbGBD0a-v?ZQB72pqSiF@?ZfZ*)O0|#Rh{fe=40g5bH3N*Eb0hg^Z_gKks?UFdw
ztAwjm5;MFE6p18G@P+0};tQUfdT2avk?=Cs`6-ViF7{hnup1inZ)7ma6;XIue1f0H
zukMTfz!$SCqWE!JC);SIs!4_?Z~q;juhRnJ=++AKwkPdEZ(34o)gNhRd(+}tYyL=U
z>rGR)?)xL{lioCC>)}7rKI~2N9Y5WZ7Kw)6=}o+Oy!`~vZhL{nYQDVf3HFy0e8;xq
z^y|QzlOx99Mb;bu51C9Wq8snLxr2$KX~BPAdZ$26^HxOj@6^l;lG5bfr0$vxFKSN}eOnZbwF4jnw%Z|1I8TtgUP0%)?QbvP+SX5)Re
z=UG;Ll8@T+t&%|94{B(Dis%dbCn{+n
z#ryn`{l;OUSdCOXiNurQ%a&^T0vH$JJ*-NrIgq3g#U~-+{v>(>L_4TD6R+YrlQwc-
zTu)mu{H_Btr>*qiAIW_5eIya=K31={Qu8PT!n!R6FF;QA*f*-Cr$3Pw);x}fqBy{O
zo_}2$H#Z_E*p5cdll*s&*pYT!o)cyE=+mju?vtf@pgj1bgk??Lq%8<$i
zB7Epc=I-Nuce119mx8hsM~i}^5`+}(4Sg%1#ABN^{N9gpgL7vX#NYg=xPSJM==IF{
ze$%2?5n&WR`{TqRl$;vv-%F<}RW5Z%#>{p}J&Onf`1K!WFe?7&$MJ(Z+y^$)cFIE&
zJ?q^CIjgz;=U6nio4@h#Lw%JO)D8sk{iU_Px;H$(-BvkeS<*m&aIN=RS)DSmO|_=wlOAgX&o(F6WKV}VkQPt#!D
z)0oVv2lKi^x?GwfG!5ontyAgx!`nrzZ15ZRl$FCos9{I+r2%`
zK?^LW-Cjmdw3X6uJSYo@JNS)X~~j8~}*(R7P`4^j}i5r!h{LKue7
zg>W#!8y-3er8Wg|=Me%wdqDhqw<^ysj_xKxgw&0<72RTlzgsNx2gI4ZV}81&1~Wy3
zu)~aAW+nW^!;iADgZXjISzMQRrkiN*h#TCs^<<>{TewbT*|>!nJuSH-gh(y@^Si{u
zL5k^9*X(*UcYlelV*`e6gFU#w|uom$;(aAdqY&9^z3O
z?~Zt{n}%(-Vq|T%z9`PVO~~i2H)ZXn%gzfYdGisIybF)c`B#pdRj$v%|FLB?K6q5e
z6xUD20D*^1_+MV&ZN&Ei`+hL)Zk|hxoGyUjo(vE@1ss-gB(j
z)>rIO4pHsKzb8}t3-PPK&%pJ&(rF&U!2$q=0>gm}U@R~J=&Os;^~Hzgf)02D`K7?(
zyXcm3#HLz~gr|UK@5&g30yzNf)bmJx3HYC#T8Fgtz*OM>)u~m;zYoX(`a1P9;`zV~
z4kzx}cV%oxd^hkmuou`590cltzQPaZ{Tbg*aWly%Ylc1uYf`5wF8CD^y0>JbOi7N4DuB~D9|4m01N_#
z09qgw7zJbiV}S|4eZXg^>mqOoIQ0;jPk&Tj0ko06-d#t$3%CKefd9nnTOP*ffae!r
zqyVK`hwn|m!O6U*ZKCZIlFtBLkDz~l`Oj62McxD;2l#(Ac?$Vwfcr`?SHOSj+9u>}
zDIt%m`Y*&J0RM?_Hu4?-9$t)b0RM?@9rD%#V;=`C@b7ed+~=EZvzMbPE2a||`V{&H
zyj_7Qszg!XD|lnxM))(r8^C9{+Gm~zvmo3C4-I`bu;oeYeS}{Dmw;8ETL+v$eEG|m
zTEw>i+koxB^Ungv%PA-MDmM}yMnz3X*p2u_V9PT6uP?&S0Bso-9pTbd=m^5Sz<%H$
za1rI|5jFvQ^~s82KZtTxgJ2D~3gM}B=o#Xl0mH%GH;~_gbj4b5CF1LlPW??|X-M->
z;cmp=21bGY=e7L2Q^_$yUjfqsbocmCr5hOV3jgM*&9b
zh(9tDvhW}>?*rjy2u}elBkS7|Wcfx^ya78NSO@fF_(6Xi-^~aagrh*GMYxxy0WGvX
zU=`Az-Gn-T?XRJu$UBAfGr$Ao%gUepE3fIsSLCz={KIQ+c
Y;!Dp=QO!YujA0r6@R>@!?yK*`SnxW#2q4$%AqeS{+mjZ|ys|
z@9%7$;y)Pe9n@ESk|^ymqMhc^#RXsXcyFU}xa*JJ|DB;-Y?RX?2z|r
z{|-8Lxl$J@W(jlC1Fdtd^Q@lYb{3|Jn9!lyZ=EhzTrRW*$)BmB`W)#yQ@(WFL<}SC
z9-%4sv*L7#rk&swJhafz9YMC6MRKlfKibkxv;Z
zx9qRTld3g#=?5MAu+M?N2Fq+u5>#OKs!y`&OK~}&j!CK644(YkRzFliA3IPBvkZhW0KF~Hl;RSG8*O0
z9p2>*Qbj{~!?UDsb-kaemKsc%38X5sJbS&|a^A3|n23MLQZR%nVzawUD$|%sKAx5w
zWNpZhS-+O@j0Fk#(%&={B^5~@Cik`4GX(2bQt`Bd=05g(sq&M2>8$B&Gx6wOMF$gh
zNjigJ_&`Vhd@O
z&>HE2$wM6J-sq66m!S-5u-zZ?{<-z2LspnuB%Ly?bkN|rL_=EM$gFW>=YHc^g!vKM
ze1>i48xozCSRu?lb(IlH^_EX=jYgxOZ7$4674OAy@~3po2KY{p{wdhg2s8E
z+$`u6UVLH|Ve(f?mrSic4ok|;?Q1QPa*bbQd@9{Bia(~@-?(;5ZfW~3_hg1KRWg*h
z4Zi11|N3#_FTEFU$=z?Z-9L0{K=*vPl2MRA{IJk#j9)+Eu=|uBOZRR7XHxSWbIi4F9N^lfsVG2gVu{yOc5c%3cw)BA37k)c=XvmUY6vVDFbzW;>1
z=6Cj!>`TAJ^!w5g{$nYf$d>mDr#~^)FD770`%pC1ju@p%^bqsghgpnhyoY#@HT4Uc
z&YQ-=<%@__4G5hWQ!Ln9rmq7R8%8%inXE3amTu_^t#XU6sFelP=Sejf!#gH23{!2b
zvMS~NiTHd;)X_*m^bvBPv00A|ixqWn()?z;;mAzzy-yZ<+lej@PCRp0Y8LLeuiasn
z?x2`n!*Hi#)sF?*?wDv)F9WYlQ%^&CC*#p*yViEl%7TR34qnJ_byquhTX^9Q96b?N
zEYHIf&XbCDh@9r^;z4#2wl>A*deHKMgmG4n=B0E_1`U;2>rT(J(&&N&Wkf#weeAbm
zeMM^X8E5_ZbVG*8BD4Njf8`N}f7jPV?k?Y<4qHDB3iV
z9+8e1X?&S99#xFN9k)KAk)fjTrXy0U=DY)Tq>b0H_`~&OQmhW?rv2sv_2(V^k^`-0
z9DXb{z~45^(wK2RE9HLMLgnU18y{sYLpbQM@DBELC(`<+gEuYvbg`pnGv$+!v}{|8
z;Iw9XNvWi+ep@2dLex&P6BG5M$+sdiAutQmLEQLZX8F`9a*M%QkU_<<>~4UDDw#VV
zz;ewruf*_ctxME090Cvs5C^VdJGg3^(V4nT-L<8>jwi*_t|ILusMd`u&2K$sVhaKv
zH&vVZ*>laRMjje=xp{aMbd|RQJ`_vvz^nACl=SkmmdAid2yG9P;^jjCzd
zA|qIUhqF$2&c2+FXhz0igF^(#kw~Q5scl8{pH9Uj7Z26YL$7#xSZbt`+CH7$^GYr?
zt%z5SaZ`^)j(6PZR_MM
z73<5S6DHO+aICJS{!jfRI1dSf(>o7mGK&uEm7E1Ctx
z|I`b`mAAyr(b5?9Nl1`@#A_ju!aF9`S37ISE9i<{O|AcObJ$E43<0wd_k>TymjHx86HRm8_gZ!o90B
zmH-ry?egSRznPCpcqU$1L3f2k+bGF`&I{s&Ml{`v!_k1BG1=_Ukkldht&IYo3w;T43r
zoDW^4O2ZaPe=glQoKm68hrJQ;DRr^b$3Ma=k7`6YRkL#=(x{0A8+9WJIjCFJ82;$six%_E5*{*}dz9BnIc8AEl+p_2mFgeCzDlRuDIJ
z1SJhj9Dvprxq_1iCS^+prUfnxo>X~j48qijkNJpB0}DYW$O3tw2o!^AUL(k9`V190Z?K%pOjzM~{fzi*Xv42*Qs(d)|zMs*s
z9nqgA`nw-G6r!a
zVCrgON7MT(G1e4t3vZz+OW%lNRei(cmVs!tpYeGj7r!lKvCWh|S-RC+D9{&6brWR*
zttkyla8t@ySmIyMgv!L*!f4<2L`%DKNqZcwX>IM!Fc+UaG1S6}wsWSFs>G>)y{Z)s?(
zk)Y;Wqp?z^?>9MLdS;psBSeUebez1oTK=G(whQ-=t}Z-X+A_(e{3;K=H0sJ}o@YjU
z;pux0oI6%~Hlj4
zC*<)pQUN|$RLd{c(?N>n^H`(t@kS3le%K
zZ_-4!@DO=oZw63E^B?dD!8)ZY_rzqcKxT4UzWqst3(iwv}!Zt
z%}OeWyV&KKGrf)(Ls$96*J5;|W_?7*vwzPr(N?CL9Y!CpgxM2m3EMSWNB_>=pFP6!
zn6Y=K=grwe9y{+Lw-^zezU&}FW9=@dzgw_eYBDnYoN@G9_Us&;?qB$lbIlkT71V#?
zZK^O@YMPAEmA9l=LELi|tFUT4J2Yo6y~9SQjiqyQ;2E9p4>
zB4T(@f6w7^Hn2Ar*y!Jw&$D6lH5UDB#E8uH>Y()7N_xz^rkTi^aOA}k%N
z1o2&LGir2U4%_`~azFt_kB^+}*Y998#{LM3>siaQixn#V9N7GYK{nrZV?~NMEp@O+
zV%wbF?L$k(Saj?8458xkvkR@TwT4^Toc?Ws_!oDZQ{PSz#qnvWgQq=|Oh}v2=^=;5
zHg}5nN@|-kskP17r(L&Ruv}l!RaO*c+X1vmjl-QFPCYA#3(iI~iOjk1pdu4H%*$+F
z`f5cPv?``rw9+S6Dw-jTk{q`^<(E60o7wh7ZwcS3*s#SvanWzdsi4bJ|B}U4A*s5F
z=y|{MkMr-Ud|sVm-!0idPqMV7&na?Y9m#5!&h*+L4Gc9Q-WDqgA8I_q<|nwG!Rck&5>&(B232U~)qC)kI}KSP|`{CqUEvk#sR
zraA2L^Z!=d?}KfZ)vd_x)>1Pjq;i|GTsFz=yymXFrNp*9r>YnQcG)g<+oo1k|7!c9
z+xAqI{a0Icx9y3l>+D8`?=bP#l#|^lgR989J*6J*whgFKzsm-$+(<{VeJfW8+IN}9
zs*n4P^x|7)ST5~ss&R(;G5iThW7%Ef|Av+4pI?*JkvvEHTcWfoEm
zHxacEOAaT=d6G9vdm*LMkz2bg)pEw@gT1M5EO
z3OHRZd*HI)OdH+K8;DhKIh;L;m;O!mtKoBe@l6e#<^?LtU-+9mx!^e>3T;FzYmnjNVV8*9wg+dI+HFzX*0!xP>G9V({a=0U
zXT=iKmCM%Trg-rZb2{(pa-$x(Q*2LAH9yR({4G6g`wW`L-rN2duC?1I_#Z$nM2z)8
zB}orX@b)dtOgO*-b_8KSqj%_WP1}(YnsJ!f
z*)Kanx#+j^e>Hq4c*O@W9Qj~(scWY%#q`wdGT<81d0pOl-P?KnWY=@Bhrh8F*Mo1Y
zrstXJ&G&_4zU<>SXVJHqf8LjhxF~##FTI(kr>VQ1K#?H&Nupc{HbLJEwu0?|bpO`H
z;JZ4Y?6cu=2-Jc)(Bp6edhkXJHRMfj88m{cpvPy;B%<5}rX-*+
zun*LM4PYr~1UjT^rePGiX~iQ_!0rW9z^1{)9|VA4paWqb0z`wcAO^&Ni69YB6y^^C
zfT9}}B(J2WapBOTK?E>?KbWlpNqs7M2P&RMPXTwV#r;LFooV)tvnghxXb?RM|D}RI
zD2l8@+6J%{{Ff?;Vm8VHo91AegFh5?Za73knjk4?Mg=Z7)GfyJ
z;DrMU6oCKR;{~Y#8sHBq;THfI%%cDD^7ObBXcj2Xz~6t6H&-F|N>qpY<_)MGr3XL{
zgH3_--Owqd7jW^eK^}+gJv(gQ#}?t>xIV7m<61-3)K3V8$E1Y=)7mth+VDxs%>aOh1)y9>Oa
z*P)DN=q;-e(Nr+(g_9043?wumW5KJqa_R$01DvnFh8(-vH?X8tDFz
z0iY53%|9VOXkLd%30pAGftjmTtXlmN`)uE=^q1bj!TbciT!8=(0>Xd+n80W-9>jOc
zo@VrflthG{bg&!YV=H7h
TKBnGGcd$yhvnK42RPeoAkNrCtn6_rX)Ru&-YK`ql3
zp5wEFny0i<0p}d4CP=ZgoA-iZfo4ZL>PTd5RGiIYocmim%I@cM`Fy_f|L_0$ulHL2
zwf1JaRk;4CFtLylb&fw#PBanaj>$wxd*ylPxv)P@`zybH&e}0CU}p0^q8zlJC?|mx
zU^m#gjwp`+E2syzKs)ewjVLz<{=N`i!CB;-7C%O
zcQ#k?6Gr<7cwPU1DC=ZIJd&b`>H`^
zVeV3;Mk^Kyb94O7bItS2uHqUN;t>&N*6uN9$`zOQngitXtEp~-lxirI(hMYQY@LfX
z{XyX*O_F+wi|8Xc?Rux$M8!4j+)gq^np{LTw!LbNjUCB0tW+U0Jsk!q^t4KI|EwEds1k)Af>Cz9%XOYvH{>0H?Q6GSX4
z^lTg#M#T3D$A?X;7uKFxD~NHzZa-D1@&4vQq83i%ThAl?e+s_}i+U_w5h{L1?rGJU
zpiDwq5{Rq#wezH;^@=Pg|2Q?k+?XdbUy@4nyAn&KVO~|`mJ~~>m$@!aFkh73pSC}K
zKwYU6cDhs=W%#s}xcF7m;e<6v!!ZycTKbpw6Nyf3l532TK8}ic?J^Tp^Pcj?7{bK*
zGiw9F?l#hcnUYRir6tPopaob#!9R6Gd6gT~zvp?_xou{zjP8|>`vt(}2HKH74jkz9
z$>=Tb-;kv3o%~Fq3F_%}rt^sHw^5rL8dqRne4Mmd^6%QPQUo$`PrY_+sU*A3hjl=U
zAXA0y`|h(=PtV|vZDK$ptN5yX&d{1xPqMyZbA=j(PNL}#oofySl9qTvuWyZatBaC^
zF-PMAt7UC(tP7Whs*B_A*Ee8N1xp051GCzjF>7U~;H
zYuI$(i9;efN21wv2!|fYE@F1)D3cx?aS@lYBfbHdyem91Hw+}|Mnq|hFZTWn!zKUR
zu<=b#rm8G8(hTihv)tq@s$~K7+of8J=WGKRg$4JbvO4|2(S%ZIzLpvU(Nov}jrk59
zWt^{tlh<#?8@BvJ?*}B;y^d(M!-;3^NiD<^_pP(lNwZN*zfpM7vckds1+xt_s$Uqd
zZD2js_D{t;se6J%z=~aoEjC`rZ*|w$cw2bk4{d$HU9@b+O5QH1wF=Xo_~H}8>d3HX
zr+QuwSh_1Q%Iw;@h|bQVTABHL#XK_|yDL!{z7zhQb^kVci?qNq%51A>%!@V2%(v^W
zKIZUC{YFV`ut;y~EmEm^PrMI`O`h7F33+ZHkGz%2WoDo1t7cx6DxCZNTz^<9MUI67
zEs{A>_al|Por90cO)#BXWo^lGw+lZYZ~)-Hko2U8K_jrK@}taJQ&Zl#LL_A?
ziym)Klo@Bt6{goQ-!N-$I5dOzuyc)TwpV~#-!d?x~6|6-Ale9Fdwt2sdj53M`3y-?a
zx?GBwL?+;f!`9y*D;0em4btNcoQt7(+Q6m-`WNJB_rxEnKWb}`Hgsp0+?Xzs_)rA7-jc)4
zVT@~~{7k3)S+u>ciZhqEb>RZ1UD3|xpzM*_L_`m?vZvxx-MO-nE5gCkk2waV`lj^m
z`;{y{u)Y*$(DbLP)FwV{PP@9Aw`o^=!NWPnkJxx&A9aY3PJ7m)p3}}n+}F-KeGKdH
zI@TZ$c-sxUUAc
z4N$}&RFO!7Ka;YPd#d}^Xm+rA|gLL#q))^G+A;h1M?s5C26Vi`t#L#GZ
zg=Gy5jy@XM?;0+4w8np0!lZkpUfVnGiGEKPR^(exO3S*f+dChMZMM9hoz8rV+?4Cb
zq${j^Xpmx=2Km^fp^^Qzt&z9gT6p}B%ixLV;EHlR_C!(51{
zlp56T7_=bJB`)sO`4y
zEcb#9g0F!MS3fiJ4(~9|36*6)+JI!wB!!svXh5>sq!5!Hsda+ZJy{*35X+oIyx5gc
zk|4@u357)bn(Ge=a}x?x*a1BMi87*mLq*iJkUv${t34?7W&hGlqC1#I>plKuhbwQ|
zTf~j1xf`!m4xMK$+eFDvc;;DoF%ix8C*gX+ud8giHaPk(4lKgyhug@avyv*N`<)>~l=ox@IsgPA`2f41({)7{#kX_Y|4=yywyZyfA7VTdD
z$gnS)1pa=JBTJHt2`o~l6RwxBXLJVoF59eoNw`y1DGb|0=_Q?yL@BbDM@^?nc41WL
zaMIiSS#J8`evOO6e#b$o+|trTXB6IUn8U7oR2dkyp3<9@e+#En@KLdY
z5vS>WwrKPxG?!_{Sf~s8cFY_)f<@{zW43jvSI9+87ghh=wgK0DJ|>42e%~9FX&g}+
z<2{KAtBt@fpt49GOsSq7h>UWPA3`4vu`7|oX+EQdtyw4f6Lk%!1GNW<@;aml$^dc4
zA^~ck2Y0|vTzU}oO~`!ob}cy34|(ux1nzR8R)U}4Q^uMNnvfK{s}$cKSfaEV;a6x0
znHrKFmEB?Fw-&8xs{#P|#^C_tp%?g51)XrX7@A;-?T-Jfb@9DSGn<
zFUrgTIFl4&3@$=~nB!36@C#VJE3wn;o^n!sB}XB;wd>6|5aGo=ra9~wk*857e^=yn
z^IiWm+Q{2FAAO~%erEnk#M4MpzAQ1RANxM)*&$3)n+&PLv;^-U@(BvjzlLOKAzdDAd4oxYR_D%E84no|C
zL2UcrGg8e*^zqT|8|nWv%5`WRA7wt;3o&JUlzT^fgj$cprIWD8;Ltbp`B+KHYYA@;D_kht3KP}
zXsRrm&%@VjXWTrG38zq1uf?4?;znTUh8V}wuUVEcl77$LG7hE}E8jD=QtDH=JASV~
z(<-AU%LKZwGB(jk>1Gz2{8v<1pWGsh59&-db=p^UPQq_)N2h&^gWR*}V+zL!JEauj
z@*sb)KB3dzuiI;0x7Rdy1+x2T$>Xne@VukDtvXnL>H1H3zv}i1==M^<>pS-1l=4CU
z$|B0pXYqjstO4(Vf|0ytOnmfDsoF6lem$Upxx%=l!3Z+7Ieqzn4{6sc3<6`U`
z6$XRwceH(aXh`Dv6}_K{+l6jDKauN_#l_@ll7;k3)2;kQDr0e(L+Gn)PG%&%&9-Jn
z(Lh$689~pmyP4DJRW@mQH0J50>0v7xJKpFG7Gtq)RM@UbkTZbNM3bpl`tf||3rFcK
zq$#qBzl)t&LQrp^UT>A@2BqP)K24Y?M6@>13G&t&`NMkJDcnc8YHvklTT+4Y;&%Ab
zsH+vQv4Jy&1Q+UAg)F6_^ZxxaOD>{rUMCMy5zTho^_y7gj9g6f@fm|dYp~G*ABC<9
zGs`<@D~&xXZOATqP%z1$9ch|pE)tz|S7QIvjW|SqnK5KglTpSGnPOhv2S<+{<;(m$
z3z}IS^hwpHt!mGf`qPq6q0QE>To4bot8t-MQbF9x+GoymE7NONdMBL4xXpUz6Z$0c
zo)t;$Z1SuS`hYE;HJKh~<+C(cc9&+2aV^vL@Ah{1Ip63FQ2~CFTc|>Bs%;(}ZM`EI1#$bQ*h$ql+1c4Uv2*6l
ziKQ)U=bSMimz;N%Hk*9Zt;U09bzVhh$Gv3=GPJ2K#Au$$Zs@xQ0HuLucghh4L
z@)f1h6?L&R72k=jkeJ@PEI%q7_HS@W{7!!cZ;Y-@a@;PzBLQab@_@~?cq3O?c@S~h
zf2?K?<{D9T^t_1~UvwJpQSU?Rb>>i0&n<4R*)LIPao9tmie?r}k#V2R<*?FpKE3x#^CPBREzzN*N@}3>38{D;`O1CVkis%mI(Dxno
zurApNy_HVTEg)eJ>+jnf_8-_kpDn;U`S|BTaM8(nE@JR2oizbDElT=+{PV3u){J{G
z=DPSMJMi3K`AEcKmL2KC>Yf`rM8XjAZ7cir8`-CNKg7M8EGRp-z_WKUB#S!D!(?0T
zYa(M}>og)Uri;@uI_x7l^;KLO4oin!-8r&6#-v%xmlYM4ewuBDtv%G#VGr#P#J@T_
z?BhEr!Z#J;x_FvbdnD49bbI*0W0NyoT!&JhZSSyaJ2h*C0jBHAdkTxf8tq~pImZ=7
zv_6%6p0i4^0oq$Edcg|Mx23Y_!Z^v+;wrz~W#7um7yM0lasbQB{gI2O79I=um*iKT
zYZg*!nu(6z6&D`ipJw?AJH=cVy-e4!qD4y-vtcb|cNficdq*0ojYOn9%2F4H(nz*u
zaU8wCEQ|jvG_9_DYRNdt3;vV&6|A~e^Ah~dS^AP!;8CKiK@ohloP(@C!hTr#1#Mh0`Co_A*1uPHUXDNj_N_|^80UYowU=2zQ?y|&@ib-&sU_SyoguODTm6|c}z_W6qC
zf_RjTUiq1CDO#km$kO<0&zD_7>c6v9R@?%GRiE+8;OSMTx!9B+?-7ohbQ&OXV$7?&
zoWGY2tX#0#mv-mw8K3;#o=6|-2Uc!dGk_xM?f=u4Zv5MmViTr<
zt$68M*e0+2CoQdXteqgIek}I2t1c3+a8ITG>jI?`3o7^)zikC01l&u87Jk9S?ZSgx
zY$=N8;=hYt=VI#m_vJC4Lg`pPPQfF|QWjktEr0Y0Oe>3hxyz>F;X|)|(i3Oo_)>Az
z{I+?oc~3lTa@ucH=O@DDtKxAzW%@F|4d#BQym1#quaUB4gMW9ir`VAVpKzbW8>e#d
zkBv`oac`r6i{YEP#oSGA(^Ks3rYLUH{<+)s%%8jc|NiHn6}2dKHrrj2?#3H>6Hj+o
zYf02&PZ66FJrvG->u>2ro2L&E;iX0whR}D
z5A)xu<>INW-wfpAz?+hXu~-O}R))OcO|dv*-wea=qVC@v-M`lE-{v=$z@D+~Mf{%K
zwuzoSOZA!
zU(Q6Lj0JZ=1~>phpTd9HASZ(<;2PM$irx;++H8cksfRbA?*Kc&?#Jvry&TULZ~4Ek#3etr6R+@R~(n{05w5NJU_142NbM-%i`z*`Us83F!p3!-6*1+DP;|5^|U
zpS$pBd#p7(U~4y$0;K~+iif_6lc7%m8DJ)u1F}F4=<`t|{H8~yV-CO+5Zy~CWS?&a
z^eiwF1OW{Q0X^wagzUz{0k9Fg3Ce*5^c8RcdfUqwSIBzsIn$JS7i1+7<;x&85xK!e
zU;&Fj1~>~mknZ5Qd%1-fXa#Mc9XJ4mp8~jXe=raX0U8hjLO}$G1kvCw%A(WA0;OUa
z3c~}Zy|;qCCJ#cI1`Gi~;ExugH3QuNhi9N`fcur>xeBadu{$Rew8Gj3G|%AwxZsaU
z%0b#9@I3hcYHUS%8(2CUix~V-c~wZW&L)eMvGXu};Ex<%Ls}8on1ybDKk_R_ng!%M
z2Vd|zKQ`wtaRr)%*e{Eax)}eW2A9E*WkmT=HU~N$ng-l+6RzU6m
z9?;t%6_97)cOJCi`7r(gQxE+zXad)ObqUHu+VcyDNjV70KxDcBc>{^Jz>!=m4Q>a`
zc)rVRD5w>(4YUIX*bhGn9|c?V*H<%#EXU#mZ{}gqKw5DFY=T||&SNQGK(kw6ci{ON
z?*e2K-|j2CYIRfbWzx6xj;g*os|S3vRuDCOnVWgw)+&
zKR5smgL;sWkLH6`a0Jh7kdfdc=$AnbbPHq^u!4aoPXXINuoHSHpwK@@+F5V|96){N
zAup^#6uAXu1)SO;9YCP6zRf`Puf}M+h{*vK(3cPaeF)N;kuMT@7W53r%b*$Dg}oJ&
z!*2Z(@`LkhurrX>#_IwzS1w<<>LvDY_cJ-^f5%59eo+I>;1|#aIsrXOl&)X^@a~m;
z&FG6HnpY4_z-x#aS&)Mub0C+3Xy}XBM|=JjyWb`g(T*cnr
T_ZiJ&8T+e+G!^rD=k@;ufzp?*

diff --git a/Tools/IO_Firmware/iofirmware_f103_lowpolh.bin b/Tools/IO_Firmware/iofirmware_f103_lowpolh.bin
index df3d1554a3a13e0b6122f807557df5cbf47d7efb..d362bb53d8ce24209266f7930361847d1d2c36d5 100755
GIT binary patch
delta 8749
zcmaKx3s_Xu+Q--0GXsM%G9zFDA~TGrIFd6UUNRJh7z9*A^Ma;$AFL-mZ6tsg`d=hFqfD1UYNhO`Au0
z7*XDgCCZqx{JYG>p!Lc
z?`-bkKN#&B&|iI$C>vx%JKe3D3*PMUzDDIp=R>=@sOe^66U4*TjyElTiwMx7NQE9)T!HNogr6TF0uy5pQ)z$9O+wAfpo(}45J&|
zf|KuO#pot$r@D#5C6~kK(pso!YvXp3GTh=O2C`kM#gooxh?b~nH1VX-nM$I47o(I>
z(I9#122HDxI<*awS{Grhk%+EA^3f?QHIf|KKph!UBPn%FY-Ycy{ybm4^sP>fe9CaS
zWnX2!RHJE-zSpr2`VE@$y-8hFB5l_uR`SOABxZ}07P-g%v^l~%U0oIZ;7oXfbV)Pc
zpP7GdqT+My<Q)&w&qfy?{
z=~-bX)ijtlJWKjU*Y~L!smYWPPpUI2vNPqD^M)-YMEpyZs%eaYh)1%<8j>4@OhKF^
zQ{w&~Swt(8WK`8dKb!TrVRTQLo8gznbKFZHtzT#80%s6%JC?YMEv|B@Tw^NzXnInB
zwP~fy`jwP#EQ~LZ{-&uctxWtNslT;hrC|M1Dw%%3+^?ZPs`|JCN6f(QJxp&~0&`CDOs`p6i!HgM17uen3)vjVYrUE6y
z_c!V?Y1gP7YD|9MdPN_IJ1V;!L**?#WQW9OL!uJ?vm6=
zYo!Y&H*vIUqg|FMLmAXyyFc!|bD5|^R+L*ToieSm)4+K|Lt5X+sI_P3e(he2`4Qc6
zhHdB{6q%Y(E1fq@PIEc>IMu;(lIErJ*)!kG)@pgLd(FfkPqDPf7}X_r8^_xdSxW!M
zyo>Q{M%bx-3sSAx9O=4A&pzxQV7sRCv2V$x`eJE`_D6d|Gu78LPu2H9SJmMJjdMe}
zSxZ~s`Yzs*yU%R9fAG|xp80ZhWnnz=!9uS!e)WjMu2ViN-TSdAIj3SDSiBE)
zW%~5g5}nrKax8dQ@k95x320i$sW>YY*K{bBp7_D#c(zj=EKl-JPsJMGi}*MeKOx=0
zfL-v`u@>)8ITd9R8|)MA-RwGJzSR)@>$D@{4Yt@v@4d}QhF@#Udc|DVw5VuO)TgbVKJidZsGyfJRo2O
zZyFDmFCtboA#`F)v0#5RedWK{F!sumN$QFk=|^3WRc`SXwX%T5e5n>=c*jIWV5+TC
zRwv&-5nCXMIvOsBUP2BuHv6#=(V`Acn%|5!?HTdj_sL?<2BOP{6VKe8nuR;=+hA{y
z?x2`HBXFl1l&c3#MDb=TN=TX^9Q?7b0J
ztjNa{&X-Dbh@9r^k|7NwWL>h?jezBa@e{0WElcU#l{8pptv@~AN+S#7m0<<&_iDHu
z?JZK9*97a&r<+!qEHdj4jaMIW_;+KDRAMTZb{os30_{F?2#Q^pOmA>YS61X~MovWw
zRmiM9)mN>&LS@*`jU*U8>Iv2(Qh}Q8Zdyr?^FWn_#XyU4q)$nXREIK0Ys#f3O*Yd{
zGTH2ga%oJ8JZw=zXp;~{!{#?VHI)V%x+2_sYhk>>S|E+lHLc{CWY()|3gdZJemBC}
zH}(j0qNl9kKUO3w5vx`N2?kTssA)f)j_4|rmk@3pnJ|5oY_@g&>K*1Ojo9pFqENJH
zG(936G1Ay_X(Fl^hdXY4LL);(6HP~?Xw7*$>`0raW3h)C%cW=?(oOr!`y0>O2PFAh
z&)9ufil47-gyqW0^I6IF+tZYrA8mYuwH)D~*TOs4+nsRhn|9u`?9(Oo-p!OxM$)=%
z9fH%^8Kq^Cy5_J%YJ`X#W(OwfNt1VFM!bI(rh~ZggN%x4Q{@(ewQwaB$FsYB8meS2
zKR?TL)BIAyueB~w%Ww!lAV3_rj_u%@X=YdIGIjTs@;aUrPrHV+lb}X7p{$_on29a)
zf811K8qknyR$bwtVW*3SS3y_xV@9-_czxYh_sz2?~5MkXTy{BW*0Rz3d9VsStKP{FtdoDn4^9(P*9!n!?
zo43da7T}?*6Yg^^7a*FE3E1EeL2@J#?s90`5dCLRG119GHT2-C?rxS^>7=$_m-qbA
zOU-M;Z{x(^_LW*!E7hi8CnrQ4*?tLo#cludhKME{bIg{cT4~@6|MW|e9Nys(hA~Z-
zB*}EozpQnmZNitAr2BC0W3V)3R8et&^OE#v1Lt8JnoR7;LH;%pyw7~N@r3=7G!W(V
zF~l_`i^Lp?$k|h};XDSkR+7(fIi5n>d#gD26}L+1F2`+&4|wrIt%Zmxw6eS6GhMmv
zr??z4Cr{6D`X&uX><%AAtC@LFV*$32nNL+}E&Lf_V5)hW3eC0$sqY=P^TOV37a@6=
z@7^rk#JAgcr%z!b-auIAakDGZFuy>9f-|;|fwXgiy
z<;tj#TNV#w(nfY*aG=7B1v!IN4>tALwqD*^nOQEKFtPT*<8`f#e;Ods3C*YJgsZ3B
z4gH$rI06V^Wzr?BCx+^{i9H?kj7IsmqD4^rPoq#$^`p2sQX0oT4hj&Ecs(dwc-zGK
zYiAF81zl-S6RoOK_3D$?(|~
zfxjW7%O=aksVq>h7nBE?SszX>u=VGO8kcOlbcG?SS^|0$>su|6Xvd)Kzp$;zse=wAugJDMo-+0qd+sgYHV2p#&MLzUok
z#CI-x)iXhE`Sf0mo6~XKNh&?2B#W*Hyq_?qZR
zo%o24=yZ?Ai5^SuvxI1q-;a1jRayFn9jopiBDV}i
zvwe)u6S??J8H;YA^vSZV<|2WB;G|SV<8EDK@+MHZVO|*I}$7%jwKy2
zxTdyuI6|D{7rSv>))--rlt|p}XDlWFdW~=vV)*
zbc_Yf@S`?1eufFJ9V=!;AcVg)BaD8=F3y-qzh%0ak@OcfXQsjSP5bLTA>!jDyHs80!ga;3|%(re9U9>R1Z_-xjJNCuXe!e%OWqiZR<~6)?;=~EQMDDV-
zr>g_2D$llPy>2&tBKc(5?R`oG@kpC?rMyK+1#u_4JZqN6F=Oy*@7OwwZp7>l=|uML
z*(Tb?baO)J0~S9gj+U~Wb9D6Y?7cao+>aUic6r{KGwiYRZgPte!Rd=mGCaD$>F{+4
zmP^e>rk^{3e#4%ftJD1ppLwnu!y^I)#@(h0qoual7+LkB6fKCm&ter;XR?EH_s~0R
zZ0dM=m#s}5MK801slHyHyRO-bTRa3|#Pusgbh5hCAjLNs??~5Kb7}xqsbbzRkME4s
zplHO~9E+Sc%=d_K^NZe<#@ftBMd^2%6
z{*J@q_r`O00d>D3$0_rB5@7W%4alp-OTD^^hZ&dSr)oY2*@b!0s8lsSik@Xj^ZmvK
zb;^?PvgJS5JU2#(LU~M}C}
z#Wbvlec8KIHW~Y8C)LNUi%~~E^>U5lB_Gj|C
z&VMy*{en^S20OYy=iSs^b6Q@|U|FB|aO7|IKtX5EN+R&RX{SJU#B`cFAQ
z@NJqX`Cv#RZ?Kyyy+??@rkw0a8Cp%=
z=`Hn8k8M!3`W-fS)kZp+?OnA((7wamR(~{Lv=?7{vMKzf=d(^B>0fE;Dx40#Ui}e2
zB<@@D2^R}9%&H4;yaR}wM0=LKn^8nH+(gtuG&z(g=SiL{^@ZdvM{e!5RJ^cb06(m&
zvhfWpB}5?OXf!|h2WGR`>)z-$8qMU%JVS$;{jzRipWklFo_KKpr6XC&dT*gYUAAm}
zKT2O@>;Lqb2mfRhwhezqu(+5030q+1`*d{K<;)3kI+Jy=&0M^_`Bg54ZaF3&au&*$TgE7O1lh$@*^z^O`jG4R
zq-VWq&9@d=3vqlQT8iZa*M-?b2iJet9dNo`cEe?#nO<=@ZX#B}P7B>87NwDYvNY;(?sJk!Lj)3|tJ>l0jjzBQbS
zhutE4+isj)>b6C2Tl==Iq{m#s-b|X$-pzXq*Sfq(zWb325hF98H1WX+-oCVq`2EapdjJMBa=RYa)a}W^`KO5T
z0z7*Wl4Ll#$`a?nyBPKcZ}$22p+d1Y`(=AD7XxEOmE~?LaiV
zE!`Z1eiR%B?>=JZ>2>fY`Y#LmA
zfgcD2IuHWFKqMFsqCgCY0||hlFkj#Y6g{XQc_qD#3xysD!hi|cD6$@D8^BiZU#cXEIVcZonu}=;{;0f*NNb!+
zmMN#s$I}FVcK_O2rdKFBE$rw=cQw=K|cst3c{fKfe>&7e%HV)&7LUySL&3kMV^0RJn<15yPvz!y}(&kr(?MgHaG88Iu+
zEKso${|!RkT8-SRP#x}DHlTWx?gu>tHU-jmL8p)&z{$G?c^tNPK^y!PtC>(Z)HiAk
zVhY%c1rZ482TUxgaEDE`4r8?z&4A@&PzUP4MbHK|WT2@?_XCZ%4}?sG?J{&H$b)_j
z@+PsbJUxCmm!65U8woRgk(DF&b!K
zCAbE96J|k=L7E0K6>NpR0n!OH(0w8Oz!m7X{)GIXWj!J#Y=J-rX02Yadd*Ah)4j9P
zUwRt{^Aq@T1^hq|2muCQ0%O5M5Zfbro6#Fm5)gXQ!7hZ4t&pLRdHfzEK;OwW?R#r{
z`A#%vluRcH}U6bC?a@Zx$|iu|@koqMl55pjx=&#lAc6>i+?N4S_NM

delta 8749
zcmaKx3tUvyzQ@1=k;edPeN
zFlUKUqZKW}oNRyd9P?bWtGI@RctpgSwR_DOa>bQ><^cJ;DyrKcr5K8(R09bcUF)Jv
zduW-cNmNgE5q%`5UGG$zsJNz$+e!LxlZ)uac6#Kz;O9luL`99nof>Z`iTWdqQeH)^
z6c{;VO10Ffua&|h4d!aeJ+f9(M=DI!5`i`(k_@Sq=rLpT+&$K*h=Jr=%@<_vEw9viL(CGTq7MX~AQwcuwHO1kWKM
z>mQ$zvh>$nU9S+`yHc6nY2W(zUFjrIS)KN6(8`F@zMiFczTy)q5#7q}R(^I^8R5q>5^J!!1&xw(qmm(zAxV1X7h(QMguaIv=+FBoRw2
zo(*Hdi1?mmY}nK~VeQ$qf*338@l%BwA8fV|wQw@edI9PGZTTuJ>WOqksQ4YZuT^V;
zG6-poC$8ex&Qp@sD>A?IJM|5Hbl*SJCbdtQW{+h+90=pOl`UjS@wpbhzB!NDG%
z^q%tm14&xn$;%*`pzdC0IFH(X8?`y1vHA8zCrE2W-aQ*uia>_%t<$b8mSi{hu=Z;f
zWU8?J-+k8N=^5Ook>i8SqzbIsvE(i}(VjjeHRwNa8V
z>R4Q0m8^B!x^QW*x-jlRT|FjM(9}z2p+<@^xQHE(7ujTMWn!#sCJoDf7;@t5TC`8L
zuc$;CY?y5;gq*LRfhMiP7R!H_euC;O&{J(`DFsDmiUQ0f(sosev_svHd#Q|1-EK_X
z1mwHwT7m^>Y&p!RSFkQNsYV)YNX&BD|JA9|PDq)P&6n$3m;BZMl*l)+FU$7|$WPL`
z+TyYG7DURr>V8}AyhC;C(TW9_$Yg_bXMGW0mnGOc)soR5-q9o%7I~o+Mfyv*XQW$t
z+nuzBudZ5ORNis_fh;VhN~SB3Ho`cliE3inu{YcO2;+Ljgnd
zx8sw{RE+OXEZl>}QdDnN@3uMZG3dBkihuSB8{6TnksA3e(=W!jnU4$&lx#
zc-{zDvO6Kl?Ao%B&dQ})nfXH5Tr(ZLJ3$$~3;v$9|1o-tG~YAIY%6QX9cPl6@6=s;
z!r_;?jgs0>A-%1ykc!oN<9twT(v+@D$a52U`D*(jaU%T9{coM0hrLW6e74`oqZMe_Ux
zb8ynsF>nNa{jKu;6l-`hlk`6HVw#UH=C+JdsLaJ2NExqKm!*6phh7+=gNEtk~Qhb2-i
zL~V_;W03_Kyerv{gN6sLHq=X!dY}LKFhygrRHx5+Fj2MvvKaAzjr8{mPe$}lGE6HC
zGoO+csk%>)4G2SgTPGnc5QJ;TmlwDB8Q4qyBO}8NzO_Yh9*ul6zv<+`P|#TK<{4eY
zuRi9P!VQMfC#_Yi&Oe&2X08DtY2jYyZM*|{6=aCQ6I_`^p&sxgztf!=SM);6M6oBH0cwh8KX
zJh`atwyrGqgAIbOfelqZH{&kvFis0qMZeU3NuG%cG4*l3B(+H)CO%f{1g(3LI!Gaw
zIEi?vGrlNZl*{5RMEsiT4=p+I78UjZ&wsLnD7UGIx(4#6@;bE#rM~Rnnu&BL(`dcN
zzT$A@O?!*D5jA(?)ykpstRA^%?Quw8nEz<@^|HXl&IPFL)S$IxT
z#dN(HWDhsV#VrnmyPU9W0o#0?f$po3EQam@sFf_NN;|-Ho%Sc3Ll$;TJ2u#2kazig
z%`Mt}{*hr{HVXVLBU_dz7vou^PAA+bVbAFd^j)@D_p)%eq+A%XiPDv9bI45J)klbu
zH}v7VMCtQ)qO8I5Pe;lhg-nsrTWnJ3x5C|nZ19Lg?~mJQqSESzz6FAfqlr>vuZ);R
zmF(h((4nN$BgtV;?_BhTdy?Gr#e-@WhyAXDRJx_6iOwjz<1mL^`M5kVY(1s7%KsKl
zso`TSdd#fQndq;iu@Gf^2b!?
zJy~!5V3o`qfRjlf#^5?6h}jM`j=+FryAwLh?#ZXrSF;tOTbtgDV-a55W2(cB5qTDM
z@;63aH{bQoqK&+*^UznC;%DYBMm&uq=E)Kg`>^k$o*%>{waJh&L`(1{A|J01Js!(j
zMiW6iz-EjdoBy6euhpbz6a8P*Ci`clJv{%?)y0Cix-%d-I4KZq|Eptg%HZTeY5!FJ
ztRO_47(}=aJ|k6pM4ue(-jV*lM!6QPZ$Du>*(DXzFmFvSIinqpwN-l;Z8R$P@eMR74zN?5))tt?fDU$UcP#$zYk9%H3H
zv%_QU^d+`0Mnfx^H71yTRDL}sozi~gqn>J|bV7N^(_u2VVeM(+()3Qdj?In@>;EBo
z_L|T3Sehcs;`8t|+Z8+4WBh4U)njpIj@V&Xx*^7~^lO%BjHKVQw~PbnrSkWTEtL9{
z?}^(d(A4tiNiu=%FCUlSq;xYIm-JUuSeMi+j1B5YGIiKjbWFr=PJ4%al!M&2>0>No
zgk4fHae0`xNFU!}@6+Wqx65lPyaL&S)TFW3+j-uRT~-~ezjXdzdB5uN3h44u!RtG=
zYI5m-e`gY9==1nY1J;1|z=`s4Q~oJ1X{tNB^@1NWj+L{#NV)sxi!G8xotIF(GB1IR
zPQNtnt_p)e_?y~(Jv1b7{i@#2#O*?to|nLNslvtNX_AHXN!6|RMk-;k8H4C+Y<5N@
zy~DON
z^aUgI6{In;lE0CiT})7~MX$HYbOTaxXP+ue5F%O{>3Dfdwfs>X?GPRyUA3>Qyfraj
zd1(iHY1Fkc*jWGRgMux3Rwhd>>v-_s?BYwPo7c&MR78^=d}8{*&}wY7
zz{jEM!p!n^+Cs;jlQv`(Jj|bH&<;1vH5Z6Zx;vq7%0?Wbzf2!ApwTGfhfEXVX+0~PrO`CwbIvzH3vDtHm(fzDoj`zI%YNtJ*ijbHJWs2MsWH$4+
z1%yR)<+A0)(p7b#GzDLau9BFZ8!bO79QJQ;Rs2qW7VnL&jdI*Ezas%=@6v$HHFz&q
zS$Pm~+JCHK59b(Bb@bc`>0fjh?^Ex?>viT(Q}dpUcFI!l=Hx#sZq`I4
zD&Y}WLM0xkW|@O8T8DkH!xDf~UY6bLO0mRVYPWyS&dxm-#HTRkJuJnF_}9EkWr;W~
zJE<;y6)$HhJ2Gz=zA|2%H_DrSqOz*sBR9=0wJb4~I_&>oo|&7wZi746fy`0#B)gcY
z@&2K`x=dxIQ66DG*FB|f!{U=O`utqg^%Yq9Xp*kZNM|BTu4*L)6pU>yx&3x<&A-L#dz7R3+)sE_b>}Dl>KkmgA
zB5T6!7;{~CiyeGnpnN!DG0TedVYM%e9wcE1`L>n)`laksy&vMVoVdKrnlRNb?7U(HWZe2ySig|X^cs;mM<$RF8MUe3|m{Msofsh
zE{K11w%f;cP=s$P#&+^FueL~}E$;I0gU2Rknz#<7KHt`E*LG;u3jItsmUR~vg*DpA
zJhD$HjA(rd`#gK4Vgt0dSoHkmo^MMf(}XdSt=Uz6rPIEZmCpa0@N_?xk@F)L&n!3|
z@NdblG{-C?S2qzIzbh^{%0JNZ6?U4rE_{WqV+9KrD`vr3%3&7xR(kyR}Ev(UJ@{F%jLC@=U==2x-mTFi^_JA28?UV+DmvKmG3)p8!P?kM|V
z$rrSV9bL+==Ko$AM5i;y(q9zQJ#pz^Ez1gfv{!OtL%B^^Axm`HzjyN20;hdel?4TM
z+vu2bo4MW@CBLRr_oO^kb@Er+KYDEXs_I{DANJUWR@MG$JJe$fth#ZGnU=pw
zi`nPPmkHuAHgd&hzQt&fszR2^Uw*#q6jJ_^rLy7{D6IU9Uk1;tJj2DNyf}|=+@wSy}=_E4-;@N8EpB2
zi#wJ>Tx=SuO?lOIu-v)D^)84oXqSr{-vcbQr*wgIjhEKT9
zqK#9y_{YYlxVXR3z{Su_U1H9rx9MqiZ&MVvY5&}1d+yI&{(t}T&x#rpJB#fpN^|24
zy@jW{tfeUGiKmFo2_6b(p7po%g3Z$giSSfbIPD9avgAum#8B-Q*G#F>DzbZ5(LXD`u~SFWUwMisUk93}iE=hr0)07n
z5v&2E=P!E#QH}%mKsq=GLZ89^+8`%^$>2KJ$qL>M&fIK-x2c;qq3;B{z@8`UJiQdp
z72qPc0&arapb7NW%>8=x3%Ehou{YVk{6WxyfChwsUXMoTEr7Qm6fy$*?-oSEHV(AF
z=l^R#Bz*3{r}c@}?1Zh&Nb;2q7%3ilD^7ww8Ki?5U^d7E*`U`)5&xSWnT9z4lRCiL53=jk~AOv)$M-j3I4+p_U@Fpk)6`;3(i_lwN!MH-!fzO$y*gHQnktkmQ
z;}Vb?Yy=fxAxH=3fCthYJa-SbF#|226|?~dpzu=wH|`JmgF!$8LO>{p0FfXX+(TJ(
zDw(fTOhsXM;I#Er(A(qzNYj8pAPD@?Vzj2CJK)H4bPaI7Qao3JHEi6j@%b&VwgSy_
z_-`)wqmr_bwh+7s{=XVqklqTG%)%lDe^g#2(yX({BIUTbm_G1Fj;|xF0Bp=eH^3kH
zl_ISIWWNAk@H;;?`!BKing!S|3z51A|ELC6z@Vi>`B4@I1yq1aU$#=M$510F?g7bQAI>5^sZ}
zIanIp4w~?MkK0gC3uG&30}gNieiS|mw(zg7Wei$|#R=Zb#iD_<;s)3Vy%Jo&Qoe|0
zx4`be^L5?@$VSMU;0nk_S^;buK^^?BFK33`LkA34iAn(9DXl271-P;0ySL`wehE!@
z5wQuWd%yv35F7z@AUzMw2QAq;4K#sYKr83~^cYdP
zf_}ieNA@{oA;m+u#8z!4Xgj4uH*I4LApK
z^n@5c_^qS6aqOLD8~5dho?7P2r#%%r@d?4{?0#?yLU)J!mZOqI><@5RcNpK$4zVfw
Z`SwTdZY$nS6(}~h+KwgHv4E9F}{Nt~m_w1RfnHRhtnZZVI
z09*iduMp)qa1FEr#b%-m1W{ne$X^%2E9gWXE_3qxWx<~J$9QerN|cL=kpVJm&rPex
zq9~%gl0cM`YF5$^4~0fjir3lhA&F6)E~R)<@|)o|^O#BY)iaV@Q=Hgor(#&=@EOB@
zWpfvAGCEW@p|&sGdQL$xf@b0b~J4tTEh>!FKR
zDs`b^zOXne$gRQXB(-$NV;w;m2MbG0&HR64A9tzB+}uNs>bg(2>zil2X^oQisi4!Sj_!*L5o7
zQ%1|p`|3-iCUuMSt&W8IHg49XJ?vVyFX&a1+Z9dn=awxG^G%;;Hc8(aRSlKWtJ;)$
z-frKNLXpyP_k`~YVtlex4RJr6h;ETCsWXC@>0T=pUu4c3FMsV$WZ26=mrXPuoi(oo*|eCcc5(BCylt;XC$(wJLUm?t-%joea6#5eN2S|>yj
z@o@f=k!dy|PY|cclz9H{e4-U9a~sY&%1LmmCgkwl``n&rAU$uNzI+u6TW!B*1vZyixi4JFDqz{_AY
zH~>y-e@(2u|2c3#cK#ne*I~N=8o+yC-hl5+=)An?kV0O6H{T4H5I)W7$oYVD9LSwR
zbiw`o&2v@Qu^uQH`<6|YNBc(Ype^ku*DLy9JW<)*cq(uAB|A;-EisZ1xpaC!;~~jS
zS7_?6UBZkAx=T_IZI;d(-NY2vCc7+8hB9cR_2I-1KFvcNvhv~z>9{e+PJnNvvk&&l<9H|bE-lYq%O|lt0%+F+F|~nfAhp6PldG9
zFttzaHB7Rnq!tu^QmnC5NUy0Xq!Mjw_Qh>NRkC2s_npfxkstBzu&dtuYi_S9-nTZ;@WP-ilet(j%7WnPZLzmVKcJW)5qQ#RYhCnTl)&SFq?+TEa$2-EHt((Q5jVVfA5yNaXupTo?^LI-I{GQ%PhBT
zS073Lx2;I3G}cOc4Yg9KRlCm=hGL&fqc^x|Fl!sKD%z<+X7O#jYT*?sqwd*AD11~?
zEQh6172VsKP2c4^Bp*A3mKRB%ks|2~3LUSmm7X#hzn978x711#(&bT0Tf$p~sWd91
z^>;IAXk_1*WLU})BQ4faX@agbn`e?)uC6Uh>QaTW6e&}3>(hIxhNA&8cz>PhYd8LR(cvWOvDqcR%xwkdC=KN#g$UYX2^UHFDrs9MP$mTiu}38rY2)_)uYzytS%^)D%stju(T!&Bkxge9T}}Kd(L_tYf_H2`merK
zd9K={CC2i)^nq?+_N_RXMG&dLmlqwce7wz;+t43ua_cD8{4g!{J9}QEALk>|vyBNTjR@{(G=G0~>U`|lhB}oqN=*S7J7+~Xrpqh?N)+rY+Ne|&W
zB+}fP+dxHs=Oqbku?{vywiv_EYAiIlUyMzqI*la&3$J{2Sz@o9H=$G_q5DjSY)9>v
zqyQ8?ByxIdnn+CHslQZr7K7X@$>+Enze9%xEB^EgZk4iJj=K_{go<9RnTTF!I&aRz
zA(1EgvOP?9Ib=@mP~`MW^-t-)VwA68rjfQ%oHBFkwPrqV7_CO$Q1!hHj`!2p~Ai
znY1sxO4@5=ChvfDA}$;38~8lm5m+zvE1M)!9IxAxF|LDd~y)}OxMxBs9Nb(Sm?_l?jW
zaP;`H#?U82e52)k`Ob4oXnBw^@;|Q#{2d}omLwNvGC#du@IAmL>!WEa%hCTq7g)Ap*f&Y=WiIO*SEM(FLa3Y?h4XvGDLOg^>rD5Rv5bk1m>|Y&eGA
zRDwO@iL!((iI_{DVpS30VO`x`$xcUV&kKL@OqQEJd(h
zi|}aoj8MPi;sAwM&`b3`GYyvaHpna*1bKzH5Vs^jTR%
z!P0*eaF4}K2S(&;)XComdEIaery*3A8k!WeE;J=5GwtEo^`A;bT0z|0qe&T+
zJd(HG8Js#QrBHfnc2H(;Qp25zh)PF4<|8^AWP)6f4@y7)X^*Kz{C)Gq2~0&bV@^Od?t5L
znqK4aRHV#9*Oex&O7C$5v#HY}hu=W|{^C?rT^@^wmR;is1OS?BdxQ(*OHU(QHY
zf7!)-$M#u+VQpi^nSSc#KC54!bqK8gWD90i`Q2SYl(Em@YYQj(gNaG&pemmLb5*?E=>so#UrD
zqV+Kiv87fWvea}t+DoPNhMSo_RoZMpe4QER80kZ{Y)%Y5zPvFfirUzjIdkcC7C1MS
z-e+lZBduR|?HULf7OWl>Htj2r#XxDM$y6-+s08}*2tysYGN~R%)CM%zKu~+J!O$Sn
z`_Cwqo}DdB6{5r|bc(#aN&b_Kb_)-Xt}3st=}59FFP6ZU#$2uDdFCdRS3j`hva#0v
z3QCJuR?~g|!Qup-#H!^f)!h#s@Cs~b6mJZVVNq=kyeZsdADbf9GbdSx)rCf
z3`q&dp?hT(^15&|W7Y6BH&T|kRk|4`d?WQ{feXT@C!4ll
zI{in1lF5T$PRkg;(sPKTdMFkfmjFwMd#^lP?Y
zp-%TNdh7-ls}iVq!*$JG(e5D#5#L-PqLVc&3Q>HW`=0a-ySYe%jq6-A
z#^aWOMk;K0Wn)o`$M_vK6ujh9Z#d<0gf<#ZVaefKJgJEqY71x&QK3ZV52&mVv!|XLtM}^3sn@THsVDkFS@ek0q3e-V8XD*n{ZbP7lkI`s
z>1bu!pR>}xGxz7i=yn$MeAI~C?j}vvT_rtYTGviwZMY6&mJ9RPy5~nAX*Bynlt?DQ_jh;BnY*B*nV
z%c1HXTQ$+F%i}AFiq=z^7T7w&&0UVbET-{{oY%wCgia&U7W8>2;ZfpB
z6JJ58vpTyR!@G5P!Z7oV)%}GfV_Ck%u4R6pcm*fW7PcpAt>OfLv9&1ET|YMDhyX=)>S6*^V+F8^f9m)CLj4+)VMJTYPOmN;
z(2}#Kg>##-PL||yeB)}kqr|Dcu(1{e_S-HE*k(00v#M;LIhTG;X&OkG-1zO!w!aV9
z42=(ewjCR=J=Q3HZ?M#Z1GbTkzV9*roK18*+mo|e82ujW&H31Wyf?qP%VzLbrfWSy
z>c28o4Y)mCT=Ox%MDAVt2^aHoO2S_gTp4GnLL?iXi>4=4NnjG<*~;6l0WUs
z-9J9L13kI-QH!c({l;OGzQhWCe|-r5o;7J3reYgg^@o4L7@zkc9beO#H$_fou-MI4
z6=m>z2aD+&(4I>(>8Wo?7-I5rr-y)^^E4h18(jUOP`)$lfkG$ulk8I*W_yt&_R9
zw>6rJ&~1HU{Fs_u1xb@AE&n{hneu>e|I#FHZB|B^KeSnEhBB^T<>9
zjzq8Py}1p)q;K9amzFTwjuG+__%m^b@7`C(`n?4m!6Q#omGaY3-pb6}#JAYgS2Y;P
zMX&1dyZP0$(30asc^;mF2&pn$aAhfr;avfHix0c^>SIEM5A)v{%EjcJ|5Wn<;ni1Q
zP|83Z)9vcUA`RXhiQnYD-;I602l{?5?0ymU*w;4T_ubdl((^3v&mRa!eAwrIo=@Lo
zx|07=Op3vG{+jj@Jx$*_8UL~ZQBM)&3a}CS%V0Ao0A%1VXDU9~gHEsnybofZ#{beF
z)4?Lp2KKWRdqb?R$HCj&&zsQqg9G60N9;Vk0neww6>t;$2--mh7_6E54eFP10lx+U
zK`_vP!L%^w;UFrWtWg>tN%#)B6YxgGLQVqzyHWA5O$Sc+{C|y_3ZG8+P{_fG_p_UO
zM_A{WE02bKUE2t>NaY;<{m
zcFczpP^2k<2k=U?5~Ui79|#1&APhtSBZvi)z*GYhIv0SSs%Owsz#SX#dEov_k*C~iJc&IG?zR1VVCfz9CmtI~;d
zx&Y-Y#F_@bRo)q-om)s=P)^UlY=Yl%+<~;+V9yeC1N@d>1JX`|oaf;Se&xre{$-kV
z>T-OchK9wkDwh~d6A?kZOFU>4pETdke!fisGtK5rgsDqyx(l3jd-q@5rX*Jpf-p|JW5h1VPX4nb+3TS&7^`m$-^xzy634I6jPDl#h
z4#)z?1F*df+TrhHUS(taV%H*o0KS9#Ak`q8C6^Ui6&o;C>(C5X>OliI4bFgeur3!(
zMYYyhB9rT+>`wmd(r%^^5^dHw^FDqc!
z4W~fJU?5Q0;I1GIFJUmyz$$PV3?|HkJ_%_akm+DE^mULOzyrD$q#D?uU;91sgSL$b
zi?I2DKrnC3>NRWsz&?L-epcZ-MCp5!C<8z+(1UO=4#a{fzyuNp&CU{#lyV{q}m{o>3uL&4-9mbC@V6
zfVJQl*tMQ0j{qCE1a5#PpxA)MLx0-{@1PcSxEyEgl+*T{8sIr$Gf~EECCVJg=l9&Q
z^cWXQlou0;(z|RS4ez0Fmz3hyY?nt;>>Zav5%nauPGbDnb3OI$(axuKchQT@>v@s(V!B?dX%;)uYni`U
zn7&Y{(TY}KdQPx;x_O4#U3`;8dPXLieX6Bm^+9u{TyeF?93r1tNh1oRG(({@-avGN
zYuvQyPpo6q$>9^+L?6lJFu2qvDz0qddXh2FxfNZZw^<$PRzsre$MMed0|ZH)KLQB@@Te9llKCHTw;X2ys0
zRGh$W^zP#}p3i{~Ywg`Ha?8`RQnvoOyZcoV@t#zwcRAjE`kr)#s485J-6)k3mtzY{
z^jhl|FOi57p#@T$K847e^n{A{TUd?Pa~74lP}1w=P3^sGc2Y^TJbJ5?tnE3rN*Zg(
zOCptdw){16)0etUXNXvA^{OALBjWqkVY*4R!kW+52;ykrK%gor;qf*rQ444CDlWnP
zjrA*C{4;h%l=uUAq*ZIeG6}htNZiHmTxTV%Ph4in$7vzv`dpd$TWPC)e^Q~;&!@b^
zmTF7$G1ue@<}1?iNr#QSYYHXZXN6L<;d~Qu3#_F539FO(V*7VV#4UX>pyf|2jL%PYL~Eit5?m3~z+t#4J67ui(0tyGOh$I$ejU8|3Vl6yu%Z|*SmsEL<^K_`u&
zm9plY>tm$8>U`tl+B)1jK~pE0h0)d0aD$uZ?V4|wt&xeNWmIQ*68X{RYY?BTXlt?5
z*D%eV4>?<(g^6d=kOey;bv(LL4E#+2B1!$jyx)`o{@H{X*3acS*i9tX}-QdO3}L8
z6Y;3cjgxiszgO@2kw$DnBy-gTQmR4vann|wg2i|!s-y&i_@gE@f2)tV7};?p_cQ6X
zptrLdK7A~M4cC4g_o(NbO$&@p4h2%R{;Ox~+fMiFvWG0$pF|@b
zV$juu475C1e>(AJlkdA7tyG+zt5KU=j>%6y{E$@dAF)2oJPcEgER?zCEQ#eHk+HPTcx;}MN3ZAh(uD!);_9nU|%afRr(g!>q1
zyoZj5zz+2ZwRHDfW#^Ibrhm3~ujQg`H`qhwruT1p18M1JHQoPx{
zX&#-LOSLldrP3K@I(UDQGG-tAy=wlI;44zEc(c8^YjCqE6e^P{bpEO@npUZ2>%rlnlPvUj?mDb!d@fgY$
z5>b;&naoU26v0f3HcMZS&C*4^?2K43C!Fd=)oUmIvoyZ5Nq88{;VF}rps}SpjD}k5
zlNnu2(qqzlDp_KkJzygCquE_G5JdWub$Rh-t*IgRODind%8kzi^fD$A4XA%np+a|z
z2J%_+lt%D(>bbxQRDE=9OX$hLUHsSJ|cDAqc}2962z?=Sw?}
zKF>z_DNMa4@>G!{g*xy1rBW=rxLe^`Ha;ZKtIJU%H+iVt#A3EGB%hmh77~rgv5R0Wd7}<1;d8{Gd=ze8L8r6iD1Cbs@i}xozwet`PrCjYn!_BEYOzl4aN6mg7LeMx<%cX~#?abAY&nz5)h2$ETn=?550r_a!69bBO)PEUgFcPy
zx{1u8R;h$
z-ggMS#dsCWw{_i@b|;*G{OJ|2UEM92A&z92VYy^5Yy
z|Bt(ZC};*{JU78jJJ7^W=5q0mPNdf4W6fmVMM*Wh;~bweaHL5tZg*m-nxo4R@RY7M
z(4uO|YUmt$jbzmx3@&YMwfy`oZzMR?J4dF)Sw(vvyM>i~s~r|@HOM>a{f%q1MZs~p
z|85ZYOG1t;SuQ5BsE7#ReleREVW4N&#)#L2C&gv05nCu-%Qi;79AG_0lzdDCQvDaa
z#6U{N${t2el+oL4RMhvvlOrr3I@!0nl_o1I0x=DtV8dXd6xs6V$<&WsjE;(ww|k~I
z9a-)3-{_ShH+}KA%FXGx?MBsfd6y_}LW-amkY30epayzy7u@I4lc;Y)
z=3#tmz!?wJ!F2-YB`0bnxDTHX*)4-6G8=Ce`H#J~Dk~D;XSGF6j7*QuZZ$`yomB^C
zE5xZS3Neojh>wlk*OpM?tLcLrEp8jH^-tLvs1RR&N+WzH=*=Ijl$k@Y-zzfZk
zCY6Pa)X942TGPcv8SRb%EMv6J=N!iO2fw#Q(==H&zZvyM*;}KhdyYGYzPeO_ta
}ZwiHvFV@2B-{4Qv1bHqEzBfEaMb*QjUN+oVj^5*Lk z+Z??+yk70_ngTC1yEi^%*sWGx*U+II0PW-U|5W#XI=sR=y!_yGlP#W5;{W|De5QE? zpIE>W@D6ytEN-T|YjZReN-OlYvVBX`xq`TdWn{)tk>zK`(@^%;%vgGv z-N~Fxue0YT51|j)vdKD2ed|sw0s`nKxz6|xBb@i_BO5=IHJO$~H}ys1k5b1iKX9>cCGDlKbHwkWUchA)l3UdroC zPAn>YY{zM2nR^4;np4)l?a|}uiQL3WWvQiYj~{=&;0glbf$$Y9w$XvZd;?3IGDl}> zEs$2^kqG)?wX`3fBdX+=YiU14QxzUl!_%nsI|B>3cabi@wp)tcclbD{L6Vfg_XBi#ngRx>LyRan;qLVZBS&R>w(g4mq*{J zf7h(eEp2Okv?!5^e|O!m7dQ0~gy_FF5V4Kjnij69%lkn3&YDy*)uiAfPj@+#mEosXqP9l5%`&DB@IR#AxXQO&f8OQLR_f0q>9Cs~V!Nh?y?9NX zFHOWpp=)F~j|;QMcN(YTI~*y0(0`6sM)w9ej-o%15VLPd$hK2jEiBs^Re$ETWyJd@GX%gI~{l1X++{m-p)*Rc;)~)i(Q;K$d`Vis=%r3 z4|3Ct66?Z*5~t(8nER}49S6iiY~QRw^gO#bOXK^`)~Zrf1&#OAJ*<5}-NI9mwal8K zy1Eok2VxS$R;SaUY-e*{85q&0eMx!5qWE$WaWsb>cRFUjuCAX>pT^++PN*DB@VX59Uh_Z*zHOe*JrdkX1BCD z`nPG;2&S8hJKIV@KDHw!6^?*{IQKlZ!t=3>BI}cLSTPS+T zYwlWVWozdxP|Sq3klmS=)#F{MuQm?r@ky3AKMJ2YmdqcGC-2n!H)(CzkOjjiZ+EGA z9n!4Pya2x$3t#t9pCrm^w7}>3Z;)3{uxksyppERvB7SQBeo+{m%9`z0fmT2Ws{BPFH<+# zg|vTVt156%Y+d>(KQDf~>@zOj$TNDz;8;E$5IIT6ExVjoM7_C+sDuPEbSdSgT()*a zdWR#|c51G!*b%T3wi}!9g$sUUI8ETE`UjiXYb)RFt;AP+ZsryA-mL$s7d?KxEL*xN zfOgdGoS(d|kv#lZ?_G9qb#IC#@5F2W@ZevYytm+g6r0)J*S~{u;hMkF!ZOX;5pwKU zvo>5;Nbm?M8}){aQi+YRe2?EC>i{9phZ(J3aN)7>T`o>uF4ie$1w7DGfT(ZDuhmL>c2p)ZGYaG8}qksng*{px67cfF1n>;>TXxq2*%s zj_2&rL&A>RrNi&?j^D!_zn40Gn|CdMe%4zn@mu@WGJ1%OdHW+l z>Bkh>R!7sIs6v5j11@3q-jZ1dSxh43LBJJg^Wf0i^41+9>?n3fuuH z-~iCPh<~s_jsoMrRj`fi+8b`!m;i56C!0~;26llx&*-`R1g=kki{LV705`xb(A_il z>n>lwq5Kk1fF8gTblbd9_6I>@h(#IpjG-3gM!hl(WDD z;17a880fa|LHPjKV8PF3Z~~kH-3}K~ey|o(4S5Nag9>l~bo*o_6XkLcmxRW^25<_@ z0x6&ZC}3|!od;dqz%6P74?q*JG~=fQI05AqKo8&zfoO-|I;ODg#7`?nTj+Azt>&~Y__RL(YP77o8b2xSHrdzY?y^%fZy{w0oy4s?N#`K zfA`BwOkcg~1$D~Og{v0k_f z&U<&k1MnEM02ff4B+8z^2lVNZ-C=aEF+uCF&VbcePqH9AA*Vs+fLN4gv66%DJa5~H z83Z@LC2$p70H?qK&4{uYn2`?*~{pYQzt`@jC{ zz1DxNy}5BpD6SW#=24=}3?j-T3sLT$PLy5)@-p;gus=%RAAkM4XU|m4yx{%F3^sxT z-~y<9g(%N~YoHw{HWOtahy*)E{<;ueK_~KXnVr`!^Y^?z#%tqNqFhvj43L?7ZrVH+ zMH1zec%qzCy^@A_C^V8%yv}wHNr>!pDaDhL-weN*$IP;?o{{95qJ&O66+=6R&lvtI zo4a_E(V?2*s$)diEF;?4ZvCA1VNVP-xtbuV)mri>AI;zx?v&_| zsSoqww22`z-NeTvmm|uhwNP<$C%2Qdu@*N`!*+Y6$DdFWE%}k$ASxP5JZWsMl4#$@ zNafTvOP;!svl^uyZL_4(MOzysqHC6XbqY(PB!?EDBcmH7rLL8w44b)v=PQ=3>r}|6 zjFMaS)fG#P>SpO%9SQSo*sM!^*tKq7(5q&*E1IOwty>=EnLp2Hl)g2o>MNvIwaIn7 z-M+~MBBf>S@!#i1`(&!>V}Cjk)hu07rw1|fy;dr|$ehDQxZU7=RI?!O(V>6ot&uW} zSKZw&6T@Mt%II?ZwfC@8K~(iFM>(`A;&S|jE%ScacY#C1*B4-!)3Drkn)QkW*WbE4Q4D*iu2nH}bq%CqxkO zaNd&bKrpN{6BoI!*&7GgZIF^0pFR>d3nDXkTZwq zg8TcM>ngWnJy0_CtrlG_?Hjd&EvY}bUNHpYiOTNAQF*&B*=crfj+TUorPBi%4oPmh z0&_>pCCrGRyCn6{Ch5G%O-y!evdeO1D1%1W9!~t=(_GXcD=R9Oj+?UWG6>D3wE>`i`D#vVv+o@p-{H@wT=^K*)c>*HH{ldHo zX_uCU6LEJQ)gP8#FcwPJbiVd2mLh5>mzHbq*qhs^p|NeIVF<=V6-CesH#8s*I<;>p z;w!Kmd!kXgWa_*fo?K8g9Mu;YFJ^rr{a_TC+Gm9Atm$93r{5pCY)jETv+d!5<0A)_ z(bcR{EQdm=$@s-1>3fd*4y0?cOB1N!9_no(WUTFB;qmyNEItSOO8M;ga-G)VaxCes zz1=^)0$Nsae7cp2Yr7RIj^1`Tmi4Ig@{}OI%thENe9OO!P(et4=wMAgI@abBCa0oI zV*b8SK5ecO=I@$ge_o$Nyus3a4L;kPWbCz;yhrS3*dE^ypD$r=`j!0{`_y+Cywv%OjR0mTdn$CFOe;+M=P z$ER=4^T{ef#g*L0M5Bj9@FuXYM~t)$*4$|4E#XD~WFL&qVr?;2da+cYLzFcaRE%yW zp&L@YZ)jGQCQPxqwXdKHv#4HXJy(@(r7@)m%E%J{w-ibhrW$Flu|_JfY4@2!QS5W6^aeK#W^F@OMLSiT6hmUHC z^{`Z;qI+Aj=(~J}e|u-o|Qj^TZhIUhE5EWHUFO#$tuM9)gd&( z)H-g~_f^sT1C0`*tdA$n&X!rz*X%UUXu;Vy7iFSJ3A^ts9B)heE8{&#eYhzn z+8S=Tl65u@DH+QAM>`X3twGEfv~d5y?nPPuZ0~DoK~;r)@FeDIlXPs`fS|T+PGz;E zYCI&7Mj?8q*@1O?%*4(IhG!_FE=iKMEa+^6;!26sV$66DCo6<3L1ap=jQF|6~)1liQO(9 zkp*4-ot#)V@%xW>rbbg#<)hZ?tTrfyD%stj(9}i@Bkxg8Eg7w_c+PqqYf_H2`merK zd9KQ%IokTV^nq?+)~#5XRS>Dbmlqwce7vnCr@lYfk>|vyBNUeR@{)xmXszbU`|lxB}oqNsE7%z7+}+bpz4lIwka1cNe|&W zB*M~~Q%^;I=Oqbku?;pxwiv_EYAP_hUyMniI*l~|3$JW-X+p1^H=#r#`hDg@El2H_ zqyQ8?Bw~7Nsz}UXDZf;A7K7X*$>+Enze9%xEB^EgZj~}!j=K_{gz{dkg@|5gI&aRz zArU9~vOP?5Ib=@mQ0Vka@lWo*VwA06=8-KWIA!M6X)S!-Fj@_~q3r9CL7E=wCZ6i# zoj#5=cmwgB2hhHt!_>hM3O;#REG{@=m{CV{M1M%yr7Dna=-8&hHTp?@2JbIk&c?!{ZW&29WB52m*|wXDmvwAm3zdnRyl4B zLS(gcN$ZJGdDp~dggmQOKA~tA6#vm8RMg)Q^JAomtS&?&An~6eQNlYWHbgsr%q!?% zvx;a{wZmo%OY%-sh*`bElC&0uXzkS+1ifdHHdrAxvhCVnHTV0roG2fMlpyn}YqegK zPGFzv;!-M|x?Im>uM}k>3G-}FTLMwUn@)FL^`A>n3D3kUD;=n?d>bWs(0M_;(8#t2 zakxS7J1a}ohtP7iRzG4=i4)OnSwyCQ9f=!7S(D@&)!!Z5-u3%}sye!CKYhX90)mp& znKC`@9r_<|1o^TC{gWZSQS!cg=eb2+7G#R}&np6dm&lYQ%Eg(?&tMRI53tFGDB8-h z4Sx_u9;m);*hXmq%MM-Of8=eVEM`l>=hCNGWq4R<;t=G)^9}fT z%86D9cERToyAY)dU4_?`f(Pm%Wqm7r^J+t9g{DSlbXh}FYP3Na3UO(tLfpiBq9bj8 z?T)SV(T%_&JlZ`&@0U~*pb+zWsljKa(fZy7nN@>euMijFwj_wFomvDU4FXZO)ib$9 z`&Fhw4C^#n`;P?fvDoRrh4|BS z>Z^SwcTk#E?eSEE%tP0eDy~ZFaRjre(;|l7K>z;e``R>`BFo^jK@PJ`(-wQBoGSgu5L#dtDNDdmiJlb^;wf) z^=DtsNK${<#eK*2S%YD1W2TvY>ZU%cU!Qddtp8*SW>)&$T|$&G&*7^J$OqNnWOeYY z4+S>ED+!%VFrOu78eciQdAY@pvdQ{l7uRs<7rG+L@vGk*2=*z>6wdBgAIvi0O&|o7$ z?L|goz0BZ0qeOakwlGzQ6tB=J^7cmgPc5`tcz|?OSygpMqD^_R7``<6Y8B5jH@>Xu zfgP8QweD9?TKKZ+?)wiG$MYmsB~PyEe(-=-(1J$s#_$*x+2+6-!%Y_Q%(AtKU4_#6 z9NdShla8{6!3__+kjr8Xne zESy5WW(yYTbpOH!p>K>)(VBqicd5c?X=*dZ)ZdX}1@Xu!Y{Z6K_U6LZ=?`q&qDfT7 zRxTPBde`-%(r%ZBf7g1@s?DnE?z+D!o{BeI*X-r(9)b}5%@ra#S^c6A#n(CSN#C%W zi!|7{&P8K9ZW(EWq6M#REOPM}zr)7-mwf7sr(6zwgYguW9M09lY~|u$^DS+GGz(vu zZjp%t_gH?)I354Mt?^sqr+6cEzaqzN^IM{^`c!ImG~q2@RnOy(%kg~!U%aeoaV#oT zq)$yd)g61E`W)I~u!dRsFL7nofCOc&(-G1mOTjx?&_eUVI3+6LflER~UZ^V5>1OeU zT;j~r;HD|dyz5T+^{LD85605Z1oO#z>2FxWwef%Ssgxx;9pCg&L;MC_&Mvm`*)e$a z-v8`4AIC?kdKG-+mh{TJm9dph$1!&O*&Tg%!}BbA$v6z{{v|q})~?1XRXvUNin!M@ zS=))l8OvIhq^q23uxHRFLF{rm9lhP`sprNTyn3?h46CB+h~ZEsJ>qoedSn&GdOF3h zltld0^1$wNw6g8b+34Sy`}3i6JBxfiazsvdqbBpNk{&UyYbUZcT#GTw1-We9^CJ-Q zc08XFSc>uEV<-Fh16z|Z0Fg46{rLPco7cchNVVD-UKaame+wBmsaYqI*i>)~larwM5b z`aG2ID0Zcaub|Xfon4OM-MU<1nB~Um{=$;5EZ<_+GCokef)i*9+mpFgaRS<>OtCcE zyGSaZD@>5=cirWedmQ;Jf9YR^uf3Rl+4o!wTYg+~Sqi9JW)+ef+lWDhPL;mPKi%@> zb)0><{AF6f(pJ2v*aho&R=;AN$7|9ky$Nx-oM~PNqiJmV3)AS2Z0if#X=k<9i%(Ks zuEn|utL?P)Mf`@X{KN3sM~U(wO5m%c2U2mARjvFCVe#cvF|?U|uqv1qu?wsIt#~+$ zXlvN%)dd4uQr5IEZd2CE5?zjOT=jR9IMo+6)S$qA+ob{9tcE65ndLL*($6W411Xam zzWv$u_W_%+;o;A=V*|Fw8szT{mU?i&HnPF@J?5XiiH>J`vR4bE-($VmAN!B@=2v&w z4F2kLtw%`tSB9z{x5tZXKIWImy=y<=Vt$U<>pUEP07On=J*(f&DWhs`A}S%4OjtvC zk|#@BpW5fht^Jnw*YEV_H+Mw=K8?YTOr){=HNdZc&DwBq*hDmwC-V%=D%QK<=^?*7 zR$E^3r+vBm$0ui?C-**TR#mUxIE>PlSpM&?58>anCT+u1Y-6kb@J|@yazCWwt2=Y2 z$mt9gv-zr`6drNaet(itTFL@#U*fmjHbyvs59fKGad9i}AQ#*6&0O>r__G`NR<0&* zIU*l^3d&DgCMb9msb!{un31g~xsH#2)~nWHYninaHyxs-*ko|sQt+7DhbMW^VaE&n zc`2V2Oz1E7PhksvaFs%@d46T>`oGIlN?#l5?0?WGG@+qP(K8@0X9HfMXE|H19|6w6W9F7|p+ss}Hz5Kl$y z$D-&*p2Bt{cwO(!ssAN?^NzW+n6>N}AuonM6L7Urp5)A1BK5@Ek-)k>P?XOI{4`a@d=F*u7UD6Uu#<|4uy@lXw18 z%?E^6Uyea31+`4Ks~d|ncy|PTllp!)_Wd5{`@OLHMc89r+koG9Ut3Ghv%o)pARO^w zpZ|G2eUs^m|4T6`8sGb?+lvh}ZR=$G>k33ZMU*SRM(8ht%^)9;fxqmj_;e3C!4mL3 zh2*eE#13Bos1o}#l3Bo`mFoD7J zx1qle_JB82iA`A#r=w1X=zl2m02GVg#xBxD$5CuAEc=zzoNWmq1(aL|co zC*c1SqIgyS58wrA;irc5%Vg#^Hl<5_!+Xd(yARqc=$SdF)Fs(D@grI7z{M95?ls@2{WNjLYfC;8rTed9b^aafbIpU1})I9 z{T}&2+eU;%*!(~sn73y2nzesmpT9Xjv)~<~^gT+H0U#I{Ko}SYV!#w&1_=Xluo;6P zB@Ury5!iw7u^Cbana`g=9Q3U$f8SpxUE75b1d81lSx6^n1DC;RpoV>!k&u_(`=z53 zhx5~aQJF0?Z?(%tQLzi39$c>e7I*|>o=5-Uy^cA{G;S4#@Kx>*8}*i1IPcAtzV$I) Q9(DU0gde=wt^I%cA2%DZlmGw# delta 8801 zcmaKx3tUr2_Qz*#5{M`gp7Ib$f+!HEA^2+5ib2CmMNnE5ZNX<$RD8ASY7<4R&sH7W zRnaZhx>Z}PfcdYqQn1DTYrFmn7F*D|tGn7ref%#f&E*mE{|%4U?q~bw^ZDk?J?G5K znYriA%)RWc5N@6qMp-FQ=LQqy5ED^u8%LBafXfSDHuTTZwDz~x3-*i($!b1Cl$ygt zIRUHz$H1<2M0o_*z$I`4Gy%nWG~V~Ojqna?QHRTM)=oKXf)6E+iN+*YE@g?xU` zElZDau|#<>ktn^(7SOOB3U^5XvZKC3e7Op25ktR3Mo$d0>o*n2z)Z_uVNmMj}^r8v3 zl|+3CGnH?vk^08uaQ#ID@%L>J?WbspAx;Dv6-fKaTXTlH@2w##Kp5NIj$q zaxkPHow_5T9+LR-fnbj z2ub!~<_-RRxNZ9Ja?AJ*Etf5eujXQdqdb$9oxB>X+8RPS=U{q#NQ3{h3M9J^5}B`(Jn zmgu#{FJ2eD)P<5>FK=q^WwVn?s^!sJrDSc-u~pJo zLw*ve%(oS+mYcrRZ9GH7VyjpEP#qE9w+_=ysufm$zFH7R3kL#KQ3;Q?S&3RWlV5QO z_HV3T>EfTUE26|7$Rn*<6PiiLy+q2|_4|_wrT#wU zCAL&snvc0APcUDRj!!yl>|IkR={_rzq7CPph+AMK9Y9!}GyoG3p{0L3o<&)CY z-gQXQ{O9~kq6zIB+zgBBg#FjqnI1LTG4CVNY|DROM^*?V@?foYb)h7?$!D+kJwc|@ z9s1$ZCNHnB*0;ovdRF>X$+Uh|O9$fe8XZH^e|D`p+Lzoj5_)rou}4k3Bn&!f z>{}^o-nlMD>ZdL+KCZ39y%RKbl35sCEe$ugiQcYxcG+r~I9f(^mM0M(eZCs;$%?iX zOZ^Pf>;;gs^jQdL9UdvmlZ=mOxE1B`_H;JEr;qo3+>cT4y5?StEK6uQ%38d`ETdDZ zrNM^e9GBxtyGlDMZF(-x!E856a|r75M>GI+0(IokChHk#r=P zx-IDK?1oPt%V5K`AIClFIeX*QgGS4f1E+nv(&&2Lex$=DsapTlGxlw#dv@7F7Vl4@ z;SVwBYC<9{Pu87I{MqFDZbvH>r{`$YCYNLK(+_{-&+`ea6NGfG8=ccAV4B`JJ zUvia*|HVT5!hK(JlE@pi)@SrZEWjH4fITL6JKkKHt8`EH_^h51cYSrvG4`C&YP&~u{dLb@tjXFd>cGlH>_b~ zn#xusP0<#a5mq*q;<{ zc5j+Xr{+J@Lcm)7S!Z<3jRtiAq>{eNpWOKO8n z+N-xog%QX#6$@wQ3kxbUB-?0`{M zW0U5Mk;ja!iL4h!(wKSm!^Tr>c*mHt&HIzW&HJQzn)*CmOJ>eqx<856@XT? zu}@}nHA#<2@2O;ob@qUX*pFs))j$yGPuAwgo3*Bfyf3Y=$Dkt!j6htYu)>uX>)gQDq5 z)-yQBlxoN>(V5S7baGajqeATHgg?irSmaX-lRK>QRGk~eCM-zH?+P^nqznzT-LnSGU7^|lmo4Y z&QzaYLB#-PorG8{-NDGFW6Wa>1xEKPL(-@w#2kq9C|a~X>8YKEP$=bT4;qiwp0w9V zn>v~qSD!8tV-!}i?(V+Cj8;qenJ&jG7*Kb|pMT4>b7r|5iWWZO#ZT2HB6=cp9?ozN z-MNlxIj9!vb zmKezQQ6>qQB~oh~GkRSqksh&cLc?Q!^4?)o)YJrzc~pqA)}+MycA|b@S9R7Ps9`)K zJ>oUKJtO_Z!uk!N*H~7+u+Won9yiWP+i4Z*@VdL(9*Kctt)=-DXQhQ~Prp9!JJByx zu}}jq_I1BFkGEFIoA0bXD+L>vTiElOM?M1rBs!w8l#aMw>ZR*lFUR&Q#Fj~Q>Ry
L zk`>~tr@d3uCWZLQQ+2qY?UkYqRbamCABA|G3L%h-0#>ZoDpy)V9 z(ih|=tXt7D>;G|A5CzSkjOQk}X(LVigf18V=tPQ5KGsa;UX)bBJI?dDkt0oVak~>s z)@)s_fTwkxffiLuRzv65Yb2}oU~p-3tL5i!c_YE8-nlX@&Meyd*fp%|TkWtgt3lpT z?{8eAEeej){da@FUlwv@$#OA~MTLh8_lw!Ya05NVHiW+}JSi?~4c|iP8nz+g3@R`xJrqKw{VqoTeSo*ZET(aFBmtu$F#5r}E%3)T-NN|7y#o=pAN z#ptLAdAnzd(~;Fa?~Pt5a?=-&tK6K9`%Y5cV|=>kipQ%8b2@sJ`RWQNeOUIV7)k{{ z6+0OFnc$SzE6;t5V1fqOs2lrc&@?)VMd>x}@3pHJ%f(?VL+|U)le^_bqD(M)5tU7D zBCy1jtn1rJSPRCY7yfd`d*kyl7E$r&%orU_3pDdr7j7fT z`ANwh?7R3^f|#T>8PfV|30@WCBNSqvr}C!3L=X?N34@1ON}PJFCQX|hyiA)KoRj|K z%jMVR3*yT5kkqi0z6kb+vtL@j)B@?yq~M&;Xxnqz=aOj@vbx6UP(D6C{+i{}ANTP?#@Y(Wleg&y~!fz0U z&ZmLZ42fh_L-wa=Tuj{VnxFo^fktYYv?!3Hav`eUUqeO z2Bm>z17B#SG^s3fq)ygD*P1Ra%xHHEWErD%KIbsLKlr^hnx@He_|2$4%HA41-E-VI z^wp&bWX+=oB4tAph6(lWv6m9`L3i=K>1pzbJznV(Avg6y;C}jrL@xeN_D(_*rRuUh z#v*}EEsGr|6X@}>xFi>)jK!t=2|-*+xhD+Mw56EZ9Lw9r;CFs&n+7#Qq|J@Bo>o#CH$_6+xTnO zAw5bk@$xl&po!}RUS^t1|Bzy}uhFA6t>mb=tj*C>C@t6D%JD5x=LzB-mXR4pMOKg* zPy4dJX2#OX>`vxndYwH#c?f;TmQL1L>RWf>f#I2wfOJyfv7G{$1C%D3LdC+5%_z@_ z*4s!!Tsh8yD?Xo3(6?2uuaJfNkH^`6k}yh$ZEBz+?bIOWhmL*6gwYZI2#LPvj<6DoZVGd;IwG`BxAS4}`B^v5gKK z>Kj<%l-W8{>n3S=J_)BUR!jTwS)xjQxt8`DAsG2_$FSIidp(gpU_O!^W`||$ws{#K|R>) zm&ehI?8M6&`cL-t%Y)pD^*uX0>C}OJs@&uzJyxiHw3En$8mA-FC79|OpJSt^j-Yky z4^uUod-!7Wo!$^15;*Q2Rp?FCjn56KxGNo86ty+dZI&^8p#LHLhLyhM`tvS_wo-o{Nr&C^ z5Zg69^u=rH0%;;X4qYR|d0d!1zSB4z-{ENagZ^{8I=VN=aU}hLgqVFxLbg>)xAm$D zz9hLEKUK2((-Sa^*z8gC3$`dbXjoLcEDf(p!BdS>$0*StU$Z1M=!qs5Io(WNkn^3^ z5S$5Qx%b>DGG}?KiFH9jiPQ04%zfszj)USMwr}PjdY)aJsqy`1YgMVLg2sF59@f5~ zZsDoOT4rXet}emTftUob)#-F7+u58~BE$Q%FD?&X7++4pkLJ?jPKT~tc1B-8M}*HJ zx}R$w+nosVqgO0=5g+tw1l_~3UX2~Jwyi28_nwj-H!f=;vPPVdagPhS=TMf$w;w^g zfbB?yAq-|Eucie_m^uE?%YOMDc3vNdW%D-k&zY_8;`e~9&k3>U+Vth=;-riLB1vd< z^lytS8E(?7<~c+~%lRBLbS+V)R!3|rvf0(@7|}+t&Qmd~o!bIh;$U0U;n5c!yItwx zx{OxGtd>^CfHuu)!E|#`XIm-A$9BY|!Vypq=bXn@cs{mKWPNfEE5>6d%4FraOBGvD zVk~ynVz0eY@nm7BWWVPwzuNBD!A{J2M;O_grOy6|i=lH)hx|hdESYTWI$WQIxFASwqS@XjG zRZQ_B>P@V1Q9)N}S>EUju2b4%$u7s=T@`ng*x#pCZbE~dy1Fji#LB{7bYFGp##X-f zi>|6m_d?}aMi=`=SN~%9u*))_vhEk%yIs1zmA6l_7ZBH_tNHeku80fmT2 zWs{BPFI6|%g|vU=s48$!Y+dpxKQDf~^fNBr$Txb%;8;E$5IIT6E4!RuM7_C+sDuPE zbP46AJhop&sUhZ(J3aN)7xT`o> z+mbvVKh3ZB)qZT-`yI9K3HYDu0T{`?O>-as~@q4M`w|Uom=x4sQ0>8Cy zEv1Lpn72O?lz!~d+b_{mEM@oCiimikj4BJ-6HYUhy+D+!K+s5{%mBG4&jky>VnDk7 zrj5eCufQFU0uBJpi}*(yTm{?MuDxNF4GHizb+Q@dZD1GJ^NgO`PvH6#xCkzT z25l>I;1nnUHc$@kok_+0=GP(Fr#`94l*4E&&&i^A{0!BlOLXt$}VmxCH;JY}EdN z{+>(G30hju6A`izP_|}&f#t?>gs=?D8a(!Zec%8%3@(9`e1s1g!4X_PfQ$miP`(VN zp?nIm1lT|iwCCg!`duh%Knt$RK?P_42hiUI$csynKQ~aA3#TT?W*|^m_hUl#t;A%k zz|8@tK(`?RWpCJSpAh*7b Date: Wed, 15 Nov 2023 11:56:29 -0600 Subject: [PATCH 0134/1335] AP_HAL: use array of UART drivers instead of consecutive variables Avoids UB-inducing assumption that UART drivers are consecutive in the serial() function. --- libraries/AP_HAL/HAL.cpp | 5 ++--- libraries/AP_HAL/HAL.h | 38 +++++++++++++++----------------------- 2 files changed, 17 insertions(+), 26 deletions(-) diff --git a/libraries/AP_HAL/HAL.cpp b/libraries/AP_HAL/HAL.cpp index a2d1216d2b389e..1cd4d5b36720cc 100644 --- a/libraries/AP_HAL/HAL.cpp +++ b/libraries/AP_HAL/HAL.cpp @@ -15,11 +15,10 @@ HAL::FunCallbacks::FunCallbacks(void (*setup_fun)(void), void (*loop_fun)(void)) // access serial ports using SERIALn numbering AP_HAL::UARTDriver* AP_HAL::HAL::serial(uint8_t sernum) const { - UARTDriver **uart_array = const_cast(&uartA); // this mapping captures the historical use of uartB as SERIAL3 const uint8_t mapping[] = { 0, 2, 3, 1, 4, 5, 6, 7, 8, 9 }; - static_assert(sizeof(mapping) == num_serial, "num_serial must match mapping"); - if (sernum >= num_serial) { + static_assert(sizeof(mapping) == ARRAY_SIZE(uart_array), "array size must match mapping"); + if (sernum >= ARRAY_SIZE(uart_array)) { return nullptr; } return uart_array[mapping[sernum]]; diff --git a/libraries/AP_HAL/HAL.h b/libraries/AP_HAL/HAL.h index f8827444204f46..0695504fb510af 100644 --- a/libraries/AP_HAL/HAL.h +++ b/libraries/AP_HAL/HAL.h @@ -53,16 +53,17 @@ class AP_HAL::HAL { AP_HAL::CANIface** _can_ifaces) #endif : - uartA(_uartA), - uartB(_uartB), - uartC(_uartC), - uartD(_uartD), - uartE(_uartE), - uartF(_uartF), - uartG(_uartG), - uartH(_uartH), - uartI(_uartI), - uartJ(_uartJ), + uart_array{ + _uartA, + _uartB, + _uartC, + _uartD, + _uartE, + _uartF, + _uartG, + _uartH, + _uartI, + _uartJ}, i2c_mgr(_i2c_mgr), spi(_spi), wspi(_wspi), @@ -112,19 +113,6 @@ class AP_HAL::HAL { virtual void run(int argc, char * const argv[], Callbacks* callbacks) const = 0; -private: - // the uartX ports must be contiguous in ram for the serial() method to work - AP_HAL::UARTDriver* uartA; - AP_HAL::UARTDriver* uartB UNUSED_PRIVATE_MEMBER; - AP_HAL::UARTDriver* uartC UNUSED_PRIVATE_MEMBER; - AP_HAL::UARTDriver* uartD UNUSED_PRIVATE_MEMBER; - AP_HAL::UARTDriver* uartE UNUSED_PRIVATE_MEMBER; - AP_HAL::UARTDriver* uartF UNUSED_PRIVATE_MEMBER; - AP_HAL::UARTDriver* uartG UNUSED_PRIVATE_MEMBER; - AP_HAL::UARTDriver* uartH UNUSED_PRIVATE_MEMBER; - AP_HAL::UARTDriver* uartI UNUSED_PRIVATE_MEMBER; - AP_HAL::UARTDriver* uartJ UNUSED_PRIVATE_MEMBER; - public: AP_HAL::I2CDeviceManager* i2c_mgr; AP_HAL::SPIDeviceManager* spi; @@ -151,6 +139,10 @@ class AP_HAL::HAL { static constexpr uint8_t num_serial = 10; +private: + AP_HAL::UARTDriver* uart_array[num_serial]; + +public: #if AP_SIM_ENABLED && CONFIG_HAL_BOARD != HAL_BOARD_SITL AP_HAL::SIMState *simstate; #endif From 8747ae539f405071ce08a2a3faac6adeaf2e1160 Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Mon, 20 Nov 2023 20:04:06 -0600 Subject: [PATCH 0135/1335] AP_HAL: move serial re-mapping to driver array initialization Saves a bit of flash and execution time. --- libraries/AP_HAL/HAL.cpp | 7 ++----- libraries/AP_HAL/HAL.h | 9 +++++---- 2 files changed, 7 insertions(+), 9 deletions(-) diff --git a/libraries/AP_HAL/HAL.cpp b/libraries/AP_HAL/HAL.cpp index 1cd4d5b36720cc..deef2581c3d76b 100644 --- a/libraries/AP_HAL/HAL.cpp +++ b/libraries/AP_HAL/HAL.cpp @@ -15,11 +15,8 @@ HAL::FunCallbacks::FunCallbacks(void (*setup_fun)(void), void (*loop_fun)(void)) // access serial ports using SERIALn numbering AP_HAL::UARTDriver* AP_HAL::HAL::serial(uint8_t sernum) const { - // this mapping captures the historical use of uartB as SERIAL3 - const uint8_t mapping[] = { 0, 2, 3, 1, 4, 5, 6, 7, 8, 9 }; - static_assert(sizeof(mapping) == ARRAY_SIZE(uart_array), "array size must match mapping"); - if (sernum >= ARRAY_SIZE(uart_array)) { + if (sernum >= ARRAY_SIZE(serial_array)) { return nullptr; } - return uart_array[mapping[sernum]]; + return serial_array[sernum]; } diff --git a/libraries/AP_HAL/HAL.h b/libraries/AP_HAL/HAL.h index 0695504fb510af..d56aeaa72485c1 100644 --- a/libraries/AP_HAL/HAL.h +++ b/libraries/AP_HAL/HAL.h @@ -53,11 +53,11 @@ class AP_HAL::HAL { AP_HAL::CANIface** _can_ifaces) #endif : - uart_array{ + serial_array{ _uartA, - _uartB, - _uartC, + _uartC, // ordering captures the historical use of uartB as SERIAL3 _uartD, + _uartB, _uartE, _uartF, _uartG, @@ -140,7 +140,8 @@ class AP_HAL::HAL { static constexpr uint8_t num_serial = 10; private: - AP_HAL::UARTDriver* uart_array[num_serial]; + // UART drivers in SERIALn_ order + AP_HAL::UARTDriver* serial_array[num_serial]; public: #if AP_SIM_ENABLED && CONFIG_HAL_BOARD != HAL_BOARD_SITL From 6a6c3ce7a199f03de28315ead7ac834df70bd994 Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Mon, 20 Nov 2023 20:20:07 -0600 Subject: [PATCH 0136/1335] AP_HAL: inline serial accessor function Saves a bit more flash. --- libraries/AP_HAL/HAL.cpp | 9 --------- libraries/AP_HAL/HAL.h | 9 +++++++++ 2 files changed, 9 insertions(+), 9 deletions(-) diff --git a/libraries/AP_HAL/HAL.cpp b/libraries/AP_HAL/HAL.cpp index deef2581c3d76b..6f796c3ab9c6a2 100644 --- a/libraries/AP_HAL/HAL.cpp +++ b/libraries/AP_HAL/HAL.cpp @@ -11,12 +11,3 @@ HAL::FunCallbacks::FunCallbacks(void (*setup_fun)(void), void (*loop_fun)(void)) } } - -// access serial ports using SERIALn numbering -AP_HAL::UARTDriver* AP_HAL::HAL::serial(uint8_t sernum) const -{ - if (sernum >= ARRAY_SIZE(serial_array)) { - return nullptr; - } - return serial_array[sernum]; -} diff --git a/libraries/AP_HAL/HAL.h b/libraries/AP_HAL/HAL.h index d56aeaa72485c1..063871d064d1d1 100644 --- a/libraries/AP_HAL/HAL.h +++ b/libraries/AP_HAL/HAL.h @@ -155,3 +155,12 @@ class AP_HAL::HAL { #endif }; + +// access serial ports using SERIALn numbering +inline AP_HAL::UARTDriver* AP_HAL::HAL::serial(uint8_t sernum) const +{ + if (sernum >= ARRAY_SIZE(serial_array)) { + return nullptr; + } + return serial_array[sernum]; +} From ebbcf42236ed57758b03c51e764c9bb291475f9f Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Sun, 10 Dec 2023 11:03:27 -0600 Subject: [PATCH 0137/1335] AP_HAL: constructor now accepts UARTs in SERIALn order --- libraries/AP_HAL/HAL.h | 40 ++++++++++++++++++++-------------------- 1 file changed, 20 insertions(+), 20 deletions(-) diff --git a/libraries/AP_HAL/HAL.h b/libraries/AP_HAL/HAL.h index 063871d064d1d1..fdaee2c43357b8 100644 --- a/libraries/AP_HAL/HAL.h +++ b/libraries/AP_HAL/HAL.h @@ -20,16 +20,16 @@ class AP_Param; class AP_HAL::HAL { public: - HAL(AP_HAL::UARTDriver* _uartA, // console - AP_HAL::UARTDriver* _uartB, // 1st GPS - AP_HAL::UARTDriver* _uartC, // telem1 - AP_HAL::UARTDriver* _uartD, // telem2 - AP_HAL::UARTDriver* _uartE, // 2nd GPS - AP_HAL::UARTDriver* _uartF, // extra1 - AP_HAL::UARTDriver* _uartG, // extra2 - AP_HAL::UARTDriver* _uartH, // extra3 - AP_HAL::UARTDriver* _uartI, // extra4 - AP_HAL::UARTDriver* _uartJ, // extra5 + HAL(AP_HAL::UARTDriver* _serial0, // console + AP_HAL::UARTDriver* _serial1, // telem1 + AP_HAL::UARTDriver* _serial2, // telem2 + AP_HAL::UARTDriver* _serial3, // 1st GPS + AP_HAL::UARTDriver* _serial4, // 2nd GPS + AP_HAL::UARTDriver* _serial5, // extra1 + AP_HAL::UARTDriver* _serial6, // extra2 + AP_HAL::UARTDriver* _serial7, // extra3 + AP_HAL::UARTDriver* _serial8, // extra4 + AP_HAL::UARTDriver* _serial9, // extra5 AP_HAL::I2CDeviceManager* _i2c_mgr, AP_HAL::SPIDeviceManager* _spi, AP_HAL::WSPIDeviceManager* _wspi, @@ -54,16 +54,16 @@ class AP_HAL::HAL { #endif : serial_array{ - _uartA, - _uartC, // ordering captures the historical use of uartB as SERIAL3 - _uartD, - _uartB, - _uartE, - _uartF, - _uartG, - _uartH, - _uartI, - _uartJ}, + _serial0, + _serial1, + _serial2, + _serial3, + _serial4, + _serial5, + _serial6, + _serial7, + _serial8, + _serial9}, i2c_mgr(_i2c_mgr), spi(_spi), wspi(_wspi), From bcfad0d71259e6ab3e1bacddf6ce7cb173138163 Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Mon, 11 Dec 2023 11:02:15 -0600 Subject: [PATCH 0138/1335] AP_HAL: remove references to legacy UART order --- libraries/AP_HAL/examples/UART_chargen/UART_chargen.cpp | 2 +- libraries/AP_HAL/examples/UART_test/UART_test.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL/examples/UART_chargen/UART_chargen.cpp b/libraries/AP_HAL/examples/UART_chargen/UART_chargen.cpp index 328da1698fac68..7a94258ab14c28 100644 --- a/libraries/AP_HAL/examples/UART_chargen/UART_chargen.cpp +++ b/libraries/AP_HAL/examples/UART_chargen/UART_chargen.cpp @@ -38,7 +38,7 @@ uint16_t buflen = 0; void setup(void) { - hal.scheduler->delay(1000); //Ensure that the uartA can be initialized + hal.scheduler->delay(1000); //Ensure that hal.serial(n) can be initialized #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX uart = hal.serial(0); // console diff --git a/libraries/AP_HAL/examples/UART_test/UART_test.cpp b/libraries/AP_HAL/examples/UART_test/UART_test.cpp index 1af94cb3bdd914..1dd5d5ed011d8f 100644 --- a/libraries/AP_HAL/examples/UART_test/UART_test.cpp +++ b/libraries/AP_HAL/examples/UART_test/UART_test.cpp @@ -30,7 +30,7 @@ void setup(void) start all UARTs at 57600 with default buffer sizes */ - hal.scheduler->delay(1000); //Ensure that the uartA can be initialized + hal.scheduler->delay(1000); //Ensure that hal.serial(n) can be initialized setup_uart(hal.serial(0), "SERIAL0"); // console setup_uart(hal.serial(1), "SERIAL1"); // telemetry 1 From 507ab623b23fda0043f0eba8bc5823ca9493062b Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Sun, 10 Dec 2023 11:06:16 -0600 Subject: [PATCH 0139/1335] AP_HAL_ChibiOS: pass UARTs to AP_HAL in SERIALn order --- libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp b/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp index 46b352e5649f50..a481977b02a57c 100644 --- a/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp +++ b/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp @@ -137,9 +137,9 @@ AP_IOMCU iomcu(uart_io); HAL_ChibiOS::HAL_ChibiOS() : AP_HAL::HAL( &uartADriver, - &uartBDriver, - &uartCDriver, + &uartCDriver, // ordering captures the historical use of uartB as SERIAL3 &uartDDriver, + &uartBDriver, &uartEDriver, &uartFDriver, &uartGDriver, From 90c14141a08e9dc74540a025fac7dcb3d742f154 Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Sun, 10 Dec 2023 11:08:50 -0600 Subject: [PATCH 0140/1335] AP_HAL_Empty: pass UARTs to AP_HAL in SERIALn order --- libraries/AP_HAL_Empty/HAL_Empty_Class.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_Empty/HAL_Empty_Class.cpp b/libraries/AP_HAL_Empty/HAL_Empty_Class.cpp index 2045e9c2893ee5..a05acc59d08a12 100644 --- a/libraries/AP_HAL_Empty/HAL_Empty_Class.cpp +++ b/libraries/AP_HAL_Empty/HAL_Empty_Class.cpp @@ -26,9 +26,9 @@ static Flash flashDriver; HAL_Empty::HAL_Empty() : AP_HAL::HAL( &uartADriver, - &uartBDriver, - &uartCDriver, + &uartCDriver, // ordering captures the historical use of uartB as SERIAL3 nullptr, /* no uartD */ + &uartBDriver, nullptr, /* no uartE */ nullptr, /* no uartF */ nullptr, /* no uartG */ From 574c8016c3da41314580cde7a3ac6647c382bbad Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Sun, 10 Dec 2023 11:10:38 -0600 Subject: [PATCH 0141/1335] AP_HAL_ESP32: pass UARTs to AP_HAL in SERIALn order --- libraries/AP_HAL_ESP32/HAL_ESP32_Class.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ESP32/HAL_ESP32_Class.cpp b/libraries/AP_HAL_ESP32/HAL_ESP32_Class.cpp index 9a175a362f7a1d..096c8ab47ad803 100644 --- a/libraries/AP_HAL_ESP32/HAL_ESP32_Class.cpp +++ b/libraries/AP_HAL_ESP32/HAL_ESP32_Class.cpp @@ -73,9 +73,9 @@ extern const AP_HAL::HAL& hal; HAL_ESP32::HAL_ESP32() : AP_HAL::HAL( &cons, //Console/mavlink - &uartBDriver, //GPS 1 - &uartCDriver, //Telem 1 + &uartCDriver, //Telem 1, ordering captures the historical use of uartB as SERIAL3 &uartDDriver, //Telem 2 + &uartBDriver, //GPS 1 &uartEDriver, //GPS 2 &uartFDriver, //Extra 1 &uartGDriver, //Extra 2 From 764b469e475f44e1dfd8bc262990d6322d10e684 Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Sun, 10 Dec 2023 11:12:06 -0600 Subject: [PATCH 0142/1335] AP_HAL_Linux: pass UARTs to AP_HAL in SERIALn order --- libraries/AP_HAL_Linux/HAL_Linux_Class.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp b/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp index 6618e83bc3240b..e264ccbdb139a5 100644 --- a/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp +++ b/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp @@ -248,9 +248,9 @@ static CANIface* canDrivers[HAL_NUM_CAN_IFACES]; HAL_Linux::HAL_Linux() : AP_HAL::HAL( &uartADriver, - &uartBDriver, - &uartCDriver, + &uartCDriver, // ordering captures the historical use of uartB as SERIAL3 &uartDDriver, + &uartBDriver, &uartEDriver, &uartFDriver, &uartGDriver, From c56599e210e6761d2f7ef46b4f54aa1ef4278e2b Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Sun, 10 Dec 2023 11:15:39 -0600 Subject: [PATCH 0143/1335] AP_HAL_SITL: pass UARTs to AP_HAL in SERIALn order --- libraries/AP_HAL_SITL/HAL_SITL_Class.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp b/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp index bf8bc073510971..57d719875c66e6 100644 --- a/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp +++ b/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp @@ -82,9 +82,9 @@ static Empty::WSPIDeviceManager wspi_mgr_instance; HAL_SITL::HAL_SITL() : AP_HAL::HAL( &sitlUart0Driver, /* uartA */ - &sitlUart1Driver, /* uartB */ - &sitlUart2Driver, /* uartC */ + &sitlUart2Driver, /* uartC */ // ordering captures the historical use of uartB as SERIAL3 &sitlUart3Driver, /* uartD */ + &sitlUart1Driver, /* uartB */ &sitlUart4Driver, /* uartE */ &sitlUart5Driver, /* uartF */ &sitlUart6Driver, /* uartG */ From dc4438d0e306f413319209cad648d4c7e2204fa6 Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Sun, 10 Dec 2023 22:55:15 -0600 Subject: [PATCH 0144/1335] AP_HAL_ChibiOS: eliminate legacy UART ordering/references SERIAL_ORDER has been around for a few years now and UART_ORDER is rejected by the hwdef script, so support for UART_ORDER and associated processing in the hwdef script is removed, along with the order conversion script. --- .../AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp | 62 +++++----- libraries/AP_HAL_ChibiOS/UARTDriver.cpp | 14 +-- libraries/AP_HAL_ChibiOS/UARTDriver.h | 6 +- .../hwdef/scripts/chibios_hwdef.py | 107 +++++++----------- .../hwdef/scripts/convert_uart_order.py | 37 ------ 5 files changed, 81 insertions(+), 145 deletions(-) delete mode 100755 libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_uart_order.py diff --git a/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp b/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp index a481977b02a57c..65ebdfafdaace5 100644 --- a/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp +++ b/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp @@ -45,27 +45,27 @@ #endif #ifndef HAL_NO_UARTDRIVER -static HAL_UARTA_DRIVER; -static HAL_UARTB_DRIVER; -static HAL_UARTC_DRIVER; -static HAL_UARTD_DRIVER; -static HAL_UARTE_DRIVER; -static HAL_UARTF_DRIVER; -static HAL_UARTG_DRIVER; -static HAL_UARTH_DRIVER; -static HAL_UARTI_DRIVER; -static HAL_UARTJ_DRIVER; +static HAL_SERIAL0_DRIVER; +static HAL_SERIAL1_DRIVER; +static HAL_SERIAL2_DRIVER; +static HAL_SERIAL3_DRIVER; +static HAL_SERIAL4_DRIVER; +static HAL_SERIAL5_DRIVER; +static HAL_SERIAL6_DRIVER; +static HAL_SERIAL7_DRIVER; +static HAL_SERIAL8_DRIVER; +static HAL_SERIAL9_DRIVER; #else -static Empty::UARTDriver uartADriver; -static Empty::UARTDriver uartBDriver; -static Empty::UARTDriver uartCDriver; -static Empty::UARTDriver uartDDriver; -static Empty::UARTDriver uartEDriver; -static Empty::UARTDriver uartFDriver; -static Empty::UARTDriver uartGDriver; -static Empty::UARTDriver uartHDriver; -static Empty::UARTDriver uartIDriver; -static Empty::UARTDriver uartJDriver; +static Empty::UARTDriver serial0Driver; +static Empty::UARTDriver serial1Driver; +static Empty::UARTDriver serial2Driver; +static Empty::UARTDriver serial3Driver; +static Empty::UARTDriver serial4Driver; +static Empty::UARTDriver serial5Driver; +static Empty::UARTDriver serial6Driver; +static Empty::UARTDriver serial7Driver; +static Empty::UARTDriver serial8Driver; +static Empty::UARTDriver serial9Driver; #endif #if HAL_USE_I2C == TRUE && defined(HAL_I2C_DEVICE_LIST) @@ -136,16 +136,16 @@ AP_IOMCU iomcu(uart_io); HAL_ChibiOS::HAL_ChibiOS() : AP_HAL::HAL( - &uartADriver, - &uartCDriver, // ordering captures the historical use of uartB as SERIAL3 - &uartDDriver, - &uartBDriver, - &uartEDriver, - &uartFDriver, - &uartGDriver, - &uartHDriver, - &uartIDriver, - &uartJDriver, + &serial0Driver, + &serial1Driver, + &serial2Driver, + &serial3Driver, + &serial4Driver, + &serial5Driver, + &serial6Driver, + &serial7Driver, + &serial8Driver, + &serial9Driver, &i2cDeviceManager, &spiDeviceManager, #if HAL_USE_WSPI == TRUE && defined(HAL_WSPI_DEVICE_LIST) @@ -155,7 +155,7 @@ HAL_ChibiOS::HAL_ChibiOS() : #endif &analogIn, &storageDriver, - &uartADriver, + &serial0Driver, &gpioDriver, &rcinDriver, &rcoutDriver, diff --git a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp index 911688f643e151..6593dffe7ee3c5 100644 --- a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp +++ b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp @@ -52,13 +52,13 @@ using namespace ChibiOS; extern ChibiOS::UARTDriver uart_io; #endif -const UARTDriver::SerialDef UARTDriver::_serial_tab[] = { HAL_UART_DEVICE_LIST }; +const UARTDriver::SerialDef UARTDriver::_serial_tab[] = { HAL_SERIAL_DEVICE_LIST }; // handle for UART handling thread thread_t* volatile UARTDriver::uart_rx_thread_ctx; // table to find UARTDrivers from serial number, used for event handling -UARTDriver *UARTDriver::uart_drivers[UART_MAX_DRIVERS]; +UARTDriver *UARTDriver::serial_drivers[UART_MAX_DRIVERS]; // event used to wake up waiting thread. This event number is for // caller threads @@ -104,8 +104,8 @@ serial_num(_serial_num), sdef(_serial_tab[_serial_num]), _baudrate(57600) { - osalDbgAssert(serial_num < UART_MAX_DRIVERS, "too many UART drivers"); - uart_drivers[serial_num] = this; + osalDbgAssert(serial_num < UART_MAX_DRIVERS, "too many SERIALn drivers"); + serial_drivers[serial_num] = this; } /* @@ -166,11 +166,11 @@ void UARTDriver::uart_rx_thread(void* arg) hal.scheduler->delay_microseconds(1000); for (uint8_t i=0; i_rx_initialised) { - uart_drivers[i]->_rx_timer_tick(); + if (serial_drivers[i]->_rx_initialised) { + serial_drivers[i]->_rx_timer_tick(); } } } diff --git a/libraries/AP_HAL_ChibiOS/UARTDriver.h b/libraries/AP_HAL_ChibiOS/UARTDriver.h index 16cac8f8d0d2e1..1a045fa9e7e818 100644 --- a/libraries/AP_HAL_ChibiOS/UARTDriver.h +++ b/libraries/AP_HAL_ChibiOS/UARTDriver.h @@ -25,7 +25,7 @@ #define RX_BOUNCE_BUFSIZE 64U #define TX_BOUNCE_BUFSIZE 64U -// enough for uartA to uartJ, plus IOMCU +// enough for serial0 to serial9, plus IOMCU #define UART_MAX_DRIVERS 11 class ChibiOS::UARTDriver : public AP_HAL::UARTDriver { @@ -148,13 +148,13 @@ class ChibiOS::UARTDriver : public AP_HAL::UARTDriver { static thread_t* volatile uart_rx_thread_ctx; // table to find UARTDrivers from serial number, used for event handling - static UARTDriver *uart_drivers[UART_MAX_DRIVERS]; + static UARTDriver *serial_drivers[UART_MAX_DRIVERS]; // thread used for writing and reading thread_t* volatile uart_thread_ctx; char uart_thread_name[6]; - // index into uart_drivers table + // index into serial_drivers table uint8_t serial_num; uint32_t _baudrate; diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index 4f0d98d5b11eff..dab87f0af3873b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -111,9 +111,6 @@ def __init__(self, bootloader=False, signed_fw=False, outdir=None, hwdef=[], def self.dma_exclude_pattern = [] - # map from uart names to SERIALn numbers - self.uart_serial_num = {} - self.mcu_type = None self.dual_USB_enabled = False @@ -1817,75 +1814,51 @@ def get_extra_bylabel(self, label, name, default=None): return default return p.extra_value(name, type=str, default=default) - def get_UART_ORDER(self): - '''get UART_ORDER from SERIAL_ORDER option''' - if self.get_config('UART_ORDER', required=False, aslist=True) is not None: - self.error('Please convert UART_ORDER to SERIAL_ORDER') - serial_order = self.get_config('SERIAL_ORDER', required=False, aslist=True) - if serial_order is None: - return None - if args.bootloader: - # in bootloader SERIAL_ORDER is treated the same as UART_ORDER - return serial_order - map = [0, 3, 1, 2, 4, 5, 6, 7, 8, 9, 10, 11, 12] - while len(serial_order) < 4: - serial_order += ['EMPTY'] - uart_order = [] - for i in range(len(serial_order)): - uart_order.append(serial_order[map[i]]) - self.uart_serial_num[serial_order[i]] = i - return uart_order - def write_UART_config(self, f): '''write UART config defines''' - uart_list = self.get_UART_ORDER() - if uart_list is None: + serial_list = self.get_config('SERIAL_ORDER', required=False, aslist=True) + if serial_list is None: return + while len(serial_list) < 3: # enough ports for CrashCatcher UART discovery + serial_list += ['EMPTY'] f.write('\n// UART configuration\n') # write out which serial ports we actually have - idx = 0 nports = 0 - serial_order = self.get_config('SERIAL_ORDER', required=False, aslist=True) - for serial in serial_order: + for idx, serial in enumerate(serial_list): if serial == 'EMPTY': f.write('#define HAL_HAVE_SERIAL%u 0\n' % idx) else: f.write('#define HAL_HAVE_SERIAL%u 1\n' % idx) nports = nports + 1 - idx += 1 f.write('#define HAL_NUM_SERIAL_PORTS %u\n' % nports) # write out driver declarations for HAL_ChibOS_Class.cpp - devnames = "ABCDEFGHIJ" sdev = 0 - idx = 0 - for dev in uart_list: + for idx, dev in enumerate(serial_list): if dev == 'EMPTY': - f.write('#define HAL_UART%s_DRIVER Empty::UARTDriver uart%sDriver\n' % - (devnames[idx], devnames[idx])) + f.write('#define HAL_SERIAL%s_DRIVER Empty::UARTDriver serial%sDriver\n' % + (idx, idx)) sdev += 1 else: f.write( - '#define HAL_UART%s_DRIVER ChibiOS::UARTDriver uart%sDriver(%u)\n' - % (devnames[idx], devnames[idx], sdev)) + '#define HAL_SERIAL%s_DRIVER ChibiOS::UARTDriver serial%sDriver(%u)\n' + % (idx, idx, sdev)) sdev += 1 - idx += 1 - for idx in range(len(uart_list), len(devnames)): - f.write('#define HAL_UART%s_DRIVER Empty::UARTDriver uart%sDriver\n' % - (devnames[idx], devnames[idx])) + for idx in range(len(serial_list), 10): + f.write('#define HAL_SERIAL%s_DRIVER Empty::UARTDriver serial%sDriver\n' % + (idx, idx)) if 'IOMCU_UART' in self.config: if 'io_firmware.bin' not in self.romfs: self.error("Need io_firmware.bin in ROMFS for IOMCU") f.write('#define HAL_WITH_IO_MCU 1\n') - idx = len(uart_list) - f.write('#define HAL_UART_IOMCU_IDX %u\n' % idx) + f.write('#define HAL_UART_IOMCU_IDX %u\n' % len(serial_list)) f.write( '#define HAL_UART_IO_DRIVER ChibiOS::UARTDriver uart_io(HAL_UART_IOMCU_IDX)\n' ) - uart_list.append(self.config['IOMCU_UART'][0]) + serial_list.append(self.config['IOMCU_UART'][0]) f.write('#define HAL_HAVE_SERVO_VOLTAGE 1\n') # make the assumption that IO gurantees servo monitoring # all IOMCU capable boards have SBUS out f.write('#define AP_FEATURE_SBUS_OUT 1\n') @@ -1900,17 +1873,17 @@ def write_UART_config(self, f): crash_uart = None # write config for CrashCatcher UART - if not uart_list[0].startswith('OTG') and not uart_list[0].startswith('EMPTY'): - crash_uart = uart_list[0] - elif not uart_list[2].startswith('OTG') and not uart_list[2].startswith('EMPTY'): - crash_uart = uart_list[2] + if not serial_list[0].startswith('OTG') and not serial_list[0].startswith('EMPTY'): + crash_uart = serial_list[0] + elif not serial_list[2].startswith('OTG') and not serial_list[2].startswith('EMPTY'): + crash_uart = serial_list[2] if crash_uart is not None and self.get_config('FLASH_SIZE_KB', type=int) >= 2048: f.write('#define HAL_CRASH_SERIAL_PORT %s\n' % crash_uart) f.write('#define IRQ_DISABLE_HAL_CRASH_SERIAL_PORT() nvicDisableVector(STM32_%s_NUMBER)\n' % crash_uart) f.write('#define RCC_RESET_HAL_CRASH_SERIAL_PORT() rccReset%s(); rccEnable%s(true)\n' % (crash_uart, crash_uart)) f.write('#define HAL_CRASH_SERIAL_PORT_CLOCK STM32_%sCLK\n' % crash_uart) - for dev in uart_list: + for num, dev in enumerate(serial_list): if dev.startswith('UART'): n = int(dev[4:]) elif dev.startswith('USART'): @@ -1921,7 +1894,7 @@ def write_UART_config(self, f): devlist.append('{}') continue else: - self.error("Invalid element %s in UART_ORDER" % dev) + self.error("Invalid element %s in SERIAL_ORDER" % dev) devlist.append('HAL_%s_CONFIG' % dev) tx_line = self.make_line(dev + '_TX') rx_line = self.make_line(dev + '_RX') @@ -1929,12 +1902,12 @@ def write_UART_config(self, f): cts_line = self.make_line(dev + '_CTS') if rts_line != "0": have_rts_cts = True - f.write('#define HAL_HAVE_RTSCTS_SERIAL%u\n' % self.uart_serial_num[dev]) + f.write('#define HAL_HAVE_RTSCTS_SERIAL%u\n' % num) if dev.startswith('OTG2'): f.write( '#define HAL_%s_CONFIG {(BaseSequentialStream*) &SDU2, 2, true, false, 0, 0, false, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2}\n' % dev) # noqa - OTG2_index = uart_list.index(dev) + OTG2_index = serial_list.index(dev) self.dual_USB_enabled = True elif dev.startswith('OTG'): f.write( @@ -1971,44 +1944,44 @@ def write_UART_config(self, f): #endif ''' % (OTG2_index, OTG2_index)) - f.write('#define HAL_UART_DEVICE_LIST %s\n\n' % ','.join(devlist)) + f.write('#define HAL_SERIAL_DEVICE_LIST %s\n\n' % ','.join(devlist)) if not need_uart_driver and not args.bootloader: f.write(''' #ifndef HAL_USE_SERIAL #define HAL_USE_SERIAL HAL_USE_SERIAL_USB #endif ''') - num_uarts = len(devlist) + num_ports = len(devlist) if 'IOMCU_UART' in self.config: - num_uarts -= 1 - if num_uarts > 10: - self.error("Exceeded max num UARTs of 10 (%u)" % num_uarts) - f.write('#define HAL_UART_NUM_SERIAL_PORTS %u\n' % num_uarts) + num_ports -= 1 + if num_ports > 10: + self.error("Exceeded max num SERIALs of 10 (%u)" % num_ports) + f.write('#define HAL_UART_NUM_SERIAL_PORTS %u\n' % num_ports) def write_UART_config_bootloader(self, f): '''write UART config defines''' - uart_list = self.get_UART_ORDER() - if uart_list is None: + serial_list = self.get_config('SERIAL_ORDER', required=False, aslist=True) + if serial_list is None: return f.write('\n// UART configuration\n') devlist = [] - have_uart = False + have_serial = False OTG2_index = None - for u in uart_list: - if u.startswith('OTG2'): + for s in serial_list: + if s.startswith('OTG2'): devlist.append('(BaseChannel *)&SDU2') - OTG2_index = uart_list.index(u) - elif u.startswith('OTG'): + OTG2_index = serial_list.index(s) + elif s.startswith('OTG'): devlist.append('(BaseChannel *)&SDU1') else: - unum = int(u[-1]) - devlist.append('(BaseChannel *)&SD%u' % unum) - have_uart = True + snum = int(s[-1]) + devlist.append('(BaseChannel *)&SD%u' % snum) + have_serial = True if len(devlist) > 0: f.write('#define BOOTLOADER_DEV_LIST %s\n' % ','.join(devlist)) if OTG2_index is not None: f.write('#define HAL_OTG2_UART_INDEX %d\n' % OTG2_index) - if not have_uart: + if not have_serial: f.write(''' #ifndef HAL_USE_SERIAL #define HAL_USE_SERIAL FALSE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_uart_order.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_uart_order.py deleted file mode 100755 index d502d91f6113be..00000000000000 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/convert_uart_order.py +++ /dev/null @@ -1,37 +0,0 @@ -#!/usr/bin/env python -''' -convert UART_ORDER in a hwdef.dat into a SERIAL_ORDER -''' - -import sys, shlex - -def convert_file(fname): - lines = open(fname, 'r').readlines() - for i in range(len(lines)): - if lines[i].startswith('SERIAL_ORDER'): - print("Already has SERIAL_ORDER: %s" % fname) - return - - for i in range(len(lines)): - line = lines[i] - if not line.startswith('UART_ORDER'): - continue - a = shlex.split(line, posix=False) - if a[0] != 'UART_ORDER': - continue - uart_order = a[1:] - if not fname.endswith('-bl.dat'): - while len(uart_order) < 4: - uart_order += ['EMPTY'] - a += ['EMPTY'] - map = [ 0, 2, 3, 1, 4, 5, 6, 7, 8, 9, 10, 11, 12 ] - for j in range(len(uart_order)): - a[j+1] = uart_order[map[j]] - a[0] = 'SERIAL_ORDER' - print("%s new order " % fname, a) - lines[i] = ' '.join(a) + '\n' - open(fname, 'w').write(''.join(lines)) - -files=sys.argv[1:] -for fname in files: - convert_file(fname) From 2aa4ee8ba7c66f5e09ed0e1558a90e7c9eb28f96 Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Mon, 11 Dec 2023 11:07:23 -0600 Subject: [PATCH 0145/1335] AP_HAL_ChibiOS: remove references to legacy UART order from hwdefs --- .../hwdef/CubeBlack-periph/hwdef-bl.dat | 2 +- .../hwdef/CubeOrange-periph/hwdef-bl.dat | 2 +- .../hwdef/CubeOrange/hwdef-bl.inc | 2 +- .../AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.inc | 2 +- .../AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat | 19 ++++++++----------- .../hwdef/DrotekP3Pro/hwdef.dat | 15 +++++++-------- .../hwdef/PixPilot-C3/hwdef-bl.dat | 2 +- .../hwdef/PixPilot-C3/hwdef.dat | 15 +++++++-------- .../hwdef/PixPilot-V3/hwdef.dat | 15 +++++++-------- .../hwdef/PixPilot-V6/hwdef-bl.dat | 2 +- .../hwdef/PixSurveyA1-IND/hwdef.dat | 15 +++++++-------- .../hwdef/fmuv3-bdshot/hwdef.dat | 2 +- .../AP_HAL_ChibiOS/hwdef/fmuv3/hwdef-bl.dat | 2 +- .../AP_HAL_ChibiOS/hwdef/fmuv3/hwdef.dat | 2 +- .../AP_HAL_ChibiOS/hwdef/mRoX21-777/hwdef.dat | 19 ++++++++----------- .../hwdef/thepeach-k1/hwdef.dat | 2 +- .../hwdef/thepeach-r1/hwdef.dat | 2 +- 17 files changed, 55 insertions(+), 65 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef-bl.dat index effd49fee7a162..ba2212fa9cb623 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeBlack-periph/hwdef-bl.dat @@ -27,7 +27,7 @@ define HAL_LED_ON 0 # order of UARTs (and USB) SERIAL_ORDER OTG1 UART7 -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters). +# UART7 maps to SERIAL5. PE7 UART7_RX UART7 PE8 UART7_TX UART7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef-bl.dat index 6d10b336b8f812..7a86058449d0db 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-periph/hwdef-bl.dat @@ -27,7 +27,7 @@ define HAL_LED_ON 0 # order of UARTs (and USB) SERIAL_ORDER OTG1 UART7 -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters). +# UART7 maps to SERIAL5. PE7 UART7_RX UART7 PE8 UART7_TX UART7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef-bl.inc b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef-bl.inc index 5da67a0bdfd8b7..f5219200982ed2 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef-bl.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef-bl.inc @@ -34,7 +34,7 @@ PD6 USART2_RX USART2 PD8 USART3_TX USART3 PD9 USART3_RX USART3 -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters). +# UART7 maps to SERIAL5. PE7 UART7_RX UART7 PE8 UART7_TX UART7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.inc b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.inc index cd7ef40d20a07e..cb5769d8d514b3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.inc +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/hwdef.inc @@ -195,7 +195,7 @@ PE6 SPI4_MOSI SPI4 # means sensors off, then it is pulled HIGH in peripheral_power_enable() PE3 VDD_3V3_SENSORS_EN OUTPUT LOW -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters). +# UART7 maps to SERIAL5. PE7 UART7_RX UART7 PE8 UART7_TX UART7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat index c3773bc7b89b80..afc44a107c6050 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeYellow/hwdef.dat @@ -86,20 +86,17 @@ USB_STRING_MANUFACTURER "Hex/ProfiCNC" # order of I2C buses I2C_ORDER I2C2 I2C1 -# now the UART order. These map to the hal.uartA to hal.uartF -# objects. If you use a shorter list then HAL_Empty::UARTDriver -# objects are substituted for later UARTs, or you can leave a gap by -# listing one or more of the uarts as EMPTY - -# the normal usage of this ordering is: +# now the SERIALn order. These map to the hal.serial(n) objects. If you use a +# shorter list then HAL_Empty::UARTDriver objects are substituted for later +# UARTs, or you can leave a gap by listing one or more of the uarts as EMPTY # 1) SERIAL0: console (primary mavlink, usually USB) -# 2) SERIAL3: primary GPS -# 3) SERIAL1: telem1 -# 4) SERIAL2: telem2 +# 2) SERIAL1: telem1 +# 3) SERIAL2: telem2 +# 4) SERIAL3: primary GPS # 5) SERIAL4: GPS2 # 6) SERIAL5: extra UART (usually RTOS debug console) -# order of UARTs (and USB) +# order of SERIALn (incl. USB) SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 UART7 OTG2 # if the board has an IOMCU connected via a UART then this defines the @@ -321,7 +318,7 @@ PE6 SPI4_MOSI SPI4 # timing affecting sensor stability. We pull it high by default PE3 VDD_3V3_SENSORS_EN OUTPUT HIGH -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters) +# UART7 maps to SERIAL5. PE7 UART7_RX UART7 PE8 UART7_TX UART7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/DrotekP3Pro/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/DrotekP3Pro/hwdef.dat index 93d2626c16acff..7b20d22a687957 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/DrotekP3Pro/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/DrotekP3Pro/hwdef.dat @@ -28,18 +28,17 @@ env OPTIMIZE -O2 # order of I2C buses I2C_ORDER I2C1 I2C2 -# now the UART order. These map to the hal.uartA to hal.uartF -# objects. If you use a shorter list then HAL_Empty::UARTDriver -# objects are substituted for later UARTs, or you can leave a gap by -# listing one or more of the uarts as EMPTY +# now the SERIALn order. These map to the hal.serial(n) objects. If you use a +# shorter list then HAL_Empty::UARTDriver objects are substituted for later +# UARTs, or you can leave a gap by listing one or more of the uarts as EMPTY # 1) SERIAL0: console (primary mavlink, usually USB) -# 2) SERIAL3: primary GPS -# 3) SERIAL1: telem1 -# 4) SERIAL2: telem2 +# 2) SERIAL1: telem1 +# 3) SERIAL2: telem2 +# 4) SERIAL3: primary GPS # 5) SERIAL4: GPS2 # 6) SERIAL5: extra UART (usually RTOS debug console) -# order of UARTs (and USB) +# order of SERIALn (incl. USB) SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 USART1 UART7 # UART for IOMCU diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/hwdef-bl.dat index f0486e5b9ca53b..c39441ecb0e56d 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/hwdef-bl.dat @@ -50,7 +50,7 @@ PD9 USART3_RX USART3 PD11 USART3_CTS USART3 PD12 USART3_RTS USART3 -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters) +# UART7 maps to SERIAL5. PE7 UART7_RX UART7 PE8 UART7_TX UART7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/hwdef.dat index 8bec6df8eea62c..720f6b747c570a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-C3/hwdef.dat @@ -22,18 +22,17 @@ env OPTIMIZE -O2 # order of I2C buses I2C_ORDER I2C1 I2C2 -# now the UART order. These map to the hal.uartA to hal.uartF -# objects. If you use a shorter list then HAL_Empty::UARTDriver -# objects are substituted for later UARTs, or you can leave a gap by -# listing one or more of the uarts as EMPTY +# now the SERIALn order. These map to the hal.serial(n) objects. If you use a +# shorter list then HAL_Empty::UARTDriver objects are substituted for later +# UARTs, or you can leave a gap by listing one or more of the uarts as EMPTY # 1) SERIAL0: console (primary mavlink, usually USB) -# 2) SERIAL3: primary GPS -# 3) SERIAL1: telem1 -# 4) SERIAL2: telem2 +# 2) SERIAL1: telem1 +# 3) SERIAL2: telem2 +# 4) SERIAL3: primary GPS # 5) SERIAL4: GPS2 # 6) SERIAL5: extra UART (usually RTOS debug console) -# order of UARTs (and USB) +# order of SERIALn (incl. USB) SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 UART7 # UART for IOMCU diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V3/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V3/hwdef.dat index 4c95268d937f28..da84f273b9614c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V3/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V3/hwdef.dat @@ -24,18 +24,17 @@ USB_STRING_MANUFACTURER "ArduPilot" # order of I2C buses I2C_ORDER I2C3 I2C2 I2C1 -# now the UART order. These map to the hal.uartA to hal.uartF -# objects. If you use a shorter list then HAL_Empty::UARTDriver -# objects are substituted for later UARTs, or you can leave a gap by -# listing one or more of the uarts as EMPTY +# now the SERIALn order. These map to the hal.serial(n) objects. If you use a +# shorter list then HAL_Empty::UARTDriver objects are substituted for later +# UARTs, or you can leave a gap by listing one or more of the uarts as EMPTY # 1) SERIAL0: console (primary mavlink, usually USB) -# 2) SERIAL3: primary GPS -# 3) SERIAL1: telem1 -# 4) SERIAL2: telem2 +# 2) SERIAL1: telem1 +# 3) SERIAL2: telem2 +# 4) SERIAL3: primary GPS # 5) SERIAL4: GPS2 # 6) SERIAL5: extra UART (usually RTOS debug console) -# order of UARTs (and USB) +# order of SERIALn (incl. USB) SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 UART7 # UART for IOMCU diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6/hwdef-bl.dat index a833003a0c44d0..7bd549b00aa7ee 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixPilot-V6/hwdef-bl.dat @@ -35,7 +35,7 @@ PD6 USART2_RX USART2 PD8 USART3_TX USART3 PD9 USART3_RX USART3 -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters). +# UART7 maps to SERIAL5. PE7 UART7_RX UART7 PE8 UART7_TX UART7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/PixSurveyA1-IND/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/PixSurveyA1-IND/hwdef.dat index 186fec11cecc93..00145bb34e56e7 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/PixSurveyA1-IND/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/PixSurveyA1-IND/hwdef.dat @@ -23,18 +23,17 @@ env OPTIMIZE -O2 # order of I2C buses I2C_ORDER I2C3 I2C2 I2C1 -# now the UART order. These map to the hal.uartA to hal.uartF -# objects. If you use a shorter list then HAL_Empty::UARTDriver -# objects are substituted for later UARTs, or you can leave a gap by -# listing one or more of the uarts as EMPTY +# now the SERIALn order. These map to the hal.serial(n) objects. If you use a +# shorter list then HAL_Empty::UARTDriver objects are substituted for later +# UARTs, or you can leave a gap by listing one or more of the uarts as EMPTY # 1) SERIAL0: console (primary mavlink, usually USB) -# 2) SERIAL3: primary GPS -# 3) SERIAL1: telem1 -# 4) SERIAL2: telem2 +# 2) SERIAL1: telem1 +# 3) SERIAL2: telem2 +# 4) SERIAL3: primary GPS # 5) SERIAL4: GPS2 # 6) SERIAL5: extra UART (usually RTOS debug console) -# order of UARTs (and USB) +# order of SERIALn (incl. USB) SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 UART7 # UART for IOMCU diff --git a/libraries/AP_HAL_ChibiOS/hwdef/fmuv3-bdshot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/fmuv3-bdshot/hwdef.dat index 5af9e12d7a18b2..781cc6e59ff853 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/fmuv3-bdshot/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/fmuv3-bdshot/hwdef.dat @@ -356,7 +356,7 @@ PE1 UART8_TX UART8 # timing affecting sensor stability. We pull it high by default. PE3 VDD_3V3_SENSORS_EN OUTPUT HIGH -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters). +# UART7 maps to SERIAL5. PE7 UART7_RX UART7 PE8 UART7_TX UART7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef-bl.dat index 002fbad6143b3c..bd90c7351d11cf 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef-bl.dat @@ -50,7 +50,7 @@ PD6 USART2_RX USART2 PD3 USART2_CTS USART2 PD4 USART2_RTS USART2 -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters) +# UART7 maps to SERIAL5. #PE7 UART7_RX UART7 #PE8 UART7_TX UART7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef.dat index 96f0b2f3117a01..67e3ebf22edd11 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/fmuv3/hwdef.dat @@ -356,7 +356,7 @@ PE6 SPI4_MOSI SPI4 # timing affecting sensor stability. We pull it high by default. PE3 VDD_3V3_SENSORS_EN OUTPUT HIGH -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters). +# UART7 maps to SERIAL5. PE7 UART7_RX UART7 PE8 UART7_TX UART7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/mRoX21-777/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/mRoX21-777/hwdef.dat index e3e4d983b95db0..7993d2e1fec0e1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/mRoX21-777/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/mRoX21-777/hwdef.dat @@ -83,20 +83,17 @@ define HAL_I2C_INTERNAL_MASK 0 # order of I2C buses I2C_ORDER I2C1 -# now the UART order. These map to the hal.uartA to hal.uartF -# objects. If you use a shorter list then HAL_Empty::UARTDriver -# objects are substituted for later UARTs, or you can leave a gap by -# listing one or more of the uarts as EMPTY - -# the normal usage of this ordering is: +# now the SERIALn order. These map to the hal.serial(n) objects. If you use a +# shorter list then HAL_Empty::UARTDriver objects are substituted for later +# UARTs, or you can leave a gap by listing one or more of the uarts as EMPTY # 1) SERIAL0: console (primary mavlink, usually USB) -# 2) SERIAL3: primary GPS -# 3) SERIAL1: telem1 -# 4) SERIAL2: telem2 +# 2) SERIAL1: telem1 +# 3) SERIAL2: telem2 +# 4) SERIAL3: primary GPS # 5) SERIAL4: GPS2 # 6) SERIAL5: extra UART (usually RTOS debug console) -# order of UARTs (and USB) +# order of SERIALn (incl. USB) SERIAL_ORDER OTG1 USART2 USART3 UART4 UART8 UART7 OTG2 # if the board has an IOMCU connected via a UART then this defines the @@ -315,7 +312,7 @@ PE1 UART8_TX UART8 # timing affecting sensor stability. We pull it high by default PE3 VDD_3V3_SENSORS_EN OUTPUT HIGH -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters) +# UART7 maps to SERIAL5. PE7 UART7_RX UART7 PE8 UART7_TX UART7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/thepeach-k1/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/thepeach-k1/hwdef.dat index 827c5ff9592282..d5c1c44015b91e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/thepeach-k1/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/thepeach-k1/hwdef.dat @@ -209,7 +209,7 @@ PE1 UART8_TX UART8 # timing affecting sensor stability. We pull it high by default. PE3 VDD_3V3_SENSORS_EN OUTPUT HIGH -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters). +# UART7 maps to SERIAL5. PE7 UART7_RX UART7 PE8 UART7_TX UART7 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/thepeach-r1/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/thepeach-r1/hwdef.dat index 4122e0fa579919..4b128cb02b6565 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/thepeach-r1/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/thepeach-r1/hwdef.dat @@ -209,7 +209,7 @@ PE1 UART8_TX UART8 # timing affecting sensor stability. We pull it high by default. PE3 VDD_3V3_SENSORS_EN OUTPUT HIGH -# UART7 maps to uartF in the HAL (serial5 in SERIALn_ parameters). +# UART7 maps to SERIAL5. PE7 UART7_RX UART7 PE8 UART7_TX UART7 From 20ee5b2d3788d6c667baa7d779e7d7f3fda5c47f Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Sun, 10 Dec 2023 11:29:32 -0600 Subject: [PATCH 0146/1335] AP_HAL_Empty: eliminate legacy UART ordering/references Fourth serial port (SERIAL2) added purely for consistency. --- libraries/AP_HAL_Empty/HAL_Empty_Class.cpp | 29 +++++++++++----------- 1 file changed, 15 insertions(+), 14 deletions(-) diff --git a/libraries/AP_HAL_Empty/HAL_Empty_Class.cpp b/libraries/AP_HAL_Empty/HAL_Empty_Class.cpp index a05acc59d08a12..9d03bcabf78953 100644 --- a/libraries/AP_HAL_Empty/HAL_Empty_Class.cpp +++ b/libraries/AP_HAL_Empty/HAL_Empty_Class.cpp @@ -9,9 +9,10 @@ using namespace Empty; -static UARTDriver uartADriver; -static UARTDriver uartBDriver; -static UARTDriver uartCDriver; +static UARTDriver serial0Driver; +static UARTDriver serial1Driver; +static UARTDriver serial2Driver; +static UARTDriver serial3Driver; static SPIDeviceManager spiDeviceManager; static AnalogIn analogIn; static Storage storageDriver; @@ -25,20 +26,20 @@ static Flash flashDriver; HAL_Empty::HAL_Empty() : AP_HAL::HAL( - &uartADriver, - &uartCDriver, // ordering captures the historical use of uartB as SERIAL3 - nullptr, /* no uartD */ - &uartBDriver, - nullptr, /* no uartE */ - nullptr, /* no uartF */ - nullptr, /* no uartG */ - nullptr, /* no uartH */ - nullptr, /* no uartI */ - nullptr, /* no uartJ */ + &serial0Driver, + &serial1Driver, + &serial2Driver, + &serial3Driver, + nullptr, /* no SERIAL4 */ + nullptr, /* no SERIAL5 */ + nullptr, /* no SERIAL6 */ + nullptr, /* no SERIAL7 */ + nullptr, /* no SERIAL8 */ + nullptr, /* no SERIAL9 */ &spiDeviceManager, &analogIn, &storageDriver, - &uartADriver, + &serial0Driver, &gpioDriver, &rcinDriver, &rcoutDriver, From 6b7934994716ed44b56776e40037eb0669207ca0 Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Sun, 10 Dec 2023 11:33:12 -0600 Subject: [PATCH 0147/1335] AP_HAL_ESP32: eliminate legacy UART ordering/references --- libraries/AP_HAL_ESP32/HAL_ESP32_Class.cpp | 41 +++++++++++----------- 1 file changed, 20 insertions(+), 21 deletions(-) diff --git a/libraries/AP_HAL_ESP32/HAL_ESP32_Class.cpp b/libraries/AP_HAL_ESP32/HAL_ESP32_Class.cpp index 096c8ab47ad803..bedff42e98b7de 100644 --- a/libraries/AP_HAL_ESP32/HAL_ESP32_Class.cpp +++ b/libraries/AP_HAL_ESP32/HAL_ESP32_Class.cpp @@ -30,25 +30,24 @@ #include "Util.h" -static Empty::UARTDriver uartADriver; static ESP32::UARTDriver cons(0); -static ESP32::UARTDriver uartBDriver(1); #ifdef HAL_ESP32_WIFI #if HAL_ESP32_WIFI == 1 -static ESP32::WiFiDriver uartCDriver; //tcp, client should connect to 192.168.4.1 port 5760 +static ESP32::WiFiDriver serial1Driver; //tcp, client should connect to 192.168.4.1 port 5760 #elif HAL_ESP32_WIFI == 2 -static ESP32::WiFiUdpDriver uartCDriver; //udp +static ESP32::WiFiUdpDriver serial1Driver; //udp #endif #else -static Empty::UARTDriver uartCDriver; +static Empty::UARTDriver serial1Driver; #endif -static ESP32::UARTDriver uartDDriver(2); -static Empty::UARTDriver uartEDriver; -static Empty::UARTDriver uartFDriver; -static Empty::UARTDriver uartGDriver; -static Empty::UARTDriver uartHDriver; -static Empty::UARTDriver uartIDriver; -static Empty::UARTDriver uartJDriver; +static ESP32::UARTDriver serial2Driver(2); +static ESP32::UARTDriver serial3Driver(1); +static Empty::UARTDriver serial4Driver; +static Empty::UARTDriver serial5Driver; +static Empty::UARTDriver serial6Driver; +static Empty::UARTDriver serial7Driver; +static Empty::UARTDriver serial8Driver; +static Empty::UARTDriver serial9Driver; static Empty::DSP dspDriver; @@ -73,15 +72,15 @@ extern const AP_HAL::HAL& hal; HAL_ESP32::HAL_ESP32() : AP_HAL::HAL( &cons, //Console/mavlink - &uartCDriver, //Telem 1, ordering captures the historical use of uartB as SERIAL3 - &uartDDriver, //Telem 2 - &uartBDriver, //GPS 1 - &uartEDriver, //GPS 2 - &uartFDriver, //Extra 1 - &uartGDriver, //Extra 2 - &uartHDriver, //Extra 3 - &uartIDriver, //Extra 4 - &uartJDriver, //Extra 5 + &serial1Driver, //Telem 1 + &serial2Driver, //Telem 2 + &serial3Driver, //GPS 1 + &serial4Driver, //GPS 2 + &serial5Driver, //Extra 1 + &serial6Driver, //Extra 2 + &serial7Driver, //Extra 3 + &serial8Driver, //Extra 4 + &serial9Driver, //Extra 5 &i2cDeviceManager, &spiDeviceManager, nullptr, From f34034584f9a5f5ca9516a5aca8605f9148e7453 Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Sun, 10 Dec 2023 21:32:18 -0600 Subject: [PATCH 0148/1335] AP_HAL_Linux: eliminate internal legacy UART ordering/references Leave the legacy command line arguments to avoid breaking users. --- libraries/AP_HAL_Linux/HAL_Linux_Class.cpp | 81 +++++++++++----------- 1 file changed, 41 insertions(+), 40 deletions(-) diff --git a/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp b/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp index e264ccbdb139a5..f51d8c4331a9d1 100644 --- a/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp +++ b/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp @@ -64,16 +64,17 @@ static UtilRPI utilInstance; static Util utilInstance; #endif -// 9 serial ports on Linux -static UARTDriver uartADriver(true); -static UARTDriver uartCDriver(false); -static UARTDriver uartDDriver(false); -static UARTDriver uartEDriver(false); -static UARTDriver uartFDriver(false); -static UARTDriver uartGDriver(false); -static UARTDriver uartHDriver(false); -static UARTDriver uartIDriver(false); -static UARTDriver uartJDriver(false); +// 10 serial ports on Linux +static UARTDriver serial0Driver(true); +static UARTDriver serial1Driver(false); +static UARTDriver serial2Driver(false); +// serial3Driver declared below depending on board type +static UARTDriver serial4Driver(false); +static UARTDriver serial5Driver(false); +static UARTDriver serial6Driver(false); +static UARTDriver serial7Driver(false); +static UARTDriver serial8Driver(false); +static UARTDriver serial9Driver(false); static I2CDeviceManager i2c_mgr_instance; static SPIDeviceManager spi_mgr_instance; @@ -81,9 +82,9 @@ static SPIDeviceManager spi_mgr_instance; #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || \ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO2 || \ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH -static SPIUARTDriver uartBDriver; +static SPIUARTDriver serial3Driver; #else -static UARTDriver uartBDriver(false); +static UARTDriver serial3Driver(false); #endif #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || \ @@ -247,22 +248,22 @@ static CANIface* canDrivers[HAL_NUM_CAN_IFACES]; HAL_Linux::HAL_Linux() : AP_HAL::HAL( - &uartADriver, - &uartCDriver, // ordering captures the historical use of uartB as SERIAL3 - &uartDDriver, - &uartBDriver, - &uartEDriver, - &uartFDriver, - &uartGDriver, - &uartHDriver, - &uartIDriver, - &uartJDriver, + &serial0Driver, + &serial1Driver, + &serial2Driver, + &serial3Driver, + &serial4Driver, + &serial5Driver, + &serial6Driver, + &serial7Driver, + &serial8Driver, + &serial9Driver, &i2c_mgr_instance, &spi_mgr_instance, &wspi_mgr_instance, &analogIn, &storageDriver, - &uartADriver, + &serial0Driver, &gpioDriver, &rcinDriver, &rcoutDriver, @@ -281,16 +282,16 @@ HAL_Linux::HAL_Linux() : void _usage(void) { - printf("Usage: --serial0 serial0Path --serial1 serial2Path \n"); + printf("Usage: --serial0 serial0Path --serial1 serial1Path \n"); printf("Examples:\n"); printf("\tserial (0 through 9 available):\n"); printf("\t --serial0 /dev/ttyO4\n"); printf("\t --serial3 /dev/ttyS1\n"); printf("\tlegacy UART options still work, their mappings are:\n"); printf("\t -A/--uartA is SERIAL0\n"); - printf("\t -B/--uartB is SERIAL3\n"); printf("\t -C/--uartC is SERIAL1\n"); printf("\t -D/--uartD is SERIAL2\n"); + printf("\t -B/--uartB is SERIAL3\n"); printf("\t -E/--uartE is SERIAL4\n"); printf("\t -F/--uartF is SERIAL5\n"); printf("\t -G/--uartG is SERIAL6\n"); @@ -334,12 +335,12 @@ void HAL_Linux::run(int argc, char* const argv[], Callbacks* callbacks) const const struct GetOptLong::option options[] = { {"uartA", true, 0, 'A'}, {"serial0", true, 0, 'A'}, - {"uartB", true, 0, 'B'}, - {"serial3", true, 0, 'B'}, - {"uartC", true, 0, 'C'}, + {"uartC", true, 0, 'C'}, // ordering captures the historical use of uartB as SERIAL3 {"serial1", true, 0, 'C'}, {"uartD", true, 0, 'D'}, {"serial2", true, 0, 'D'}, + {"uartB", true, 0, 'B'}, + {"serial3", true, 0, 'B'}, {"uartE", true, 0, 'E'}, {"serial4", true, 0, 'E'}, {"uartF", true, 0, 'F'}, @@ -371,34 +372,34 @@ void HAL_Linux::run(int argc, char* const argv[], Callbacks* callbacks) const while ((opt = gopt.getoption()) != -1) { switch (opt) { case 'A': - uartADriver.set_device_path(gopt.optarg); - break; - case 'B': - uartBDriver.set_device_path(gopt.optarg); + serial0Driver.set_device_path(gopt.optarg); break; case 'C': - uartCDriver.set_device_path(gopt.optarg); + serial1Driver.set_device_path(gopt.optarg); break; case 'D': - uartDDriver.set_device_path(gopt.optarg); + serial2Driver.set_device_path(gopt.optarg); + break; + case 'B': + serial3Driver.set_device_path(gopt.optarg); break; case 'E': - uartEDriver.set_device_path(gopt.optarg); + serial4Driver.set_device_path(gopt.optarg); break; case 'F': - uartFDriver.set_device_path(gopt.optarg); + serial5Driver.set_device_path(gopt.optarg); break; case 'G': - uartGDriver.set_device_path(gopt.optarg); + serial6Driver.set_device_path(gopt.optarg); break; case 'H': - uartHDriver.set_device_path(gopt.optarg); + serial7Driver.set_device_path(gopt.optarg); break; case 'I': - uartIDriver.set_device_path(gopt.optarg); + serial8Driver.set_device_path(gopt.optarg); break; case 'J': - uartJDriver.set_device_path(gopt.optarg); + serial9Driver.set_device_path(gopt.optarg); break; case 'l': utilInstance.set_custom_log_directory(gopt.optarg); From 9044632315f9c25e7e4cf92ca2f583ba1b54056d Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Sun, 10 Dec 2023 21:55:21 -0600 Subject: [PATCH 0149/1335] AP_HAL_SITL: eliminate internal legacy UART ordering/references Legacy command line arguments are kept to avoid breaking users. The vestigial `_tcp_client_addr` variable is removed. Serial port status messages are updated to a slightly different format to clarify the numbering scheme being used and prompt any external consumers to update. --- libraries/AP_HAL_SITL/HAL_SITL_Class.cpp | 42 ++++++------- libraries/AP_HAL_SITL/SITL_Periph_State.cpp | 6 +- libraries/AP_HAL_SITL/SITL_Periph_State.h | 4 +- libraries/AP_HAL_SITL/SITL_State.h | 4 +- libraries/AP_HAL_SITL/SITL_cmdline.cpp | 70 +++++++-------------- libraries/AP_HAL_SITL/UARTDriver.cpp | 22 +++---- libraries/AP_HAL_SITL/UARTDriver.h | 3 - 7 files changed, 61 insertions(+), 90 deletions(-) diff --git a/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp b/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp index 57d719875c66e6..0d79624ee6bcf3 100644 --- a/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp +++ b/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp @@ -53,16 +53,16 @@ static DSP dspDriver; static Empty::OpticalFlow emptyOpticalFlow; static Empty::Flash emptyFlash; -static UARTDriver sitlUart0Driver(0, &sitlState); -static UARTDriver sitlUart1Driver(1, &sitlState); -static UARTDriver sitlUart2Driver(2, &sitlState); -static UARTDriver sitlUart3Driver(3, &sitlState); -static UARTDriver sitlUart4Driver(4, &sitlState); -static UARTDriver sitlUart5Driver(5, &sitlState); -static UARTDriver sitlUart6Driver(6, &sitlState); -static UARTDriver sitlUart7Driver(7, &sitlState); -static UARTDriver sitlUart8Driver(8, &sitlState); -static UARTDriver sitlUart9Driver(9, &sitlState); +static UARTDriver sitlSerial0Driver(0, &sitlState); +static UARTDriver sitlSerial1Driver(1, &sitlState); +static UARTDriver sitlSerial2Driver(2, &sitlState); +static UARTDriver sitlSerial3Driver(3, &sitlState); +static UARTDriver sitlSerial4Driver(4, &sitlState); +static UARTDriver sitlSerial5Driver(5, &sitlState); +static UARTDriver sitlSerial6Driver(6, &sitlState); +static UARTDriver sitlSerial7Driver(7, &sitlState); +static UARTDriver sitlSerial8Driver(8, &sitlState); +static UARTDriver sitlSerial9Driver(9, &sitlState); static I2CDeviceManager i2c_mgr_instance; @@ -81,22 +81,22 @@ static Empty::WSPIDeviceManager wspi_mgr_instance; HAL_SITL::HAL_SITL() : AP_HAL::HAL( - &sitlUart0Driver, /* uartA */ - &sitlUart2Driver, /* uartC */ // ordering captures the historical use of uartB as SERIAL3 - &sitlUart3Driver, /* uartD */ - &sitlUart1Driver, /* uartB */ - &sitlUart4Driver, /* uartE */ - &sitlUart5Driver, /* uartF */ - &sitlUart6Driver, /* uartG */ - &sitlUart7Driver, /* uartH */ - &sitlUart8Driver, /* uartI */ - &sitlUart9Driver, /* uartJ */ + &sitlSerial0Driver, + &sitlSerial1Driver, + &sitlSerial2Driver, + &sitlSerial3Driver, + &sitlSerial4Driver, + &sitlSerial5Driver, + &sitlSerial6Driver, + &sitlSerial7Driver, + &sitlSerial8Driver, + &sitlSerial9Driver, &i2c_mgr_instance, &spi_mgr_instance, /* spi */ &wspi_mgr_instance, &sitlAnalogIn, /* analogin */ &sitlStorage, /* storage */ - &sitlUart0Driver, /* console */ + &sitlSerial0Driver, /* console */ &sitlGPIO, /* gpio */ &sitlRCInput, /* rcinput */ &sitlRCOutput, /* rcoutput */ diff --git a/libraries/AP_HAL_SITL/SITL_Periph_State.cpp b/libraries/AP_HAL_SITL/SITL_Periph_State.cpp index 27f1b063c86a42..618f26a1aeabd7 100644 --- a/libraries/AP_HAL_SITL/SITL_Periph_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_Periph_State.cpp @@ -83,11 +83,9 @@ void SITL_State::init(int argc, char * const argv[]) { case CMDLINE_SERIAL6: case CMDLINE_SERIAL7: case CMDLINE_SERIAL8: - case CMDLINE_SERIAL9: { - static const uint8_t mapping[] = { 0, 2, 3, 1, 4, 5, 6, 7, 8, 9 }; - _uart_path[mapping[opt - CMDLINE_SERIAL0]] = gopt.optarg; + case CMDLINE_SERIAL9: + _serial_path[opt - CMDLINE_SERIAL0] = gopt.optarg; break; - } case CMDLINE_DEFAULTS: defaults_path = strdup(gopt.optarg); break; diff --git a/libraries/AP_HAL_SITL/SITL_Periph_State.h b/libraries/AP_HAL_SITL/SITL_Periph_State.h index b7e21d1491cc94..47bb61ee79639f 100644 --- a/libraries/AP_HAL_SITL/SITL_Periph_State.h +++ b/libraries/AP_HAL_SITL/SITL_Periph_State.h @@ -61,11 +61,11 @@ class HALSITL::SITL_State : public SITL_State_Common { } // paths for UART devices - const char *_uart_path[9] { + const char *_serial_path[9] { "none:0", - "GPS1", "none:1", "sim:adsb", + "GPS1", "udpclient:127.0.0.1:15550", // for CAN UART test "none:5", "none:6", diff --git a/libraries/AP_HAL_SITL/SITL_State.h b/libraries/AP_HAL_SITL/SITL_State.h index 8ca5afd4526af9..461ff51d600bed 100644 --- a/libraries/AP_HAL_SITL/SITL_State.h +++ b/libraries/AP_HAL_SITL/SITL_State.h @@ -29,11 +29,11 @@ class HALSITL::SITL_State : public SITL_State_Common { } // paths for UART devices - const char *_uart_path[9] { + const char *_serial_path[9] { "tcp:0:wait", - "GPS1", "tcp:2", "tcp:3", + "GPS1", "GPS2", "tcp:5", "tcp:6", diff --git a/libraries/AP_HAL_SITL/SITL_cmdline.cpp b/libraries/AP_HAL_SITL/SITL_cmdline.cpp index a413c3840c799c..5ca530e38b0727 100644 --- a/libraries/AP_HAL_SITL/SITL_cmdline.cpp +++ b/libraries/AP_HAL_SITL/SITL_cmdline.cpp @@ -92,16 +92,16 @@ void SITL_State::_usage(void) "\t--gimbal enable simulated MAVLink gimbal\n" "\t--autotest-dir DIR set directory for additional files\n" "\t--defaults path set path to defaults file\n" - "\t--uartA device set device string for UARTA\n" - "\t--uartB device set device string for UARTB\n" - "\t--uartC device set device string for UARTC\n" - "\t--uartD device set device string for UARTD\n" - "\t--uartE device set device string for UARTE\n" - "\t--uartF device set device string for UARTF\n" - "\t--uartG device set device string for UARTG\n" - "\t--uartH device set device string for UARTH\n" - "\t--uartI device set device string for UARTI\n" - "\t--uartJ device set device string for UARTJ\n" + "\t--uartA device set device string for SERIAL0\n" + "\t--uartB device set device string for SERIAL3\n" // ordering captures the historical use of uartB as SERIAL3 + "\t--uartC device set device string for SERIAL1\n" + "\t--uartD device set device string for SERIAL2\n" + "\t--uartE device set device string for SERIAL4\n" + "\t--uartF device set device string for SERIAL5\n" + "\t--uartG device set device string for SERIAL6\n" + "\t--uartH device set device string for SERIAL7\n" + "\t--uartI device set device string for SERIAL8\n" + "\t--uartJ device set device string for SERIAL9\n" "\t--serial0 device set device string for SERIAL0\n" "\t--serial1 device set device string for SERIAL1\n" "\t--serial2 device set device string for SERIAL2\n" @@ -246,17 +246,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) CMDLINE_FGVIEW, CMDLINE_AUTOTESTDIR, CMDLINE_DEFAULTS, - CMDLINE_UARTA, - CMDLINE_UARTB, - CMDLINE_UARTC, - CMDLINE_UARTD, - CMDLINE_UARTE, - CMDLINE_UARTF, - CMDLINE_UARTG, - CMDLINE_UARTH, - CMDLINE_UARTI, - CMDLINE_UARTJ, - CMDLINE_SERIAL0, + CMDLINE_SERIAL0, // must be in 0-9 order and numbered consecutively CMDLINE_SERIAL1, CMDLINE_SERIAL2, CMDLINE_SERIAL3, @@ -305,16 +295,16 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) {"disable-fgview", false, 0, CMDLINE_FGVIEW}, {"autotest-dir", true, 0, CMDLINE_AUTOTESTDIR}, {"defaults", true, 0, CMDLINE_DEFAULTS}, - {"uartA", true, 0, CMDLINE_UARTA}, - {"uartB", true, 0, CMDLINE_UARTB}, - {"uartC", true, 0, CMDLINE_UARTC}, - {"uartD", true, 0, CMDLINE_UARTD}, - {"uartE", true, 0, CMDLINE_UARTE}, - {"uartF", true, 0, CMDLINE_UARTF}, - {"uartG", true, 0, CMDLINE_UARTG}, - {"uartH", true, 0, CMDLINE_UARTH}, - {"uartI", true, 0, CMDLINE_UARTI}, - {"uartJ", true, 0, CMDLINE_UARTJ}, + {"uartA", true, 0, CMDLINE_SERIAL0}, + {"uartB", true, 0, CMDLINE_SERIAL3}, // ordering captures the historical use of uartB as SERIAL3 + {"uartC", true, 0, CMDLINE_SERIAL1}, + {"uartD", true, 0, CMDLINE_SERIAL2}, + {"uartE", true, 0, CMDLINE_SERIAL4}, + {"uartF", true, 0, CMDLINE_SERIAL5}, + {"uartG", true, 0, CMDLINE_SERIAL6}, + {"uartH", true, 0, CMDLINE_SERIAL7}, + {"uartI", true, 0, CMDLINE_SERIAL8}, + {"uartJ", true, 0, CMDLINE_SERIAL9}, {"serial0", true, 0, CMDLINE_SERIAL0}, {"serial1", true, 0, CMDLINE_SERIAL1}, {"serial2", true, 0, CMDLINE_SERIAL2}, @@ -449,18 +439,6 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) case CMDLINE_DEFAULTS: defaults_path = strdup(gopt.optarg); break; - case CMDLINE_UARTA: - case CMDLINE_UARTB: - case CMDLINE_UARTC: - case CMDLINE_UARTD: - case CMDLINE_UARTE: - case CMDLINE_UARTF: - case CMDLINE_UARTG: - case CMDLINE_UARTH: - case CMDLINE_UARTI: - case CMDLINE_UARTJ: - _uart_path[opt - CMDLINE_UARTA] = gopt.optarg; - break; case CMDLINE_SERIAL0: case CMDLINE_SERIAL1: case CMDLINE_SERIAL2: @@ -470,11 +448,9 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) case CMDLINE_SERIAL6: case CMDLINE_SERIAL7: case CMDLINE_SERIAL8: - case CMDLINE_SERIAL9: { - static const uint8_t mapping[] = { 0, 2, 3, 1, 4, 5, 6, 7, 8, 9 }; - _uart_path[mapping[opt - CMDLINE_SERIAL0]] = gopt.optarg; + case CMDLINE_SERIAL9: + _serial_path[opt - CMDLINE_SERIAL0] = gopt.optarg; break; - } case CMDLINE_RTSCTS: _use_rtscts = true; break; diff --git a/libraries/AP_HAL_SITL/UARTDriver.cpp b/libraries/AP_HAL_SITL/UARTDriver.cpp index 9c90928630dea3..900ef64ab61628 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.cpp +++ b/libraries/AP_HAL_SITL/UARTDriver.cpp @@ -56,11 +56,11 @@ bool UARTDriver::_console; void UARTDriver::_begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace) { - if (_portNumber >= ARRAY_SIZE(_sitlState->_uart_path)) { - AP_HAL::panic("port number out of range; you may need to extend _sitlState->_uart_path"); + if (_portNumber >= ARRAY_SIZE(_sitlState->_serial_path)) { + AP_HAL::panic("port number out of range; you may need to extend _sitlState->_serial_path"); } - const char *path = _sitlState->_uart_path[_portNumber]; + const char *path = _sitlState->_serial_path[_portNumber]; if (baud != 0) { _uart_baudrate = baud; @@ -95,11 +95,11 @@ void UARTDriver::_begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace) char *args1 = strtok_r(nullptr, ":", &saveptr); char *args2 = strtok_r(nullptr, ":", &saveptr); #if APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane) - if (_portNumber == 2 && AP::sitl()->adsb_plane_count >= 0) { + if (_portNumber == 1 && AP::sitl()->adsb_plane_count >= 0) { // this is ordinarily port 5762. The ADSB simulation assumed // this port, so if enabled we assume we'll be doing ADSB... // add sanity check here that we're doing mavlink on this port? - ::printf("SIM-ADSB connection on port %u\n", _portNumber); + ::printf("SIM-ADSB connection on SERIAL%u\n", _portNumber); _connected = true; _sim_serial_device = _sitlState->create_serial_sim("adsb", nullptr); } else @@ -122,7 +122,7 @@ void UARTDriver::_begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace) _uart_start_connection(); } else if (strcmp(devtype, "sim") == 0) { if (!_connected) { - ::printf("SIM connection %s:%s on port %u\n", args1, args2, _portNumber); + ::printf("SIM connection %s:%s on SERIAL%u\n", args1, args2, _portNumber); _connected = true; _sim_serial_device = _sitlState->create_serial_sim(args1, args2); } @@ -334,7 +334,7 @@ void UARTDriver::_tcp_start_connection(uint16_t port, bool wait_for_connection) exit(1); } - fprintf(stderr, "bind port %u for %u\n", + fprintf(stderr, "bind port %u for SERIAL%u\n", (unsigned)ntohs(_listen_sockaddr.sin_port), (unsigned)_portNumber); @@ -352,7 +352,7 @@ void UARTDriver::_tcp_start_connection(uint16_t port, bool wait_for_connection) exit(1); } - fprintf(stderr, "Serial port %u on TCP port %u\n", _portNumber, + fprintf(stderr, "SERIAL%u on TCP port %u\n", _portNumber, (unsigned)ntohs(_listen_sockaddr.sin_port)); fflush(stdout); } @@ -630,7 +630,7 @@ void UARTDriver::_check_connection(void) setsockopt(_fd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one)); setsockopt(_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)); fcntl(_fd, F_SETFD, FD_CLOEXEC); - fprintf(stdout, "New connection on serial port %u\n", _portNumber); + fprintf(stdout, "New connection on SERIAL%u\n", _portNumber); } } } @@ -917,7 +917,7 @@ void UARTDriver::handle_reading_from_device_to_readbuffer() close(_fd); _fd = -1; _connected = false; - fprintf(stdout, "Closed connection on serial port %u\n", _portNumber); + fprintf(stdout, "Closed connection on SERIAL%u\n", _portNumber); fflush(stdout); #if defined(__CYGWIN__) || defined(__CYGWIN64__) || defined(CYGWIN_BUILD) if (_portNumber == 0) { @@ -990,7 +990,7 @@ ssize_t UARTDriver::get_system_outqueue_length() const uint32_t UARTDriver::bw_in_bytes_per_second() const { // if connected, assume at least a 10/100Mbps connection - const uint32_t bitrate = (_connected && _tcp_client_addr != nullptr) ? 10E6 : _uart_baudrate; + const uint32_t bitrate = _connected ? 10E6 : _uart_baudrate; return bitrate/10; // convert bits to bytes minus overhead }; #endif // CONFIG_HAL_BOARD diff --git a/libraries/AP_HAL_SITL/UARTDriver.h b/libraries/AP_HAL_SITL/UARTDriver.h index d47378a8054dae..cac1dc4e7aa2c7 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.h +++ b/libraries/AP_HAL_SITL/UARTDriver.h @@ -89,9 +89,6 @@ class HALSITL::UARTDriver : public AP_HAL::UARTDriver { const char *_uart_path; uint32_t _uart_baudrate; - // IPv4 address of target for uartC - const char *_tcp_client_addr; - void _tcp_start_connection(uint16_t port, bool wait_for_connection); void _uart_start_connection(void); void _check_reconnect(); From f6ea8201b2c5243fd3c470e66f0eaf181137f750 Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Mon, 11 Dec 2023 11:13:24 -0600 Subject: [PATCH 0150/1335] SITL: remove references to legacy UART order incl. sim arguments --- libraries/SITL/SIM_ADSB.cpp | 2 +- libraries/SITL/SIM_AIS.cpp | 2 +- libraries/SITL/SIM_AIS.h | 2 +- libraries/SITL/SIM_CRSF.h | 2 +- libraries/SITL/SIM_EFI_Hirth.h | 2 +- libraries/SITL/SIM_EFI_MegaSquirt.h | 2 +- libraries/SITL/SIM_FETtecOneWireESC.h | 2 +- libraries/SITL/SIM_Frsky_D.h | 2 +- libraries/SITL/SIM_GPS.h | 2 +- libraries/SITL/SIM_Gimbal.cpp | 2 +- libraries/SITL/SIM_IntelligentEnergy24.h | 2 +- libraries/SITL/SIM_Morse.cpp | 2 +- libraries/SITL/SIM_PS_LightWare_SF45B.h | 2 +- libraries/SITL/SIM_PS_RPLidar.h | 2 +- libraries/SITL/SIM_PS_RPLidarA1.h | 2 +- libraries/SITL/SIM_PS_RPLidarA2.h | 2 +- libraries/SITL/SIM_PS_TeraRangerTower.h | 2 +- libraries/SITL/SIM_RF_BLping.h | 2 +- libraries/SITL/SIM_RF_Benewake_TF02.h | 2 +- libraries/SITL/SIM_RF_Benewake_TF03.h | 2 +- libraries/SITL/SIM_RF_Benewake_TFmini.h | 2 +- libraries/SITL/SIM_RF_GYUS42v2.h | 2 +- libraries/SITL/SIM_RF_JRE.h | 2 +- libraries/SITL/SIM_RF_Lanbao.h | 2 +- libraries/SITL/SIM_RF_LeddarOne.h | 2 +- libraries/SITL/SIM_RF_LightWareSerial.h | 2 +- libraries/SITL/SIM_RF_LightWareSerialBinary.h | 2 +- libraries/SITL/SIM_RF_MAVLink.h | 2 +- libraries/SITL/SIM_RF_MaxsonarSerialLV.h | 2 +- libraries/SITL/SIM_RF_NMEA.h | 2 +- libraries/SITL/SIM_RF_RDS02UF.h | 2 +- libraries/SITL/SIM_RF_TeraRanger_Serial.h | 2 +- libraries/SITL/SIM_RF_USD1_v0.h | 2 +- libraries/SITL/SIM_RF_USD1_v1.h | 2 +- libraries/SITL/SIM_RF_Wasp.h | 2 +- libraries/SITL/SIM_RichenPower.h | 2 +- libraries/SITL/SIM_VectorNav.h | 2 +- libraries/SITL/examples/Airsim/follow-copter.sh | 4 ++-- libraries/SITL/examples/Airsim/multi_vehicle.sh | 4 ++-- libraries/SITL/examples/Follow/plane_quad.sh | 8 ++++---- libraries/SITL/examples/Morse/start_follow.sh | 4 ++-- libraries/SITL/examples/follow-copter.sh | 4 ++-- 42 files changed, 49 insertions(+), 49 deletions(-) diff --git a/libraries/SITL/SIM_ADSB.cpp b/libraries/SITL/SIM_ADSB.cpp index 784d032902642a..2168b922946e0c 100644 --- a/libraries/SITL/SIM_ADSB.cpp +++ b/libraries/SITL/SIM_ADSB.cpp @@ -164,7 +164,7 @@ void ADSB::send_report(const class Aircraft &aircraft) { if (AP_HAL::millis() < 10000) { // simulated aircraft don't appear until 10s after startup. This avoids a windows - // threading issue with non-blocking sockets and the initial wait on uartA + // threading issue with non-blocking sockets and the initial wait on SERIAL0 return; } diff --git a/libraries/SITL/SIM_AIS.cpp b/libraries/SITL/SIM_AIS.cpp index 4372cabd5dd4f3..6aae9c3717331f 100644 --- a/libraries/SITL/SIM_AIS.cpp +++ b/libraries/SITL/SIM_AIS.cpp @@ -14,7 +14,7 @@ */ /* Dump logged AIS data to the serial port - ./Tools/autotest/sim_vehicle.py -v Rover -A --uartF=sim:AIS --custom-location 51.58689798356386,-3.9044570193067965,0,0 + ./Tools/autotest/sim_vehicle.py -v Rover -A --serial5=sim:AIS --custom-location 51.58689798356386,-3.9044570193067965,0,0 param set SERIAL5_PROTOCOL 40 param set AIS_TYPE 1 diff --git a/libraries/SITL/SIM_AIS.h b/libraries/SITL/SIM_AIS.h index 14bc6c90159f9f..395f0f11e5bec5 100644 --- a/libraries/SITL/SIM_AIS.h +++ b/libraries/SITL/SIM_AIS.h @@ -14,7 +14,7 @@ */ /* Dump logged AIS data to the serial port - ./Tools/autotest/sim_vehicle.py -v Rover --no-mavproxy -A --uartF=sim:AIS --custom-location 51.58689798356386,-3.9044570193067965,0,0 + ./Tools/autotest/sim_vehicle.py -v Rover --no-mavproxy -A --serial5=sim:AIS --custom-location 51.58689798356386,-3.9044570193067965,0,0 param set SERIAL5_PROTOCOL 40 param set AIS_TYPE 1 diff --git a/libraries/SITL/SIM_CRSF.h b/libraries/SITL/SIM_CRSF.h index bd02e92dded553..c4fcda7efabf87 100644 --- a/libraries/SITL/SIM_CRSF.h +++ b/libraries/SITL/SIM_CRSF.h @@ -15,7 +15,7 @@ /* Simulated CRSF device -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:crsf --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:crsf --speedup=1 param set SERIAL5_PROTOCOL 23 reboot diff --git a/libraries/SITL/SIM_EFI_Hirth.h b/libraries/SITL/SIM_EFI_Hirth.h index cfc32517e6a76e..8ccbb8286a8ad2 100644 --- a/libraries/SITL/SIM_EFI_Hirth.h +++ b/libraries/SITL/SIM_EFI_Hirth.h @@ -15,7 +15,7 @@ /* simulate Hirth EFI system -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduPlane -A --uartF=sim:hirth --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduPlane -A --serial5=sim:hirth --speedup=1 param set SERIAL5_PROTOCOL 24 param set SIM_EFI_TYPE 6 param set EFI_TYPE 6 diff --git a/libraries/SITL/SIM_EFI_MegaSquirt.h b/libraries/SITL/SIM_EFI_MegaSquirt.h index 813e22e5e65d90..352fbd44589eb3 100644 --- a/libraries/SITL/SIM_EFI_MegaSquirt.h +++ b/libraries/SITL/SIM_EFI_MegaSquirt.h @@ -15,7 +15,7 @@ /* simulate MegaSquirt EFI system -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduPlane -A --uartF=sim:megasquirt --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduPlane -A --serial5=sim:megasquirt --speedup=1 param set SERIAL5_PROTOCOL 24 param set SIM_EFI_TYPE 1 param set EFI_TYPE 1 diff --git a/libraries/SITL/SIM_FETtecOneWireESC.h b/libraries/SITL/SIM_FETtecOneWireESC.h index 2d983e3b0e6cc5..a434d066987bf7 100644 --- a/libraries/SITL/SIM_FETtecOneWireESC.h +++ b/libraries/SITL/SIM_FETtecOneWireESC.h @@ -15,7 +15,7 @@ /* Simulator for the FETtecOneWire ESCs -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:fetteconewireesc --speedup=1 --console +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:fetteconewireesc --speedup=1 --console param set SERIAL5_PROTOCOL 38 param set SERIAL5_BAUD 500000 diff --git a/libraries/SITL/SIM_Frsky_D.h b/libraries/SITL/SIM_Frsky_D.h index 5d5c8fa96a36a8..eccd37db325a06 100644 --- a/libraries/SITL/SIM_Frsky_D.h +++ b/libraries/SITL/SIM_Frsky_D.h @@ -15,7 +15,7 @@ /* Simulated Frsky D device -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:frsky-d --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:frsky-d --speedup=1 param set SERIAL5_PROTOCOL 3 reboot diff --git a/libraries/SITL/SIM_GPS.h b/libraries/SITL/SIM_GPS.h index 334ea2e0a077e7..87eafb00c43081 100644 --- a/libraries/SITL/SIM_GPS.h +++ b/libraries/SITL/SIM_GPS.h @@ -18,7 +18,7 @@ Usage example: param set SERIAL5_PROTOCOL 5 - sim_vehicle.py -D --console --map -A --uartB=sim:gps:2 + sim_vehicle.py -D --console --map -A --serial5=sim:gps:2 */ #pragma once diff --git a/libraries/SITL/SIM_Gimbal.cpp b/libraries/SITL/SIM_Gimbal.cpp index a1997dd00fbd19..5aede11b3b40a3 100644 --- a/libraries/SITL/SIM_Gimbal.cpp +++ b/libraries/SITL/SIM_Gimbal.cpp @@ -258,7 +258,7 @@ void Gimbal::send_report(void) if (now < 10000) { // don't send gimbal reports until 10s after startup. This // avoids a windows threading issue with non-blocking sockets - // and the initial wait on uartA + // and the initial wait on SERIAL0 return; } if (!mavlink.connected && mav_socket.connect(target_address, target_port)) { diff --git a/libraries/SITL/SIM_IntelligentEnergy24.h b/libraries/SITL/SIM_IntelligentEnergy24.h index 68d8782937f627..794addc7a9b033 100644 --- a/libraries/SITL/SIM_IntelligentEnergy24.h +++ b/libraries/SITL/SIM_IntelligentEnergy24.h @@ -15,7 +15,7 @@ /* Simulator for the IntelligentEnergy 2.4kW FuelCell -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:ie24 --speedup=1 --console +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:ie24 --speedup=1 --console param set SERIAL5_PROTOCOL 30 # Generator param set SERIAL5_BAUD 115200 diff --git a/libraries/SITL/SIM_Morse.cpp b/libraries/SITL/SIM_Morse.cpp index 81ba8ce34972f7..221c6c1abe011c 100644 --- a/libraries/SITL/SIM_Morse.cpp +++ b/libraries/SITL/SIM_Morse.cpp @@ -602,7 +602,7 @@ void Morse::send_report(void) if (now < 10000) { // don't send lidar reports until 10s after startup. This // avoids a windows threading issue with non-blocking sockets - // and the initial wait on uartA + // and the initial wait on SERIAL0 return; } #endif diff --git a/libraries/SITL/SIM_PS_LightWare_SF45B.h b/libraries/SITL/SIM_PS_LightWare_SF45B.h index 901a6c7988ebc5..16fd9955734efd 100644 --- a/libraries/SITL/SIM_PS_LightWare_SF45B.h +++ b/libraries/SITL/SIM_PS_LightWare_SF45B.h @@ -15,7 +15,7 @@ /* Simulator for the LightWare S45B proximity sensor -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:sf45b --speedup=1 -l 51.8752066,14.6487840,54.15,0 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:sf45b --speedup=1 -l 51.8752066,14.6487840,54.15,0 param set SERIAL5_PROTOCOL 11 # proximity param set PRX1_TYPE 8 # s45b diff --git a/libraries/SITL/SIM_PS_RPLidar.h b/libraries/SITL/SIM_PS_RPLidar.h index bf2444f5cd5172..bb694a7bab31cb 100644 --- a/libraries/SITL/SIM_PS_RPLidar.h +++ b/libraries/SITL/SIM_PS_RPLidar.h @@ -17,7 +17,7 @@ /* Simulator for the RPLidarA2 proximity sensor -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:rplidara2 --speedup=1 -l 51.8752066,14.6487840,54.15,0 --map +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:rplidara2 --speedup=1 -l 51.8752066,14.6487840,54.15,0 --map param set SERIAL5_PROTOCOL 11 param set PRX1_TYPE 5 diff --git a/libraries/SITL/SIM_PS_RPLidarA1.h b/libraries/SITL/SIM_PS_RPLidarA1.h index d374354e6b37aa..ca0b625270ea5f 100644 --- a/libraries/SITL/SIM_PS_RPLidarA1.h +++ b/libraries/SITL/SIM_PS_RPLidarA1.h @@ -15,7 +15,7 @@ /* Simulator for the RPLidarA2 proximity sensor -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:rplidara1 --speedup=1 -l 51.8752066,14.6487840,0,0 --map +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:rplidara1 --speedup=1 -l 51.8752066,14.6487840,0,0 --map param set SERIAL5_PROTOCOL 11 param set PRX1_TYPE 5 diff --git a/libraries/SITL/SIM_PS_RPLidarA2.h b/libraries/SITL/SIM_PS_RPLidarA2.h index b5beb50f3cf022..785c2bd6bce337 100644 --- a/libraries/SITL/SIM_PS_RPLidarA2.h +++ b/libraries/SITL/SIM_PS_RPLidarA2.h @@ -15,7 +15,7 @@ /* Simulator for the RPLidarA2 proximity sensor -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:rplidara2 --speedup=1 -l 51.8752066,14.6487840,0,0 --map +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:rplidara2 --speedup=1 -l 51.8752066,14.6487840,0,0 --map param set SERIAL5_PROTOCOL 11 param set PRX1_TYPE 5 diff --git a/libraries/SITL/SIM_PS_TeraRangerTower.h b/libraries/SITL/SIM_PS_TeraRangerTower.h index f17f491bceb67b..71b0798d52a355 100644 --- a/libraries/SITL/SIM_PS_TeraRangerTower.h +++ b/libraries/SITL/SIM_PS_TeraRangerTower.h @@ -15,7 +15,7 @@ /* Simulator for the TeraRangerTower proximity sensor -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:terarangertower --speedup=1 -l 51.8752066,14.6487840,54.15,0 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:terarangertower --speedup=1 -l 51.8752066,14.6487840,54.15,0 param set SERIAL5_PROTOCOL 11 param set PRX1_TYPE 3 # terarangertower diff --git a/libraries/SITL/SIM_RF_BLping.h b/libraries/SITL/SIM_RF_BLping.h index 7c76b31d1fc650..762e5de9611992 100644 --- a/libraries/SITL/SIM_RF_BLping.h +++ b/libraries/SITL/SIM_RF_BLping.h @@ -15,7 +15,7 @@ /* Simulator for the BLping rangefinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduSub -A --uartF=sim:blping --speedup=1 -l 33.810313,-118.393867,0,185 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduSub -A --serial5=sim:blping --speedup=1 -l 33.810313,-118.393867,0,185 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 23 diff --git a/libraries/SITL/SIM_RF_Benewake_TF02.h b/libraries/SITL/SIM_RF_Benewake_TF02.h index fac8443f6bf656..3d9604559c5ae0 100644 --- a/libraries/SITL/SIM_RF_Benewake_TF02.h +++ b/libraries/SITL/SIM_RF_Benewake_TF02.h @@ -15,7 +15,7 @@ /* Simulator for the Benewake TF02 RangeFinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:benewake_tf02 --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:benewake_tf02 --speedup=1 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 19 diff --git a/libraries/SITL/SIM_RF_Benewake_TF03.h b/libraries/SITL/SIM_RF_Benewake_TF03.h index f8d86fdbd59d45..cd01419e3338c0 100644 --- a/libraries/SITL/SIM_RF_Benewake_TF03.h +++ b/libraries/SITL/SIM_RF_Benewake_TF03.h @@ -15,7 +15,7 @@ /* Simulator for the Benewake TF03 RangeFinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:benewake_tf03 --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:benewake_tf03 --speedup=1 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 27 diff --git a/libraries/SITL/SIM_RF_Benewake_TFmini.h b/libraries/SITL/SIM_RF_Benewake_TFmini.h index b204fb6bf023f1..5589b5f303bc14 100644 --- a/libraries/SITL/SIM_RF_Benewake_TFmini.h +++ b/libraries/SITL/SIM_RF_Benewake_TFmini.h @@ -15,7 +15,7 @@ /* Simulator for the TFMini RangeFinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:benewake_tfmini --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:benewake_tfmini --speedup=1 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 20 diff --git a/libraries/SITL/SIM_RF_GYUS42v2.h b/libraries/SITL/SIM_RF_GYUS42v2.h index 308123dd1813c8..7188cd30f9f92c 100644 --- a/libraries/SITL/SIM_RF_GYUS42v2.h +++ b/libraries/SITL/SIM_RF_GYUS42v2.h @@ -15,7 +15,7 @@ /* Simulator for the GY-US42-v2 serial rangefinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:gyus42v2 --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:gyus42v2 --speedup=1 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 31 diff --git a/libraries/SITL/SIM_RF_JRE.h b/libraries/SITL/SIM_RF_JRE.h index d10c77a5258909..4dbdbfe2c0ffdc 100644 --- a/libraries/SITL/SIM_RF_JRE.h +++ b/libraries/SITL/SIM_RF_JRE.h @@ -15,7 +15,7 @@ /* Simulator for the JAE JRE radio altimiter -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:jre --speedup=1 -L KalaupapaCliffs --map +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:jre --speedup=1 -L KalaupapaCliffs --map param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 38 diff --git a/libraries/SITL/SIM_RF_Lanbao.h b/libraries/SITL/SIM_RF_Lanbao.h index a3bc74e87e05db..d773287a3ed45e 100644 --- a/libraries/SITL/SIM_RF_Lanbao.h +++ b/libraries/SITL/SIM_RF_Lanbao.h @@ -15,7 +15,7 @@ /* Simulator for the Lanbao rangefinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:lanbao --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:lanbao --speedup=1 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 26 diff --git a/libraries/SITL/SIM_RF_LeddarOne.h b/libraries/SITL/SIM_RF_LeddarOne.h index ad54ce38991441..21f74ac8a70cee 100644 --- a/libraries/SITL/SIM_RF_LeddarOne.h +++ b/libraries/SITL/SIM_RF_LeddarOne.h @@ -15,7 +15,7 @@ /* Simulator for the LeddarOne rangefinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:leddarone --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:leddarone --speedup=1 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 12 diff --git a/libraries/SITL/SIM_RF_LightWareSerial.h b/libraries/SITL/SIM_RF_LightWareSerial.h index 4591fa4a5c0ac8..686b448bcf2384 100644 --- a/libraries/SITL/SIM_RF_LightWareSerial.h +++ b/libraries/SITL/SIM_RF_LightWareSerial.h @@ -15,7 +15,7 @@ /* Simulator for the serial LightWare rangefinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:lightwareserial --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:lightwareserial --speedup=1 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 8 diff --git a/libraries/SITL/SIM_RF_LightWareSerialBinary.h b/libraries/SITL/SIM_RF_LightWareSerialBinary.h index 992a7b160aacad..0454fb28904f25 100644 --- a/libraries/SITL/SIM_RF_LightWareSerialBinary.h +++ b/libraries/SITL/SIM_RF_LightWareSerialBinary.h @@ -15,7 +15,7 @@ /* Simulator for the serial LightWare rangefinder - binary mode -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:lightwareserial-binary --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:lightwareserial-binary --speedup=1 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 8 diff --git a/libraries/SITL/SIM_RF_MAVLink.h b/libraries/SITL/SIM_RF_MAVLink.h index 23b04bdaf0ea00..9d901ba75a4e65 100644 --- a/libraries/SITL/SIM_RF_MAVLink.h +++ b/libraries/SITL/SIM_RF_MAVLink.h @@ -15,7 +15,7 @@ /* Simulator for the NMEA serial rangefinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:rf_mavlink --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:rf_mavlink --speedup=1 param set SERIAL5_PROTOCOL 1 param set RNGFND1_TYPE 10 diff --git a/libraries/SITL/SIM_RF_MaxsonarSerialLV.h b/libraries/SITL/SIM_RF_MaxsonarSerialLV.h index 6397637f33ac40..d23a865f7f8fee 100644 --- a/libraries/SITL/SIM_RF_MaxsonarSerialLV.h +++ b/libraries/SITL/SIM_RF_MaxsonarSerialLV.h @@ -15,7 +15,7 @@ /* Simulator for the MaxsonarSerialLV rangefinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:maxsonarseriallv --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:maxsonarseriallv --speedup=1 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 13 diff --git a/libraries/SITL/SIM_RF_NMEA.h b/libraries/SITL/SIM_RF_NMEA.h index d9dbb8079bc3e3..4ba8feaf61244e 100644 --- a/libraries/SITL/SIM_RF_NMEA.h +++ b/libraries/SITL/SIM_RF_NMEA.h @@ -15,7 +15,7 @@ /* Simulator for the NMEA serial rangefinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:nmea --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:nmea --speedup=1 param set SERIAL5_PROTOCOL 9 param set SERIAL5_BAUD 9600 diff --git a/libraries/SITL/SIM_RF_RDS02UF.h b/libraries/SITL/SIM_RF_RDS02UF.h index a96bb9b56564d0..44a387370db6b7 100644 --- a/libraries/SITL/SIM_RF_RDS02UF.h +++ b/libraries/SITL/SIM_RF_RDS02UF.h @@ -15,7 +15,7 @@ /* Simulator for the RDS02UF rangefinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:rds02uf --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:rds02uf --speedup=1 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 36 diff --git a/libraries/SITL/SIM_RF_TeraRanger_Serial.h b/libraries/SITL/SIM_RF_TeraRanger_Serial.h index 314460699fe083..31544f913826a3 100644 --- a/libraries/SITL/SIM_RF_TeraRanger_Serial.h +++ b/libraries/SITL/SIM_RF_TeraRanger_Serial.h @@ -12,7 +12,7 @@ */ /* Simulator for the TeraRanger NEO RangeFinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:teraranger_serial --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:teraranger_serial --speedup=1 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 35 graph RANGEFINDER.distance diff --git a/libraries/SITL/SIM_RF_USD1_v0.h b/libraries/SITL/SIM_RF_USD1_v0.h index 866c5a8ea3f295..7a3498adb64311 100644 --- a/libraries/SITL/SIM_RF_USD1_v0.h +++ b/libraries/SITL/SIM_RF_USD1_v0.h @@ -15,7 +15,7 @@ /* Simulator for the USD1 v0 Serial RangeFinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:USD1_v0 --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:USD1_v0 --speedup=1 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 11 diff --git a/libraries/SITL/SIM_RF_USD1_v1.h b/libraries/SITL/SIM_RF_USD1_v1.h index 2b3b4901d1c22b..d2982e2cb863b8 100644 --- a/libraries/SITL/SIM_RF_USD1_v1.h +++ b/libraries/SITL/SIM_RF_USD1_v1.h @@ -15,7 +15,7 @@ /* Simulator for the USD1 v1 Serial RangeFinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:USD1_v1 --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:USD1_v1 --speedup=1 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 11 diff --git a/libraries/SITL/SIM_RF_Wasp.h b/libraries/SITL/SIM_RF_Wasp.h index e52d9aba989d46..a1e9b37acf5e5f 100644 --- a/libraries/SITL/SIM_RF_Wasp.h +++ b/libraries/SITL/SIM_RF_Wasp.h @@ -15,7 +15,7 @@ /* Simulator for the Wasp serial rangefinder -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:wasp --speedup=1 +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:wasp --speedup=1 param set SERIAL5_PROTOCOL 9 param set RNGFND1_TYPE 18 diff --git a/libraries/SITL/SIM_RichenPower.h b/libraries/SITL/SIM_RichenPower.h index f0d604c60528e3..1fa763fcf2778c 100644 --- a/libraries/SITL/SIM_RichenPower.h +++ b/libraries/SITL/SIM_RichenPower.h @@ -15,7 +15,7 @@ /* Simulator for the RichenPower Hybrid generators -./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --uartF=sim:richenpower --speedup=1 --console +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduCopter -A --serial5=sim:richenpower --speedup=1 --console param set SERIAL5_PROTOCOL 30 param set SERIAL5_BAUD 9600 diff --git a/libraries/SITL/SIM_VectorNav.h b/libraries/SITL/SIM_VectorNav.h index 436e19cd22d0b5..589539e5d9a8f3 100644 --- a/libraries/SITL/SIM_VectorNav.h +++ b/libraries/SITL/SIM_VectorNav.h @@ -20,7 +20,7 @@ AHRS_EKF_TYPE = 11 EAHRS_TYPE=1 - sim_vehicle.py -D --console --map -A --uartF=sim:VectorNav + sim_vehicle.py -D --console --map -A --serial5=sim:VectorNav */ #pragma once diff --git a/libraries/SITL/examples/Airsim/follow-copter.sh b/libraries/SITL/examples/Airsim/follow-copter.sh index 29fe62d0b7b64f..47625999c82c9e 100755 --- a/libraries/SITL/examples/Airsim/follow-copter.sh +++ b/libraries/SITL/examples/Airsim/follow-copter.sh @@ -46,7 +46,7 @@ BASE_DEFAULTS="$ROOTDIR/Tools/autotest/default_params/copter.parm,$ROOTDIR/Tools } # start up main copter in the current directory -$COPTER --model airsim-copter --uartA udpclient:$GCS_IP --uartC mcast:$MCAST_IP_PORT --defaults $BASE_DEFAULTS & +$COPTER --model airsim-copter --serial0 udpclient:$GCS_IP --serial1 mcast:$MCAST_IP_PORT --defaults $BASE_DEFAULTS & # Set number of extra copters to be simulated, change this for increasing the count NCOPTERS="1" @@ -71,7 +71,7 @@ FOLL_SYSID $FOLL_SYSID FOLL_DIST_MAX 1000 EOF pushd copter$i - $COPTER --model airsim-copter --uartA tcp:0 --uartC mcast:$MCAST_IP_PORT --instance $i --defaults $BASE_DEFAULTS,follow.parm & + $COPTER --model airsim-copter --serial0 tcp:0 --serial1 mcast:$MCAST_IP_PORT --instance $i --defaults $BASE_DEFAULTS,follow.parm & popd done wait diff --git a/libraries/SITL/examples/Airsim/multi_vehicle.sh b/libraries/SITL/examples/Airsim/multi_vehicle.sh index 4fdd20301754b8..f02717e6fc3895 100755 --- a/libraries/SITL/examples/Airsim/multi_vehicle.sh +++ b/libraries/SITL/examples/Airsim/multi_vehicle.sh @@ -28,7 +28,7 @@ BASE_DEFAULTS="$ROOTDIR/Tools/autotest/default_params/copter.parm,$ROOTDIR/Tools } # start up main copter in the current directory -$COPTER --model airsim-copter --uartA udpclient:$GCS_IP:14550 --uartB tcp:0 --defaults $BASE_DEFAULTS & +$COPTER --model airsim-copter --serial0 udpclient:$GCS_IP:14550 --serial3 tcp:0 --defaults $BASE_DEFAULTS & # Set number of "extra" copters to be simulated, change this for increasing the count NCOPTERS="1" @@ -49,7 +49,7 @@ SYSID_THISMAV $SYSID EOF pushd copter$i - $COPTER --model airsim-copter --uartA udpclient:$GCS_IP:$UDP_PORT --uartB tcp:$i \ + $COPTER --model airsim-copter --serial0 udpclient:$GCS_IP:$UDP_PORT --serial3 tcp:$i \ --instance $i --defaults $BASE_DEFAULTS,identity.parm & popd done diff --git a/libraries/SITL/examples/Follow/plane_quad.sh b/libraries/SITL/examples/Follow/plane_quad.sh index 49dd4fd02aa46a..171bcdff20cbd6 100755 --- a/libraries/SITL/examples/Follow/plane_quad.sh +++ b/libraries/SITL/examples/Follow/plane_quad.sh @@ -13,14 +13,14 @@ PLANE=$ROOTDIR/build/sitl/bin/arduplane } # setup for either TCP or multicast -#UARTA="tcp:0" -UARTA="mcast:" +#SERIAL0="tcp:0" +SERIAL0="mcast:" PLANE_DEFAULTS="$ROOTDIR/Tools/autotest/models/plane.parm" COPTER_DEFAULTS="$ROOTDIR/Tools/autotest/default_params/copter.parm" mkdir -p swarm/plane swarm/copter -(cd swarm/plane && $PLANE --model plane --uartA $UARTA --defaults $PLANE_DEFAULTS) & +(cd swarm/plane && $PLANE --model plane --serial0 $SERIAL0 --defaults $PLANE_DEFAULTS) & # create default parameter file for the follower cat < swarm/copter/follow.parm @@ -32,5 +32,5 @@ FOLL_SYSID 1 FOLL_DIST_MAX 1000 EOF -(cd swarm/copter && $COPTER --model quad --uartA $UARTA --instance 1 --defaults $COPTER_DEFAULTS,follow.parm) & +(cd swarm/copter && $COPTER --model quad --serial0 $SERIAL0 --instance 1 --defaults $COPTER_DEFAULTS,follow.parm) & wait diff --git a/libraries/SITL/examples/Morse/start_follow.sh b/libraries/SITL/examples/Morse/start_follow.sh index 7e5300fcaa6cc5..e213eaeb8daadf 100755 --- a/libraries/SITL/examples/Morse/start_follow.sh +++ b/libraries/SITL/examples/Morse/start_follow.sh @@ -9,7 +9,7 @@ GCS_IP=192.168.2.48 BASE_DEFAULTS="$ROOTDIR/Tools/autotest/default_params/rover.parm,$ROOTDIR/Tools/autotest/default_params/rover-skid.parm" # start up main rover in the current directory -$ROVER --model morse-skid --uartA udpclient:$GCS_IP --uartC mcast: --defaults $BASE_DEFAULTS & +$ROVER --model morse-skid --serial0 udpclient:$GCS_IP --serial1 mcast: --defaults $BASE_DEFAULTS & # now start 2 rovers to follow the first, using # a separate directory for each to keep the eeprom.bin @@ -37,7 +37,7 @@ FOLL_SYSID $FOLL_SYSID FOLL_DIST_MAX 1000 EOF pushd rov$i - $ROVER --model "morse-skid:127.0.0.1:$port1:$port2" --uartA tcp:0 --uartC mcast: --instance $i --defaults $BASE_DEFAULTS,follow.parm & + $ROVER --model "morse-skid:127.0.0.1:$port1:$port2" --serial0 tcp:0 --serial1 mcast: --instance $i --defaults $BASE_DEFAULTS,follow.parm & popd done wait diff --git a/libraries/SITL/examples/follow-copter.sh b/libraries/SITL/examples/follow-copter.sh index 88067001719521..8dbeebc75f0d68 100755 --- a/libraries/SITL/examples/follow-copter.sh +++ b/libraries/SITL/examples/follow-copter.sh @@ -75,7 +75,7 @@ AUTO_OPTIONS 7 EOF pushd copter1 -$COPTER --model quad --home=$HOMELAT,$HOMELONG,$HOMEALT,0 --uartA udpclient:$GCS_IP --uartC mcast:$MCAST_IP_PORT --defaults $BASE_DEFAULTS,leader.parm & +$COPTER --model quad --home=$HOMELAT,$HOMELONG,$HOMEALT,0 --serial0 udpclient:$GCS_IP --serial1 mcast:$MCAST_IP_PORT --defaults $BASE_DEFAULTS,leader.parm & popd # now start other copters to follow the first, using @@ -103,7 +103,7 @@ EOF pushd copter$i LAT=$(echo "$HOMELAT + 0.0005*$i" | bc -l) LONG=$(echo "$HOMELONG + 0.0005*$i" | bc -l) - $COPTER --model quad --home=$LAT,$LONG,$HOMEALT,0 --uartA tcp:0 --uartC mcast:$MCAST_IP_PORT --instance $i --defaults $BASE_DEFAULTS,follow.parm & + $COPTER --model quad --home=$LAT,$LONG,$HOMEALT,0 --serial0 tcp:0 --serial1 mcast:$MCAST_IP_PORT --instance $i --defaults $BASE_DEFAULTS,follow.parm & popd done wait From de5b46e028379845b96ebe7394e9c58d3d040403 Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Mon, 11 Dec 2023 12:52:03 -0600 Subject: [PATCH 0151/1335] Tools: remove references to legacy UART order Also delete some unused variables and update the completions. --- Tools/autotest/arducopter.py | 29 +++++++++--------- Tools/autotest/arduplane.py | 4 +-- Tools/autotest/pysim/util.py | 2 +- Tools/autotest/rover.py | 4 +-- Tools/autotest/sim_vehicle.py | 17 +++++------ Tools/autotest/vehicle_test_suite.py | 24 +++++++-------- Tools/completion/zsh/_ap_bin | 30 ++++++++++++------- Tools/ros2/README.md | 6 ++-- .../test/ardupilot_dds_tests/conftest.py | 2 +- .../ardupilot_sitl/config/copter_quad.yaml | 2 -- 10 files changed, 63 insertions(+), 57 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 449b09064e06a2..991f088098d9c5 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -3052,7 +3052,7 @@ def VisionPosition(self): """Disable GPS navigation, enable Vicon input.""" # scribble down a location we can set origin to: - self.customise_SITL_commandline(["--uartF=sim:vicon:"]) + self.customise_SITL_commandline(["--serial5=sim:vicon:"]) self.progress("Waiting for location") self.change_mode('LOITER') self.wait_ready_to_arm() @@ -3153,7 +3153,7 @@ def BodyFrameOdom(self): # only tested on this EKF return - self.customise_SITL_commandline(["--uartF=sim:vicon:"]) + self.customise_SITL_commandline(["--serial5=sim:vicon:"]) if self.current_onboard_log_contains_message("XKFD"): raise NotAchievedException("Found unexpected XKFD message") @@ -3293,7 +3293,7 @@ def InvalidJumpTags(self): def GPSViconSwitching(self): """Fly GPS and Vicon switching test""" - self.customise_SITL_commandline(["--uartF=sim:vicon:"]) + self.customise_SITL_commandline(["--serial5=sim:vicon:"]) """Setup parameters including switching to EKF3""" self.context_push() @@ -7193,7 +7193,7 @@ def ProximitySensors(self): self.start_subtest("Testing %s" % name) self.set_parameter("PRX1_TYPE", prx_type) self.customise_SITL_commandline([ - "--uartF=sim:%s:" % name, + "--serial5=sim:%s:" % name, "--home", home_string, ]) self.wait_ready_to_arm() @@ -7630,7 +7630,7 @@ def RichenPower(self): }) self.reboot_sitl() self.set_rc(9, 1000) # remember this is a switch position - stop - self.customise_SITL_commandline(["--uartF=sim:richenpower"]) + self.customise_SITL_commandline(["--serial5=sim:richenpower"]) self.wait_statustext("requested state is not RUN", timeout=60) self.set_message_rate_hz("GENERATOR_STATUS", 10) @@ -7697,7 +7697,7 @@ def run_IE24(self, proto_ver): "LOG_DISARMED": 1, }) - self.customise_SITL_commandline(["--uartF=sim:ie24"]) + self.customise_SITL_commandline(["--serial5=sim:ie24"]) self.start_subtest("Protocol %i: ensure that BATTERY_STATUS for electrical generator message looks right" % proto_ver) self.start_subsubtest("Protocol %i: Checking original voltage (electrical)" % proto_ver) @@ -8182,7 +8182,7 @@ def fly_rangefinder_mavlink(self): "SERIAL5_PROTOCOL": 1, "RNGFND1_TYPE": 10, }) - self.customise_SITL_commandline(['--uartF=sim:rf_mavlink']) + self.customise_SITL_commandline(['--serial5=sim:rf_mavlink']) self.change_mode('GUIDED') self.wait_ready_to_arm() @@ -8329,17 +8329,16 @@ def RangeFinderDrivers(self): drivers = drivers[3:] command_line_args = [] self.context_push() - for (offs, cmdline_argument, serial_num) in [(0, '--uartE', 4), - (1, '--uartF', 5), - (2, '--uartG', 6)]: + for offs in range(3): + serial_num = offs + 4 if len(do_drivers) > offs: if len(do_drivers[offs]) > 2: (sim_name, rngfnd_param_value, kwargs) = do_drivers[offs] else: (sim_name, rngfnd_param_value) = do_drivers[offs] kwargs = {} - command_line_args.append("%s=sim:%s" % - (cmdline_argument, sim_name)) + command_line_args.append("--serial%s=sim:%s" % + (serial_num, sim_name)) sets = { "SERIAL%u_PROTOCOL" % serial_num: 9, # rangefinder "RNGFND%u_TYPE" % (offs+1): rngfnd_param_value, @@ -8380,7 +8379,7 @@ def RangeFinderDriversMaxAlt(self): "WPNAV_SPEED_UP": 1000, # cm/s }) self.customise_SITL_commandline([ - "--uartE=sim:lightwareserial", + "--serial4=sim:lightwareserial", ]) self.takeoff(95, mode='GUIDED', timeout=240, max_err=0.5) self.assert_rangefinder_distance_between(90, 100) @@ -9776,7 +9775,7 @@ def FETtecESC(self): "SERVO8_FUNCTION": 36, "SIM_ESC_TELEM": 0, }) - self.customise_SITL_commandline(["--uartF=sim:fetteconewireesc"]) + self.customise_SITL_commandline(["--serial5=sim:fetteconewireesc"]) self.FETtecESC_safety_switch() self.FETtecESC_esc_power_checks() self.FETtecESC_btw_mask_checks() @@ -10251,7 +10250,7 @@ def test_rplidar(self, sim_device_name, expected_distances): "PRX1_TYPE": 5, }) self.customise_SITL_commandline([ - "--uartF=sim:%s:" % sim_device_name, + "--serial5=sim:%s:" % sim_device_name, "--home", "51.8752066,14.6487840,0,0", # SITL has "posts" here ]) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index 09041b17dab928..eb84112528a9da 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -3160,7 +3160,7 @@ def TerrainLoiter(self): def fly_external_AHRS(self, sim, eahrs_type, mission): """Fly with external AHRS (VectorNav)""" - self.customise_SITL_commandline(["--uartE=sim:%s" % sim]) + self.customise_SITL_commandline(["--serial4=sim:%s" % sim]) self.set_parameters({ "EAHRS_TYPE": eahrs_type, @@ -4218,7 +4218,7 @@ def EFITest(self, efi_type, name, sim_name, check_fuel_flow=True): }) self.customise_SITL_commandline( - ["--uartF=sim:%s" % sim_name, + ["--serial5=sim:%s" % sim_name, ], ) self.wait_ready_to_arm() diff --git a/Tools/autotest/pysim/util.py b/Tools/autotest/pysim/util.py index beed41e777c75c..fb20b0c61a942a 100644 --- a/Tools/autotest/pysim/util.py +++ b/Tools/autotest/pysim/util.py @@ -539,7 +539,7 @@ def start_SITL(binary, if unhide_parameters: cmd.extend(['--unhide-groups']) # somewhere for MAVProxy to connect to: - cmd.append('--uartC=tcp:2') + cmd.append('--serial1=tcp:2') if not enable_fgview_output: cmd.append("--disable-fgview") diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index f1eeb76c618015..2f0870b351c16e 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -6114,14 +6114,14 @@ def DepthFinder(self): '''Test mulitple depthfinders for boats''' # Setup rangefinders self.customise_SITL_commandline([ - "--uartH=sim:nmea", # NMEA Rangefinder + "--serial7=sim:nmea", # NMEA Rangefinder ]) # RANGEFINDER_INSTANCES = [0, 2, 5] self.set_parameters({ "RNGFND1_TYPE" : 17, # NMEA must attach uart to SITL "RNGFND1_ORIENT" : 25, # Set to downward facing - "SERIAL7_PROTOCOL" : 9, # Rangefinder on uartH + "SERIAL7_PROTOCOL" : 9, # Rangefinder on serial7 "SERIAL7_BAUD" : 9600, # Rangefinder specific baudrate "RNGFND3_TYPE" : 2, # MaxbotixI2C diff --git a/Tools/autotest/sim_vehicle.py b/Tools/autotest/sim_vehicle.py index 065b5265c1c53f..5a0ccb5c5ddf3b 100755 --- a/Tools/autotest/sim_vehicle.py +++ b/Tools/autotest/sim_vehicle.py @@ -635,13 +635,13 @@ def run_in_terminal_window(name, cmd, **kw): subprocess.Popen(runme, **kw) -tracker_uarta = None # blemish +tracker_serial0 = None # blemish def start_antenna_tracker(opts): """Compile and run the AntennaTracker, add tracker to mavproxy""" - global tracker_uarta + global tracker_serial0 progress("Preparing antenna tracker") tracker_home = find_location_by_name(opts.tracker_location) vehicledir = os.path.join(autotest_dir, "../../" + "AntennaTracker") @@ -652,7 +652,7 @@ def start_antenna_tracker(opts): tracker_instance = 1 oldpwd = os.getcwd() os.chdir(vehicledir) - tracker_uarta = "tcp:127.0.0.1:" + str(5760 + 10 * tracker_instance) + tracker_serial0 = "tcp:127.0.0.1:" + str(5760 + 10 * tracker_instance) binary_basedir = "build/sitl" exe = os.path.join(root_dir, binary_basedir, @@ -669,7 +669,6 @@ def start_antenna_tracker(opts): def start_CAN_Periph(opts, frame_info): """Compile and run the sitl_periph""" - global can_uarta progress("Preparing sitl_periph_gps") options = vinfo.options["sitl_periph_gps"]['frames']['gps'] defaults_path = frame_info.get('periph_params_filename', None) @@ -838,9 +837,9 @@ def start_vehicle(binary, opts, stuff, spawns=None): if spawns is not None: c.extend(["--home", spawns[i]]) if opts.mcast: - c.extend(["--uartA", "mcast:"]) + c.extend(["--serial0", "mcast:"]) elif opts.udp: - c.extend(["--uartA", "udpclient:127.0.0.1:" + str(5760+i*10)]) + c.extend(["--serial0", "udpclient:127.0.0.1:" + str(5760+i*10)]) if opts.auto_sysid: if opts.sysid is not None: raise ValueError("Can't use auto-sysid and sysid together") @@ -901,12 +900,12 @@ def start_mavproxy(opts, stuff): if opts.tracker: cmd.extend(["--load-module", "tracker"]) - global tracker_uarta - # tracker_uarta is set when we start the tracker... + global tracker_serial0 + # tracker_serial0 is set when we start the tracker... extra_cmd += ("module load map;" "tracker set port %s; " "tracker start; " - "tracker arm;" % (tracker_uarta,)) + "tracker arm;" % (tracker_serial0,)) if opts.mavlink_gimbal: cmd.extend(["--load-module", "gimbal"]) diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index b94581334ae6fb..04ce66a804d472 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -2942,7 +2942,7 @@ def customise_SITL_commandline(self, wipe=False, set_streamrate_callback=None, binary=None): - '''customisations could be "--uartF=sim:nmea" ''' + '''customisations could be "--serial5=sim:nmea" ''' self.contexts[-1].sitl_commandline_customised = True self.mav.close() self.stop_SITL() @@ -11939,8 +11939,8 @@ def NMEAOutput(self): self.set_parameter("GPS_TYPE2", 5) # GPS2 is NMEA port = self.spare_network_port() self.customise_SITL_commandline([ - "--uartE=tcp:%u" % port, # GPS2 is NMEA.... - "--uartF=tcpclient:127.0.0.1:%u" % port, # serial5 spews to localhost port + "--serial4=tcp:%u" % port, # GPS2 is NMEA.... + "--serial5=tcpclient:127.0.0.1:%u" % port, # serial5 spews to localhost port ]) self.do_timesync_roundtrip() self.wait_gps_fix_type_gte(3) @@ -12556,7 +12556,7 @@ def FRSkyPassThroughStatustext(self): }) port = self.spare_network_port() self.customise_SITL_commandline([ - "--uartF=tcp:%u" % port # serial5 spews to localhost port + "--serial5=tcp:%u" % port # serial5 spews to localhost port ]) frsky = FRSkyPassThrough(("127.0.0.1", port), get_time=self.get_sim_time_cached) @@ -12647,7 +12647,7 @@ def FRSkyPassThroughSensorIDs(self): }) port = self.spare_network_port() self.customise_SITL_commandline([ - "--uartF=tcp:%u" % port # serial5 spews to localhost port + "--serial5=tcp:%u" % port # serial5 spews to localhost port ]) frsky = FRSkyPassThrough(("127.0.0.1", port), get_time=self.get_sim_time_cached) @@ -12802,7 +12802,7 @@ def FRSkyMAVlite(self): self.set_parameter("SERIAL5_PROTOCOL", 10) # serial5 is FRSky passthrough port = self.spare_network_port() self.customise_SITL_commandline([ - "--uartF=tcp:%u" % port # serial5 spews to localhost port + "--serial5=tcp:%u" % port # serial5 spews to localhost port ]) frsky = FRSkyPassThrough(("127.0.0.1", port)) frsky.connect() @@ -13077,7 +13077,7 @@ def FRSkySPort(self): self.set_parameter("RPM1_TYPE", 10) # enable SITL RPM sensor port = self.spare_network_port() self.customise_SITL_commandline([ - "--uartF=tcp:%u" % port # serial5 spews to localhost port + "--serial5=tcp:%u" % port # serial5 spews to localhost port ]) frsky = FRSkySPort(("127.0.0.1", port), verbose=True) self.wait_ready_to_arm() @@ -13150,7 +13150,7 @@ def FRSkyD(self): self.set_parameter("SERIAL5_PROTOCOL", 3) # serial5 is FRSky output port = self.spare_network_port() self.customise_SITL_commandline([ - "--uartF=tcp:%u" % port # serial5 spews to localhost port + "--serial5=tcp:%u" % port # serial5 spews to localhost port ]) frsky = FRSkyD(("127.0.0.1", port)) self.wait_ready_to_arm() @@ -13269,7 +13269,7 @@ def LTM(self): self.set_parameter("SERIAL5_PROTOCOL", 25) # serial5 is LTM output port = self.spare_network_port() self.customise_SITL_commandline([ - "--uartF=tcp:%u" % port # serial5 spews to localhost port + "--serial5=tcp:%u" % port # serial5 spews to localhost port ]) ltm = LTM(("127.0.0.1", port)) self.wait_ready_to_arm() @@ -13312,7 +13312,7 @@ def DEVO(self): self.set_parameter("SERIAL5_PROTOCOL", 17) # serial5 is DEVO output port = self.spare_network_port() self.customise_SITL_commandline([ - "--uartF=tcp:%u" % port # serial5 spews to localhost port + "--serial5=tcp:%u" % port # serial5 spews to localhost port ]) devo = DEVO(("127.0.0.1", port)) self.wait_ready_to_arm() @@ -13385,7 +13385,7 @@ def MSP_DJI(self): self.set_parameter("MSP_OPTIONS", 1) # telemetry (unpolled) mode port = self.spare_network_port() self.customise_SITL_commandline([ - "--uartF=tcp:%u" % port # serial5 spews to localhost port + "--serial5=tcp:%u" % port # serial5 spews to localhost port ]) msp = MSP_DJI(("127.0.0.1", port)) self.wait_ready_to_arm() @@ -13413,7 +13413,7 @@ def CRSF(self): self.set_parameter("SERIAL5_PROTOCOL", 23) # serial5 is RCIN input port = self.spare_network_port() self.customise_SITL_commandline([ - "--uartF=tcp:%u" % port # serial5 reads from to localhost port + "--serial5=tcp:%u" % port # serial5 reads from to localhost port ]) crsf = CRSF(("127.0.0.1", port)) crsf.connect() diff --git a/Tools/completion/zsh/_ap_bin b/Tools/completion/zsh/_ap_bin index cc5b7417f63657..67e1cdd867e01e 100644 --- a/Tools/completion/zsh/_ap_bin +++ b/Tools/completion/zsh/_ap_bin @@ -21,16 +21,26 @@ _ap_bin() { '--gimbal[enable simulated MAVLink gimbal]' \ '--autotest-dir[set directory for additional files]:DIR:' \ '--defaults[set path to defaults file]:PATH:' \ - '--uartA[set device string for UARTA]:DEVICE:' \ - '--uartB[set device string for UARTB]:DEVICE:' \ - '--uartC[set device string for UARTC]:DEVICE:' \ - '--uartD[set device string for UARTD]:DEVICE:' \ - '--uartE[set device string for UARTE]:DEVICE:' \ - '--uartF[set device string for UARTF]:DEVICE:' \ - '--uartG[set device string for UARTG]:DEVICE:' \ - '--uartH[set device string for UARTH]:DEVICE:' \ - '--uartI[set device string for UARTI]:DEVICE:' \ - '--uartJ[set device string for UARTJ]:DEVICE:' \ + '--uartA[set device string for SERIAL0]:DEVICE:' \ + '--uartC[set device string for SERIAL1]:DEVICE:' \ + '--uartD[set device string for SERIAL2]:DEVICE:' \ + '--uartB[set device string for SERIAL3]:DEVICE:' \ + '--uartE[set device string for SERIAL4]:DEVICE:' \ + '--uartF[set device string for SERIAL5]:DEVICE:' \ + '--uartG[set device string for SERIAL6]:DEVICE:' \ + '--uartH[set device string for SERIAL7]:DEVICE:' \ + '--uartI[set device string for SERIAL8]:DEVICE:' \ + '--uartJ[set device string for SERIAL9]:DEVICE:' \ + '--serial0[set device string for SERIAL0]:DEVICE:' \ + '--serial1[set device string for SERIAL1]:DEVICE:' \ + '--serial2[set device string for SERIAL2]:DEVICE:' \ + '--serial3[set device string for SERIAL3]:DEVICE:' \ + '--serial4[set device string for SERIAL4]:DEVICE:' \ + '--serial5[set device string for SERIAL5]:DEVICE:' \ + '--serial6[set device string for SERIAL6]:DEVICE:' \ + '--serial7[set device string for SERIAL7]:DEVICE:' \ + '--serial8[set device string for SERIAL8]:DEVICE:' \ + '--serial9[set device string for SERIAL9]:DEVICE:' \ '--rtscts[enable rtscts on serial ports (default false)]' \ '--base-port[set port num for base port(default 5670) must be before -I option]:PORT:' \ '--rc-in-port[set port num for rc in]:PORT:' \ diff --git a/Tools/ros2/README.md b/Tools/ros2/README.md index bdd055e3f13291..9832e412f999d5 100644 --- a/Tools/ros2/README.md +++ b/Tools/ros2/README.md @@ -187,7 +187,7 @@ ros2 run micro_ros_agent micro_ros_agent serial --baudrate 115200 --dev ./dev/tt ``` ```bash -arducopter --synthetic-clock --wipe --model quad --speedup 1 --slave 0 --instance 0 --uartC uart:./dev/ttyROS1 --defaults $(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/copter.parm,$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/dds_serial.parm --sim-address 127.0.0.1 +arducopter --synthetic-clock --wipe --model quad --speedup 1 --slave 0 --instance 0 --serial1 uart:./dev/ttyROS1 --defaults $(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/copter.parm,$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/dds_serial.parm --sim-address 127.0.0.1 ``` ```bash @@ -205,7 +205,7 @@ ros2 launch ardupilot_sitl micro_ros_agent.launch.py transport:=serial refs:=$(r ``` ```bash -ros2 launch ardupilot_sitl sitl.launch.py synthetic_clock:=True wipe:=True model:=quad speedup:=1 slave:=0 instance:=0 uartC:=uart:./dev/ttyROS1 defaults:=$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/copter.parm,$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/dds_serial.parm sim_address:=127.0.0.1 +ros2 launch ardupilot_sitl sitl.launch.py synthetic_clock:=True wipe:=True model:=quad speedup:=1 slave:=0 instance:=0 serial1:=uart:./dev/ttyROS1 defaults:=$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/copter.parm,$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/dds_serial.parm sim_address:=127.0.0.1 ``` ```bash @@ -231,7 +231,7 @@ model:=quad \ speedup:=1 \ slave:=0 \ instance:=0 \ -uartC:=uart:./dev/ttyROS1 \ +serial1:=uart:./dev/ttyROS1 \ defaults:=$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/copter.parm,$(ros2 pkg prefix ardupilot_sitl)/share/ardupilot_sitl/config/default_params/dds_serial.parm \ sim_address:=127.0.0.1 \ \ diff --git a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/conftest.py b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/conftest.py index 66a71779fa28ff..f1a1a4532ea243 100644 --- a/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/conftest.py +++ b/Tools/ros2/ardupilot_dds_tests/test/ardupilot_dds_tests/conftest.py @@ -145,7 +145,7 @@ def sitl_copter_dds_serial(device_dir, virtual_ports, micro_ros_agent_serial, ma "speedup": "10", "slave": "0", "instance": "0", - "uartC": f"uart:{str(tty1)}", + "serial1": f"uart:{str(tty1)}", "defaults": str( Path( get_package_share_directory("ardupilot_sitl"), diff --git a/Tools/ros2/ardupilot_sitl/config/copter_quad.yaml b/Tools/ros2/ardupilot_sitl/config/copter_quad.yaml index 02ad121f3a9c95..9fa079957a9f8a 100644 --- a/Tools/ros2/ardupilot_sitl/config/copter_quad.yaml +++ b/Tools/ros2/ardupilot_sitl/config/copter_quad.yaml @@ -12,8 +12,6 @@ # rate: 400 # console: true # home: [lat, lon, alt, yaw] - # uartA: /dev/tty0 - # uartB: /dev/tty1 # serial0: /dev/usb0 # serial1: /dev/usb1 # sim_port_in: 5501 From a82d051140528bb0f2b7df58e69c7453c93bd1a6 Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Mon, 11 Dec 2023 10:55:07 -0600 Subject: [PATCH 0152/1335] Tracker: remove references to legacy UART order --- AntennaTracker/Parameters.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/AntennaTracker/Parameters.h b/AntennaTracker/Parameters.h index 972c36f52505e8..e43876f8ded8d5 100644 --- a/AntennaTracker/Parameters.h +++ b/AntennaTracker/Parameters.h @@ -44,8 +44,8 @@ class Parameters { k_param_format_version = 0, k_param_software_type, // deprecated - k_param_gcs0 = 100, // stream rates for uartA - k_param_gcs1, // stream rates for uartC + k_param_gcs0 = 100, // stream rates for SERIAL0 + k_param_gcs1, // stream rates for SERIAL1 k_param_sysid_this_mav, k_param_sysid_my_gcs, k_param_serial0_baud, // deprecated @@ -60,7 +60,7 @@ class Parameters { k_param_sitl, k_param_pidPitch_old, // deprecated k_param_pidYaw_old, // deprecated - k_param_gcs2, // stream rates for uartD + k_param_gcs2, // stream rates for SERIAL2 k_param_serial2_baud, // deprecated k_param_yaw_slew_time, From f20893259d28c48550e3ef5498c4c4cd649c3158 Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Mon, 11 Dec 2023 10:56:09 -0600 Subject: [PATCH 0153/1335] Plane: remove references to legacy UART order --- ArduPlane/Parameters.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index 7210bfe7771267..2a9a5ef0719868 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -159,14 +159,14 @@ class Parameters { // 110: Telemetry control // - k_param_gcs0 = 110, // stream rates for uartA - k_param_gcs1, // stream rates for uartC + k_param_gcs0 = 110, // stream rates for SERIAL0 + k_param_gcs1, // stream rates for SERIAL1 k_param_sysid_this_mav, k_param_sysid_my_gcs, k_param_serial1_baud_old, // deprecated k_param_telem_delay, k_param_serial0_baud_old, // deprecated - k_param_gcs2, // stream rates for uartD + k_param_gcs2, // stream rates for SERIAL2 k_param_serial2_baud_old, // deprecated k_param_serial2_protocol, // deprecated From 93724d9e757aebab71eef44eab35c7daf139b88c Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Mon, 11 Dec 2023 10:57:00 -0600 Subject: [PATCH 0154/1335] Rover: remove references to legacy UART order --- Rover/Parameters.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Rover/Parameters.h b/Rover/Parameters.h index 035d16f4d0ffb4..b4b7b019845cd8 100644 --- a/Rover/Parameters.h +++ b/Rover/Parameters.h @@ -79,15 +79,15 @@ class Parameters { // 110: Telemetry control // - k_param_gcs0 = 110, // stream rates for uartA - k_param_gcs1, // stream rates for uartC + k_param_gcs0 = 110, // stream rates for SERIAL0 + k_param_gcs1, // stream rates for SERIAL1 k_param_sysid_this_mav, k_param_sysid_my_gcs, k_param_serial0_baud_old, // unused k_param_serial1_baud_old, // unused k_param_telem_delay, k_param_skip_gyro_cal, // unused - k_param_gcs2, // stream rates for uartD + k_param_gcs2, // stream rates for SERIAL2 k_param_serial2_baud_old, // unused k_param_serial2_protocol, // deprecated, can be deleted k_param_serial_manager, // serial manager library From 94888822be838df27612cf6c8e1b3abd89da694a Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Mon, 11 Dec 2023 10:59:20 -0600 Subject: [PATCH 0155/1335] GCS_MAVLink: correct comment about stream array --- libraries/GCS_MAVLink/GCS_MAVLink.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/GCS_MAVLink/GCS_MAVLink.h b/libraries/GCS_MAVLink/GCS_MAVLink.h index 26a30d068d312c..36e0cd3fb0851b 100644 --- a/libraries/GCS_MAVLink/GCS_MAVLink.h +++ b/libraries/GCS_MAVLink/GCS_MAVLink.h @@ -43,7 +43,7 @@ #include "include/mavlink/v2.0/mavlink_types.h" -/// MAVLink stream used for uartA +/// MAVLink streams used for each telemetry port extern AP_HAL::UARTDriver *mavlink_comm_port[MAVLINK_COMM_NUM_BUFFERS]; extern bool gcs_alternative_active[MAVLINK_COMM_NUM_BUFFERS]; From 8ee9dd13bedffb7b52648fe3c172b0d7b81f2007 Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Mon, 11 Dec 2023 12:51:04 -0600 Subject: [PATCH 0156/1335] AP_Scripting: remove references to legacy UART order --- .../applets/Aerobatics/FixedWing/dual_plane.sh | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Scripting/applets/Aerobatics/FixedWing/dual_plane.sh b/libraries/AP_Scripting/applets/Aerobatics/FixedWing/dual_plane.sh index 64704f9cc70231..fa67876008e8e8 100755 --- a/libraries/AP_Scripting/applets/Aerobatics/FixedWing/dual_plane.sh +++ b/libraries/AP_Scripting/applets/Aerobatics/FixedWing/dual_plane.sh @@ -15,12 +15,12 @@ LOC2="-35.36274593,149.16516256,585,353.8" } # setup multicast -#UARTA="tcp:0" -UARTA="mcast:" +#SERIAL0="tcp:0" +SERIAL0="mcast:" PLANE_DEFAULTS="$ROOTDIR/Tools/autotest/models/plane-3d.parm" -(cd ArduPlane/AeroBatics1 && $PLANE --instance 1 --home $LOC1 --model plane-3d --uartA $UARTA --defaults $PLANE_DEFAULTS) & -(cd ArduPlane/AeroBatics2 && $PLANE --instance 2 --home $LOC2 --model plane-3d --uartA $UARTA --defaults $PLANE_DEFAULTS) & +(cd ArduPlane/AeroBatics1 && $PLANE --instance 1 --home $LOC1 --model plane-3d --serial0 $SERIAL0 --defaults $PLANE_DEFAULTS) & +(cd ArduPlane/AeroBatics2 && $PLANE --instance 2 --home $LOC2 --model plane-3d --serial0 $SERIAL0 --defaults $PLANE_DEFAULTS) & wait From f0a92889fa0ffb565690f5e27a1eab0b2546f875 Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Mon, 11 Dec 2023 13:21:14 -0600 Subject: [PATCH 0157/1335] AP_DDS: remove references to legacy UART order --- libraries/AP_DDS/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_DDS/README.md b/libraries/AP_DDS/README.md index 1af0af6f6001a1..bbbe091d9412d6 100644 --- a/libraries/AP_DDS/README.md +++ b/libraries/AP_DDS/README.md @@ -189,7 +189,7 @@ Next, follow the associated section for your chosen transport, and finally you c - Run SITL (remember to kill any terminals running ardupilot SITL beforehand) ```console # assuming we are using /dev/pts/1 for Ardupilot SITL - sim_vehicle.py -v ArduPlane -DG --console --enable-dds -A "--uartC=uart:/dev/pts/1" + sim_vehicle.py -v ArduPlane -DG --console --enable-dds -A "--serial1=uart:/dev/pts/1" ``` ## Use ROS 2 CLI From ae7170501d249439501daa5411ba592487854a99 Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Mon, 11 Dec 2023 13:32:53 -0600 Subject: [PATCH 0158/1335] AP_FETtecOneWire: remove references to legacy UART order --- libraries/AP_FETtecOneWire/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_FETtecOneWire/README.md b/libraries/AP_FETtecOneWire/README.md index 482670b0fbf832..7f0d2549f02f44 100644 --- a/libraries/AP_FETtecOneWire/README.md +++ b/libraries/AP_FETtecOneWire/README.md @@ -30,7 +30,7 @@ For purchase, connection and configuration information please see the [ArduPilot - check that the ESCs are periodically sending telemetry data - re-init and configure an ESC(s) if not armed (motors not spinning) when - telemetry communication with the ESC(s) is lost -- adds a serial simulator (--uartF=sim:fetteconewireesc) of FETtec OneWire ESCs +- adds a serial simulator (--serial5=sim:fetteconewireesc) of FETtec OneWire ESCs - adds autotest (using the simulator) to: - simulate telemetry voltage, current, temperature, RPM data using SITL internal variables - test the safety switch functionality From cc5b095d59f6044adeb54460eca31d00031322dc Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Mon, 11 Dec 2023 13:03:32 -0600 Subject: [PATCH 0159/1335] AP_SerialManager: clarify comment regarding legacy UART order --- libraries/AP_SerialManager/AP_SerialManager_config.h | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/libraries/AP_SerialManager/AP_SerialManager_config.h b/libraries/AP_SerialManager/AP_SerialManager_config.h index 801b52a163ae0a..386d15dbfbc4e7 100644 --- a/libraries/AP_SerialManager/AP_SerialManager_config.h +++ b/libraries/AP_SerialManager/AP_SerialManager_config.h @@ -27,8 +27,7 @@ #if HAL_UART_NUM_SERIAL_PORTS >= 4 #define SERIALMANAGER_NUM_PORTS HAL_UART_NUM_SERIAL_PORTS #else -// we need a minimum of 4 to allow for a GPS due to the odd ordering -// of hal.uartB as SERIAL3 +// we want a minimum of 4 as the default GPS port is SERIAL3 #define SERIALMANAGER_NUM_PORTS 4 #endif #else From 14180b5b93843ac7d5a7c926458392ff5ac2dec0 Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Tue, 12 Dec 2023 11:24:53 -0600 Subject: [PATCH 0160/1335] AP_HAL_SITL: deprecate and warn on legacy --uartX option use --- Tools/completion/zsh/_ap_bin | 20 ++++---- libraries/AP_HAL_SITL/SITL_cmdline.cpp | 71 ++++++++++++++++++-------- 2 files changed, 61 insertions(+), 30 deletions(-) diff --git a/Tools/completion/zsh/_ap_bin b/Tools/completion/zsh/_ap_bin index 67e1cdd867e01e..87352789163701 100644 --- a/Tools/completion/zsh/_ap_bin +++ b/Tools/completion/zsh/_ap_bin @@ -21,16 +21,16 @@ _ap_bin() { '--gimbal[enable simulated MAVLink gimbal]' \ '--autotest-dir[set directory for additional files]:DIR:' \ '--defaults[set path to defaults file]:PATH:' \ - '--uartA[set device string for SERIAL0]:DEVICE:' \ - '--uartC[set device string for SERIAL1]:DEVICE:' \ - '--uartD[set device string for SERIAL2]:DEVICE:' \ - '--uartB[set device string for SERIAL3]:DEVICE:' \ - '--uartE[set device string for SERIAL4]:DEVICE:' \ - '--uartF[set device string for SERIAL5]:DEVICE:' \ - '--uartG[set device string for SERIAL6]:DEVICE:' \ - '--uartH[set device string for SERIAL7]:DEVICE:' \ - '--uartI[set device string for SERIAL8]:DEVICE:' \ - '--uartJ[set device string for SERIAL9]:DEVICE:' \ + '--uartA[(deprecated) set device string for SERIAL0]:DEVICE:' \ + '--uartC[(deprecated) set device string for SERIAL1]:DEVICE:' \ + '--uartD[(deprecated) set device string for SERIAL2]:DEVICE:' \ + '--uartB[(deprecated) set device string for SERIAL3]:DEVICE:' \ + '--uartE[(deprecated) set device string for SERIAL4]:DEVICE:' \ + '--uartF[(deprecated) set device string for SERIAL5]:DEVICE:' \ + '--uartG[(deprecated) set device string for SERIAL6]:DEVICE:' \ + '--uartH[(deprecated) set device string for SERIAL7]:DEVICE:' \ + '--uartI[(deprecated) set device string for SERIAL8]:DEVICE:' \ + '--uartJ[(deprecated) set device string for SERIAL9]:DEVICE:' \ '--serial0[set device string for SERIAL0]:DEVICE:' \ '--serial1[set device string for SERIAL1]:DEVICE:' \ '--serial2[set device string for SERIAL2]:DEVICE:' \ diff --git a/libraries/AP_HAL_SITL/SITL_cmdline.cpp b/libraries/AP_HAL_SITL/SITL_cmdline.cpp index 5ca530e38b0727..1daa760e8526ca 100644 --- a/libraries/AP_HAL_SITL/SITL_cmdline.cpp +++ b/libraries/AP_HAL_SITL/SITL_cmdline.cpp @@ -92,16 +92,16 @@ void SITL_State::_usage(void) "\t--gimbal enable simulated MAVLink gimbal\n" "\t--autotest-dir DIR set directory for additional files\n" "\t--defaults path set path to defaults file\n" - "\t--uartA device set device string for SERIAL0\n" - "\t--uartB device set device string for SERIAL3\n" // ordering captures the historical use of uartB as SERIAL3 - "\t--uartC device set device string for SERIAL1\n" - "\t--uartD device set device string for SERIAL2\n" - "\t--uartE device set device string for SERIAL4\n" - "\t--uartF device set device string for SERIAL5\n" - "\t--uartG device set device string for SERIAL6\n" - "\t--uartH device set device string for SERIAL7\n" - "\t--uartI device set device string for SERIAL8\n" - "\t--uartJ device set device string for SERIAL9\n" + "\t--uartA device (deprecated) set device string for SERIAL0\n" + "\t--uartC device (deprecated) set device string for SERIAL1\n" // ordering captures the historical use of uartB as SERIAL3 + "\t--uartD device (deprecated) set device string for SERIAL2\n" + "\t--uartB device (deprecated) set device string for SERIAL3\n" + "\t--uartE device (deprecated) set device string for SERIAL4\n" + "\t--uartF device (deprecated) set device string for SERIAL5\n" + "\t--uartG device (deprecated) set device string for SERIAL6\n" + "\t--uartH device (deprecated) set device string for SERIAL7\n" + "\t--uartI device (deprecated) set device string for SERIAL8\n" + "\t--uartJ device (deprecated) set device string for SERIAL9\n" "\t--serial0 device set device string for SERIAL0\n" "\t--serial1 device set device string for SERIAL1\n" "\t--serial2 device set device string for SERIAL2\n" @@ -246,6 +246,16 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) CMDLINE_FGVIEW, CMDLINE_AUTOTESTDIR, CMDLINE_DEFAULTS, + CMDLINE_UARTA, // must be in A-J order and numbered consecutively + CMDLINE_UARTB, + CMDLINE_UARTC, + CMDLINE_UARTD, + CMDLINE_UARTE, + CMDLINE_UARTF, + CMDLINE_UARTG, + CMDLINE_UARTH, + CMDLINE_UARTI, + CMDLINE_UARTJ, CMDLINE_SERIAL0, // must be in 0-9 order and numbered consecutively CMDLINE_SERIAL1, CMDLINE_SERIAL2, @@ -295,16 +305,16 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) {"disable-fgview", false, 0, CMDLINE_FGVIEW}, {"autotest-dir", true, 0, CMDLINE_AUTOTESTDIR}, {"defaults", true, 0, CMDLINE_DEFAULTS}, - {"uartA", true, 0, CMDLINE_SERIAL0}, - {"uartB", true, 0, CMDLINE_SERIAL3}, // ordering captures the historical use of uartB as SERIAL3 - {"uartC", true, 0, CMDLINE_SERIAL1}, - {"uartD", true, 0, CMDLINE_SERIAL2}, - {"uartE", true, 0, CMDLINE_SERIAL4}, - {"uartF", true, 0, CMDLINE_SERIAL5}, - {"uartG", true, 0, CMDLINE_SERIAL6}, - {"uartH", true, 0, CMDLINE_SERIAL7}, - {"uartI", true, 0, CMDLINE_SERIAL8}, - {"uartJ", true, 0, CMDLINE_SERIAL9}, + {"uartA", true, 0, CMDLINE_UARTA}, + {"uartB", true, 0, CMDLINE_UARTB}, + {"uartC", true, 0, CMDLINE_UARTC}, + {"uartD", true, 0, CMDLINE_UARTD}, + {"uartE", true, 0, CMDLINE_UARTE}, + {"uartF", true, 0, CMDLINE_UARTF}, + {"uartG", true, 0, CMDLINE_UARTG}, + {"uartH", true, 0, CMDLINE_UARTH}, + {"uartI", true, 0, CMDLINE_UARTI}, + {"uartJ", true, 0, CMDLINE_UARTJ}, {"serial0", true, 0, CMDLINE_SERIAL0}, {"serial1", true, 0, CMDLINE_SERIAL1}, {"serial2", true, 0, CMDLINE_SERIAL2}, @@ -439,6 +449,27 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) case CMDLINE_DEFAULTS: defaults_path = strdup(gopt.optarg); break; + case CMDLINE_UARTA: + case CMDLINE_UARTB: + case CMDLINE_UARTC: + case CMDLINE_UARTD: + case CMDLINE_UARTE: + case CMDLINE_UARTF: + case CMDLINE_UARTG: + case CMDLINE_UARTH: + case CMDLINE_UARTI: + case CMDLINE_UARTJ: { + int uart_idx = opt - CMDLINE_UARTA; + // ordering captures the historical use of uartB as SERIAL3 + static const uint8_t mapping[] = { 0, 3, 1, 2, 4, 5, 6, 7, 8, 9 }; + int serial_idx = mapping[uart_idx]; + char uart_letter = (char)(uart_idx)+'A'; + printf("WARNING: deprecated option --uart%c will be removed in a " + "future release. Use --serial%d instead.\n", + uart_letter, serial_idx); + _serial_path[serial_idx] = gopt.optarg; + break; + } case CMDLINE_SERIAL0: case CMDLINE_SERIAL1: case CMDLINE_SERIAL2: From e460a19b1750049fa527706cdbbb84fb45d5223a Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Tue, 12 Dec 2023 11:43:50 -0600 Subject: [PATCH 0161/1335] AP_HAL_Linux: deprecate and warn on legacy --uartX option use --- libraries/AP_HAL_Linux/HAL_Linux_Class.cpp | 96 ++++++++++++++-------- 1 file changed, 62 insertions(+), 34 deletions(-) diff --git a/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp b/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp index f51d8c4331a9d1..d89296b6a0feca 100644 --- a/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp +++ b/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp @@ -87,6 +87,19 @@ static SPIUARTDriver serial3Driver; static UARTDriver serial3Driver(false); #endif +static UARTDriver* serialDrivers[] = { + &serial0Driver, + &serial1Driver, + &serial2Driver, + &serial3Driver, + &serial4Driver, + &serial5Driver, + &serial6Driver, + &serial7Driver, + &serial8Driver, + &serial9Driver, +}; + #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_NAVIO || \ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_ERLEBRAIN2 || \ CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BH || \ @@ -287,9 +300,9 @@ void _usage(void) printf("\tserial (0 through 9 available):\n"); printf("\t --serial0 /dev/ttyO4\n"); printf("\t --serial3 /dev/ttyS1\n"); - printf("\tlegacy UART options still work, their mappings are:\n"); + printf("\tlegacy UART options are deprecated, their mappings are:\n"); printf("\t -A/--uartA is SERIAL0\n"); - printf("\t -C/--uartC is SERIAL1\n"); + printf("\t -C/--uartC is SERIAL1\n"); // ordering captures the historical use of uartB as SERIAL3 printf("\t -D/--uartD is SERIAL2\n"); printf("\t -B/--uartB is SERIAL3\n"); printf("\t -E/--uartE is SERIAL4\n"); @@ -331,28 +344,41 @@ void HAL_Linux::run(int argc, char* const argv[], Callbacks* callbacks) const const char *module_path = AP_MODULE_DEFAULT_DIRECTORY; #endif + enum long_options { + CMDLINE_SERIAL0 = 1, // must be in 0-9 order and numbered consecutively + CMDLINE_SERIAL1, + CMDLINE_SERIAL2, + CMDLINE_SERIAL3, + CMDLINE_SERIAL4, + CMDLINE_SERIAL5, + CMDLINE_SERIAL6, + CMDLINE_SERIAL7, + CMDLINE_SERIAL8, + CMDLINE_SERIAL9, + }; + int opt; const struct GetOptLong::option options[] = { {"uartA", true, 0, 'A'}, - {"serial0", true, 0, 'A'}, - {"uartC", true, 0, 'C'}, // ordering captures the historical use of uartB as SERIAL3 - {"serial1", true, 0, 'C'}, - {"uartD", true, 0, 'D'}, - {"serial2", true, 0, 'D'}, {"uartB", true, 0, 'B'}, - {"serial3", true, 0, 'B'}, + {"uartC", true, 0, 'C'}, + {"uartD", true, 0, 'D'}, {"uartE", true, 0, 'E'}, - {"serial4", true, 0, 'E'}, {"uartF", true, 0, 'F'}, - {"serial5", true, 0, 'F'}, {"uartG", true, 0, 'G'}, - {"serial6", true, 0, 'G'}, {"uartH", true, 0, 'H'}, - {"serial7", true, 0, 'H'}, {"uartI", true, 0, 'I'}, - {"serial8", true, 0, 'I'}, {"uartJ", true, 0, 'J'}, - {"serial9", true, 0, 'J'}, + {"serial0", true, 0, CMDLINE_SERIAL0}, + {"serial1", true, 0, CMDLINE_SERIAL1}, + {"serial2", true, 0, CMDLINE_SERIAL2}, + {"serial3", true, 0, CMDLINE_SERIAL3}, + {"serial4", true, 0, CMDLINE_SERIAL4}, + {"serial5", true, 0, CMDLINE_SERIAL5}, + {"serial6", true, 0, CMDLINE_SERIAL6}, + {"serial7", true, 0, CMDLINE_SERIAL7}, + {"serial8", true, 0, CMDLINE_SERIAL8}, + {"serial9", true, 0, CMDLINE_SERIAL9}, {"log-directory", true, 0, 'l'}, {"terrain-directory", true, 0, 't'}, {"storage-directory", true, 0, 's'}, @@ -372,34 +398,36 @@ void HAL_Linux::run(int argc, char* const argv[], Callbacks* callbacks) const while ((opt = gopt.getoption()) != -1) { switch (opt) { case 'A': - serial0Driver.set_device_path(gopt.optarg); - break; + case 'B': case 'C': - serial1Driver.set_device_path(gopt.optarg); - break; case 'D': - serial2Driver.set_device_path(gopt.optarg); - break; - case 'B': - serial3Driver.set_device_path(gopt.optarg); - break; case 'E': - serial4Driver.set_device_path(gopt.optarg); - break; case 'F': - serial5Driver.set_device_path(gopt.optarg); - break; case 'G': - serial6Driver.set_device_path(gopt.optarg); - break; case 'H': - serial7Driver.set_device_path(gopt.optarg); - break; case 'I': - serial8Driver.set_device_path(gopt.optarg); + case 'J': { + int uart_idx = opt - 'A'; + // ordering captures the historical use of uartB as SERIAL3 + static const uint8_t mapping[] = { 0, 3, 1, 2, 4, 5, 6, 7, 8, 9 }; + int serial_idx = mapping[uart_idx]; + printf("WARNING: deprecated option --uart%c/-%c will be removed in " + "a future release. Use --serial%d instead.\n", + (char)opt, (char)opt, serial_idx); + serialDrivers[serial_idx]->set_device_path(gopt.optarg); break; - case 'J': - serial9Driver.set_device_path(gopt.optarg); + } + case CMDLINE_SERIAL0: + case CMDLINE_SERIAL1: + case CMDLINE_SERIAL2: + case CMDLINE_SERIAL3: + case CMDLINE_SERIAL4: + case CMDLINE_SERIAL5: + case CMDLINE_SERIAL6: + case CMDLINE_SERIAL7: + case CMDLINE_SERIAL8: + case CMDLINE_SERIAL9: + serialDrivers[opt - CMDLINE_SERIAL0]->set_device_path(gopt.optarg); break; case 'l': utilInstance.set_custom_log_directory(gopt.optarg); From 1d805555f571ff26f8e35965387e9ba63ce9a7c2 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Sun, 17 Dec 2023 15:33:30 -0700 Subject: [PATCH 0162/1335] AP_ExternalAHRS: Fix typos in configuration for microstrain7 Signed-off-by: Ryan Friedman --- libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.cpp | 2 +- libraries/AP_ExternalAHRS/MicroStrain_common.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.cpp index 5f2a066907bd04..09762f67d6aa88 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.cpp @@ -16,7 +16,7 @@ $ sim_vehicle.py -v Plane -A "--serial3=uart:/dev/3dm-gq7" --console --map -DG $ ./Tools/autotest/sim_vehicle.py -v Plane -A "--serial3=uart:/dev/3dm-gq7" -DG param set AHRS_EKF_TYPE 11 - param set EAHRS_TYPE 4 + param set EAHRS_TYPE 7 param set GPS_TYPE 21 param set SERIAL3_BAUD 115 param set SERIAL3_PROTOCOL 36 diff --git a/libraries/AP_ExternalAHRS/MicroStrain_common.cpp b/libraries/AP_ExternalAHRS/MicroStrain_common.cpp index 66d324df99554a..19a6e22509c7e8 100644 --- a/libraries/AP_ExternalAHRS/MicroStrain_common.cpp +++ b/libraries/AP_ExternalAHRS/MicroStrain_common.cpp @@ -11,7 +11,7 @@ along with this program. If not, see . */ /* - support for MicroStrain CX5/GX5-45 serially connected AHRS Systems + support for MicroStrain MIP parsing */ #define ALLOW_DOUBLE_MATH_FUNCTIONS From 368ec28ab6047644f00bf8388ad0da557c0563cc Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Tue, 26 Sep 2023 14:58:26 -0700 Subject: [PATCH 0163/1335] AP_Relay: Refactor to support RELAYx_FUNCTION --- libraries/AP_Relay/AP_Relay.cpp | 255 +++++++++++++++++-------- libraries/AP_Relay/AP_Relay.h | 26 +-- libraries/AP_Relay/AP_Relay_Params.cpp | 32 ++++ libraries/AP_Relay/AP_Relay_Params.h | 30 +++ 4 files changed, 255 insertions(+), 88 deletions(-) create mode 100644 libraries/AP_Relay/AP_Relay_Params.cpp create mode 100644 libraries/AP_Relay/AP_Relay_Params.h diff --git a/libraries/AP_Relay/AP_Relay.cpp b/libraries/AP_Relay/AP_Relay.cpp index 1c4cb143f7b0fc..4ffe1d3562bef5 100644 --- a/libraries/AP_Relay/AP_Relay.cpp +++ b/libraries/AP_Relay/AP_Relay.cpp @@ -60,54 +60,37 @@ const AP_Param::GroupInfo AP_Relay::var_info[] = { - // @Param: PIN - // @DisplayName: First Relay Pin - // @Description: Digital pin number for first relay control. This is the pin used for camera shutter control. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. - // @User: Standard - // @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5,27:BBBMini Pin P8.17,101:MainOut1,102:MainOut2,103:MainOut3,104:MainOut4,105:MainOut5,106:MainOut6,107:MainOut7,108:MainOut8 - AP_GROUPINFO("PIN", 0, AP_Relay, _pin[0], RELAY1_PIN_DEFAULT), - - // @Param: PIN2 - // @DisplayName: Second Relay Pin - // @Description: Digital pin number for 2nd relay control. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. - // @User: Standard - // @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5,65:BBBMini Pin P8.18,101:MainOut1,102:MainOut2,103:MainOut3,104:MainOut4,105:MainOut5,106:MainOut6,107:MainOut7,108:MainOut8 - AP_GROUPINFO("PIN2", 1, AP_Relay, _pin[1], RELAY2_PIN_DEFAULT), - - // @Param: PIN3 - // @DisplayName: Third Relay Pin - // @Description: Digital pin number for 3rd relay control. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. - // @User: Standard - // @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5,22:BBBMini Pin P8.19,101:MainOut1,102:MainOut2,103:MainOut3,104:MainOut4,105:MainOut5,106:MainOut6,107:MainOut7,108:MainOut8 - AP_GROUPINFO("PIN3", 2, AP_Relay, _pin[2], RELAY3_PIN_DEFAULT), - - // @Param: PIN4 - // @DisplayName: Fourth Relay Pin - // @Description: Digital pin number for 4th relay control. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. - // @User: Standard - // @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5,63:BBBMini Pin P8.34,101:MainOut1,102:MainOut2,103:MainOut3,104:MainOut4,105:MainOut5,106:MainOut6,107:MainOut7,108:MainOut8 - AP_GROUPINFO("PIN4", 3, AP_Relay, _pin[3], RELAY4_PIN_DEFAULT), - - // @Param: DEFAULT - // @DisplayName: Default relay state - // @Description: The state of the relay on boot. - // @User: Standard - // @Values: 0:Off,1:On,2:NoChange - AP_GROUPINFO("DEFAULT", 4, AP_Relay, _default, 0), - - // @Param: PIN5 - // @DisplayName: Fifth Relay Pin - // @Description: Digital pin number for 5th relay control. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. - // @User: Standard - // @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5,62:BBBMini Pin P8.13,101:MainOut1,102:MainOut2,103:MainOut3,104:MainOut4,105:MainOut5,106:MainOut6,107:MainOut7,108:MainOut8 - AP_GROUPINFO("PIN5", 5, AP_Relay, _pin[4], RELAY5_PIN_DEFAULT), - - // @Param: PIN6 - // @DisplayName: Sixth Relay Pin - // @Description: Digital pin number for 6th relay control. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. - // @User: Standard - // @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5,37:BBBMini Pin P8.14,101:MainOut1,102:MainOut2,103:MainOut3,104:MainOut4,105:MainOut5,106:MainOut6,107:MainOut7,108:MainOut8 - AP_GROUPINFO("PIN6", 6, AP_Relay, _pin[5], RELAY6_PIN_DEFAULT), + // 0 was PIN + // 1 was PIN2 + // 2 was PIN3 + // 3 was PIN4 + // 4 was DEFAULT + // 5 was PIN5 + // 6 was PIN6 + + // @Group: 1_ + // @Path: AP_Relay_Params.cpp + AP_SUBGROUPINFO(_params[0], "1_", 7, AP_Relay, AP_Relay_Params), + + // @Group: 2_ + // @Path: AP_Relay_Params.cpp + AP_SUBGROUPINFO(_params[1], "2_", 8, AP_Relay, AP_Relay_Params), + + // @Group: 3_ + // @Path: AP_Relay_Params.cpp + AP_SUBGROUPINFO(_params[2], "3_", 9, AP_Relay, AP_Relay_Params), + + // @Group: 4_ + // @Path: AP_Relay_Params.cpp + AP_SUBGROUPINFO(_params[3], "4_", 10, AP_Relay, AP_Relay_Params), + + // @Group: 5_ + // @Path: AP_Relay_Params.cpp + AP_SUBGROUPINFO(_params[4], "5_", 11, AP_Relay, AP_Relay_Params), + + // @Group: 6_ + // @Path: AP_Relay_Params.cpp + AP_SUBGROUPINFO(_params[5], "6_", 12, AP_Relay, AP_Relay_Params), AP_GROUPEND }; @@ -128,48 +111,147 @@ AP_Relay::AP_Relay(void) singleton = this; } +void AP_Relay::convert_params() +{ + // Find old default param + int8_t default_state = 0; // off was the old behaviour + const bool have_default = AP_Param::get_param_by_index(this, 4, AP_PARAM_INT8, &default_state); + + // grab the old values if they were set + for (uint8_t i = 0; i < MIN(AP_RELAY_NUM_RELAYS, 6); i++) { + + uint8_t param_index = i; + if (i > 3) { + // Skip over the old DEFAULT parameter at index 4 + param_index += 1; + } + + int8_t pin = 0; + if (!_params[i].pin.configured() && AP_Param::get_param_by_index(this, param_index, AP_PARAM_INT8, &pin) && (pin >= 0)) { + // if the pin isn't negative we can assume the user might have been using it, map it to the old school relay interface + _params[i].pin.set_and_save(pin); + _params[i].function.set_and_save(int8_t(AP_Relay_Params::Function::relay)); + + if (have_default) { + _params[i].default_state.set_and_save(default_state); + } + } + + } +} + +void AP_Relay::set_defaults() { + const int8_t pins[] = { RELAY1_PIN_DEFAULT, + RELAY2_PIN_DEFAULT, + RELAY3_PIN_DEFAULT, + RELAY4_PIN_DEFAULT, + RELAY5_PIN_DEFAULT, + RELAY6_PIN_DEFAULT }; + + for (uint8_t i = 0; i < MIN(uint8_t(AP_RELAY_NUM_RELAYS), ARRAY_SIZE(pins)); i++) { + // set the default + if (pins[i] != -1) { + _params[i].pin.set_default(pins[i]); + } + } +} void AP_Relay::init() { - if (_default != 0 && _default != 1) { + set_defaults(); + + convert_params(); + + // setup the actual default values of all the pins + for (uint8_t instance = 0; instance < AP_RELAY_NUM_RELAYS; instance++) { + const int8_t pin = _params[instance].pin; + if (pin == -1) { + // no valid pin to set it on, skip it + continue; + } + + const AP_Relay_Params::Function function = _params[instance].function; + if (function < AP_Relay_Params::Function::relay || function >= AP_Relay_Params::Function::num_functions) { + // invalid function, skip it + continue; + } + + if (function == AP_Relay_Params::Function::relay) { + // relay by instance number, set the state to match our output + const AP_Relay_Params::DefaultState default_state = _params[instance].default_state; + if ((default_state == AP_Relay_Params::DefaultState::OFF) || + (default_state == AP_Relay_Params::DefaultState::ON)) { + + set_pin_by_instance(instance, (bool)default_state); + } + } else { + // all functions are supposed to be off by default + // this will need revisiting when we support inversion + set_pin_by_instance(instance, false); + } + } +} + +void AP_Relay::set(const AP_Relay_Params::Function function, const bool value) { + if (function <= AP_Relay_Params::Function::none && function >= AP_Relay_Params::Function::num_functions) { + // invalid function return; } - for (uint8_t i=0; i= AP_RELAY_NUM_RELAYS) { + const int8_t pin = _params[instance].pin; + if (pin == -1) { + // no valid pin to set it on, skip it return; } - if (_pin[instance] == -1) { - return; - } - const uint32_t now = AP_HAL::millis(); - _pin_states = value ? _pin_states | (1U< 10)) { - AP::logger().Write("RELY", "TimeUS,State", "s-", "F-", "QB", - AP_HAL::micros64(), - _pin_states); - _last_log_ms = now; - _last_logged_pin_states = _pin_states; - } + #if AP_SIM_ENABLED if (!(AP::sitl()->on_hardware_relay_enable_mask & (1U << instance))) { return; } #endif - hal.gpio->pinMode(_pin[instance], HAL_GPIO_OUTPUT); - hal.gpio->write(_pin[instance], value); + + hal.gpio->pinMode(pin, HAL_GPIO_OUTPUT); + const bool initial_value = (bool)hal.gpio->read(pin); + + if (initial_value != value) { + hal.gpio->write(pin, value); + AP::logger().Write("RELY", "TimeUS,Instance,State", "s#-", "F--", "QBB", + AP_HAL::micros64(), + instance, + value); + } +} + +void AP_Relay::set(const uint8_t instance, const bool value) +{ + if (instance >= AP_RELAY_NUM_RELAYS) { + return; + } + + if (_params[instance].function != AP_Relay_Params::Function::relay) { + return; + } + + set_pin_by_instance(instance, value); } void AP_Relay::toggle(uint8_t instance) { - if (instance < AP_RELAY_NUM_RELAYS && _pin[instance] != -1) { - bool ison = hal.gpio->read(_pin[instance]); - set(instance, !ison); + if (instance < AP_RELAY_NUM_RELAYS) { + set(instance, !get(instance)); } } @@ -177,12 +259,10 @@ void AP_Relay::toggle(uint8_t instance) bool AP_Relay::arming_checks(size_t buflen, char *buffer) const { for (uint8_t i=0; ivalid_pin(pin)) { - char param_name_buf[11] = "RELAY_PIN"; - if (i > 0) { - hal.util->snprintf(param_name_buf, ARRAY_SIZE(param_name_buf), "RELAY_PIN%u", unsigned(i+1)); - } + char param_name_buf[14]; + hal.util->snprintf(param_name_buf, ARRAY_SIZE(param_name_buf), "RELAY%u_PIN", unsigned(i+1)); uint8_t servo_ch; if (hal.gpio->pin_to_servo_channel(pin, servo_ch)) { hal.util->snprintf(buffer, buflen, "%s=%d, set SERVO%u_FUNCTION=-1", param_name_buf, int(pin), unsigned(servo_ch+1)); @@ -195,6 +275,29 @@ bool AP_Relay::arming_checks(size_t buflen, char *buffer) const return true; } +bool AP_Relay::get(uint8_t instance) const +{ + if (instance >= AP_RELAY_NUM_RELAYS) { + // invalid instance + return false; + } + + const int8_t pin = _params[instance].pin.get(); + + if (pin < 0) { + // invalid pin + return false; + } + + return (bool)hal.gpio->read(pin); +} + +// see if the relay is enabled +bool AP_Relay::enabled(uint8_t instance) const +{ + // Must be a valid instance with function relay and pin set + return (instance < AP_RELAY_NUM_RELAYS) && (_params[instance].pin != -1) && (_params[instance].function == AP_Relay_Params::Function::relay); +} #if AP_MAVLINK_MSG_RELAY_STATUS_ENABLED // this method may only return false if there is no space in the @@ -214,7 +317,7 @@ bool AP_Relay::send_relay_status(const GCS_MAVLINK &link) const const uint16_t relay_bit_mask = 1U << i; present_mask |= relay_bit_mask; - if (_pin_states & relay_bit_mask) { + if (get(i)) { on_mask |= relay_bit_mask; } } diff --git a/libraries/AP_Relay/AP_Relay.h b/libraries/AP_Relay/AP_Relay.h index c14e964c54ea47..5a5237d18cec5e 100644 --- a/libraries/AP_Relay/AP_Relay.h +++ b/libraries/AP_Relay/AP_Relay.h @@ -14,6 +14,8 @@ #if AP_RELAY_ENABLED #include +#include +#include #define AP_RELAY_NUM_RELAYS 6 @@ -29,9 +31,6 @@ class AP_Relay { // setup the relay pin void init(); - // set relay to state - void set(uint8_t instance, bool value); - // activate the relay void on(uint8_t instance) { set(instance, true); } @@ -39,12 +38,10 @@ class AP_Relay { void off(uint8_t instance) { set(instance, false); } // get state of relay - uint8_t get(uint8_t instance) const { - return instance < AP_RELAY_NUM_RELAYS ? _pin_states & (1U< +#include "AP_Relay_Params.h" + +const AP_Param::GroupInfo AP_Relay_Params::var_info[] = { + // @Param: FUNCTION + // @DisplayName: Relay function + // @Description: The function the relay channel is mapped to. + // @Values: 0:None,1:Relay,2:Ignition,3:Starter + // @User: Standard + AP_GROUPINFO_FLAGS("FUNCTION", 1, AP_Relay_Params, function, (float)Function::none, AP_PARAM_FLAG_ENABLE), + + // @Param: PIN + // @DisplayName: Relay pin + // @Description: Digital pin number for relay control. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. + // @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5,62:BBBMini Pin P8.13,101:MainOut1,102:MainOut2,103:MainOut3,104:MainOut4,105:MainOut5,106:MainOut6,107:MainOut7,108:MainOut8 + // @User: Standard + AP_GROUPINFO("PIN", 2, AP_Relay_Params, pin, -1), + + // @Param: DEFAULT + // @DisplayName: Relay default state + // @Description: Should the relay default to on or off, this only applies to function Relay. All other uses will pick the appropriate default output state. + // @Values: 0: Off,1:On,2:NoChange + // @User: Standard + AP_GROUPINFO("DEFAULT", 3, AP_Relay_Params, default_state, (float)DefaultState::OFF), + + AP_GROUPEND + +}; + +AP_Relay_Params::AP_Relay_Params(void) { + AP_Param::setup_object_defaults(this, var_info); +} diff --git a/libraries/AP_Relay/AP_Relay_Params.h b/libraries/AP_Relay/AP_Relay_Params.h new file mode 100644 index 00000000000000..cb1815156c0a21 --- /dev/null +++ b/libraries/AP_Relay/AP_Relay_Params.h @@ -0,0 +1,30 @@ +#pragma once + +#include +#include "AP_Relay_config.h" + +class AP_Relay_Params { +public: + static const struct AP_Param::GroupInfo var_info[]; + + AP_Relay_Params(void); + + /* Do not allow copies */ + CLASS_NO_COPY(AP_Relay_Params); + + enum class DefaultState : uint8_t { + OFF = 0, + ON = 1, + NO_CHANGE = 2, + }; + + enum class Function : uint8_t { + none = 0, + relay = 1, + num_functions // must be the last entry + }; + + AP_Enum function; // relay function + AP_Int16 pin; // gpio pin number + AP_Enum default_state; // default state +}; From 18ba0c5d2bfcf0343f3224be940e926de9e9f386 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Tue, 3 Oct 2023 17:17:23 -0700 Subject: [PATCH 0164/1335] Copter: Fix AP_Relay param naming --- ArduCopter/Parameters.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 80a79da030a7c5..f56ef3b0205554 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -451,9 +451,9 @@ const AP_Param::Info Copter::var_info[] = { #endif #if AP_RELAY_ENABLED - // @Group: RELAY_ + // @Group: RELAY // @Path: ../libraries/AP_Relay/AP_Relay.cpp - GOBJECT(relay, "RELAY_", AP_Relay), + GOBJECT(relay, "RELAY", AP_Relay), #endif #if PARACHUTE == ENABLED From 9aa0ceb9ddda45519f1d44064ee230cc3573ed32 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Tue, 3 Oct 2023 17:17:44 -0700 Subject: [PATCH 0165/1335] Plane: Fix AP_Relay param naming --- ArduPlane/Parameters.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index fbecd0ee40b6c4..bb4a2a86a5fbae 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -757,9 +757,9 @@ const AP_Param::Info Plane::var_info[] = { GOBJECT(arming, "ARMING_", AP_Arming_Plane), #if AP_RELAY_ENABLED - // @Group: RELAY_ + // @Group: RELAY // @Path: ../libraries/AP_Relay/AP_Relay.cpp - GOBJECT(relay, "RELAY_", AP_Relay), + GOBJECT(relay, "RELAY", AP_Relay), #endif #if PARACHUTE == ENABLED From 6dc891baf9c6c1465b5e0f3b636a0dc44456b4f1 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Tue, 3 Oct 2023 17:17:55 -0700 Subject: [PATCH 0166/1335] Sub: Fix AP_Relay param naming --- ArduSub/Parameters.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index d43b149820f740..5711f4fe31dc8e 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -476,9 +476,9 @@ const AP_Param::Info Sub::var_info[] = { #endif #if AP_RELAY_ENABLED - // @Group: RELAY_ + // @Group: RELAY // @Path: ../libraries/AP_Relay/AP_Relay.cpp - GOBJECT(relay, "RELAY_", AP_Relay), + GOBJECT(relay, "RELAY", AP_Relay), #endif // @Group: COMPASS_ From 3937e96738a6207b2a743c911c9e8eb61399b324 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Tue, 3 Oct 2023 17:18:04 -0700 Subject: [PATCH 0167/1335] Rover: Fix AP_Relay param naming --- Rover/Parameters.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index 5d4a84fc9b08b6..ac1bdb29abdc14 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -223,9 +223,9 @@ const AP_Param::Info Rover::var_info[] = { GOBJECT(barometer, "BARO", AP_Baro), #if AP_RELAY_ENABLED - // @Group: RELAY_ + // @Group: RELAY // @Path: ../libraries/AP_Relay/AP_Relay.cpp - GOBJECT(relay, "RELAY_", AP_Relay), + GOBJECT(relay, "RELAY", AP_Relay), #endif // @Group: RCMAP_ From a45353b17fcf26d9430f3c05c372097aa40498fc Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Tue, 7 Nov 2023 09:42:15 -0700 Subject: [PATCH 0168/1335] autotest: Update tests for relay --- Tools/autotest/arduplane.py | 7 +++++-- Tools/autotest/default_params/rover.parm | 4 ++-- .../default_params/vee-gull 005.param | 5 +---- Tools/autotest/rover.py | 20 ++++++++++++++++--- 4 files changed, 25 insertions(+), 11 deletions(-) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index eb84112528a9da..be66a0447821f3 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -1124,9 +1124,12 @@ def TestFlaps(self): def TestRCRelay(self): '''Test Relay RC Channel Option''' - self.set_parameter("RC12_OPTION", 28) # Relay On/Off + self.set_parameters({ + "RELAY1_FUNCTION": 1, # Enable relay as a standard relay pin + "RC12_OPTION": 28 # Relay On/Off + }) self.set_rc(12, 1000) - self.reboot_sitl() # needed for RC12_OPTION to take effect + self.reboot_sitl() # needed for RC12_OPTION and RELAY1_FUNCTION to take effect off = self.get_parameter("SIM_PIN_MASK") if off: diff --git a/Tools/autotest/default_params/rover.parm b/Tools/autotest/default_params/rover.parm index 9095f40720d5d8..58e064d81b3f5c 100644 --- a/Tools/autotest/default_params/rover.parm +++ b/Tools/autotest/default_params/rover.parm @@ -24,8 +24,8 @@ RC1_MAX 2000 RC1_MIN 1000 RC3_MAX 2000 RC3_MIN 1000 -RELAY_PIN 1 -RELAY_PIN2 2 +RELAY1_PIN 1 +RELAY2_PIN 2 SERVO1_MIN 1000 SERVO1_MAX 2000 SERVO3_MAX 2000 diff --git a/Tools/autotest/default_params/vee-gull 005.param b/Tools/autotest/default_params/vee-gull 005.param index 2ae334ae8b7fc1..6e5143632d452c 100644 --- a/Tools/autotest/default_params/vee-gull 005.param +++ b/Tools/autotest/default_params/vee-gull 005.param @@ -456,10 +456,7 @@ RCMAP_ROLL,1 RCMAP_THROTTLE,3 RCMAP_YAW,4 RELAY_DEFAULT,0 -RELAY_PIN,13 -RELAY_PIN2,-1 -RELAY_PIN3,-1 -RELAY_PIN4,-1 +RELAY1_PIN,13 RLL_RATE_D,0.000000 RLL_RATE_FF,0.255000 RLL_RATE_I,0.050000 diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index 2f0870b351c16e..8df67796676461 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -568,6 +568,13 @@ def ServoRelayEvents(self): '''Test ServoRelayEvents''' for method in self.run_cmd, self.run_cmd_int: self.context_push() + + self.set_parameters({ + "RELAY1_FUNCTION": 1, # Enable relay 1 as a standard relay pin + "RELAY2_FUNCTION": 1, # Enable relay 2 as a standard relay pin + }) + self.reboot_sitl() # Needed for relay functions to take effect + method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=0) off = self.get_parameter("SIM_PIN_MASK") method(mavutil.mavlink.MAV_CMD_DO_SET_RELAY, p1=0, p2=1) @@ -602,8 +609,14 @@ def ServoRelayEvents(self): "on": 0, }) - # add another servo: - self.set_parameter("RELAY_PIN6", 14) + # add another relay and ensure that it changes the "present field" + self.set_parameters({ + "RELAY6_FUNCTION": 1, # Enable relay 6 as a standard relay pin + "RELAY6_PIN": 14, # Set pin number + }) + self.reboot_sitl() # Needed for relay function to take effect + self.set_message_rate_hz("RELAY_STATUS", 10) # Need to re-request the message since reboot + self.assert_received_message_field_values('RELAY_STATUS', { "present": 35, "on": 0, @@ -5352,7 +5365,8 @@ def test_scripting_auxfunc(self): self.context_collect("STATUSTEXT") self.set_parameters({ "SCR_ENABLE": 1, - "RELAY_PIN": 1, + "RELAY1_FUNCTION": 1, + "RELAY1_PIN": 1 }) self.install_example_script_context("RCIN_test.lua") self.reboot_sitl() From f26ff3ee5a1800502e96d6658c8eb279f4612394 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 8 Dec 2023 04:27:06 +0000 Subject: [PATCH 0169/1335] AP_LandingGear: remove unneeded relay include --- libraries/AP_LandingGear/AP_LandingGear.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/libraries/AP_LandingGear/AP_LandingGear.cpp b/libraries/AP_LandingGear/AP_LandingGear.cpp index b7a7bc3ebb45bd..8f77d5e3df7501 100644 --- a/libraries/AP_LandingGear/AP_LandingGear.cpp +++ b/libraries/AP_LandingGear/AP_LandingGear.cpp @@ -2,7 +2,6 @@ #if AP_LANDINGGEAR_ENABLED -#include #include #include #include From 8292c6ea9f9c5959a8483377735ad4d43b7b5bd2 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 8 Dec 2023 04:29:31 +0000 Subject: [PATCH 0170/1335] AP_Camera: move to new relay functions --- libraries/AP_Camera/AP_Camera.cpp | 20 ++++++++++++++++++++ libraries/AP_Camera/AP_Camera.h | 3 +++ libraries/AP_Camera/AP_Camera_Relay.cpp | 12 ++---------- 3 files changed, 25 insertions(+), 10 deletions(-) diff --git a/libraries/AP_Camera/AP_Camera.cpp b/libraries/AP_Camera/AP_Camera.cpp index a44243c8caccaa..76f3524e22e2b0 100644 --- a/libraries/AP_Camera/AP_Camera.cpp +++ b/libraries/AP_Camera/AP_Camera.cpp @@ -771,6 +771,26 @@ void AP_Camera::convert_params() } } +#if AP_RELAY_ENABLED +// Return true and the relay index if relay camera backend is selected, used for conversion to relay functions +bool AP_Camera::get_legacy_relay_index(int8_t &index) const +{ + // PARAMETER_CONVERSION - Added: Dec-2023 + + // Note that this assumes that the camera param conversion has already been done + // Copter, Plane, Sub and Rover all have both relay and camera and all init relay first + // This will only be a issue if the relay and camera conversion were done at once, if the user skipped 4.4 + for (uint8_t i = 0; i < AP_CAMERA_MAX_INSTANCES; i++) { + if ((CameraType)_params[i].type.get() == CameraType::RELAY) { + // Camera was hard coded to relay 0 + index = 0; + return true; + } + } + return false; +} +#endif + // singleton instance AP_Camera *AP_Camera::_singleton; diff --git a/libraries/AP_Camera/AP_Camera.h b/libraries/AP_Camera/AP_Camera.h index 356901ab262816..71ef3ffda4614a 100644 --- a/libraries/AP_Camera/AP_Camera.h +++ b/libraries/AP_Camera/AP_Camera.h @@ -182,6 +182,9 @@ class AP_Camera { bool get_state(uint8_t instance, camera_state_t& cam_state); #endif + // Return true and the relay index if relay camera backend is selected, used for conversion to relay functions + bool get_legacy_relay_index(int8_t &index) const; + // allow threads to lock against AHRS update HAL_Semaphore &get_semaphore() { return _rsem; } diff --git a/libraries/AP_Camera/AP_Camera_Relay.cpp b/libraries/AP_Camera/AP_Camera_Relay.cpp index a48adeb348d51d..db8fc2adec4811 100644 --- a/libraries/AP_Camera/AP_Camera_Relay.cpp +++ b/libraries/AP_Camera/AP_Camera_Relay.cpp @@ -14,11 +14,7 @@ void AP_Camera_Relay::update() if (ap_relay == nullptr) { return; } - if (_params.relay_on) { - ap_relay->off(0); - } else { - ap_relay->on(0); - } + ap_relay->set(AP_Relay_Params::FUNCTION::CAMERA, !_params.relay_on); } // call parent update @@ -39,11 +35,7 @@ bool AP_Camera_Relay::trigger_pic() return false; } - if (_params.relay_on) { - ap_relay->on(0); - } else { - ap_relay->off(0); - } + ap_relay->set(AP_Relay_Params::FUNCTION::CAMERA, _params.relay_on); // set counter to move servo to off position after this many iterations of update (assumes 50hz update rate) trigger_counter = constrain_float(_params.trigger_duration * 50, 0, UINT16_MAX); From 8ce490d9856691a7445d3b25c7c5f4c19f67e3be Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 8 Dec 2023 04:30:34 +0000 Subject: [PATCH 0171/1335] AP_ICEngine: move to new relay functions --- libraries/AP_ICEngine/AP_ICEngine.cpp | 34 ++++++++++++++++----------- libraries/AP_ICEngine/AP_ICEngine.h | 10 ++++---- 2 files changed, 25 insertions(+), 19 deletions(-) diff --git a/libraries/AP_ICEngine/AP_ICEngine.cpp b/libraries/AP_ICEngine/AP_ICEngine.cpp index d7afd09e92fd8f..ad66e49ded7d07 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.cpp +++ b/libraries/AP_ICEngine/AP_ICEngine.cpp @@ -165,14 +165,8 @@ const AP_Param::GroupInfo AP_ICEngine::var_info[] = { AP_GROUPINFO("REDLINE_RPM", 17, AP_ICEngine, redline_rpm, 0), #endif -#if AP_RELAY_ENABLED - // @Param: IGNITION_RLY - // @DisplayName: Ignition relay channel - // @Description: This is a a relay channel to use for ignition control - // @User: Standard - // @Values: 0:None,1:Relay1,2:Relay2,3:Relay3,4:Relay4,5:Relay5,6:Relay6 - AP_GROUPINFO("IGNITION_RLY", 18, AP_ICEngine, ignition_relay, 0), -#endif + // 18 was IGNITION_RLY + AP_GROUPEND }; @@ -608,15 +602,14 @@ void AP_ICEngine::update_idle_governor(int8_t &min_throttle) void AP_ICEngine::set_ignition(bool on) { SRV_Channels::set_output_pwm(SRV_Channel::k_ignition, on? pwm_ignition_on : pwm_ignition_off); + #if AP_RELAY_ENABLED - // optionally use a relay as well - if (ignition_relay > 0) { - auto *relay = AP::relay(); - if (relay != nullptr) { - relay->set(ignition_relay-1, on); - } + AP_Relay *relay = AP::relay(); + if (relay != nullptr) { + relay->set(AP_Relay_Params::FUNCTION::IGNITION, on); } #endif // AP_RELAY_ENABLED + } /* @@ -638,6 +631,19 @@ bool AP_ICEngine::allow_throttle_while_disarmed() const hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED; } +#if AP_RELAY_ENABLED +bool AP_ICEngine::get_legacy_ignition_relay_index(int8_t &num) +{ + // PARAMETER_CONVERSION - Added: Dec-2023 + if (!enable || !AP_Param::get_param_by_index(this, 18, AP_PARAM_INT8, &num)) { + return false; + } + // convert to zero indexed + num -= 1; + return true; +} +#endif + // singleton instance. Should only ever be set in the constructor. AP_ICEngine *AP_ICEngine::_singleton; namespace AP { diff --git a/libraries/AP_ICEngine/AP_ICEngine.h b/libraries/AP_ICEngine/AP_ICEngine.h index 919e763b28201f..351302e7638f0f 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.h +++ b/libraries/AP_ICEngine/AP_ICEngine.h @@ -66,6 +66,11 @@ class AP_ICEngine { // do we have throttle while disarmed enabled? bool allow_throttle_while_disarmed(void) const; +#if AP_RELAY_ENABLED + // Needed for param conversion from relay numbers to functions + bool get_legacy_ignition_relay_index(int8_t &num); +#endif + static AP_ICEngine *get_singleton() { return _singleton; } private: @@ -136,11 +141,6 @@ class AP_ICEngine { AP_Float idle_slew; #endif -#if AP_RELAY_ENABLED - // relay number for ignition - AP_Int8 ignition_relay; -#endif - // height when we enter ICE_START_HEIGHT_DELAY float initial_height; From 8ab6f01942cc40001b1f0dcb828d3c05a03bdff5 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 8 Dec 2023 04:36:03 +0000 Subject: [PATCH 0172/1335] AP_Relay: add enabled method by function --- libraries/AP_Relay/AP_Relay.cpp | 12 ++++++++++++ libraries/AP_Relay/AP_Relay.h | 3 +++ 2 files changed, 15 insertions(+) diff --git a/libraries/AP_Relay/AP_Relay.cpp b/libraries/AP_Relay/AP_Relay.cpp index 4ffe1d3562bef5..e5cdde29c0b23c 100644 --- a/libraries/AP_Relay/AP_Relay.cpp +++ b/libraries/AP_Relay/AP_Relay.cpp @@ -299,6 +299,18 @@ bool AP_Relay::enabled(uint8_t instance) const return (instance < AP_RELAY_NUM_RELAYS) && (_params[instance].pin != -1) && (_params[instance].function == AP_Relay_Params::Function::relay); } +// see if the relay is enabled +bool AP_Relay::enabled(AP_Relay_Params::Function function) const +{ + bool valid = false; + for (uint8_t instance = 0; instance < AP_RELAY_NUM_RELAYS; instance++) { + if ((_params[instance].function == function) && (_params[instance].pin != -1)) { + valid = true; + } + } + return valid; +} + #if AP_MAVLINK_MSG_RELAY_STATUS_ENABLED // this method may only return false if there is no space in the // supplied link for the message. diff --git a/libraries/AP_Relay/AP_Relay.h b/libraries/AP_Relay/AP_Relay.h index 5a5237d18cec5e..a668e9144c71a1 100644 --- a/libraries/AP_Relay/AP_Relay.h +++ b/libraries/AP_Relay/AP_Relay.h @@ -57,6 +57,9 @@ class AP_Relay { void set(AP_Relay_Params::Function function, bool value); + // see if the relay is enabled + bool enabled(AP_Relay_Params::Function function) const; + private: static AP_Relay *singleton; From 5a5ee0c44c41ac1acbde18662281a1bbb9b6ab0f Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 8 Dec 2023 04:36:47 +0000 Subject: [PATCH 0173/1335] AP_Parachute: move to new relay functions --- libraries/AP_Parachute/AP_Parachute.cpp | 21 +++++++++++++++++---- libraries/AP_Parachute/AP_Parachute.h | 5 ++++- 2 files changed, 21 insertions(+), 5 deletions(-) diff --git a/libraries/AP_Parachute/AP_Parachute.cpp b/libraries/AP_Parachute/AP_Parachute.cpp index 9b4075dc719642..6ed1618b1904aa 100644 --- a/libraries/AP_Parachute/AP_Parachute.cpp +++ b/libraries/AP_Parachute/AP_Parachute.cpp @@ -142,7 +142,7 @@ void AP_Parachute::update() // set relay AP_Relay*_relay = AP::relay(); if (_relay != nullptr) { - _relay->on(_release_type); + _relay->set(AP_Relay_Params::FUNCTION::PARACHUTE, true); } #endif } @@ -159,7 +159,7 @@ void AP_Parachute::update() // set relay back to zero volts AP_Relay*_relay = AP::relay(); if (_relay != nullptr) { - _relay->off(_release_type); + _relay->set(AP_Relay_Params::FUNCTION::PARACHUTE, false); } #endif } @@ -218,8 +218,8 @@ bool AP_Parachute::arming_checks(size_t buflen, char *buffer) const } else { #if AP_RELAY_ENABLED AP_Relay*_relay = AP::relay(); - if (_relay == nullptr || !_relay->enabled(_release_type)) { - hal.util->snprintf(buffer, buflen, "Chute invalid relay %d", int(_release_type)); + if (_relay == nullptr || !_relay->enabled(AP_Relay_Params::FUNCTION::PARACHUTE)) { + hal.util->snprintf(buffer, buflen, "Chute has no relay"); return false; } #else @@ -235,6 +235,19 @@ bool AP_Parachute::arming_checks(size_t buflen, char *buffer) const return true; } +#if AP_RELAY_ENABLED +// Return the relay index that would be used for param conversion to relay functions +bool AP_Parachute::get_legacy_relay_index(int8_t &index) const +{ + // PARAMETER_CONVERSION - Added: Dec-2023 + if (!enabled() || (_release_type > AP_PARACHUTE_TRIGGER_TYPE_RELAY_3)) { + return false; + } + index = _release_type; + return true; +} +#endif + // singleton instance AP_Parachute *AP_Parachute::_singleton; diff --git a/libraries/AP_Parachute/AP_Parachute.h b/libraries/AP_Parachute/AP_Parachute.h index 7793a202d23bbd..30005e7543067e 100644 --- a/libraries/AP_Parachute/AP_Parachute.h +++ b/libraries/AP_Parachute/AP_Parachute.h @@ -85,7 +85,10 @@ class AP_Parachute { // check settings are valid bool arming_checks(size_t buflen, char *buffer) const; - + + // Return the relay index that would be used for param conversion to relay functions + bool get_legacy_relay_index(int8_t &index) const; + static const struct AP_Param::GroupInfo var_info[]; // get singleton instance From abcbc66c5cf3feb2dd303fb2d79aeec00f59a33d Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 8 Dec 2023 04:37:15 +0000 Subject: [PATCH 0174/1335] AP_Relay: param conversion from ICE, chute and camera --- libraries/AP_Relay/AP_Relay.cpp | 69 +++++++++++++++++++++++--- libraries/AP_Relay/AP_Relay_Params.cpp | 4 +- libraries/AP_Relay/AP_Relay_Params.h | 3 ++ 3 files changed, 67 insertions(+), 9 deletions(-) diff --git a/libraries/AP_Relay/AP_Relay.cpp b/libraries/AP_Relay/AP_Relay.cpp index e5cdde29c0b23c..02b9816a089ae7 100644 --- a/libraries/AP_Relay/AP_Relay.cpp +++ b/libraries/AP_Relay/AP_Relay.cpp @@ -15,6 +15,10 @@ #include #include +#include +#include +#include + #if CONFIG_HAL_BOARD == HAL_BOARD_SITL #define RELAY1_PIN_DEFAULT 13 @@ -113,12 +117,45 @@ AP_Relay::AP_Relay(void) void AP_Relay::convert_params() { + // PARAMETER_CONVERSION - Added: Dec-2023 + + // Before converting local params we must find any relays being used by index from external libs + int8_t relay_index; + + int8_t ice_relay = -1; +#if AP_ICENGINE_ENABLED + AP_ICEngine *ice = AP::ice(); + if (ice != nullptr && ice->get_legacy_ignition_relay_index(relay_index)) { + ice_relay = relay_index; + } +#endif + + int8_t chute_relay = -1; +#if HAL_PARACHUTE_ENABLED + AP_Parachute *parachute = AP::parachute(); + if (parachute != nullptr && parachute->get_legacy_relay_index(relay_index)) { + chute_relay = relay_index; + } +#endif + + int8_t cam_relay = -1; +#if AP_CAMERA_ENABLED + AP_Camera *camera = AP::camera(); + if ((camera != nullptr) && (camera->get_legacy_relay_index(relay_index))) { + cam_relay = relay_index; + } +#endif + // Find old default param int8_t default_state = 0; // off was the old behaviour const bool have_default = AP_Param::get_param_by_index(this, 4, AP_PARAM_INT8, &default_state); // grab the old values if they were set for (uint8_t i = 0; i < MIN(AP_RELAY_NUM_RELAYS, 6); i++) { + if (_params[i].function.configured()) { + // Conversion already done, or user has configured manually + continue; + } uint8_t param_index = i; if (i > 3) { @@ -128,15 +165,34 @@ void AP_Relay::convert_params() int8_t pin = 0; if (!_params[i].pin.configured() && AP_Param::get_param_by_index(this, param_index, AP_PARAM_INT8, &pin) && (pin >= 0)) { - // if the pin isn't negative we can assume the user might have been using it, map it to the old school relay interface + // Copy old pin parameter _params[i].pin.set_and_save(pin); + } + if (_params[i].pin < 0) { + // Don't enable if pin is invalid + continue; + } + // Valid pin, this is either due to the param conversion or default value + + // Work out what function this relay should be + if (i == chute_relay) { + _params[i].function.set_and_save(int8_t(AP_Relay_Params::Function::parachute)); + + } else if (i == ice_relay) { + _params[i].function.set_and_save(int8_t(AP_Relay_Params::Function::ignition)); + + } else if (i == cam_relay) { + _params[i].function.set_and_save(int8_t(AP_Relay_Params::Function::camera)); + + } else { _params[i].function.set_and_save(int8_t(AP_Relay_Params::Function::relay)); - if (have_default) { - _params[i].default_state.set_and_save(default_state); - } } + // Set the default state + if (have_default) { + _params[i].default_state.set_and_save(default_state); + } } } @@ -302,13 +358,12 @@ bool AP_Relay::enabled(uint8_t instance) const // see if the relay is enabled bool AP_Relay::enabled(AP_Relay_Params::Function function) const { - bool valid = false; for (uint8_t instance = 0; instance < AP_RELAY_NUM_RELAYS; instance++) { if ((_params[instance].function == function) && (_params[instance].pin != -1)) { - valid = true; + return true; } } - return valid; + return false; } #if AP_MAVLINK_MSG_RELAY_STATUS_ENABLED diff --git a/libraries/AP_Relay/AP_Relay_Params.cpp b/libraries/AP_Relay/AP_Relay_Params.cpp index 01eb6374451e39..9ea593cea6f65d 100644 --- a/libraries/AP_Relay/AP_Relay_Params.cpp +++ b/libraries/AP_Relay/AP_Relay_Params.cpp @@ -5,7 +5,7 @@ const AP_Param::GroupInfo AP_Relay_Params::var_info[] = { // @Param: FUNCTION // @DisplayName: Relay function // @Description: The function the relay channel is mapped to. - // @Values: 0:None,1:Relay,2:Ignition,3:Starter + // @Values: 0:None,1:Relay,2:Ignition,3:Parachute,4:Camera // @User: Standard AP_GROUPINFO_FLAGS("FUNCTION", 1, AP_Relay_Params, function, (float)Function::none, AP_PARAM_FLAG_ENABLE), @@ -15,7 +15,7 @@ const AP_Param::GroupInfo AP_Relay_Params::var_info[] = { // @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5,62:BBBMini Pin P8.13,101:MainOut1,102:MainOut2,103:MainOut3,104:MainOut4,105:MainOut5,106:MainOut6,107:MainOut7,108:MainOut8 // @User: Standard AP_GROUPINFO("PIN", 2, AP_Relay_Params, pin, -1), - + // @Param: DEFAULT // @DisplayName: Relay default state // @Description: Should the relay default to on or off, this only applies to function Relay. All other uses will pick the appropriate default output state. diff --git a/libraries/AP_Relay/AP_Relay_Params.h b/libraries/AP_Relay/AP_Relay_Params.h index cb1815156c0a21..6e9105dbc7ddb5 100644 --- a/libraries/AP_Relay/AP_Relay_Params.h +++ b/libraries/AP_Relay/AP_Relay_Params.h @@ -21,6 +21,9 @@ class AP_Relay_Params { enum class Function : uint8_t { none = 0, relay = 1, + ignition = 2, + parachute = 3, + camera = 4, num_functions // must be the last entry }; From a0eb3396f85e667c2dd7b6767cafdb4da70862f7 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 9 Dec 2023 19:11:44 +0000 Subject: [PATCH 0175/1335] AR_Motors: Move to new relay functions --- libraries/AR_Motors/AP_MotorsUGV.cpp | 95 +++++++++++++++++++++++----- libraries/AR_Motors/AP_MotorsUGV.h | 3 + 2 files changed, 81 insertions(+), 17 deletions(-) diff --git a/libraries/AR_Motors/AP_MotorsUGV.cpp b/libraries/AR_Motors/AP_MotorsUGV.cpp index c1b2177a46b9e0..061c1b3a25bd90 100644 --- a/libraries/AR_Motors/AP_MotorsUGV.cpp +++ b/libraries/AR_Motors/AP_MotorsUGV.cpp @@ -16,7 +16,7 @@ #include #include #include "AP_MotorsUGV.h" -#include +#include #define SERVO_MAX 4500 // This value represents 45 degrees and is just an arbitrary representation of servo max travel. @@ -147,6 +147,33 @@ void AP_MotorsUGV::init(uint8_t frtype) } } +bool AP_MotorsUGV::get_legacy_relay_index(int8_t &index1, int8_t &index2, int8_t &index3, int8_t &index4) const +{ + if (_pwm_type != PWM_TYPE_BRUSHED_WITH_RELAY) { + // Relays only used if PWM type is set to brushed with relay + return false; + } + + // First relay is always used, throttle, throttle left or motor 1 + index1 = 0; + + // Second relay is used for right throttle on skid steer and motor 2 for omni + if (have_skid_steering()) { + index2 = 1; + } + + // Omni can have a variable number of motors + if (is_omni()) { + // Omni has at least 3 motors + index2 = 2; + if (_motors_num >= 4) { + index2 = 3; + } + } + + return true; +} + // setup output in case of main CPU failure void AP_MotorsUGV::setup_safety_output() { @@ -457,10 +484,14 @@ bool AP_MotorsUGV::output_test_pwm(motor_test_order motor_seq, float pwm) // returns true if checks pass, false if they fail. report should be true to send text messages to GCS bool AP_MotorsUGV::pre_arm_check(bool report) const { + const bool have_throttle = SRV_Channels::function_assigned(SRV_Channel::k_throttle); + const bool have_throttle_left = SRV_Channels::function_assigned(SRV_Channel::k_throttleLeft); + const bool have_throttle_right = SRV_Channels::function_assigned(SRV_Channel::k_throttleRight); + // check that there's defined outputs, inc scripting and sail - if(!SRV_Channels::function_assigned(SRV_Channel::k_throttleLeft) && - !SRV_Channels::function_assigned(SRV_Channel::k_throttleRight) && - !SRV_Channels::function_assigned(SRV_Channel::k_throttle) && + if(!have_throttle_left && + !have_throttle_right && + !have_throttle && !SRV_Channels::function_assigned(SRV_Channel::k_steering) && !SRV_Channels::function_assigned(SRV_Channel::k_scripting1) && !has_sail()) { @@ -470,14 +501,14 @@ bool AP_MotorsUGV::pre_arm_check(bool report) const return false; } // check if only one of skid-steering output has been configured - if (SRV_Channels::function_assigned(SRV_Channel::k_throttleLeft) != SRV_Channels::function_assigned(SRV_Channel::k_throttleRight)) { + if (have_throttle_left != have_throttle_right) { if (report) { GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "PreArm: check skid steering config"); } return false; } // check if only one of throttle or steering outputs has been configured, if has a sail allow no throttle - if ((has_sail() || SRV_Channels::function_assigned(SRV_Channel::k_throttle)) != SRV_Channels::function_assigned(SRV_Channel::k_steering)) { + if ((has_sail() || have_throttle) != SRV_Channels::function_assigned(SRV_Channel::k_steering)) { if (report) { GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "PreArm: check steering and throttle config"); } @@ -493,6 +524,35 @@ bool AP_MotorsUGV::pre_arm_check(bool report) const return false; } } + + // Check relays are configured for brushed with relay outputs +#if AP_RELAY_ENABLED + AP_Relay*relay = AP::relay(); + if ((_pwm_type == PWM_TYPE_BRUSHED_WITH_RELAY) && (relay != nullptr)) { + // If a output is configured its relay must be enabled + struct RelayTable { + bool output_assigned; + AP_Relay_Params::FUNCTION fun; + }; + + const RelayTable relay_table[] = { + { have_throttle || have_throttle_left || (SRV_Channels::function_assigned(SRV_Channel::k_motor1) && (_motors_num >= 1)), AP_Relay_Params::FUNCTION::BRUSHED_REVERSE_1 }, + { have_throttle_right || (SRV_Channels::function_assigned(SRV_Channel::k_motor2) && (_motors_num >= 2)), AP_Relay_Params::FUNCTION::BRUSHED_REVERSE_2 }, + { SRV_Channels::function_assigned(SRV_Channel::k_motor3) && (_motors_num >= 3), AP_Relay_Params::FUNCTION::BRUSHED_REVERSE_3 }, + { SRV_Channels::function_assigned(SRV_Channel::k_motor4) && (_motors_num >= 4), AP_Relay_Params::FUNCTION::BRUSHED_REVERSE_4 }, + }; + + for (uint8_t i=0; ienabled(relay_table[i].fun)) { + if (report) { + gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: relay function %u unassigned", uint8_t(relay_table[i].fun)); + } + return false; + } + } + } +#endif + return true; } @@ -918,9 +978,9 @@ void AP_MotorsUGV::output_throttle(SRV_Channel::Aux_servo_function_t function, f throttle = get_rate_controlled_throttle(function, throttle, dt); // set relay if necessary -#if AP_SERVORELAYEVENTS_ENABLED && AP_RELAY_ENABLED - if (_pwm_type == PWM_TYPE_BRUSHED_WITH_RELAY) { - auto &_relayEvents { *AP::servorelayevents() }; +#if AP_RELAY_ENABLED + AP_Relay*relay = AP::relay(); + if ((_pwm_type == PWM_TYPE_BRUSHED_WITH_RELAY) && (relay != nullptr)) { // find the output channel, if not found return const SRV_Channel *out_chan = SRV_Channels::get_channel_for(function); @@ -930,30 +990,31 @@ void AP_MotorsUGV::output_throttle(SRV_Channel::Aux_servo_function_t function, f const int8_t reverse_multiplier = out_chan->get_reversed() ? -1 : 1; bool relay_high = is_negative(reverse_multiplier * throttle); + AP_Relay_Params::FUNCTION relay_function; switch (function) { case SRV_Channel::k_throttle: case SRV_Channel::k_throttleLeft: case SRV_Channel::k_motor1: - _relayEvents.do_set_relay(0, relay_high); + default: + relay_function = AP_Relay_Params::FUNCTION::BRUSHED_REVERSE_1; break; case SRV_Channel::k_throttleRight: case SRV_Channel::k_motor2: - _relayEvents.do_set_relay(1, relay_high); + relay_function = AP_Relay_Params::FUNCTION::BRUSHED_REVERSE_2; break; case SRV_Channel::k_motor3: - _relayEvents.do_set_relay(2, relay_high); + relay_function = AP_Relay_Params::FUNCTION::BRUSHED_REVERSE_3; break; case SRV_Channel::k_motor4: - _relayEvents.do_set_relay(3, relay_high); - break; - default: - // do nothing + relay_function = AP_Relay_Params::FUNCTION::BRUSHED_REVERSE_4; break; } + relay->set(relay_function, relay_high); + // invert the output to always have positive value calculated by calc_pwm throttle = reverse_multiplier * fabsf(throttle); } -#endif // AP_SERVORELAYEVENTS_ENABLED && AP_RELAY_ENABLED +#endif // AP_RELAY_ENABLED // output to servo channel switch (function) { diff --git a/libraries/AR_Motors/AP_MotorsUGV.h b/libraries/AR_Motors/AP_MotorsUGV.h index df61e8734d974f..42c2df5377ae98 100644 --- a/libraries/AR_Motors/AP_MotorsUGV.h +++ b/libraries/AR_Motors/AP_MotorsUGV.h @@ -114,6 +114,9 @@ class AP_MotorsUGV { // returns true if the vehicle is omni bool is_omni() const { return _frame_type != FRAME_TYPE_UNDEFINED && _motors_num > 0; } + // Return the relay index that would be used for param conversion to relay functions + bool get_legacy_relay_index(int8_t &index1, int8_t &index2, int8_t &index3, int8_t &index4) const; + // structure for holding motor limit flags struct AP_MotorsUGV_limit { uint8_t steer_left : 1; // we have reached the steering controller's left most limit From f907694c6e3e71ffe95c22441061510630ce81a4 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 9 Dec 2023 19:12:10 +0000 Subject: [PATCH 0176/1335] AP_Relay: add rover motor reverse functions --- libraries/AP_Relay/AP_Relay.cpp | 51 +++++++++++++++++++++----- libraries/AP_Relay/AP_Relay_Params.cpp | 11 +++++- libraries/AP_Relay/AP_Relay_Params.h | 4 ++ 3 files changed, 55 insertions(+), 11 deletions(-) diff --git a/libraries/AP_Relay/AP_Relay.cpp b/libraries/AP_Relay/AP_Relay.cpp index 02b9816a089ae7..f9c7cbfa35d5c5 100644 --- a/libraries/AP_Relay/AP_Relay.cpp +++ b/libraries/AP_Relay/AP_Relay.cpp @@ -19,6 +19,11 @@ #include #include +#include +#if APM_BUILD_TYPE(APM_BUILD_Rover) +#include +#endif + #if CONFIG_HAL_BOARD == HAL_BOARD_SITL #define RELAY1_PIN_DEFAULT 13 @@ -146,6 +151,14 @@ void AP_Relay::convert_params() } #endif +#if APM_BUILD_TYPE(APM_BUILD_Rover) + int8_t rover_relay[] = { -1, -1, -1, -1 }; + AP_MotorsUGV *motors = AP::motors_ugv(); + if (motors != nullptr) { + motors->get_legacy_relay_index(rover_relay[0], rover_relay[1], rover_relay[2], rover_relay[3]); + } +#endif + // Find old default param int8_t default_state = 0; // off was the old behaviour const bool have_default = AP_Param::get_param_by_index(this, 4, AP_PARAM_INT8, &default_state); @@ -165,29 +178,47 @@ void AP_Relay::convert_params() int8_t pin = 0; if (!_params[i].pin.configured() && AP_Param::get_param_by_index(this, param_index, AP_PARAM_INT8, &pin) && (pin >= 0)) { - // Copy old pin parameter + // Copy old pin parameter if valid _params[i].pin.set_and_save(pin); } - if (_params[i].pin < 0) { - // Don't enable if pin is invalid - continue; - } - // Valid pin, this is either due to the param conversion or default value // Work out what function this relay should be + AP_Relay_Params::Function new_fun; if (i == chute_relay) { - _params[i].function.set_and_save(int8_t(AP_Relay_Params::Function::parachute)); + new_fun = AP_Relay_Params::Function::parachute; } else if (i == ice_relay) { - _params[i].function.set_and_save(int8_t(AP_Relay_Params::Function::ignition)); + new_fun = AP_Relay_Params::Function::ignition; } else if (i == cam_relay) { - _params[i].function.set_and_save(int8_t(AP_Relay_Params::Function::camera)); + new_fun = AP_Relay_Params::Function::camera; + +#if APM_BUILD_TYPE(APM_BUILD_Rover) + } else if (i == rover_relay[0]) { + new_fun = AP_Relay_Params::Function::brushed_reverse_1; + + } else if (i == rover_relay[1]) { + new_fun = AP_Relay_Params::Function::brushed_reverse_2; + + } else if (i == rover_relay[2]) { + new_fun = AP_Relay_Params::Function::brushed_reverse_3; + + } else if (i == rover_relay[3]) { + new_fun = AP_Relay_Params::Function::brushed_reverse_4; +#endif } else { - _params[i].function.set_and_save(int8_t(AP_Relay_Params::Function::relay)); + if (_params[i].pin < 0) { + // Don't enable as numbered relay if pin is invalid + // Other functions should be enabled with a invalid pin + // This will result in a pre-arm promoting the user to resolve + continue; + } + new_fun = AP_Relay_Params::Function::relay; } + _params[i].function.set_and_save(int8_t(new_fun)); + // Set the default state if (have_default) { diff --git a/libraries/AP_Relay/AP_Relay_Params.cpp b/libraries/AP_Relay/AP_Relay_Params.cpp index 9ea593cea6f65d..37b04e89d34be2 100644 --- a/libraries/AP_Relay/AP_Relay_Params.cpp +++ b/libraries/AP_Relay/AP_Relay_Params.cpp @@ -5,7 +5,16 @@ const AP_Param::GroupInfo AP_Relay_Params::var_info[] = { // @Param: FUNCTION // @DisplayName: Relay function // @Description: The function the relay channel is mapped to. - // @Values: 0:None,1:Relay,2:Ignition,3:Parachute,4:Camera + // @Values: 0:None + // @Values: 1:Relay + // @Values{Plane}: 2:Ignition + // @Values{Plane, Copter}: 3:Parachute + // @Values: 4:Camera + // @Values{Rover}: 5:Bushed motor reverse 1 throttle or throttle-left or omni motor 1 + // @Values{Rover}: 6:Bushed motor reverse 2 throttle-right or omni motor 2 + // @Values{Rover}: 7:Bushed motor reverse 3 omni motor 3 + // @Values{Rover}: 8:Bushed motor reverse 4 omni motor 4 + // @User: Standard AP_GROUPINFO_FLAGS("FUNCTION", 1, AP_Relay_Params, function, (float)Function::none, AP_PARAM_FLAG_ENABLE), diff --git a/libraries/AP_Relay/AP_Relay_Params.h b/libraries/AP_Relay/AP_Relay_Params.h index 6e9105dbc7ddb5..29161adf329113 100644 --- a/libraries/AP_Relay/AP_Relay_Params.h +++ b/libraries/AP_Relay/AP_Relay_Params.h @@ -24,6 +24,10 @@ class AP_Relay_Params { ignition = 2, parachute = 3, camera = 4, + brushed_reverse_1 = 5, + brushed_reverse_2 = 6, + brushed_reverse_3 = 7, + brushed_reverse_4 = 8, num_functions // must be the last entry }; From c917480cde61b98c3fc90224d34baef8792431ef Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 12 Dec 2023 14:02:14 +0000 Subject: [PATCH 0177/1335] AP_Relay: capitalize function enum --- libraries/AP_Relay/AP_Relay.cpp | 34 +++++++++++++------------- libraries/AP_Relay/AP_Relay.h | 4 +-- libraries/AP_Relay/AP_Relay_Params.cpp | 2 +- libraries/AP_Relay/AP_Relay_Params.h | 24 +++++++++--------- 4 files changed, 32 insertions(+), 32 deletions(-) diff --git a/libraries/AP_Relay/AP_Relay.cpp b/libraries/AP_Relay/AP_Relay.cpp index f9c7cbfa35d5c5..8c4f3f08bc31be 100644 --- a/libraries/AP_Relay/AP_Relay.cpp +++ b/libraries/AP_Relay/AP_Relay.cpp @@ -183,28 +183,28 @@ void AP_Relay::convert_params() } // Work out what function this relay should be - AP_Relay_Params::Function new_fun; + AP_Relay_Params::FUNCTION new_fun; if (i == chute_relay) { - new_fun = AP_Relay_Params::Function::parachute; + new_fun = AP_Relay_Params::FUNCTION::PARACHUTE; } else if (i == ice_relay) { - new_fun = AP_Relay_Params::Function::ignition; + new_fun = AP_Relay_Params::FUNCTION::IGNITION; } else if (i == cam_relay) { - new_fun = AP_Relay_Params::Function::camera; + new_fun = AP_Relay_Params::FUNCTION::CAMERA; #if APM_BUILD_TYPE(APM_BUILD_Rover) } else if (i == rover_relay[0]) { - new_fun = AP_Relay_Params::Function::brushed_reverse_1; + new_fun = AP_Relay_Params::FUNCTION::BRUSHED_REVERSE_1; } else if (i == rover_relay[1]) { - new_fun = AP_Relay_Params::Function::brushed_reverse_2; + new_fun = AP_Relay_Params::FUNCTION::BRUSHED_REVERSE_2; } else if (i == rover_relay[2]) { - new_fun = AP_Relay_Params::Function::brushed_reverse_3; + new_fun = AP_Relay_Params::FUNCTION::BRUSHED_REVERSE_3; } else if (i == rover_relay[3]) { - new_fun = AP_Relay_Params::Function::brushed_reverse_4; + new_fun = AP_Relay_Params::FUNCTION::BRUSHED_REVERSE_4; #endif } else { @@ -214,7 +214,7 @@ void AP_Relay::convert_params() // This will result in a pre-arm promoting the user to resolve continue; } - new_fun = AP_Relay_Params::Function::relay; + new_fun = AP_Relay_Params::FUNCTION::RELAY; } _params[i].function.set_and_save(int8_t(new_fun)); @@ -257,13 +257,13 @@ void AP_Relay::init() continue; } - const AP_Relay_Params::Function function = _params[instance].function; - if (function < AP_Relay_Params::Function::relay || function >= AP_Relay_Params::Function::num_functions) { + const AP_Relay_Params::FUNCTION function = _params[instance].function; + if (function <= AP_Relay_Params::FUNCTION::NONE || function >= AP_Relay_Params::FUNCTION::NUM_FUNCTIONS) { // invalid function, skip it continue; } - if (function == AP_Relay_Params::Function::relay) { + if (function == AP_Relay_Params::FUNCTION::RELAY) { // relay by instance number, set the state to match our output const AP_Relay_Params::DefaultState default_state = _params[instance].default_state; if ((default_state == AP_Relay_Params::DefaultState::OFF) || @@ -279,8 +279,8 @@ void AP_Relay::init() } } -void AP_Relay::set(const AP_Relay_Params::Function function, const bool value) { - if (function <= AP_Relay_Params::Function::none && function >= AP_Relay_Params::Function::num_functions) { +void AP_Relay::set(const AP_Relay_Params::FUNCTION function, const bool value) { + if (function <= AP_Relay_Params::FUNCTION::NONE && function >= AP_Relay_Params::FUNCTION::NUM_FUNCTIONS) { // invalid function return; } @@ -328,7 +328,7 @@ void AP_Relay::set(const uint8_t instance, const bool value) return; } - if (_params[instance].function != AP_Relay_Params::Function::relay) { + if (_params[instance].function != AP_Relay_Params::FUNCTION::RELAY) { return; } @@ -383,11 +383,11 @@ bool AP_Relay::get(uint8_t instance) const bool AP_Relay::enabled(uint8_t instance) const { // Must be a valid instance with function relay and pin set - return (instance < AP_RELAY_NUM_RELAYS) && (_params[instance].pin != -1) && (_params[instance].function == AP_Relay_Params::Function::relay); + return (instance < AP_RELAY_NUM_RELAYS) && (_params[instance].pin != -1) && (_params[instance].function == AP_Relay_Params::FUNCTION::RELAY); } // see if the relay is enabled -bool AP_Relay::enabled(AP_Relay_Params::Function function) const +bool AP_Relay::enabled(AP_Relay_Params::FUNCTION function) const { for (uint8_t instance = 0; instance < AP_RELAY_NUM_RELAYS; instance++) { if ((_params[instance].function == function) && (_params[instance].pin != -1)) { diff --git a/libraries/AP_Relay/AP_Relay.h b/libraries/AP_Relay/AP_Relay.h index a668e9144c71a1..51e08a4015a01d 100644 --- a/libraries/AP_Relay/AP_Relay.h +++ b/libraries/AP_Relay/AP_Relay.h @@ -55,10 +55,10 @@ class AP_Relay { bool send_relay_status(const class GCS_MAVLINK &link) const; - void set(AP_Relay_Params::Function function, bool value); + void set(AP_Relay_Params::FUNCTION function, bool value); // see if the relay is enabled - bool enabled(AP_Relay_Params::Function function) const; + bool enabled(AP_Relay_Params::FUNCTION function) const; private: static AP_Relay *singleton; diff --git a/libraries/AP_Relay/AP_Relay_Params.cpp b/libraries/AP_Relay/AP_Relay_Params.cpp index 37b04e89d34be2..afce285cd4fe4b 100644 --- a/libraries/AP_Relay/AP_Relay_Params.cpp +++ b/libraries/AP_Relay/AP_Relay_Params.cpp @@ -16,7 +16,7 @@ const AP_Param::GroupInfo AP_Relay_Params::var_info[] = { // @Values{Rover}: 8:Bushed motor reverse 4 omni motor 4 // @User: Standard - AP_GROUPINFO_FLAGS("FUNCTION", 1, AP_Relay_Params, function, (float)Function::none, AP_PARAM_FLAG_ENABLE), + AP_GROUPINFO_FLAGS("FUNCTION", 1, AP_Relay_Params, function, (float)FUNCTION::NONE, AP_PARAM_FLAG_ENABLE), // @Param: PIN // @DisplayName: Relay pin diff --git a/libraries/AP_Relay/AP_Relay_Params.h b/libraries/AP_Relay/AP_Relay_Params.h index 29161adf329113..7239dda9c9106c 100644 --- a/libraries/AP_Relay/AP_Relay_Params.h +++ b/libraries/AP_Relay/AP_Relay_Params.h @@ -18,20 +18,20 @@ class AP_Relay_Params { NO_CHANGE = 2, }; - enum class Function : uint8_t { - none = 0, - relay = 1, - ignition = 2, - parachute = 3, - camera = 4, - brushed_reverse_1 = 5, - brushed_reverse_2 = 6, - brushed_reverse_3 = 7, - brushed_reverse_4 = 8, - num_functions // must be the last entry + enum class FUNCTION : uint8_t { + NONE = 0, + RELAY = 1, + IGNITION = 2, + PARACHUTE = 3, + CAMERA = 4, + BRUSHED_REVERSE_1 = 5, + BRUSHED_REVERSE_2 = 6, + BRUSHED_REVERSE_3 = 7, + BRUSHED_REVERSE_4 = 8, + NUM_FUNCTIONS // must be the last entry }; - AP_Enum function; // relay function + AP_Enum function; // relay function AP_Int16 pin; // gpio pin number AP_Enum default_state; // default state }; From a77faaf125f1299afd191eb76d3ef788db8b4714 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Mon, 18 Dec 2023 03:24:09 +0000 Subject: [PATCH 0178/1335] AP_Relay: move from using AP_RELAY_NUM_RELAYS to ARRAY_SIZE(_params) --- libraries/AP_Relay/AP_Relay.cpp | 22 +++++++++++----------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/libraries/AP_Relay/AP_Relay.cpp b/libraries/AP_Relay/AP_Relay.cpp index 8c4f3f08bc31be..921163fbd6262f 100644 --- a/libraries/AP_Relay/AP_Relay.cpp +++ b/libraries/AP_Relay/AP_Relay.cpp @@ -164,7 +164,7 @@ void AP_Relay::convert_params() const bool have_default = AP_Param::get_param_by_index(this, 4, AP_PARAM_INT8, &default_state); // grab the old values if they were set - for (uint8_t i = 0; i < MIN(AP_RELAY_NUM_RELAYS, 6); i++) { + for (uint8_t i = 0; i < MIN(ARRAY_SIZE(_params), 6U); i++) { if (_params[i].function.configured()) { // Conversion already done, or user has configured manually continue; @@ -235,7 +235,7 @@ void AP_Relay::set_defaults() { RELAY5_PIN_DEFAULT, RELAY6_PIN_DEFAULT }; - for (uint8_t i = 0; i < MIN(uint8_t(AP_RELAY_NUM_RELAYS), ARRAY_SIZE(pins)); i++) { + for (uint8_t i = 0; i < MIN(ARRAY_SIZE(_params), ARRAY_SIZE(pins)); i++) { // set the default if (pins[i] != -1) { _params[i].pin.set_default(pins[i]); @@ -250,7 +250,7 @@ void AP_Relay::init() convert_params(); // setup the actual default values of all the pins - for (uint8_t instance = 0; instance < AP_RELAY_NUM_RELAYS; instance++) { + for (uint8_t instance = 0; instance < ARRAY_SIZE(_params); instance++) { const int8_t pin = _params[instance].pin; if (pin == -1) { // no valid pin to set it on, skip it @@ -285,7 +285,7 @@ void AP_Relay::set(const AP_Relay_Params::FUNCTION function, const bool value) { return; } - for (uint8_t instance = 0; instance < AP_RELAY_NUM_RELAYS; instance++) { + for (uint8_t instance = 0; instance < ARRAY_SIZE(_params); instance++) { if (function != _params[instance].function) { continue; } @@ -324,7 +324,7 @@ void AP_Relay::set_pin_by_instance(uint8_t instance, bool value) void AP_Relay::set(const uint8_t instance, const bool value) { - if (instance >= AP_RELAY_NUM_RELAYS) { + if (instance >= ARRAY_SIZE(_params)) { return; } @@ -337,7 +337,7 @@ void AP_Relay::set(const uint8_t instance, const bool value) void AP_Relay::toggle(uint8_t instance) { - if (instance < AP_RELAY_NUM_RELAYS) { + if (instance < ARRAY_SIZE(_params)) { set(instance, !get(instance)); } } @@ -345,7 +345,7 @@ void AP_Relay::toggle(uint8_t instance) // check settings are valid bool AP_Relay::arming_checks(size_t buflen, char *buffer) const { - for (uint8_t i=0; ivalid_pin(pin)) { char param_name_buf[14]; @@ -364,7 +364,7 @@ bool AP_Relay::arming_checks(size_t buflen, char *buffer) const bool AP_Relay::get(uint8_t instance) const { - if (instance >= AP_RELAY_NUM_RELAYS) { + if (instance >= ARRAY_SIZE(_params)) { // invalid instance return false; } @@ -383,13 +383,13 @@ bool AP_Relay::get(uint8_t instance) const bool AP_Relay::enabled(uint8_t instance) const { // Must be a valid instance with function relay and pin set - return (instance < AP_RELAY_NUM_RELAYS) && (_params[instance].pin != -1) && (_params[instance].function == AP_Relay_Params::FUNCTION::RELAY); + return (instance < ARRAY_SIZE(_params)) && (_params[instance].pin != -1) && (_params[instance].function == AP_Relay_Params::FUNCTION::RELAY); } // see if the relay is enabled bool AP_Relay::enabled(AP_Relay_Params::FUNCTION function) const { - for (uint8_t instance = 0; instance < AP_RELAY_NUM_RELAYS; instance++) { + for (uint8_t instance = 0; instance < ARRAY_SIZE(_params); instance++) { if ((_params[instance].function == function) && (_params[instance].pin != -1)) { return true; } @@ -408,7 +408,7 @@ bool AP_Relay::send_relay_status(const GCS_MAVLINK &link) const uint16_t present_mask = 0; uint16_t on_mask = 0; - for (auto i=0; i Date: Wed, 13 Dec 2023 02:52:56 +0000 Subject: [PATCH 0179/1335] AP_Motors: Heli: RotorControlState to enum class --- libraries/AP_Motors/AP_MotorsHeli.cpp | 2 +- libraries/AP_Motors/AP_MotorsHeli.h | 2 +- libraries/AP_Motors/AP_MotorsHeli_Dual.cpp | 12 ++++++------ libraries/AP_Motors/AP_MotorsHeli_Dual.h | 2 +- libraries/AP_Motors/AP_MotorsHeli_Quad.cpp | 12 ++++++------ libraries/AP_Motors/AP_MotorsHeli_Quad.h | 2 +- libraries/AP_Motors/AP_MotorsHeli_RSC.cpp | 6 +++--- libraries/AP_Motors/AP_MotorsHeli_RSC.h | 14 +++++++------- libraries/AP_Motors/AP_MotorsHeli_Single.cpp | 12 ++++++------ libraries/AP_Motors/AP_MotorsHeli_Single.h | 2 +- 10 files changed, 33 insertions(+), 33 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsHeli.cpp b/libraries/AP_Motors/AP_MotorsHeli.cpp index 52176330bac8b3..0e246ded6bd2ea 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli.cpp @@ -190,7 +190,7 @@ void AP_MotorsHeli::output_min() // move swash to mid move_actuators(0.0f,0.0f,0.5f,0.0f); - update_motor_control(ROTOR_CONTROL_STOP); + update_motor_control(AP_MotorsHeli_RSC::RotorControlState::STOP); // override limits flags set_limit_flag_pitch_roll_yaw(true); diff --git a/libraries/AP_Motors/AP_MotorsHeli.h b/libraries/AP_Motors/AP_MotorsHeli.h index 7cf311a84ca50d..82287f9b1ea5a4 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.h +++ b/libraries/AP_Motors/AP_MotorsHeli.h @@ -189,7 +189,7 @@ class AP_MotorsHeli : public AP_Motors { AP_MotorsHeli_RSC _main_rotor; // main rotor // update_motor_controls - sends commands to motor controllers - virtual void update_motor_control(RotorControlState state) = 0; + virtual void update_motor_control(AP_MotorsHeli_RSC::RotorControlState state) = 0; // run spool logic void output_logic(); diff --git a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp index 06abef19c2f76b..18a916e4ae0250 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp @@ -360,12 +360,12 @@ void AP_MotorsHeli_Dual::mix_intermeshing(float pitch_input, float roll_input, f } // update_motor_controls - sends commands to motor controllers -void AP_MotorsHeli_Dual::update_motor_control(RotorControlState state) +void AP_MotorsHeli_Dual::update_motor_control(AP_MotorsHeli_RSC::RotorControlState state) { // Send state update to motors _main_rotor.output(state); - if (state == ROTOR_CONTROL_STOP) { + if (state == AP_MotorsHeli_RSC::RotorControlState::STOP) { // set engine run enable aux output to not run position to kill engine when disarmed SRV_Channels::set_output_limit(SRV_Channel::k_engine_run_enable, SRV_Channel::Limit::MIN); } else { @@ -528,20 +528,20 @@ void AP_MotorsHeli_Dual::output_to_motors() switch (_spool_state) { case SpoolState::SHUT_DOWN: // sends minimum values out to the motors - update_motor_control(ROTOR_CONTROL_STOP); + update_motor_control(AP_MotorsHeli_RSC::RotorControlState::STOP); break; case SpoolState::GROUND_IDLE: // sends idle output to motors when armed. rotor could be static or turning (autorotation) - update_motor_control(ROTOR_CONTROL_IDLE); + update_motor_control(AP_MotorsHeli_RSC::RotorControlState::IDLE); break; case SpoolState::SPOOLING_UP: case SpoolState::THROTTLE_UNLIMITED: // set motor output based on thrust requests - update_motor_control(ROTOR_CONTROL_ACTIVE); + update_motor_control(AP_MotorsHeli_RSC::RotorControlState::ACTIVE); break; case SpoolState::SPOOLING_DOWN: // sends idle output to motors and wait for rotor to stop - update_motor_control(ROTOR_CONTROL_IDLE); + update_motor_control(AP_MotorsHeli_RSC::RotorControlState::IDLE); break; } } diff --git a/libraries/AP_Motors/AP_MotorsHeli_Dual.h b/libraries/AP_Motors/AP_MotorsHeli_Dual.h index 22b2d2502fff4e..46672faddb3004 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Dual.h +++ b/libraries/AP_Motors/AP_MotorsHeli_Dual.h @@ -65,7 +65,7 @@ class AP_MotorsHeli_Dual : public AP_MotorsHeli { void init_outputs () override; // update_motor_controls - sends commands to motor controllers - void update_motor_control(RotorControlState state) override; + void update_motor_control(AP_MotorsHeli_RSC::RotorControlState state) override; // get_swashplate - calculate movement of each swashplate based on configuration float get_swashplate(int8_t swash_num, int8_t swash_axis, float pitch_input, float roll_input, float yaw_input, float coll_input); diff --git a/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp b/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp index 2b0fd53083c23b..27ea78b251f4aa 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp @@ -145,12 +145,12 @@ void AP_MotorsHeli_Quad::calculate_roll_pitch_collective_factors() } // update_motor_controls - sends commands to motor controllers -void AP_MotorsHeli_Quad::update_motor_control(RotorControlState state) +void AP_MotorsHeli_Quad::update_motor_control(AP_MotorsHeli_RSC::RotorControlState state) { // Send state update to motors _main_rotor.output(state); - if (state == ROTOR_CONTROL_STOP) { + if (state == AP_MotorsHeli_RSC::RotorControlState::STOP) { // set engine run enable aux output to not run position to kill engine when disarmed SRV_Channels::set_output_limit(SRV_Channel::k_engine_run_enable, SRV_Channel::Limit::MIN); } else { @@ -276,20 +276,20 @@ void AP_MotorsHeli_Quad::output_to_motors() switch (_spool_state) { case SpoolState::SHUT_DOWN: // sends minimum values out to the motors - update_motor_control(ROTOR_CONTROL_STOP); + update_motor_control(AP_MotorsHeli_RSC::RotorControlState::STOP); break; case SpoolState::GROUND_IDLE: // sends idle output to motors when armed. rotor could be static or turning (autorotation) - update_motor_control(ROTOR_CONTROL_IDLE); + update_motor_control(AP_MotorsHeli_RSC::RotorControlState::IDLE); break; case SpoolState::SPOOLING_UP: case SpoolState::THROTTLE_UNLIMITED: // set motor output based on thrust requests - update_motor_control(ROTOR_CONTROL_ACTIVE); + update_motor_control(AP_MotorsHeli_RSC::RotorControlState::ACTIVE); break; case SpoolState::SPOOLING_DOWN: // sends idle output to motors and wait for rotor to stop - update_motor_control(ROTOR_CONTROL_IDLE); + update_motor_control(AP_MotorsHeli_RSC::RotorControlState::IDLE); break; } } diff --git a/libraries/AP_Motors/AP_MotorsHeli_Quad.h b/libraries/AP_Motors/AP_MotorsHeli_Quad.h index 3644255b1cb4b7..a67cb409116eb5 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Quad.h +++ b/libraries/AP_Motors/AP_MotorsHeli_Quad.h @@ -49,7 +49,7 @@ class AP_MotorsHeli_Quad : public AP_MotorsHeli { void init_outputs () override; // update_motor_controls - sends commands to motor controllers - void update_motor_control(RotorControlState state) override; + void update_motor_control(AP_MotorsHeli_RSC::RotorControlState state) override; // calculate_roll_pitch_collective_factors - setup rate factors void calculate_roll_pitch_collective_factors (); diff --git a/libraries/AP_Motors/AP_MotorsHeli_RSC.cpp b/libraries/AP_Motors/AP_MotorsHeli_RSC.cpp index bb5a1ba4f88ec3..a54c583d6a0da7 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_RSC.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_RSC.cpp @@ -275,7 +275,7 @@ void AP_MotorsHeli_RSC::output(RotorControlState state) } switch (state) { - case ROTOR_CONTROL_STOP: + case RotorControlState::STOP: // set rotor ramp to decrease speed to zero, this happens instantly inside update_rotor_ramp() update_rotor_ramp(0.0f, dt); @@ -296,7 +296,7 @@ void AP_MotorsHeli_RSC::output(RotorControlState state) _idle_throttle = get_idle_output(); break; - case ROTOR_CONTROL_IDLE: + case RotorControlState::IDLE: // set rotor ramp to decrease speed to zero update_rotor_ramp(0.0f, dt); @@ -348,7 +348,7 @@ void AP_MotorsHeli_RSC::output(RotorControlState state) _control_output = _idle_throttle; break; - case ROTOR_CONTROL_ACTIVE: + case RotorControlState::ACTIVE: // set main rotor ramp to increase to full speed update_rotor_ramp(1.0f, dt); diff --git a/libraries/AP_Motors/AP_MotorsHeli_RSC.h b/libraries/AP_Motors/AP_MotorsHeli_RSC.h index 5d06b37b43a2ea..276728ca4d1dc3 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_RSC.h +++ b/libraries/AP_Motors/AP_MotorsHeli_RSC.h @@ -30,13 +30,6 @@ // RSC governor defaults #define AP_MOTORS_HELI_RSC_GOVERNOR_RANGE_DEFAULT 100 -// rotor controller states -enum RotorControlState { - ROTOR_CONTROL_STOP = 0, - ROTOR_CONTROL_IDLE, - ROTOR_CONTROL_ACTIVE -}; - // rotor control modes enum RotorControlMode { ROTOR_CONTROL_MODE_DISABLED = 0, @@ -60,6 +53,13 @@ class AP_MotorsHeli_RSC { AP_Param::setup_object_defaults(this, var_info); }; + // rotor controller states + enum class RotorControlState { + STOP = 0, + IDLE, + ACTIVE + }; + // init_servo - servo initialization on start-up void init_servo(); diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp index 30f10cda24bc37..f9ba47407a2d9f 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp @@ -347,13 +347,13 @@ uint32_t AP_MotorsHeli_Single::get_motor_mask() } // update_motor_controls - sends commands to motor controllers -void AP_MotorsHeli_Single::update_motor_control(RotorControlState state) +void AP_MotorsHeli_Single::update_motor_control(AP_MotorsHeli_RSC::RotorControlState state) { // Send state update to motors _tail_rotor.output(state); _main_rotor.output(state); - if (state == ROTOR_CONTROL_STOP){ + if (state == AP_MotorsHeli_RSC::RotorControlState::STOP){ // set engine run enable aux output to not run position to kill engine when disarmed SRV_Channels::set_output_limit(SRV_Channel::k_engine_run_enable, SRV_Channel::Limit::MIN); } else { @@ -504,20 +504,20 @@ void AP_MotorsHeli_Single::output_to_motors() switch (_spool_state) { case SpoolState::SHUT_DOWN: // sends minimum values out to the motors - update_motor_control(ROTOR_CONTROL_STOP); + update_motor_control(AP_MotorsHeli_RSC::RotorControlState::STOP); break; case SpoolState::GROUND_IDLE: // sends idle output to motors when armed. rotor could be static or turning (autorotation) - update_motor_control(ROTOR_CONTROL_IDLE); + update_motor_control(AP_MotorsHeli_RSC::RotorControlState::IDLE); break; case SpoolState::SPOOLING_UP: case SpoolState::THROTTLE_UNLIMITED: // set motor output based on thrust requests - update_motor_control(ROTOR_CONTROL_ACTIVE); + update_motor_control(AP_MotorsHeli_RSC::RotorControlState::ACTIVE); break; case SpoolState::SPOOLING_DOWN: // sends idle output to motors and wait for rotor to stop - update_motor_control(ROTOR_CONTROL_IDLE); + update_motor_control(AP_MotorsHeli_RSC::RotorControlState::IDLE); break; } diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.h b/libraries/AP_Motors/AP_MotorsHeli_Single.h index 870d4801c96050..61e6588a5ab9fb 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.h +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.h @@ -86,7 +86,7 @@ class AP_MotorsHeli_Single : public AP_MotorsHeli { void init_outputs() override; // update_motor_controls - sends commands to motor controllers - void update_motor_control(RotorControlState state) override; + void update_motor_control(AP_MotorsHeli_RSC::RotorControlState state) override; // heli_move_actuators - moves swash plate and tail rotor void move_actuators(float roll_out, float pitch_out, float coll_in, float yaw_out) override; From 1bcf69e0c7f55139ee0d9a5bb16577428016336a Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Wed, 13 Dec 2023 03:06:29 +0000 Subject: [PATCH 0180/1335] AP_Motors: Heli: add helper to convert from AP_Motors::SpoolState to AP_MotorsHeli_RSC::RotorControlState --- libraries/AP_Motors/AP_MotorsHeli.cpp | 23 ++++++++++++++++++++ libraries/AP_Motors/AP_MotorsHeli.h | 3 +++ libraries/AP_Motors/AP_MotorsHeli_Dual.cpp | 21 ++---------------- libraries/AP_Motors/AP_MotorsHeli_Quad.cpp | 21 ++---------------- libraries/AP_Motors/AP_MotorsHeli_Single.cpp | 20 +---------------- 5 files changed, 31 insertions(+), 57 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsHeli.cpp b/libraries/AP_Motors/AP_MotorsHeli.cpp index 0e246ded6bd2ea..fc93264ed5d7f9 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli.cpp @@ -590,3 +590,26 @@ void AP_MotorsHeli::set_desired_rotor_speed(float desired_speed) { _main_rotor.set_desired_speed(desired_speed); } + +// Converts AP_Motors::SpoolState from _spool_state variable to AP_MotorsHeli_RSC::RotorControlState +AP_MotorsHeli_RSC::RotorControlState AP_MotorsHeli::get_rotor_control_state() const +{ + switch (_spool_state) { + case SpoolState::SHUT_DOWN: + // sends minimum values out to the motors + return AP_MotorsHeli_RSC::RotorControlState::STOP; + case SpoolState::GROUND_IDLE: + // sends idle output to motors when armed. rotor could be static or turning (autorotation) + return AP_MotorsHeli_RSC::RotorControlState::IDLE; + case SpoolState::SPOOLING_UP: + case SpoolState::THROTTLE_UNLIMITED: + // set motor output based on thrust requests + return AP_MotorsHeli_RSC::RotorControlState::ACTIVE; + case SpoolState::SPOOLING_DOWN: + // sends idle output to motors and wait for rotor to stop + return AP_MotorsHeli_RSC::RotorControlState::IDLE; + } + + // Should be unreachable, but needed to keep the compiler happy + return AP_MotorsHeli_RSC::RotorControlState::STOP; +} diff --git a/libraries/AP_Motors/AP_MotorsHeli.h b/libraries/AP_Motors/AP_MotorsHeli.h index 82287f9b1ea5a4..f2a8ce6100400b 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.h +++ b/libraries/AP_Motors/AP_MotorsHeli.h @@ -191,6 +191,9 @@ class AP_MotorsHeli : public AP_Motors { // update_motor_controls - sends commands to motor controllers virtual void update_motor_control(AP_MotorsHeli_RSC::RotorControlState state) = 0; + // Converts AP_Motors::SpoolState from _spool_state variable to AP_MotorsHeli_RSC::RotorControlState + AP_MotorsHeli_RSC::RotorControlState get_rotor_control_state() const; + // run spool logic void output_logic(); diff --git a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp index 18a916e4ae0250..ddbcedc896e44f 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Dual.cpp @@ -525,25 +525,8 @@ void AP_MotorsHeli_Dual::output_to_motors() _swashplate1.output(); _swashplate2.output(); - switch (_spool_state) { - case SpoolState::SHUT_DOWN: - // sends minimum values out to the motors - update_motor_control(AP_MotorsHeli_RSC::RotorControlState::STOP); - break; - case SpoolState::GROUND_IDLE: - // sends idle output to motors when armed. rotor could be static or turning (autorotation) - update_motor_control(AP_MotorsHeli_RSC::RotorControlState::IDLE); - break; - case SpoolState::SPOOLING_UP: - case SpoolState::THROTTLE_UNLIMITED: - // set motor output based on thrust requests - update_motor_control(AP_MotorsHeli_RSC::RotorControlState::ACTIVE); - break; - case SpoolState::SPOOLING_DOWN: - // sends idle output to motors and wait for rotor to stop - update_motor_control(AP_MotorsHeli_RSC::RotorControlState::IDLE); - break; - } + update_motor_control(get_rotor_control_state()); + } // servo_test - move servos through full range of movement diff --git a/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp b/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp index 27ea78b251f4aa..515ec063e0f2c0 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Quad.cpp @@ -273,25 +273,8 @@ void AP_MotorsHeli_Quad::output_to_motors() rc_write_angle(AP_MOTORS_MOT_1+i, _out[i] * QUAD_SERVO_MAX_ANGLE); } - switch (_spool_state) { - case SpoolState::SHUT_DOWN: - // sends minimum values out to the motors - update_motor_control(AP_MotorsHeli_RSC::RotorControlState::STOP); - break; - case SpoolState::GROUND_IDLE: - // sends idle output to motors when armed. rotor could be static or turning (autorotation) - update_motor_control(AP_MotorsHeli_RSC::RotorControlState::IDLE); - break; - case SpoolState::SPOOLING_UP: - case SpoolState::THROTTLE_UNLIMITED: - // set motor output based on thrust requests - update_motor_control(AP_MotorsHeli_RSC::RotorControlState::ACTIVE); - break; - case SpoolState::SPOOLING_DOWN: - // sends idle output to motors and wait for rotor to stop - update_motor_control(AP_MotorsHeli_RSC::RotorControlState::IDLE); - break; - } + update_motor_control(get_rotor_control_state()); + } // servo_test - move servos through full range of movement diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp index f9ba47407a2d9f..6fcefd60048846 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp @@ -501,25 +501,7 @@ void AP_MotorsHeli_Single::output_to_motors() _swashplate.output(); // Output main rotor - switch (_spool_state) { - case SpoolState::SHUT_DOWN: - // sends minimum values out to the motors - update_motor_control(AP_MotorsHeli_RSC::RotorControlState::STOP); - break; - case SpoolState::GROUND_IDLE: - // sends idle output to motors when armed. rotor could be static or turning (autorotation) - update_motor_control(AP_MotorsHeli_RSC::RotorControlState::IDLE); - break; - case SpoolState::SPOOLING_UP: - case SpoolState::THROTTLE_UNLIMITED: - // set motor output based on thrust requests - update_motor_control(AP_MotorsHeli_RSC::RotorControlState::ACTIVE); - break; - case SpoolState::SPOOLING_DOWN: - // sends idle output to motors and wait for rotor to stop - update_motor_control(AP_MotorsHeli_RSC::RotorControlState::IDLE); - break; - } + update_motor_control(get_rotor_control_state()); // Output tail rotor switch (get_tail_type()) { From c98bdd155aaa2cb1b8288a2932bfaceb9c915b1c Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 15 Dec 2023 01:37:11 +0000 Subject: [PATCH 0181/1335] Plane: Quadplane: log tailsitter speed scailing in TSIT msg --- ArduPlane/Log.cpp | 19 +++++++++++++++++-- ArduPlane/defines.h | 1 + ArduPlane/quadplane.cpp | 1 - ArduPlane/quadplane.h | 1 - ArduPlane/tailsitter.cpp | 26 +++++++++++++++++++++++--- ArduPlane/tailsitter.h | 22 +++++++++++++++++++++- 6 files changed, 62 insertions(+), 8 deletions(-) diff --git a/ArduPlane/Log.cpp b/ArduPlane/Log.cpp index 55d5ab4c46b495..a5e97fe2ae4970 100644 --- a/ArduPlane/Log.cpp +++ b/ArduPlane/Log.cpp @@ -33,6 +33,9 @@ void Plane::Log_Write_Attitude(void) logger.Write_PID(LOG_PIQP_MSG, quadplane.attitude_control->get_rate_pitch_pid().get_pid_info()); logger.Write_PID(LOG_PIQY_MSG, quadplane.attitude_control->get_rate_yaw_pid().get_pid_info()); logger.Write_PID(LOG_PIQA_MSG, quadplane.pos_control->get_accel_z_pid().get_pid_info() ); + + // Write tailsitter specific log at same rate as PIDs + quadplane.tailsitter.write_log(); } if (quadplane.in_vtol_mode() && quadplane.pos_control->is_active_xy()) { logger.Write_PID(LOG_PIDN_MSG, quadplane.pos_control->get_vel_xy_pid().get_pid_info_x()); @@ -383,12 +386,11 @@ const struct LogStructure Plane::log_structure[] = { // @Field: DCRt: desired climb rate // @Field: CRt: climb rate // @Field: TMix: transition throttle mix value -// @Field: Sscl: speed scalar for tailsitter control surfaces // @Field: Trn: Transition state: 0-AirspeedWait,1-Timer,2-Done / TailSitter: 0-FW Wait,1-VTOL Wait,2-Done // @Field: Ast: Q assist active #if HAL_QUADPLANE_ENABLED { LOG_QTUN_MSG, sizeof(QuadPlane::log_QControl_Tuning), - "QTUN", "QffffffeccffBB", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DCRt,CRt,TMix,Sscl,Trn,Ast", "s----mmmnn----", "F----00000-0--" , true }, + "QTUN", "QffffffeccfBB", "TimeUS,ThI,ABst,ThO,ThH,DAlt,Alt,BAlt,DCRt,CRt,TMix,Trn,Ast", "s----mmmnn---", "F----00000---" , true }, #endif // @LoggerMessage: PIQR,PIQP,PIQY,PIQA @@ -406,6 +408,7 @@ const struct LogStructure Plane::log_structure[] = { // @Field: SRate: slew rate // @Field: Flags: bitmask of PID state flags // @FieldBitmaskEnum: Flags: log_PID_Flags +#if HAL_QUADPLANE_ENABLED { LOG_PIQR_MSG, sizeof(log_PID), "PIQR", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS , true }, { LOG_PIQP_MSG, sizeof(log_PID), @@ -414,6 +417,18 @@ const struct LogStructure Plane::log_structure[] = { "PIQY", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS , true }, { LOG_PIQA_MSG, sizeof(log_PID), "PIQA", PID_FMT, PID_LABELS, PID_UNITS, PID_MULTS , true }, +#endif + +// @LoggerMessage: TSIT +// @Description: tailsitter speed scailing values +// @Field: TimeUS: Time since system startup +// @Field: Ts: throttle scailing used for tilt motors +// @Field: Ss: speed scailing used for control surfaces method from Q_TAILSIT_GSCMSK +// @Field: Tmin: minimum output throttle caculated from disk thoery gain scale with Q_TAILSIT_MIN_VO +#if HAL_QUADPLANE_ENABLED + { LOG_TSIT_MSG, sizeof(Tailsitter::log_tailsitter), + "TSIT", "Qfff", "TimeUS,Ts,Ss,Tmin", "s---", "F---" , true }, +#endif // @LoggerMessage: PIDG // @Description: Plane Proportional/Integral/Derivative gain values for Heading when using COMMAND_INT control. diff --git a/ArduPlane/defines.h b/ArduPlane/defines.h index c7389daf49bdca..a480162eff722e 100644 --- a/ArduPlane/defines.h +++ b/ArduPlane/defines.h @@ -102,6 +102,7 @@ enum log_messages { LOG_PIDG_MSG, LOG_AETR_MSG, LOG_OFG_MSG, + LOG_TSIT_MSG, }; #define MASK_LOG_ATTITUDE_FAST (1<<0) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index db7df54d9b7313..06e18814c5a59a 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -3663,7 +3663,6 @@ void QuadPlane::Log_Write_QControl_Tuning() target_climb_rate : target_climb_rate_cms, climb_rate : int16_t(inertial_nav.get_velocity_z_up_cms()), throttle_mix : attitude_control->get_throttle_mix(), - speed_scaler : tailsitter.log_spd_scaler, transition_state : transition->get_log_transition_state(), assist : assisted_flight, }; diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index ad5e6251af2df8..2c5a624ff4a4e4 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -156,7 +156,6 @@ class QuadPlane int16_t target_climb_rate; int16_t climb_rate; float throttle_mix; - float speed_scaler; uint8_t transition_state; uint8_t assist; }; diff --git a/ArduPlane/tailsitter.cpp b/ArduPlane/tailsitter.cpp index f40fa33d1f26eb..a94e4cb8c5ea0a 100644 --- a/ArduPlane/tailsitter.cpp +++ b/ArduPlane/tailsitter.cpp @@ -755,9 +755,6 @@ void Tailsitter::speed_scaling(void) spd_scaler /= plane.barometer.get_air_density_ratio(); } - // record for QTUN log - log_spd_scaler = spd_scaler; - const SRV_Channel::Aux_servo_function_t functions[] = { SRV_Channel::Aux_servo_function_t::k_aileron, SRV_Channel::Aux_servo_function_t::k_elevator, @@ -778,6 +775,29 @@ void Tailsitter::speed_scaling(void) if (tailsitter_motors != nullptr) { tailsitter_motors->set_min_throttle(disk_loading_min_throttle); } + + // Record for log + log_data.throttle_scaler = throttle_scaler; + log_data.speed_scaler = spd_scaler; + log_data.min_throttle = disk_loading_min_throttle; + +} + +// Write tailsitter specific log +void Tailsitter::write_log() +{ + if (!enabled()) { + return; + } + + struct log_tailsitter pkt = { + LOG_PACKET_HEADER_INIT(LOG_TSIT_MSG), + time_us : AP_HAL::micros64(), + throttle_scaler : log_data.throttle_scaler, + speed_scaler : log_data.speed_scaler, + min_throttle : log_data.min_throttle, + }; + plane.logger.WriteBlock(&pkt, sizeof(pkt)); } // return true if pitch control should be relaxed diff --git a/ArduPlane/tailsitter.h b/ArduPlane/tailsitter.h index 4f2ff33c3ba370..fbf26702f8ca9f 100644 --- a/ArduPlane/tailsitter.h +++ b/ArduPlane/tailsitter.h @@ -17,6 +17,7 @@ #include #include "transition.h" #include +#include class QuadPlane; class AP_MotorsMulticopter; @@ -66,9 +67,11 @@ friend class Plane; // return true if pitch control should be relaxed bool relax_pitch(); + // Write tailsitter specific log + void write_log(); + // tailsitter speed scaler float last_spd_scaler = 1.0f; // used to slew rate limiting with TAILSITTER_GSCL_ATT_THR option - float log_spd_scaler; // for QTUN log static const struct AP_Param::GroupInfo var_info[]; @@ -112,6 +115,23 @@ friend class Plane; private: + // Tailsitter specific log message + struct PACKED log_tailsitter { + LOG_PACKET_HEADER; + uint64_t time_us; + float throttle_scaler; + float speed_scaler; + float min_throttle; + }; + + // Data to be logged + struct { + float throttle_scaler; + float speed_scaler; + float min_throttle; + } log_data; + + bool setup_complete; // true when flying a tilt-vectored tailsitter From e33f0269d304f5da518530d50c847627bccf02de Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 18 Dec 2023 09:17:32 +1100 Subject: [PATCH 0182/1335] Tools: improved benchmarking of time functions --- Tools/CPUInfo/CPUInfo.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/Tools/CPUInfo/CPUInfo.cpp b/Tools/CPUInfo/CPUInfo.cpp index a20db4924d95d6..4929cc51a759b9 100644 --- a/Tools/CPUInfo/CPUInfo.cpp +++ b/Tools/CPUInfo/CPUInfo.cpp @@ -15,6 +15,7 @@ #if HAL_WITH_DSP && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS #include +#include #endif void setup(); @@ -129,6 +130,13 @@ static void show_timings(void) TIMEIT("millis16()", AP_HAL::millis16(), 200); TIMEIT("micros64()", AP_HAL::micros64(), 200); +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS + TIMEIT("hrt_micros32()", hrt_micros32(), 200); + TIMEIT("hrt_micros64()", hrt_micros64(), 200); + TIMEIT("hrt_millis32()", hrt_millis32(), 200); + TIMEIT("hrt_millis64()", hrt_millis64(), 200); +#endif + TIMEIT("fadd", v_out += v_f, 100); TIMEIT("fsub", v_out -= v_f, 100); TIMEIT("fmul", v_out *= v_f, 100); From 6dbc3b6a70ad15a5d0d80411f408d1fb0e7d6ea9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 18 Dec 2023 12:15:35 +1100 Subject: [PATCH 0183/1335] HAL_ChibiOS: speed up millis(), micros64() etc these use faster primitives and an assembly division by 1000 to get between 2x and 3x speedup on these critical calls --- libraries/AP_HAL_ChibiOS/hwdef/common/hrt.c | 82 +++++++++++++++------ libraries/AP_HAL_ChibiOS/hwdef/common/hrt.h | 38 ++++++++++ libraries/AP_HAL_ChibiOS/system.cpp | 5 +- 3 files changed, 101 insertions(+), 24 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/hrt.c b/libraries/AP_HAL_ChibiOS/hwdef/common/hrt.c index 6c481475dab5de..f99110f08093b4 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/hrt.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/hrt.c @@ -37,7 +37,7 @@ boot in microseconds, and which wraps at 0xFFFFFFFF. On top of this base function we build get_systime_us32() which has - the same property, but which also maintains timer_base_us64 to allow + the same property, but which allows for a startup offset for micros64() */ @@ -68,48 +68,84 @@ static uint32_t system_time_u32_us(void) #error "unsupported timer resolution" #endif -// offset for micros64() -static uint64_t timer_base_us64; - static uint32_t get_systime_us32(void) { - static uint32_t last_us32; uint32_t now = system_time_u32_us(); #ifdef AP_BOARD_START_TIME now += AP_BOARD_START_TIME; #endif - if (now < last_us32) { - const uint64_t dt_us = 0x100000000ULL; - timer_base_us64 += dt_us; - } - last_us32 = now; return now; } /* - for the exposed functions we use chSysGetStatusAndLockX() to prevent - an interrupt changing the globals while allowing this call from any - context + for the exposed functions we use chVTGetTimeStampI which handles + wrap and directly gives a uint64_t (aka systimestamp_t) */ +uint64_t hrt_micros64I() +{ +#ifdef AP_BOARD_START_TIME + return chVTGetTimeStampI() + AP_BOARD_START_TIME; +#endif + return chVTGetTimeStampI(); +} + +static inline bool is_locked(void) { + return !port_irq_enabled(port_get_irq_status()); +} + uint64_t hrt_micros64() { - syssts_t sts = chSysGetStatusAndLockX(); - uint32_t now = get_systime_us32(); - uint64_t ret = timer_base_us64 + now; - chSysRestoreStatusX(sts); - return ret; + if (is_locked()) { + return chVTGetTimeStampI(); + } else if (port_is_isr_context()) { + uint64_t ret; + chSysLockFromISR(); + ret = chVTGetTimeStampI(); + chSysUnlockFromISR(); + return ret; + } else { + uint64_t ret; + chSysLock(); + ret = chVTGetTimeStampI(); + chSysUnlock(); + return ret; + } } uint32_t hrt_micros32() { - syssts_t sts = chSysGetStatusAndLockX(); - uint32_t ret = get_systime_us32(); - chSysRestoreStatusX(sts); - return ret; +#if CH_CFG_ST_RESOLUTION == 16 + // boards with 16 bit timers need to call get_systime_us32() in a + // lock state because on those boards we have local static + // variables that need protection + if (is_locked()) { + return get_systime_us32(); + } else if (port_is_isr_context()) { + uint32_t ret; + chSysLockFromISR(); + ret = get_systime_us32(); + chSysUnlockFromISR(); + return ret; + } else { + uint32_t ret; + chSysLock(); + ret = get_systime_us32(); + chSysUnlock(); + return ret; + } +#else + return get_systime_us32(); +#endif } +uint32_t hrt_millis64() +{ + return _hrt_div1000(hrt_micros64()); +} + uint32_t hrt_millis32() { - return (uint32_t)(hrt_micros64() / 1000U); + return (uint32_t)(hrt_millis64()); } + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/hrt.h b/libraries/AP_HAL_ChibiOS/hwdef/common/hrt.h index 9ecfd9a373c812..c11637ec12e3e5 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/hrt.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/hrt.h @@ -4,10 +4,48 @@ #ifdef __cplusplus extern "C" { #endif + void hrt_init(void); uint64_t hrt_micros64(void); +uint64_t hrt_micros64I(void); // from locked context +uint64_t hrt_micros64_from_ISR(void); // from an ISR uint32_t hrt_micros32(void); uint32_t hrt_millis32(void); +uint32_t hrt_millis32I(void); // from locked context +uint32_t hrt_millis32_from_ISR(void); // from an ISR +uint32_t hrt_millis64(void); + +/* + thanks to: + https://0x414b.com/2021/04/16/arm-division.html + */ +static inline uint64_t _hrt_umul64x64hi(uint32_t b, uint32_t a, uint32_t d, uint32_t c) +{ + __asm__ ("\n\ +umull r4, r5, %[b], %[d] \n\ +umull %[d], r4, %[a], %[d] \n\ +adds r5, %[d] \n\ +umull %[d], %[a], %[a], %[c] \n\ +adcs r4, %[d] \n\ +adc %[a], #0 \n\ +umull %[c], %[b], %[b], %[c] \n\ +adds r5, %[c] \n\ +adcs %[b], r4 \n\ +adc %[a], #0 \n\ +" : [a] "+r" (a), [b] "+r" (b), [c] "+r" (c), [d] "+r" (d) : : "r4", "r5"); + return (uint64_t) a << 32 | b; +} + +/* + return x / 1000 + faster than the gcc implementation using _hrt_umul64x64hi() by about 3x +*/ +static inline uint64_t _hrt_div1000(uint64_t x) +{ + x >>= 3U; + return _hrt_umul64x64hi((uint32_t)x, x >> 32U, 0xe353f7cfU, 0x20c49ba5U) >> 4U; +} + #ifdef __cplusplus } #endif diff --git a/libraries/AP_HAL_ChibiOS/system.cpp b/libraries/AP_HAL_ChibiOS/system.cpp index d58b069f7b73f7..183484c4280b31 100644 --- a/libraries/AP_HAL_ChibiOS/system.cpp +++ b/libraries/AP_HAL_ChibiOS/system.cpp @@ -30,6 +30,9 @@ #include "hal.h" #include +// we rely on systimestamp_t for 64 bit timestamps +static_assert(sizeof(uint64_t) == sizeof(systimestamp_t), "unexpected systimestamp_t size"); + #if CH_CFG_ST_RESOLUTION == 16 static_assert(sizeof(systime_t) == 2, "expected 16 bit systime_t"); #elif CH_CFG_ST_RESOLUTION == 32 @@ -385,7 +388,7 @@ __FASTRAMFUNC__ uint64_t micros64() __FASTRAMFUNC__ uint64_t millis64() { - return hrt_micros64() / 1000U; + return hrt_millis64(); } From 388fab1ef8e2290eaca09643e528859a2a60c14e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 18 Dec 2023 12:15:52 +1100 Subject: [PATCH 0184/1335] Tools: added testing of _hrt_div1000() --- Tools/CPUInfo/CPUInfo.cpp | 43 +++++++++++++++++++++++++++++++++++++-- 1 file changed, 41 insertions(+), 2 deletions(-) diff --git a/Tools/CPUInfo/CPUInfo.cpp b/Tools/CPUInfo/CPUInfo.cpp index 4929cc51a759b9..2b2ee927527340 100644 --- a/Tools/CPUInfo/CPUInfo.cpp +++ b/Tools/CPUInfo/CPUInfo.cpp @@ -13,10 +13,13 @@ #include #include "EKF_Maths.h" -#if HAL_WITH_DSP && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +#if HAL_WITH_DSP #include -#include #endif +#include +#include +#endif // HAL_BOARD_CHIBIOS void setup(); void loop(); @@ -202,11 +205,47 @@ static void show_timings(void) TIMEIT("SEM", { WITH_SEMAPHORE(sem); v_out_32 += v_32;}, 100); } +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +static void test_div1000(void) +{ + hal.console->printf("Testing div1000\n"); + for (uint32_t i=0; i<2000000; i++) { + uint64_t v; + hal.util->get_random_vals((uint8_t*)&v, sizeof(v)); + uint64_t v1 = v / 1000ULL; + uint64_t v2 = _hrt_div1000(v); + if (v1 != v2) { + AP_HAL::panic("ERROR: 0x%llx v1=0x%llx v2=0x%llx\n", + (unsigned long long)v, (unsigned long long)v1, (unsigned long long)v2); + return; + } + } + // test from locked context + for (uint32_t i=0; i<2000000; i++) { + uint64_t v; + hal.util->get_random_vals((uint8_t*)&v, sizeof(v)); + chSysLock(); + uint64_t v1 = v / 1000ULL; + uint64_t v2 = _hrt_div1000(v); + chSysUnlock(); + if (v1 != v2) { + AP_HAL::panic("ERROR: 0x%llx v1=0x%llx v2=0x%llx\n", + (unsigned long long)v, (unsigned long long)v1, (unsigned long long)v2); + return; + } + } + hal.console->printf("div1000 OK\n"); +} +#endif + void loop() { show_sizes(); hal.console->printf("\n"); show_timings(); +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS + test_div1000(); +#endif hal.console->printf("\n"); hal.scheduler->delay(3000); } From 6fa2829ad42cbf99a2b6d30906d6bba7b20ffdcf Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 18 Dec 2023 19:42:20 +0900 Subject: [PATCH 0185/1335] Rover: 4.4.0 release notes --- Rover/release-notes.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Rover/release-notes.txt b/Rover/release-notes.txt index 96c3a1ca40427a..5d6c5cae88c073 100644 --- a/Rover/release-notes.txt +++ b/Rover/release-notes.txt @@ -1,6 +1,6 @@ Rover Release Notes: ------------------------------------------------------------------ -Rover 4.4.0-beta11 05-Dec-2023 +Rover 4.4.0 19-Dec-2023 / Rover 4.4.0-beta11 05-Dec-2023 Changes from 4.4.0-beta10 1) Autopilot related enhancement and fixes - CubeOrange Sim-on-hardware compilation fix From d78cd222858b35ddb08aefd1af3bdc9ffedd4aeb Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 18 Dec 2023 19:42:48 +0900 Subject: [PATCH 0186/1335] Copter: 4.4.4 release notes --- ArduCopter/ReleaseNotes.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/ReleaseNotes.txt b/ArduCopter/ReleaseNotes.txt index 62b8ca786a0e61..6ccc0923aa6fe0 100644 --- a/ArduCopter/ReleaseNotes.txt +++ b/ArduCopter/ReleaseNotes.txt @@ -1,6 +1,6 @@ ArduPilot Copter Release Notes: ------------------------------------------------------------------ -Copter 4.4.4 05-Dec-2023 +Copter 4.4.4 19-Dec-2023 / 4.4.4-beta1 05-Dec-2023 Changes from 4.4.3 1) Autopilot related enhancement and fixes - CubeOrange Sim-on-hardware compilation fix From 0ec994c46b76a365ed839f8a608bc377b5ff23b9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 19 Dec 2023 15:05:45 +1100 Subject: [PATCH 0187/1335] Plane: release notes for 4.4.4 --- ArduPlane/ReleaseNotes.txt | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduPlane/ReleaseNotes.txt b/ArduPlane/ReleaseNotes.txt index 7c1d1f296ad642..9f965c9b002398 100644 --- a/ArduPlane/ReleaseNotes.txt +++ b/ArduPlane/ReleaseNotes.txt @@ -1,5 +1,5 @@ -Release 4.4.4-beta1 5th December 2023 -------------------------------------- +Release 4.4.4 19th December 2023 +-------------------------------- Changes from 4.4.3: From 23e67f7b535dcf12447ba803089be4dcd5daaf89 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 16 Dec 2023 08:43:37 +1100 Subject: [PATCH 0188/1335] waf: enable CAN deadlines in AP_Periph --- Tools/ardupilotwaf/boards.py | 28 +++++++++++++++------------- Tools/ardupilotwaf/chibios.py | 16 ++++++++++++++++ 2 files changed, 31 insertions(+), 13 deletions(-) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index c7644558e979a4..d785c6161b82d6 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -438,22 +438,24 @@ def configure_env(self, cfg, env): '-Wl,--gc-sections', ] - if self.with_can and not cfg.env.AP_PERIPH: - env.AP_LIBRARIES += [ - 'AP_DroneCAN', - 'modules/DroneCAN/libcanard/*.c', - ] - if cfg.options.enable_dronecan_tests: + if self.with_can: + # for both AP_Perip and main fw enable deadlines + env.DEFINES.update(CANARD_ENABLE_DEADLINE = 1) + + if not cfg.env.AP_PERIPH: + env.AP_LIBRARIES += [ + 'AP_DroneCAN', + 'modules/DroneCAN/libcanard/*.c', + ] + if cfg.options.enable_dronecan_tests: + env.DEFINES.update(AP_TEST_DRONECAN_DRIVERS = 1) + env.DEFINES.update( - AP_TEST_DRONECAN_DRIVERS = 1 + DRONECAN_CXX_WRAPPERS = 1, + USE_USER_HELPERS = 1, + CANARD_ALLOCATE_SEM=1 ) - env.DEFINES.update( - DRONECAN_CXX_WRAPPERS = 1, - USE_USER_HELPERS = 1, - CANARD_ENABLE_DEADLINE = 1, - CANARD_ALLOCATE_SEM=1 - ) if cfg.options.build_dates: diff --git a/Tools/ardupilotwaf/chibios.py b/Tools/ardupilotwaf/chibios.py index 0262eeecffa021..dbc6c9b18779e8 100644 --- a/Tools/ardupilotwaf/chibios.py +++ b/Tools/ardupilotwaf/chibios.py @@ -468,6 +468,20 @@ def setup_canmgr_build(cfg): cfg.get_board().with_can = True +def setup_canperiph_build(cfg): + '''enable CAN build for peripherals''' + env = cfg.env + env.DEFINES += [ + 'CANARD_ENABLE_DEADLINE=1', + ] + + if cfg.env.HAL_CANFD_SUPPORTED: + env.DEFINES += ['UAVCAN_SUPPORT_CANFD=1'] + else: + env.DEFINES += ['UAVCAN_SUPPORT_CANFD=0'] + + cfg.get_board().with_can = True + def load_env_vars(env): '''optionally load extra environment variables from env.py in the build directory''' print("Checking for env.py") @@ -578,6 +592,8 @@ def bldpath(path): load_env_vars(cfg.env) if env.HAL_NUM_CAN_IFACES and not env.AP_PERIPH: setup_canmgr_build(cfg) + if env.HAL_NUM_CAN_IFACES and env.AP_PERIPH and not env.BOOTLOADER: + setup_canperiph_build(cfg) if env.HAL_NUM_CAN_IFACES and env.AP_PERIPH and int(env.HAL_NUM_CAN_IFACES)>1 and not env.BOOTLOADER: env.DEFINES += [ 'CANARD_MULTI_IFACE=1' ] setup_optimization(cfg.env) From cd72dcb73f914f19f3fd06ac019dee1a46e3463c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 16 Dec 2023 08:44:25 +1100 Subject: [PATCH 0189/1335] AP_Periph: use a 1s deadline for packets this fixes an issue with early discard of packets on MCUs with small number of transmit slots and higher packet send count --- Tools/AP_Periph/AP_Periph.h | 14 ++- Tools/AP_Periph/can.cpp | 206 ++++++++++++++++++------------------ Tools/AP_Periph/gps.cpp | 44 +++----- 3 files changed, 126 insertions(+), 138 deletions(-) diff --git a/Tools/AP_Periph/AP_Periph.h b/Tools/AP_Periph/AP_Periph.h index b0e0839d6f08c9..26468de8c1e6a5 100644 --- a/Tools/AP_Periph/AP_Periph.h +++ b/Tools/AP_Periph/AP_Periph.h @@ -424,8 +424,16 @@ class AP_Periph_FW { uint16_t data_type_id, uint8_t priority, const void* payload, - uint16_t payload_len); - + uint16_t payload_len, + uint8_t iface_mask=0); + + bool canard_respond(CanardInstance* canard_instance, + CanardRxTransfer* transfer, + uint64_t data_type_signature, + uint16_t data_type_id, + const uint8_t *payload, + uint16_t payload_len); + void onTransferReceived(CanardInstance* canard_instance, CanardRxTransfer* transfer); bool shouldAcceptTransfer(const CanardInstance* canard_instance, @@ -473,7 +481,7 @@ class AP_Periph_FW { #if HAL_PERIPH_CAN_MIRROR void processMirror(void); #endif // HAL_PERIPH_CAN_MIRROR - void cleanup_stale_transactions(uint64_t ×tamp_usec); + void cleanup_stale_transactions(uint64_t timestamp_usec); void update_rx_protocol_stats(int16_t res); void node_status_send(void); bool can_do_dna(); diff --git a/Tools/AP_Periph/can.cpp b/Tools/AP_Periph/can.cpp index 89611c5cac5477..4cb0d495ed90c3 100644 --- a/Tools/AP_Periph/can.cpp +++ b/Tools/AP_Periph/can.cpp @@ -62,6 +62,9 @@ extern AP_Periph_FW periph; #endif #endif +// timeout all frames at 1s +#define CAN_FRAME_TIMEOUT 1000000ULL + #define DEBUG_PKTS 0 #if HAL_PERIPH_CAN_MIRROR @@ -207,25 +210,12 @@ void AP_Periph_FW::handle_get_node_info(CanardInstance* canard_instance, uint16_t total_size = uavcan_protocol_GetNodeInfoResponse_encode(&pkt, buffer, !canfdout()); - const int16_t resp_res = canardRequestOrRespond(canard_instance, - transfer->source_node_id, - UAVCAN_PROTOCOL_GETNODEINFO_SIGNATURE, - UAVCAN_PROTOCOL_GETNODEINFO_ID, - &transfer->transfer_id, - transfer->priority, - CanardResponse, - &buffer[0], - total_size -#if CANARD_MULTI_IFACE - , IFACE_ALL -#endif -#if HAL_CANFD_SUPPORTED - , canfdout() -#endif -); - if (resp_res <= 0) { - printf("Could not respond to GetNodeInfo: %d\n", resp_res); - } + canard_respond(canard_instance, + transfer, + UAVCAN_PROTOCOL_GETNODEINFO_SIGNATURE, + UAVCAN_PROTOCOL_GETNODEINFO_ID, + &buffer[0], + total_size); } /* @@ -316,23 +306,12 @@ void AP_Periph_FW::handle_param_getset(CanardInstance* canard_instance, CanardRx uint8_t buffer[UAVCAN_PROTOCOL_PARAM_GETSET_RESPONSE_MAX_SIZE] {}; uint16_t total_size = uavcan_protocol_param_GetSetResponse_encode(&pkt, buffer, !canfdout()); - canardRequestOrRespond(canard_instance, - transfer->source_node_id, - UAVCAN_PROTOCOL_PARAM_GETSET_SIGNATURE, - UAVCAN_PROTOCOL_PARAM_GETSET_ID, - &transfer->transfer_id, - transfer->priority, - CanardResponse, - &buffer[0], - total_size -#if CANARD_MULTI_IFACE - , IFACE_ALL -#endif -#if HAL_CANFD_SUPPORTED - ,canfdout() -#endif -); - + canard_respond(canard_instance, + transfer, + UAVCAN_PROTOCOL_PARAM_GETSET_SIGNATURE, + UAVCAN_PROTOCOL_PARAM_GETSET_ID, + &buffer[0], + total_size); } /* @@ -376,22 +355,12 @@ void AP_Periph_FW::handle_param_executeopcode(CanardInstance* canard_instance, C uint8_t buffer[UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_RESPONSE_MAX_SIZE] {}; uint16_t total_size = uavcan_protocol_param_ExecuteOpcodeResponse_encode(&pkt, buffer, !canfdout()); - canardRequestOrRespond(canard_instance, - transfer->source_node_id, - UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_SIGNATURE, - UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_ID, - &transfer->transfer_id, - transfer->priority, - CanardResponse, - &buffer[0], - total_size -#if CANARD_MULTI_IFACE - , IFACE_ALL -#endif -#if HAL_CANFD_SUPPORTED - ,canfdout() -#endif -); + canard_respond(canard_instance, + transfer, + UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_SIGNATURE, + UAVCAN_PROTOCOL_PARAM_EXECUTEOPCODE_ID, + &buffer[0], + total_size); } void AP_Periph_FW::handle_begin_firmware_update(CanardInstance* canard_instance, CanardRxTransfer* transfer) @@ -419,22 +388,12 @@ void AP_Periph_FW::handle_begin_firmware_update(CanardInstance* canard_instance, reply.error = UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_RESPONSE_ERROR_OK; uint32_t total_size = uavcan_protocol_file_BeginFirmwareUpdateResponse_encode(&reply, buffer, !canfdout()); - canardRequestOrRespond(canard_instance, - transfer->source_node_id, - UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_SIGNATURE, - UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_ID, - &transfer->transfer_id, - transfer->priority, - CanardResponse, - &buffer[0], - total_size -#if CANARD_MULTI_IFACE - ,IFACE_ALL -#endif -#if HAL_CANFD_SUPPORTED - ,canfdout() -#endif -); + canard_respond(canard_instance, + transfer, + UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_SIGNATURE, + UAVCAN_PROTOCOL_FILE_BEGINFIRMWAREUPDATE_ID, + &buffer[0], + total_size); uint8_t count = 50; while (count--) { processTx(); @@ -1015,7 +974,7 @@ static bool shouldAcceptTransfer_trampoline(const CanardInstance* canard_instanc return fw->shouldAcceptTransfer(canard_instance, out_data_type_signature, data_type_id, transfer_type, source_node_id); } -void AP_Periph_FW::cleanup_stale_transactions(uint64_t ×tamp_usec) +void AP_Periph_FW::cleanup_stale_transactions(uint64_t timestamp_usec) { canardCleanupStaleTransfers(&dronecan.canard, timestamp_usec); } @@ -1058,9 +1017,11 @@ bool AP_Periph_FW::canard_broadcast(uint64_t data_type_signature, uint16_t data_type_id, uint8_t priority, const void* payload, - uint16_t payload_len) + uint16_t payload_len, + uint8_t iface_mask) { - if (canardGetLocalNodeID(&dronecan.canard) == CANARD_BROADCAST_NODE_ID) { + const bool is_dna = data_type_id == UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID; + if (!is_dna && canardGetLocalNodeID(&dronecan.canard) == CANARD_BROADCAST_NODE_ID) { return false; } @@ -1069,21 +1030,69 @@ bool AP_Periph_FW::canard_broadcast(uint64_t data_type_signature, return false; } - const int16_t res = canardBroadcast(&dronecan.canard, - data_type_signature, - data_type_id, - tid_ptr, - priority, - payload, - payload_len + // create transfer object + CanardTxTransfer transfer_object = { + .transfer_type = CanardTransferTypeBroadcast, + .data_type_signature = data_type_signature, + .data_type_id = data_type_id, + .inout_transfer_id = tid_ptr, + .priority = priority, + .payload = (uint8_t*)payload, + .payload_len = payload_len, +#if CANARD_ENABLE_CANFD + .canfd = is_dna? false : canfdout(), +#endif + .deadline_usec = AP_HAL::micros64()+CAN_FRAME_TIMEOUT, #if CANARD_MULTI_IFACE - , IFACE_ALL // send over all ifaces + .iface_mask = iface_mask==0 ? uint8_t(IFACE_ALL) : iface_mask, #endif -#if HAL_CANFD_SUPPORTED - , canfdout() + }; + const int16_t res = canardBroadcastObj(&dronecan.canard, &transfer_object); + +#if DEBUG_PKTS + if (res < 0) { + can_printf("Tx error %d\n", res); + } +#endif +#if HAL_ENABLE_SENDING_STATS + if (res <= 0) { + protocol_stats.tx_errors++; + } else { + protocol_stats.tx_frames += res; + } #endif - ); + return res > 0; +} +/* + send a response + */ +bool AP_Periph_FW::canard_respond(CanardInstance* canard_instance, + CanardRxTransfer *transfer, + uint64_t data_type_signature, + uint16_t data_type_id, + const uint8_t *payload, + uint16_t payload_len) +{ + CanardTxTransfer transfer_object = { + .transfer_type = CanardTransferTypeResponse, + .data_type_signature = data_type_signature, + .data_type_id = data_type_id, + .inout_transfer_id = &transfer->transfer_id, + .priority = transfer->priority, + .payload = payload, + .payload_len = payload_len, +#if CANARD_ENABLE_CANFD + .canfd = canfdout(), +#endif + .deadline_usec = AP_HAL::micros64()+CAN_FRAME_TIMEOUT, +#if CANARD_MULTI_IFACE + .iface_mask = IFACE_ALL, +#endif + }; + const auto res = canardRequestOrRespondObj(canard_instance, + transfer->source_node_id, + &transfer_object); #if DEBUG_PKTS if (res < 0) { can_printf("Tx error %d\n", res); @@ -1151,15 +1160,17 @@ void AP_Periph_FW::processTx(void) canardPopTxQueue(&dronecan.canard); dronecan.tx_fail_count = 0; } else { - // just exit and try again later. If we fail 8 times in a row - // then start discarding to prevent the pool filling up + // exit and try again later. If we fail 8 times in a row + // then cleanup any stale transfers to keep the queue from + // filling if (dronecan.tx_fail_count < 8) { dronecan.tx_fail_count++; } else { #if HAL_ENABLE_SENDING_STATS protocol_stats.tx_errors++; #endif - canardPopTxQueue(&dronecan.canard); + dronecan.tx_fail_count = 0; + cleanup_stale_transactions(now_us); } break; } @@ -1490,8 +1501,6 @@ bool AP_Periph_FW::can_do_dna() const uint32_t now = AP_HAL::millis(); - static uint8_t node_id_allocation_transfer_id = 0; - if (AP_Periph_FW::no_iface_finished_dna) { printf("Waiting for dynamic node ID allocation %x... (pool %u)\n", IFACE_ALL, pool_peak_percent()); } @@ -1525,24 +1534,11 @@ bool AP_Periph_FW::can_do_dna() memmove(&allocation_request[1], &my_unique_id[dronecan.node_id_allocation_unique_id_offset], uid_size); // Broadcasting the request - const int16_t bcast_res = canardBroadcast(&dronecan.canard, - UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_SIGNATURE, - UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID, - &node_id_allocation_transfer_id, - CANARD_TRANSFER_PRIORITY_LOW, - &allocation_request[0], - (uint16_t) (uid_size + 1) -#if CANARD_MULTI_IFACE - ,(1U << dronecan.dna_interface) -#endif -#if HAL_CANFD_SUPPORTED - // always send allocation request as non-FD - ,false -#endif - ); - if (bcast_res < 0) { - printf("Could not broadcast ID allocation req; error %d\n", bcast_res); - } + canard_broadcast(UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_SIGNATURE, + UAVCAN_PROTOCOL_DYNAMIC_NODE_ID_ALLOCATION_ID, + CANARD_TRANSFER_PRIORITY_LOW, + &allocation_request[0], + (uint16_t) (uid_size + 1)); // Preparing for timeout; if response is received, this value will be updated from the callback. dronecan.node_id_allocation_unique_id_offset = 0; diff --git a/Tools/AP_Periph/gps.cpp b/Tools/AP_Periph/gps.cpp index e8262e2efb4345..029676f26d1b8a 100644 --- a/Tools/AP_Periph/gps.cpp +++ b/Tools/AP_Periph/gps.cpp @@ -163,10 +163,10 @@ void AP_Periph_FW::can_gps_update(void) uint16_t total_size = uavcan_equipment_gnss_Fix2_encode(&pkt, buffer, !canfdout()); canard_broadcast(UAVCAN_EQUIPMENT_GNSS_FIX2_SIGNATURE, - UAVCAN_EQUIPMENT_GNSS_FIX2_ID, - CANARD_TRANSFER_PRIORITY_LOW, - &buffer[0], - total_size); + UAVCAN_EQUIPMENT_GNSS_FIX2_ID, + CANARD_TRANSFER_PRIORITY_LOW, + &buffer[0], + total_size); } /* @@ -258,34 +258,18 @@ void AP_Periph_FW::send_moving_baseline_msg() uint8_t buffer[ARDUPILOT_GNSS_MOVINGBASELINEDATA_MAX_SIZE] {}; const uint16_t total_size = ardupilot_gnss_MovingBaselineData_encode(&mbldata, buffer, !canfdout()); -#if HAL_NUM_CAN_IFACES >= 2 + uint8_t iface_mask = 0; +#if HAL_NUM_CAN_IFACES >= 2 && CANARD_MULTI_IFACE if (gps_mb_can_port != -1 && (gps_mb_can_port < HAL_NUM_CAN_IFACES)) { - uint8_t *tid_ptr = get_tid_ptr(MAKE_TRANSFER_DESCRIPTOR(ARDUPILOT_GNSS_MOVINGBASELINEDATA_SIGNATURE, ARDUPILOT_GNSS_MOVINGBASELINEDATA_ID, 0, CANARD_BROADCAST_NODE_ID)); - canardBroadcast(&dronecan.canard, - ARDUPILOT_GNSS_MOVINGBASELINEDATA_SIGNATURE, - ARDUPILOT_GNSS_MOVINGBASELINEDATA_ID, - tid_ptr, - CANARD_TRANSFER_PRIORITY_LOW, - &buffer[0], - total_size -#if CANARD_MULTI_IFACE - ,(1U< Date: Wed, 6 Dec 2023 23:49:01 -0700 Subject: [PATCH 0190/1335] AP_DDS: add REP-147 Global Position Control Signed-off-by: Ryan Friedman --- libraries/AP_DDS/AP_DDS_Client.cpp | 16 +++++ libraries/AP_DDS/AP_DDS_Client.h | 4 ++ libraries/AP_DDS/AP_DDS_ExternalControl.cpp | 63 +++++++++++++++++++ libraries/AP_DDS/AP_DDS_ExternalControl.h | 8 +++ libraries/AP_DDS/AP_DDS_Topic_Table.h | 11 ++++ .../Idl/ardupilot_msgs/msg/GlobalPosition.idl | 60 ++++++++++++++++++ libraries/AP_DDS/README.md | 5 ++ libraries/AP_DDS/dds_xrce_profile.xml | 15 +++++ 8 files changed, 182 insertions(+) create mode 100644 libraries/AP_DDS/Idl/ardupilot_msgs/msg/GlobalPosition.idl diff --git a/libraries/AP_DDS/AP_DDS_Client.cpp b/libraries/AP_DDS/AP_DDS_Client.cpp index 43dd37f7887094..b743ed8aa01510 100644 --- a/libraries/AP_DDS/AP_DDS_Client.cpp +++ b/libraries/AP_DDS/AP_DDS_Client.cpp @@ -44,6 +44,7 @@ static constexpr uint16_t DELAY_PING_MS = 500; sensor_msgs_msg_Joy AP_DDS_Client::rx_joy_topic {}; tf2_msgs_msg_TFMessage AP_DDS_Client::rx_dynamic_transforms_topic {}; geometry_msgs_msg_TwistStamped AP_DDS_Client::rx_velocity_control_topic {}; +ardupilot_msgs_msg_GlobalPosition AP_DDS_Client::rx_global_position_control_topic {}; const AP_Param::GroupInfo AP_DDS_Client::var_info[] { @@ -391,6 +392,8 @@ void AP_DDS_Client::update_topic(geographic_msgs_msg_GeoPoseStamped& msg) if (ahrs.get_location(loc)) { msg.pose.position.latitude = loc.lat * 1E-7; msg.pose.position.longitude = loc.lng * 1E-7; + // TODO this is assumed to be absolute frame in WGS-84 as per the GeoPose message definition in ROS. + // Use loc.get_alt_frame() to convert if necessary. msg.pose.position.altitude = loc.alt * 0.01; // Transform from cm to m } @@ -502,6 +505,19 @@ void AP_DDS_Client::on_topic(uxrSession* uxr_session, uxrObjectId object_id, uin if (!AP_DDS_External_Control::handle_velocity_control(rx_velocity_control_topic)) { // TODO #23430 handle velocity control failure through rosout, throttled. } +#endif // AP_EXTERNAL_CONTROL_ENABLED + break; + } + case topics[to_underlying(TopicIndex::GLOBAL_POSITION_SUB)].dr_id.id: { + const bool success = ardupilot_msgs_msg_GlobalPosition_deserialize_topic(ub, &rx_global_position_control_topic); + if (success == false) { + break; + } + +#if AP_EXTERNAL_CONTROL_ENABLED + if (!AP_DDS_External_Control::handle_global_position_control(rx_global_position_control_topic)) { + // TODO #23430 handle global position control failure through rosout, throttled. + } #endif // AP_EXTERNAL_CONTROL_ENABLED break; } diff --git a/libraries/AP_DDS/AP_DDS_Client.h b/libraries/AP_DDS/AP_DDS_Client.h index 19d20c3017d244..3751a697e8c1bd 100644 --- a/libraries/AP_DDS/AP_DDS_Client.h +++ b/libraries/AP_DDS/AP_DDS_Client.h @@ -4,6 +4,8 @@ #include "uxr/client/client.h" #include "ucdr/microcdr.h" + +#include "ardupilot_msgs/msg/GlobalPosition.h" #include "builtin_interfaces/msg/Time.h" #include "sensor_msgs/msg/NavSatFix.h" @@ -65,6 +67,8 @@ class AP_DDS_Client static sensor_msgs_msg_Joy rx_joy_topic; // incoming REP147 velocity control static geometry_msgs_msg_TwistStamped rx_velocity_control_topic; + // incoming REP147 goal interface global position + static ardupilot_msgs_msg_GlobalPosition rx_global_position_control_topic; // outgoing transforms tf2_msgs_msg_TFMessage tx_static_transforms_topic; tf2_msgs_msg_TFMessage tx_dynamic_transforms_topic; diff --git a/libraries/AP_DDS/AP_DDS_ExternalControl.cpp b/libraries/AP_DDS/AP_DDS_ExternalControl.cpp index a72536d6ffde84..fcc6fc5d306a14 100644 --- a/libraries/AP_DDS/AP_DDS_ExternalControl.cpp +++ b/libraries/AP_DDS/AP_DDS_ExternalControl.cpp @@ -6,6 +6,49 @@ #include +// These are the Goal Interface constants. Because microxrceddsgen does not expose +// them in the generated code, they are manually maintained +// Position ignore flags +static constexpr uint16_t TYPE_MASK_IGNORE_LATITUDE = 1; +static constexpr uint16_t TYPE_MASK_IGNORE_LONGITUDE = 2; +static constexpr uint16_t TYPE_MASK_IGNORE_ALTITUDE = 4; + +bool AP_DDS_External_Control::handle_global_position_control(ardupilot_msgs_msg_GlobalPosition& cmd_pos) +{ + auto *external_control = AP::externalcontrol(); + if (external_control == nullptr) { + return false; + } + + if (strcmp(cmd_pos.header.frame_id, MAP_FRAME) == 0) { + // Narrow the altitude + const int32_t alt_cm = static_cast(cmd_pos.altitude * 100); + + Location::AltFrame alt_frame; + if (!convert_alt_frame(cmd_pos.coordinate_frame, alt_frame)) { + return false; + } + + constexpr uint32_t MASK_POS_IGNORE = + TYPE_MASK_IGNORE_LATITUDE | + TYPE_MASK_IGNORE_LONGITUDE | + TYPE_MASK_IGNORE_ALTITUDE; + + if (!(cmd_pos.type_mask & MASK_POS_IGNORE)) { + Location loc(cmd_pos.latitude * 1E7, cmd_pos.longitude * 1E7, alt_cm, alt_frame); + if (!external_control->set_global_position(loc)) { + return false; // Don't try sending other commands if this fails + } + } + + // TODO add velocity and accel handling + + return true; + } + + return false; +} + bool AP_DDS_External_Control::handle_velocity_control(geometry_msgs_msg_TwistStamped& cmd_vel) { auto *external_control = AP::externalcontrol(); @@ -40,5 +83,25 @@ bool AP_DDS_External_Control::handle_velocity_control(geometry_msgs_msg_TwistSta return false; } +bool AP_DDS_External_Control::convert_alt_frame(const uint8_t frame_in, Location::AltFrame& frame_out) +{ + + // Specified in ROS REP-147; only some are supported. + switch (frame_in) { + case 5: // FRAME_GLOBAL_INT + frame_out = Location::AltFrame::ABSOLUTE; + break; + case 6: // FRAME_GLOBAL_REL_ALT + frame_out = Location::AltFrame::ABOVE_HOME; + break; + case 11: // FRAME_GLOBAL_TERRAIN_ALT + frame_out = Location::AltFrame::ABOVE_TERRAIN; + break; + default: + return false; + } + return true; +} + #endif // AP_DDS_ENABLED \ No newline at end of file diff --git a/libraries/AP_DDS/AP_DDS_ExternalControl.h b/libraries/AP_DDS/AP_DDS_ExternalControl.h index dbffafdd81ad1c..3986ef63774aa6 100644 --- a/libraries/AP_DDS/AP_DDS_ExternalControl.h +++ b/libraries/AP_DDS/AP_DDS_ExternalControl.h @@ -1,11 +1,19 @@ #pragma once #if AP_DDS_ENABLED +#include "ardupilot_msgs/msg/GlobalPosition.h" #include "geometry_msgs/msg/TwistStamped.h" +#include + class AP_DDS_External_Control { public: + // REP-147 Goal Interface Global Position Control + // https://ros.org/reps/rep-0147.html#goal-interface + static bool handle_global_position_control(ardupilot_msgs_msg_GlobalPosition& cmd_pos); static bool handle_velocity_control(geometry_msgs_msg_TwistStamped& cmd_vel); +private: + static bool convert_alt_frame(const uint8_t frame_in, Location::AltFrame& frame_out); }; #endif // AP_DDS_ENABLED diff --git a/libraries/AP_DDS/AP_DDS_Topic_Table.h b/libraries/AP_DDS/AP_DDS_Topic_Table.h index 8ce9507d08005d..8df056d484fc71 100644 --- a/libraries/AP_DDS/AP_DDS_Topic_Table.h +++ b/libraries/AP_DDS/AP_DDS_Topic_Table.h @@ -22,6 +22,7 @@ enum class TopicIndex: uint8_t { JOY_SUB, DYNAMIC_TRANSFORMS_SUB, VELOCITY_CONTROL_SUB, + GLOBAL_POSITION_SUB, }; static inline constexpr uint8_t to_underlying(const TopicIndex index) @@ -142,4 +143,14 @@ constexpr struct AP_DDS_Client::Topic_table AP_DDS_Client::topics[] = { .dw_profile_label = "", .dr_profile_label = "velocitycontrol__dr", }, + { + .topic_id = to_underlying(TopicIndex::GLOBAL_POSITION_SUB), + .pub_id = to_underlying(TopicIndex::GLOBAL_POSITION_SUB), + .sub_id = to_underlying(TopicIndex::GLOBAL_POSITION_SUB), + .dw_id = uxrObjectId{.id=to_underlying(TopicIndex::GLOBAL_POSITION_SUB), .type=UXR_DATAWRITER_ID}, + .dr_id = uxrObjectId{.id=to_underlying(TopicIndex::GLOBAL_POSITION_SUB), .type=UXR_DATAREADER_ID}, + .topic_profile_label = "globalposcontrol__t", + .dw_profile_label = "", + .dr_profile_label = "globalposcontrol__dr", + }, }; diff --git a/libraries/AP_DDS/Idl/ardupilot_msgs/msg/GlobalPosition.idl b/libraries/AP_DDS/Idl/ardupilot_msgs/msg/GlobalPosition.idl new file mode 100644 index 00000000000000..7b6325d9e02019 --- /dev/null +++ b/libraries/AP_DDS/Idl/ardupilot_msgs/msg/GlobalPosition.idl @@ -0,0 +1,60 @@ +// generated from rosidl_adapter/resource/msg.idl.em +// with input from ardupilot_msgs/msg/GlobalPosition.msg +// generated code does not contain a copyright notice + +#include "geometry_msgs/msg/Twist.idl" +#include "std_msgs/msg/Header.idl" + +module ardupilot_msgs { + module msg { + module GlobalPosition_Constants { + const uint8 FRAME_GLOBAL_INT = 5; + const uint8 FRAME_GLOBAL_REL_ALT = 6; + const uint8 FRAME_GLOBAL_TERRAIN_ALT = 11; + @verbatim (language="comment", text= + "Position ignore flags") + const uint16 IGNORE_LATITUDE = 1; + const uint16 IGNORE_LONGITUDE = 2; + const uint16 IGNORE_ALTITUDE = 4; + @verbatim (language="comment", text= + "Velocity vector ignore flags") + const uint16 IGNORE_VX = 8; + const uint16 IGNORE_VY = 16; + const uint16 IGNORE_VZ = 32; + @verbatim (language="comment", text= + "Acceleration/Force vector ignore flags") + const uint16 IGNORE_AFX = 64; + const uint16 IGNORE_AFY = 128; + const uint16 IGNORE_AFZ = 256; + @verbatim (language="comment", text= + "Force in af vector flag") + const uint16 FORCE = 512; + const uint16 IGNORE_YAW = 1024; + const uint16 IGNORE_YAW_RATE = 2048; + }; + @verbatim (language="comment", text= + "Experimental REP-147 Goal Interface" "\n" + "https://ros.org/reps/rep-0147.html#goal-interface") + struct GlobalPosition { + std_msgs::msg::Header header; + + uint8 coordinate_frame; + + uint16 type_mask; + + double latitude; + + double longitude; + + @verbatim (language="comment", text= + "in meters, AMSL or above terrain") + float altitude; + + geometry_msgs::msg::Twist velocity; + + geometry_msgs::msg::Twist acceleration_or_force; + + float yaw; + }; + }; +}; diff --git a/libraries/AP_DDS/README.md b/libraries/AP_DDS/README.md index bbbe091d9412d6..252a6075fba43c 100644 --- a/libraries/AP_DDS/README.md +++ b/libraries/AP_DDS/README.md @@ -216,6 +216,7 @@ Published topics: * /rosout [rcl_interfaces/msg/Log] 1 publisher Subscribed topics: + * /ap/cmd_gps_pose [ardupilot_msgs/msg/GlobalPosition] 1 subscriber * /ap/cmd_vel [geometry_msgs/msg/TwistStamped] 1 subscriber * /ap/joy [sensor_msgs/msg/Joy] 1 subscriber * /ap/tf [tf2_msgs/msg/TFMessage] 1 subscriber @@ -311,6 +312,10 @@ cp /opt/ros/humble/share/builtin_interfaces/msg/Time.idl libraries/AP_DDS/Idl/bu # Build the code again with the `--enable-dds` flag as described above ``` +If the message is custom for ardupilot, first create the ROS message in `Tools/ros2/ardupilot_msgs/msg/GlobalPosition.msg`. +Then, build ardupilot_msgs with colcon. +Finally, copy the IDL folder from the install directory into the source tree. + ### Rules for adding topics and services to `dds_xrce_profile.xml` Topics and services available from `AP_DDS` are automatically mapped into ROS 2 diff --git a/libraries/AP_DDS/dds_xrce_profile.xml b/libraries/AP_DDS/dds_xrce_profile.xml index abfa47779e9abc..b8e80c6e49e6cc 100644 --- a/libraries/AP_DDS/dds_xrce_profile.xml +++ b/libraries/AP_DDS/dds_xrce_profile.xml @@ -276,4 +276,19 @@ rq/ap/mode_switchRequest rr/ap/mode_switchReply + + rt/ap/cmd_gps_pose + ardupilot_msgs::msg::dds_::GlobalPosition_ + + KEEP_LAST + 5 + + + + + NO_KEY + rt/ap/cmd_gps_pose + ardupilot_msgs::msg::dds_::GlobalPosition_ + + From c22a3439d445df877bdc186f96feec38b977008c Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Wed, 6 Dec 2023 23:49:02 -0700 Subject: [PATCH 0191/1335] AP_ExternalControl: add REP-147 Global Position Control Signed-off-by: Ryan Friedman --- ArduPlane/AP_ExternalControl_Plane.cpp | 22 +++++++++++++++++++ .../AP_ExternalControl/AP_ExternalControl.h | 10 +++++++++ 2 files changed, 32 insertions(+) create mode 100644 ArduPlane/AP_ExternalControl_Plane.cpp diff --git a/ArduPlane/AP_ExternalControl_Plane.cpp b/ArduPlane/AP_ExternalControl_Plane.cpp new file mode 100644 index 00000000000000..c5afabf5843216 --- /dev/null +++ b/ArduPlane/AP_ExternalControl_Plane.cpp @@ -0,0 +1,22 @@ +/* + external control library for plane + */ + + +#include "AP_ExternalControl_Plane.h" +#if AP_EXTERNAL_CONTROL_ENABLED + +#include "Plane.h" + +/* + Sets the target global position for a loiter point. +*/ +bool AP_ExternalControl_Plane::set_global_position(const Location& loc) +{ + + // set_target_location already checks if plane is ready for external control. + // It doesn't check if flying or armed, just that it's in guided mode. + return plane.set_target_location(loc); +} + +#endif // AP_EXTERNAL_CONTROL_ENABLED diff --git a/libraries/AP_ExternalControl/AP_ExternalControl.h b/libraries/AP_ExternalControl/AP_ExternalControl.h index b72190d9c4da81..34228e2b7ab4ff 100644 --- a/libraries/AP_ExternalControl/AP_ExternalControl.h +++ b/libraries/AP_ExternalControl/AP_ExternalControl.h @@ -8,6 +8,7 @@ #if AP_EXTERNAL_CONTROL_ENABLED +#include #include class AP_ExternalControl @@ -24,9 +25,18 @@ class AP_ExternalControl return false; } + /* + Sets the target global position with standard guided mode behavior. + */ + virtual bool set_global_position(const Location& loc) WARN_IF_UNUSED { + return false; + } + static AP_ExternalControl *get_singleton(void) WARN_IF_UNUSED { return singleton; } +protected: + ~AP_ExternalControl() {} private: static AP_ExternalControl *singleton; From 003c50a13c917f1705be0416959cd6afafd50ccf Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Wed, 6 Dec 2023 23:49:02 -0700 Subject: [PATCH 0192/1335] ArduPlane: add REP-147 Global Position Control Signed-off-by: Ryan Friedman --- ArduPlane/AP_ExternalControl_Plane.h | 21 +++++++++++++++++++++ ArduPlane/Plane.h | 10 +++++++--- 2 files changed, 28 insertions(+), 3 deletions(-) create mode 100644 ArduPlane/AP_ExternalControl_Plane.h diff --git a/ArduPlane/AP_ExternalControl_Plane.h b/ArduPlane/AP_ExternalControl_Plane.h new file mode 100644 index 00000000000000..71308780d55fdb --- /dev/null +++ b/ArduPlane/AP_ExternalControl_Plane.h @@ -0,0 +1,21 @@ + +/* + external control library for plane + */ +#pragma once + +#include + +#if AP_EXTERNAL_CONTROL_ENABLED + +#include + +class AP_ExternalControl_Plane : public AP_ExternalControl { +public: + /* + Sets the target global position for a loiter point. + */ + bool set_global_position(const Location& loc) override WARN_IF_UNUSED; +}; + +#endif // AP_EXTERNAL_CONTROL_ENABLED diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index b40ab6a1321723..3a91aea65afd36 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -85,7 +85,7 @@ #include #include #if AP_EXTERNAL_CONTROL_ENABLED -#include +#include "AP_ExternalControl_Plane.h" #endif #include "GCS_Mavlink.h" @@ -167,6 +167,10 @@ class Plane : public AP_Vehicle { friend class ModeThermal; friend class ModeLoiterAltQLand; +#if AP_EXTERNAL_CONTROL_ENABLED + friend class AP_ExternalControl_Plane; +#endif + Plane(void); private: @@ -776,9 +780,9 @@ class Plane : public AP_Vehicle { AP_Param param_loader {var_info}; - // dummy implementation of external control + // external control library #if AP_EXTERNAL_CONTROL_ENABLED - AP_ExternalControl external_control; + AP_ExternalControl_Plane external_control; #endif static const AP_Scheduler::Task scheduler_tasks[]; From 7f9992dd2460afdfca4962e1ae3e832a498ff7cd Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Wed, 6 Dec 2023 23:49:02 -0700 Subject: [PATCH 0193/1335] Tools: add REP-147 Global Position Control Signed-off-by: Ryan Friedman --- .../plane_waypoint_follower.py | 213 ++++++++++++++++++ Tools/ros2/ardupilot_dds_tests/package.xml | 3 + Tools/ros2/ardupilot_dds_tests/setup.py | 1 + Tools/ros2/ardupilot_msgs/CMakeLists.txt | 4 + .../ardupilot_msgs/msg/GlobalPosition.msg | 30 +++ Tools/ros2/ardupilot_msgs/package.xml | 3 + 6 files changed, 254 insertions(+) create mode 100755 Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/plane_waypoint_follower.py create mode 100644 Tools/ros2/ardupilot_msgs/msg/GlobalPosition.msg diff --git a/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/plane_waypoint_follower.py b/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/plane_waypoint_follower.py new file mode 100755 index 00000000000000..27de6f272f2ed8 --- /dev/null +++ b/Tools/ros2/ardupilot_dds_tests/ardupilot_dds_tests/plane_waypoint_follower.py @@ -0,0 +1,213 @@ +#!/usr/bin/env python3 +# Copyright 2023 ArduPilot.org. +# +# This program is free software: you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation, either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, +# but WITHOUT ANY WARRANTY; without even the implied warranty of +# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the +# GNU General Public License for more details. +# +# You should have received a copy of the GNU General Public License +# along with this program. If not, see . + +""" +Run a single-waypoint mission on Plane. + +Warning - This is NOT production code; it's a simple demo of capability. +""" + +import math +import rclpy +import time +import errno + +from rclpy.node import Node +from builtin_interfaces.msg import Time +from ardupilot_msgs.msg import GlobalPosition +from geographic_msgs.msg import GeoPoseStamped +from geopy import distance +from geopy import point +from ardupilot_msgs.srv import ArmMotors +from ardupilot_msgs.srv import ModeSwitch + + +PLANE_MODE_TAKEOFF = 13 +PLANE_MODE_GUIDED = 15 + +FRAME_GLOBAL_INT = 5 + +# Hard code some known locations +# Note - Altitude in geopy is in km! +GRAYHOUND_TRACK = point.Point(latitude=-35.345996, longitude=149.159017, altitude=0.575) +CMAC = point.Point(latitude=-35.3627010, longitude=149.1651513, altitude=0.585) + + +class PlaneWaypointFollower(Node): + """Plane follow waypoints using guided control.""" + + def __init__(self): + """Initialise the node.""" + super().__init__("plane_waypoint_follower") + + self.declare_parameter("arm_topic", "/ap/arm_motors") + self._arm_topic = self.get_parameter("arm_topic").get_parameter_value().string_value + self._client_arm = self.create_client(ArmMotors, self._arm_topic) + while not self._client_arm.wait_for_service(timeout_sec=1.0): + self.get_logger().info('arm service not available, waiting again...') + + self.declare_parameter("mode_topic", "/ap/mode_switch") + self._mode_topic = self.get_parameter("mode_topic").get_parameter_value().string_value + self._client_mode_switch = self.create_client(ModeSwitch, self._mode_topic) + while not self._client_mode_switch.wait_for_service(timeout_sec=1.0): + self.get_logger().info('mode switch service not available, waiting again...') + + self.declare_parameter("global_position_topic", "/ap/cmd_gps_pose") + self._global_pos_topic = self.get_parameter("global_position_topic").get_parameter_value().string_value + self._global_pos_pub = self.create_publisher(GlobalPosition, self._global_pos_topic, 1) + + # Create subscriptions after services are up + self.declare_parameter("geopose_topic", "/ap/geopose/filtered") + self._geopose_topic = self.get_parameter("geopose_topic").get_parameter_value().string_value + qos = rclpy.qos.QoSProfile( + reliability=rclpy.qos.ReliabilityPolicy.BEST_EFFORT, durability=rclpy.qos.DurabilityPolicy.VOLATILE, depth=1 + ) + + self._subscription_geopose = self.create_subscription(GeoPoseStamped, self._geopose_topic, self.geopose_cb, qos) + self._cur_geopose = GeoPoseStamped() + + def geopose_cb(self, msg: GeoPoseStamped): + """Process a GeoPose message.""" + stamp = msg.header.stamp + if stamp.sec: + self.get_logger().info("From AP : Geopose [sec:{}, nsec: {}]".format(stamp.sec, stamp.nanosec)) + + # Store current state + self._cur_geopose = msg + + def arm(self): + req = ArmMotors.Request() + req.arm = True + future = self._client_arm.call_async(req) + rclpy.spin_until_future_complete(self, future) + return future.result() + + def arm_with_timeout(self, timeout: rclpy.duration.Duration): + """Try to arm. Returns true on success, or false if arming fails or times out.""" + armed = False + start = self.get_clock().now() + while not armed and self.get_clock().now() - start < timeout: + armed = self.arm().result + time.sleep(1) + return armed + + def switch_mode(self, mode): + req = ModeSwitch.Request() + assert mode in [PLANE_MODE_TAKEOFF, PLANE_MODE_GUIDED] + req.mode = mode + future = self._client_mode_switch.call_async(req) + rclpy.spin_until_future_complete(self, future) + return future.result() + + def switch_mode_with_timeout(self, desired_mode: int, timeout: rclpy.duration.Duration): + """Try to switch mode. Returns true on success, or false if mode switch fails or times out.""" + is_in_desired_mode = False + start = self.get_clock().now() + while not is_in_desired_mode: + result = self.switch_mode(desired_mode) + # Handle successful switch or the case that the vehicle is already in expected mode + is_in_desired_mode = result.status or result.curr_mode == desired_mode + time.sleep(1) + + return is_in_desired_mode + + def get_cur_geopose(self): + """Return latest geopose.""" + return self._cur_geopose + + def send_goal_position(self, goal_global_pos): + """Send goal position. Must be in guided for this to work.""" + self._global_pos_pub.publish(goal_global_pos) + + +def achieved_goal(goal_global_pos, cur_geopose): + """Return true if the current position (LLH) is close enough to the goal (within the orbit radius).""" + # Use 3D geopy distance calculation + # https://geopy.readthedocs.io/en/stable/#module-geopy.distance + goal_lat = goal_global_pos + + p1 = (goal_global_pos.latitude, goal_global_pos.longitude, goal_global_pos.altitude) + cur_pos = cur_geopose.pose.position + p2 = (cur_pos.latitude, cur_pos.longitude, cur_pos.altitude) + + flat_distance = distance.distance(p1[:2], p2[:2]).m + euclidian_distance = math.sqrt(flat_distance**2 + (p2[2] - p1[2]) ** 2) + print(f"Goal is {euclidian_distance} meters away") + return euclidian_distance < 150 + + +def main(args=None): + """Node entry point.""" + rclpy.init(args=args) + node = PlaneWaypointFollower() + try: + # Block till armed, which will wait for EKF3 to initialize + if not node.arm_with_timeout(rclpy.duration.Duration(seconds=30)): + raise RuntimeError("Unable to arm") + + # Block till in takeoff + if not node.switch_mode_with_timeout(PLANE_MODE_TAKEOFF, rclpy.duration.Duration(seconds=20)): + raise RuntimeError("Unable to switch to takeoff mode") + + is_ascending_to_takeoff_alt = True + while is_ascending_to_takeoff_alt: + rclpy.spin_once(node) + time.sleep(1.0) + + # Hard code waiting in takeoff to reach operating altitude of 630m + # This is just a hack because geopose is reported with absolute rather than relative altitude, + # and this node doesn't have access to the terrain data + is_ascending_to_takeoff_alt = node.get_cur_geopose().pose.position.altitude < CMAC.altitude * 1000 + 45 + + if is_ascending_to_takeoff_alt: + raise RuntimeError("Failed to reach takeoff altitude") + + if not node.switch_mode_with_timeout(PLANE_MODE_GUIDED, rclpy.duration.Duration(seconds=20)): + raise RuntimeError("Unable to switch to guided mode") + + # Send a guided WP with location, frame ID, alt frame + goal_pos = GlobalPosition() + goal_pos.latitude = GRAYHOUND_TRACK.latitude + goal_pos.longitude = GRAYHOUND_TRACK.longitude + DESIRED_AGL = 60 + goal_pos.altitude = GRAYHOUND_TRACK.altitude * 1000 + DESIRED_AGL + goal_pos.coordinate_frame = FRAME_GLOBAL_INT + goal_pos.header.frame_id = "map" + + node.send_goal_position(goal_pos) + + start = node.get_clock().now() + has_achieved_goal = False + while not has_achieved_goal and node.get_clock().now() - start < rclpy.duration.Duration(seconds=120): + rclpy.spin_once(node) + has_achieved_goal = achieved_goal(goal_pos, node.get_cur_geopose()) + time.sleep(1.0) + + if not has_achieved_goal: + raise RuntimeError("Unable to achieve goal location") + + print("Goal achieved") + + except KeyboardInterrupt: + pass + + # Destroy the node explicitly. + node.destroy_node() + rclpy.shutdown() + + +if __name__ == "__main__": + main() diff --git a/Tools/ros2/ardupilot_dds_tests/package.xml b/Tools/ros2/ardupilot_dds_tests/package.xml index 7b44fbffdcbf94..b4cc9fa2a0e358 100644 --- a/Tools/ros2/ardupilot_dds_tests/package.xml +++ b/Tools/ros2/ardupilot_dds_tests/package.xml @@ -8,11 +8,13 @@ GLP-3.0 ament_index_python + ardupilot_msgs ardupilot_sitl launch launch_pytest launch_ros micro_ros_msgs + python3-geopy python3-pytest rclpy socat @@ -23,6 +25,7 @@ ament_uncrustify ament_xmllint ament_lint_auto + ardupilot_msgs ardupilot_sitl launch launch_pytest diff --git a/Tools/ros2/ardupilot_dds_tests/setup.py b/Tools/ros2/ardupilot_dds_tests/setup.py index 3d2039beb5c0fd..bbe11e6a5c8123 100644 --- a/Tools/ros2/ardupilot_dds_tests/setup.py +++ b/Tools/ros2/ardupilot_dds_tests/setup.py @@ -25,6 +25,7 @@ entry_points={ 'console_scripts': [ "time_listener = ardupilot_dds_tests.time_listener:main", + "plane_waypoint_follower = ardupilot_dds_tests.plane_waypoint_follower:main", ], }, ) diff --git a/Tools/ros2/ardupilot_msgs/CMakeLists.txt b/Tools/ros2/ardupilot_msgs/CMakeLists.txt index 8096431370687c..d066a2d32b2e43 100644 --- a/Tools/ros2/ardupilot_msgs/CMakeLists.txt +++ b/Tools/ros2/ardupilot_msgs/CMakeLists.txt @@ -5,14 +5,18 @@ project(ardupilot_msgs) # Find dependencies. find_package(ament_cmake REQUIRED) +find_package(geometry_msgs REQUIRED) +find_package(std_msgs REQUIRED) find_package(rosidl_default_generators REQUIRED) # --------------------------------------------------------------------------- # # Generate and export message interfaces. rosidl_generate_interfaces(${PROJECT_NAME} + "msg/GlobalPosition.msg" "srv/ArmMotors.srv" "srv/ModeSwitch.srv" + DEPENDENCIES geometry_msgs std_msgs ADD_LINTER_TESTS ) diff --git a/Tools/ros2/ardupilot_msgs/msg/GlobalPosition.msg b/Tools/ros2/ardupilot_msgs/msg/GlobalPosition.msg new file mode 100644 index 00000000000000..f34b84c3ea34e8 --- /dev/null +++ b/Tools/ros2/ardupilot_msgs/msg/GlobalPosition.msg @@ -0,0 +1,30 @@ +# Experimental REP-147 Goal Interface +# https://ros.org/reps/rep-0147.html#goal-interface + +std_msgs/Header header + +uint8 coordinate_frame +uint8 FRAME_GLOBAL_INT = 5 +uint8 FRAME_GLOBAL_REL_ALT = 6 +uint8 FRAME_GLOBAL_TERRAIN_ALT = 11 + +uint16 type_mask +uint16 IGNORE_LATITUDE = 1 # Position ignore flags +uint16 IGNORE_LONGITUDE = 2 +uint16 IGNORE_ALTITUDE = 4 +uint16 IGNORE_VX = 8 # Velocity vector ignore flags +uint16 IGNORE_VY = 16 +uint16 IGNORE_VZ = 32 +uint16 IGNORE_AFX = 64 # Acceleration/Force vector ignore flags +uint16 IGNORE_AFY = 128 +uint16 IGNORE_AFZ = 256 +uint16 FORCE = 512 # Force in af vector flag +uint16 IGNORE_YAW = 1024 +uint16 IGNORE_YAW_RATE = 2048 + +float64 latitude +float64 longitude +float32 altitude # in meters, AMSL or above terrain +geometry_msgs/Twist velocity +geometry_msgs/Twist acceleration_or_force +float32 yaw diff --git a/Tools/ros2/ardupilot_msgs/package.xml b/Tools/ros2/ardupilot_msgs/package.xml index 08e92bf1df7d99..2e2a118fa5ae2c 100644 --- a/Tools/ros2/ardupilot_msgs/package.xml +++ b/Tools/ros2/ardupilot_msgs/package.xml @@ -11,6 +11,9 @@ ament_cmake rosidl_default_generators + std_msgs + geometry_msgs + rosidl_default_runtime ament_cmake_copyright From 76861eaa9b207b0dbf62865d911749583024acf9 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Thu, 7 Dec 2023 00:10:04 -0700 Subject: [PATCH 0194/1335] AP_Common: Define units for locatoin data members Signed-off-by: Ryan Friedman --- libraries/AP_Common/Location.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Common/Location.h b/libraries/AP_Common/Location.h index 134a27e590af36..eab834e2d427f3 100644 --- a/libraries/AP_Common/Location.h +++ b/libraries/AP_Common/Location.h @@ -15,9 +15,9 @@ class Location uint8_t loiter_xtrack : 1; // 0 to crosstrack from center of waypoint, 1 to crosstrack from tangent exit location // note that mission storage only stores 24 bits of altitude (~ +/- 83km) - int32_t alt; - int32_t lat; - int32_t lng; + int32_t alt; // in cm + int32_t lat; // in 1E7 degrees + int32_t lng; // in 1E7 degrees /// enumeration of possible altitude types enum class AltFrame { From faa8ac0085d8ff556e847fa8085e7a6119df83f4 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Tue, 12 Dec 2023 21:31:29 -0700 Subject: [PATCH 0195/1335] AP_Vehicle: Set position target depends on ext control * Used to depend on scripting but now it's used in AP_ExternalControl Signed-off-by: Ryan Friedman --- libraries/AP_Vehicle/AP_Vehicle.h | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Vehicle/AP_Vehicle.h b/libraries/AP_Vehicle/AP_Vehicle.h index 1ccbe4d5500140..b8d98d2377d519 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.h +++ b/libraries/AP_Vehicle/AP_Vehicle.h @@ -34,6 +34,7 @@ #include #include #include +#include #include #include #include // Notify library @@ -155,12 +156,15 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { // returns true if the vehicle has crashed virtual bool is_crashed() const; +#if AP_EXTERNAL_CONTROL_ENABLED + // Method to control vehicle position for use by external control + virtual bool set_target_location(const Location& target_loc) { return false; } +#endif // AP_EXTERNAL_CONTROL_ENABLED #if AP_SCRIPTING_ENABLED /* methods to control vehicle for use by scripting */ virtual bool start_takeoff(float alt) { return false; } - virtual bool set_target_location(const Location& target_loc) { return false; } virtual bool set_target_pos_NED(const Vector3f& target_pos, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative, bool terrain_alt) { return false; } virtual bool set_target_posvel_NED(const Vector3f& target_pos, const Vector3f& target_vel) { return false; } virtual bool set_target_posvelaccel_NED(const Vector3f& target_pos, const Vector3f& target_vel, const Vector3f& target_accel, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative) { return false; } From 2e393bbbc6a5c0e73ad00cd02d7bd4ca997e066c Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Tue, 12 Dec 2023 21:32:43 -0700 Subject: [PATCH 0196/1335] ArduPlane: Make set position tgt depend on ext ctrl * Set position target used to just be used in scripting, now it's used by DDS in external control Signed-off-by: Ryan Friedman --- ArduPlane/ArduPlane.cpp | 6 ++++-- ArduPlane/Plane.h | 4 +++- 2 files changed, 7 insertions(+), 3 deletions(-) diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 36bc4f5b53e091..02dcd401eb2dda 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -798,8 +798,8 @@ bool Plane::get_wp_crosstrack_error_m(float &xtrack_error) const return true; } -#if AP_SCRIPTING_ENABLED -// set target location (for use by scripting) +#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED +// set target location (for use by external control and scripting) bool Plane::set_target_location(const Location &target_loc) { Location loc{target_loc}; @@ -816,7 +816,9 @@ bool Plane::set_target_location(const Location &target_loc) plane.set_guided_WP(loc); return true; } +#endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED +#if AP_SCRIPTING_ENABLED // set target location (for use by scripting) bool Plane::get_target_location(Location& target_loc) { diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 3a91aea65afd36..b0baf16706a72b 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -1245,8 +1245,10 @@ class Plane : public AP_Vehicle { void failsafe_check(void); bool is_landing() const override; bool is_taking_off() const override; -#if AP_SCRIPTING_ENABLED +#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED bool set_target_location(const Location& target_loc) override; +#endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED +#if AP_SCRIPTING_ENABLED bool get_target_location(Location& target_loc) override; bool update_target_location(const Location &old_loc, const Location &new_loc) override; bool set_velocity_match(const Vector2f &velocity) override; From ab0755d0d8ec55d23816b14b09d875c33ecc5774 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 16 Dec 2023 17:23:56 +0000 Subject: [PATCH 0197/1335] Plane: rework forward throttle votlage compensation into sub class and split min/max from throttle --- ArduPlane/Parameters.cpp | 6 ++--- ArduPlane/Parameters.h | 23 ++++++++++++++--- ArduPlane/Plane.h | 1 - ArduPlane/servos.cpp | 54 ++++++++++++++++++++++++++++++---------- 4 files changed, 64 insertions(+), 20 deletions(-) diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index bb4a2a86a5fbae..fd5288223d8f8b 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -1175,7 +1175,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Units: V // @Increment: 0.1 // @User: Advanced - AP_GROUPINFO("FWD_BAT_VOLT_MAX", 23, ParametersG2, fwd_thr_batt_voltage_max, 0.0f), + AP_GROUPINFO("FWD_BAT_VOLT_MAX", 23, ParametersG2, fwd_batt_cmp.batt_voltage_max, 0.0f), // @Param: FWD_BAT_VOLT_MIN // @DisplayName: Forward throttle battery voltage compensation minimum voltage @@ -1184,14 +1184,14 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @Units: V // @Increment: 0.1 // @User: Advanced - AP_GROUPINFO("FWD_BAT_VOLT_MIN", 24, ParametersG2, fwd_thr_batt_voltage_min, 0.0f), + AP_GROUPINFO("FWD_BAT_VOLT_MIN", 24, ParametersG2, fwd_batt_cmp.batt_voltage_min, 0.0f), // @Param: FWD_BAT_IDX // @DisplayName: Forward throttle battery compensation index // @Description: Which battery monitor should be used for doing compensation for the forward throttle // @Values: 0:First battery, 1:Second battery // @User: Advanced - AP_GROUPINFO("FWD_BAT_IDX", 25, ParametersG2, fwd_thr_batt_idx, 0), + AP_GROUPINFO("FWD_BAT_IDX", 25, ParametersG2, fwd_batt_cmp.batt_idx, 0), // @Param: FS_EKF_THRESH // @DisplayName: EKF failsafe variance threshold diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index 2a9a5ef0719868..ef126900dfccf1 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -542,9 +542,26 @@ class ParametersG2 { AP_Int8 crow_flap_aileron_matching; // Forward throttle battery voltage compensation - AP_Float fwd_thr_batt_voltage_max; - AP_Float fwd_thr_batt_voltage_min; - AP_Int8 fwd_thr_batt_idx; + class FWD_BATT_CMP { + public: + // Calculate the throttle scale to compensate for battery voltage drop + void update(); + + // Apply throttle scale to min and max limits + void apply_min_max(int8_t &min_throttle, int8_t &max_throttle) const; + + // Apply throttle scale to throttle demand + float apply_throttle(float throttle) const; + + AP_Float batt_voltage_max; + AP_Float batt_voltage_min; + AP_Int8 batt_idx; + + private: + bool enabled; + float ratio; + } fwd_batt_cmp; + #if OFFBOARD_GUIDED == ENABLED // guided yaw heading PID diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index b0baf16706a72b..8dcb90e47d8dd0 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -1107,7 +1107,6 @@ class Plane : public AP_Vehicle { void servos_auto_trim(void); void servos_twin_engine_mix(); void force_flare(); - void throttle_voltage_comp(int8_t &min_throttle, int8_t &max_throttle) const; void throttle_watt_limiter(int8_t &min_throttle, int8_t &max_throttle); void throttle_slew_limit(SRV_Channel::Aux_servo_function_t func); bool suppress_throttle(void); diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index 35dc8b08017280..c8f03bb8968486 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -384,23 +384,26 @@ void Plane::set_servos_idle(void) /* - Scale the throttle to conpensate for battery voltage drop + Calculate the throttle scale to compensate for battery voltage drop */ -void Plane::throttle_voltage_comp(int8_t &min_throttle, int8_t &max_throttle) const +void ParametersG2::FWD_BATT_CMP::update() { + // Assume disabled + enabled = false; + // return if not enabled, or setup incorrectly - if (!is_positive(g2.fwd_thr_batt_voltage_min) || g2.fwd_thr_batt_voltage_min >= g2.fwd_thr_batt_voltage_max) { + if (!is_positive(batt_voltage_min) || batt_voltage_min >= batt_voltage_max) { return; } - float batt_voltage_resting_estimate = AP::battery().voltage_resting_estimate(g2.fwd_thr_batt_idx); + float batt_voltage_resting_estimate = AP::battery().voltage_resting_estimate(batt_idx); // Return for a very low battery - if (batt_voltage_resting_estimate < 0.25f * g2.fwd_thr_batt_voltage_min) { + if (batt_voltage_resting_estimate < 0.25f * batt_voltage_min) { return; } // constrain read voltage to min and max params - batt_voltage_resting_estimate = constrain_float(batt_voltage_resting_estimate,g2.fwd_thr_batt_voltage_min,g2.fwd_thr_batt_voltage_max); + batt_voltage_resting_estimate = constrain_float(batt_voltage_resting_estimate, batt_voltage_min, batt_voltage_max); // don't apply compensation if the voltage is excessively low if (batt_voltage_resting_estimate < 1) { @@ -409,14 +412,38 @@ void Plane::throttle_voltage_comp(int8_t &min_throttle, int8_t &max_throttle) co // Scale the throttle up to compensate for voltage drop // Ratio = 1 when voltage = voltage max, ratio increases as voltage drops - const float ratio = g2.fwd_thr_batt_voltage_max / batt_voltage_resting_estimate; + ratio = batt_voltage_max / batt_voltage_resting_estimate; + + // Got this far then ratio is valid + enabled = true; +} + +// Apply throttle scale to min and max limits +void ParametersG2::FWD_BATT_CMP::apply_min_max(int8_t &min_throttle, int8_t &max_throttle) const +{ + // return if not enabled + if (!enabled) { + return; + } // Scale the throttle limits to prevent subsequent clipping + // Ratio will always be >= 1, ensure still within max limits min_throttle = int8_t(MAX((ratio * (float)min_throttle), -100)); max_throttle = int8_t(MIN((ratio * (float)max_throttle), 100)); - SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, - constrain_float(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) * ratio, -100, 100)); +} + +// Apply throttle scale to throttle demand +float ParametersG2::FWD_BATT_CMP::apply_throttle(float throttle) const +{ + // return if not enabled + if (!enabled) { + return throttle; + } + + // Ratio will always be >= 1, ensure still within max limits + return constrain_float(throttle * ratio, -100, 100); + } /* @@ -504,7 +531,8 @@ void Plane::set_throttle(void) } // compensate for battery voltage drop - throttle_voltage_comp(min_throttle, max_throttle); + g2.fwd_batt_cmp.update(); + g2.fwd_batt_cmp.apply_min_max(min_throttle, max_throttle); #if AP_BATTERY_WATT_MAX_ENABLED // apply watt limiter @@ -573,9 +601,9 @@ void Plane::set_throttle(void) #endif // HAL_QUADPLANE_ENABLED } else { - // Apply min/max limits to throttle output from flight mode - SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, - constrain_float(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle), min_throttle, max_throttle)); + // Apply min/max limits and voltage compensation to throttle output from flight mode + const float throttle = g2.fwd_batt_cmp.apply_throttle(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)); + SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, constrain_float(throttle, min_throttle, max_throttle)); } } From 86a199c1bf6c2414d1d7367e848742d6e66b0918 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 19 Dec 2023 02:13:25 +0000 Subject: [PATCH 0198/1335] AP_ICEngine: add support for starter relay --- libraries/AP_ICEngine/AP_ICEngine.cpp | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/libraries/AP_ICEngine/AP_ICEngine.cpp b/libraries/AP_ICEngine/AP_ICEngine.cpp index ad66e49ded7d07..b5202ea7220cb5 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.cpp +++ b/libraries/AP_ICEngine/AP_ICEngine.cpp @@ -622,6 +622,13 @@ void AP_ICEngine::set_starter(bool on) #if AP_ICENGINE_TCA9554_STARTER_ENABLED tca9554_starter.set_starter(on); #endif + +#if AP_RELAY_ENABLED + AP_Relay *relay = AP::relay(); + if (relay != nullptr) { + relay->set(AP_Relay_Params::FUNCTION::ICE_STARTER, on); + } +#endif // AP_RELAY_ENABLED } From 46dd402a1ab32b0dc23e1bc25d7c40c3561a845d Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 19 Dec 2023 02:15:12 +0000 Subject: [PATCH 0199/1335] AP_Relay: add ICE_STARTER function --- libraries/AP_Relay/AP_Relay_Params.cpp | 1 + libraries/AP_Relay/AP_Relay_Params.h | 1 + 2 files changed, 2 insertions(+) diff --git a/libraries/AP_Relay/AP_Relay_Params.cpp b/libraries/AP_Relay/AP_Relay_Params.cpp index afce285cd4fe4b..c5381188068f21 100644 --- a/libraries/AP_Relay/AP_Relay_Params.cpp +++ b/libraries/AP_Relay/AP_Relay_Params.cpp @@ -14,6 +14,7 @@ const AP_Param::GroupInfo AP_Relay_Params::var_info[] = { // @Values{Rover}: 6:Bushed motor reverse 2 throttle-right or omni motor 2 // @Values{Rover}: 7:Bushed motor reverse 3 omni motor 3 // @Values{Rover}: 8:Bushed motor reverse 4 omni motor 4 + // @Values{Plane}: 9:ICE Starter // @User: Standard AP_GROUPINFO_FLAGS("FUNCTION", 1, AP_Relay_Params, function, (float)FUNCTION::NONE, AP_PARAM_FLAG_ENABLE), diff --git a/libraries/AP_Relay/AP_Relay_Params.h b/libraries/AP_Relay/AP_Relay_Params.h index 7239dda9c9106c..c5c783677143e0 100644 --- a/libraries/AP_Relay/AP_Relay_Params.h +++ b/libraries/AP_Relay/AP_Relay_Params.h @@ -28,6 +28,7 @@ class AP_Relay_Params { BRUSHED_REVERSE_2 = 6, BRUSHED_REVERSE_3 = 7, BRUSHED_REVERSE_4 = 8, + ICE_STARTER = 9, NUM_FUNCTIONS // must be the last entry }; From a94484d770c993cd49ca8bd77bea1cdd36818a00 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 20 Dec 2023 06:06:02 +1100 Subject: [PATCH 0200/1335] HAL_ChibiOS: fixed SPI build on F1xx F1 does not have palReadLineMode() --- libraries/AP_HAL_ChibiOS/SPIDevice.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/SPIDevice.h b/libraries/AP_HAL_ChibiOS/SPIDevice.h index c082b4f7283a2a..5845e0448c81eb 100644 --- a/libraries/AP_HAL_ChibiOS/SPIDevice.h +++ b/libraries/AP_HAL_ChibiOS/SPIDevice.h @@ -26,7 +26,7 @@ #include "Device.h" #ifndef HAL_SPI_SCK_SAVE_RESTORE -#define HAL_SPI_SCK_SAVE_RESTORE TRUE +#define HAL_SPI_SCK_SAVE_RESTORE !defined(STM32F1) #endif namespace ChibiOS { From 65cae116a2b52f070b44335c5cf6546914e1e3aa Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 20 Dec 2023 06:12:20 +1100 Subject: [PATCH 0201/1335] hwdef: fixed build of CarbonixL496 --- libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat index c621a9f58bd269..807e790e303287 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat @@ -139,3 +139,5 @@ define HAL_PERIPH_ADSB_BAUD_DEFAULT 57600 BARO MS56XX I2C:0:0x76 COMPASS QMC5883P I2C:0:0x2C false ROTATION_YAW_180 + +define AP_COMPASS_QMC5883P_ENABLED 1 From cf481a895294090d00718b106bd5277d17eb83f2 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Fri, 18 Aug 2023 16:29:30 +1000 Subject: [PATCH 0202/1335] AP_HAL_ChibiOS: allow option to enable scripting on CubeRedSecondary --- libraries/AP_HAL_ChibiOS/hwdef/CubeRedSecondary/hwdef.dat | 2 -- 1 file changed, 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedSecondary/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedSecondary/hwdef.dat index 82c5ad28103c86..19fe6a4e3cee64 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeRedSecondary/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeRedSecondary/hwdef.dat @@ -152,8 +152,6 @@ define DEFAULT_SERIAL2_PROTOCOL SerialProtocol_RCIN define DEFAULT_SERIAL3_PROTOCOL SerialProtocol_Sbus1 define DEFAULT_SERIAL4_PROTOCOL SerialProtocol_RCIN -define AP_SCRIPTING_ENABLED 0 - # only use pulse input for PPM, other protocols # are on serial define HAL_RCIN_PULSE_PPM_ONLY From 49c3536ca7ab2686788702aaee5e526e079337d3 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 20 Dec 2023 14:26:12 +1100 Subject: [PATCH 0203/1335] AP_Math: added uint64_div1000() and test suite --- libraries/AP_Math/div1000.h | 26 ++++++++++++++++++++++++++ libraries/AP_Math/tests/test_math.cpp | 12 ++++++++++++ 2 files changed, 38 insertions(+) create mode 100644 libraries/AP_Math/div1000.h diff --git a/libraries/AP_Math/div1000.h b/libraries/AP_Math/div1000.h new file mode 100644 index 00000000000000..e80a52d542180d --- /dev/null +++ b/libraries/AP_Math/div1000.h @@ -0,0 +1,26 @@ +/* + return 64 bit x / 1000 + faster than the normal gcc implementation using by about 3x + With thanks to https://0x414b.com/2021/04/16/arm-division.html + and https://stackoverflow.com/questions/74765410/multiply-two-uint64-ts-and-store-result-to-uint64-t-doesnt-seem-to-work +*/ +static inline uint64_t uint64_div1000(uint64_t x) +{ + x >>= 3U; + uint64_t a_lo = (uint32_t)x; + uint64_t a_hi = x >> 32; + const uint64_t b_lo = 0xe353f7cfU; + const uint64_t b_hi = 0x20c49ba5U; + + uint64_t a_x_b_hi = a_hi * b_hi; + uint64_t a_x_b_mid = a_hi * b_lo; + uint64_t b_x_a_mid = b_hi * a_lo; + uint32_t a_x_b_lo = (a_lo * b_lo)>>32; + + // 64-bit product + two 32-bit values + uint64_t middle = a_x_b_mid + a_x_b_lo + (uint32_t)b_x_a_mid; + + // 64-bit product + two 32-bit values + uint64_t r = a_x_b_hi + (middle >> 32) + (b_x_a_mid >> 32); + return r >> 4U; +} diff --git a/libraries/AP_Math/tests/test_math.cpp b/libraries/AP_Math/tests/test_math.cpp index 0043a38c5b1b14..afd8a164c829f3 100644 --- a/libraries/AP_Math/tests/test_math.cpp +++ b/libraries/AP_Math/tests/test_math.cpp @@ -7,6 +7,7 @@ #include #include +#include const AP_HAL::HAL& hal = AP_HAL::get_HAL(); @@ -692,6 +693,17 @@ TEST(CRCTest, parity) EXPECT_EQ(parity(0b11111111), 0); } +TEST(MathTest, div1000) +{ + for (uint32_t i=0; i<1000000; i++) { + uint64_t v; + EXPECT_EQ(hal.util->get_random_vals((uint8_t*)&v, sizeof(v)), true); + uint64_t v1 = v / 1000ULL; + uint64_t v2 = uint64_div1000(v); + EXPECT_EQ(v1, v2); + } +} + AP_GTEST_PANIC() AP_GTEST_MAIN() From 4a59097b5e211a5789ba34e33dd3972ccc4f60a1 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 20 Dec 2023 14:26:48 +1100 Subject: [PATCH 0204/1335] HAL_ChibiOS: use C implemention of div1000 --- libraries/AP_HAL_ChibiOS/hwdef/common/hrt.c | 6 ++-- libraries/AP_HAL_ChibiOS/hwdef/common/hrt.h | 33 +-------------------- 2 files changed, 5 insertions(+), 34 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/hrt.c b/libraries/AP_HAL_ChibiOS/hwdef/common/hrt.c index f99110f08093b4..c7ea3bdff5fe3f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/hrt.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/hrt.c @@ -25,6 +25,8 @@ #pragma GCC optimize("O2") +#include "../../../AP_Math/div1000.h" + /* we have 4 possible configurations of boards, made up of boards that have the following properties: @@ -139,9 +141,9 @@ uint32_t hrt_micros32() #endif } -uint32_t hrt_millis64() +uint64_t hrt_millis64() { - return _hrt_div1000(hrt_micros64()); + return uint64_div1000(hrt_micros64()); } uint32_t hrt_millis32() diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/hrt.h b/libraries/AP_HAL_ChibiOS/hwdef/common/hrt.h index c11637ec12e3e5..ac1cf915d8b094 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/hrt.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/hrt.h @@ -13,38 +13,7 @@ uint32_t hrt_micros32(void); uint32_t hrt_millis32(void); uint32_t hrt_millis32I(void); // from locked context uint32_t hrt_millis32_from_ISR(void); // from an ISR -uint32_t hrt_millis64(void); - -/* - thanks to: - https://0x414b.com/2021/04/16/arm-division.html - */ -static inline uint64_t _hrt_umul64x64hi(uint32_t b, uint32_t a, uint32_t d, uint32_t c) -{ - __asm__ ("\n\ -umull r4, r5, %[b], %[d] \n\ -umull %[d], r4, %[a], %[d] \n\ -adds r5, %[d] \n\ -umull %[d], %[a], %[a], %[c] \n\ -adcs r4, %[d] \n\ -adc %[a], #0 \n\ -umull %[c], %[b], %[b], %[c] \n\ -adds r5, %[c] \n\ -adcs %[b], r4 \n\ -adc %[a], #0 \n\ -" : [a] "+r" (a), [b] "+r" (b), [c] "+r" (c), [d] "+r" (d) : : "r4", "r5"); - return (uint64_t) a << 32 | b; -} - -/* - return x / 1000 - faster than the gcc implementation using _hrt_umul64x64hi() by about 3x -*/ -static inline uint64_t _hrt_div1000(uint64_t x) -{ - x >>= 3U; - return _hrt_umul64x64hi((uint32_t)x, x >> 32U, 0xe353f7cfU, 0x20c49ba5U) >> 4U; -} +uint64_t hrt_millis64(void); #ifdef __cplusplus } From f3303c92725d10e6da0727b97be9148d22a489d1 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 20 Dec 2023 16:24:27 +1100 Subject: [PATCH 0205/1335] HAL_SITL: use uint64_div1000() match ChibiOS --- libraries/AP_HAL_SITL/system.cpp | 14 ++------------ 1 file changed, 2 insertions(+), 12 deletions(-) diff --git a/libraries/AP_HAL_SITL/system.cpp b/libraries/AP_HAL_SITL/system.cpp index 138ee2a7c2bef6..1e4a59be2019ec 100644 --- a/libraries/AP_HAL_SITL/system.cpp +++ b/libraries/AP_HAL_SITL/system.cpp @@ -9,6 +9,7 @@ #include #include "Scheduler.h" +#include extern const AP_HAL::HAL& hal; @@ -179,18 +180,7 @@ uint64_t micros64() uint64_t millis64() { - const HALSITL::Scheduler* scheduler = HALSITL::Scheduler::from(hal.scheduler); - uint64_t stopped_usec = scheduler->stopped_clock_usec(); - if (stopped_usec) { - return stopped_usec / 1000; - } - - struct timeval tp; - gettimeofday(&tp, nullptr); - uint64_t ret = 1.0e3*((tp.tv_sec + (tp.tv_usec*1.0e-6)) - - (state.start_time.tv_sec + - (state.start_time.tv_usec*1.0e-6))); - return ret; + return uint64_div1000(micros64()); } } // namespace AP_HAL From ff22c103b2fcbb223399221f8ddca89e820e2c58 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 20 Dec 2023 14:28:23 +1100 Subject: [PATCH 0206/1335] Tools: allow div1000 testing on all boards --- Tools/CPUInfo/CPUInfo.cpp | 25 +++++++++++++++---------- 1 file changed, 15 insertions(+), 10 deletions(-) diff --git a/Tools/CPUInfo/CPUInfo.cpp b/Tools/CPUInfo/CPUInfo.cpp index 2b2ee927527340..05409f1418df5e 100644 --- a/Tools/CPUInfo/CPUInfo.cpp +++ b/Tools/CPUInfo/CPUInfo.cpp @@ -10,6 +10,7 @@ #include #include #include +#include #include #include "EKF_Maths.h" @@ -205,28 +206,34 @@ static void show_timings(void) TIMEIT("SEM", { WITH_SEMAPHORE(sem); v_out_32 += v_32;}, 100); } -#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS static void test_div1000(void) { hal.console->printf("Testing div1000\n"); for (uint32_t i=0; i<2000000; i++) { - uint64_t v; - hal.util->get_random_vals((uint8_t*)&v, sizeof(v)); + uint64_t v = 0; + if (!hal.util->get_random_vals((uint8_t*)&v, sizeof(v))) { + AP_HAL::panic("ERROR: div1000 no random\n"); + break; + } uint64_t v1 = v / 1000ULL; - uint64_t v2 = _hrt_div1000(v); + uint64_t v2 = uint64_div1000(v); if (v1 != v2) { AP_HAL::panic("ERROR: 0x%llx v1=0x%llx v2=0x%llx\n", (unsigned long long)v, (unsigned long long)v1, (unsigned long long)v2); return; } } +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS // test from locked context for (uint32_t i=0; i<2000000; i++) { - uint64_t v; - hal.util->get_random_vals((uint8_t*)&v, sizeof(v)); + uint64_t v = 0; + if (!hal.util->get_random_vals((uint8_t*)&v, sizeof(v))) { + AP_HAL::panic("ERROR: div1000 no random\n"); + break; + } chSysLock(); uint64_t v1 = v / 1000ULL; - uint64_t v2 = _hrt_div1000(v); + uint64_t v2 = uint64_div1000(v); chSysUnlock(); if (v1 != v2) { AP_HAL::panic("ERROR: 0x%llx v1=0x%llx v2=0x%llx\n", @@ -234,18 +241,16 @@ static void test_div1000(void) return; } } +#endif hal.console->printf("div1000 OK\n"); } -#endif void loop() { show_sizes(); hal.console->printf("\n"); show_timings(); -#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS test_div1000(); -#endif hal.console->printf("\n"); hal.scheduler->delay(3000); } From 5c1ed968b18ea196b8376cdd6cc7aeae9b3085c4 Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Sat, 25 Nov 2023 19:15:03 -0600 Subject: [PATCH 0207/1335] AP_Motors:expand heli tail param metadata --- libraries/AP_Motors/AP_MotorsHeli_Single.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp index 6fcefd60048846..1c73e10f5082ac 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp @@ -28,8 +28,8 @@ const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = { // @Param: TAIL_TYPE // @DisplayName: Tail Type - // @Description: Tail type selection. Simpler yaw controller used if external gyro is selected. Direct Drive Variable Pitch is used for tails that have a motor that is governed at constant speed by an ESC. Tail pitch is still accomplished with a servo. Direct Drive Fixed Pitch (DDFP) CW is used for helicopters with a rotor that spins clockwise when viewed from above. Direct Drive Fixed Pitch (DDFP) CCW is used for helicopters with a rotor that spins counter clockwise when viewed from above. In both DDFP cases, no servo is used for the tail and the tail motor esc is controlled by the yaw axis. - // @Values: 0:Servo only,1:Servo with ExtGyro,2:DirectDrive VarPitch,3:DirectDrive FixedPitch CW,4:DirectDrive FixedPitch CCW,5:DDVP with external governor + // @Description: Tail type selection. Servo Only uses tail rotor pitch to provide yaw control (including stabilization) via an output assigned to Motor4. Servo with External Gyro uses an external gyro to control tail rotor pitch via a servo. Yaw control without stabilization is passed to the external gyro via the output assigned to Motor4. Direct Drive Variable Pitch(DDVP) is used for tails that have a motor whose ESC is connected to an output with function HeliTailRSC. Tail pitch is still accomplished with a servo on an output assigned to Motor4 function. Direct Drive Fixed Pitch (DDFP) CW is used for helicopters with a rotor that spins clockwise when viewed from above with a motor whose ESC is controlled by an output whose function is Motor4. Direct Drive Fixed Pitch (DDFP) CCW is used for helicopters with a rotor that spins counter clockwise when viewed from above with a motor whose ESC is controlled by an output whose function is Motor4. In both DDFP cases, no servo is used for the tail and the tail motor esc on Motor4 output is used to control the yaw axis using motor speed. + // @Values: 0:Servo only,1:Servo with ExtGyro,2:DirectDrive VarPitch,3:DirectDrive FixedPitch CW,4:DirectDrive FixedPitch CCW // @User: Standard AP_GROUPINFO("TAIL_TYPE", 4, AP_MotorsHeli_Single, _tail_type, float(TAIL_TYPE::SERVO)), @@ -37,7 +37,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = { // @Param: GYR_GAIN // @DisplayName: External Gyro Gain - // @Description: PWM in microseconds sent to external gyro on ch7 when tail type is Servo w/ ExtGyro + // @Description: PWM in microseconds sent to external gyro on an servo/output whose function is Motor7 when tail type is Servo w/ ExtGyro // @Range: 0 1000 // @Units: PWM // @Increment: 1 @@ -57,7 +57,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = { // @Param: TAIL_SPEED // @DisplayName: DDVP Tail ESC speed - // @Description: Direct drive, variable pitch tail ESC speed in percent output to the tail motor esc (HeliTailRSC Servo) when motor interlock enabled (throttle hold off). + // @Description: Direct drive, variable pitch tail ESC speed in percent output to the tail motor esc (HeliTailRSC Servo) when motor interlock enabled (throttle hold off) and speed fully ramped up after spoolup. // @Range: 0 100 // @Units: % // @Increment: 1 @@ -66,7 +66,7 @@ const AP_Param::GroupInfo AP_MotorsHeli_Single::var_info[] = { // @Param: GYR_GAIN_ACRO // @DisplayName: ACRO External Gyro Gain - // @Description: PWM in microseconds sent to external gyro on ch7 when tail type is Servo w/ ExtGyro. A value of zero means to use H_GYR_GAIN + // @Description: PWM in microseconds sent to external gyro on an servo/output whose function is Motor7 when tail type is Servo w/ ExtGyro in mode ACRO instead of H_GYR_GAIN. A value of zero means to use H_GYR_GAIN // @Range: 0 1000 // @Units: PWM // @Increment: 1 From d2d2067f1ce3e76374b9c5bc5a983057ba98268b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 24 Dec 2023 09:28:21 +1100 Subject: [PATCH 0208/1335] HAL_ChibiOS: fixed micros and millis on boards without 1MHz clock --- libraries/AP_HAL_ChibiOS/hwdef/common/hrt.c | 16 ++++++++++------ libraries/AP_HAL_ChibiOS/hwdef/common/hrt.h | 1 - 2 files changed, 10 insertions(+), 7 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/hrt.c b/libraries/AP_HAL_ChibiOS/hwdef/common/hrt.c index c7ea3bdff5fe3f..f1e510ccebd07e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/hrt.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/hrt.c @@ -84,12 +84,16 @@ static uint32_t get_systime_us32(void) wrap and directly gives a uint64_t (aka systimestamp_t) */ -uint64_t hrt_micros64I() +static uint64_t hrt_micros64I(void) { + uint64_t ret = chVTGetTimeStampI(); +#if CH_CFG_ST_FREQUENCY != 1000000U + ret *= 1000000U/CH_CFG_ST_FREQUENCY; +#endif #ifdef AP_BOARD_START_TIME - return chVTGetTimeStampI() + AP_BOARD_START_TIME; + ret += AP_BOARD_START_TIME; #endif - return chVTGetTimeStampI(); + return ret; } static inline bool is_locked(void) { @@ -99,17 +103,17 @@ static inline bool is_locked(void) { uint64_t hrt_micros64() { if (is_locked()) { - return chVTGetTimeStampI(); + return hrt_micros64I(); } else if (port_is_isr_context()) { uint64_t ret; chSysLockFromISR(); - ret = chVTGetTimeStampI(); + ret = hrt_micros64I(); chSysUnlockFromISR(); return ret; } else { uint64_t ret; chSysLock(); - ret = chVTGetTimeStampI(); + ret = hrt_micros64I(); chSysUnlock(); return ret; } diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/hrt.h b/libraries/AP_HAL_ChibiOS/hwdef/common/hrt.h index ac1cf915d8b094..e8ca91ef724423 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/hrt.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/hrt.h @@ -7,7 +7,6 @@ extern "C" { void hrt_init(void); uint64_t hrt_micros64(void); -uint64_t hrt_micros64I(void); // from locked context uint64_t hrt_micros64_from_ISR(void); // from an ISR uint32_t hrt_micros32(void); uint32_t hrt_millis32(void); From 57ac86edd916ded485f5c0ee962897f044e63fe6 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 21 Dec 2023 15:06:36 +0000 Subject: [PATCH 0209/1335] AP_IOMCU: fix occasional startup internal errors with mixing allow DIRECT_PWM pages to be smaller than max channels correct some over-eager register clearing in the global interrupt handler (NFC) only sent TX events when using shared DMA (NFC) zero out rx packet code and size to prevent errors with spurious callbacks add a comment and check for offsets that are codes --- libraries/AP_IOMCU/AP_IOMCU.cpp | 5 +- libraries/AP_IOMCU/iofirmware/iofirmware.cpp | 59 +++++++++++++------- libraries/AP_IOMCU/iofirmware/ioprotocol.h | 1 + 3 files changed, 44 insertions(+), 21 deletions(-) diff --git a/libraries/AP_IOMCU/AP_IOMCU.cpp b/libraries/AP_IOMCU/AP_IOMCU.cpp index b77f4f94c9d006..4768ec6e2fb925 100644 --- a/libraries/AP_IOMCU/AP_IOMCU.cpp +++ b/libraries/AP_IOMCU/AP_IOMCU.cpp @@ -691,7 +691,10 @@ bool AP_IOMCU::read_registers(uint8_t page, uint8_t offset, uint8_t count, uint1 */ bool AP_IOMCU::write_registers(uint8_t page, uint8_t offset, uint8_t count, const uint16_t *regs) { - while (count > PKT_MAX_REGS) { + // The use of offset is very, very evil - it can either be a command within the page + // or a genuine offset, offsets within PAGE_SETUP are assumed to be commands, otherwise to be an + // actual offset + while (page != PAGE_SETUP && count > PKT_MAX_REGS) { if (!write_registers(page, offset, PKT_MAX_REGS, regs)) { return false; } diff --git a/libraries/AP_IOMCU/iofirmware/iofirmware.cpp b/libraries/AP_IOMCU/iofirmware/iofirmware.cpp index 55e67dd9978df0..2b1e65d145a1ab 100644 --- a/libraries/AP_IOMCU/iofirmware/iofirmware.cpp +++ b/libraries/AP_IOMCU/iofirmware/iofirmware.cpp @@ -51,6 +51,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); */ #define IOMCU_ENABLE_RESET_TEST 0 +//#define IOMCU_LOOP_TIMING_DEBUG // enable timing GPIO pings #ifdef IOMCU_LOOP_TIMING_DEBUG #undef TOGGLE_PIN_DEBUG @@ -103,9 +104,6 @@ static void dma_rx_end_cb(hal_uart_driver *uart) chSysLockFromISR(); uart->usart->CR3 &= ~USART_CR3_DMAR; - (void)uart->usart->SR; // sequence to clear IDLE status - (void)uart->usart->DR; - (void)uart->usart->DR; dmaStreamDisable(uart->dmarx); iomcu.process_io_packet(); @@ -139,8 +137,11 @@ static void dma_tx_end_cb(hal_uart_driver *uart) TOGGLE_PIN_DEBUG(108); TOGGLE_PIN_DEBUG(108); #endif - +#if AP_HAL_SHARED_DMA_ENABLED + chSysLockFromISR(); chEvtSignalI(iomcu.thread_ctx, IOEVENT_TX_END); + chSysUnlockFromISR(); +#endif } /* replacement for ChibiOS uart_lld_serve_interrupt() */ @@ -154,41 +155,44 @@ static void idle_rx_handler(hal_uart_driver *uart) USART_SR_NE | /* noise error - we have lost a byte due to noise */ USART_SR_FE | USART_SR_PE)) { /* framing error - start/stop bit lost or line break */ + + (void)uart->usart->DR; /* SR reset step 2 - clear ORE | FE.*/ + /* send a line break - this will abort transmission/reception on the other end */ chSysLockFromISR(); - uart->usart->SR = ~USART_SR_LBD; uart->usart->CR1 = cr1 | USART_CR1_SBK; + iomcu.reg_status.num_errors++; iomcu.reg_status.err_uart++; + /* disable RX DMA */ uart->usart->CR3 &= ~USART_CR3_DMAR; - (void)uart->usart->SR; // clears ORE | FE - (void)uart->usart->DR; - (void)uart->usart->DR; setup_rx_dma(uart); chSysUnlockFromISR(); - return; } if ((sr & USART_SR_TC) && (cr1 & USART_CR1_TCIE)) { - chSysLockFromISR(); - /* TC interrupt cleared and disabled.*/ uart->usart->SR &= ~USART_SR_TC; uart->usart->CR1 = cr1 & ~USART_CR1_TCIE; - +#ifdef HAL_GPIO_LINE_GPIO105 + TOGGLE_PIN_DEBUG(105); + TOGGLE_PIN_DEBUG(105); +#endif /* End of transmission, a callback is generated.*/ - _uart_tx2_isr_code(uart); - - chSysUnlockFromISR(); + dma_tx_end_cb(uart); } - if (sr & USART_SR_IDLE) { + if ((sr & USART_SR_IDLE) && (cr1 & USART_CR1_IDLEIE)) { + (void)uart->usart->DR; /* SR reset step 2 - clear IDLE.*/ + /* the DMA size is the maximum packet size, but smaller packets are perfectly possible leading to an IDLE ISR. The data still must be processed. */ + + /* End of receive, a callback is generated.*/ dma_rx_end_cb(uart); } } @@ -248,9 +252,9 @@ static UARTConfig uart_cfg = { dma_tx_end_cb, dma_rx_end_cb, nullptr, - nullptr, - idle_rx_handler, - nullptr, + nullptr, // error + idle_rx_handler, // global irq + nullptr, // idle 1500000, //1.5MBit USART_CR1_IDLEIE, 0, @@ -660,6 +664,12 @@ void AP_IOMCU_FW::process_io_packet() { iomcu.reg_status.total_pkts++; + if (rx_io_packet.code == CODE_NOOP) { + iomcu.reg_status.num_errors++; + iomcu.reg_status.err_bad_opcode++; + return; + } + uint8_t rx_crc = rx_io_packet.crc; uint8_t calc_crc; rx_io_packet.crc = 0; @@ -714,9 +724,18 @@ void AP_IOMCU_FW::process_io_packet() default: { iomcu.reg_status.num_errors++; iomcu.reg_status.err_bad_opcode++; + rx_io_packet.code = CODE_NOOP; + rx_io_packet.count = 0; + return; } break; } + + // prevent a spurious DMA callback from doing anything bad + rx_io_packet.code = CODE_NOOP; + rx_io_packet.count = 0; + + return; } /* @@ -942,7 +961,7 @@ bool AP_IOMCU_FW::handle_code_write() // no input when override is active break; } - if (rx_io_packet.count != sizeof(reg_direct_pwm.pwm)/2) { + if (rx_io_packet.count > sizeof(reg_direct_pwm.pwm)/2) { return false; } /* copy channel data */ diff --git a/libraries/AP_IOMCU/iofirmware/ioprotocol.h b/libraries/AP_IOMCU/iofirmware/ioprotocol.h index 01a29b15ff5f28..9e13fafc48478f 100644 --- a/libraries/AP_IOMCU/iofirmware/ioprotocol.h +++ b/libraries/AP_IOMCU/iofirmware/ioprotocol.h @@ -37,6 +37,7 @@ enum iocode { // read types CODE_READ = 0, CODE_WRITE = 1, + CODE_NOOP = 2, // reply codes CODE_SUCCESS = 0, From da1066124e4893061c7b0f853a213834e36cc2dc Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 21 Dec 2023 15:09:55 +0000 Subject: [PATCH 0210/1335] IO_Firmware: fix occasional internal errors on startup --- .../IO_Firmware/iofirmware_dshot_highpolh.bin | Bin 47164 -> 47260 bytes .../IO_Firmware/iofirmware_dshot_lowpolh.bin | Bin 47164 -> 47260 bytes .../iofirmware_f103_8MHz_highpolh.bin | Bin 40592 -> 40600 bytes .../iofirmware_f103_8MHz_lowpolh.bin | Bin 40592 -> 40600 bytes .../iofirmware_f103_dshot_highpolh.bin | Bin 52668 -> 52756 bytes .../iofirmware_f103_dshot_lowpolh.bin | Bin 52668 -> 52756 bytes .../IO_Firmware/iofirmware_f103_highpolh.bin | Bin 40592 -> 40592 bytes Tools/IO_Firmware/iofirmware_f103_lowpolh.bin | Bin 40592 -> 40592 bytes Tools/IO_Firmware/iofirmware_highpolh.bin | Bin 40592 -> 40600 bytes Tools/IO_Firmware/iofirmware_lowpolh.bin | Bin 40592 -> 40600 bytes 10 files changed, 0 insertions(+), 0 deletions(-) diff --git a/Tools/IO_Firmware/iofirmware_dshot_highpolh.bin b/Tools/IO_Firmware/iofirmware_dshot_highpolh.bin index 817ba4fed0b98f46bc0e55683f6e77310ada1350..5934290788ad07b8b5c953e7b309c95443a8c4ef 100755 GIT binary patch delta 7750 zcmaJ`30PCd_Mf>~xF{&dB0Dz;NHB^4)Z$hH=w%6rOBbtE1B%9ID{aN4Y7+%3cCqMa zORH8CY_)X(BR)}6P|>QbeNbzw_1S8*jg)75Q8br?B>!^*`t18&|M|Y(oS8FcX3jk` zbLPzC1V?Rar^=`H+h2$1s{qLnL?;4f9NB0{lB|bZ`^KGPar?%bM#;q_M0c7CvDHT! zZujOy4l=n98`|0F&HZc-$_dKdmnQo08D1P-meFa&oRie{2^f5{9w8G(OtT0v$Pdx< zU33E>#0Wh8459`8Vku&l0lqW0_vuX~&~o85M=Bv?lgG#St zr|T;+LTb106V#LnH+$D`mSp`@19_+4AW5MN(RIYqZ%o)!gGe8~pd!QfMjc5rm|HInNyk%0I7L5sMz_CItDGG|g=gF3!=$9M= z5Pcf3JPy%WfMH5R&jb2l>|f#T;oa(?r~ik{Uf_KISO@qD`izFYgnq6=UZAfKS+Fc( zUuUJYoNvNNxvfRE40B^K9lz^J-b43FMI4T@2p|*6< z*0M_eK;j}Rj+}a4>wyr5_=6#YX`L~!x{z@XU4$dwq>j&DEsV5sw8Tl@??YF#+*I!#xW_H}WFH)s6 zh!mCln;`sk;_ttWzt?;AnzE15j2-(9ME6YYwS^TK2vloQ|M*1xwgdfp>cd~E$iRv} z1Un<7G4C}V(T_=7M%xoMhqQH9pI51w1xd9GIVeM~g$}lLP zXDY33+ck%uT%--lFSeqFY8tjP!W!g*HRcEBjK+tn4t86_*s<(jUdOpt1K3@rSFNFP zyOpoYnD9M+RE?9*3MouKLAzVc8U@3OWg1>R7IO+7 zwhQ{6Kg_((f2qbvf&zz`HzChky1D0`;GR<(d5cN*zba%foG^T`6Db>8Opk{^+&%Yy zhB*I3XXn-XtWV1Q^n~1nC*&@uE5Mq9^Gm5yk5-6T!Ktm$2j&XyPb0X$`P1|PdIi^4 z6rk&)STkSAPFm4V|F&idEYfG(f>OB-G2_J<$idJcqtV&z7E>(Uooep&^)CW1OiLrVCsAXftE8ofu~8KAJ+<^)eAe8xYm3|j@Bo2n7qp4+yrVW&P8 zKB|{q&S|J#x?SMqFG2dq(^oy=>BT*s-ir(F`J@9@QXUqCGs(fQ*ij*ZvjwlL&`(}A@{!+)m0@p0iX0tt@DkzbjQ zV!|D;x|e{bqi+ z44BHuC~Bfm7f4==^y?$kUt3g>k)$7#)odWIN6t)m)C6{TQL=s@`-0(|DX+t>qgPKg z9Oj4mcQ;7ZABGJF9ZI97^$Iay?$1t@KEyx_QEFlAZBY>dITkes-yqS^K?5%zE3zPN zja#LcvLV8tpwwo*1sqZ{O6Mq1DdbgpKRI+UGdcnfAS)YW6=Zf&*WzG5U={q z$QziuK>9Or{uR)}Ryf97)^2-MlRSptIph{I!uvG;9q%(4bEza&wg9gn8)d5gZs2t# z-VZZBc-?sI5(8&$7c7BK$R(Ky)Z8Qw4oK-l$`j3=-ei_LyasdoNxVD~=a3A!5yy}( z<&n~z5LtMu$nWx__$^YU(Be7fKNah-cc^1+n!OowL1cAo5ME3^h>e?d$Jr-~VWr${ zC!?U`K3PnplpF0v+|aJ{vUE-?N;e@cLCANQW~ZC{U?*G&KupLnL=Ocz2>BVz8umQzHxY5UqyF zQ4Jn?`_SRE8<%?Dh{}|5XG!0{D!_Qrx@vILTLrdX*lhYrVL&WVJGy$~;ECS1zF@9wQUte=&}5OIW5> z29EBbYm`={+pQ~Q+_nVZ`T>{Xp6&cqX97;FM-IznY_gW(vhA_?`+yq;+^L?{Ke&|a zU@d~tZzgK^@=+A`mTPzZ9+06yM(>e1<3jRStstS&t>vF)B<=4Q5ydTW{hEIi1Up<3 zc8^D}7CMX2D&+_~u6~pkSM2WY_)Kezd^cYK4YxtNX|C9UYG`)_+I0`G1qSH*mjTK^ zj&=Q7uo>i1eGYcE z6(P~G-YRi3l{}GGKzua%3&a#<{FOJH*i=jLQL<=|7M~@@2W_QbTTC510IP{{a4e1_ zy9e)}CLSkjLT2CZyKp9LxdMyjUx2%0dxA{HcQLG=C8bWx2Ek11hZ6nRmKw07j{KYu zgp0_71jVR}U6pS*Z67&&vz)dz$J{r3vc&A!`;AhkZH*Jvd*|eF?qoQ)h|_k?*?0(* zC$oMsB};vVxlLrskdqLW1*xCH`$?`k5r0OEY6ad#svuoy{!$%;eV01LZR5pwPjwjt zA*3~N2!4TtCPm`8IT8=jq>AFibeO7cZ>!n9%8>5!%slz8%|Azf1-D)jIn zJylRr7?vHTrDmV@(6rg2xllH0*UV0zi@3X;p<0Gj=mZa<2W86oAm$ywGrbX0))z6Q zkk>)}wl88j04Y9*5d$v}P!5Oz3@ z2V*6;ap8dM1@^t*mU5@MG_?V;U~o|vyK>}#S!E$!Tmg?20l8}Z=dX3kO1Tv%Qym6!VPuLgX9$2pt4JeOOSuE2@2C-Y z8Oa*;6h1*#LwbYMj~c8Rc}&VJ0fZgn>wH-+)*ph7U^t+VTg<+hwz+{~(<0*86yRJW z{-Xy|SKtCTItm{qvqlf2AaHwsbf&z<(4Pg9LohG+^ZSM>KCOrWgKvd7jI2fS`-Vef zZeZ`%jzZAQNVx^1_2~uFL<@Ot>=AsG_-dl@Me|_IBuoW&5mV{~Tw~UzoyYirIcVG@ zQS>f8q?Xc(bd)w-M_Wq4Dk}mvjK#ny%79p&tj!pKSCWPdneTmJfFAyBayKKcKMfui zq|hS>d(vfNi7Hcut4VHVB7UD3GyCJW%pYVXW4wfXm1V*IHm}bvrtrUrJ13TkX)q7S z&BSojFPiY4z?%?{7n|erwqwkbFDK^XR1!bw1N?xToHPSmT=e7;JdIRMw&M5AZ%;|4 z1kIjJ#Aed|>?DW|(w~#z<)rYrSUlJK_H#CjcbQA3zCz*YyY` z3rKju`rHpXnMFv6xGko`{9@)YTy+^gJDfzb8B9zl3)XUqb_ams~VF4|^$g zK`hjhoCOio5H~R_Sco@}9~S(8%ghHCeg!rnD_%~f+Mv6aqXg3YvW}@VtgV3^y}%4N z0hf*M($`lSAToWWd(l-I$izjrA@CbkG|PX7y-lA3hkO%%Ld`4^aU03*qK(uw14()1 zYw96Hs;@TUZ^)Og-XBuY<9~j!3NB&cNksdwbe-=Lm(|`{pG-7}ZU}*x}~TCg?#pZ8fppS`8mF3UPLRAd6(;_R-*3vhCe@6XeI)g>&UL z8DA`mKik=O$j^e4eN}(7jAS~Yuar}W=IYkgc(K%enu%i9-jPDU@jZF3cyLUAr-W73 zGoTN0LOce~JD71mn^kXipFk8B;UYJR_u=j2-6b+g+(~Mdq+lg!U6O%cB#BG=Ckui7 zCAflz2)hZsTZlV^{X%iWPtdG)EyX3A5XvcaxSc`1FwzaOVrhIoQ70CBRKp#cJDT#? zh#Xlu0q-P|Winh&;+Dlp7M`HEm1N4Y=V6zvPgNa8D8`T$=J`*lnnzxwjB;*itDofW_{EL8gL*@{H@)# z$z3^x8qQnWyu_F7lnBL0J*}B3aire92J!Nrw3Q`orE-hS2aa+jtHzM(y)k+DWuOtNzUyouaUdqMh(IjLN{!D* zrZyqEgIqU`nsC0$FZn^@zyXc-BYTXmHpzy2VdfSj!!*gnY)qJ_Ed0xD@Db4|kouR8L$Hzx76SUYbEbrxAD&acZ{V;YKa8Tobf zI!Iqy^XZr}P=T%!Wx8$Oxh;2SIPhW`DjxGL^zgzO_B`e__VD}~j*>|w0rBS^*X--5 z>H6ZzW8SVF-n}pGkatV0m^T-fJ};(x&X~U`dtWlF%2_pEHLfbZN_glDuhQ`rpQ|Bk z5=6J}I}e7BWN+%#<1kn5yrmyCuFV?44uqQZKFFkx z``s!?OgBH+aEYRrGvva?pQu!``Lj*Dba+jd+qSq%k|oVVoY+ahGtOFgC-8zmR2Phx zoHK|P0t&kB)gxkU#XQ8x9f<4IMXr2Ujt`RgA8o}tvt;X+SP}$$Cu!LhjXx*t+f@NO12`SJ23nFEu{Ls8F5i|QvPuuZXvrro)rnv zGk3F7lKpKfJzf;P^-xIY_;!R(wbD4n(n#=*A(0K8B34~b!%fC*tA{*N{?Q!5%3*~g zZZOH+5&l9|rx@-!f*V6zs8euZf}0Stx?0TAas=VqrcU8D)ZK;#2bE%xunucxy4!ZV z0U^59ZELSD%J8a#=d`_kEZ*d{slXid*i}F82r}xyu)>QsTtDG9`^(Xkx7Ztwrz;&|pPde|W~YPd7ttp1nVuTa zCiY2hL&(3a4^C@GR96`Jx)qI2u~fjIGz>c5ErJ&*YRg3__`D za&l)lt|ZrYDj>zX@_e_QL-cnb=>eIsODov}r7L9rt~k7hT;8P!5XxL#e|B9BE%#-k zAhbF_dRK*p7dpBZo*p!u@4yNqGx4!%;W{*zjID}=Yhhv4DBPRutWtyqIRvQ`hZNrJ zgpITk=6f-qj$E&b_Frdr+itnsw!5xw?~+e^tHPTfu$Tu8=g$$a46qgTz0= zau=oBB@YtD4fx#)@fP2#2et%{#Geogqd~o{fj59RUEcDKc6Xlr5@sLRqDbDJ7lySv zaXCCgS3I!&?o@LqUD^T@4Ib*D?GP`}#{0pd#`|ARPVYeIRQvm)E1GN8+vNJ5bX-Sd zd&`Ms?-0rP6hvP%x9?TpNtUM(eG*WpLG*UOe#qAX>Hzfs_%F=!+nJK&K%J0ZUtuotlZ34S5SuL1}f)B@@N|E+-qcqakN0e`Cjizd_c zAW#fg1$Z=YBy_$S%4-4ZpWwGZ{xaYy;5y(Y;8#E^;8EL+=GJ|S@UXwL@yQnueFm`i zMd%73$kjpF0;nhN9?<@6%fgvpJ3ui&Hub+|k@y}A|J#-p9oPaeW;UYp0e{hr%=mv= z))j(QfWmoT2*6)jn)e^f6DI`1As-5e1jqqOKmuSWU?e~T$N=PcC>eP8ER}hN+&lbn zmhM@%5%-wQ?Z(*c?k+ePSO)R`u_*k*<*}~rRxtc~+x>G5#OPZwLJZs^%gvYT=28C# Do@4(! delta 7598 zcmZ`;30xFc(toe#pb=0IP;Pn{kU`W8U?N711H|SSQSpjLjDttgDx)N7B$_xQctAXY zd2ttm2T@4Wcz`2D)Db+AsL>TP?uWTnjf$)>`-sOh!yI2VsOx6GZ+^djzv}9$>UvjI zy`C*?%yG(;PU<kF0XxvWS=|b68arH8WFkLxd^9RDq@U>PTO| zK6nDj@f(L1kSf1)oJsEcMS3k0HT)T|A%~$iN$;LXV}BFfwu3H?$MmaqWz^`0C`ZG4 z&>JF9~ug1APF!BP!jW> za6aMPc+#HyKV-fD-X_2*z(PQ{rprbk(2_kLlF&=VncFK`O2so6X|^<}3NRfmW8-%; zjehKYUmXs2n9T3hFG=fO+9E5E!9yHxdN}mJ=>l{wO;%o9A?{Bww&3t72tC@6f2O6V z_y>;)7)xE-5u)fFX_}OIM!b-aVQ|~lIeeog>ZjyNBRy4Vdc+^V>XqWJ2`QjcAuf*P4sOZPuP8oM94b_Z8+ zaUF;IBD&U$qbkKWwJXINs(_Y4Q!!Roh_kr6Esd>M-O!q??go7gNJP*HB{*OP8n+Y{ zH;Ueg72=0ngV>zVey49%QE^XreX;g(-YLy$o!w2H6V< zzup<~hu6%);!jge53BZvJ(=ns^UBf@bncASbmcjLP5T3$2!tBT(y{t?Y1k3cm>w4I zPkYS!@8~r1&Hh;`j(6K~UA1?*Mw|g>tM`u(FjaRbX79P1(*k z3eu%%#Y}=fZRnAjKl-03%ETtQ3RAtfCe^=5Ej?v=^$ln)_tZ4v_~DIL#Y5aC@vIgn zN)`@rtAG}*3B0tc6T~B_w;Oe8j+d)+qIS3mQ;i6_1$8NX`<&9Zol3V`q`t0mBF)cD z=4Wb{`aGv~?m4Ys&i(?Im0``_<5|5Rfxcy}IDP`wn%l54eUIbZa^ueea? zl|62bn(AcZatr4a31fv|VKRg=e?d)q$ovi6)rE63e9p3-!dl%pSiG~`(o1J{$T<&c zc5)DfF2MM$f~#D06+)s1-9*}g{Y~21LZPVIUy$?V2lt6e?G?c)DmlMYO_S8-C>7sB ztNl?K^1ZBDYn`IBUDZYvf(*6{msMNu zYISbg$Ms#B3m%#muMm1<`50CRX@e=2eP_5V9`gNI{7#D#aMCHD3xO^ao_4oL=!)8I z+ari&l5xouav>xF&mi|gVuqASArxY*S_l}~8BT$gdOxj0x;DBse2+{Iy1yfe*YH}E z2mPu8tG*W-Fs9>)KJ*_9gtLBO(NZ%uY$P)&k5q(3NOuik$x>qvePrS-OBPX^|Z$eWqIWD2(9E$b3~Zb zJdT(Z?K;}IdlM3CzK6MGR8qe1pbw7bTM^yjju(_Xs4b5SVW9amG7Rg;SCPY{o<5H3 zgPkOtd%@#Md-!!s?~+JWZ!(wj^$Rk}gmTDBu9mK$IziTQ1Q){d!JgN|??vyim`*3T zs(E-bxu}Zo9oYW8=ty`FVtKUG^y3u{lBgrsZ97hSM8#)H-7TLl<&uEJwRO^@oOZFW zFekPn&GE)g`{1&u!}QxDpFj|r4|@#JefHMQy=HSVFkRA;olAi;I0pAN3JjN&cbMq4=n@<`sAE;Cy%E!-4$hElh0>vx z)t6L<7NphTJ&0}~S7KtPD_z|)IbKN_7pG>Tyfe9QC7t3%bd)2lIE~6>X=X$-B>JIw zW}4X-Hfggz;*QrLb|AEk(C!5f`nS^2YpQW6roY)0(2o}!al9E?LMHdg?BTHMYT|eu ze@^rrgXmkNrqAM-qfdC}J9#m7wr-7xs`0>E2M?uQzv6X0B11`U5q)e*px&t}@Xqql zvl%GPyWWov25*zdXR&If^!DR*o8m+S+c}tE%S+@^Fpd8ISkKP8HW9F0RDSyuDt&r##4C z^d351R3im!K2%>_M}E<~%RHkXSiDxg^3@_;MA1^2dxh&W18J~dM9*_&Fk-C8B-`ZnlCR^zV zf5cX-#wh;;VoU20s{;rmGky(Lk*4_IK-~$%<)_OEyyE4JOwt$_Lrh;L?)WA6I9bw9 zkI$3S{mP}SY3Sbv4}BKsD$W2gmzb zlWXOCAdGqq+_BHbO$XyP%Yh&{trUyLtQ1S2xcFELi@rX9I0vYQG&w4kJ8j!Kd@`N3 ze|5aM+&fdwfAgS0>9nnOqB_r!qp3RyawBotE;t(wqS7SZSEb>ZJ(&K5Onu=b)P3RF zLAZuY&?eyhWQ|shE6A5{9cj6w4a7dnobr1k}N%UGWY?Rh$a)+K)qVop2ItBQ`@~hRhD-vZ4AO%r_CXDE602g@MU&~ zt%bZjP>ugZHVssJ3dazO(Am@lmXibZOz?V#213#ik>iuC$qk70g;CYQRPQD+gJKmU zk4v+eGe~9H0202|BcLovxNWpE$9~YsMJO!Gx3mcJTM;r@S2QqiT9t#DClyNotN~dAGL;mQYlGEzFmVnJH(hse88W)e8Il#5DFx+bSA;$?t4Q23Cd3c{$tYRp zwpE^x27e5|0LTZJ0i}QnKsBHN&L>LKpBfg&Cj)0Q@f+HonPeoop%K_j zrVo9Q$v2X}49$qr8hi6F4RC6ZBK$(*PBAr~gCQ@6Sq!g1Q45U+hh4{>Gmk)>&nf9t z()!9g=HYQNarj|;j`-*zvDMOFmxGy`9mJe+9=~tVr=G+3q$Tjx99iT_F{p;o%M6S@ z&A?hUR>Up~*f1OeCqEt4XOLCtgYg@rK3(NgFTLOiznI)lkL|q|q(KTjg|t&$HVui- zP~i-cosj@FqbZ{|o@n`NMiR!8$ak4mTxu!FTFl@R#62>GIeWs=Cp!aUC0Q`)BZ)UE z4hLD{MsLOV2lDNhTl9M^pa2bglTZAW)onu>Yfo1KuBu4UVLIOTO+9u@S z)g*1A3g%$;#27rovUZ{k<879rNpCYamOPqrx@R?H3TaaFq1G?@B{c1Lz2*GW0)`1P zl2_jt%Y+(9*&8o`-7&M3(y?c4&S zL3ES(khq9DnyPM`sh^p7MMUOial97VhM&ao)oVxS=mE2g&UHy24;E?R8Jd~}^Jyfh zI{JlqFpoJIeT}ru_)hMyIozaSrWOw;Z8Oz=3*2YKJabBmqV)QFta8}SSz>0b#W;Y} z%yvp%SHC$@YFux=!ekgNue@bo@MW@njuDp=pSksTGPyYSH9U^Q%!`5NWaPXsro%<% z&db9elK+|aKX|3(K;CySMr7IiBxW9%n;#)Hjq?p0XIxbcdwQNF)u+j26CFYwXN2PfiXuTcnWSdlIqUJX`DY+^N`0@124AvGqYv#T+B83)8WNBrHn956I$0AEi9i zzwzW)D}V(lC+lK7^*S+n2%>heFOO96wxJMNdfB^ZGtjnE^7Ygbi!@XS7zi{Mw?RYD2!4f$ws|7Z`Vg4aM1%}@#fPyt_+FxLS( zAFS@mOANj1B-a=3#p}uXcU8N#*zzD6@lLH%a}LsuO9y zFtpEcmiMe-XvA^pKDidRamWYW)JT>siR*bu#2gDr=dR5i$#jkpIlN>PHWEdF3cpTb z3t|-y^_;A=y#qUYg)b|BhE2L-!>hL=)Pi>$+`%~qY?Y0f>igC%A$;tQM!depdK@OBX%RX?%EOch- z6JdHQf@d0L=QDJklkdEjwjF=^}moPM!Y+W9X$C6{qBXKJE5w3}(W4Q_{yl|5W z`;y@%RkYhN4?ezJ*LuM9rZ(V-4F@_S-jcoxjbZ5T4zkiTUg0>6*fR37X~?Ke4&SV^ zBV@d<;N5hw6$^+&@o~JjUT5sEZFI{AS$XSST6D1$y>zjaDUqHjJD(M~X-lUSuq4fW z1+=?QlQ+#T1yps6rpt3gTZ~<_1v~St4E?FYQf(fHaX)f<#TvL83%?lF?~GIx$THlv z@7>br%WaFUANq`U{s}Lne&jP=!xNrw{p%#B$UiRc*^|9bo;Xgt|BSce3Ga^+>&W_| z7QDr>c;#zyruvNKZ^eI6ytu%*b58uLJ9BqR-&aF-8bqu2wIDtbYTy~p1EDYTHw5jg zn7;1(RT%Q>y_O)pFFct*HgAZpDmI^tmV;$D-3hy z3^~8?7v|bQ%bt%#>ZtAU+D#FruEsxIJ{TrCko^8!1pB`Us8{(pgywX@(livr!02v>olz38+iw7KET= ztAg)n$w+hCj@2W?*0^o>Xnwj!EsDaseR=$`+cpF`youb{9*#E<_x3=OH+-;{KBdDk z70$pXjzG0f`?oWEw~=1i>SC|V(;*t6{9sU!mk?zxN-eJU$kG^!>&FSKVP!o|8Yi9K z>({{)d;%y1lmYT<-L^{(CG@M=E#sA0TK;k?8W9#eq75nBwhPdcIEWdj9%LuNcQv=I z&Y=L|Q*JrbKk%WVv#XMkeVs-QgAw*mM)o)$;k+ZAtK#^_wglKB(u<|R@c|3~7nyF1PKzt83%0B8w}B<2j_ZG9G_LZd8Us zDsWb&;Q3^D)klo{1Zk}5i+?AVssf4c=e=-qCp8qPQ=OCm)Lvrxd^UcM-2QyA=@l!I zW8L_kh*PTAS{6Fx)1g#(a4wrCv@Em=Xg#6D&~}5?X;-RxL)&hb98#(@KtDJNYY-;j zOBb8rv_-oR?Jl}(T!+gR;&j;xoNn8cC+;t|j)blu+U*Ed%kmMq_QiC3gbdy_#ABfg zsUF(~l4ZL>*%_U*x}9v>6$D}Yt6h^rV_dj2j>lz>Y!NOkMQO?=m{o`hk8O8I{O({3 zS$%gJZY3qVOT8EwmMfGVtS3SwXpdI0J{hqaE!lh2IH&d%#MS|(>EKTfKo!ut0s8|%f-7383;1Ec``9<(a}C4fhO_2lH2Q&T+QTyRm}1s|aO0D*wu=lIg| z1h{_@kPVms$OX&>%pueE_BLgw0~fF!I2!?*08jnd4D?pOXMn2b_|rgsF+lQQH((#& z&mPnQuMY4w;Q#f2M=!E9AYcS620VRnAQ*oS?mqymc#eM#=!*ct?F)c$?)sHjM(kUF zeg0!m$;thpot)aqh_wQ0Nb7$6pJY-FbjduM3Nq)vI2-?qQ}zclFZA!HmWI idx)++p$)(Gf`3W7ey+Y4U6vzs29B2lEiWE^i}_zZ;@)!r diff --git a/Tools/IO_Firmware/iofirmware_dshot_lowpolh.bin b/Tools/IO_Firmware/iofirmware_dshot_lowpolh.bin index 15a5f4dbf802a9bc5d7fa68be9050253a133f69b..c65751281d15ac8135d3597a067783fae524d3d1 100755 GIT binary patch delta 7750 zcmaJ`30PCd_Mf>~xF{&dB0Dz;NHB^4)Z$hH=w%6rOBbtE1B%9ID{aN4Y7+%3cCqMa zORH8CY_)X(BR)}6P|>QbeNbzw_1S8*jg)75Q8br?B>!^*`t18&|M|Y(oS8FcX3jk` zbLPzC1V?Rar^=`H+h2$1s{qLnL?;4f9NB0{lB|bZ`^KGPar?%bM#;q_M0c7CvDHT! zZujOy4l=n98`|0F&HZc-$_dKdmnQo08D1P-meFa&oRie{2^f5{9w8G(OtT0v$Pdx< zU33E>#0Wh8459`8Vku&l0lqW0_vuX~&~o85M=Bv?lgG#St zr|T;+LTb106V#LnH+$D`mSp`@19_+4AW5MN(RIYqZ%o)!gGe8~pd!QfMjc5rm|HInNyk%0I7L5sMz_CItDGG|g=gF3!=$9M= z5Pcf3JPy%WfMH5R&jb2l>|f#T;oa(?r~ik{Uf_KISO@qD`izFYgnq6=UZAfKS+Fc( zUuUJYoNvNNxvfRE40B^K9lz^J-b43FMI4T@2p|*6< z*0M_eK;j}Rj+}a4>wyr5_=6#YX`L~!x{z@XU4$dwq>j&DEsV5sw8Tl@??YF#+*I!#xW_H}WFH)s6 zh!mCln;`sk;_ttWzt?;AnzE15j2-(9ME6YYwS^TK2vloQ|M*1xwgdfp>cd~E$iRv} z1Un<7G4C}V(T_=7M%xoMhqQH9pI51w1xd9GIVeM~g$}lLP zXDY33+ck%uT%--lFSeqFY8tjP!W!g*HRcEBjK+tn4t86_*s<(jUdOpt1K3@rSFNFP zyOpoYnD9M+RE?9*3MouKLAzVc8U@3OWg1>R7IO+7 zwhQ{6Kg_((f2qbvf&zz`HzChky1D0`;GR<(d5cN*zba%foG^T`6Db>8Opk{^+&%Yy zhB*I3XXn-XtWV1Q^n~1nC*&@uE5Mq9^Gm5yk5-6T!Ktm$2j&XyPb0X$`P1|PdIi^4 z6rk&)STkSAPFm4V|F&idEYfG(f>OB-G2_J<$idJcqtV&z7E>(Uooep&^)CW1OiLrVCsAXftE8ofu~8KAJ+<^)eAe8xYm3|j@Bo2n7qp4+yrVW&P8 zKB|{q&S|J#x?SMqFG2dq(^oy=>BT*s-ir(F`J@9@QXUqCGs(fQ*ij*ZvjwlL&`(}A@{!+)m0@p0iX0tt@DkzbjQ zV!|D;x|e{bqi+ z44BHuC~Bfm7f4==^y?$kUt3g>k)$7#)odWIN6t)m)C6{TQL=s@`-0(|DX+t>qgPKg z9Oj4mcQ;7ZABGJF9ZI97^$Iay?$1t@KEyx_QEFlAZBY>dITkes-yqS^K?5%zE3zPN zja#LcvLV8tpwwo*1sqZ{O6Mq1DdbgpKRI+UGdcnfAS)YW6=Zf&*WzG5U={q z$QziuK>9Or{uR)}Ryf97)^2-MlRSptIph{I!uvG;9q%(4bEza&wg9gn8)d5gZs2t# z-VZZBc-?sI5(8&$7c7BK$R(Ky)Z8Qw4oK-l$`j3=-ei_LyasdoNxVD~=a3BfYOEmV z<>Atu5LtMu$nWx__$^YU(Be7fKNah-cc^1+n!OowL1cAo5ME3^h>e?d$Jr-~VWr${ zC!?U`K3PnplpF0v+|aJ{vUE-?N;e@cLCANQW~ZC{U?*G&KupLnL=Ocz2>BVz8umQzHxY5UqyF zQ4Jn?`_SRE8<%?Dh{}|5XG!0{D!_Qrx@vILTLrdX*lhYrVL&WVJGy$~;ECS1zF@9wQUte=&}5OIW5> z29EBbYm`={+pQ~Q+_nVZ`T>{Xp6&cqX97;FM-IznY_gW(vhA_?`+yq;+^L?{Ke&|a zU@d~tZzgK^@=+A`mTPzZ9+06yM(>e1<3jRStstS&t>vF)B<=4Q5ydTW{hEIi1Up<3 zc8^D}7CMX2D&+_~u6~pkSM2WY_)Kezd^cYK4YxtNX|C9UYG`)_+I0`G1qSH*mjTK^ zj&=Q7uo>i1eGYcE z6(P~G-YRi3l{}GGKzua%3&a#<{FOJH*i=jLQL<=|7M~@@2W_QbTTC510IP{{a4e1_ zy9e)}CLSkjLT2CZyKp9LxdMyjUx2%0dxA{HcQLG=C8bWx2Ek11hZ6nRmKw07j{KYu zgp0_71jVR}U6pS*Z67&&vz)dz$J{r3vc&A!`;AhkZH*Jvd*|eF?qoQ)h|_k?*?0(* zC$oMsB};vVxlLrskdqLW1*xCH`$?`k5r0OEY6ad#svuoy{!$%;eV01LZR5pwPjwjt zA*3~N2!4TtCPm`8IT8=jq>AFibeO7cZ>!n9%8>5!%slz8%|Azf1-D)jIn zJylRr7?vHTrDmV@(6rg2xllH0*UV0zi@3X;p<0Gj=mZa<2W86oAm$ywGrbX0))z6Q zkk>)}wl88j04Y9*5d$v}P!5Oz3@ z2V*6;ap8dM1@^t*mU5@MG_?V;U~o|vyK>}#S!E$!Tmg?20l8}Z=dX3kO1Tv%Qym6!VPuLgX9$2pt4JeOOSuE2@2C-Y z8Oa*;6h1*#LwbYMj~c8Rc}&VJ0fZgn>wH-+)*ph7U^t+VTg<+hwz+{~(<0*86yRJW z{-Xy|SKtCTItm{qvqlf2AaHwsbf&z<(4Pg9LohG+^ZSM>KCOrWgKvd7jI2fS`-Vef zZeZ`%jzZAQNVx^1_2~uFL<@Ot>=AsG_-dl@Me|_IBuoW&5mV{~Tw~UzoyYirIcVG@ zQS>f8q?Xc(bd)w-M_Wq4Dk}mvjK#ny%79p&tj!pKSCWPdneTmJfFAyBayKKcKMfui zq|hS>d(vfNi7Hcut4VHVB7UD3GyCJW%pYVXW4wfXm1V*IHm}bvrtrUrJ13TkX)q7S z&BQo{ESm71z?%?{7n|erwqwkbFDK^XR1!bw1N?xToHPSmT=e7;JdIRMw&M5AZ%;|4 z1kIjJ#Aed|>?DW|(w~#z<)rYrSUlJK_H#CjcbQA3zCz*YyY` z3rKju`rHpXnMFv6xGko`{9@)YTy+^gJDfzb8B9zl3)XUqb_ams~VF4|^$g zK`hjhoCOio5H~R_Sco@}9~S(8%ghHCeg!rnD_%~f+Mv6aqXg3YvW}@VtgV3^y}%4N z0hf*M($`lSAToWWd(l-I$izjrA@CbkG|PX7y-lA3hkO%%Ld`4^aU03*qK(uw14()1 zYw96Hs;@TUZ^)Og-XBuY<9~j!3NB&cNksdwbe-=Lm(|`{pG-7}ZU}*x}~TCg?#pZ8fppS`8mF3UPLRAd6(;_R-*3vhCe@6XeI)g>&UL z8DA`mKik=O$j^e4eN}(7jAS~Yuar}W=IYkgc(K%enu%i9-jPDU@jZF3cyLUAr-W73 zGoTN0LOce~JD71mn^kXipFk8B;UYJR_u=j2-6b+g+(~Mdq+lg!U6O%cB#BG=Ckui7 zCAflz2)hZsTZlV^{X%iWPtdG)EyX3A5XvcaxSc`1FwzaOVrhIoQ70CBRKp#cJDT#? zh#Xlu0q-P|Winh&;+Dlp7M`HEm1N4Y=V6zvPgNa8D8`T$=J`*lnnzxwjB;*itDofW_{EL8gL*@{H@)# z$z3^x8qQnWyu_F7lnBL0J*}B3aire92J!Nrw3Q`orE-hS2aa+jtHzM(y)k+DWuOtNzUyouaUdqMh(IjLN{!D* zrZyqEgIqU`nsC0$FZn^@zyXc-BYTXmHpzy2VdfSj!!*gnY)qJ_Ed0xD@Db4|kouR8L$Hzx76SUYbEbrxAD&acZ{V;YKa8Tobf zI!Iqy^XZr}P=T%!Wx8$Oxh;2SIPhW`DjxGL^zgzO_B`e__VD}~j*>|w0rBS^*X--5 z>H6ZzW8SVF-n}pGkatV0m^T-fJ};(x&X~U`dtWlF%2_pEHLfbZN_glDuhQ`rpQ|Bk z5=6J}I}e7BWN+%#<1kn5yrmyCuFV?44uqQZKFFkx z``s!?OgBH+aEYRrGvva?pQu!``Lj*Dba+jd+qSq%k|oVVoY+ahGtOFgC-8zmR2Phx zoHK|P0t&kB)gxkU#XQ8x9f<4IMXr2Ujt`RgA8o}tvt;X+SP}$$Cu!LhjXx*t+f@NO12`SJ23nFEu{Ls8F5i|QvPuuZXvrro)rnv zGk3F7lKpKfJzf;P^-xIY_;!R(wbD4n(n#=*A(0K8B34~b!%fC*tA{*N{?Q!5%3*~g zZZOH+5&l9|rx@-!f*V6zs8euZf}0Stx?0TAas=VqrcU8D)ZK;#2bE%xunucxy4!ZV z0U^59ZELSD%J8a#=d`_kEZ*d{slXid*i}F82r}xyu)>QsTtDG9`^(Xkx7Ztwrz;&|pPde|W~YPd7ttp1nVuTa zCiY2hL&(3a4^C@GR96`Jx)qI2u~fjIGz>c5ErJ&*YRg3__`D za&l)lt|ZrYDj>zX@_e_QL-cnb=>eIsODov}r7L9rt~k7hT;8P!5XxL#e|B9BE%#-k zAhbF_dRK*p7dpBZo*p!u@4yNqGx4!%;W{*zjID}=Yhhv4DBPRutWtyqIRvQ`hZNrJ zgpITk=6f-qj$E&b_Frdr+itnsw!5xw?~+e^tHPTfu$Tu8=g$$a46qgTz0= zau=oBB@YtD4fx#)@fP2#2et%{#Geogqd~o{fj59RUEcDKc6Xlr5@sLRqDbDJ7lySv zaXCCgS3I!&?o@LqUD^T@4Ib*D?GP`}#{0pd#`|ARPVYeIRQvm)E1GN8+vNJ5bX-Sd zd&`Ms?-0rP6hvP%x9?TpNtUM(eG*WpLG*UOe#qAX>Hzfs_%F=!+nJK&K%J0ZUtuotlZ34S5SuL1}f)B@@N|E+-qcqakN0e`Cjizd_c zAW#fg1$Z=YBy_$S%4-4ZpWwGZ{xaYy;5y(Y;8#E^;8EL+=GJ|S@UXwL@yQnueFm`i zMd%73$kjpF0;nhN9?<@6%fgvpJ3ui&Hub+|k@y}A|J#-p9oPaeW;UYp0e{hr%=mv= z))j(QfWmoT2*6)jn)e^f6DI`1As-5e1jqqOKmuSWU?e~T$N=PcC>eP8ER}hN+&lbn zmhM@%5%-wQ?Z(*c?k+ePSO)R`u_*k*<*}~rRxtc~+x>G5#OPZwLJZs^%gvYT=28C# Dv@riY delta 7596 zcmZ`;30xFc(toe#pb=0IP;Pn{kwMf9U?N711H|SSQSpjLjDttgDx)N7B$_xQctAXY zd2ttm2T@4Wcz`2D)Db+AsL>TP?x(p{jf$)>`-sOhbAHvJuABY7`ThR=s;jH2>s?j# zdN#K)$0$=avHS2k#J&yK0yqnJRJUPHl0tO|v85Y68-`0a+%PFNBq6rVG7Go(DqGsU z=|wvk)0GeX8ptp0!6Slm_N2*v7$?fZOETJ9F#QLq?Hbr`Z#_b0jJPHl;*dXL+56}^ zLWq-iqoN%uLP;6DA8&1eV^bCw&5X z#>EptHc`QZ}r&1fI5IYHh-cHdM|K_ z9jSLktPm5mSxDZdMVMxi{XvWTzB40^sVT6YO+fT8Neou^^|T)p4+bRG9@B?|n=;|D zSf(w{_(VJuu&MSF(VBZmkA{Xc;8^J?F$ed;7f5w*wDGInh*iWPb{ZfRkPMg&D2@G3 zxSsHCJZVq-A2MG6ZzEtOU;!Xf(`h3ZXvv-*N$jEG%3Io2>OLX^|Dm;2};hJsh(CR3W;TE~_Z16!#?>TX5uLgdVLgINefQ z@`G0;jHRyaFj4f3HciYrEuK%zGvIc^$PLV#8l9!6sK#4 zcC;UB2eoADmzSI@2^T8G_5PJ&8Fw}R(gA7wDq;Nkv|x1+$P3&G@n)hLbV3r)A4TRG zaV>}YAiBnkW2(eAwJXFMs-Tu4QwdgAiZi*pElsUh-PoF=?gD)cNHB{*OP8n+ac zG>N`RmEwn7qj)v3{Z60k;*#$0`V#G>{F9!nw zOMlDw=M?H~2<%sYYncJsoP&=`9QiV^FESOHY{|eS)r5cx#$)!my?*;z4esct(qp zBnt<*l|YNuL|)p}iQ?h3+f6z($IDeZQ9I0psYZm|f;yGHeNO4y4yD^IQeW4)kml!R z^D{L}{hrf0`<&KU(2_KM2949tX(0O0^Y8bZd#W)9ygLUfs6mQkDRo-4oG*S5P*NoH z$Qe6ZO?9%dc}25}g)u^?FbP6gprEGRWPygR>Y~{iK6hz%VU2DqEZ&(O>7_Fqa?XpI zT^vNA^DurZ;VM^Mfsp7$HBi=jxkY)A)hWVO;dlKkz|x^;!)Wi{5j zTAj!CaYLu({DyC4X;&s z(XSj>^}X1LF&#(r;s0PDob`?9B{gFrMlcieNo7Qobk`V>A~p61PHG||Q?!zGDXJ$3 zpNKE1uI3*U2L#B3ALo~692AEnN_Tw(pY$rAks6bxe6k|4S64|%5=j#JW{ozILy>Rv ze`*JIX+g5khrgD8#yskw-M}t?-e$6J5W)t$IxT8)m-2i}z3mA?c|Q3(N-H^ZH7Y`C z9!JgWI!@Mb1Q)^cLEhKI??vA+m`)>k zs=0U*xu8nu8QlK8=uCVNW_h&4^y6g?lBhG!V>?E=#Ux}&-L04><&vPJHTBY@oN}|U zFekJl&9SBq`{1&u!}Qz3pFj|r2YU?Bz4q3Qy=HSUFkRA;okNOamdB(z6naH=h(VF1 z%(UKRb%_3SMA|G;T$u%>#f3hkxB4)yBL7h9@iI$7uTmU6(6KVj-h^qggEOR9p>U{U z^`$l8h3WNpH=^sw<=D7sN_W>Rj#pB~&8e9f-z+XtNhf;{9qCLjNvCpIx*5?-iGFCF zk#6>fEqXN&amVTrI{?}yX!n2z{aWd$)it;b)8Fh0=*0`pc-{;xA(MJ%b#vNvweh@; zKP&o=M)WOG+j~*$kte)!9lTgOTfbUFHF&_S0|(QtU-r2km8qn+h(0bgSnpC5`eys- z*-RAg+YrEqg15=!vpBU_3=@*)(c#+YNB8I4OD%2ZC#g~l{K>kd89`0PQbfmCrcU-7hf7+-qs-BT@ex} z`VJWpAI=3qvDhG3>|5Y&D#T91l)-o+CREAd_O$`k8dRE#InH*UGJ{W+X*tiyA{09 zA#>J^Vq*1@M1o7RhyZjcM9mAZiF-`Znmq*&?k zK*UzA!l>XlV#^v3s{;rmD`7QOk>-TZVBK-V6=cW?eG=qNO!8NmUxMQDvV<=9?wwzj@H8blFz9P`&qvQPh(RnUT0`=Ut5lP+2nXuhQ_$ZcP6|ro3DN(Sdiu-Xe>W;uVoDM0b$tq!$AtTvBXLsYAWwIT{`hP}05Reo`skO%^A| z;ge)r@@szC_A??vnSB2&L{o@tfL^U^&*fdVDeXR=Dl58_HHBcU%jOijRA4>?_%gfG z)DRus&|ptfpLlv z$E4ZJ9jG#`2MK@cVNjMNJT}^qVL#~LA{3GBUsq&^$d>ab4dK}ldL}O-TV_bhljtI# z(+wwqW~PT{rvZupCjrb16q7b1EV~HM*xF4Urca+4rY{DZ0?1~;J)jtH$^;kLn~1ix zhw3?AZII&6Xg|am00jVFaMTQK89)c91k?Z;0Zo9Cu83O;DCvf{70{0J0bM|fFX+Ji zb&&CuBaQ{E1(~~GkA?C>%C}xn1)4q;HqHGo4L22~p-bh4@)=6{ve=o9S?d`vWUlKy zviGQDgI(yYKgfj{l+@7fu|>F)G~XGcN2&;c-QKP#<9rBbz@XbER z{g9`mvF%!+Gfhhpue)tfbDjqW8-oxhIV$CeThLpn*HuT!D}&78N_x>FZySJQbQeTV zY5o5?vwwE~EG5O{+8{L^L|lU+P1oIAri?Cig=I%)NkRFlJ4zp&T`X=M9cGAvRFtCg z*s6|8gFhNz02BbsfHFWOpa#$gXaYzR5(0xPO^7rxdw`ZEIzQfv4}hAe2c(hnZaKdy?UM$EPm74>Q-HIH1PtlNOf(YRkSJ^> z(}ujr6d1{0hGfQQjXimo1~@ZF5q^PjhnQBt!H`$LEJoI%m<7fIL$71+8Hb_D=ah5` zX?9INaBr* z$03&ZQCl$nfqXkU5Brh$+`r-zRtnxLYmY9C|-(x2~R)PU^zFXkYPfM zDq-_r*6<3>1!kys?VW8Of4q*u>5V>2rnh zXSpP=Yu+3oHSRZGVKR-DSKcx(_!8MR+lVWO-<$?KiCmcT8Xikx=f=WwGGcB7<8YHX zbMx_sw#m8CTZ8o}Oz-^J{k7M5j>C8KHQ7 zyK~WTMlyQ-EzFV^3#J8B*zXA=Anl(Pk7>F2GCGx17i?gr7)i?8=b3knMEOo5J?x#d8EAjIlx<4L@I|WllkJTM{H-|I zFX8v*m$`PZ^%K~kbt`MUcxErlMe!@|Dxn1VhJ3WBUoS70g4aL^%}@#fPyyeRFy{cB z4_0;NC5GO0k?V{0;B{o(yDH|6NNV0q!J|p*yBQdf#Kk?6rDFUt6xkuLo1}hA)rquU z7~1<7%X`-{H0qdipHhe0IOGR!Y9dP)$9KOdVvdERbJymHW;(`*99ldQ8;PP&gj0MV+?#<8e8}pY_l&5v(zCc5!(yE&_Xcnu+4_b8|vfKk{Ul=zEiP_p>L9&?@cnj z4l-{6SiVa=L;raM_rc8!wI9J8L%ol}cCPb!o83Lk}Hc zAe|_Ar1_%>J{$H`@w?MB4Shh?3Mra_I{Z${QyZxFzBKtIyKTLvaxC+b*mBQHe#Oq% zR+F~(a&VDl*pmA=K;;gpogpxgkda!-vO~zw_lxm3a^n5Bu$IJskPBtc(hpp*3tU4nV1q_|*;ydo;Z7E1SJ$CV|#SG0OTb4!QG34m7Xq-lVgliIUEK@;+7im&q ze=^LZ>g93Hg-f?#R4KRd_3=~*BKqQ4IcSGD{s9^i!ZdImoBt2rP4EH$FpJ&ZRxNAmZZ6_ zgm%{{@}~KvplZh`x-3_;#o9$%sH?!r(4QQZ8uI{*`;yzsSHsm<^u^G=r=_Yumg%v5 z?~%@49$T-5AQ{yiRh91LO0bJ=yc*iSzjT&v@IP@cuZymaHpo z!J93MR=g%>YEE1JR`M6ci}PJOW+%M5BX5WFbv1m4LA3f_3*nQX2A=NPAO13bL(sm8 z>Fcgvg~6}hYYE}|z?1Q0)A~4^N=~eg?3v_BVXhsp?EY9(zVyD+V_WEy4w;BHIT^LOV5L+FL3wKEfj9~-O9cg6_s$`?zWgmj zyE_p5yMtWaREC$5*`HQmxkXX&EmqvHBYKuJZ;r-`N!#WG#V)x2jHtE*$L+EA=7;kC zYGL}zuXP-MIYhIMO5c7Y%Tj)ZMNNyz)Ggcm(vJj|;!>Yi1D7M(k9cn#hyzIK*2E~* zUJ71aX_X~v`0|X-a_!3xQNrJw5dCL6Dcc%^w~*?s(@3vveIqZn%Xn=)3#S*4?JUqp z^LtYW9|LO`QEy`07Cy<+E{F4t6sQn=1jh>LtSp5zLoMdn7z8ES_IBw6)Twg|LQslT z!8=+q(>=DM4G6Kd9vePVkl|H_V(>119)Iky4TcVHBsaE2;`PL{E!gA>pX;R$>2OSi zGw|`lQ0>!x?F`>#ginsT#3$=im`12L5E9}e#F&fIN*cVfHHMOgu>xyY(SVc3O6T{6 zwJ-&r0LlR6fPy-Y?V?i&{krOr@ycv1f2kD>j|d&!h7=y#dFV+z#0=B`vJ>E|n#We} zRDkeFj~wbB_)O8!RmsTS4kL%a2>T}^yPc45-jU8#@%&?3B5V=q#nRyTfrSQ=_*u`; zO5m_yWxq$34GttVhNRuYn6*}tyw5Dbd*G=|A6^(HP93`C>;bzCkYR7!2v%yGk9J z<&dQE9ZL9HKw9G*OjHOUhYYWZ4mfJ}*nV|;Z1>%r8-FEPR5c9GCUsQ__$zXwDjZUQ zt11=GBg3jcV&un3Q*|HwJGodLO#DCZfvdMcDv+|Ql$a z*-V$MmmATpqT9wf+_o^6+g9lE*d{-5f0=azbPdrihp}2#fXKBkrs2b6(9XeL3*1Qc z*fxMH-5JhK@1WJ~Wb4il2;*PvoD?4G#%1w5E`MZ;a%(9{S2n|}LR5HcyF(Iog<{C+ zyV7whDcx1(!^p5)q4Z+C5h5YGwTg8qh}~ex*{#O8b*~_{9xzo0e|Z3^f!+n!3#bLa zH>!?bbt+;P0TgK<2W>qd73lY%T@EM(JOZpEC%&AL>J8_D3;Is@0UZDc282Gxm!2oW z{fmGcz<59&U>0CDnYyQ^DJKKCfOWvx0N4n4>dz*iw*Wo^R6oa`3i68pk_Wp0djWs; zpbmKTfVTnvuLnGOk*x&*BVZBW>5GHG_brY`n*Wp>rM&#vV^+FI^nWSp2_- h=*kn?@M{nFkF@jW?t{@KIYOu5csaoG;-R;g{{_db-LL=v diff --git a/Tools/IO_Firmware/iofirmware_f103_8MHz_highpolh.bin b/Tools/IO_Firmware/iofirmware_f103_8MHz_highpolh.bin index 04a25723c84407f7d52dda07a0c8dde5e9cf4526..adbf98f090cde56c90c61ec90d7e209182f8ae6a 100755 GIT binary patch delta 8474 zcma)>4O~=J`p3_?GlLfe1@VPfy~BurK+K5LsJXn!MHm%HGZoE21qaN+)YeKH1WZgR z?Bs@NyZF{>sewofyp@9W*FxGyS((b|7Y9JpU>xepXWa3 zIp?1HoO7Og&QM|FDs9}XB1(juK*9%zgkPUZ_!~fx$G~dX@1^sZU*7NAJ1gj6?dyb} z2c8DUKnvKhmGJw)DR2R_f==K9yMlk&i1Gjz>L_wn(SXd_dn(-9umc4<37-m?ySL5i znHxj+6DfrEtj(trJvF{EFSWAr;b}2HxOu5Y9y@pJypzeQ&lbt*pt7`{4k|_UjGjCC z7q(&2KNuYmMSE?cS?rM4+A$@T zW%;2}5w|QS(6Y>uZ7ED6jV#)G{(>>G+ir9VB9(Uac!XwlldK5QL-LfNEexC=l@n(P zNWWIVSsr@)h2(&i%>Qruo|#10+$r1 zEJ5ok)4ac`lgosEC61OTH?pO_c5hS*D`-{Z`Fmc!@kk$Lfu}HPZp^s;_b2h|m$cWZ=F`AY-eQC!w6^HZzj7liZjRRigW$tWosjoy{%A1Zj?D*sz= z|2DJxnT^F|way>!sG^LGDqWTQJe)5XZho8k2GeV4DxsRtnfSeFM2vv>A+dxdFZljzm^u=wExMj#p9I6Kj9(~=Ua;I zdBX31enR%|A$~ zFkdGnsut#y8?FJ#6I&Fy z#Dlixdknj(=$}Eq~X$pwcjVQ6u+fy5d zUeH4%!tlAn=M`70Ly_BOdf(zGWkhOb3&({S{FPjZM5?olp4*={p-14AQ=H1R8L#i1 z?jb$poFeKmOFbkjJ29?}L*m>sev%^2jGxP0%YWH_f^sAH8x^t4Ur@wWf1_S$QpwX% zmRIEawMz=l%F}#Rmd~H4Ogk$-Xi)B^SVp8Ag-&#oArpS%KWU^=NpYEKiB4}WVB-QF zy>F-;EX%?;%M@{G!KI?iZikuQes7y`ma|wTc=X|bWyAdos5H?LW$`ay9)WtLL&m^h zMJx_nGwGdomF0TgFtz5Y+)FvF5;PC#t#=D;M5=N}Sv*8k`!X<)gKz`}(=%**&@8+t zTO2frKE<95nn>rc13^)q<9e>j{6kcVW`7G>$H~3y!Qcs8WdU0rJY)O}l*xuWfwgy^ zv3_tx5HHGdj@#bGP6fv({rDny1}$UbL#&izuZDzZrsMm(nKgto(5-Ca1QT6c+c;qt z6}lWdk{!)dy6q6mMjIidjyLV94%(8^K;I;i>|z#S@=9ah$aF!}NYnZR9T)1AE`(^L zJ#He^_okGkNNQC|5s}U)dUw(4lp-G+X>9f(!WUJ9kA{>Wi+Cc$bV`{!t7!$5-f(D; z754W=ibas?*li(wRGu>txgt?)l6@8sDS@SGH-}9cw0+!fbM^2IJ7rQ$r+stgZ1PuE zMtn74jz;3xKeb788`FmR(OecEs?#XX`+}_qjR`1rWlCh>vAZPqL)piu>;Q^#B1EH{k$spNKZ z5iA$_{b;CGj5BePEQjTsg!LU*m-N@(;ffGrOau>XGbG9tGdaoVI+k-BK1bnW>G#>l zvckriCb`;k>S3>d{dm89CF%y7B0>o=o@J(owBI$*&WD|oLXXLnf~M;r;UwM_w(2PA zZTh*r6jl>9HnzLBebp5_QF=%uvm!`$@jn;7^9ko@_M(Vw`SA8p0O^+WfBhoh39uqq;z4vP8@GPPWT~CkiPv#rcv$gGQ>j)>7mDoG=r_XFNR)W`|r~QrMbTCP*U6}mrv~n zq3W(_RPng!B+~orANR$N?R2WDB`h~39$})OB^HfT&a|(x?tFBRVCD3$ekOz+i4)_jSN&lZHe z{WlorjffhV5bb>8vPMvQd~D^t&8B{ zV>>wL;kHXi)? zs52``MM7uFyoj&|s6B~L=1qiB=swWD89{_@FlRW*U>gG}z$7pYB%*9Kq?eiqiy(Q( zHIRGI#wN&5@Zvl^*UE=-81_|6o;upP09$dzz}v3j5k+;n`MS(Fv%{h@ofQJj8fi|C zMk;j*CS{oiTZG4mlMX*fg#6qASESA)`b-xFFCRGDn$KZu{v!55;UKUPG}` z;-th#iH{N+CFZ?K>=7#^_7#Yg67y2%$~Y*~XkHTGD^RY)U+Kd^WSDf=l(-Xmg54J% z$aNR6jCiBBRN&YDMO5oG((l%7Hb zqOTYsj>8w|H!ijKeDW)eoR}OODH>rJ;Sxj{D~W2$l8uc#EMM01H5%!k^@V9}yQ5LA z^DAKpm2cuM;(;b;oK~}Flo-Iv?^1X)OJUiya1Zq;5 zm4m3v_9bL{=hvf$gBBxmC4|%EEG+Q>Dzg=dv1*OvRnICC$3P)+?eRp3(!|>R$p<*P zr8YiQ#nDT()6?9P{)tUbf0eFdE$J)h_bfJ}gr2Oe&G6(Nh;^omPJ59v3D?aIr#;C< ze(ca2i|*(4$r;3>yD(3m;L&JE<6))$vF;cBUNQY% zq44^iZJbw5HH^;J#lE+K@R~;n9|^KR3D^xZk`;%#L}_19k({_7QmmGrCoXJv7tYtx zzp~Bq!)Sf&f%$eyyKC73J2i}K^f_0Urfd^-RL?dQiC6Hk=idHYjv(F`xN%}O*25O_ zl7^{bq&Um;xg5>jd&odCRItnj+7B1TQf24# z)1t|=t~TW1cokPxz!ohz%rzI(%1cgCukQvolS0F-0#?23QDqb5lf89_2I z?Ds}h4leG0btvoYF;>2OJm$x-<>54kU0xnboy@iTCEp>hw!ut%k-fem#ILkxib%BT zt|Fq6p6gN4?>Fr73a#H4j`L@HY&6b0>id=%LJ#T~8GUptzOmyUjhUo#X~c*I0W01M z`vMI<8dPw?=kntNsT(_iK4y9JB$n9NmDx0cZCIJ6UVfbL%xoCLnpY;qDVy6XI6L}d zGAg}RzVeuu*h7S#<3-OJP6|ZSl}{1v5)f%l`h=yJ!^fzk5Sa=*^6qzb_e8G$tjV4; zhi1n*^$nTQf~?6BNp#pFoDnrfQM<+Vot#Le{BvdtY(0^p!)|bJ(tB=)J;6z_QgJTq zRmuW;3@Ce|-$Q`Mo9;|$YnH>F*W<8HVNP?9=E-xMRLp{M9--B2V@`U|CcI54;G`|* zFgcRSs=Y<^am@)%%47e?S!z9pvcCXc9Nxf5H{YdGXbUGf-lYO3dA>(TVVxKD98(&2 zyqd;&pQslLZ9ZZ^gR(2npVS)$%lDAgYfI$~DBr@atku%B>@Kd0*?5bVrn2d{PGi}Yb;{1;l4SxC zPKPBP-zGL8|Ea)TPM?fRsVdRO;?;7wlUfK1#iH~woiAXg^8*9U7hroYOC5{eB)oir z@cr`+x@T=$eh{U5n5*Cpt!G{9cH;W|7<%sXq()~GsAj6>d#WwchHF1n8y<|qg#s!PqM-|Vx)=6 zA*H>TJ-6{iWOVOM*(%N59r#JKcKvVHa`E}jBl%IYkK`OtehUmbVwP=Q*Zsw*n8(YV zZwJi~+bsIoR9fu(+A?$Ytqy;23Q97W=QH8>@EV>8@sD;Ui(gr~0;m)YpOo1*I}{JC zvo`OUPdU1PP2cuU8dDqa+zmBNWcK1&bSaB3iRV1dvBydhv12_|(hzTUy6qqLYSKOC z5b3Ow!*3)zlz;f^ZK_;LBp(NnuCW89d+A?mV|F~t`D-%t zbyxB~?c`H~g8Tzgy9j;1lc#zcJGxUJ67E!q`UW0H1h-uaokV=!>@S95?qMIpx^@Ox zM>y3uL?~&CNNK%F${N_Qnro=YhZ5{;95~7O*9_FTzc&IN8qwJ?C&g`luaOYG#%*8v zUSZm>I{Yql!bhYpyX_2n;Aea20sq;m>J_ru=~t&dc)62I^Am@Q6h9^qX;TkZ?PKFi zDyx|@QDFo=qigWG6?omu?y4jl>2N@Nzus8)!yVrpw)cLxqba?3hga)$7i*Nw8h-0? z&!#3iDKO<`^Xk>NsOm5|Kt}tg+aVK{Xja zy&1}x0ukC*SkenY$W$v{(BZoMg-mVbX~JKG=MWf)j6kz0V;Q_FVZX$>UI?d^EMT|J zPq~-s#)~_v`A~0h0%p=8mbp71sIGTlD{X-E6zS<1XtVssRPeGnWvfaNL~>-jqTPSE4F-@u9(=62hC2iN#9mbxbu zKbh>_^G8b9%JQ*nPWd?Q=AW6ldZve;{CP z`z9QO2M!%dn|JzO)MamBdtX{et62L>kI+}ytcnVDy&_hV8i!qWt@mCX%~~;o@Hs&9 zApTPW=0VQ_4}+xuKkfAYrOqOJ2xtNEUQz7O~NK@DgCAA%-u84NvH@f*@l;b>3?x=?->^xWg;f=*GUNg`I>6UtB} z8}wG7bjlmj7yRE&1;7>pTH*8GIyDwPE%3PxhT7i@+YQ{ef%bko8_C95XTh8VQo)dG zXY&8*-kInQhy=caXds7tW1vq52GBDf|26~kp7PDmw}Bjx56Zz_Fj(J8PT;2fX#^MY z6nGsR0>{A6L#EHcP=m2)Xbj|ly&wt1fJ2}YTt}UjK`vlGE`t`(3a*12pbfNxPHJV+~~@{pm1#RFqI0V0A;1s9Z3Y+Me|bHdS~+=~<_V+{ zG^H$|cE~o+^Ei9F@W^qP@F{gnb9}0MLc|8c+vXz+ODB0n+vaGFU5=6>#c=ybU<28d?{md=tX45fcR* z149KN&^=Lh9rd)(=Rr?`{199RH(+lAhhRVT6zYS9&G=6|%G#A@frlSo_xKaPWsd!e zbDn(zzv{h7_+X#~;UEUYf$1Oth`=-`hq^J8RD7R7b^}Y1VCF$~Vclmb_rO<4Jgnxm zKSXZdgVYR8fPLT)Cj~Myo<8tW1(LqEp%E~1+!iYfBjhAQ!uWf`lxwvAoowT-Ms;l0rZfc!ejgw0&qeLi*Bz&Pr_(O9DA2uLwL0<*?Ptm{n^Xu)q)1nrI zyhHdjupaCMe+JIq622YW1>GQME8+DZ1yo1>yb|>W4-uovO=bPEdiU`OLF>08po;KY zAs6kwV-F}wB>bH$!e=4jrf_(U;Zyfhem}2A0vF5h6n|I{d~?6hbHk8y}cd&a)^hm9eRNq_6eI9_%bbF z2LsoQ(}@1L`=!f@hb~>u>kV=lx3nlyS}HA*{N?H<(yZ3QqJ!oa#40|Q*(Zopws-p( z^1Dc3tmr4lD9{!}&QB;xmLhT%mvGWk&%d4-(VpK`R`9;^K3QIpAjOKyq}uH8hP}#s zGnYWxY|doqdNDf_Bt>2?)<{tsYO{lGH!4-aKhsCZlpEIGS3GN&5O}@#VMns$yl+c~ zzcj3vu4C7RWtiUXJ*8O9H~syu5##&HNwd$jzxREmo&-C6t^?3c5})gBHgouvk$DO+ z9*M40lFT_o+i50L_UmC6hrb;3Uu8t#>TS-}1R|ehIl=nz{&J`9lyWL0so@h#6xyee zt|&F;+Uz~bpF)}%nsU!rMo4YNtR{FW-N9Od$CkMCgr8#|{JUTqcnKTN;wabCkp$XxEogdA5d6c&|PG2j6dv zF}R}a&5()7Q+=;=Xi7CGqzU$})Q`@Wl5es!`>X1d6GT?b81{Duid$A+J(9=N-O5?0Nt$0m2ZKlaB z_|=qVtB;m)Nulz&;hDDluQU9nv}^TL)+jqNL)(pNDK{#9$LNa69Raxk#y9#N(=@)rbQ*U-I^>bY_8_IEqZIW8|5Xm5?b3?4<(iLkK zGN7hGogHcm`lG(OCWxAP=Y4a!&$Y6-KXPMN*`{sM@Z2ElHYsa{Of~;$y{w!Hep~rZ zGfkq&pF%H(UM>wbze4IyuRhltcYoz-Q&{S#G4yNp^e9tOt(p^&FpbiPd42g2dMtXF z=T?8)(A%IKKY5QkUNmF+`N{9F3yNRTz7$Eo5^qvshG7gK{qYCXA3qA9i6eBvG~ z{^4!kq=(9M_)O`$lW-dso~nAU2p3dQ7M>cc-b~HZ3DO>AnjXfB;bS8=q7t8XydaV4m>&2&(sUiIV$L_Xt7ko?42^`>al9;F?r zqK#z9oTd_bf)s2(6}^$s^m7&!mBuYb4N>Fh9%hdkOV_e@qY?sy?yCy_6qR$?m8cEe zC@)Ko9>ax~Fl+P^qn|{XlJqFj@%R<{`745WK~ai)u5VaFbfVgr+tE+Z4_H);oeFG! zOpGoCJM;_88Pi1nooyatp*F|)G1XKU?%tl+(?;c?Zo!)BB!o2bmg@Sb(yS(Wl*l7` zS+Oww*Lc=HPgYfytkqve>m2>C5!88S!W137<3J*}bgg&rLiufr23mO*Z3okGs=GIx4IoR}`QD!~OrUcz$p zn@qnNuzl8N8{NYvb{a$@(U~Z6wpG)Ebn?uA1 zw6=oHFc@{}-LJDELn5tXZy82oct14kqIoREXq?6$B>Yg(+&Cm}d;NMz8xt!9B+#Rp zPpg`V5LX>i_HMKG=>G6fC2-b4#Yl9R<)r!ZI=0mK8yd{ojbE1BP;{cupvRHouy>{< z!FtGADNyiv%H6j4#Vd#e55{~%}j3!v&4Gu7M+HD5A28g?5hwPZHYAyeYzse^pm%E`|D|W zFwSsDsTFjc2M8wzdQB_eM_lQT^<}edrm)G1=kCfqu&;(ayg_Xtk*z(ZRjJMchX`Ny z8YR(?vpyjFw~!-Qi)jaKWO?Hw!oE981Y5SIbZCOMjY}@T08#lqdv*L~`W|~UK96o@ z856EyoJPl5=smV7c0X5J{C3=UTE!;Bndl~#7xykoAI9YjztBVH^3G$JBK2S&n-i~} z?$;}b!Oql1tr&*Uz0@O!{Ey?4j`1n$AxPhqN>xFnQjK->wi&ax+05RFH_m+6Q}=IP z*AMQX9Iq?ev-aNtbF|`L9-Z^^y8iAZO#$=rWnVImfz0db^`1LPYLdlZeXPhGrSeJU zj{h@#z?=!w=_U3!A&Gv*CQLNaE@qi%V~@cUIn-o_deCy&kZ zTzxR4kQfam^zgn+zIkuvg$F~7Bb%v-n25ZTX(mkwiT9Yrl_W04PxdPGFp+=7W==|^ z|IOAKH z=%`f8W}I+W{bBXr2ln-_*@REe98Q993j#lrqtF~mBi=#ICUPalKh?STJ;JNSW`W3? z*w&;8x`}^K=fsgDy?rq}f}OPk9zK_hEKlT|J}V*7xxtO)*63WV_^CB2H`>A#Mdxa) znMJBz4n52IDRgdSRBk3H2cH6N6)|M4ip(ts=N=3TxHD$j|iDZRp=Ig_3?bMDV#`cxm(O+d zlXUnO04uP8GEf8RKs`7I+JHKy3dUU>Q*~^2V$9Sr9UNbEI&IA$d=1J6$GH}XW(#b$ z5$}mP3ItoWwC>Doxk80qB_HX9mQp;`bJ#(-Q4slTKa%4- z)mLSvHuJEwo#q>Ka{Fmpw$IhmtTYB%sC5huXXcX8B8DG_Z#C7wRPqNU(R9?8jzg)1l!iN8Gagf#?RYpdK@$+u zlP^D4=y63b{p^I0s~E9YN4`0mS~ON$Hfio+%V#eOnsXX09I#AfEwd-k#q8ni=}1zh z^vTg$`F^tv{Tz{axOs$0D~>^bN1C4_TKNl~!$$b(zh~+l3aj<{85t zEyov(6@)JW)!<`rp3(Uc^g4^0ucv=yY4c6=lw;L=7p1aeS%Hftef>%BSzESx+Sp$I zq@_%}f-?j6(M_d*1mT&D5|?3xlv)=zO%db7G|Nq8A**;Q2{ko7HJdJEkDszfJcC&n zjFoPK{4L-`nnUHRIgi(v|cqo4G6>+sPZtKAsScBViPL{@J0fKj}j?mt?&f+Mt<>Ey_cU zSugR(UuCT1nF(|b+xyI9>S8U=yp=H+cV{4HpF^a&C8V1IEa}R)nMCeU;zgp@cFrOi z+1lN&mqB0JttRl>Z0~Y?-1VMwCxe|dIVj<~_9ujH)HM|gO>W#??=N!4d0~vW{k|WL z3|HAdmM4x2^XkOdCIQ)_*Apx1unkecjTqg={>^}szw$Ekieq#?yR~8&EnqXA&Blb> z_UzNi>e>1V-b}+Wb=8hyK(jH8QT52Pycp1cQwbiFx~tJn0S||hKVd_y6Gn1!w~q?y z5Zrh9#&UfxvP`rZ?4fRRQ@&hKI9?{{J+44^Y(uK3FLmBm(y6@utW|=oJ5KCzh4paq z?|eNjqnlz~q}{ z80Sb%o`05;SDeLsVjb26bSIlxloMsch?N0OUZ|F2RMiKG+QYgdoV=L5TeQS}8fE7J zFAizqsaX8IJ$(Tt({FDv#o1)Ab}Fz z))+mWnk@6CU@ocm+v~}(sCr$*D(e~>C-3rzeb?H~RAO9d+Pr2nhtqc2x)}O0Tefa2 zUCmy_??SeJot|bfCw`}}f8bZosHDf4#3*f04=6R#7%Yg7q!i9p!tP1Gp=;Rk^`leL zONjiTqMhy(o%iL6OApAjOAoke16He_MJ?N>$Q=bo3Ey>u@anYkK&KE~10~~|wSOF}^}PXGbn{3Sgs)TM9FI$8>qZ1s;44X?i6f~rU40jdsbJzuZ_-r9 zwU?G@bcwIw+p8mG^EwX8`<*QjQK{~aqMi`%NaiQ0JjMN`H1o-CI>NzgrTO*pAc)Tq5T$7=b*zelHMFVCCk>_|c;(g3c zH7`jG{!_=v{yN?eClVZKBHUWMWT;t*$Vu31)fZ0H&)Psm-k^H$ZuK>!zb1i=tqKcU z_pvS8zmXW|kzkR&?Q$;{I0r;e3{@q z^4Muxqt8Wq@p}J4kR@pT&Gl0x>ef7BnbVtx<_^gzl)|KG&GVw$ACQF$t;-{x>?GP` ztIzd4UaIt1lcZT4j!M*91%gr6O|M#4KyHBDa&>(qD${oD!C}EaC))a}=3I$R$wl}T zuX-B(d9d0LXJ7De%kZByBq%qquOUyMAq%Z)Q~uSE6KceZ#HcpM9{wHq3X5VI9l9M z&l`ep%<#EN*|Tp%MBVW8AB!beZecSc`ZC32*5c}KjJ;u^Ev)H{nbgi6zhO+P_NZRR zJbw6)taSpQ{${wEgc7 zYMqbz`ssB&W(VI|Ko7IWZ#_-lWqCCiqoq07BRoHD+B#GQQ(GLUtQz;jSkz za3EzC;Y+|)=-a?{Pz~^br|)l58a~Mb`YXb(foue6&-fCu0)=muUecxTmbP``zf{#~F4CJ>jw{tt_^4;DX!Nta1@ z_4aAdGr<46eGY7Ssvr2@Za)X*6a;|5`VT=50wEymUv@iLj*B9&2CN4q;03S=3(n% zcsCqUAd?^|=)?`YaA;kH>7iB*D9{1*pF;tVK_CQ#0Vn(-AY+QybH97#sf-P17icWT zKM5i4K9BGc+z;2CTX26=9|7G2n-1l>p;O2J;8ptuc?7oOpd0?W=h?K{@uSi6;q23u@sEXpH5JFa6Om%w%nx))SKzXf>* z+yygUM5ke!0i4haK^*i4D0>J3ptquqPUw#}5<4FR!(KS)Ax(gzn!$BJT3*I*pn*-` z78op81U&;~A&^VJcIaCmy&wd77-R&v0sZc85Dz+Wbbkl77@!A>p5O5N#?7pE->-`{ ze}E5lM+qMeVt^6Efyp2R%mkSrdq560V=$@YAo&!5-AEwYA>$yc)oYLgeHUx|{kw5Z zJ298Q9dHTU04<;ayaOJBRc1n7W?T2aHK%NY&rWe8A3i_$eEoL}h{2N`_pf2tV(Qne bUydTd1C8p9r{uDhkoW(9J~4_H)H`p3_?GlLfe1@R9spm!J%5QrI(8a0=HauG&F(o98jP{9GSFtxSPK)}S5 z!cK0Owu}E-Ej18np`1m_T50oHNZHlOHnxb+wJwRxWrksX-^-tV_ItK{emu|TzVCg{ zd(J)gJ?FgloT0+TRob{&MU)8HfrJkb3BNvt@Hc=WkAc;&-%IB+zr5eKcb4{H-Rp#( z2c8DUKnvKhmGJw)DR2R_f==K9yMlh%i1Gjz>L_wn(SXd{dn(M^xB~?{37-O)v$w6# zGbftxCz1*8S(`^EdTM-SUTS6K!&9SwaPv})Ja+Ebc_))ppDmKr+OpK14k|_VjGjCC z7q(&2KNuaM_4PkV_+}Lm7I+MBkwuR%@;O7utNGX}T)NZ(Ppn)uk<_M_0w5V!p`W*+tQm=!Y7p9m_IjfOO$?lKT6{nW#* zjoRdWxrhi{b%CuZl1T5er9QgJyhP=*@>ySFjm@k@|5Vm1a)qHX^%eOY--ep{^ak^2 z>w#; z{GhK3x>9#9%l6d;J?F0KsF2T75`M5nw}ndal#e)kE#oKmR(&u#>>IT%#J#mcwM8Yx zt7v3l_l&nc*g|e4s}7V^$)}A^bkN{sgxr0x;G>QbSXLQw(U{Lv0?$=%Q+*Ni6&+dT z?Pc$mX{}ZAi#}Cyg|H<5(=$pWst}3!sQ1~hDuh0v>mZ|}Cl;F1F3OjTb1ZJV-0KsP zW?q)93`~|s;oT^-SStV17=}9jk>tnci>l>40-Zvnmx^e}Q90L8D&NrgcQkiW{rS#$ zdcXcYy=)lOLG{Jx-5Q}({?f>I6qhy2{M0J>1>wAW)kr#`(@V-mqjzP7hw|Sql>cq8 zf1A<$%*NufTIY{c-&R~1FhY9=Ad5Oc=VEoyNdNh)}&CPE}qx4S+`+oD%S znHx7{+_eLq3C%Rp*rIgIzmJ4J)Lf+37sxiXj!0j+cP4cG>zZmFLr2}V$=b_8C0qdoEte0Rd()}m94v$kF|AdQ#pKmF; z=Lx_6`3YISlbh~otjTb)<6g%Xes=tw{P8`09~&w=NTZUx3hE4cwODe;w`^o+u{CP` z!aTi{pjwz+lDCZgZA`$hg~&~A`xoqoG3A8?b;Z`=YCo%5JaFce>|toN+Heg>n%JVq zB_6aj&tuqCMgI)?EswaXN-j8L4MmH?tsznZH{5dAdc|_&|0Kiqj)hi(Ug^UV-9=Ar zxB8k#TDDtLkhDIwTtVpQ)DLiF3*^5-Ey1R^S?VDbvJ>OlI3&(J<0mQN%=o$7wY-=8Cnz_9zey3x`~^j9^*0%mCY3xL zX?;b$U$-RxtUS$EW&Qk#%G9&+gGS|UigiTtQRqZZ88YEF{*y*3l@yn$)~K}Rd^RrN z(ffwl!LlrfwN4S2=3gqx=yq86?f14BYdwoqf=3??ST@{0pGp%QkyihF<`HO6I%EnA zQpDoGHIv?XS6Qy-jZvdMx-itq}4-2wJ!q$IS5B!5Iw`jYiHp_ z*<$S^`V@OsJCV*|2egr%<9e>j{6kcVVt>=F6l=vKCIf|)L^ZJe-+ z3SEvJNseYJ-F65TlZ_Bk$D4OmYqumf&^L)ByO>p&ywcP+GEERQ(zHH7&xLrU3Bej^ zkDEyKy~$EH@I@8jqaY>7BAy7*ol?fmYFa_1Hyj#d zh5fw|ViDvzc3VgrmFrAEu1FA@WS<2@if1Xh&7qS9Z6EjBTs?flPMK8GY2TbVoAlL{ z5noN1qmelFPhBG2#&jWmG>657=rzjozF;dtq63Ou84_7|>@LaqQ1&q?JAk6>a8WHi z#g2rO(->yd>p8DO>;?T(bPS`DzFyxdYeb<&hYiC~*GzMy<(Q>Zpwh>%`oPLbD!JWK z1j~hfKN_MFW6hi-%c0pPVSNYICH=K`xWdI~GrIj=Oe_|cv7 z9xnS&F4EvRH$!sAVwcBU_HljZ&yb2((MK09a&J=UG>eS9K-<~v$OmW>3ym_;kJuwo zdMdGJqx9TJM{QM%H1JJd@}{*3;wrllaDcNf$eZ z>&G9i>6oD{`>UWRM)p1N{Tz>@~QnG zMBO!wDjqkTM0%h7kC>%2ni&ncnEGB}y;=(ErNSE>rLw_*>Am{MnlJJ3*@CdQ z{|4inG>Z7(5d?m^+U*8E8n7R!mqqHrit9#Q;UakW z*bWYQxa|^>HIY*Kt%L-bed<(}AhTLbwrI^k=_MAT{{Y(i*{bY7vo<|BTWjW4m1L{d z1eycWlW|R2Rno72fNSw8RZhPh*Y{VIauryflk%?5<%&l zGUBuGj>2}q6Upr2BtK~b>8AI z(N_!?$Kea~8<$#qKIxT4PD~1l5KXX*a0#M}l|*%ANv1{~mM`o18jbYN`hrxq-O(u5 zd6}tY0`^ta`Qt^z8JlS(o!`knA}19H25dF3KeN{!$Ck!N`d&kDo*naIJT8Wl?|HP)Jy-L@ymb4Z0dlr*kLQmG#rh9S^#5mJLr@hFTi0fvD)1K%e zKXw>QMfY?2RL?dSiC6Hk=idHY4kz9ixN%|@*25Od zl7^{bggDFmxg5pbd&o#{vD**D(QL6(W2}7nc+8Ju%fo0kySzMxI+<(vOTI&1ZG)NkB71#BuwQA<6p`rE zT}4DCJ=de8-*4FE6*|8!9OuvY*l4VG{i z_5~VzG^pT&&*jGlQa5%2ea!mkNi4CkE3;@g+pscKz5F=gnZ-DUHLpyFRW`R*aCY>^ zWK?>seC07Qv4;pb$BUjdoD_(tE1x3TB_PtA^a)G0gpE;2!7>$ijwua1 zUQOe?Pc(=HHXkvdLD`ja(mU^R(pd+NG2uTp;{X$-6W>esU>fu(AV+da<%dyT z*1HxZ1qKzaPa2Ga<$K8LwWaa~ly6~I*6Qe5b{E&hY`j%RQ`mG|r?D*SI%Vf^$vOcE zr^6bDZxfr4_f+66r%(E&6qV>>^=i4?Nv(v1U{QLR&*!t#d4U1v^Rc~`rH(~!5?($* z`2KkZ-LtkWPfO_@=E}cA>si;jowz>z*ut^(DCFx@bKLf;ZrgV}K2P%-FR`}A{AOMI zx#av{$&AMDezv_cXfrg*Kif_Y+9o&h%(&i<`m>bv9W=Z)`tf+p=+ zNNF!-&ux4W8QptRmP&JX2YwQ*UH{v)TwI>>NM7XZBiTok-vYHqEV9k(y1zIT^LV-Q zZS4%P&1#rUrNz##tutre>hKq*pd^ENJ`;uyuko2+|0rjY_?5LQfJ$NTNuGVPL-Ei# zYjdCZl%osS^lks7(X|23-B8m6W-p#am$JB$IL_l7d#oe@JJwSr4RIEy+x~H{Ce33G zkW*YhcG}si7htLa?)O;3Vf?Gf?OL-f(zmL}$mGWVijjMnd=+w|(h* z1*ya8@Vn3nACbQ7wlnO3pY5Rs{Aa7GSIBCoU!D5keY#X(ov`AKIXV(qtQ`VRomWM)c1$-t4bY zn0#~JFRGOGS8>~?{l6ZdoL`h*6gczec`CfMvKvsw%T(vKA954@sC1vX=lO)2i3L?o z?$IW`%Bl7`QHy%%nvuV|ReIu6JN7ZH1+wm+FbGNDeiqarX`@*&Rv`u@k#z(k#}# zTR$tOSMe(A^}z30%Dh%$bQFVq5F9#yz={~=cH4ai*Z47(vL^*U zne5*4M@rbr^091A`8e+8pP8k63U^fzV^|d|e;!ajDIZ6Vv#-l@=w_Do;^x8`e*&S9z}=zr+* zoP#529~PqAXRqk(vws3U>g%&lLYH6cQ)&=tWPLMUj7U-Sl+Ai6I?Qq|K7gYBK)~Gg zO*jY-96FRX@ASW@%ihBFzO;~5vG$i9p|7%86&37yMT{mT7Q5_P@4b4Oxnc(4vw`M8 z{HF%YgPsW<21@~c+UfsGnML?u&;sJX4&eP8!s{R-fDv2(o7wi4Cl;WdZ!!{N*$OR0@WzYgz!F6y0w1IZe32uvp z7$GPwK+%8(cmi+W3!2c_4bTQI57G*$JY=YIUC>?NF6aTjHaGWY;^n~hMR-x5_?7c8 z>;p^L^nEi6FT>mdTn}TM7yo)wvrv|(l!O2F$jc~i0Vzu`xxue>Z6C_^FCn@7*er}D z_%+9+C|d!tSKvLsulbduY%iF#629OUer)OQ;tRdkU|4c6#d8q=Z~1#RFqI0V0A;1s9;o4-VgWh}+Q5F?w?pc{>(D<0nb40x zo&cu+MSFJ@3HuJ{0iX-_HJ}c(fW3HL1ElQ;{%1!OVl~!n)5??t!n8cv#JA ze~8$=2dNpH0QM%h^_0~g>>*iZv3|4b`RWm24h?%{ck9C Tu;_zY&2jvy;$J)OU^4eV{0R=& delta 8496 zcmaKx3s@9Kw#Tb_W}s0}5K*4mGvg=^(LqEp%E}`)!iY%JjgM#spKXLVdAMS--a)_! zi6)rRySVBNW@DnR8gOJ+j1$}_yONFff{*X&8h3RQMU$AXiI{1a8Rq_*M>e_N&E@-k zb55T+r@E@T>Qr@8zNU4`JJWn-c#Nq%Zd}ESaGRTlO0~aN11Ep z5=g7fnJir|VrPP+$m>NKDQbO9cF^qxrBe83`Y@StL)v8e(i|62AY8bEbI4K2wnBdV+A34;dx(ed$n?olGy!i`VuP7)bI)Kw&j2C`?WC! zSCqXOGCp~-@0E5<&}T)uf;H? zcbsOXVWaJfb1o-g z#NKKv?G5XTYW`7F%a5X35T!=^HzF?lB;weQB0g0kCil1QQ-t(o9b1Fhs1?f}g;WkP zl}Quk&R=Jg(>3!8%hr`kPe~EdVreP6IXuFDC6bcQ^-ty=zSC}QD3i+TLM5%Z@8ogC z&wNF4Dt5UDdKvUGX`uP#QeS%Yxn{ZhDp#ArQb&xUU$Li0n38JLoQQ;Jl!nde&5zJy(Zf8q z`rC@$2Ict4yWR1k8Pm^CKERHTxWgeqR*xK`ia(5;V^~x~4H~KCb*Q%P(^8YYOs1UHB%=@yOk+=7%zs8;*j!6!-q3Zc<>Ol z{N{$5>`Bu2oO#78GGh6Jfe@@ZTe1`{-YB|Qn%~)N<+olhI;Bhw=?h4fP9Y7T!uKPV z45}%j^0e**siuexiZrYDo)H#UhP@M&5Fm72Rrsf;E~ zS$gy+F1(moqn{Z0B+8VeN0E-luh`FD5yT6MQs{Gi&FZ5Q)yCY8euBQwqGGnv(d zlr9B3^b5=x(@6iFZ5m~vHplrtVVj2$isSA zkudhzU-k^i5k#H*RF7cf41qa9j7~o4Bl2ZWR%Mo~)nt_t`7>4TEM1vZ8jR`R8cc-i zwS*rJ`3+<#GDqSAIe&W{t)}vYZXFh{!xJZ#LT+OnLe9`qcY1xCm@c*`!Sjf`nC0j< zntsu5`?S|KvYT(*u8=x9`OA~1GH+iQe0$Vvoh+~~^ci9My!w*B+#m}-o5Te+g@_So zZ8@7}FzVF1UuT7eL|V(I zR5lSIt}3MTohI$kec_=>;EV-|k?1hXNz-SwY>Dw#G?=v+zbL+;=tQAjk0Zrl?{rIo z^^mnfpz?ph8VoBZ`zv>?rLZ*j`cZ>kOtx^cM==#1gY^uoi+ZE0ys=`Uh2T(fCn;U2 zp3ccLyoU-8!{;!3q+Xv*Om7Oa#Cq=*o`!ul?1y{pD-j!Qi8T;?x*|>YlQ(<&>S=y3 z#&Aff5p*5<2`2}7O)K6*T*(jhWwWiOu!)N2?uy;8uYx_iUTqTehZTaDuj#OP+@TqVj$A>ex;6UG`{f9^J$; z#$CfWjf}O>du(OwKCY(d?YObDl8uWq(TyxG?j4jqjLR8%p_|U;oyRam>cCz$D_%d< zuSXDrov964F$|-7sap{FAI2vg<5SvAkiILF%6Sz^71q_;X3X9uGdmD(oc^%8_TRj& z@7+N;URSnf&A$caXvIH2I_Kwg{oP9%1Low*zGNH&nb+0hJ$I5+CyT-QSdlwQ<&(@E z|0nu@ITNPROYCt%68)5o8*ikY%rf4{ecR=*jZdXP>pj}9XKCr-_bQ3Jl{F+z9G&O6 z`e0B2F&c{L;k}uB)1J%=4+a^BH&GKY5qSyIOc)mu?=g!jNL-Ac>{aMtBL9L-pO8rZ zo2{E*jIwy|wX3=DxHs5w-k|N6OjVC>-9-K~`(Q#!*h9CbPR8m~$HOEFdLrrMV%9NX zW#}c(=vcoSaiXK8OeqxPBDAvje9xA-w zUZI%HIN`4R-KxL$@9SYR37?)hlmz1z1b!w*fjN{$96-({as|de)w$?h!mGt*fyf)# zmZWjI@xN2&#E~SueGxo@oi+U)K9`IvPvo3lDifp5^TQpjqM4r)OiI0srmWgroDfXW~uR6uG2h!6~B4?+yC zZ^I{0O9US5fX_vAoX7UAZms?}X|aowhS?Y3tgae(=XHdZHkjs`@{_IIlF4#Ph_veD zIbAw=mD^w;`e;er@rU5m<4zKhpXsh$-?w85#eH&+;B&S3baE9EV5oj1(%f$M979-6 zWw=h>)I*J-d1mSNFZKEAV4$ zj>er1L4Jl*Pjp|RZ)zVa*skPqI+BG=o=NN3!pVAjtvALpDz{wOKQGc6Gh3ZrKG)HY z)8Ri4Sb+_cf@)9;>cBbB3e+)GFz)J@s$;tYW2TPj!1$`uX-fv-t5H5M&NWChn_;_+ zcu&k>C$XSl1MK}FT*M?h0NiP?(VJWFWw&GB|`gWx?>*QD1(<#%CSazjM zrH!lwzqc5jl4utjb@B=j-KaDKiT+}U7%Psz{t)TaimzqvZsNqu=r}PImUfRI;_ybO zzA`hliHD{2G+(ci+fLiEeXi~%r6JHlt)p-_GZ&8(G5k1utEv8_;@>HmHUT5O4;y_< zJu&oJ1huvjc6^GH`?8A_P5quqY-OsRo@d)qN7Fw#4y6`Q8t!mSdrWDza6D?}VGlo4{ zhA$Y)310}Rz(?RbqjMwZbrv;OPyfQw=9=g!$I7`bN@d5=c`lmt)yKhSZQ1H+V_V&m zmQwKw&J5g#H)sHx$pnREer{FFW78O*|9 ztaKaXuK_R894gnGsc`I^Kar{ju#Xpvr4Jo<7o=!7zL-TXdY7A5>^QgR7!8!Lgw->s z(73*sl`L7Vp2e;&SwYXT=}YsmoxHL1qjBLl5=O!2pY7`UlRi*$N!F{O^_tn(qCC`? z^%9T#RmzH=8AoTaJkLb@rylCF%IPULPSUL<;L#|)y8 ztzCV3DfA^>Y68E__AJxKUGF}3GT2FzgA%@NdqU_!U6ZlUl*5uTG3@6p%f7Jh7q<+YlAph|z86+YC7QOD{7oKSuYlTg#Wyd2HIV*_e=9 zpM5%6JzHPFn`trVx@qS7pNr}m32X)_OR{~U2pwez_tO8eLT+G`%pwUupN zkw@zse_7$Bw1zdWDyMZUXZ2dNzkc=NfY+5#h9s=bS{Aw{jxJ_tYi82NY|EPMNT7tb zHAIi4Cd-^jm`m#Y_IPqEs$Lth(z@El$vZt_@3pogl^9o;Hm%;o;k2E$Hio{;maZL5 zSFu;|yMXOmtEXAaiQh@=ANbWXD(P`1F-q&z14^|t3Jc;xDTT8YvwPC7=xVlX-N=;m zVj_Q_Xs0?w=Y6^S(gQN((gUu_fYs_}QOou!a{Iiagzr2;cy(HNAa#x->!K*mmd(#S zqNiBn`tA75D4L&k3XXh(X133D)#tp=V*{Jpbm0fvr~S4ko38#~JJ)Y}qUlT4Rumf7 z`9sOE{*tjx+TRb<`fk51x@kBI!q=%Wj>p9_b;E+n@s*^&#F12*uD%P!lr!~IPPq@rKMw7Q&}3_#k^%H z+*cp5$>r&^g>5WvOqt>Kxjyyia{Oi!x!TPcjkay-5eBa|i$ZZ6K)=+Z0pIZAAGDU5 zwM6E+iF}H!tk^|Aa6GPfm18@$k6)YO)`;dt9xn?%*F@+f_S@EQ(SR93e)GTYU}bt4Uy^E5pLp zeq_t`Zy*MGBv_#~R^JBT*f z>T`XEmnuEhBxzEIqXP9-f?(8j)2r4MkQ-pPTwNE5%Cw!kaai!riMIZtDOaMCauI&T ztDc5`8mu-qZX6NLW^o&#WTb0e*q+$Hd?g}s&0H^$*bI_?c)sCq3oj1;%m z@rEEAGkmTR_Us!GQ8zq&$6^VVTiDEqzEm-pwYd5lV{e#fGi!WfI<>RMZy3|6JgV0* zj~_l{tMgCoTP+@74cN60OGr*V%{LHveHR|0$LI3*`CK9WEAAt*Ep4?Jof@zcjbKX{f9b|oA`bFgNrzy*OD{)-K*_ja(@qOdvbJgITw(tEx zt@BZDKfSKU?BHAT>0$Qxt*7ZbEU&tHFsGqfou5A+KnVN1+N{e+#&>*2$Sxx-*!cto z4y4Q=d@zt1FMy3;AUGoH zU;3X^aM%^7;v})J?0e*D&$>o z4cq{?z<|#SvkAWw2GT$Vm<4hGMP*?i0_ge)f>duZ(6~70DIgIffuEa~Z3U?38h#oVpr=4}Y{vB^ zP{q>rOt*+yxIn7;J~4@qb?E9pEwO0(aJueEtT4 zcflbAG6|A`4&1;ChnAI?9%|))0v%BQITQdH1VTUKeMdqEZSTab6a zT`=uMbQ-p4zzMwo#6f?6vWFl5dJF34fc|&`vGYMN?17UW(gZlF8CVyj`DF|T8rTSK zfq{aB&@)gL0=XD$gT5Kk3qqiWK}LWZ(C_{V@t^}o_XDuS06kdv{QBoNY+^loe_6Qc zeSD}pO89UP1B@UJOav)lI>-ds{c@lg14$(Z$)^zPLIT+a83$RVUV|LyJ6XeT--&D7 zfw=_kfJ@*8Xa@D*0C)&inhANCZQ1wMtkU&9JH?HB`267W_1!Tb22Xa(zlLG6sZY0l aF@gm5H>xL|lFM2`-uoT;NU5g&!G1fR>AilvEVKUM(+O+yEZ z!V;7ES@{4LQq&bv^OY9(NKJo*nXTy0yd-unyDa-ZcR_#l>-XQ!=R0TS+%q$0&di)S zGkdIBQn^D?k>l)q2GMbVe86_V*IVA&wWm^2c~-Ngj}h~b%JZ=-XzJ7Qw6DaS!%Zdb4N-2K$nOOM-W0%#7we5 z401v={SdVShY@*&HxMoI|80*L4sb=+IdA|qoNipFR?4U3D>$uWN?x(rOFct9Q@!@F zbD2y<%P$KFHg?=5BT^Itht?A>=b_k^Bsx#QaYGcdQVZ*& z)Y1SD88~DdE+v^mJUw$XwhvOgDfPA`6{(S|g&)^#&pDYa{7_Of#M3tdN*1GqcQv(Z zZwh4+Q9=Q{C%_v(8i$Mu+GuVNa+No2ZLcClt#D9j;fc9cs6$SA3ttJjgUG^fB!gUw zoDUm6_bCw~bJLNuQ;9IQp6qnp<#^d4u}tqyHgu6?i8BIsgxCs`_Q^`ei=?N)?_gq_}wM1CN-{cz!vV<37meYJ zLXg^^kR5IELd?ZuI`ot4S$|sAD16Bl_wdEBmNf=Rp@fT<;IN{uaR*Koq6f*6>arSP zf8;U)_ML&ylPv|O4aLBjt6T_;O^rbyIrjioXdyq_FjKX*>_nNjx<=UIR3lU{Ihsoc zCF;vU4cKTR)ceu42IeE7a|e0o?q8IVeoAnNNz1kHS4>U;X{s4{;%v>dDS8qPEtUw1 zm|&>m5r+OK(bfs?FnAc^HfwP}t*}s8BFKk&7+O29qNO8K;bPTkn{to=E7pN_^O+JM zAci)qD{B=d#MB5InHIq#1{oqUipvIrc4f-RniEo?B$6j>9-c+_e@ppez`S*3A0`!b z?cML+Keabstx83p#wq2G&wbyq-@X64H>_E#_#Mn}3Zamqu6Oq*|H-<1Vr}K({`qnS zmZQ4&*l&F%rNB^!_NS;ZH`ydxQ2*PyGOVZ()J%=RQpBgg_$4Z@yp;yjJj)q81i}f( z0Vn95oGmK)^X&tDqc7?zJdo9O_B9vw6YXmT&j6!AXiS~>gK$`hqfUz{Olpfn8y44! z0>tU1B2x>cY$i%7__96}cK-_DFzj!IIK!0NFt_W~b_uOGEV8Xg)YPvRg-mYMDij5R zUMk1jE5e4Pj@D3CbQ?KP@lI=kf?=id1VI^(xhw%T3;IE5VBQnXDDg;9fd*zhChT27~;08%Xx#SL1tjiB!v)>x5-jpx}7UWcmXp=)m zDMNFGW(FMK1u$|cq*D1+@WM2=nRI%&6cvEKURUR$ma^3c_X#%2t7<)@o=J{vBF(YE zSMzNmuZZ~{A^*TeaYb||Q`AbU2Vd5uePgYfQ4P#pt4;x*c|P|tSP_pr2`Lf2g(ozGw(yJkegF3chTW~6nXablM89g`H#F~32f?`P)d5@rWuN;A93z(@eR`Dae(ord z_8%oQ7ijJ~O7gP-g52~D8si~)b8!0#^^gfx&klLf8udmoZMB53gVJg4V^aVd z!Ybu7_fHd+UlCd`<`5a<^D_mG&&M}VBuTy#sO$Np!q-nM)%nJX5(mFnrP#W7 zz=WwQg&28`ra_2yhO=NkcS1m4Jxhh8#+>~bXlkbk0Mrk(Ydd@ zr@#EyX2R6raI%pLeyEdk+of zb{WIe9vX7oUnwfh`TK}uATxjVk4Hq`AdMMWe+AY9B^RfG=Dt5tphw(?mN2yq>mii4ct{LO6Dj@3FO1nP5~YoY3CITqtCBOy#g*u2?w^Ij4CVvTtxnF{}O(RkHM#i2}%+0-O1g9E)ZYz@C|6mp=|ss$K8NWh$`sS+IK3|O9st2cH4 zweWY$6f6*N(~Kl16-9RKy(K~*=;%dMfxb4r5Lk^0Crbklu2mNA90PmT=o)erVAuf}22d@mO>F1rd@&*{`rVRqB!_mJUY)ERqJfPh# z&6e9kNJygFAhW#CA;VEcr=d`XW@pwDwB>uq{g42e*!>#f92$XbNPMU}Wi*qV(0AlI z*prXIb0H@<18AIpYWcsjGxPi0{yR+m4i;QLJ<>08h zEMrt*xu52iFcy9|aGiilaZ`+UbG5(;vdZBAIUA*-xHMBx-d^B(0XN55`zmbh2o-_| z@pfc_P%(z$$}FGe?Ex7YWYkuflSCfws#;;Wn|B!aUA;1PkClG_>iVcc0uUS!>M=C8 zz|z;wHywcip9)ostaAsVxExE++*+u29qRS9N66Z6SLJxi-MN*(KLvb`dQn5feb*f{ zFIIoJ4be60F^UD6a|vQ-fbtSK9ljoWlgtQD*B6@+Q;;et91tdLrJ^PY3JBh!$y*Vt z@K@wcYWJC~D3>~o(YQ2IE~gJzW6+O6dmmR zp;^h!MWMbl_t=Q{AZ|Yi9u+Ek+l)8~nKo*a%Nnz!P6<{)fzr$n7DwAc8y}4-$G?-{ zm|$4KSurm=p6@;@Ae6=qPe)u8(Z#3~pINfm9^Pab@S#n$eMPGWR`&2aEcVry^o1E*d^2sR9MT(P< zJCP^J^HO?lKEaLuZ(0!ljas%^Cux)H&?R2%7^sC+~NgZ8D1)C-bpJ> znkQKZEaCD1aUwLmXG8x26~VB|CeHDX9(3(+XKK4x%HfaU46Pz%j! z8v`c>W<}*1)q$!8#w*vBOA{=x25q@A6QdG$xR0876>&$6On%>SUjsf~JofEjAD*|^ za&@MJdKbAHc(S9W2?0aW%RFqkSr)8t$yBPpe7#TBmdiJVuu^WRxn`_b9S$Xv+99KX z`7zIya}t#5zVlranQi6`C7@V~KPU%O40B6hoZ`4E$-c40*i0hh++9ZWMox%SNjn{o zB3G$UEVuA~l9_S7cqUmL=UYVg%G0FWsvfTlCfy%YL%segCZkx`G07{}KTUrxHo?Mw zay$^)j0TJcOa;sbtN@e%Dgm{C27ov}?czLvUB!7?0d^JV=M?0{ISYs7*b3ifXCPXf zt34jT5EtSCV2Fz60Tm}pOCrX3Q(YR8F)r4T)3{ip0jbiKt0eD^djS`cbK^$iV+6;K z#_i;V_=qsSCR=U>p!cxQ=*Zf#&Jatv!O`%CS<0?Ys%)m%B%e?=7C6mhYkUNCT|-*p z{qSex=lD?+ry*_$X#sT_cNT08w-nLQKi2FPk_s5Gcr{F-Z#@cltkG!`+Ogfs&2XJy zY`83vpR^dXxSDhbHvZ;he_XHImz<3$+O#d@JpM%YZOS=}4Z7{A*%GGK;!#hjB)OC- z8T<|hhIwnqmUs-Df>hM()JkkrvG^Y(UL_xRS8Tuk!=zTSR5jFnMJu8~4n2jqam{=h z`BEjPoZ85DDkUx>7L_|*qjR4Sg~33oOg)v;rn8^8g2F$MqDeuxLig#Ubc~0RN7?U+ ztjVFcUHAFqk1#fp)Twz?l!<&X^*wALiPL7|kIBwy#dsD`ykx*tx&bdoQKE9wBXJ{H zK0O=1LrzYYm0{u0W-;fCgRmymSiBC)Eo!;gKYG zp|5Ya^0I(hZV6Lc-bqQ|E@-9PEI2o6g%afrA)MqbbiwIl<-(hoknBaXaRNE8Na4)& zo)XqnC=9ZS_GMV!!)NI3EZU0kEwVD-B5L!7W`amgX~t4#H9BhXTnZfLf+fqb8@aaR z49*}sm(GSG#Jn_8TrtXJKKK#IT$Tud{kzNVQuwIuje--@pq<@F0XOf+zCNl*>gyw@ z2O3iNx}Qj@UY~^p-ILejF)k*fR{G;5WZFsv_9d%VF2+IR?#dv1g$#IOI~K^UHx@(c zxN5q~ukg^qO}Zjzois@Lq`W}NeXCo&>U|8N&Z~d+mvW4NV`~K`Ea6jSJM4vGUiF#Ti%20dJr?Roq=dV%}Tgm$fCD=@nur_Rux zVIj><0pgmPjA&NcIUh^7RYbmK4pXBktpk^{SO*udUfxGgH`Qn$;9uUiDQYyNX3eh< zUzWb@F2%2skJe7}pI{2hmqYY>K^X#(YPqQj`h;PiO5s+G1TJ~b>pq}vYRKMo7pOlq zV~~|1Hol-%AuPCmc`-_GP^9*>lU;thE!OE8P9@()WhD0kyyt?j+c3O zGRJ7vuAbsNj)|K)wh?zS$Pqe%AfhaEut~s-HTd8y{#0M3VdWF?2V`}*9JYLQd9duI zV-&ZLoGE`9Zz290(-mFNpX>*Cvf`?sX(K=AI6@GSCzjPYveG@W&nYgKY}z=zXe`L2 z0%+F0iQ;}ef`{QYit9Rp8H$q}1z*$X0P)(eCK{Bn7>Bb;wm|R1dNzp{Gm5J_LUH?z zHY^JHqZQt1!{zK3Ng>U{K(+&-1d993_?zKr8))eMBnAJg}8s?WTA_ z7HrDI`*pfa5AopCUXS{DYAU0p11ZGg-sc)QxOp8FeT~FySx7luBOh;>gpZI%Tg*W_ z&FQL@W!#v;Yspj8W2QQ|_Y@CBDOqQYPFGmySQmQ~1cCfN$< zSfZbcJ(L>ryS=>Led46#>&(G;8(8J>B(FJac#+1W# zGJ~ua$uH!yB8Tf@)FDZO=Q@l29t|gLV6)FN-uZr>S9AC?UQ0jEsd?-(-dFuRo8}46 zczgSKJ;!G~<9*W4`{Velz(Wd8V!Qn|oEIJ2lcjJrM0{8z!}Vm}PEYSz^8xP{+1qO6 zc+7olzM~#9{(-@R9R{KM`{ee{VDMsgHNNgE%t>s!y3-SL%RnZ1{C$Hck*|xZxlG|& z;=KE3yjj<|yW1w_V2_1g(IZQ@Nkg2CnSvLwQZdeg;5Sze@d{`o#xQi_YhOuKRf`Z8 zU_zWj4`IHnfMd1(%WC|qE_3f0EOQ6Gg?R4w$NR_&`@<4{HX`ntG1F?ILcBS;F3f zEh1iv)b+N}ft;<34hUrtgp0eorEqN%9T(z);kqPV*G0M9dd$)RqQtgt@nYB4lAD>d z*9~#)Y$`~#ZG?xN&z)Gj&BBL)d5#jhdf%dkZmP~n-xqygW&lJSuY%$K4TjI^s!7b^ z5ZuFmJsjKk=&^I@M@^3&%Sui?rlm?nbiEi5Tll#aal&HteWjU}5^Je1IGoyCV67K- z^gs1Vto0BV-c7Nt6J3kaqskoAC%r@qjnvY)Vq*o?#t`QXA`TNBLBi20kzLf-GI}>}vqjhcC_VzyK-$v5jCY2-F8T1}h} zx_eeZ7c_K{Z;`+>qmeBhNe?il^;IPC;33yq_zIr9(7Qh4&o2Tfl^0mHmN@FXaSaL8 zDIm?%WjPM{3DH+T(hBmqP9@s|rR$_y7YsL2d4nQVEOU+S?1nlzz>)QXo7P^7lx?kd zs7~~h631$AJ_RxY?#Io-&olL1Q`Dg2A`@01xmE~LN})8LY-$Js=T+Y@2HTN`4GJ$8 zlPDEqvVkYkT<8PAe`Es8I{tEOstWCb`|1h$j-oSO3JSf!YCW25JxVC{TBxhm4|@ zHu4b2*TWxyqDDJ=X}F{daHSq7^zuI$d->}!cXiU(`)*07&PMS4`YR-0FkSQ z=ioXrs%cE}W;2pM;U@|;^(b8WBm8wINjA!!3?D!AzAX~;j_Fa=7TFJrcgf0gK(rjLp@;|lmQpsI_HH7hxkY|{pd0({#O9tk3CdF&=>d3m5wgq|5uL4@b`+w*M0lf00dyoHTAqaHNXU-@ zya0$J+mDS2T`(RvfNucP0ILBw1tfqb0@4AE0C-tDwm9)z8lo=(+5lGpHvsVV;5J!u+`Z@%FU5|3oyN8n?>^3Km{bv@yG8Y1GTC4E%RHO>)qmsc`Wxrm-#DFr<9MDhIeNl4 zd;xMm5RspZcg=^~62Njm`BGR`K;PD_JUKubQ3avRM}S>`&j5P?2LXox#{s7R-vU}i zO7@*O12O%|vpa)sC0dFwSi)k#*kb83iJ3w4xnch?Py~rP=Pi2&?!!I0+2`g+{|^Bd B=hgrK delta 8186 zcmaJ`3s_Xu_TT%=>+n(#khh$f0Ubbe5J5~$9(i~Sgrt_5UI(A!gQU!S+-gQ1I;17K z^+sVyrT40-fCDDz2)oxqTspOB{|M^d=}o`BvMJSD z;WHA^yKVDuhqvNwrzf|Z6!gmsSq!xTS72^n-rjWCcasHqm^IVUfw>PzeLw&BNzDi$ zIbtR%5rcdYP2WS;fx<{M<_e-E`Y)b{;Q&`{o&CJ1K{8gAQ*Amgq$;N`q}3YELQO9W zHBC3YX!77THj`Mt!MHyu@SB8V$WA{4_8^^pkzSV^I`*W{T0n7QN!WnI=XN+mzOI{L zF}K30)Z{-v1v-}I-g7{0QpB@yg^8x{?5RbR>A9EQN)Kz#e_)xoL)d|47R8x#?2D$V z%;5U1!n1lR4!6;D#r8zg_p~_@LYOSp_R`$xPoDRb{TMPc+Fjz%nS{ zY5X>s84wb3d5P-ogfPmqxu`NTffaey;mQ5v6!~FfV?anm60|NrE5dc%^1Wb{NgQ!N zI}0>_aw;Gxdb7JhFzUZosV*Vy4&i`ai|`)zRU4lffD zjM+%usYjT5i_`{wNai`(usz1NvxKNhB{ha?`^|BJH&2|5GSzJns z40NsqUhm|aKTo*tHK)Y-e!BU=&i&zii~s$Ss!RlvJE=Ecc#L7|{(wG)Fxb{u`zx4o z5+R-WfpvezAFTh!J!(GRKUdAbjxFqN{JGcT6c}5#e}V~f`7Xu0JwJ=Q0emSlgceTg zKrJ);AW|Tlio9{E?co`-`44k#uQ$vOR-0?{ADnr`pZ(bKYDb91*?}}d}ZP5Z0ypw`-+dYG7=@_c1dVp zwhCwTc!Z>(fhmW&U{7GBKr&M}lzyu%Rm-q)b*i8rZ^qnY0nQKV6*~Qx(CHqbTOHC| zUv(qh5ABve#V|MeF{!hUNu32LN#X~PIQfJG^O(dJk0geHbzgu8YLS9xN~2yYXG?$g zvzC|!=1p3tizzH`o4TCn)t7Om;!Z_@(RGrLsV&xCo{Gdu8ZF zS)JZKUCCe4Yf3=J8k1y&r%A)5Ql7>V(*?6J1H!nhUfM#^AiZKgU1C^So&B~x6(Unh zujtYTmgQ?q{d0VbYfKp&mVIeFFEsdW7QWQu1e|yr>LpMwF+G}Ssj2sh5cyfoUfq%@ zl4FV+l`LXBb3OA)>Ifa)55Gf#!lTDjN%0#3z19?v+Y`&7F8SuPQ~GTab!`7^nmgjs zusT++rnyrttiC9;V$6k-72($?DXd3CNyVEHxzyApn8tD5Ah2wl9{UElI-s2bzL#JrY5+GEYpnkNE9v# zxzA(BA{sTT@CGtm8#nGppminO4LuY0?G*;@^R5Dsw*qZ!^6#OxhpWx)7bNP~`690n zq-7cgH$37(dX_AQysM3jle|*>l4SGbJwPi;31n|-VU>1x}0tWeu;3#pi!M{d9! zFp-E_vxl?0Oo#$oQpmcf2<44LL_6Zho~T232bmLXz;D`WqbsmSQdfDpvkh|zByC6_ z){z&644HM?-7lMARoqW*MoVeDvzZ7LH&#U4vt1e13{Eb~upll=sz0#I$*}msp}IT> zGM_IIJrc^1P|k%I7k`J#Uss1KG50T*0%kP4D~7c|NyraFvio;AQ|n{cRQ9akI}vdU zNRn=ObaNl=iym6ElWtlkpgKJArvnY?*DrWoAC#ryJ}2Mk(r`TSi}9xd-DGf#Mj;Kz zki3}q(5UWw4o%wm5Y0O!_@+oHlBH0`D!JfpvL$8%ZYS#45Y?-P>3SMgC@nTJX(EVv zvHC{Oyz;t*CV7O;I^Y@_731X`lrHoL1F(V6k0)FmUwIS z7U0_he8KgS$%y;f5j`ixKBFDcHES`t+J@*ZsP6?_Y$sn2T{}Fo83GLlaijww*-EcC zc^j2D5j=*ur@@oOnNQMENNM~E+)P~Y27HEO4y&f%sV?J=C+V)`eXP@@=?MlTuZJbB;dWoYlIemNQRGy@TutbHPSH3ZLqS6 zOdC;-v&c2*9Z6(~(H`$PFssON^B<9f#At7M_an|j=g92DDEzT)U1A{ix#pJNogl}% zc32VjknA2g93LZBMn>ST2|sd(--m8JI~&DB(A)_p-i5dWWO!1HVvQSdDl#)E$=~9Z zE{Bvx6eZ8ov3R5kbnHy3!1u}U$~_G(X$$}!K|DAhtS2ZCo!Y6coNAQrS<4KhiHV(q|0opM#*F$Tf1~@ zH-8+i-xT|<^N99^CDAk8yp3#qYKZyJ*RVal0RatVEY5`YQC|sM201G;rY@rEyZI`R z_O(X=uOuz<9JIUnbv;ys!gG8ZON`+;a`w0}EGOJR6^7@?jOm3^y#(qR#^X?@W{2gZ z14;nL0n{9%NjJ|4%_#x2-s!ImHDt^UHIxEQ0A%x^4JZYi0LbPe&fy3#Fs#-n1+&V5 zh^Yb80ak)xtx&cBEP(3(4uFCX;|n+gI470Ch&d_I0uU1n-~yo024Dai;5}#soCBuG zqL7@cR#&bjFxwie;$lRs_0Q9rK3&$!tKyPf zx@TB9x76Ju4i}lr}M)gfBh3p$! ziqDdSaY6nrcS3H0LEh<&v_`#F`?AR2CohhRz~jiOaS`T=ZgrNNThSGo!(>N-ap&BT z1}3Le*fufL7@1|iosuf@A0Cyw`?%*HdHuh6ybM-F^0?&rVAx`k#~*pW4fbdo^i9b@ zGzawD;I9xZ?arA%kXB?Gl+vn1k@%;>s8@?f&eJJA#YO&bg%+pE^(xLtHam`m?uW#k+z)^ zvoWU0Zv`7A(sMDm%(nZv4=}z;GA9>OqLb{I{5NbPX;Wt6_sRAtr4Z+}&v)R}Hm?^F zDap8L3AmoTJgop*$%$!dyn@`C7LDiHyr%OQ*Vtq;7E(BZ6#eCdUpTC(1#lbk;nM#L z%h1`}YCY5qWL)S}L`ObkEN5SP4Q)08?!RbF!r| ztLLr9!^n{N5fPL17X;LLRhZnmVL~c*&LZb>;WF7Fl|EjpZ`7HND3Cr z#2Qk&KM&?&4Y7%>|n`YZY5sNaQH7g$QLy+fLh^?d#d7Xl+o~1sV!V?0t-2N|<9-ow$_~L7 z3-+pXS-bT5zpCHXaZK>WF8(RffAt+$Bgg6tFn-)$!}=?_5HsRB18Ikem2vyYg1<)K z?WFv#r6Idr-*))M>RNm?(w=$_(X704E|zf_ME&|KhAAqqgP^n6mhRKu&4&x7CZ-7T z|Cf6Y1ye+7UjGTxw(>WE z@*eeK5!qXEj(V+#tS)VZEMrXB@56&3kCx))j~!AVtGtM4Z4fpTojAfBp-f2NHj)uHF#ZHr^ zwd$BJ9IXd@?KsgV?$`FG7>6Wu34&5%d7X--_R-8Bw*0mdQm#58TNfYI*`;80klj<< zcW|#N>Nq=QTp-i=ZtvYlaTncW^18inB(POY{VI?sYYOE0Gp(7S7SJo@S=fM?kmBOZ zLt%)K^~{SLwFZay9-&!}dWxfuNQXP65qC1k2L@^;zgc4joE9+ClacUZB-JYvTk$Mx zq*WDaIP%pMLll}L6gPsLu6O}XedJr&+A0`tH-O^if@&x4brd1U_tUI(KCFC~VmHN2 zBGJaq{%>NJrodw4)hcX0h269p*&(n=S7>$l{<+a=WHZ%Ohy^Qne!$%pSu z#0SZ5@3^BEyR!`=U{PyA<{0M{Q`{Uk+tZeJrXcO?=oRx;P|`-LjKDc$cx9v%XW%!M zEUi?-soMmAwu5tB zwy4b`F;(|ZGM%iIiXX|}&2=C_H_Ea^{-S8VO~Xwa)zbPW?TbEIXiM9lwAMbFZ_D*R zX$Sjg$`44_Z4U`6 zcGreI#ojRKpTXQB_f6B7XYO_cv$2rR&mlLq4}tjQQ4P}~`n>s@`CLFzxP##US2-qTod(}}n*Nyz?4yo!w8AD8wiv_ElX zgjFB-BwfYQ7hVnDaX=ShIe@tR&cW)Q-abq@p$fvhu^VVL`t*_PkYdSMCw%tZ?K^C}DlhQ=n@* zxmP=jEU6o6`oQ|ywGeLYGJ zf)ct{$)7s*biobtiu6p3VIT5u!vX5mC1-s=LyK6JzWgqhDK12XQigeVvEsy?2s9zZ zUIPQtptx3)<$z5iT7%Q?LbhYCA-fNJ2JgW_n}5V!;6ZwnDmR3hVw(Z$3X5qrBRy=$vw~)xs>qF z4ivb@xV%QgWrF+UPH1Err{E@{@_0-@1w-{SpdoUY#{!F%=#=2Ux(j7QUmQTdTQsO z)h_5A8-=KcSl+;OgeR-QD~mx5z)+XZ|bpHkdTxJP%>5tQe7T zO|$SJ@a02mEO1MCA#AXDs%vyWvV`V`Pz}bja5PVdth=*DNi8-2ShDZ7nf2*M9kK<8r}qk(xGAPq19 zkPXNK6aXFxI}El1EiYl8Cs#K9SXd7wX(ng@B#|k{4FAEi?^syU6H>4z9%)@Z8>S1m zHwUIW_doZI`+rE{1>jYH$3l>j@WhVGJKk&8zxUws<1QaRm~$W?1Q0>qI59r35Nh)P z3jq}`!LEdIxvl+#mppzfBm!xG34k2HM8NZa8GzXU6JROeRjDK%XHLU=rv1$J?38rT yjQi#%iWrMxZ^O;NKT>1=J#`${TQ}Yu2>)X5{p*g!=)4>uJ-lpdY>j7U$^RcdGJ=!< diff --git a/Tools/IO_Firmware/iofirmware_f103_dshot_lowpolh.bin b/Tools/IO_Firmware/iofirmware_f103_dshot_lowpolh.bin index 30603776fedbc6e4731a62951df9771143ed338d..1a0426c5761b65fb228d5fad58608d905fab956d 100755 GIT binary patch delta 8278 zcmZ`;3tUvy*5CWg3>*X$MBcA63l(et&ICf`cqQ8qxK- z`Pkqf``S2w`HNs=F@3R3U#)NTXjj*|L;E)naGAcUldnPh_) zqF+%R+*U9k*bk1H zyrbK~@9AY&%xyB-1Y~ug>=2gbwsb>kitog*yePF#`gIMZp1fp3l6PBHmv&OEP>cSh z2~&r#Gu2h89`)OWiApLAx6*Zm`Y3gdhExt#%I3=v-AKL}9Ospzk*K{FRi!$%Hwxv< zFA0M=Obu+aD*CuE4mp~KhA6fEUSR^{Omle^&n1m6i5~mSP7`IUs3lR~TwIk}R3D|5 z27t=IA>(iv$sFS8nWM3Nkm60Lw=S+sjbttSxb6X*lgYvlCB;KLeIww_VzltCrgrU3 zpKOr|T}qb6Uhu(C2eui2I6Ux+%g_jSWJBb7cKdmAAFwmxW4Y zRq8h3E9VdDw+Z^}Miq+lXvRU}SF*z`5I-SbyZILfhambX0=wuPa#Zw=6#DvE4%g7w}K|W`@YYdfw z)CPs@XpkM(Y6N0BcXE#dFbw6oRNM?aEM9EweVL=P627E8F}Jp&9o_g5)LJn3W}Iu z$m0=){wUSf3GXm?7~(c*aX_uGKv^othk6)VJFudqBU9mGZPQleAOlvch1ShuN`-(J z+OW2~RhSS{BWz$=1dkYGh{z}@9}KN4S5DTPkP4-dJZbarEWZC+${+S~*Oq^nRNS?9 zzkmPG-h8zx6+tsjDSv$K`;PtY{olP|&SJ&yV1`o&g%o$ayFd9)*5wmxDHr$8lQS?K z)xF1l>oX|@hB~xAMUA=1CfWS@-`196MU9|lY7CZQJ_Y(OQF-O9FremH&fp;sPCyPg zLHFcraq*vTAL#3SaaYlStgf@Kxv-yTUo&_H7!5*W>ck&}!%7@=T71Hwwn(&Lajhso z99}9iwMfclqNKtv>qBAnFBcBO`c{Y|Ot}qnyIyUV(2Bz%+ls}O`t_oa$*o$2qEOIF z<(PX#SfA9<8p?`pBL_0xX-!ZttW=&LDC04gCBR}qKL`!Xd%_td9w|1UfmsJ>LEp!o zeU3c~tXBTNcsbO@6hrm1%_yX$P5WFGe$Q2L?zzIwDfb$l*BkJh-udVB&MT|Hnxb!w zZB#0xtmrb=s)uBX&NV@Ft_3sHE@}lgNHWSLcc5ZzK?s}u)?oFgt95PB7 znkzCh-~caxk;~vIm0txfOmmw^rZeV%@C*BW|Mv!l-L0OPuBPflziQ#vH}6shLB9s51GofgK<+27ja-K3)2(Fpb6bhD ze=DK6Ky%+#vfn_CdHdnzoppx?Vskef`9@I^S4P-1lWf;oujm6iXL3 zm@xG=Ax55~X%M2FVJ}!(mD(VTm5Xm->H*2MkcJ7p6*4XN8#+?VbXnL29!1RdqI2K- zp8og0789lphnNnsWSS4e-!l zZkI7k?V%yZ{gq;)Ie#Bf3}oib{_%+D8>BHK>#x9kpyc8((A@V&3iXKl&=RJ$VLils z4SKgtXajfEijp}>QVQuXwNrqHM%sA=L+=Z!Qm=rEQo@EUD5Hu>g-c4rjU(SPaiZl0 z%7@|`WR!e_?INRZJLcNSB6+ZL6%uU7s3+UPzXsgcn8#kaCvO(FT^8A~3wrrS)@eT+VgeQ4gapi~nzn(%oB`7larMRy zkQV-qnSu!-E}D_#q@viqy;n3{U<~FwNoJt8jW2{&qr%COz{7Y02@X=>dAiqwDzLwM zPg#<&6>}~%oSk_RIF| zerdMc9zsGA-3FQEMGhH`Dmo2?Iy5`8p3qvphujYdkcri=CeEP|*oMT1x>H6o$q9W& zu7g$i2z(cEf?a^d30Pj96x&Qg%(mbtT~BihiENlZ-bcti!?z`@w zxv~1gZHTT}hfyrZoJ$Zz1C*D@>F{;fn`B0Ky1v+qn8H*^k$sr7m5Q1qC?I@`CT~To z#9xue5h{FF5gU=iOMJ`@ipk`Y0WF?7UEu-&;4>4Q%9;51ra3A11uU>T7s<)eij zhIP`%HcDAnu<4g(hNYibB>}AR3XBlLmI~#QN`(qo+*_3}Kbx#G(;wV?_c+)I>kRru?EaQ+yCqob=l7`cy1D2k*W7E-QWq7HmxhJhM zX|7}eycet1&P`r`xF_A7Duz|$ijL+AH0G>3VlDujh9Ksw2Vzb^+5^&oAfo{sq{oAt z3TOq)11tw<-4Ig>@*OxLZUb2kvKHh8D5C*n9rT=rutp4OY#|;c*T)Pl4zN5u7;2$d zZDZiXz^tfTqdHL4z8gOR$+l#<{zU=#88Zsgia& zAVscHp;%_&|0FZxeDO@OD$cimuvz1Rc` z|H<({C^H%`9xxR!53n3i3fKmy1vCJ}@o5*w3G6D4({iw@I6kK!Esj|@OvhIEHai2+ z;#lqR079II^MMc>o(EDKEG>x`=S_8KNXEEWM^58njR&MkTW%Y9ciaoOh@2ZY8XqG# zel%_;FT_WL`8C;cGXTAZg+@o#mUV_`$_=)LKg?2gUDCE@icRtfWn+P9CR^eosOuWi z67PpUBR|KFqBsq4OGpc-)3~!>b2z7nj{dP`w~$oGfW@m}5Pj=Wz+;V0o6wH!UT%g1 z1!Kcyk%FW}(2A=`hhX7vO7_R~x_!ynn4(QvQ_ka0bl;|&!`PtPo|-LTYAqi1luD9I zsgl9(aA26XhHQ?geVLKQf2C?oHpHniOVVc6Dgh)ge!HQPD;mkD0!6q zu1HM|#qGM!Cx3*ok)%$|qoPdYi>dEn14*1V8-Gl8PAkE)h~gy!uF~1R97TzZn;wZ9 z$+GF$_#JX`x*Wen?oJQFYMuQI9^+b_WL5!%v&rIDPC6ICu5t@-56%lEKY1sY>JsOa zP*jzMoX(p>RcnYxehh?DS@}U!tA@Ohzm96rkly?ZyDO0CETBP`JvW`g^GNmljd&yp zUf}B+uDmRumRrKqmUmJTxC>e-Hw*TSTA@^VLkK5%3tVtIS+U?ICM0{|Y@9$2EL1pi zy{ClLl?sEbvVAF*_wX6II}5j9e2c6ou!yaBLo-1Xr!-@!vl<<>D4znyIe+mo>_)CF zK7%vJ&Ly*93o$Q=6laWbsSkccGM6SoX#eigyA(dEd!z6KHE3ryQoz|evagORlKT1x z>Vbw7z3wN9s@G>>LHFeKc#KQPs1^QrF`2ePfqluU6^n2Xxw|3=Um^ByY{vrG^~NH2 zIvP_q*57qajzUwoOAy;b75&-8=A zX;?_JQ-C<9CL@}acFw~RZY7bgp2O5=%Id)7EYiUdte5u@)J-)S2>F-wEs7cqsagFi z#Fu4nyG!w_g3gi&~UQmWWtXg5Jf;yoaXq#}WMgqq?=d~YDH#KDM+6&a5 z8uDgI3%)?cls+C&)$cWbF^G=r-&YXrz|xJ5&s`qas~pl$INj_45!ekfyDXKGUL~KE zCBdCgN7=iBpB8Yt|Ik1FD%r5k$0f-)j74&3rxr=Lu@HmD>gSQBb@I^fx?2u9>2Z`} z*zavGGTo5r@Ktb1jb(MVEVYkj{MfR4HV|R85Xt(8Kx~$=ArPrk+ z`F`IHNpW;9nYw;2UQckjoO0+Uf#tC{gv>5a^|}S+iXjzNVaBttF!iuEVkFjnk>lka zp3E_twX3H%k7MHEj%~!94042uAc!ar9c&UXV+}rdi$B$uX;{TX`~g{2A%`VjT@fsM z=@`W=AZIFG#+!-%hIB<2)F=A^F0HsKDB8#mI*t%T~o6CB^x(PFCGgz zsQ{WC&_r>+9>K$K8^v`U!3@Poj)JdgbbxqmSQ8D6u^5N5O14n%#CkS~M>C46J3?{$ zjW#R_`J)wXYQyF17fB(_!$7wKq6CWj&G?()X&Gqf{v_$8ZvI0{%@is|Fg&o8UhSrM zLgsJG#QSx+jSunQ)LxJJxoRq-r2{F%?cV1aIk;&p6@87wY+gV)T_YcFo`jE(N1M$- zJI(2;kuaz=o^x~O7gF5&X4d*H?Tkf={GgTdS5o3ctMmnzHKNjA^fT~$g)FU<<4m#z zo@0rwQci`L$q$tbA$V`GEI}>}|Dj zJmx+&-%*bl|G?nE4ujDBeR6weFnBS$8ejM2<|MXV-RX(BrJ$2M{=PxfDA2{#T&8d> zao+ti-lXf?-E9+du*bqL?~$e3q#@46Ou?O4nHXn5@S7`#cm-M`#xQi_YhOuKRSOXp zU_zWj4`IHngl)C{%WC|qE_3f0EOQ6mLOl2T<9+0X{b7ke8xeQSnCxABaCed|OJ82@ zQ+qJPQ+p6`zZi$IaqJ@lHC%ebdXQ!ir#&jbv=VC)BLtYZTod_p|4zqMM_ej!h5dM! zHHe!_vJZ^LsifjSBpyeO9`JT&j9+Z1c_6j(H&%3Kq^xBfFHum|W%BUA9A60CxjWsm zj7uGKiUeBW;hEBj@QDr@$Ld>1dffU!JgK+aZ12ZXW+!o}U)QaHAWjtg!Mz6J!a_uQDbYjc(Cg$$<0jK z>xQ^?HWjAYHp11;=T0o%YT?7cJV%LLy>D?tH&y4P?~6V#V-FF>t6=zlgWdhA^GQPZQxveHwJX{k~XT`va27Czr14p^+d?`@`~)cV#J98PU6wC0OD z`k#EI)_jNy@1|JSiLS-zQRNQmlU|~QMr!F?v9LmGVTkhv6^DtApy6oM$gygO6^J)K z4)9erL6)v~_B8 zx_eeZ6*N>)V3EKuqmeBhNe?il^;IPC;33yq_zIr9$h$t{&o2Tfl^0mHmN@FXaSaL8 zDd3r@%W@p@6QZwxrWNFKol3R`-ma5wT`-(T|cZO4`42!zZjMheK{~l_GMnka`bNVOUGv zIy4_V@9je?iU;eF6empeMU0J{Zls~B-x_V?wr~bL1Cj=L5~Ll-W{?9w9tG(R@{mz% zrHwoU()I9HpxC0Fy)+!s1vpX<6ngoejJ^Ezo?br2Y~d&N_vtl#ICL6u0}f+_q!5v- zhv(orGOB4z@+LEqKj9||HT5W5`Xl^#CrLKSo(vy9^u8?;^p5FW{A#O4oZtZ(18#!f z&@-%{Kh$Z-GG4}P7yl~JHBBECZ^o7IcR*DaA8S@}DA}eBCI$GmCp;2F+49&;((?Gs z+EUM6^5!(UFiI z1$Y4vN46gu6FPr9Fo16W(*UagI0ZC7CIZp{jR3e=JGLnCTpFS;0@?sq0XG2u0%T_W z6}N%w0CWPL0J;HY04DqN3R!46q9e#ved_d8ka`;c_lJM^tpV<7nPrf!0Bizmd5#yq ze-7{a0N(&E0&W2Q1-MNXA9pYQ2F`yM0WyFcz!C7Y8fQqm0z3h}&+%6w{SY9wKn^kp z@ZT+n04@^H0XqM03)0aPIuw-dg3?34(~36%*9q@W0Nu~=iNL1-(gB%(Y``?YbimWR zc!KVw<|Wwiufy2Z;@!v0hCvlUx?5ELrIY=2zs|G4U-dU;*WZ|Pe`7lT#(17EIeJ1r zd;xMm5RspZcP)U_V!$#$#S)lSAm7%lIB749sDjYuBfu`eXMnwcgMh<;T>sftY^9*_}bR5-r6TEMc)=Y_as2#LOW2+_3)`D1yYD^On5>=iwgR>~nLZ{|AI1 B=h^@O delta 8188 zcmaJ`30M?I_OI%>noB`IZt0l;9YAytL5v!%*c<~QQ4=+~4j#!EMKQ*BY?2v4%n(gP zOIH$1B#G{-Q2_^xpd)xiO-uqFSPtjA_n;)n!by!0f&)z%oRjS{9ip0!vTJ+pWWdQ`MPd~ z#oThIQd4jr73x@;d(Q!-Nf8s`iV{uXIa7-%)3b}-&IoHSxNn)bL)d|47RQ-%>_qF_@LW&f`XN#WTx+ntFl(qCz|9M5E&Hk zG=7K73CcgR9u;rz=}NU@Z^4Wiu^FLAs{3o32GOh7U8;P`ChQfB#AiS zoduphITer;y~*7m81>()RF{x;hj2hI^40DgLLKt8i~Key9Y7+#i9`mP{nk5ohp!P5 zj5$c&sYjT5o74t=7#f5 zi_8V!9Rt(@wgYndWYeK6*&7X%T5)0p#idg31t-U(@=M6#p#ID@M@>hiAXg&Yws!Rj z%%#fcxR2Wl{uE!=MnDad_k)HeJ}s{5kgbqGBaSoQA6t831-g?dtG3n%`xA;gaKvkf3BK=9b44h_)D+HDHv?s{_!Tv6}S}h_WUC92JofK5Lz^? z1GUWXgGhmJ8uG?zwg+d-=0DA~z1}e2UuCW>xPRsqfA(X`s~sU4X9v;?Prl z9w(lHU)hQ*X<0Fq;Lo-8&nPMQSGsaUyIc)HL3k^}zg;V}QUhZHE?0Z#+HhQI+a;la z*&>|L;}MdD2BsX!f<1wi0?AC_P{z%+G%dr*)oFr0)r`5x0-PVzt91G?rPDo1H#?-c zzUoH0AKNXD)G#;tF|D(YX`KZvN#jS*IQfJI^O(jL4>g9t=)M3I)FK7Xlt#T)&X)b* zXDu}i%%3!0%caRC6_w5}Gd*hxF-|nCFU82VXhm49&gkW+2F&17DTHuUvfz zA}-B+;znA@N=l#Iw0r&i^o^yavO0g0oUJ~vPf+SFnCya*@ypP)OSDj_xCm7Ly)yKo ztWIyAuH-N2HKkxq1e|yr%B4^)H9eeYnW^`R5cyfoUfa@8 zB*&CADp|yM=6U9q))6|qAAXkvg-4I6lHxZ6daWrSuP2s6S@O+kr}Wz<>e&7{G?JQSbb4w#h42v%fqiyQdp0OlE|A8dDPT}& zZzvNkkz8gj7Dz1<7<;$5#E!TIG0vo9tE5W`2EAEmhnUlbGC4}N2Fh_JUk#Y}jS0t7 ziI;kuH2YljV9b*x>fx$#XT&wkb(4Rnhxi2-%S_d9Np^Six~_y=RTErAmTE?OBnlUW zyyq}v5sjLacs&`ejT`q9@VXN2gr14}_6h^{c~_yxTY)z=`HxWBgH`7C3lewiiz2TO zq-7cgH$37(dX_AgY}H1_NnWX5B#n7;^13ETrnZ}g%|6zFbhT|gqfpy#32B&{N3O#i zFp-E_vzN153TaWvm>WeZqQaEd6A|r*BYUC_;T>d7v;n_qtBtO}9!Xv08O}D$C6M$X zfmlbLA2MXtEqA{hhE;JtyBRH|@y=l)RNPn*aTB^St(lx$mT5s;wp6}vnUiVpg=2Mj z5ad2zB6=jykwE7{l#9R36}(l4D>3&kmjdQAyeo#a043zdAvyiKoN4tjY#Mu3@STXb zmq?OsS#)zB?~5K@w3BXnOF(saf;uqsj1-i-L7>z>e zkRkao@u5-O1ss~R^8uQ7O7KmQk|ax!j#YBO-DGpjdfZObu_3Bg57YHDtWkPwWYR=X z^ z5_`iODJoc|UJapC5XTtej602M7?BSEt}k#Y?s?};qXjr#J#tv1W)lq*m*J%H1cKjz;I1A)8yE{W=rjmox@io}C6S_`fm3IQ(X)4e+|fq{w}Qd`PZ+d z#mU>K#EIZB%smaBEXjJ3mqN!Wq>7~fOf~?kS$9&_idDG4R;PlCH^YN}1-}KIrv!DObs&w-wyHJxyUI8a2!p%tB zyr;YM0IE!6ebqXa+Jm{xykd_Jt+UGu^z6Ytby@)u6BgDY4TB8)q zDhDE_22clB0Rw9V+6J%yt^qgz3POx8;0)lLM1v7?QsM<5CK$j4K&1`90M^5c&})Uo+dEI8m!`CM6C7C*PA|F+AFK# zl3luISUI=Y-J=dynakvz+rWHRq~iPpy{Y$B*MY=e+&m<#YhZw_kuXT0Qt}$rH?b75 zZ)_PpOA^Kf`McZ+c?kx2r#I3X^;+!`k-tY?7#D%Zk(J{j%opA2Y&o~QD>RqMiG;zO zb4MDO+%jR?#86{ow*6L0n#g~6RPyfQo`2}||K{;Euqu+rCC>-L7Lz>w(EDw$N86xn zN-m-~;O7N@g=lGa&IE?EBGZ6Ms}e=xpAMs5Ehf27r}&f<`@ zF>A%(ddeU(Qie6OG348+t~Q(JgjXrtO3V|Z@kraw zi8&b41S$T@3BPbyQw!i0WW;6v z7nZ5BrOzs(sNiDqdC^2Fte6DPPR37>g4xm3#A5Q=?6p){G3lP2>#+iq76PW)3g_fV zeOAv~hli0NFGfU6)?W}%>kq=@*7f7lxN{acmj{>04q=V{iZGcJz37ielVvY{k2jFQ zmu6xOseMW7_iOh_;q^*whobV@Vyy1sS=)`5Hezfc%jS#HXkL3cPa-E@9!q5x+o%Pz zDQqC~ikIL4ul*|7K~V;ymxAYwKS}|Ew)(Tn1m^FV44~9%yikCliNP(>KBBH%ny3yyc&j4Nq?`$-b zZV86mZ6}#oo<;4tNd8`)fji0V@(lwX8o1u~kiT`2yuCKuzn?RfMQVAc1<5!XGWQfa zO`6uKW4>^-9`Lo}M4!0d+Mi+^lF}szN{!`pDwf(uGlSUjTS`c|>WJ*E_^8e<1*?Pn zp5nfPdsR`#*)ih+ozAVjcO%7Jbd$+%?S&(Ot!nBwfkatTAlsj5%?h=ET`AAP2F!$% zlw=(WLyW9vUgW4XIK=k|&3e>R9DPJO+$oK?lR-YvQ8W478Z+RufSI0*gcl>JUZvQI z39yk?R;b~~S62*CXpT_a2y(jOc{ufvZ|7*MpugP!ikl0joxImkgdpEfx7PWv@?DDE z6gQEqdwZJs8pzxM(5z<@jK3Mj;&zJrxfwGQ_Xm7OEotgRihd)$E=OT}v#;HbQ3C=Z4c?z2KkwlGCe}=% zl7)^tD)}V`#cv?<*5yNVv8}s{2gGy-*UvFgkP;xRbkVndOAfqKN?rbzB)|J2)$lF( z@ZE{{Ao=}Wck}{xj$s5WYE8%-hjJMq@5kTeBN?O+Gv##IF}5sjFjRG z{Kk^Sm1;P38{wBGwn{a{cad)^8S0lVB2-RRSpJFVa8kH&415@UXJb%OTCt1YD#%CK zS^F)n?5o=-`K#Mhg@%n`l?JJ;Lf|@jbU?4??gbi8u526?@PVsm%M5eZ0_?wnx0yKAvyO zwMV>zeLQ6g_lUQ*kJoh+U4Gcd$9=qeM}2{Zv>`;bkrIkbT=j z!b;q=VNbEwP5Ngr_p)VGw{PL)Y2ugEju-8nTA($HjGMUf( zt3#4VvW=^`KtY1-_sLZpZR`BRp-g_W3qDJADRPwAh&$g!X|*Ng@G(XO8L?4~m{(ym zQVv5mzH(4*sCo%;16+u^>>|vkmAHb`e_D;Lw*0-PvEqgkabJ><{gHSj8NEL){Zpua z;>--IKJZC~ilr~S8ouLzF2r&Gar>Qv*>UXe9n>)Sm7eD}gSfoI(zh$ACn-aKjmwpj zo%^@@jBoa@z!hH4_^*a%Fe$7Zh5boIZ31NFhik)ves%15yXKDEBhp#n$Q@tG`kbf0 z)^>8Yb{1J!H`MfvL&oZxXn2W<{8=a?-EVEdtOj-`;)2{V_7)rh={01kSB;F~R0>)X z1D}UP-sX_Q3r-46h?Bu930^@xa>jbh(i%zPV~6y{>$P;RYg2tdAZ{+nQZ*tC-tEic zO(H)A=D(H1)JK>r9aNpKy*ItUj2EO73&FFM;Ms!vHRf77Le z*6p1+OEa`_jeZWGCxF%!S9V}B^hzg|)^X_29iQ5rq ze2TpWI;6pHttiWdF^y;q&bR~Fj=hHLKJXd52a9a}5qm)f=~0^85Ne8TqB<=Z)C2j5 zXI~BlkL@BGZCbpGG};P$j{Jz|A3(MT#IM1isDs)yQq(X6*O7__t-n;~8iUxk>S&D* zI|!Zt*GNl4NZ3}FzUNb;35Htj!dj%Z2+?}!@l-|rXo$uSNJ!%t$i1gDYI7jD2mZ@0 zCH(ut2=;csdTj%|cM^hk?xY2>%t>>k*09 zoYH`lY8{ks!VMxV$M$X-9@j&=5!X-X<_EaCd2e?&|FT=;C-e>f6?+>@8gZV7uvS)r z$hf9i_z?M^X^iTa8>t`grQ~W;n5wR)yoBK95L`pTnx};=b>qqy7FXTp7rONv%2c+) zy$V6)0Y8##04Z;>yEzk&B6piBy(k%$E0ikQ10nMIVZFldDMSa_>JMvi#OO3cj{{s! zM|4OAqGO;O4@dwckE#Y($>|oCSOZ zXa`&Zx=ssKP+Z~q=p@d5Y&0(%>J z^uB`fO@K705TFr&{~S~_@L~YhLFRuAN)0kUg3L|8!$Fnjjs;Hv<1V1{v4+tgJPwc! z7!Sw+CXMnedGQgn)oH~D!^ktXi0ct$K@aI9oN72;IiW`A3vCLARq(~LEbo#8dwCS zd4TzVibb$1fiAPPpYW2$kA*}a9WWk{3z!Ia4ln~S8(;z~2D~a!;&J9Qyl2|aY|lx_ z5Y4!6exiu6DE3y|4E!rK_TN*-alK{Zje+n__TInlSd7lg5z@oUw#L?Yc9#7A0c}}= Am;e9( diff --git a/Tools/IO_Firmware/iofirmware_f103_highpolh.bin b/Tools/IO_Firmware/iofirmware_f103_highpolh.bin index 463495e2d5c242eb8c48ffc9af3014d5730576a5..af9d068cd5ea5783a1c53df815f555281ed96437 100755 GIT binary patch delta 8448 zcma)>3s_X;y2rn7%?vIS6vPWxUBifgK+LGrsJXexLKqcEGZoFj3l5ltscpO1jDU$3 z3j1=0X?x?Xt)&JcZ764>X&q_jvmxbdt!&3GBJ@~`#Ad>zv^FoF zmu>!0`6#(r5MzlFb1W6B*W~y7>#OTB>rEpq^9xv|-&Fd0*5WsQ zeMmUrztN(*A@jkbI>PUOtQUUGc-R%2YCwMTZ+seI`wRFpxQ#Ls2YlVomArdduD>?) zMNegWxqP0IsDsVgEmTUReDvY#SwDMT(1o$X{;})AJukGYwy2~;6^*fWO@H^|7IHgP zb)d9TK5claorWzXbx>TJ-Lx96C)m3~+nVyTp0_N$c3 zg~bJ*olzoDiAc;tzR!nLBJ@d}2N@kX-fGIYBwsenHhUbh%P%~`v@}=gm>e(by;zi3 zBLCA6i9CTZPNIwT@hNh zS}2jfGVtw1rA;zFxl-OGoR_Z|NPApnap_33u2la>!G~7)zx0mpvbvtzSX5f${OPVL z#@L|JRmv~H`Lf~GcWFNjTUAv0MvArT`04Qjo%+QS73l;`yQKg8zVwRIV+Ybh)>ouc z-46)OB|@UCUAs@G{wxL@?knZW>D5|6^f*@cp8HM-b7Z25L-hV~I?Y0*Jf~(&^>;<3 z6b-NlmF*r!K4PLa1?O&NTLXfu&%fIr0c+PY?`CyfemX!rY%6RJ3h!x`Yt!fbr(CC} zQ$ALn=-BfrTg=QR60USHXGq_o7Uz1>QX|QbxJRDV0H z{6YQ?J)NvH;H>ZxblKi-y?mebGORZ3zq4ymol^Z%ZW49A*>+zIfBdC}oIl8o_Z8Nt zKiPi207r7Ub7M_R++3wnt}7&>R@+@dOV zIM(tRzPC9_8IhXUf-w<>KxM7OLaMWjoYS{%LXW~Lr#h8q6JFmp!%KR`IZ4!GlzK^4 zc4AB`hlO*`*a?a_GjN`s8Sp^8`(yn4cW?<>>w zykT7Dlr?L?~d#8|vUWcw;On1kpE4y9+<*pQicQMM>#0)2)(A2OcK zW(PuIyvKB3lle!e6wCe|vW}Bo?BURHTtxv}7CL?Gbfn3KyTLX0p0i%ODu|b4IoIQ8 zWv4>ply-a>I-QoXv0+xqvDd@GG}EvjZ)Wvj_4Ea{ah!=Rs%aRvlM0*BuL+uc!OoQa^qRzs3pK7*5t?qj*f;d2x|mOh`2EIVSfX@a{gw+{Al z*pK(wS0HbwDJq;`#k0)tlJ>j%%lW8dLijPcLeO*`B%H*%BUTWBm&&RmM#p!# z+E%^>yBYStYNdrlGWSHRGTJMT5x(*z93UZ+-XgpN8OZKM?4Z?b>%^eZx6Wa~N>^g6_n98n9(#`1TseIAx81C}Ta64AG@?P}GP>UbmJ@4gq{Ol(6-gB}f z&lH^UnAZ`+Q=ee4fJF7Sgejp?D<$7H@v5& zGS*0a*SgfV)713%(NZF9Wo>cs<1<{>I)-KwUHE!>e18hxurK9O$57p<1{y&kh_r}J zc_7k%qDwEXB++4BQdl=VPNeB<-2-v-D%<~nE+pOkUAwZxopSrtTntxtPNj;+Ehmva zWdC>|VRVO6RV87%De;I91ud~?q%x+BUlq{k8Xx6#BU&`C7sBn|8H_BKE$?jX&!dsn zpm#W_z}=VIh+Br!;*)t+_&ir5jqKK2`nNm9Wr^F-{v{e!=T8KsaY~QR!aFMOT*?}! z6w?`O?$ktzJJ(dL^^!ZxG%mAPJ~%(v95!1SRvyRczYfN1FkXYPQsShI1*VRNk9Ha7{){`X_WV;**Y)N8_|8<1s`B5(?Qj^N8Ttj8HFEPhAzYZ-N zuo#&;F_JE05lIhGnJrI>S8F7nI#!-E3JQ^HjweZ!Ce`duIl$2^H3?}dj$W>rmhPeS zFKk-I>vSD!&R9-=VDXv7^khvuB>04x2sdB5!QitFZ;VRW7@ z{)6R&*E~-6Xpjwx!ET_Dthmx8N&9RzIca{hSS7zi+&Jtmn5U(GW1Hti(7Kuf^Bk0R z)v);vY8c+&cdjs9IV5banq{(ySFzP|?|vai5npuN7%>O4VT*Zj{bVs(oN4+(j%6P_ zVxYI#oktRBEQ?!U4KicQ`C(pfg0ul%q#0DIc)zsfqXqF)IXC^ha3Za(341g_#g!JY zg^Le!O$9ab;*-?p`+=jRP=C9CRV{s7IYRm6tfc4J#+)qr9lMzG!H9~1sr|2ZWwt%R z%9f4A_&ByKlIF52%i^h%xtG1-Kj_suunu2hZ!QlDDCwRg60N$^MpV*^-OA$oExWQ@ z8}Mb%`7?fYI>k5Uhvw-*H}V)6eS9=_*s+htP0+bDVpP3=`R;>Lfd*R!6`b(7@?`(Q zjdMURvpjy1o?xR_S=%vtbl#T9GtGIoe*u%`p&zQE9cZ$75jP1QC9Y z7rm=FDHu^#HX_<7Akv)lDN8j+j#5csG8K5Ny5BoITQpEFxv>y8$C9EKiF`oPoUNOV%nRNM+(N?LHY0clV5c?j@$ z+mj`|klo|R>+W$(Vor02=IL{sRK!AZAEQ-lV{S&sCcKRmaMG4@7#zu^RlcJ7xaI^W z<*|R{F0s}j?IPgCq4k_}>wP+jHgi(X`&8g0?+*wmto6Z(V^TejSJOBj5cOiA-A@dv zSI*>|^xpfNbhZbVn5dtcaD9o@if^YxHB5r<2<&&9^j|&SwGWm-CZ0}Ff97)Rkt-K) z56bPghp1azoMStyUOAUutMROKQ(D2?tBcX{ZEM!jJ*;ER67RRZ^BUm=wJ-Xq9A4PhpYb{a=^(s7{)*A-W z_mEXl0)zY=>9-fQXSc{gXv1xctWjU60%DLmRWgHfqc1r?wCN?hrnc$sH zzs$>ND$&p4(|o0aS_lirr1UYJFJPzhgM-c&;BYTX?epIzeAfxWE91@usi|qr523h~ zxC`#mv#fL74m_WIV!`OMaO7)MvptS$9{cw^Hm7+Fmssl)0W+`tl5&0^WqQN6zu4Xz zu<0ARezBb#uuW`GGsF4-oJiBwx6=tVaZe^{Mz$0Yo@7UG#7L8rD@t1tdvW8-)L7%Y zDMzKbw;dlqYu5jMEtin*Jdz(X>qzbq>2ZAG(qwqeCem3ahc6`CmBUGu z-o7{h8~!_lS2lmX_UZT3ri!&h^6Meeb#|a+Fa29h-1g_WKuxB;_G0>yBQJ)B}#=Z+BTFsB+<2xZwKQo2i7 zvii@f=4vYP;RNTJ9^B&stNZgj=!$}eMs&8%PW3oGXdr~I_BfV&P?$cX7GH%<_=)sY zkAvX^{Cqb(5I9R!wOm#^18UU=uXK>90pd`R;!^^VHg$7Ves<2JvYI&)6^3COU5(e> zgV)XKs!Ya(4%fpE>x{KO-u2&Z|KP{FnvzR*d9_}5saiRz;Y*ii7B$fc!Kt^JR;{{C zRfov|GBPmr)@vJ+Z>wk{X(GwD9@(IT(rE9`Ve+IQN8B$t-tNm`O}(}6S6NE>vUnU* z|6dg-w-@Dm0%!UnUxl|;P6JAR8EZX`Lmr|Vk?A+*JfCzcxvJMyI@Lahoa&@Q zPHtrAZH-S(WOC?jwNL78Li}$JrzxF;OAf@7czY+`B85i#u>+TczdIIu!%B7<=?Z4w zIX0*if#OkqmPeKOSqGVXJ}~7rrM$hA-PxHq`Zc7gOd(rBsxyCnJDf8GBebuvJP!YX`F)I~?McJOlHGg$ObJ_2Hk!>Y8^hiD zD>Ii(;;t!T6sv^gul?$$Wn<`Z_D$Iux|wCXyxBVauLM(X>IfouY57`S>~*~E^3o0w zdL0ashkOOn8*(?~P{psPc5h=EgvYD^MMVikg22tei517ZX30L6$>xNS1-M$xfJDSg> zGYKCCnn42C4t#${cr9c!Fn|kSGu!s+c1B&c;}0!ki4!z@TeK%KzxTS!fQ32L1zRAP0Tp zpict^&^-_TAOrNi^v%$>f?SXf%D`SQkl#v9;78lD2rlF)@Fq9}j)B2Srp-oIgVE_I z4CI2nAQ{AgL!blPK%V9SE}%oMfM(DFZh)Jh6|{j4a7VPFhoHCtMFAS%4Saz=XhdN* zK`Xd2KntW&$zbC;p}WC7&<%cTZ0^s-%YkhR@uEQSE8}6<2bQpD`({|Lz}yVnkD{L! z{dQ3^k(R8aga50_D@bn!X^Szq!EZHfAJXhwB#a4NY92eti)J? zd=}gTt>6wg1ixe86sQI_VLKLzxd^=;*ue#GVlBzy4#FMDJ&%@N|{1!kgcHmN%myLE^Euv zh}H%)1TH&48Q2TI%E4&bP2a9)tIO$f(E3>0t-3?_s@_eRN2gUuLRRQ#WVKUjhVW-eqW=6$yE8~7^=4?Fe7pQ5+z!O{#)fPLT)CPyq-!wd){u;f*&?giACk)$J+`$mdaePe)teJZ-mHTgD Cz6*8$ delta 8458 zcmaKx3s@9amdEd{?uJ4^K}30Kb+@fNL>m#sD3M1jY+6L3nfQpN5g%oQ*m*c&GHxSa zghUg})g2to1~V~HM-#ARMvNVtL}nxtcfrTEI>s5DiK0o&S42%0bT_^K;*m-A+brMr z>vQVdb8g*x>b|O|b#b*WE~A_hp(vX0g(Be(&LMonfV>X981^5dfBC1^+jeEdJQ4O5 z;WNNGum}7RxPC?W4sZ)}gODwR*Ml@r6Z_Lj)EnGGj4C&l_sg1H$0mfV+lGK@!f%0m zV%JSaP*F1BZ{`p_%ejt@4blZEynLSR9Fm*d>F4FcO2oW~{G-{Lzb;a=G1a-kV=_x3nl)S}HA*0_B=!(y}0c2rM>a{(^YL?>74dk;;zl07Jn8QW!4=$Z-m^ zh0*hqic+O0%i>Z_di>c}v!gl+9+WS5S9zB#FHMr-#br`mZe-&gWxkn9BJFlps&u7< zoeGhnuasz{nDuqJAvc*y<h$tG}1+-)?AmnTlsxh zb7OPfDeDNSy@b_( zT7eTRAMkksy6TtD3d8imv;O+dTICES@%uaUWmKN6;gjC!DEQw0D`On4D0@9@V(L`? zOP!iB4GL+J<3aj|pO%rYb2R&^>y-~uN;_%XQbHcSZa>>uS^d|*dZaP4>m)Oc80%PK zIjfvYnQQaAhxkGbPg<82sYzZI;CLv0NR3s>-&3*>Q?INvXY|Q8%`-altXr!;sg9BA zmDfY-m0ICS$%W%;-s+LJ#7=6gfWIVEDSt~bA|^74d{E!Go7xsHk>&zPqnUN^jAi&R5`jF6E!M=X^J`xT5+u*^UPX zK8PK7#MesdatS(j*6g_WBZpldj2v)?DXq(;#&6M-vxLMu9#nmh^Sv1UPG2>D`e2n_ z5dH4uy-m0KGtQy04Ij*rsJy|WTYcoV-~F^V)S$IS7cJ=|EoD3r4r5Iqgl3Xpn(2Ia z&f)le%ZGg#aU?n(lzmw6;N0`!;ydNfcSad{I*CDPnw75=FDoa_G_@7KnzCH=(NZoY zTs|{A+g|WhR=|`Ft)9vnWqWpbhfyu%MkS8CvM(sUohHq0zpR`P_9*Afbc$NT31J&_ z#g!roB9ZUNdY`}>NI#9!|y?+fdX zYW-1E+mE8!5T!=^HzLmdB;x3gB0f_irVh03GlcZ7I`$^BQ7cy7533$#s*onlU%1XF zXKEG}RjjL&9+#q|CDJl>ZDdqnF%~7i`yb3Ra;L-GR3TM1giBg+-|=Hgfcc{2QUZjq z?D!5<76#}pL7J}xL|@W0m|aT)+?UOU3fy6PP)>xtsrypf^9)beW^>T;(@ z6DSXC^IUPUjlmgtDYwo`T&kx%)PqyVu_y(t>CTj{`3(N1z?PE!Rv zNeVTfir(m0Y;iF$8Qfyj5HpVMW{#M#bPanuCMihhzNGMvQ#p@aj9Jf(^0Ca=Fi_@iHM}CgE z;+pBdvrS{H)b9LrObr!=d$wiwv{QMgN3f;42q8_pwWcAaET@?sA@Yb`Rw9gl`WL;! zEP|+$AMX{6oFUjE#OdTCej;D+=2Yj%T1`$lkv~`U2j#^%<)Ik#A0ORx+t_hdFEh?!!W61srMOPEE!(e&tm?Xy1H z=pMd#yFwc1)Gv>p$i8uL=#4RRb+W+zsn3eo=hK%3=Y?4Lxg;UDB}|M$Yb)6dgHfm6 z{R%5GB-48KhG8_)`@Uf(&1Y#w<23#N;fIRmrXl&;8rDhLxOgcji5}5>Qr$v?gqpDO zw_CJF_C-AA|@-|TPt_Nz6$opMzw`Rw)L2b(_Q-y62ATwN@5{ry+`_wKHbE!CR|3IM#o#} zZB`t=kE<(rGhsZfW)l)jbR)}8cpIhn5-h{d_RzV!>nMgu1K7*vB&|75{YqOn}e*Hy>#ZnpYtEQ*jJrK6kJ0%yCkiDu(LgMeYcdk26o=AL(7@N}5j3 zvxiA3^fNYLqLDse)`>>$+is_QVmb|3@6~=iM@tXATTSGxtSNc&*nID$yF&_z(NIbc z?ak&}_GF*EJH$A$g_?+o$V-`K(uA-?uUTA465;}6pF$52`B64=QZoH-wr-L!#_GG> zsjiL3e4)-y4ce}$RQ34QL*zfP_a~)A-1BG}WXw)AA0|=I6G*p!Y%&o zs=p2F>k+dFpP4IOXgZW*gQku7~zLSpkmn<{Lvd0O!kTTEW8l`D$P)7Y|$RJ{Uvj_niZ z+{&1|Y)}C{0bDULWEV&0Re&>hha01^rszZoS1*r`pLMWI!1Tnb20iR$k5qPiz zKIhPJ9^1RRwFcs(#m-F`;aG&Tx@zEER}fm>WSVa(NVWAyChG|y+NP7|b?f9+9)p$W zV3)UpQVyJW_Dp3E{6rIyt=CEcNe+s>@QJ8&CTSH11>=)@Mld zME527ruMOl?Mkhrqglk%*|d>8F;(xV_r+Pq_QzCj1uw8?b|N zPz&lo12_ZPftphVc~^6)=5_~irsi}ozv^(>l12Dhln>^)4hzj@*lr+Ri8}-Z0rsXi zaTJoA<6Ks9Ezop%q;-t+VksMumL6g+4cDu0S6Z`9eu+JqHUkUGuC(d2nYH2fI-}E) z9b&UiUI}8Gm8K9ePz)2}#ZlNFqJ3KNmF(RuoR}S(Ag068=@mpA-U!uKXQ#LDu(Y4# z8+CHWNqer}-P58p1zV|Y3=U`J($ON)kHfdR)W1;rTP52rAk+J>(Z@9sL!U)ZYb#^N zrn$H;yIINf@2SL!)AjUIwk>@u{e$yhdLgBePWOz5l;%3`%}mk+#q|`(&lGyyQA|HO zDeMw5_VUQrXH%=jX3r%p57_eA%R=UyL<!i7UN*SY;U(;N+*RmX^ zIJc#e9&)~%7sO2u_gF-adzB{(ze{>NZj+CE*J(~KpT_M`@<_k~`x$66|ddvHN#h&T&3hVOfi^WBun&SeYSH07(0Lr>dt)zikdhR3Ys;zgVpxDT%> z3rGl_*(h-tW=NTBaq|>0LCmmTQx>tx$5T*K)8n)0BKGicN7Pdog`t?~cF11=UZfT( z*PW_z?p!#Tst2%-7mcU)oVOOGX*j-=#V&q_TTtpev-l_tmN13YGpNwKzLb?MU7?=E zt}I*G>im=5SJ#r9m%|%1bFoEvsWImT9_v>*D}8DL zox}D#HJQ3u>r-!J4aVIZShLR{Qr!|VO+nU7W!y|6_b7=X(QCVA5shr??$^tqFYQ(r z@EdH;a(%*;o-@ZoT{JZ$>D!J+gl^O|6%$Qv+SU*#a>saKjJWMi0FDfo*x#2YkBji> z#Q0_bt4FUlUesY5qJjr8x()rC0VjXyW9Ah{={|OS#WK2p&3HN&19I!rPo}D8>x+0Z zjl|GZJBoznVi=?9k*9evs1c_UJScTnqg?_X4kv%ihT0~K6=X9&>Ynyr6KrOfq}i!JhcWbWvaCx}#)LdEIH71Y384*yE1q;pAWYd)!73#k|Ic z1+QAxtE8Z8VV{Q<9t0Haq@dT0V0Y2t{tDqChEl_ z+3_uj@ckOcB2NBW&+X2^I>`7Bvb7hy?rNoeAvaCw{5nv3*~_`Nvdt^=X@m36D}5Aa z-qux>^eD5eUW?;b2W48O6%1FO06^o6XHWDjkA}s+tM%TYPNjc=(NmIBEPR_r@KVg z9l7%ST{7+bU9QG}*&1L~%l0aA=e#2rv4;t-4l4zcIuEalp|py%K69Tou;%sK@tak$ zFrxvEe3NFb-+jsNy2E1wo8NNg2is=@w#Qo9f3TeyuszapgLRaIC&)jP933bb-$H&j zSnE3jw%C?X7J{!+g7abNY~6^EN_-_LG;t)IW~%Q(ag|Jb;dMIIdHIE98eQ@$_}1!7 z+q9O$^nPn|R7|?(!)1R2n{xN&xJcfUE#8p2 zqVTN*J~@wl)v0>;dYqG9y1>!7jBfcmjdR}Ia$QTuv6hMqx{LWL(zvfaVpA(KX&c*E z*_<}Z<9C1N)mZ}O61mpH8IAUB>JbL7HjBfF@FM!99u4@W=YOxY)~zKn*F)qJthj0y zec$=8>Sd1Y*gkP>nnxp=n|Zt}_}!DCllX7jBSiy72$AP_HR2tNPIX<98Uv?}lLK|U zAweWK(nNW*c*#&#B_gL_uT@_-RX3lX)W_&JMNN2i)_oI9_u37RGZ)Z9bT&Rn3JSM zO-GelF9=0l*L-SSL3u$A>!o$ks7(7{Hx3JdmRQ@PEqM~1l85k%KJ_&G(_pnBuD;;m z*5N;CNJw6AUqc>2Ll)W8ru?fRAE*(}6QkN3x4Wy??iy^6R&5d6U6YO@&-t3sQMI__ zagWu0P2PpOWXhSy?5`>1UA4?tGdp5GN;TG)vY5ua?~fQbYc$fepB26uL+e=St493p zdUavk=kOW?iOq|)Y4VoBvmW+#MqitNm*|AojN$6F+%#I;-oP6|aK!Mt%h=PeMa5k8 z_8*BQSgvCuBl>d1WY*&9uZ+EBqOGj?wVBkx9=>MGsPU>^N4){~h^>x2wO{-3@OFb; z`!Idv^pkuOk=J+Q0eb!JK)>G|HZa>hVo&UtLx02e?RcLX*TU>ON3z8`M{&bcHIXW8 z!_ElSuyYjsN1yfuw9nc7ovZ0yw&eAVjujshEzO)doCpDWzKIum-5+@a^npUJ`wx&j zq!Tg-@wL>`#)#?HQ`5;2r7qwj*J zxYPHyF$16D0ezJ4t09{}2J}M6C7=j&frD(@n`57OD-+&gKL?;61c$+~AKBINR$RA% zo8T^Z2)cm}4BlDw8`Q7klz$88fe9pJvHxJvj=|!4FzK=huiicbdKUQKx3|ESulj-i z@Ah+0PC*bDtp6bN5D*3;{$+QN<+vyUtHC-@3Z4TS!C-Jy&cF0I1$Y3U2v`QlfE@H) z4gEQ=4y1rIFar#hAA{Zm_JRWi4)g>{8yIxB2|ey5Bo*=&xD2j>>tN95xw(Yj3G#DM z8Q2Tjz-F)-Tm^cRhb=%B2I$7a(7_%ALO>XZaNs8j!~s1pfn<;dW`GQk1?B(?pr|YY zL;>9ZA&}}#1{;?EJq;v-6!3H7vZE07T*goHBJ>ofj;**p4{BJ(o|z8a6Q~-b{R01I z1V2~RMwD#^+ra;KOWl*G4{TYC0S$hxzVj&SSWMRN`OEM$!OuDFLfIa$cR9KNe$KBI zWo=;N)9?j9@ng&XeYRuHDm<1om}}rX=mr_j;D5F@Bn7mA^PmG<1|cgk`%zv~gs}$w z0AwRbh8_h>;41vCgInM(h=A>2EdHkpy$d`9-Qeb0QovtD@Gdx{L8d@b(1jcL;Lui# z;h|OzD9{1*A45TqAs`Gy02lnCAmfVIGrxZ6@vQY|7icQMKL{ajJ&W*C+z;1Xn{j_s z9|he6n-1l>pi{^o;8Xhsc^I~1pd0?WXW6v6@uM;}VEF**6pDk40x28V^L4K}LS8_& zoY<~;3IG_hlJiGqc4Vzfc-d_}LdJk`ENARHzM1iru1d>1s zm<}EVIRkRA8H0<81&dD+*o6gT8)O1xjd~3%(08)N-@KjByaQti+yv*rRnQ6=!CT-S zC^qA*g>ByVMnctkzk?3k$dAttet-W(P#m7_xPPT$GfUndqkH$aXuUIke-8IQ!@BXv diff --git a/Tools/IO_Firmware/iofirmware_f103_lowpolh.bin b/Tools/IO_Firmware/iofirmware_f103_lowpolh.bin index d362bb53d8ce24209266f7930361847d1d2c36d5..8db3cfaad172de3f9f2d3aab4316d639fd0c58b0 100755 GIT binary patch delta 8448 zcma)>3s_X;y2rn7%?vIS6vPWKplcWr5QrI-8Z|dJSqP&dX{Mq%c)PeLoLSf}v-X~f@HK8n!VbcxLay1{YV%$b zOZXEhg!it=qvO3b{xUDMu(F|Pu|IlvsahUAXY|~Y$*Rv6%4%(CT6a5@qPs`V8Tl*Q z5a}O`4vVIjSnMz(@8|AqA0pjzvfN>pxS#AS#%B}FVuyUzjw-e;%?pzXxurS5)}_{L zYe5=mU@^Y)=8uv+4wFX^skF1(D=f2%WJQWzlD71}IR0Hyxf8)~#+h4$+!EKb8FyQNkuH@aza{P56 zFM2B5%jNTwL>_F`ZJ|;E<)aQ?&-~f*fQjCO^GYSS9Zf=p-V&Qb@y&%DILT`KB(gy{Uuh&v(q#2lTb+Rl|sOsxLz8 zRtqKaS4O_QsI*DuCs)e5g!A$>BWaJ#C@vj|)|DC_$^XzM|Chn>U1ryF8;eS7oIl-F zMVlH_`bzmFIA1p2`Y!dSVXKNt-$=G~9X~yOpi{qiq9To;X_pM2-<);J0!-WOyL18`Za&6kY|CH+t zbjrud6CHbARTw?9iG(R#%o)?RsKvP?x!|4ZD3M5Ap1NdhvtH?CZp@@H*AI9nHqmHf zv(m7@UK068Q=wj8AlubCB7NoAk=)S~B?=<3N!O9_o2Ep)AgXnVvLS&;fA?T!kpGm= z3V)FQ!$2o14LB>j1YNfGTQA>dy$oxi?%&yUs7|T=DL08c-&}ZK4S)QlhU`DcjrSGS zXgJw^zvHf79RDDHa-ZKPhKhF5FyD&^1+@mfS}eZnUphRz$Qml4M&MXtzl9kH`H?2dew5|e=UY>?F+01z0!uKx(c7!X7x7@w`{YfV$u4< zauuPYlP}`Q=F5MBT8w9rb+DNphuKN`vfA4P@d#E{u1ZM*S3GkkAzlrkbUu?1toje*KqiG@^e9XY3O-Gm;AS59#%&nCRSZ@QQCjB}D`z$o>S zZ0y9CRt^j2p0N`Yac1ls?t0#4 zXR`y^XzwxI*JSK&dgh#F~Xub}6`eA0zbjkL!@q&inhX^Ny) zr4$nBjG}iHu1YENvy+AspTCSt8f6dPr~`9w-!sk+VK69#Ob^x53qeEklYRMDy5o;jQR_0?ftkDINLIQCCn z65YylVF7dvix1Oll={A8%fn)WirkqJS#azgS@V(XXHrf8g*lO;T6%^Z2`i&<%&6CM zK8M&Y{WEkFqZ7Va-y&;7p<0In!%_DPbF}4{r9`08C$Rd#%1J7@%~A-im_&b3R{hda`_BSGP#fC9EZXJ3K5A?C<1f)&p?!%N!l?l0$~jtODM1FMx563NmNzRF~;JVyA+mvDfDOni&*5@aB|7ruj5v#k?@M&CMz1uIRp zWmvSjiJLNC))Ojy%ifvzd-_MFkC;n0vJDX})Q6=-n(4n7i#(u=UPIJGTEZTS3a1;` z)~G)rjG>d#M||5uXY=-x=<_O&$2L#WJ;e12qMzMVs}@Hiyp27A$o~?cLFxMv0*B^GD$z9qo?vkw_~`=H{I=6;mUo{CtWRmeD}PU+wrrT)O*j# zlsr>#%42TFnBMbeNcj}ePZue2Z&T?si;liP+t{7xhiD@Uk1^7Z*<&$!DzWEd^xW{C zn#vdx^y-%eH2<3~%0w3W5R#*I&RUF#T{Mf73o>GA!^e8axvOC3Y?qZ(*92`ADb zHsyf`|A{VxxROMLdP$+(^f-~Gvvm)|(yMI$1A1+m`@42!i96-?tGO7a?wm>$k6TV6 zeaQatK>X+qr>aWAbW`FHE($tg)ktMb7q=>)(KSBO>qeAlSucdyzc(ck=|T2-+<5MK zKC6oxhxq>^ZV8QLMuRS{&Lyl@OA#(AywzSJ8w?oUtB$Px3Y*UsguU%|=;!1S#1B;v z_~~l483Jg~ek{F2Dn$HE_GO0&uOu4;B5h!&j1d~c5oJ)^FzRdz;o)aLIN;%NNLZ|i zl-g${B*g4jtFnZc)nbZ8YYxdMwh;YAXdmXNa)Qm;jFcR$nOj+$qgowo4$eryGkIlk zpMDX~qLr#OeRe!QTv@y(I3w81t-9DJlUJ#7@!MuDT9uMZq_*xLvmoj%%Az8nF{M64 z*aOtwL@4zoLJ4#~=-&<_LKm1l6lt)H0_9)=mdj|`V2ehY-K~*IoPt@I<{?($ z2_j|p2zmWmUgf~nH&pOAKJ{p%lUU0FbYrk${lz&aY*cz_phkM5m+AxN8m#YZ?9Zc- z)}VJdDc{|f+k{(&)9RCPR`@(eBaQ4fSo^m-#bt@x(f%bGRp(CxrEyA+&%!$@?_A0n zrxeo}Z0^(qiaXa-o$Zo4)I2VuSUxyE*b+Kh8CD+0>Aw!fY%pGfu~Oos#7K#c5*sDv zE+zJel@j}M#7c>I33R0&lwmYCiSXq}SK_a<;UHF+bl8-*yI5?zmg~xA8Sy4xDL2oSa|@!3c|>)k$)*M#mappgYK`>Ix`H&1qo+Zx^)XY+IGn1g^2dsZ zGLF*9VtzOOh@4y?AfN|ueh955VSN@sDQydDd(h629(MGhpRu?dFzIMBvzx}#k7{n3 zvM7DHCT{vYO4rqdKOC*{p4O8oqFh5|wl5*uH?IyY z9I%*}J0XHDW8sMpQJF1Ij8khQpE_2aI0_1pYmO&MlqS~fPd>oWEj96}Dvn;RnU?0E z^e=2$`s;KZYffKIe_(ML#q?xNO@=r3P@FSebUF&1NqBDVaXOOR-C?t*zb`ZuWEDEUup{Mu{`cU&t}+ zgGY??HoNmk0*zs@3v59aj5$Bd>rIe_fEQ^xl`7sZt@&s{997OuKQEj}YimLujaPA{ z`E23h!(3B-jlB3I_4$6_C@Iw6&SzCiA6Jf0e%UMOdA2b-lYYl8W`8iEVqj|jt6iCG zPq4COV=+FCEsLNz?8>q@>SXR^ulNsowGOPqm)M)jLjy{>Cy7L-?kprK>BVkk@%@%v zS*{ECvgiC6KRcb`8~sD`bfFu0OpHE08awRR$73hx-5N2nUch|!!KpxlErSY9_*{9i zf8oYCpqE)6KS@up(JQiPB-^keO}*?m;hDuaiZ!iBoT40Uuj1wyh{33|TG`_2V}DDP}5eg)Sv6xZ8-dr}{hu zc)ab&lwQc{apZRQI3_WtMXP!G948eqZO&t~ifznE*KWew*Z?POIfucKR9fXLs*h_< za8fS&N6r#k9nvlWUL0D_Nw?molV~$1^}J67PV)YMkb+ttoH!=c^LRCl^8wKy7TEp7 zpnBy@&PngR&q-%{aEXchsR`GY7@hcba%96K_>RDS$4URy^IiL38D!$=Wc6n*#~!(I z0r#NXetU?z#l<9rcqN;jny%)Po8E#J0gE#1R9)-3UUOCA?y#1uQq%(+oi z$2R9CP&=#5-4WiniSPxrAroo1dCp`E4yC?&SGrlzD}z>9))a73HOpBWu;S0IHMmch z42gYd>duAan^h(9G@O*C&*!8HS1wW)8aO-`8B7B{1?0$@68TZ2m%7#>rNE%V^J#-| zAbk&6wYEgwfb=cw>RKIL%kJU1h>f-CXeyhA=Tw$$U8kHoE?dW8!D+X~V`pOH@}3Fa z>GaFEoT?K2tUk?GI;fSfFic7x^Z9&sIxjfrd_E5MveZ8RZNhh*AiOf}T#%ZY);ul6 zt;C&wm!4&v>vrJz>=O${pM@h|tD5a`T=Uq!=dn4>Yq-Q(p9q+F?U$7E11ZxRzWv4a z-hj=}(DjS$7JTy49|D=$tjV&wa+xIc(b2 zf6~~RpcikdX(DqJ&7@0Md~rPIb&fqzoQU)4sp9&0i__!y#HC61noXp$P7Ys4wkwB| zDuaD-05<%02(N7ZeC^Zksm&E@iR9Nqr0eWJ$zJ-mn%M2nbAg%+L+#bP&pP;2tu`FtaFFfHq5EU6+&6Ih?M41 zmaP8ss->EWd>FyGrU&=9!0P@y54s}Zp%Ie(b;{;qQ(G->{OMCc1*z zca9AzMWA?;pXpI$eAYoGpASsFO(}0LWp{QajD8KNDzkQrwmReIx5GGdFhctpOWLKS z@IUo>&&Fl67n4x#b(Fh$9iM`a zdwU%d(BzkUl^jGGUiT?pj7Twcl+Ao4Ho|f)A&4S>f51GBO}GO0UpJI8@Akc@+tJMS zzOsN;vbI+qqp!1><>l-~d7LJ73eMLxzI*jFYx#7-=K#&a_@4}z3q1=w3YGwT)am<6 zok{pm&jV&rJxpcBK;odzR%AMogz(>L~Oh_l)+4P=q*5LlrN+|_}`5Rf-MxZ zz~}#J)M)rL!{-JVEPpd>H}Sg_wDsB9a5ly^6Xqn43I<&}lK)5d%|vrR6!0HF13Bm$ z3w;_eg6?_v2N|IErEiA5736?CPzLsbf&4ad0zcZGMQ|Zcfj7Y+a10DqGHo`x8jMau zVIT+W1xX+l90DES2J$oyZ~+~11vG;ea0A=~t)LBbfIFfMJp{!KC<@R3Z{Q33K_d#g z30lFG0a_rHN(LL(3Ed6ufo||yV{?BNUJh(qh!+KlUl|X>KCpyM+c(2@1?FbpeiZ$@ z=(mfSiL@jo9sFNaUO{>@NL`G<4SuU>`;fMOG0EjeXQMa4Z#gbO+H#Py9Pa^s%dZS+ zd%?^V@CCo}V@v*!VDnv#ZdrpNo{Ip03qX^P|HfJn6|fiV1N*_7pd|-ELV6aYaV5qQ z>sjZs?7m9u<6q-+NbK zd_dj%kKsG`)E7gK5q-}t0Gq?c%E9=?hiiu-1PhlxRQOXo*gKP!ePqHT~cG+5< zMzl7dA#m9V%D`T*4_p9A1!yd21^e;44N?c*g#Ho8f_@D01ULmK%DbmX*tbIu0-g9> z4QfF%*o*q=A?;6L1#5w_98MjOcK}CKgY$xvZ9+IUVxWLyU@##Rx;N5pAfFEUTG?{J|0|FmoY0G4HdK-@sp4c-W~o{uH%s50++d0_+2aKpA)z ztO2!Pm4T2=Z1aIv!VA}VY!nrF@J++x>95f{6n!$`f5Nbx#U9jZj^k@eV9nfvDcpYp DdWs8o delta 8458 zcmaKx3se+Ww)fAe?uJ4^K}30Kb+@fNL>m#sD6xT92rVMfOngMsh>tQt>^vMX8E+$C zghUg}(K|Tm7tF*&9ZkTNxnk_#Br+qp@w?z-T^-|$&P359W))G>1>H@5|KgEJ?)q|B z>(_hNK6{@!XV-aEQS0JrU0g;vB|=d&;R{8=ADTn>hyi&6dNJ%jMgQv0uea^WhLw}l82`76Mem%fpVCatr>cb8}SzekX#f!_Nx}3P1EF)yf4eRJDo;6GezFKm>GgWfkwOimX4J)B**_C0L zrnh@fDmL@=z`!fS_?~jY?04_$eNSm1p)S9BKeQ9X?|z%j9KLyEzCw&gVyl!Cb1u<# znF*Bxdf55lFNgeBIT5%9yQ?jU$Y)q?sD6B)+~q&1oD558{KOiA_GzR`O0BsrXSedl zu;#|*ywlbZQhN!j4V_B2v)0hDrEWdp=NJh84%iA_0!Kib@N+VZ{nz>dNeARl{W=kM z1+)SuSU%wM6m-=upB0Abh3EbCowdqYO5*o-=*y@)Tf-;4+fnd?|2M`sTv7IB*u>PS z{#QCRWf~OHB*(+_k3K6S-(+j{Ro5#Yrj&NlxTSN>l)tBBBBowhY0l`AZ<}Xy=2^E^e_9T|QjV@Z!Nm|NyA{@b*KnS&vU}|wb zI`44&u;rt^j5rb<56eC(czFKBaPi&p7dxX2J)Oj$G|kG_idU3VW}4cHUrkw#`e-Sa z5-y(|o@FoiIx}EOhgMHzjj}x}yu+xLa-$MQUfmZI-%gWew_j0C3VW3EW;#W!;iRw) zy5dR^1(C@2{HL;Rw_A*YsMR|xig`AXZ~8G=NPo~@eiHPTzM$KkYJXqzk@y=O<$YoO zQLR6TYWqo48=};R|3<{QpG6$|NyO)B#MFV-eU6a+Rma|BHfqJn2VvF2Ocm0k`3u(> zWs7EEQN_AS=}9R{S|TlD*GEPL7GqKJyZ^yFBX>H?O%+mQL%5_B_nkPd1eh;LE+s$+ z%Zl$%WnqBsGNk!>K=frzgW0t-zhS(~kOSWvRfSN{ibf_)p zkNWD0AZi+1cg+^Rdu2<1UJqH;3yZRJ1BG=-*q3cUh) zg*4dwN~wQ&^}FYI`YTtP!qP{Lpx^l~8#` zPm)wu!iGef)qBs1j#b6d=vDMGYl)6XY&>5&5(~NeU3_)SIGFyOjVv>S{?#l}QB$e~nrI_{HC?B)Lj^QFp znJxCQ(NCaENqG?MeDsRrvrB?_PEm^d?r&IQY_i&zo3W44_gPHbRyvj)h>OvsVMl&} zx#F7Xzq3tatkmxOY)lOmhI_VU^|VuYs7J7+y9gmoytSqwrYyUe9wqXKURENEfA&|s z!*T^tCqLOM7&$|5t`Mh_kNSyx(VJbJEo(K|`JP;`y@A$J`CN|Ym>^ojHYIcck(aPs{YKN{1Gdlm zY@>Vl=Ish;pi{p(aWd=XrJ*;+%+<*P`=>rLVxLc67MvGi<>!)w;Fd5k3azbVGYm$Z zdiSfW$dF9y*;|IuNbd)Roiv}N8I9BUgM=R{nwy5?Z);d5Y2)Ihpd@-!^J#Sp5fW;` z%HL_x9^Drit_06oq!@_~qnxySQO}kde@#PKhw-1K*A$&7H0p7rIP9BgO|l)bRS8u7 zzp#eF%E^JsZCg1kt$lvfpchlEoa|LhMaN)04eR2*=o(+Vm~16Dl-x?OD77;=d6w@` z(P8);hL68dvDSD4(OVR0W`Mle*I!TTy>W&^N}ZtV z+D|w+*k@Y#9^%S=tS^UcHAPHTyth~GhJ6+6k&S8#iEQgJ6{oxQA0mAHYm~%7&U&Bl z-$IULt)}g?iRF)viumpf5$rjdvY|=Zb}n@R5=7;@?A7s`=)3H}__TFoXTnCM29pYRS!?S`Ske~7%g5|qPsa{Z})L>q{ZN}(rF|z}S#+mnf>i^B>{=pNH>vQLL z*Zf;>u2%f>gR=oX_uqV^IcQ#i>`%opkonxbzOyGtZK@cmj~BV4R6fBxiGQN^m@8>I zy}%wNrO?mWgo#G_kXa`hx$nB2_KE2$z$`qm+uWJBt}Ci zJ-j!IZ`qS|?%ojN$QEiMCL%9onn@GF61`?|B}s@2kbMe0OytMe%t^`gzuCG;#u%&b zPN%vy9`}VhKQm~%rc%}8I}efn%s!Zu7IELBX^=5H)qI#lK~E%|T*|s86^CE&j*Snv zmLS?n1%vBux`oJ(v9*)Oa*In@_2e-~@CTEZ&=f|^`pI=(p;Rj;d8zPzXO&_$Q1b!xGp*fsJ9l)ARs~{R} z>Ke3QC=qPH4!%Xh${}lk1=NEEa2B+K>R=-50M#KxsDji65g`=J9fBBK--J)FmIyr9 z0iW~eIFIdJ-C6^2(qiYQjBqT%SzR^ouB!+wZ!*m{6{OmFB$M@|5N*@R^SX8NDv!ZR z^s$n<;}65D$E_41KhsmczJJFQO8eyy!S8PK>*N|NfZ_VlSmt(n<{2V#t0Q&tre10c z&o@hdc&Xo4CuiXqaq@bLuP+=gBOWO@@1*e8BAp!GZI=4?MAc=f&yA=3B^q}s4C^zb zdZPOZeN+2b#df7u($Oqp>TKG`o|>w6)cfMBWAZAM{R^UPadXw-<#!+b!~*{Xzy|D~ z9Mpn(&;ZVYcA(}|LEhDzs=3{PoT)h-%&$6}wqz2%7UhF^uERpJ8Md23q}cySc=hiIQxd@XBt3nym9CWz^} z_(q-Famt?KclWd?O~F=b8-v4{xpcIM^yBcYF7+>!{$9zl3&`|7Z1i!B#L#CE)Y{6} z@o6sZt8P{@{Rb+s;&eUzjBQIFOaH@pD7}!#?kJ|8 zofLK%8GCi)o3p7^W3%UwmWOQl>}4TyPN9VZmZ_|D_5`|^-Jd-ji%7tc@_3~ ziSQc1KAx95{Zfw_JFd?f1?z3^|1b7zpI2C)R{*>&vYGii(W16|W5k2y_+qhw@I{~o zd<;Hgbbb`Q%3|j0>0emJd=owCES~SCRCX>~;HD{Ge-e7eo}->NwlzFqEf+80%)otg zU0Fav@XSVu%P>RAY>S(xhzVkb^}4c%RX&-5nwp-RO&768PdcKW!6*#HOt(Y+2Jj-y zrE=ZrD(B9Hlc{v5w$$mAwQ8O1?l$RQ_U*fTTm9x@k zCeS%-&oh&$o3%dkR_0*bt${WBEF#q{!D0%sT9k1!iQJdTxNe?o;)tX zrxW9w1*{&u-gr@mZHNjU#OOBkZw8$Fm5-TM9HaZ#jTOu20yg8>91O^<&pw^1o~aM$f0%k{m; zGSOymgnP`*1@eNz@iMXWxPv|Mjp?Gk%yn0>P{Tg4pAZ=;7qw`g`0)55>I3 zhXt=%)~lqTY+;{=79Owp3*_Gv_PF!9d)&i3`Z7+uxxT-y)H8}}KUSqsoFh4T{uxeQ zaR%dwb=nrv9c*S%Zj2ondlhi^V({y(t(6o5W@w^}Bl}iDuF6!rhwHwTzPwpXTKEdjdof|9v|?kxkT# zN3-Hv65;y|jzygOx1KwlgLRPcA7*JUdfnAZ{X%Y<()mrG_KKHtZ)KZT=FCo zg0ZCDZ;vwTJ>BP9wv}yGw4yWymwQ=-iwruTKx{AGu-$iWS zT0PBXF8oemf5)$$QAv+8iBVdw9#CqfF_;h^NokzDl--ejO;@w!>qe(pN{Re|qMhy% zU3cZm3-`#h3-`Dh17>T0RV~}A$er_!V#FRHygIBDNa{SYE{4)7*81E7+Q6FEZ^v(D z$-;~VIPy)JxqkO$zw0iK4QzhP*&l7657?e)Y5&o7cEI*n%T3l%5}qLcSaNKjWPA(x z!(grN4%lK_LRkpDP6^IOrL%P-LMricM-|*O3021U9xhB4X{w_ME^bVxUJt zMf$eieGrG@)hxF<&atAKYY265*aoW^vg7?T{r|eCBH|@pi z{R<)1koniwO_8Wa^MGYdZyB05B)3qCkfycFi|x2a7A>+Zk9wkuXj5%|_xE_I(qm4N z7BwAJYP}#7bzS$Vbp_=GIjoo0MWZt9!`(P61m?!t9&gE$=#)H!U-GG^;hzVq4RQ4a z54R5gSwlkdg8Lfs7#gz3rZ(kY4f#-wc##;@=D6Kmy>{1NgS2Xk*zTHi9CmN?$kP zch~C+Tn_i==mmI>~(+a4bTS)z3%^j zqbyy_YfppS=s@C+epzTfE$!nPfa&mo~ouluC8*DZsudwbn; z(c(9I)d(UFJ9QrYBJ#vjl;yvbJfZ5$>?n%({(Sk}b$Flce|J#pe9+fVpZgIz_|`&t zm_2&yY5ES!udN-*X{c5g5Xc7+!oI9E>oQaE4c{5I%Sa1%K8D1Bv{{5N1zVtR1=~Ok zz{j1wzl|CA91rN@gkKHW1Tvr(LM{PCpbH#g+uk1g+yM)`#eNP#KLn0|<3F*h<*m4G z1Gm6E@CbAR9~iu|>Nlw0z$yPW&;t`l$YlSAMLPzI@57|aBD{M04CtBQf8IV9wtUqO z{BO6PgK`Rjz+nA{pof4k5b-a&gDl5I5m*h@fl}}S*a!xLqq6^{&ndtI07W2ofDFh% z-__7x0P8>sNCPv#VEJ+AO<*rLSl~cUptONOhg;C&UO`eJZ-Xn~8n^)leO{PL_?;j> z2bF=npbcyWtHCv(M|s!+WMP1AJPaM|K_CQ#fd~hFqCgzb0~1IFXDnWRL=WXkOfe7G&Ule3q5qs{puRNK#9_<26CHMy+3>I83cT4-yn~`b{urWU-vwlRyTfB#s(}OK%GKykWnCI1ADRVbw|ic z$kq#J2uyzht)LBD0Nr4-9gRhK6zITp9OM$%u0Z#J8t6A5Z-Luj#*64QY%_ohdLc-F zeh+2$K@jvd)X@d~(FWq+LtxkgCq1MIa8xrmFG%alNCz6&3~qqIf~TNoqAUz@3D^dG zGo%lML63lp0@tA5{x#x37mn=*V2cBK@YM6`pWm>F_3Zss(WdwDrgjt`>Od423rrvh zq=4z*agaSA2b(dtsN`btDFVB&fNX3s_Xwwa529GXn<&1r+7&8Ab#IbP!S0P!Z%HjEZP%ebhMk955J+nvhqAfJBTM zHQTfpHN^+5CO$x*7ZRuVA{AR2FxsmzwA$1ldQA@zGKU$4x&Ol>HT|0VUB2&k)|$1~ zeyzRFI{O^-__p ztJKcu&;T#rQ-p6;5n+K#KUY}v&=}VcM{k>}AscDV@KTAk1R4R%MOtW zxMf-Xre&t(ro2>A&!RliC8ttXPw8+N~VU zv~c6wNq#LEodpYy%g0G;4m;y9id&MyKJ{4Rza&Rx3fNGZ>T$P5E)o8o=q*uhSWB!4 z#j}SA?n`nWx5b()5AqUW$Q$-N{TXW=HY@al-fG#XzvJq9ljx4i=k!kNZ+nl+6~xox zw4Q)=jySC!u;k&dj9f1h-O0dha*RHWs5|t8O5b&}=HXjBnhJ=(RpeP3BZ>4e%k$sO>W z5;4=7%Qkoo4=iz(we6KJP!fKqMVn8hnUs$>dMo2Q=j*y4_P$q?Io|ntn<`%=%~a7y zbLaH4m-ES^WYxivGWkr*3vD!L86jQo|=~`5n(Pd9Sb}=lVG%Hf4y-eAN5GwG4}q*m0;Jqx01lE9AEp=%it)}V`EZ=e$b5|64*(U!jCJgQPMv`yeDyWcm33NP>_7u>N zt|cN-&Ho`Y)a; zFFiAQpgbVAG?nVUL1?ZJ5^nC?c_#Tgam3NSR+`SN(F&r|x~BL1*ZpDU5WN37lVYOM zI=g0V<=2HJR97aOgt9iL*_w;_s}25HTiZx|K2L;`NC++bY6XNgm|D_oi0zdsI^4;t8;r&dvk;+ zpyDl5{Hi%oCx~ioqO6}uq|cnVf5>0tYT=jiAM|vRGJtB~E$FhP-+J{a>s43_wExMj zHKRMF`xhJ}{6b5?Q(b)UR2Pj;HP)y<)%LXC+fVsjd&=*cz7!Ev@>yPuUZ)m|o_LiE z3oSH7&0mzQlM+>nvWl{onZ}GT>7?PR5yrx7y}0N#Z7>iJvKaY~P>XOa zG!2g3Y0a>czN(fsK|F>W%vC5k(P>SoS90;FVA{+Kqe5eRm27G%P1Tva=k{e*=;4@I zs$ID@W0oFiF48Xhcu|jC>mt3!j*Pmeq~dL($138((Q~<5*-RcCto-uzjUT%tN7F$y zD$~gNJEnl_(o{bBn-&sMEx+qI!*pEU?@8Z<;}+j|Po=x%=q}QJ(SZb;c<~Jew=3^ zQkgT-ADh2TzOEl*mom0j(7japjZK48aiAwcEP&j=?h9$d*Vz-1c@o7& z*>eGrX0inB*3hv7wrhPhM>k)$T_zQD@;}a1C*A#g=-uEs8p)Uaw|15fb7=G3(>)CQ z91`JP?Qp{Q+AX675&$$dJgQ@-DKrLH3MSjvNJ9;i6i4i5(2tO((Jl zosRQ8!U}aSQGs>qzB1pGHKI_d#R=uOV}>EpSZ>@VQ0W@1p0IL~O1^I_faPMJ9}Urp zu?9|(<KC#C4IGv9pPfMfuO^CF^Tft8JraFD9<_ppX2Z`_4#aekdRP=;t^>q zmVY8>I(CgCoHW*PKdTmwd*OJZ&v7Lh3p9j>5TsYr3>WDbdo$GMXS^eH)p7W3`M$wq zG&uYR4VIw2&Yt_L_QTHzKi^7a$V4*QLRZIIPL&hB>@7;7Am{#u@I8=Y+2hdd6Dw;= zQw51qsf`d-{?JHuGZ(u+))6W_Jdcc-`a|14*s*ahW9J2g&7+%HcGyko&Sr)i=-=7S z@PnLh4hxSMN4K$zh)}wTZH@RfV(l|NZTL4fI)}HM!ZxV@SuA(FR?GDYqNgRkMlJea z4H|8N$bTQjL`3m*c6PiEO=Jz@bu-#+WxsG(y?Z>;9M;u6>we*$rWQYaa>2!6wK+(g z+uRJv8H=+fb6EX*FPtNLV?|GGxX67-r87(yd6C{{_amp$MivwmLqBC1Q93HI%~9A8 zwyM&occQSRTYD5@`zCGjR-eD~DA~3`Sf(o4AxFvk1M`_0K&*u3Ac9 znflRQtv?}rV$yKpi3SO*Q>$LlkDz`Bkj05qfGEaWOh*Z?6zc^dZDQpyVVY--Da+jw zqcuMZ4^PX90S~8DLf$7*N}rXGK!azE${1)+i^;|SLtuK5k?1Z%yOgEM@;3yeCuap1 zxK%}2sx|%w|MX;BlU5b=>6dXWT%}suXUFx@s-m_2>HY?8_2oX9v|6;h^xB9wR#VHHf>gibJL2+Cj^3HE}qU@}NV*=$I6 zH4&bLqtz8hHYQE-Hm}3EUor5OTj-*oMmJxV5o@%WbcSld z->8wE>()r`+l9W{E6^l7Po(8GA-n(SSvK$#9U?fbe{yQ1OGsiPw4;!!n(T8!My8ec zYNX@6R5xOt-t^Jt{yIojSRGEvarD)W$19E9kjveaR1`x1ky z^}^U8m2=>1%u$*1es(doh^DZV$usHSSn*`7`Ol6ZLvVVLd}x8cF=&pmiJaCmzaNa* zV7vxnrNl{zkrE#zHcHHS#7Bv@68l5Ym6&gXuB?NyjZ$V2elNO{4kjV%$`E zo^|7Tm&HtpHvh6tBYgl8>*N{_(N**k!^Kg^@N*n$@vWr&^_-X#7$L^P;^PoR88;Kv zmL$d3^RRT*@|7B?t2QsyX|>hMHSPv#494-SB4@OS;N$SFr1K{^$K<3u0dYQvhkQ^a z3F)&4N^AM7b&7>k+t{J0-_a7r;FN9-C`1!U4-{)-^MXnpjZcRJ=DYPMjF1 zkw(?#VV>U6C+fXJ)nYK_J5rxRG|~{csw@$icy86cq=OvYRu!G1;^>X4m{cdF7gKGvAMX$qe(g^p7leekiT2V)Lz(c2@0NV5Kp>^`7VRQkC;Uam8#y zf%rL|`rO$&ayaq8nvD{d74EN~Is~ud*zfNV(D+_RX{7=;lQiieJ8pUSJ!RXV8c2ljWa;l@8qOe{WOnzx>}SIVAbD5tXVr4(nfgs4jUk zkG!>)9sYS3UCSDNK9Sm4*U$IN8mxD3;0>-BHI>Al80uz7l*i5>l1&~j60N%98KRQj z>F(DHpqF$jiCba~E3^?`+Af^)w9r_O$ZuMv3*BgI_6fpEHN_RKB6pe>g2mzoE_m9@ zZ1{80W2ZSZVtAc^+!2Dag9Z;9D%eq{VPpS8fRloInen+(w4QmaTu#GT_R3Uj$jX&J zi&f6qpX1He7h6}EsPeeSHb&F&=Xuesl9TjUDCOBjI|M8aC;gqxFh+QX$y87R@WARE z!}YxfvzLq^=2*MFE<;+7IZh&pHfxkUyfR+Y=35@fiBvM5H=1DUju36uI2$K5IBnKs zJH=g1rNuo;S#Wm@$~O0TjD<(FGedek(`L=-wpl0GwfUTQcSC<$Y3F6jA><@aoC7(j zn*@Z?M89%l>Gtl;*dH{ zBA?Llw1tyAKcNCAjroL-yc%~LO2*gmXg|O{LDY+R7W7u9yf|>upFZZKYc>~=gn!$N zFKSU*@x!F>`tk7f!^4!5IQ!Q)OZB%w#+^x0U+=N*lFJrxQ{=WsuIigToVA#pTs4pW zwaU86LFpmZwWf$xvsc!xr+eAGwM*STl!HTJaAzK8$?GDhAIn`glh&})>$Xq3xP|a} zHG$)3sA29T>?EbX%ROlZMKAMPZCsnjNuTtHeZSQm@kF;O^yRfLb5bSCT^~e`vYqS4 z(0AEKxE8WMuGiv__83JgyPuL>U2IUZP!4yno_BT@;9$aix_Dhtp-Pxn# zF60pDx3YSwMYKGSikjNVl%{rWM+oj!7lTrEK$hB`{gCi79u9q*3c6d>?d$+bcd@RV zC$yHeZ`h9Orso$W)S{5DQO$8$Z#XRvcs#!5*I)hKc5T2myZ+YqwhIHc>Gcm7%^eXT ze_wKHpk!P<|IuKpM+aIaw@op-_mz60SDT$|v%DYT!A$w`_QTj}k z-(2ZiW3=cI511S;tJ_;_`rFM%m(i+gF@~UAw@3HekAV&!nGC zrF8pOrWvyzwfTzUQIgD}Uk#fw(Y_irSASm<(R$PU_H?oQkt{V$p|96juD6y>xtxP!}l9jzil6_ugWZb zjq}x{>uWyGzTVEK1O)i{rF0N_shy{K3%j~qzdp>a67_XFULl-TEp!t8O|!2Uf^9~m zj2@Nv09#y1ZKg`s$zvr~4IhFJOE?n^wX5;!p(HjU&FE2*TECyMl8StY;$g$

Jh> zOXJzf5+9$XpX8;w*5FgsNl%f!>$EbQo?l}-N`lN=y15EZ3x|g(XQ0ARJY?5kZhJ8| z<%=?2`0z4$sW!gmpHIAsEuZ}JiDuiCC%js(yHcr~@9^c#Ihz{jSpVdQ&8t^GqN=0h zAo2E1ez<@0tVb%^NSev4hYL3;af`R~*DyF!P$Rm(h8a~p9H{c%52|eItKzgy{(p6V zAk-@#GdRPYY!xP_oE4PCiLY^5k2r~Lc)I7@3w+|kS$So4?zu+3%&vAnVpk{XkJvfy zz(*SQ<+B1Gsoj$w5#se|7)|OR+$>*QiJRN3ha@lFQhxA?@R@bdSM0=&c)F6^+cDa& z1cBnweuh((e!ZPcy5O7ih*I8C!o1#|N%ynNw?_o+hY!({M0|BLjj!W63X-@k^`wP4 z{s{D5_U79<gJ40@{f(;hW$-J7{VMa>8AeN4!cJY^Z>eUqxV?f8 z@xbZEX??a^EjCxWADrc&yy^-xc*^%l6^+iTTh%Z=Me8AK2kNi)b0^*z+^GkEQM1%kJ-;s7Z*$nZ3$ypN?iOo{s-X z0mlr&$327NJ@hm%4`c#-A?o`}NFclqXav#V4WPk`ryryiM1VSw%XYsz#=JI>@E&46 z+0b*rCb0D>yHdUzzxRQYpb}WXMbH2Sdsh4g^>VyuoCfVEe+)XF^6P@$4IGKY%u_fG zR;q#C1e8H(Al<;f56TNRAJ7D!|7%bl@M(lk3m9xa7q*-DeH*m)+0Fe$p(uy|(I5uI zfoUKC3|79E^eyu*HA~&;ffF=zgj^7xt}SsTr3nPz-i}!Oo6A zZ+!*fhAao~fdk+$81#vmgT)6Psb~x=1v|hr5DE@}d!Pk%8V9Ju5;cHE&;-maxZDJ{ zK`Xci?t{mm3v>eqplC<~+`vUNb`#tN4FfbmDxC}tt{r+8cnmtgkL=c9vM&>}1Ft-b znF7VJ7{7OeOqTNA408jlji75WR{p0y+7yXH*)*jb{2yJC29!5~geBPS;75i=cB5?H z5^PbA;SvLKJXrB%0l#VkRTuxjN=6a z4itkOU^l1()ABG@a2xEy?^Z}Z@E&vvNP~VD@(3sg-DvBvBEcJI+Y7WqKM78QMz8}u zm5?H49S*y|)SiEt=#ur{@wgW%S+Ws5D`+i9HK%fO-AR5GiX<#N0fnh)n z4r4IcxV?&cAQOov1+pFaAWiuV+?0gGD&PNgMENd65Hx{0&;TmIVXy<-2CMaivX!TJ-I$Gg!N-lp%SJa*WOL0n5qEl+8Rq_)M>hUHHv6iNvvaj}ZnljQp*WoIxgz1;okRG5A$bM*YS@2D*h>#y@7_H-VoB7y zs0=oP{on#GBfZ5G~ud<;CIBa%qL+EAMR~t!gVQG9WK?lHzqt^9mxBw>W*G^Lt5Q ztmq?0D9{##El4O%mO^uvm2uL-r(eqo>&Wl56&z3wkdwAS54=5j+ypDbS2b2b)w|gD+&^{zy$8T72;0t4xD#ZAHWVMoH$|c$!6QQzCA8QMI zF5o|GMBp0A?dKDSe41tI4U>Fjm-o1GJSeI0V{-%o&`6h*T2o!lo61K)EsZUCC(Wa! z_EJ`(pH8<4Fr2T3swUWW}y=l|mKHEb7v9sC|F8Sb>~&xfZWult&-E)V#b{9rhJI*8AcI)L5;2os@|>^~x&K>;d^}Q(9M^ zd27ulH4#$1^18lWsTHo4Ui?rU$$E@rd>1uV!e0`qmA@t#Q71Hk{7`LcP<9G5p2)jw zH2Q$D&Qz^*8pd>0iZ#?&udEU7bhUR=V_Wxp;|TOsKaHRhJ_x`Dopx2$v@86ydgV2t zO}U)pyd9rcRWlm5uQ6RL{Y3e1lgwI2hgrY5J?Dp!t1D}Mn`Q0Ye=Kt70behz%OU8< zS<|JTlhz>y^fXr&9?^!mqT0) z$L2^>-ssY;J$&2iSnbwFYt7-sMXWeD%(~@+!H!ycD?Z5Y{p^`w@jcr!U18CET_jp* zeq_E@yrP^i(d2XZ)l}rD4~%k2!E#$*R(by4GkvCYXbn`>DBH7wJB(^6H#UCE)xCbP z?KC01{fcs2cuV=rM5n1O92d4hSL{imAQHLTdm`(WwLQZqh+0F2VoE3S4KEf28LafD zpH%wOK&4w%@j7m^dt-K4P0f{3RYS0(759F4RPixglI)6)5R?_$p~^xZ-DODAb)WFd zng)}7xsT(DDY_DO-HNs|G$W*FIfENvsgy2RvT;XEqdGU#s0M3&dqog64fZ>x46kEV z>tM}|y|&F;rNF!Z%T_5nO{SVZTP`Zc^}kmBY@$gt`4i}s&?}|kE>%f`JE_-^>l$oa z4TYJ;j;DWT`D0^}>eT&Es>?A-qvs9mjnHG!!$Oz(+m7A_Y}`C})qeCyr9fu5YZ%nI=uiEhuB7!=89(*ge1Z#qwk+Uc6TNnJvG!&%$rLT6$cW9yC}X zSvrn&jmG{hZ25?~QYxqQB}jFpj0-oxdR$qfAH1o$-2R&MrqY?Ts4)R`)*&3WFnrC# zzn@f#+LER9vDfh(dp|N!9k{EJGwEp-9Az~ME}hvYFVy0b>oeDW zhtDALf1Dhg#1%Xd5^-pku;!>1`Wv=!yqT6aof^M`3W2U|S$*wP9_bP+sdhq0GjHC} z5K)ocLJt#pbU#}oOnS1ke^jm@>SU>3FmloUxk8jqZu1iPqC2}LTh?l_ZRne-_u5ux z+w@pE?Rp}7TTl2YkP4(tji6i3-`+rLseHCihlStdjuUN=+gP`d8)$Q7G{%V;;(0}1 zK;$BpY1ka|=#cI60o%AfzGb^Y8tC+IKRljw0*sW|R6Qyvv` zJv%26PLB25Dn0?nH{p0_z;QJii!{eZ6YQ_jEFZaw6~=@t_4mZAIsm_l9~;a;gMkk; zScCQy_pMcL!fy@yLL1ePiEQbMS)FP>bdd1%ui|`%ocr&DS0DvukJ&!8`9xigAX6%L z5u&LWnV@awk_#|mRQ~=n5z2EOwB2FPPI{ic$G)31pFYphCSRd?78q-$x7mu=y&RU7 z5<7|3unBQ7bTgY1w+~}|D=s(iFMV__Z$E;m)c|(0+3^O0Pro4Q?WxULF$B-xLZ2Y= zKaOGsM$yKs@gejP_Ex-c*4@7PS3HhBS3s`EVRo;3#Xnao{_$R$kH_&h4{7n6moIyh zkwG$#gX?emkklrNdPA(p9j5Y!>|XpC+Rd619;O%A-Gn6iIh!!WNPAiK6eFiNo1`hJ zG+={U``sKZJ#?Uk$XnUb#HpBMorzI&IddgW4vKf1#8o6N%18Ef(nCaklqEluNWWyo z4;drOp4(mOo_f@yZ~8P^+cTZ29^bo&{71I$p_GujE=_}s)vES0MidN0(&3?YKeRgd zf_p-&&$T$wQYJ*(@1$ZAn8}`;I)PhO#%xo^V_f%5EuuNhIo05M%q^5@GUIBJ;H3Czgo3NHbR)nWwR26{~tB^lZx~(79C+d0C(m zd;+-DBsyz#cwQxF>kc%Ao3q!1o2$U5K(iLtpbC6y#gAqkQVD06SrCmDbq6XKNdyZh z2MPkSLDqr{P!AeF8)yeL{zTXbY66H*4XO1bf*#BrfjYRp0Uv)Y5qPi@K9|vP9*Kc^ z0Q({xV{Ow$Tc1KUuNrv!RaCV#$1I4+Pqy?)G3Mh!xJ4(ga_Zz4UD0M@h?La4U=-d( zZYB}=@xJ;EgXgMHHYi63UdMT_PTq&@FW4{+o7`d7yy%eJnoym*wVxV;=bNP8KRf8F zlb7Kcaq@-?&p>s&uDB%syyL=G#X338X_5v{Hq~Xh$I(Sv{|mvL2qJtRond3;`#@=igxB?>1>Dw2!CA7{Y709Zgduz^}o4;nxl zXb0+;YB5ggn5tu22VEW0;qg_c)82V7pGCV>JHCd^xJS?|Q@QpgT>qL2u*U{IiH2a&WWjwMqQ`tBX zBaK{K-NBzN`<;?iE?`jiB1eg8B+&yFL2a#q9h_n3?l{?+hyO`S*@{#Hy~ehrPM{Z> z-c2o}G`i^@Y4<5DY`QfoLE~rW%a@-jbUUJ0Sb9Rx4GhjpV_r|EW{sshhqMy5Bz;9d z{s}}lWXWLm^vQG$yOsVhB`hjqs#Yui(8>xj#z494ZIUvu+scr6+5%7fQf)-*5o;V=8ty0HV+C|JAQ|6AR&170BmUL)Z3pDcO) zE=t*%`NpZ=tt5QP6ZoKyEh=!(q~4G9r^|EH++th9V`iIp2^j+S!F8p81mMAq6<1(IR9Kd^OcUe8 z+2-rYV)oL)B-+7_E=;G3+1-WKFbT6xkCpv0WDVd&noH%nleJCT7EPsU8uroRN%U4z z=i(F%$Ct4&%iiM(%9>6rJ3{>>ELk;O6R&ll2_!@zp$zmrvgKV z(&oQ)sq5`IHvjQ)bSGQ;_+*;Pc0E3oI+*?OH-d(}Zeoq9eqXSaE2Dy+a>k3qpzW~{ zjl9OGZo~i0cC9o7U+ruAP;aNn0SVuC%oLoclfllc48a5ba%JMg1dmRPZ4t2M$Kd4G z;i#a33qGEw2e)ue?(?wNCyvlYcIAl`w16c&nS;6Y!jnsr)r9&I-Z?`t3)L{x!x}RZ zX+ZpGUi53^dmJWFE z@Tm3X%P$x9ITkqk9HZGOON4ICX-6$C!8XXGV_DjZZbyw$ zzlfWmbbaTmz2fE^TiK>n^XbW^)>R%#>zI8_6>VUdYu95&yuY@{?{#H-bP`rpJsY_$ z4vRKrT{^wXHm}v2bTWwie&dF~x!}{PSce&T% zWhK>=F;J%MSxmlJU9F@QR4X$JIQbR#I+QLparpg(DRs!FocwNWwXy`|PrKKnq}-&z z?=z;Pq4J$%_4;aM6Uv`pY`p=AOf!BTVPE1mfjRLT&LX4@YMN0aji;B{|C3U<@-p^U z>6hUfUHZJw=4eE{ zG_~pGv(IXL(q2W3uQn}zejP{C*qIl?BBr=Lh?ptfluVCNd6MfJY1U)kb%l!Yn9dW} z{TC+Fku2)Ps8DxbmUu(z38S*3?;9!mvA=hz9zA_c3tzm*(RnOp%hxosN%u;pmX2oM zRL-W&%utm=ud=08ne-2APgP6GBQCGwbGHufc|@*taYkeLHZ>E$+sLwDoa(UXgIP!gSBQ1}%=1Fu~9;#pRsOjs2mDND( z1C;~Kfe!={kmo-T$V>#X*rJB=uRxBeHJ%|xH5`ZI>;7{4a6no$B6ea&DiW8T9pl1k zamnKzYrUGhi``^eTWHpIl=AjkW_T@~zQc-N3yyjRKEy;a@R?4EZ{d1uS=@c?w1rQF zWAN(O?$?aiL7HF7H`E>@{1@;Y27{azZqei|hhIJH?JVY3lW9Gh|10CbwcI>T+}^-P z2Z-bG@GG2JvAxlMZ)TX51?;`hP0DrbLN_$v6~%yA`nb-JmM7;H+6NsFtm*dKls zLqA}hznVp@ENrK7_71n|b;Rw1@7C%pRQp|zhg%1l_hKQ*sVDemB0uTG19p2IzFw~* zXlV7FVlV8RL#tWq&NsMlBsII@Ijt(ju-aW?>Gv#uR|q=|?dpJb2ihmhyK60dgROmi zvvu*uL`yTK2NJ=@z&G<^zvEACAA_&Z@AwpwhirxPgFFQ}0`d=#;~<;d>i*$lh=qRi zG$t^f$M5_7=6W1@eBID1{f;(wzrzjw+28M2jEH~RKlo*3)QK<9FCtGlL0QooQ)Av3 zs69AZUdMsH;a35*#d`z2^x%`t(Ki+$tEII|=^j>8TRW1|P_53#m-i!t-KjO{(vtDf zzA0+Akrr;7iGR3̋f7Ho$80@wn!0(_|%_$!-@@9)3~R)V7-SCF)Kf-n#T3}Cn{ z26`Mw%p|Op>8!){Td;Y68dC~n8u;`-C zt>_7qGho=^8uXACG18Eo-~#9XSHQ4O$y~y319NiF7}yQYfK6Z}=m23T_bb3C4AFxp zVcImL36(#{Cx0pO_iZ+6W9X&uUmRhPM4yc zWtipQ=h{1mvh&NxI)2UyJWcR(jyq7c3+!HrZh)Wjv!m<`D0>pV-~m5Y@|$$)>@^t4 zby$Gl9OwZlPZ7SwfZ9LDgTl8L>i2<*WA zu?5lqxmCRenb5bf=HKp%>)eSE1iD=qSx67)23Not5Cr>b6CuyBEqmXXW82`hQryUk uFA!eu;2r&<@L(tYYZx}g4C24Y+CY8HupcRT=MGx diff --git a/Tools/IO_Firmware/iofirmware_lowpolh.bin b/Tools/IO_Firmware/iofirmware_lowpolh.bin index 3acc3a9d079fbce058442aaedf3b00cdfe2ed6fd..059048670ef3f500e6a0dbbb88b998b9bc9df041 100755 GIT binary patch delta 8686 zcma)>3s@A_*~ibB-GxCx0R_40EGq&cx`-%hCC^Q2c%I+9@4n|f zxA&ZR=ghFj!j)RM_yS6VtN_A$iG*LBLin3Nk%z!a*q`R!t3UjGcyD~*!l*-pUkr*t zC1?R}yiWMNpd8eKMsN>wg6%;+Y((k6?fpJmY(bw)+j}a^BfgmM+7iNNLT=c5&+N7= zitvY%2~VrC=_ogiPUfXnwrfzz1YV-hFUdZ$ede4@Qho8PtPU(m?P{e`SeN%~?;qG) zr8Y(f2YUIPBz%*K2=iR}xXhvkN4thNdRkp2SGIca6{=>D?wjcxcG!LG@FLTa>=3Dd zTap!ET4Gvi%1b46Y@A1WoVV<>PIC$(m9}-cgk*G(%y7{~a+RSi@Shu*6=U*CyOqP4 z=C6M%$-g65TQRtlnw;P0um8f_Pe- z*5lC55~uZjmOS*8;cI20I}x;1j@G9Ub-SKW>ANo0G<1_kV*wGkiabk0B#}O5nV#A) zyfj!oC!h0*uCy2eF#wh6b9s-xGU zBND8+Y@OH8pb}?U>mIqDlJJAg+I%V{P(I?wt&H!Suj_)@dtT$ran9FURrx9@K}93Y z9n;QS$|sMKRR>DSh$gL3 z=|v^p7;%Yye$GX;{J(lDYw`9sKm0o7+rcXfOWsQ|cN{-Gs(+d9JYSkhFpSIkFP%tPME0aw^S*z1*&BgrHhJdWit)woWC&CFN1VU&cai@t@omb7~?_N987Xfp} zOJ_1VuD&=-JW`O?>K|fjm8(n(uZM)sZz|B~@??uzOQgR#wOge6x|Fmg-D6q zAmb6!=fkJ%D`UeD0pd$$;&XrxW$x$e0RdrwKlTStsm#D^nhbGNdYJYuBs%g--v^r9S1JJqO6 z!|U#t0<%j~`KWK2Nys_*9na~eWAZ*v`VJg7`NerE-7Q6Tk*0m}WG#&6{YG*~mtXpg z9-@@pd7(6QqG?=OQw|&A|J?WicchHG7}HpBan4nw51WzSvMA@AJjtuCLX7Dg?i@7s zp8t|TemPVcWs5ZV<**)qy)r<3K#(Hl2CQ24r;n98xITJfg_J_cA zA#(Q(*?r{t=H!0;%m3bq=HWR$Juj9cRwF|cjPRM19SGS)C$I>e zj`KUr3Ux10fpzJ=GT)RnqEM;D3FVk$x*^h7ZrmzR=^Ct_uyT@0zHcmmC7iSnN5oD}CM&pHmDWAHKc`fPNNkWho-5os)z ze`Ls|JpH;CQ^(aXA_bGK7Z^q*v2)7wIV566*6a-VwUu82mPU-(WHt z9QuO>OVD0N_x%<7;Ae!NU!^i+A{lL=E8{FD%L!lhCMDw_XaAb;-H@Z%k!O)5YZ%N?uLay^3RX^E>=i#}L` z2Ad%A-$yYKQGA`98S6t6*_E-n>20>MUpTDZ-5zNU>&osmzi>}ei=RHJcX3#44pQqj zJ415D;H=3U)_|V+vt&<<=&21Cxeuvyn&~1h(EIFuq&HYg)C8KwJjMsppR&mDVP0dp_2LQ=5$u9vGd)hEX>8^A zDEc|uJ6;!<>iD`<$)Bejo>iAZ)a{d~;_=WJpc@v%N_c2$LhJ5QNss3>TONrOf8 zpRjURL-(j~m)jAdF;@t&Jcvsq(qy)K!YJ-m4y%|j5^?=(!eW}tBJ^6PL9B{Dkm{NkfSz8YHkzsd_~}jQa0K7AH~xq8Mi}9U;6@tQUy1ft5#xX`VT%EO&FX z*8D6yJT1rjJ)Bkvd7nrry;eek44&00V~{~DCL03{LFq+CqPqm`VwNf^zz~?8oE2!` zRupBaRs|RW(vxvbT2a)iU&6I;g=%%L9oLI1idF}t2N<}OmwIK=O4S4+!D1&V{*aJp`NgxqrGa=p8 zM0ggGhg=1@6K!mQyoHJLc`w9gJ1o>tL6KRbvP-<(OWwXuQYa(d-^%yi!6;4-laG7JslO7#SUxhml#xy z7sd{$oC9ZKj>??(u?sOpG=-&1N}zvZ#gnw=KRbdABh!oIgYyE6!LyW2#Um3%3P()%E>R<8CCT}3Z3T=YeTpXE@CZzk=lE{tF2D1b~jMtNF2{9az=;0CZ%Fk*tAYcH&+Ee6RC2Gw`E8< zncdc@EHfd}>mP{NYs248pazvudGl4XT?tD)Hr8N-{g#=mGa-zcSa9MLyf-gQoDigu zd~5PBPw%MXb>5+BaU|wDT%SWU(jd92ED@P_cGcdb103C26_ujm=#8rAR41huSajO2 z=w{ZCwv2wm!qSWA$*Pai-MA?+_B7FM-D;nK>nk?9HN`=`ZPmvWOy=H|(}_z*-Wq+f z-755YZRqt{1Fwnf(d@J-Pi#uvnZ4GjuxkEe-MhVB(Y;<{;PowAH)j{su&y~epQ>eq zcL42kgiiynfg%nA5A;i{rL%W91C4w_J1C`&=Yrh z0pw1=i!_Z&r62FBvMiWDxzZf=&9h_ZsVbj^u_~@4hs|Deglo#Fk`|q$?hpFUqC)MX z9Cm!kbINIoU%GSjokM^7h`O&%)}t-AdgqLSY3 z>eCCLmvkwKTVhw1X(PV0)t~jW&=`-%ZxAoTSG>DbFt2E?{vu>F;d1F~U1crh*cH2Uh1O zuJ=8dy<`kA$Jq6?8PdGWF%n6%S;yJKE8|3MzU6_ONG0=mqY1XI2+?MZwQkSqv3JRnIXNNX|v{Z*{tL3+I&vDyRNUTwDYp%Aaar?&Vig% za-Ne)&to^S5m^i9$823zT3`X<^(Nq?x0R9^B^4f``ncwVa;W$$Yq9w}%KiX&aZoKM zkx%GY+RRCwpHP95Mtwp^UbQ<8C1Y!Ov>#|6FY3iS3woy0P%}$HSD9IQ!Q)OZBxu#+*)4U+=c=l*<-yljYV&uIiiJoVA#pSTTqG zwaU7}LFqx(xvGesW3Q}UOZTvQs~5X{D31(@#+`YLC9jE~{w#M*06-ZYZR>~E%6Jh+%|_DhtpUD+dI z>vM?o8(BTYB3d3uMU8D_a$_5}Jp}ivi$N*dFH5b@en@y34~O1O1>LRcc6K18J6UJW z6I#RC)@{Re!}AN`Yf#8nt7bW^H=LFSJRV#lxpyVh@;S$FGuTYbN6THOOibB9I9 z-1FBwzEe>BkQk$ziHoga(OZKdH=q3aVg-i?L$vNCx+C2=%Sd6#J^WG`(zLZ7Mf z-?UNXLf^!P+2X2qUS7k+F0&uaj+}Wk>!>MQTpD=PC|lfb`-u~=Yv`CHXQ@cOK{`$(4 zJo90zQq#v?_13G`IXaImd*g33vnu`nquXUQ=zvk8b*ZI5d-BA!B@ZdTeYEdEs;EJ_Xkg-*i1Y4Q_8u+4~+ z(XA36V2dlM%~a_+X|&|3;Y09Y31_0gb~Ro-l*C4)>D@|F>+>^KQjrf)JZyM9^sDS^ zX)Ie_;^VXUle|>dYJ93X;VII0oK}X@^J{E-Nw9fS7gynF;qWl!3{)75hwLiMZ4c(A zd{M>=A6_Oe*2Go+^NCln<&%Ft(QLi^gjefzmn)U?9lpFdXHo+l9gzI6Y30gCRCR}vPJc6Fluu$}V` zdZck*IwRm+|N>64PQ;9nikEKY-*R4?wy>{t9vsB!e6Qxw~6QYcASw=-bZ| zqO8bAJ#IKh{BI9#Nx8>*u)D{43taE%vFb7A_j;5XL>f}lgqaa(Tn%MuyC;OM>#f}v zFQ>J@Ht-6gwD_cVo(}6D*rDAEXc=qY{WH3krR~|n?(dnPiI2gVy~=;Dj%F^LhW|+c z$8^HSK7->u^fWLBWCDC4>ivt4C%g}608!u#puvl$Kcp5!fLf5tcD*yoygHHa9%3Ka z&~w2Cu=y#wQoakn_kt6k5?H_ma0LwXtoRM+<#^FJ1=>*l7_>j-*9pA~I1-7Or*Imm zR1LimD1*{Kx`BTmloxD1pb>&G$oU*(~&MS}>?4tpo)da67Z_RV0i8J8?j47P)T&JIIw zc?IEyEC=s`{ooK7@QI#<#Rnd#Xbda{+rd;23igA0pc!=<`l-bdT>%ZC5ty5Cxe0EA z7H|*T2aiD~=mHKv(U1nXfeUEtCb$i*^wS8bbTTlwHt3z;F=z)rvRg-zy_uLDc;#8l z6ey0x_`M5cvXpnHo3Fsy06G_9<$wC4O_5lXO;yUlf9aB3L3sm+Uxe)req?B57s~c7 z!WQ*diq!-^=9r1Hg<$bAOauIwUopzIgV^Qp1^@0hKRILbrfEXj`s_{FSnjF(O)EJJ<#Gf_Fh<7NVDf1OXYb0(%T{19%K> zgZp4V{0@O~a01+ftsMWiIt9HFRD)V@crD4`_oFZq4RylM4*deCLroy0VNi*^UybH(!+syX zuRza)ya3stbPLi@mJM4jsD=L(7GE0X>p&}QU@FkzMj2WT4-*35y9GkalC-Q zfnu;7>;ko5Y97W4ZiBt}-2&+k-i2-fY0wWr9tP#03vE4CBzOaDdx19SC%`Gt0Jg)Y z60-UQY@|jg3*mGR@;>0GYT$k$#hVa~jo3io5Ev-%flg7@jC%giQ=m_Uw18%C6ZYF+ zKkVf%p+2bGO!#FeYf<_F3)in(|H8}6w*RMD+kQ=WzYhr?1hgOwM1dGE6(j%=82aVF zFb0y1+pDMtGLd*vAlr}+(v;u8O-V?s^1Tlt%6B4ypb^x9E1(h_0^7lDuu@M*K6~ZB s?uggdInA`cBPYI>IGuez+=5Yi^uI#!28%ivs5yrZH>0cO98Bi^4>dPc!vFvP delta 8478 zcmaKx3s@9aw(s|@?uJ4^8WH8G)wC!NiH(Q>jo}pwp;f@gC>oQ-XAvP{5+~$gx&e)t z(FA8F6C9HxX7pU+sDU6EQ9EFwGcgnAf{z=Gmx)fI$mEzQB2HJ+-Sqhvk4!w@GBfZ5G~ud<;CIBa%qL+EAMR~t!gVQG9WK?lHzqt^9mxBw>W*G^Lt5Q ztmq?0D9{##El4O%mO^uvm2uL-r(eqo>&Wl56&z3wkdwAS54=5j+ypDbS2b2b)w|gD+&^{zy$8T72;0t4xD#ZAH-JwKTTmoivY@ z+DloDemdRG?D`4Te;5cqJDTusgBQRCupgWe9wfy$cpWw*o&Uz?YuGLTJNP|VGUPiS zy4v0xNUq}33QkVv_Jq!eOLvs96+wYQg}1(|R%xRo_MHwx1(nk^e8PJj`Tz93Y>dJc zWv>QJNzU`W*rln^ppYh5ds9F7w1Rw>t=U^suN+G%>!MN13Az7z`Pr`Ony-B8F|Zju zCs@?z3D%M)itAW`x?{5(odBCGRdrUbeQ#<+jD*xxw@+6w^`QS{l_AQ9`NznY31^?^|?DOhd`%qq|Sd#2B{4y}R88fAM{aEDPX<;KR3xw_Xc zww)%Vw_j0?3vVf(ndmgNh2z3D=!!i_6htC-drxHDvbJX!1yO6rP)zAWzTw59AcK|u z^pi?|8mM%uOYPdL9unKxVf#s~b3dtd{wKB0qn29ZOVl{~K#e0m)>!eD^7&7ye2yxE zn@M@I$*2{p?*-M2im8$wTCk|ZC}(IE6<3v1OADnisR&z7uw;}2HNlpu5|g;-rO}eE zPjhb(Cgy7FKVHXec5lostEst4s%{9DwBp_mk19TJTjh;8KH$sm^4+~xDZ##M$kn1BKcEyV(%swBvi5(n! zQ{7B!#!Xbkv2pXbWu?qLZoGOG8Jen!UxW&(xDh&r?F^l$SKD2Ib`zvGl^F&Uw1tl6 zu(RC=oj6J@yS}k5XPPu6x1fxT4twIEVfXyr7t52Sc=1~4XSV#_J_}!Ywe+|$J!r5( zvUD8l8jbx&*zyr|rBqJqOOWbH85eGX^|-P|KX_Ahx&1ZiO{FtwQDXw?tV1|#VfdPf ze?O@fwIxk!yo{rVGpL)skNow?ayyYvdJ`lc5v_d{9zLP2RNHfzqP3E`oXc4HCh@GI zn35~DDi=*e{(=QZ%vOhBVZ=mwm^~jcfv#h3MOZ>&ZMVVa8#vXf=g%C<%L>wxju94 zclZn<|K+559#-%~NW_s{!kVL6=x^A@@n%}ybZYz#Dg?T=W%adFd8A9Qq}mA~&AfR> zLqtV(3q4Ha(fw?VFzLzC{!zJtsFS6B!N^7X=L%6exy?)Di|*{2Y+0+xwxMUL-fLT( zZPR1nwCjoRZ9Un}U@MLlwep*6U-T|IpCuZN zGsf&E{7BK%JYxQ~h7w5|6)X8A(8HQfYFdd9w21KU_A-zvVqz=Jh5V;nIOoUNf}D*EKYvJbFlajd=9}!8t{4EL!x8Msz-uloARij z>)APpaB{5YR`Cfqz6r-e1CFcFSfn{NnqYU8X8Fj~tS}~IslO*?)dBcb{McX)8Vr1( z!5XxuxNog`6Mk#p7uu+XOk_)6%<5G8p@W34e-)=Y20&5k!1eEJ1ZZ%=L3iXnIg7y1N| z|8W#EFp4&2jSr!Zu(#rkv+nlQzv6N9xdL)M4zqjREB?7!@sIb~d_0c7c}R=jynNZ4 zjQo*#99)0fhom-H)Ei<&?l6@7fHPM6P5<6Q^R5btXp9<;;~hIVj$35?7J9C?DC^Ne>bEQI`BrBK?vT zKV*zBdv15BJL*x7zUk9wZO?S7dVKF9@*mm0hf+fBx-<I80C8M93tk8#~MwTR|0=Tw95F}F~rl{1;aG%hG0 zo$wi1fkcl639Pf4a!tWB>|N~ZMBa)~Otr6hkML@-Ng(oOwmE6CF7@TX&!_+?>58+*}Pl1)8NFrE3 zIZzOo4YC$wfO^mX+CV#~@h8GgP!m9et&mzjBIv=~5vYUf8}RYh5`hOh;d2=s=aCku z$FDDvG1fM1wDl?E@~VNiUqw}0bIgL6{A5d?6k|Rvgj;m-DyL3<(G_hbhDb@x3P#~g zg0Xc{(=qTu*n^E&5I7ntqIl1mHpHhJl`b!{@Foa zoxBXsh?6&Dcm}HDWyK}==N%WmD%QzyPLnivuBk4|J&rEY`u`E!i6A1VL8|A%x9FSN z$6B@{xtbbS!1Q!_ip`&HupahAnaAf+$ zl$Qk$oVi+)POfG7DQVaVcBDK^Ti6-=b~0y5qV@3>om>H?wJ6O2qOTYv#)@Nc5KQ!F z#aFZ5Y~{qP$T%?-mL9htBEKWlP?MF~%ENN|1mCEWyH1qncpZJMO0&P2TE-(+GnI`K zG1ADy)gAoVvfn9L5!BWy*ufcg?v9hKdHA2Sl&wfL&}(c<>I8bB z>D|;qN~4?pk#?Wb!lqlZ5;T5>zI^$qLboG|g{3D1-N4|yH0JemYSviFb4V*;OVU>a z-AclzJb~{Dpb|8JQ$QzM@gA5Vzh$#283l1-gYqizIIgnb1qS*jma-s* z9&cK)z=5NsX;FcLCiQ--KV6=q<`&x;9y8m-OUMwo53VZ(BmfU?thfRzqQbJQWttc# z&Ng3H7PFTYCeaRdbYVJO%fzvH6dWqdVE!$0yTVw(Ie!)WPhJzY#R-brWk;_4|UYTp1Polrvr=25pax zXyi3cbsPRKwriy!_-bFR+3KL#hi z4o3wQT=4NcJ-CH)a-WCAK5>LLvMW!lpam@H$sEkB7oJ?2tfteK@WvU6S*V7g9@dzV zNCV*M78-af}<7sUdl@)EaN#yOKvwsgRQ zhexe9Uw*l;&#}PS=NQdSSt4|6PIK~e?7C$svfAY0+=!PC5xxp=@>8cVCo*dq0z~a0 z-TR#UG<&QbUSL4 z`bFFfrRzIi?G-oYsAQW~&8H`uT32}}tz-5z)wF?Su3e8A@&4K(zt@%V(MecY^=#z2 zI4s(fb?Njj+q`ajjPp6dmp4aFqA})q(=aF0`|We*npM3%Y_(-=IVZo(4C{lR+~r=2 zSCv###z2|2XEFI^^;RXVV5>5-fRkTwuS4l#6Nlelm{Ny)%E|B6ZdI0`{Au@kl$4t^ z_ zRr+Q4MwdSCvpE`3FZp*|=%x~3(O8TA=8Q7-bV+zvMj4U!C~{Z9VZ!&mPk43Kxgm8; z`%5Ay(mwlB_vmrfxM4ef(@GbG9ET&{teNX|T=uGOIbO$t*0XGXY4GgJKbEu&mCS7Y z_D9=CLpD=u?~k@4L$*n+TGmqTnx?7g68?CD*Jelz{C8;z+eW3}dW{*Dm z9!+h!`RubApR`vI&e(djEsz*;>)4~@oa&#Vx+442bY|_2bsimXY zH&wG~Gc#1D(5q}|bte4-+f&_=@`%gp_}s0&WHcB>d_IMC2G|s0n$Pcd4%cgFa*2vDl7uqN{6ew%2j0l@Pws>sWuPJjb`0 zMAP^6BK@`3u^&0>T2@vQWqrcQHR$ae&NI$Tg^@Vt)*#rO2v+?zi&rze_8mD<-t2YI ze!R?Y3NQyOxLz_%qAtxnmi2J!$h;A`g;Iz#qjg?nM>ko#*s?P0u^ysLws;*sV4E{w zsghQ;<6F^g4bY>l>mIc&zdS#y`Ep4(8q@Z^i6h@PH`4NGYo0`><)Qi|kD9(dSXm9k zK2SN(9QZ&W0eSudfy_i8i!Ev>{|e-oTH_gFRKsyNzV0u#4+o@GBVs3Zq#|+Y*)cAx z7MDEkvDT}}yVy;pwS{JVM=5WwWro+%={v0Wwcx0C;6qF#10U(6_!h3mmc`xIPFwg? zI0mnd?S9RO9i;iSd_(Oq!hZqZVKB&f;TBEaa`@H5-p*ovHJR44`M)v_T+7Yl#O)1y zbbvS>55K~x726yA_hyD^S-{>4-K1Q{E_8Eay^d?{!5mkDSErjAiNU7Cn6$Y1iv8hN zG4uo0`Kwvf%EERUXYX*UUPs(M_-d`rLbc!Zc(`?-c`p`{oO*(9Ci0U`JYcui;p_D} zf`(S#DfYt7Idm&)-T4L=j-+N+Jf~H~7*@M$Ed8G4?+Rh3pG_@{p~NevqdiM?n4oavWrnTiri=46)FU zp2h^m^Z0$g-&~JFkFOhgrQgx!?svGsKl}R~ixKf}`v!#mmYkuIr_#TWVN(*Dc!@0YHLSw8miU#`0{>)usgLTU0O0e z**8V)HqydvGx6^hkoXAU*MiN^UjSP`CBT=OfxoiZ`1%fh_Vfcs$h&Z^(Aeg#Q;CkO*kzyOBJ zVxY%?#7x3kna(IM#c0Qg8C<2*7q(Bb)u7q9!ia{Jm1W91H{2=tBU^m#4 zZ$(d_oB_iQ*Pw^Ih>?cu1Q$RDxB`ZKO6C%N8<>-W#=vfH25bT=K?ev!xnBWBVTc|) zArGJ^(*ZvaV8u@m2mxUr3dDd!kOWdd8kh|-ffGRlpur&Efv%z(y1{U823#kC7!U`3 zZnB;)#62(Ir*ScQ3RFisuFru=miyK$s|QxP1kL?|@bkgXHC2YPO<)W7-)`waIbDi& zmSL8IpKI?N%FZt%>-ae<@HD~CIqpE&F0gwgx&eO9&yKP)pzKNbf(QIq$#2rFv)5oG z*I@yIbD#&LJVp2x3kC(80q4MZZ~^F6VM{=HWijR&^gWR8gBa*RAPRKA?+WMyH$ebw z2k~#-ThP0~UC;xrtta_>2P*G?Ln34xq!Y3mH@FXnGpq5a)W(4m*BWICg4mI>??Hf#;0hQnm=8S-Wqy!_U<>q3koSQf^Z>{p&;h;km#7cAH)E@W zEd+#tB~Nd7dgJq~f6p(9tN)YmV-6EO6hr|dhyznW3YZ15K+cdH4r6#v$;94M1a@Hm z*aB&QtW>W-CiHEr`M3MxI(K3Ofo>N@7SaQ{!4+@@1i`-AM96b&%icHU*fw~r6gTqX u3xwA@ct^h|JlKi<8iq|VgSzFLu|z) Date: Thu, 7 Dec 2023 15:27:16 +1100 Subject: [PATCH 0211/1335] AP_ExternalAHRS: avoid uart owner issue ensure we own uart before read --- libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp | 2 ++ libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp | 2 ++ 2 files changed, 4 insertions(+) diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp index 0ab6857f63ca39..a20beb13c0e920 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp @@ -156,6 +156,8 @@ bool AP_ExternalAHRS_InertialLabs::check_uart() if (!setup_complete) { return false; } + // ensure we own the uart + uart->begin(0); uint32_t n = uart->available(); if (n == 0) { return false; diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp index 13acaf4fc993c3..66c20f05590e22 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp @@ -208,6 +208,8 @@ bool AP_ExternalAHRS_VectorNav::check_uart() return false; } WITH_SEMAPHORE(state.sem); + // ensure we own the uart + uart->begin(0); uint32_t n = uart->available(); if (n == 0) { return false; From 74c2855be383e68ebd3c46e0c53257926a50ff40 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 19 Dec 2023 09:53:32 +1100 Subject: [PATCH 0212/1335] HAL_SITL: implement begin(0) on UARTs the begin(0) is used to claim a uart for the current thread in ChibiOS, we need to ignore it on SITL and not change baudrate --- libraries/AP_HAL_SITL/UARTDriver.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/libraries/AP_HAL_SITL/UARTDriver.cpp b/libraries/AP_HAL_SITL/UARTDriver.cpp index 900ef64ab61628..401fb17a0ce395 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.cpp +++ b/libraries/AP_HAL_SITL/UARTDriver.cpp @@ -56,6 +56,12 @@ bool UARTDriver::_console; void UARTDriver::_begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace) { + if (baud == 0 && rxSpace == 0 && txSpace == 0) { + // this is a claim of the uart for the current thread, which + // is currently not implemented in SITL + return; + } + if (_portNumber >= ARRAY_SIZE(_sitlState->_serial_path)) { AP_HAL::panic("port number out of range; you may need to extend _sitlState->_serial_path"); } From 813c732a839e8a889a3e0237541b644869c18a96 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Wed, 6 Dec 2023 15:01:07 -0800 Subject: [PATCH 0213/1335] AP_Baro: slow down Baro offset slew --- libraries/AP_Baro/AP_Baro.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Baro/AP_Baro.cpp b/libraries/AP_Baro/AP_Baro.cpp index 874f4e054ad405..5435ae060c86cc 100644 --- a/libraries/AP_Baro/AP_Baro.cpp +++ b/libraries/AP_Baro/AP_Baro.cpp @@ -899,7 +899,7 @@ void AP_Baro::update(void) if (fabsf(_alt_offset - _alt_offset_active) > 0.01f) { // If there's more than 1cm difference then slowly slew to it via LPF. // The EKF does not like step inputs so this keeps it happy. - _alt_offset_active = (0.95f*_alt_offset_active) + (0.05f*_alt_offset); + _alt_offset_active = (0.98f*_alt_offset_active) + (0.02f*_alt_offset); } else { _alt_offset_active = _alt_offset; } From 7a9c6eea9cc59fa0be11e7e1f8a281a6bc4a9b34 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Tue, 19 Dec 2023 15:55:00 -0800 Subject: [PATCH 0214/1335] AP_Landing: move wind helper functions to AP_AHRS --- libraries/AP_Landing/AP_Landing.cpp | 27 ----------------------- libraries/AP_Landing/AP_Landing.h | 2 -- libraries/AP_Landing/AP_Landing_Slope.cpp | 2 +- 3 files changed, 1 insertion(+), 30 deletions(-) diff --git a/libraries/AP_Landing/AP_Landing.cpp b/libraries/AP_Landing/AP_Landing.cpp index 8a5800d3179d74..211ecdd46f1da3 100644 --- a/libraries/AP_Landing/AP_Landing.cpp +++ b/libraries/AP_Landing/AP_Landing.cpp @@ -548,33 +548,6 @@ bool AP_Landing::get_target_altitude_location(Location &location) } } -/* - * Determine how aligned heading_deg is with the wind. Return result - * is 1.0 when perfectly aligned heading into wind, -1 when perfectly - * aligned with-wind, and zero when perfect cross-wind. There is no - * distinction between a left or right cross-wind. Wind speed is ignored - */ -float AP_Landing::wind_alignment(const float heading_deg) -{ - const Vector3f wind = ahrs.wind_estimate(); - const float wind_heading_rad = atan2f(-wind.y, -wind.x); - return cosf(wind_heading_rad - radians(heading_deg)); -} - -/* - * returns head-wind in m/s, 0 for tail-wind. - */ -float AP_Landing::head_wind(void) -{ - const float alignment = wind_alignment(ahrs.yaw_sensor*0.01f); - - if (alignment <= 0) { - return 0; - } - - return alignment * ahrs.wind_estimate().length(); -} - /* * returns target airspeed in cm/s depending on flight stage */ diff --git a/libraries/AP_Landing/AP_Landing.h b/libraries/AP_Landing/AP_Landing.h index b9cfc80e888a9e..5022412d9552df 100644 --- a/libraries/AP_Landing/AP_Landing.h +++ b/libraries/AP_Landing/AP_Landing.h @@ -91,8 +91,6 @@ class AP_Landing { // helper functions bool restart_landing_sequence(void); - float wind_alignment(const float heading_deg); - float head_wind(void); int32_t get_target_airspeed_cm(void); // accessor functions for the params and states diff --git a/libraries/AP_Landing/AP_Landing_Slope.cpp b/libraries/AP_Landing/AP_Landing_Slope.cpp index 7c7a9da3253b2a..4ec0c7cfa7c15d 100644 --- a/libraries/AP_Landing/AP_Landing_Slope.cpp +++ b/libraries/AP_Landing/AP_Landing_Slope.cpp @@ -368,7 +368,7 @@ int32_t AP_Landing::type_slope_get_target_airspeed_cm(void) // when landing, add half of head-wind. const float head_wind_comp = constrain_float(wind_comp, 0.0f, 100.0f)*0.01; - const int32_t head_wind_compensation_cm = head_wind() * head_wind_comp * 100; + const int32_t head_wind_compensation_cm = ahrs.head_wind() * head_wind_comp * 100; const uint32_t max_airspeed_cm = AP_Landing::allow_max_airspeed_on_land() ? aparm.airspeed_max*100 : aparm.airspeed_cruise_cm; From 39e7209e33e7688304eecde7ee79f3f20126cdab Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Tue, 19 Dec 2023 15:55:33 -0800 Subject: [PATCH 0215/1335] AP_AHRS: move wind helper functions from AP_Landing --- libraries/AP_AHRS/AP_AHRS.cpp | 26 ++++++++++++++++++++++++++ libraries/AP_AHRS/AP_AHRS.h | 9 +++++++++ 2 files changed, 35 insertions(+) diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index c48b06bfd3773d..efec6b0e9de96c 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -812,6 +812,32 @@ bool AP_AHRS::_wind_estimate(Vector3f &wind) const return false; } + +/* + * Determine how aligned heading_deg is with the wind. Return result + * is 1.0 when perfectly aligned heading into wind, -1 when perfectly + * aligned with-wind, and zero when perfect cross-wind. There is no + * distinction between a left or right cross-wind. Wind speed is ignored + */ +float AP_AHRS::wind_alignment(const float heading_deg) const +{ + Vector3f wind; + if (!wind_estimate(wind)) { + return 0; + } + const float wind_heading_rad = atan2f(-wind.y, -wind.x); + return cosf(wind_heading_rad - radians(heading_deg)); +} + +/* + * returns forward head-wind component in m/s. Negative means tail-wind. + */ +float AP_AHRS::head_wind(void) const +{ + const float alignment = wind_alignment(yaw_sensor*0.01f); + return alignment * wind_estimate().xy().length(); +} + /* return true if the current AHRS airspeed estimate is directly derived from an airspeed sensor */ diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index 1d6841a28a0dde..f8c87da36fd49f 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -114,6 +114,15 @@ class AP_AHRS { // return a wind estimation vector, in m/s; returns 0,0,0 on failure bool wind_estimate(Vector3f &wind) const; + // Determine how aligned heading_deg is with the wind. Return result + // is 1.0 when perfectly aligned heading into wind, -1 when perfectly + // aligned with-wind, and zero when perfect cross-wind. There is no + // distinction between a left or right cross-wind. Wind speed is ignored + float wind_alignment(const float heading_deg) const; + + // returns forward head-wind component in m/s. Negative means tail-wind + float head_wind(void) const; + // instruct DCM to update its wind estimate: void estimate_wind() { #if AP_AHRS_DCM_ENABLED From 47fdf2295cbc742676f5b1b04e2137c9ce3b0c59 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Tue, 19 Dec 2023 17:41:28 -0800 Subject: [PATCH 0216/1335] AP_Scripting: add bindings for ahrs.wind_alignment and ahrs.head_wind --- libraries/AP_Scripting/docs/docs.lua | 12 ++++++++++++ .../AP_Scripting/generator/description/bindings.desc | 2 ++ 2 files changed, 14 insertions(+) diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index 7e3be1f487dba4..8bded69e237c33 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -3008,6 +3008,18 @@ function ahrs:groundspeed_vector() end ---@return Vector3f_ud function ahrs:wind_estimate() end +-- Determine how aligned heading_deg is with the wind. Return result +-- is 1.0 when perfectly aligned heading into wind, -1 when perfectly +-- aligned with-wind, and zero when perfect cross-wind. There is no +-- distinction between a left or right cross-wind. Wind speed is ignored +---@param heading_deg number +---@return number +function ahrs:wind_alignment(heading_deg) end + +-- Forward head-wind component in m/s. Negative means tail-wind +---@return number +function ahrs:head_wind() end + -- desc ---@return number|nil function ahrs:get_hagl() end diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index 94557841c84a0e..1ce091781525cf 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -38,6 +38,8 @@ singleton AP_AHRS method get_gyro Vector3f singleton AP_AHRS method get_accel Vector3f singleton AP_AHRS method get_hagl boolean float'Null singleton AP_AHRS method wind_estimate Vector3f +singleton AP_AHRS method wind_alignment float'skip_check float'skip_check +singleton AP_AHRS method head_wind float'skip_check singleton AP_AHRS method groundspeed_vector Vector2f singleton AP_AHRS method get_velocity_NED boolean Vector3f'Null singleton AP_AHRS method get_relative_position_NED_home boolean Vector3f'Null From 1f78cb29b43d65e32f55e4af219da5fb35a683c1 Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Tue, 19 Dec 2023 11:24:08 -0600 Subject: [PATCH 0217/1335] Plane: correct TKOFF_LVL_ALT metadata --- ArduPlane/mode_takeoff.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/mode_takeoff.cpp b/ArduPlane/mode_takeoff.cpp index db212361c398e8..c303d459b27ff3 100644 --- a/ArduPlane/mode_takeoff.cpp +++ b/ArduPlane/mode_takeoff.cpp @@ -17,7 +17,7 @@ const AP_Param::GroupInfo ModeTakeoff::var_info[] = { // @Param: LVL_ALT // @DisplayName: Takeoff mode altitude level altitude - // @Description: This is the altitude below which the wings are held level for TAKEOFF and AUTO modes. Below this altitude, roll demand is restricted to LEVEL_ROLL_LIMIT. Normal-flight roll restriction resumes above TKOFF_LVL_ALT*2 or TKOFF_ALT, whichever is lower. Roll limits are scaled while between those altitudes for a smooth transition. + // @Description: This is the altitude below which the wings are held level for TAKEOFF and AUTO modes. Below this altitude, roll demand is restricted to LEVEL_ROLL_LIMIT. Normal-flight roll restriction resumes above TKOFF_LVL_ALT*3 or TKOFF_ALT, whichever is lower. Roll limits are scaled while between TKOFF_LVL_ALT and those altitudes for a smooth transition. // @Range: 0 50 // @Increment: 1 // @Units: m From ea3dc78a9656d0487feef8b2ff3493be5f1f1c8e Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Sun, 24 Dec 2023 08:57:43 -0600 Subject: [PATCH 0218/1335] AP_Relay:correct function param metadata Co-authored-by: Peter Hall <33176108+IamPete1@users.noreply.github.com> --- libraries/AP_Relay/AP_Relay_Params.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Relay/AP_Relay_Params.cpp b/libraries/AP_Relay/AP_Relay_Params.cpp index c5381188068f21..c6734fb9b93501 100644 --- a/libraries/AP_Relay/AP_Relay_Params.cpp +++ b/libraries/AP_Relay/AP_Relay_Params.cpp @@ -5,11 +5,11 @@ const AP_Param::GroupInfo AP_Relay_Params::var_info[] = { // @Param: FUNCTION // @DisplayName: Relay function // @Description: The function the relay channel is mapped to. - // @Values: 0:None - // @Values: 1:Relay + // @Values{Copter, Rover, Plane, Blimp,Sub}: 0:None + // @Values{Copter, Rover, Plane, Blimp,Sub}: 1:Relay // @Values{Plane}: 2:Ignition // @Values{Plane, Copter}: 3:Parachute - // @Values: 4:Camera + // @Values{Copter, Rover, Plane, Blimp,Sub}: 4:Camera // @Values{Rover}: 5:Bushed motor reverse 1 throttle or throttle-left or omni motor 1 // @Values{Rover}: 6:Bushed motor reverse 2 throttle-right or omni motor 2 // @Values{Rover}: 7:Bushed motor reverse 3 omni motor 3 @@ -28,7 +28,7 @@ const AP_Param::GroupInfo AP_Relay_Params::var_info[] = { // @Param: DEFAULT // @DisplayName: Relay default state - // @Description: Should the relay default to on or off, this only applies to function Relay. All other uses will pick the appropriate default output state. + // @Description: Should the relay default to on or off, this only applies to RELAYx_FUNC "Relay" (1). All other uses will pick the appropriate default output state from within the controlling function's parameters. // @Values: 0: Off,1:On,2:NoChange // @User: Standard AP_GROUPINFO("DEFAULT", 3, AP_Relay_Params, default_state, (float)DefaultState::OFF), From 46171a7c79637c57d44223c85de6ac2364b3e0b6 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 20 Dec 2023 07:40:51 +1100 Subject: [PATCH 0219/1335] hwdef: give a more useful error message on no bootloader --- libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index dab87f0af3873b..cec867a6dc6934 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -2430,8 +2430,10 @@ def embed_bootloader(self, f): bp = self.bootloader_path() if not os.path.exists(bp): - self.error("Bootloader (%s) does not exist and AP_BOOTLOADER_FLASHING_ENABLED" % - (bp,)) + self.error('''Bootloader (%s) does not exist and AP_BOOTLOADER_FLASHING_ENABLED +Please run: Tools/scripts/build_bootloaders.py %s +''' % + (bp,os.path.basename(os.path.dirname(args.hwdef[0])))) bp = os.path.realpath(bp) From 6c2a7b8cfdbd017ca22a539e275457b1b7e71ec3 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 20 Dec 2023 09:03:01 +1100 Subject: [PATCH 0220/1335] AP_SerialManager: expose HAVE_SERIAL_xxx in config --- .../AP_SerialManager/AP_SerialManager.cpp | 31 ------------------- .../AP_SerialManager_config.h | 31 +++++++++++++++++++ 2 files changed, 31 insertions(+), 31 deletions(-) diff --git a/libraries/AP_SerialManager/AP_SerialManager.cpp b/libraries/AP_SerialManager/AP_SerialManager.cpp index 5b961da0722eac..24a694e2d074b4 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.cpp +++ b/libraries/AP_SerialManager/AP_SerialManager.cpp @@ -28,37 +28,6 @@ #include "AP_SerialManager.h" #include -#ifndef HAL_HAVE_SERIAL0 -#define HAL_HAVE_SERIAL0 HAL_NUM_SERIAL_PORTS > 0 -#endif -#ifndef HAL_HAVE_SERIAL1 -#define HAL_HAVE_SERIAL1 HAL_NUM_SERIAL_PORTS > 1 -#endif -#ifndef HAL_HAVE_SERIAL2 -#define HAL_HAVE_SERIAL2 HAL_NUM_SERIAL_PORTS > 2 -#endif -#ifndef HAL_HAVE_SERIAL3 -#define HAL_HAVE_SERIAL3 HAL_NUM_SERIAL_PORTS > 3 -#endif -#ifndef HAL_HAVE_SERIAL4 -#define HAL_HAVE_SERIAL4 HAL_NUM_SERIAL_PORTS > 4 -#endif -#ifndef HAL_HAVE_SERIAL5 -#define HAL_HAVE_SERIAL5 HAL_NUM_SERIAL_PORTS > 5 -#endif -#ifndef HAL_HAVE_SERIAL6 -#define HAL_HAVE_SERIAL6 HAL_NUM_SERIAL_PORTS > 6 -#endif -#ifndef HAL_HAVE_SERIAL7 -#define HAL_HAVE_SERIAL7 HAL_NUM_SERIAL_PORTS > 7 -#endif -#ifndef HAL_HAVE_SERIAL8 -#define HAL_HAVE_SERIAL8 HAL_NUM_SERIAL_PORTS > 8 -#endif -#ifndef HAL_HAVE_SERIAL9 -#define HAL_HAVE_SERIAL9 HAL_NUM_SERIAL_PORTS > 9 -#endif - extern const AP_HAL::HAL& hal; #ifndef DEFAULT_SERIAL0_PROTOCOL diff --git a/libraries/AP_SerialManager/AP_SerialManager_config.h b/libraries/AP_SerialManager/AP_SerialManager_config.h index 386d15dbfbc4e7..88bf3ccaa3c7db 100644 --- a/libraries/AP_SerialManager/AP_SerialManager_config.h +++ b/libraries/AP_SerialManager/AP_SerialManager_config.h @@ -136,3 +136,34 @@ #define AP_SERIALMANAGER_IMUOUT_BAUD 921600 #define AP_SERIALMANAGER_IMUOUT_BUFSIZE_RX 128 #define AP_SERIALMANAGER_IMUOUT_BUFSIZE_TX 2048 + +#ifndef HAL_HAVE_SERIAL0 +#define HAL_HAVE_SERIAL0 HAL_NUM_SERIAL_PORTS > 0 +#endif +#ifndef HAL_HAVE_SERIAL1 +#define HAL_HAVE_SERIAL1 HAL_NUM_SERIAL_PORTS > 1 +#endif +#ifndef HAL_HAVE_SERIAL2 +#define HAL_HAVE_SERIAL2 HAL_NUM_SERIAL_PORTS > 2 +#endif +#ifndef HAL_HAVE_SERIAL3 +#define HAL_HAVE_SERIAL3 HAL_NUM_SERIAL_PORTS > 3 +#endif +#ifndef HAL_HAVE_SERIAL4 +#define HAL_HAVE_SERIAL4 HAL_NUM_SERIAL_PORTS > 4 +#endif +#ifndef HAL_HAVE_SERIAL5 +#define HAL_HAVE_SERIAL5 HAL_NUM_SERIAL_PORTS > 5 +#endif +#ifndef HAL_HAVE_SERIAL6 +#define HAL_HAVE_SERIAL6 HAL_NUM_SERIAL_PORTS > 6 +#endif +#ifndef HAL_HAVE_SERIAL7 +#define HAL_HAVE_SERIAL7 HAL_NUM_SERIAL_PORTS > 7 +#endif +#ifndef HAL_HAVE_SERIAL8 +#define HAL_HAVE_SERIAL8 HAL_NUM_SERIAL_PORTS > 8 +#endif +#ifndef HAL_HAVE_SERIAL9 +#define HAL_HAVE_SERIAL9 HAL_NUM_SERIAL_PORTS > 9 +#endif From 83cfcd841bae3c8b9fba6d00c4accbd23266d189 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 20 Dec 2023 07:40:30 +1100 Subject: [PATCH 0221/1335] AP_Periph: added support for SERIAL_OPTIONS allows for options and flow control per serial port --- Tools/AP_Periph/AP_Periph.cpp | 4 + Tools/AP_Periph/AP_Periph.h | 5 ++ Tools/AP_Periph/Parameters.cpp | 6 ++ Tools/AP_Periph/Parameters.h | 1 + Tools/AP_Periph/serial_options.cpp | 110 +++++++++++++++++++++++++ Tools/AP_Periph/serial_options.h | 30 +++++++ Tools/AP_Periph/serial_options_dev.cpp | 47 +++++++++++ 7 files changed, 203 insertions(+) create mode 100644 Tools/AP_Periph/serial_options.cpp create mode 100644 Tools/AP_Periph/serial_options.h create mode 100644 Tools/AP_Periph/serial_options_dev.cpp diff --git a/Tools/AP_Periph/AP_Periph.cpp b/Tools/AP_Periph/AP_Periph.cpp index 4d5cfdcbea1558..85672d9d62f636 100644 --- a/Tools/AP_Periph/AP_Periph.cpp +++ b/Tools/AP_Periph/AP_Periph.cpp @@ -140,6 +140,10 @@ void AP_Periph_FW::init() node_stats.init(); #endif +#ifdef HAL_PERIPH_ENABLE_SERIAL_OPTIONS + serial_options.init(); +#endif + #ifdef HAL_PERIPH_ENABLE_GPS if (gps.get_type(0) != AP_GPS::GPS_Type::GPS_TYPE_NONE && g.gps_port >= 0) { serial_manager.set_protocol_and_baud(g.gps_port, AP_SerialManager::SerialProtocol_GPS, AP_SERIALMANAGER_GPS_BAUD); diff --git a/Tools/AP_Periph/AP_Periph.h b/Tools/AP_Periph/AP_Periph.h index 26468de8c1e6a5..97c89cdd3b5b24 100644 --- a/Tools/AP_Periph/AP_Periph.h +++ b/Tools/AP_Periph/AP_Periph.h @@ -36,6 +36,7 @@ #include "rc_in.h" #include "batt_balance.h" #include "networking.h" +#include "serial_options.h" #include #if HAL_NMEA_OUTPUT_ENABLED && !(HAL_GCS_ENABLED && defined(HAL_PERIPH_ENABLE_GPS)) @@ -331,6 +332,10 @@ class AP_Periph_FW { void batt_balance_update(); BattBalance battery_balance; #endif + +#ifdef HAL_PERIPH_ENABLE_SERIAL_OPTIONS + SerialOptions serial_options; +#endif #if AP_TEMPERATURE_SENSOR_ENABLED AP_TemperatureSensor temperature_sensor; diff --git a/Tools/AP_Periph/Parameters.cpp b/Tools/AP_Periph/Parameters.cpp index 27c985a3bf6218..2faf850167d598 100644 --- a/Tools/AP_Periph/Parameters.cpp +++ b/Tools/AP_Periph/Parameters.cpp @@ -610,6 +610,12 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { GOBJECT(battery_balance, "BAL", BattBalance), #endif +#ifdef HAL_PERIPH_ENABLE_SERIAL_OPTIONS + // @Group: UART + // @Path: serial_options.cpp + GOBJECT(serial_options, "UART", SerialOptions), +#endif + // NOTE: sim parameters should go last #if AP_SIM_ENABLED // @Group: SIM_ diff --git a/Tools/AP_Periph/Parameters.h b/Tools/AP_Periph/Parameters.h index ff64f16d1e9508..9ff079217a22ec 100644 --- a/Tools/AP_Periph/Parameters.h +++ b/Tools/AP_Periph/Parameters.h @@ -88,6 +88,7 @@ class Parameters { k_param_can_terminate0, k_param_can_terminate1, k_param_can_terminate2, + k_param_serial_options, }; AP_Int16 format_version; diff --git a/Tools/AP_Periph/serial_options.cpp b/Tools/AP_Periph/serial_options.cpp new file mode 100644 index 00000000000000..cc480eee5b7f77 --- /dev/null +++ b/Tools/AP_Periph/serial_options.cpp @@ -0,0 +1,110 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ +/* + serial options support, for serial over DroneCAN + */ + +#include "AP_Periph.h" + +#ifdef HAL_PERIPH_ENABLE_SERIAL_OPTIONS + +#include "serial_options.h" +#include + +extern const AP_HAL::HAL &hal; + +const AP_Param::GroupInfo SerialOptions::var_info[] { + +#if HAL_HAVE_SERIAL0 + // @Group: 0_ + // @Path: serial_options_dev.cpp + AP_SUBGROUPINFO(devs[0], "0_", 1, SerialOptions, SerialOptionsDev), +#endif + +#if HAL_HAVE_SERIAL1 + // @Group: 1_ + // @Path: serial_options_dev.cpp + AP_SUBGROUPINFO(devs[1], "1_", 2, SerialOptions, SerialOptionsDev), +#endif + +#if HAL_HAVE_SERIAL2 + // @Group: 2_ + // @Path: serial_options_dev.cpp + AP_SUBGROUPINFO(devs[2], "2_", 3, SerialOptions, SerialOptionsDev), +#endif + +#if HAL_HAVE_SERIAL3 + // @Group: 3_ + // @Path: serial_options_dev.cpp + AP_SUBGROUPINFO(devs[3], "3_", 4, SerialOptions, SerialOptionsDev), +#endif + +#if HAL_HAVE_SERIAL4 + // @Group: 4_ + // @Path: serial_options_dev.cpp + AP_SUBGROUPINFO(devs[4], "4_", 5, SerialOptions, SerialOptionsDev), +#endif + +#if HAL_HAVE_SERIAL5 + // @Group: 5_ + // @Path: serial_options_dev.cpp + AP_SUBGROUPINFO(devs[5], "5_", 6, SerialOptions, SerialOptionsDev), +#endif + +#if HAL_HAVE_SERIAL6 + // @Group: 6_ + // @Path: serial_options_dev.cpp + AP_SUBGROUPINFO(devs[6], "6_", 7, SerialOptions, SerialOptionsDev), +#endif + +#if HAL_HAVE_SERIAL7 + // @Group: 7_ + // @Path: serial_options_dev.cpp + AP_SUBGROUPINFO(devs[7], "7_", 8, SerialOptions, SerialOptionsDev), +#endif + +#if HAL_HAVE_SERIAL8 + // @Group: 8_ + // @Path: serial_options_dev.cpp + AP_SUBGROUPINFO(devs[8], "8_", 9, SerialOptions, SerialOptionsDev), +#endif + +#if HAL_HAVE_SERIAL9 + // @Group: 9_ + // @Path: serial_options_dev.cpp + AP_SUBGROUPINFO(devs[9], "9_", 10, SerialOptions, SerialOptionsDev), +#endif + + AP_GROUPEND +}; + +SerialOptions::SerialOptions(void) +{ + AP_Param::setup_object_defaults(this, var_info); +} + +void SerialOptions::init(void) +{ + for (uint8_t i=0; iset_options(d.options); + uart->set_flow_control(AP_HAL::UARTDriver::flow_control(d.rtscts.get())); + } + } +} + +#endif // HAL_PERIPH_ENABLE_SERIAL_OPTIONS diff --git a/Tools/AP_Periph/serial_options.h b/Tools/AP_Periph/serial_options.h new file mode 100644 index 00000000000000..d71bdf43138117 --- /dev/null +++ b/Tools/AP_Periph/serial_options.h @@ -0,0 +1,30 @@ +#pragma once + +#ifdef HAL_PERIPH_ENABLE_SERIAL_OPTIONS + +#ifndef HAL_UART_NUM_SERIAL_PORTS +#define HAL_UART_NUM_SERIAL_PORTS AP_HAL::HAL::num_serial +#endif + +class SerialOptionsDev { +public: + SerialOptionsDev(void); + static const struct AP_Param::GroupInfo var_info[]; + AP_Int32 options; + AP_Int8 rtscts; +}; + +class SerialOptions { +public: + friend class AP_Periph_FW; + SerialOptions(void); + void init(void); + + static const struct AP_Param::GroupInfo var_info[]; + +private: + SerialOptionsDev devs[HAL_UART_NUM_SERIAL_PORTS]; +}; + + +#endif // HAL_PERIPH_ENABLE_SERIAL_OPTIONS diff --git a/Tools/AP_Periph/serial_options_dev.cpp b/Tools/AP_Periph/serial_options_dev.cpp new file mode 100644 index 00000000000000..26ba2bb137453c --- /dev/null +++ b/Tools/AP_Periph/serial_options_dev.cpp @@ -0,0 +1,47 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ +/* + serial options support, for serial over DroneCAN + */ + +#include "AP_Periph.h" + +#ifdef HAL_PERIPH_ENABLE_SERIAL_OPTIONS + +#include "serial_options.h" + +SerialOptionsDev::SerialOptionsDev(void) +{ + AP_Param::setup_object_defaults(this, var_info); +} + +const AP_Param::GroupInfo SerialOptionsDev::var_info[] { + + // @Param: OPTIONS + // @DisplayName: Serial options + // @Description: Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire. The Swap option allows the RX and TX pins to be swapped on STM32F7 based boards. + // @Bitmask: 0:InvertRX, 1:InvertTX, 2:HalfDuplex, 3:SwapTXRX, 4: RX_PullDown, 5: RX_PullUp, 6: TX_PullDown, 7: TX_PullUp, 8: RX_NoDMA, 9: TX_NoDMA, 10: Don't forward mavlink to/from, 11: DisableFIFO, 12: Ignore Streamrate + AP_GROUPINFO("OPTIONS", 1, SerialOptionsDev, options, 0), + + // @Param: RTSCTS + // @DisplayName: Serial1 flow control + // @Description: Enable flow control. You must have the RTS and CTS pins available on the port. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup. + // @Values: 0:Disabled,1:Enabled,2:Auto + AP_GROUPINFO("RTSCTS", 2, SerialOptionsDev, rtscts, float(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE)), + + AP_GROUPEND +}; + +#endif // HAL_PERIPH_ENABLE_SERIAL_OPTIONS From e94ab529cc3cc074ae6c1c1fba10d06b8d7ddb06 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 20 Dec 2023 07:41:09 +1100 Subject: [PATCH 0222/1335] waf: enable periph serial options in SITL periph --- Tools/ardupilotwaf/boards.py | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index d785c6161b82d6..2c9432d85eb652 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -849,6 +849,7 @@ def configure_env(self, cfg, env): HAL_PERIPH_ENABLE_RPM = 1, HAL_PERIPH_ENABLE_RC_OUT = 1, HAL_PERIPH_ENABLE_ADSB = 1, + HAL_PERIPH_ENABLE_SERIAL_OPTIONS = 1, AP_ICENGINE_ENABLED = 0, AP_AIRSPEED_ENABLED = 1, AP_AIRSPEED_AUTOCAL_ENABLE = 0, From e5f1c6e27de785f06a8600e67e789bfaa3e7ecc8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 20 Dec 2023 09:03:50 +1100 Subject: [PATCH 0223/1335] Tools: added MatekL431-Serial bootloader --- Tools/bootloaders/MatekL431-Serial_bl.bin | Bin 0 -> 17668 bytes 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100755 Tools/bootloaders/MatekL431-Serial_bl.bin diff --git a/Tools/bootloaders/MatekL431-Serial_bl.bin b/Tools/bootloaders/MatekL431-Serial_bl.bin new file mode 100755 index 0000000000000000000000000000000000000000..80b78370907fa835cf3efa8e324d91e8898dc12b GIT binary patch literal 17668 zcmd6PeRxw<*6%*&B+W^h(v%kH7my|e0x1|;&?=6mX?hARQWSVEg7ccTq9+B13gZll zN=mC!`51wsLMzIM&Zx-P7OGUNK|UNAbta)O(}KR%(J|2aancWRXxg6p+ez`onR}o6 z+&}K~+&<6F{#twQwb$Nzt+m(Mr$kGPO$_1BmOBmke?JIf4+qd=^T64Tt zLQUJ4RgKp84TSwc(7(IPSwX_u{jUDEs-NPl)GTY<@X+=97w|etrRqSA3 z;)3Msa;d0GE3S9k=DicO4g@(sjLAQN;UsB@la3E3EgW~pn-1>6QdyN&TX;1*M*svrIMN78Mb^N z>wPE1eL~x}hAnNEq-Th^x-X&DBJ3|DMowCMbtJ$^oih1iBtVGVLZpNdPMSBQ5jbhv zkXrB^n_m2q<0c=ILw~0gPm>h3-Z9rNHv{LPS%Rb2@Jk})5AjVTbE?2dZ_3LLb4DWF zCe!@frgXICe4O;3Lo`oEoG>(|iAYYFNGpbj^w}`lC~DzIE0OAlO8OtIG^3x7DzUm~>B>A%d@iIiy2r@NJy+zx| z7bjP87JbJTmx#oxS)K((>i6ld+{P9Y(+XE*A*EXlf}w?x?v!m!=3>s2T4|2d8rn?7 zrlNEqMPz2nK2=Vg4tXooiEmk$Qi->@l2_Jx0W~b#IqQU1nRxNtwUn z++~tog>~5{RAWCI3fltL@FV*PZ$zN$O$@AETa+j+=yj95&1rfPW^xi;F~!NEvv+an z=4PU2!YoO4d73K=ljz(c^CKAslS&}ci^E(o_p#Ac>Pi;(y9{l_yW?SHGWJQ{p@GGZ z#|3ZYfAOZh_u;V`Ax<#7MlwEJtob;xZoW9B!T#X zi8)tbrMm~?fHih>74g2+M?5c9oXV)$B7DCMbN1yEp3W<4q507ZjULQr<*{k6ThRB0 z5sg4B4*x!RpX;Mpw{d3H%ZL9EXy>9->`&dCxH2ydKQ}foX`(n!9-+3*Y7^Rjei%R;pJgg3rRl&yR`gJj4p7!+CUvtPjh(NF;KWLAUES}9`J9oy8a^#|kzC=SMybsxgaaF{cT8F|spP3f3ufZI$_dL4lgv*qbIwC@lAYbST~0FY740Isn|p&hktTj2 zFZJY0B%iHgq_>ARr{o0*M|QKX=YnT!koP;(pVNL`x>_p}`}x2gnbHO$zbLZ=}`C;IcwPwIZI8XXTlqrqN(~YBg}7&re6pnp3CF_Zfu*3hCW))l3?xB<_SI@x8srS-E1vzqAcd}721j{NaZ+a-gYn@^-)y-(+#1vy|u zJId>yX(Vr{1wH6sk%?u2-~0q?P4j=Xg|R048EJ4RMo>au4s+P=A60%KpW1vlEcM0= zjQQ}BbMjf7^uvQH!PaV9N2I?DQVRTT zu&L{B@;R&tt$$n2nzGr!bSNQCp`|mNyB+-5Yc-55S~oCKDc(Eybno409~k6YPYaK9 ztrIEK4Cgu*ZKv*GwI9mob`WXfU{!&(9d$;O6DFIaJ%u#th%z(2gJjMDCQnB&xn~e^ zZ0Kjj$yI!-5_)Oqv@k7j483*|U6?Bii)ZDp4V&dlHfF$6dP459oj_g*ogY?0<`F;{ znQT_#*r$+sI{+^8s4mP7sDs_iY$u)P#v$27ESvgA{y5jkn80m}jC3)4UhXpf?K|@5 z7vE)6cv4d=x!x3`{mRko9S)1vARPVvfk!pp@6gHL2OfRk``-g9xgzlW)JKPq{}8P( zs_mHTU2(mLvHG)9cFC6vcQ;Wyw>mBfxA#wbi(~*}1F$um7S@X~MGZPgwyI;_5br+h za{}E*MF!RMj8Ojm=_jB3?Ed@jzkNUI7|8m{LgL+n^4u0^a!V77O=7*n=pS2L_W0QO zkm-+e>nLwOKFZsVgSV3@l)E1Xch@aAE`PoFj7e)FQuu0@X}UnEzz;G;oJ!+Rp#G5a zH0_&?J)RKbP0*2U9!j|*Wr3xNH8ZB<`Kupdq)S)9Y3jxoPgp?eCd{7z3F*0uk#a`H z7pH7UXc{}8k(P}x(oJC%_Ua_)IUlWW4EOc2;Y3a~Fuu|-SS{&`lU=NIR^glC&DJWe z(FUGC=X#CTwP^_d0`ipqeZUi*;zZ|9&;HEs*sbxsxzjr@lc%c})-}fd@ulyc*s6rA z!&N0;$d;FhSyy*Ro@0xxTkiseVpj^=zav|jDRIGxtOh)IyPUpwyF9Uxk>*_8C#Tzp z)s9nU#HnRRVjwRI{FNn))G;_u+~c^tosrrHH)9^}hOeK8Zgd{GuKP=#mr3KtL4)pC zki;i>a|Ek!@8FifF|TcxEjA_ecKF?3OuWTgBE{&&9OQapnY$oir{m1cyQ(|L)g_zR zI$e-qmldCd%pyxvyNtrZ2(M-&GICobBh?L-6qVeOD4t9`Jn-nIS?vZFBW)dIg;=Z| zBRvIP$w;pb8xC6^EnGybNnXy(n%85MemywmE$A-m855{4-7MH#HmtR3kdFAXVybD_ zdzU3bidB+2hfo~p?N7tjN9&px=o@6J2HbPYqtD``*_=e;aNY>`^d;l2!_1AUS-t*` zj4XJ+^-*Ho)c>=$5*ypTWw%l;dO=RIRZBegXT*042GbZwt!ATtdh7R;6QvdLC zmpBrCuo}Pnuu|J)r%l%|rf$sZpI_$9bUr^Q8G&}3LPwKT9JJ*q=O&+;RBz@#}gHq&$p-{ zUxbmiOT3*cQZ1l5`_rw&OZ!O9CB~<*_i)}wWeY2{4`~-^@347DrbW!Dt#u^u`__CM9FOa6_3A z`bt3wISx(tW$;Rq@VDkXVHZ*Ncpynn(mLBKX_K5+n)z81oI9LfH$N$7x-R;aP@O_7 zfA{lU)(Wm?Ggs~St4|3%jk1sZ#MpL8u4atk0G%Jse_@;e{XSy{B%!_ck+DkXb;T?g zp_fv*`|yZ)B5N{6(rZV`CvqlJB<&tKfb^6|x_m?x{OXlpR%1G{Jup+v>dsn)|NQJc&HA1Nsv zip#u7Xx?xPGe~H+ZhCEtX3p3AvDO;LZZD*rk%LZtaLYx)&%4MUuH-W>1;S{bAz=SU zsE{|r&tY!*uYfT%8K)o+_-`EeQ5CC+U^Qh}F zY9P>;a{Z_=7N%y@JoXnCz)OXfg86V!6odj4mGUf+UF(UoG%2J}YP>VKzFk|NFHuU~SfW3|O0a6R)Sz`tVQJ#@3>}L+9M-i1Q`L%)I4x-fZt9DrR1m zJyBA)n(oEqivNdzt<6|{^t(_?ZjnK}Q(P@@Co6;-7u-0XH?vZ@f|GB_@$07KTvt1L z!3~kxxJc~+ALl+iu>AIdjz;-@gS~gEW2fVG|MVi($p-IXwmNQZzh|BqeE!8$$Yv#5 z&yC~|0~FS-bfTxW`mNVk;3@X)B~V<n( zeyM7;>y@;5;z5_udCA2Z2LeW+FK`Wqmqu~W1N%q*7dU+T6C9MhTEPu0l+ZiM8X=}x z)$?HtnR3LT^_7W6k?&D6N~m(ET;%6WboK?N3%P*&vtkickvq8@p>I6OoYztKHeg^A zYQ1ZKc`m4$>oPXkge>G{D@LabdaZ9s!tS6mpEWvjX2)ku%KW{$#FHA z`X**_PF8uA%6!_<6bEXxLjq=E8=V1NJGydRI4MlzCYhob1*{OUMeL+yZ&O_-YBPh=K5-F$ot7jtVP>Wt{lZ};0 zxUEbQ*7{>N^42xDOP*E=+y}*#jQ-p~F^%ERy(uP1o~1vBHt;^MqUVLlj1_UJ^u&79 zdy$lM>(h^T^CcCxQe7bHZLwnfV9ijXh;THRZl*` zs)DQjnmIFTCwc&#q>(so$|F;xShY3Z{E!k774m!zblQImF~(N{Z04(h5=pVWgtL{{ z0;()!c6L3ego;NdTXdbw-mV9sD}~-2*$-`Dxnp@Am74^*4NqYgE1`MHaX|ACeN+kE z;w2{5wYkdS+U%+S*g3F}IG&b^g)ADVmw*MC^ukMNQ{EP`!i;CTqAi3^~c--C~l! zo#JzjIZQ&xpDY?(4Ydb6pI;sW%O382=0h@Xvx;uv;%bYqrx5*)vp$llxd*GmbJmBL zE;6Ivuf+;deGU3zqXv`^g?ea?O6bhUPW4TyR!iMJ=aBSWYPx#C!&!4LH03tBVr){Ya6pM99N=<>^T+B$D<$@RSi^ zjO2eq&x>3_X~*PDDOL$~Ie8vE$BPwJ&;rhJ7vlN6YGCs+LEz`w1mlfLXuk4C*uhl; zo@Kb*F2Oxgd-`(X&8Ox09>)CrD%HSmma7J8{^PW~bjOqOa#$=~HvUFF$n${IA;b!o z`Gda?CZqR>it$E4w!9z|^!uNb&s0umqIZs$!>Z!)QX}k6@-xIsZCfhp=eUp94J|6% zqg6stdTON-dO5PfNw^zOT9WCDebb9)l)MuT4(xSo^XkkA=H-)G!hJ(rIDN^fW@{5` z;e>$>sx?c$(Fc_q-yZO+4V^vJb85_(Ajg$-f2BRy_b2X^9*)-r86ED258pdjD`~^( zWh(}2<(9BK&@xcE=>zYWppru&yHbxg-;=(0u%=%hR`tIV?(hGd&G2T z?(t@g7RK|>ncr{kLSBjj(aEBcl>f6BG zcKZ->YoFgJRJJj&K7bFkINWvaM5!`!5WtIIL0PCa)(BH{%MWoe4cx$ zY+k(GmGDTOq+${tVsbcZkKfjo4En8anJDDD#|!o1S&d52p05{~jJ>WCeRdZ6b`{A` zLKP$B?t0O$jzt|-_Mu3viPkc(`YWLok@~aTX#MO+y@S@Xk@_M?WEQ)u(yoMF^UBbn z1vi<##vc>ZYjQ=8rotD~!;H%n&&!RB0q2m$sovwfT_SdS-2PJJKS-C@_;jyb^4Mwq z2!j?0u*s7e+@1XLQO5Xd`b%`KXsq8KjmLB$evhenuMJe+ISDlN4SgXykMpxhCODCr^b~+w+^ZRL?qZDoy#F#;|GeXHp5|=6`yM&7 z@+Ft`5sCr0$Q&+<2^yKN{ZUK~;|@&Mm~T-+e;9&3Gs-3ZfP1yvlJ8avdqg62Ep7~U z-5W1V_FZbiy>duBP`%VJhfIwL)^O^c{KPcyshIQ3jod8U*i?OfYB67_xpFQ8+yl0* zL1K|0fgT@{qdO8jm5#S|i1Ot{VX7bGYxTHmfVY6}%GhtjoLCtT37>?S1{9CPkle~C zP17U#*I~t2Np*mkmyhP@g>k}U!GlrWyc#QHY+wa#t7XIDCaV9q6?zArC(IBskUOVP z&F5$pAqI>+duRfDYz~R6t6x>WIue)HucoraM9a#R(A1&bSg(tkUO-L{^usmi9fY7W`}x-U41%+xV<}#>QAx;MC)VO&y++ z{~?==y4FJ3O#UvD{qPidrvCC>+(yfNQOLEv=(%|VGx#iA=1vsNkiLm7nxbPRy2{;T z+P$SwC_g9|8YUJZJ?psyiq;LP2CDCVSI`D|Exp5w!U%kd>}yJB^U$Yq^8N}zi`#5m zFnP>w;XPQ3`U{d>ce~024)>k`|7S9R|Ic{S3$n_X`jG2}&;8G0W@{nw$h0Sss(?%| z3WsD;c}Qj}x63N<(|d-?-SdyZLgGkuMWsVtuaB_Ob8?knXu1>BzdZCOne1rA9Jj;z z@NFPhy0D2Pn1cj+MIoGBG(MhW!9>G-v96>@Jfu=DHF`zpISam$^^KN!j#Qh2Oj@ z%0nk){aBi}M@pU9l(ISmeMwE2h<##x%abCrb6Hbb?MjX2obNKZv4O5?{Rho9;k7~vQ`si9JS9He zNIgsc+0-WI+E!|G6!IntX%aqY&J`K~Ni`d)i&0&OM06pYz#U|8>!NqobgDUJH#^MG zoD9%ecGbS@Q9{j%YE)}NE9T;AH}vm4g&h%@$BA0;^Z1q?|0c8Ka%M;_M@hH8GS)}+ z-dFTw`cdyL{cc#}=0y08t!=kM?f;<9Qwbe!eYN9?f43tmVl4><=sl~TVq9xp8NE3b z<1D%gPxfsQO1j&h0Q83O-R78F?`^`Huu`uO-|soQ$%GMgJ~AWu!YleCjtTyKj(C5Z z>%Rht!uNqcI5d7%@;FcQdDb}!Vtq@SehBbqzYBZd-IFMfIo@iYJ{S|q7}N!o=55^!Q#hy#-E2on&!KjXbFTAz zz|+kbd2?QG2FoU*I?F!IK-kR z@F`dR(^XG1IStKw9r;zc-s&oYfcs5LZKDxy3E~71cAb&X!^1{F^{f*5r@{)$n^xlv z%>NN<{mBuB#pQ+#4L4!+6~6&GXk{C3nb4`V=zThbSOh&n9Ksk&lGkpu87m9*2nK{C zgk%IG0wJ^=U^@*6NeIaZMg*H>n>XG_Z(3Re9YQPu?IR8$qTl9gwrOrq36nZ~m)Sk= z_*_xepAH&hUJV*y(gkjVF;^_`rOnP~^3OCUj%(}>eUm4kGI4NC;POFdU}LU~T#(^n+QVCP&ayr&7v9VmQ@c`S;`(MOW9ts= zClfE`5?omO`izgV*hhCly`%js_2~E_qxXy$TTj8y;|(yTK;Sr1|0x(ir@J^ojbb(uL~Am2PGiwVe|yJj@>RHfz&A+++rkc6&6| zxgDAywPCz7qQ)#SM>Vw=UGu0UK{Aen<_?**ed(t5mXXlJA>%g2=4pm6WJC#lG{WS1 znvFG#&GO4~w`p72h8a#yn#`3;w{!C$V-nZp3U1eQVEMx^GsPbuK|KeGY5DIBx0Fa8 z-6G)*AsH{il+dq7sv+gx_eDn>3X@s4_?d=-xM{Jb*dRY<^5EtneUKsV!Kan64R1X< ze(SKpBXa;)JULS49=n0bWu?jNZ(%_zk?cB0_kyu$gPvefH>+c8z{OD|^ZU2T2J$f^ z;oT7n%d5lYZOq)mj+xC*ON5lq01&Haxz?bf)e?CTL4a|*iH#6DC18XHly)GcP zjKh7x2AZg#PmP3L563i=yIKawWKF{#Tywk?TI}I<2g;sr{-zYReb_VV9WfnvqvHC* z=C3xJtG{x|Z80t;$A)`e5NpJ3NNX)_Cf1L<4E3!NvZ1n2hK=itTO%a2nzs?_P5voQ zOrANXBX@)4m}#44MpnnvEjPjrVD;0}0{wQ_2(526YggrUt4rOR! zhjy$-Ke4Te+g2XC>50iVSUR4SiHG_XruwKQ>c56_He|4Q-6v<~b@NQlmb`9FXcO5_0p$6|g4Cey1f>y*i@_K3}QF&Lg zwJ}ckTwc5*Nob%NKJ?p^Dyl&eXjsvHJ%ko}n zzD*!?(}fNhZpwq%SfRY3KlH@t<~pedn)Z&@drQ>wE)rE8?UAdqWN;0MO;mr+@}pN` zkEGQ;@*IEgF2N03ws9!8ncQ&HcfUsGgMYf`98=~ zBYxlU&^Zz51rKkY)Ag=Erk)6>8oI0&Z&Nq5k-8gs!Db}inn0oczhE!D@*MN1Y`+a}_cRIgYaGL%Ypra-F z81oU(ZHht;Ce8U;Q%m~=CtUmavSCvjW70h5?31)Cp z2brK6I7~sSg#48Jk2Pb@Gp1Ky=R1WvEQ?YTAYQiL<;aH?UEY(=W#?P-u?x)9=S}Td z$~W}<4B?k2SHI!2_JhiYJB?Z2cbtsO`jC$`S4UFEd@A!30b2_*BMI6QlWEU-veDwT zXObz*44jo^$sK7Mwu5JvV+~bw4b^3iaieQkXICRdc5;FV=aSyEriImbf5FfAy3;U& z>qx7mw!JR{#u?ka^z~ty$kw4xb4S3?^0AoKy44k1y7k|*fj_&X02i~+d%W+sjfF-6 ztsJ}Yio#lA{7Yg^^u-$)KYc^Mx1H$I*uzv$Evak7+XJ&sR0#&ab^$iYd!jF9Dw#@V z#0i@PPj7G4Sn2ozyYzjPb|aaN_lQ-nZu!g`4m<2ppz1`QsywF7fHz>9ICUMhC#xH# zJ4?E&=g;rfAqe7MHb6gzZHG7aX{&|#-GpcB9`LCfNF6IYATAO3*Nwta+~0_FvT9mI zNoyV~jZ_M=VU4hZN@23JYo2>gL7eY)k=$_Af33cEkiM(@-e<0u=bBdbygcD}j5L}5 zq_0N*W)DxG?|@Gpg$2z>UhC0wlLxCu{(hOwIO-*kGMc*gX$_awtf{*TJ0aJ{HGCmw zepR2UYQU-1m-jHta|Ms}Fr2l0^~UGr)UNdfDSozrSU30>OU7p#M7i|~Svs-1pb{|S z+i&WcRxu5@>Iq(8fO}AUTYztWpn3id2knOeXORN5he4mFA>KOSv%$v?+&PdehW|S8qJ_E4E=?Yxwb#eKjnTUDo#$7k=0msMvVyiF(Jy2o`gFhqbIV8(1H6 zsT#sAswu?1HXQm!;Tm*xs)pD)>qLE>b>kuVwnl0tJS5+0i)q*{J8WwF=G%75S>W>a z{nfZ@(sv)*| z!`53jzO5xQ?(p?$etwR#+IxFE*D$hf{NqFpBWDXYkFMvNu&#VZsb~$_<2m87|LEo!8@XG~ zHqXZX{ma$x<3~4N$Uo6{d~8|YpAy3l=Leo@oi<J-0>0GPacamL1@TbM|@e*~^> z`2dech(3@+nTbp@X>m7RBI@d}D^1(M7p+UdpQyZDCbX$%v zNhGrd{n}K1;;f0uPNqkze=nF8kGFw+`#S0!4V~lR|0M{pKx==1zMv)h!S!@xAAVy= zJ$~cJ^Y|S@cH=jm?EHql3!}0Yc7tm5f}+(XSU`%(#hhw<2@&;IL38_oblLDFLqcuY z+xp_TqE0cRzpGTM(&}~j7hLV~kWst9A$iuFL`o-88;Z_lG+p?0HEgG79kD$SZcvSP z;9Z86s7Gu}@k%kVpOh#0g3y&QdX0E1H0JeRm1>JGt~TFaL&uk1kqu2T#Rp0aZR+B1 zfPQfR-)gi!;H0qNJ79hE{W~!&7a^f$*AXu0%I5}3^BKG<#2b0~PClXUY()PYt-I> zeycFh4yoOFC^Yguh0ATxEYvLE=QCz9#ay|{MWk=Stl3=oBxVLbr*}TS9jSy3Inrm# zy0>A&S_OM7&iT?X8~G+;B!UZtBa#8qjy3a;cRcI?)#3s8BJ$;=EY_VbJF^`4wP$II z^5x8|6JoxcoW+_rS)WDl8=Iv2S0LMy$5u*Da}J*DwR zCG;Or+C}`ZN~jNYu$zsp5s&(%ScmBP;C+Dj0>01CcibaxamBh8x-wuB-79WMt&gr6 zzII3x$EMNuBf9CiUR_2dEcbDOZmKJVNXx_c9wn?wdleq`htp@_EmdDYH%rw?JsJ$= z{M%!d5xaI$ah%Wz?~8%SbLnQJxHr4dlZkQ7cO{p;mW-D!(v+}n8ooyf(=StEgqZfn z(kp~;^s$To`}*4>uor496AIsQ}1*>cI#h3H$zLx zLbH1h-kHF1mt7^&eOoW;ob@hx2c-L&o>a5IV$BRUEOAjEtI1stu19wgkv@30POK7R zopsnfZw;EI@^S}a(Q`w6AL^pBm-zxNEjgtC_T3Ygd4`@DT2KA`)ZR+@ z6DWw=7a{aLJ6n|KzQ_%oqk9~$5AA%5wm5CWdc4$@6ix98*f+f1n4)?Y8?4Q)ccqG^ zeoqL)H5dyv~?L9cjY06X#kDQ88zq4%q7)$o5Y)Nd2DMkGbR;2Zi*S=W14PCx2)kWW5>x4{+UA!OJ+be)Kbr}JBk^m2ry2>b%jcY~!V4XdVB7;|hTsA?VZQO?H0A~Fu=gRXH& zzX$jeoQju^@JQBJ3Xj*LY4 zb~JZrq$a|}+b-pT?!SLO7k+{-mAHj*MJM_E?!5IM@fpH_FjKHU%p^USyg$qu7UtQ5 zgdBhbIFwu-NvCP^yGdnk+h0RVzIwIclo38Fuc3u?#^Ck!4p@f`ZO(MkyaXOr`qg7s zb3bUX*h1_H#kQ7qd51kyr9DUElL$0+_7f*f>lT{De7w3hyI3bb+LtZT7pS^2Up6j| z_C|WapPClN#Jo;lp1rRyd$>mMurPg-sf2p*rbz9J)-t=5&~b&n6QO(iTF?|1 z^e)4xz;1QfVQH#&ExhuH1NmYG-?IS9M(iT!&*5aHHF3p7SKcsDeSwzII{FSdyOj-k z9PEH9`>ed%7||xY_n|)WewaOpGV}v{sXr#5u<-UA@3Ui_DGbGf@&jFQ?EKiG9gf)c z*y0Q6V^cqvWWv2-D_$_cKaw#Vy4bn|Uwy*&3~8h)AbdaCUJFEe|0r~+{N)vug*1k4 zR8G&|1>hOY(-h@5fGHp4KP_p+OgWjN5}s;Y?s~Fp45+2Xw=D+l)MZr;a{?w8Fv);HoW!FRaV7%Er4o=x%Z`E%(>=zJOa#kf zqJtiR??DHZ&_m&<-oZddQo6=RyvhsMPKH*`A7y3YVlI9c3LAWHe4*ol>5>Iu&8h>b>QAR@WnR ztnMuDSbYH@c}>cFDQi;iOI@T8{Mv_>E4MZq4VesSaK%X zM@rEJl+qgtt=-8CogZJ6O68zLq3H#pU`{@m!#eXYNx{|3ij>kn|gAK~o(24}d|Uj_QB zxYl3Rk8tC0Ke)%O>ff+#Md^VU)%nDtIzajW=|av>l(-u0;KR*8PG3}qoDaEws8#3j zh4C8Ht=Us}06BG09dbV8qS8G~&(kOkQbxyk4BAN+V9OHIAO99 z3P-&1$V2BRW_3}Dz~mULCoYo&`n9qg**kRoW1*oZLtf8Bdm`D7GWaHrF;e}Bem`cD zZLPFF9>03oQ`jH*ri4n2=*wi{{T6-jEisV%H8On-&^bu&K04Yf-c$4*OHP0m)uLXQ zC}cI!Qr1YnMm6BID}5D4VWW^=9>W_Tz+TILKAOjO?KiW|9aN(>s=K%icwt_00N&~3 zG(#I>>y7xu4>X-gov?v%;_YNmxpkWZ-x+lhqqa-Eq0ONRGO7W;zDK408@$93A9d9@ znb{6Y#dlJ{fG+?nCQr|e+@n;TToTW*_U&Df^9tS-D69n4Q>{Z^4{GP|fA zE`f%46Z$SEV0Kn~nPVk0u40AOu6tls>AL$Ku5_Tzn>V=|!;=aBGo&9vcrcald5G^sC_uOaVFALkDTH5!_)GjRk5!1>$d}s)Sp(U*0e6V` o!2iKg_b-V1zBQ}R_f%D62tr(3Br!6BA!kvR4qA-X{6CBSCtx#7n*aa+ literal 0 HcmV?d00001 From 1e626a70cba53a575e88c47d6501aed0c78ccd2f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 20 Dec 2023 09:04:32 +1100 Subject: [PATCH 0224/1335] hwdef: added MatekL431-Serial --- .../hwdef/MatekL431-Serial/hwdef-bl.dat | 2 ++ .../hwdef/MatekL431-Serial/hwdef.dat | 19 +++++++++++++++++++ .../hwdef/scripts/defaults_periph.h | 2 +- 3 files changed, 22 insertions(+), 1 deletion(-) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Serial/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Serial/hwdef.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Serial/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Serial/hwdef-bl.dat new file mode 100644 index 00000000000000..b9005f84941a6a --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Serial/hwdef-bl.dat @@ -0,0 +1,2 @@ +include ../MatekL431/hwdef-bl.inc + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Serial/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Serial/hwdef.dat new file mode 100644 index 00000000000000..e9ace8923ddcb2 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Serial/hwdef.dat @@ -0,0 +1,19 @@ +include ../MatekL431/hwdef.inc + +define HAL_PERIPH_ENABLE_SERIAL_OPTIONS + +# enable serial3 port with DMA +undef PB10 +undef PB11 +PB10 USART3_TX USART3 SPEED_HIGH +PB11 USART3_RX USART3 SPEED_HIGH + +# larger CAN pool for faster serial +undef HAL_CAN_POOL_SIZE +define HAL_CAN_POOL_SIZE 12000 + +define HAL_USE_ADC FALSE + +# make the UARTn numbers in parameters match the silkscreen +undef SERIAL_ORDER +SERIAL_ORDER EMPTY USART1 USART2 USART3 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h index 3a0a8c372330d5..e0b0f894a666a9 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h @@ -335,7 +335,7 @@ #endif #ifndef AP_UART_MONITOR_ENABLED -#define AP_UART_MONITOR_ENABLED defined(HAL_PERIPH_ENABLE_GPS) && (GPS_MOVING_BASELINE || BOARD_FLASH_SIZE>=256) +#define AP_UART_MONITOR_ENABLED defined(HAL_PERIPH_ENABLE_SERIAL_OPTIONS) || (defined(HAL_PERIPH_ENABLE_GPS) && (GPS_MOVING_BASELINE || BOARD_FLASH_SIZE>=256)) #endif #ifndef HAL_BOARD_LOG_DIRECTORY From d01a330588d9d38a496938ee66fc2812ba95a21c Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 14 Dec 2023 10:36:43 +0900 Subject: [PATCH 0225/1335] AC_Avoidance: constify get_shortest_path_point --- libraries/AC_Avoidance/AP_OADijkstra.cpp | 2 +- libraries/AC_Avoidance/AP_OADijkstra.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AC_Avoidance/AP_OADijkstra.cpp b/libraries/AC_Avoidance/AP_OADijkstra.cpp index 749cb140ee24a1..8a0913c63b57e0 100644 --- a/libraries/AC_Avoidance/AP_OADijkstra.cpp +++ b/libraries/AC_Avoidance/AP_OADijkstra.cpp @@ -934,7 +934,7 @@ bool AP_OADijkstra::calc_shortest_path(const Location &origin, const Location &d } // return point from final path as an offset (in cm) from the ekf origin -bool AP_OADijkstra::get_shortest_path_point(uint8_t point_num, Vector2f& pos) +bool AP_OADijkstra::get_shortest_path_point(uint8_t point_num, Vector2f& pos) const { if ((_path_numpoints == 0) || (point_num >= _path_numpoints)) { return false; diff --git a/libraries/AC_Avoidance/AP_OADijkstra.h b/libraries/AC_Avoidance/AP_OADijkstra.h index 48e91f6cc1269c..b37b644c44dcf3 100644 --- a/libraries/AC_Avoidance/AP_OADijkstra.h +++ b/libraries/AC_Avoidance/AP_OADijkstra.h @@ -182,7 +182,7 @@ class AP_OADijkstra { Vector2f _path_destination; // destination position used in shortest path calculations (offset in cm from EKF origin) // return point from final path as an offset (in cm) from the ekf origin - bool get_shortest_path_point(uint8_t point_num, Vector2f& pos); + bool get_shortest_path_point(uint8_t point_num, Vector2f& pos) const; // find the position of a node as an offset (in cm) from the ekf origin // returns true if successful and pos is updated From bf2b0f890fa22e3fd5ff685fb59ac5669550189d Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 1 Dec 2023 17:10:34 +0900 Subject: [PATCH 0226/1335] AC_WPNav: record next destination This allows AC_WPNav_OA to completely restore the path on deactivation --- libraries/AC_WPNav/AC_WPNav.cpp | 4 ++++ libraries/AC_WPNav/AC_WPNav.h | 1 + 2 files changed, 5 insertions(+) diff --git a/libraries/AC_WPNav/AC_WPNav.cpp b/libraries/AC_WPNav/AC_WPNav.cpp index 116e85911c0e2f..03200a463ef62f 100644 --- a/libraries/AC_WPNav/AC_WPNav.cpp +++ b/libraries/AC_WPNav/AC_WPNav.cpp @@ -350,6 +350,7 @@ bool AC_WPNav::set_wp_destination(const Vector3f& destination, bool terrain_alt) _this_leg_is_spline = false; _scurve_next_leg.init(); + _next_destination.zero(); // clear next destination _flags.fast_waypoint = false; // default waypoint back to slow _flags.reached_destination = false; @@ -380,6 +381,9 @@ bool AC_WPNav::set_wp_destination_next(const Vector3f& destination, bool terrain // next destination provided so fast waypoint _flags.fast_waypoint = true; + // record next destination + _next_destination = destination; + return true; } diff --git a/libraries/AC_WPNav/AC_WPNav.h b/libraries/AC_WPNav/AC_WPNav.h index e4563f7ce6de16..c060498263dd01 100644 --- a/libraries/AC_WPNav/AC_WPNav.h +++ b/libraries/AC_WPNav/AC_WPNav.h @@ -273,6 +273,7 @@ class AC_WPNav float _wp_desired_speed_xy_cms; // desired wp speed in cm/sec Vector3f _origin; // starting point of trip to next waypoint in cm from ekf origin Vector3f _destination; // target destination in cm from ekf origin + Vector3f _next_destination; // next target destination in cm from ekf origin float _track_scalar_dt; // time compression multiplier to slow the progress along the track float _offset_vel; // horizontal velocity reference used to slow the aircraft for pause and to ensure the aircraft can maintain height above terrain float _offset_accel; // horizontal acceleration reference used to slow the aircraft for pause and to ensure the aircraft can maintain height above terrain From 8546dfaf4de29d8f4554f63193f247037d59b9ab Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 18 Dec 2023 13:20:32 +0900 Subject: [PATCH 0227/1335] AC_WPNav: add force_stop_at_next_wp --- libraries/AC_WPNav/AC_WPNav.cpp | 23 +++++++++++++++++++++++ libraries/AC_WPNav/AC_WPNav.h | 5 +++++ 2 files changed, 28 insertions(+) diff --git a/libraries/AC_WPNav/AC_WPNav.cpp b/libraries/AC_WPNav/AC_WPNav.cpp index 03200a463ef62f..e2163264e01abf 100644 --- a/libraries/AC_WPNav/AC_WPNav.cpp +++ b/libraries/AC_WPNav/AC_WPNav.cpp @@ -627,6 +627,29 @@ bool AC_WPNav::is_active() const return (AP_HAL::millis() - _wp_last_update) < 200; } +// force stopping at next waypoint. Used by Dijkstra's object avoidance when path from destination to next destination is not clear +// only affects regular (e.g. non-spline) waypoints +// returns true if this had any affect on the path +bool AC_WPNav::force_stop_at_next_wp() +{ + // exit immediately if vehicle was going to stop anyway + if (!_flags.fast_waypoint) { + return false; + } + + _flags.fast_waypoint = false; + + // update this_leg's final velocity and next leg's initial velocity to zero + if (!_this_leg_is_spline) { + _scurve_this_leg.set_destination_speed_max(0); + } + if (!_next_leg_is_spline) { + _scurve_next_leg.init(); + } + + return true; +} + // get terrain's altitude (in cm above the ekf origin) at the current position (+ve means terrain below vehicle is above ekf origin's altitude) bool AC_WPNav::get_terrain_offset(float& offset_cm) { diff --git a/libraries/AC_WPNav/AC_WPNav.h b/libraries/AC_WPNav/AC_WPNav.h index c060498263dd01..74bd95075c92af 100644 --- a/libraries/AC_WPNav/AC_WPNav.h +++ b/libraries/AC_WPNav/AC_WPNav.h @@ -163,6 +163,11 @@ class AC_WPNav // returns true if update_wpnav has been run very recently bool is_active() const; + // force stopping at next waypoint. Used by Dijkstra's object avoidance when path from destination to next destination is not clear + // only affects regular (e.g. non-spline) waypoints + // returns true if this had any affect on the path + bool force_stop_at_next_wp(); + /// /// spline methods /// From 0c8f427d42d756b704f4f594f51ef03b64258f09 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 1 Dec 2023 17:11:44 +0900 Subject: [PATCH 0228/1335] AC_WPNav: OA handles failure to set wp on deactivation This may never happen in practice but just in case --- libraries/AC_WPNav/AC_WPNav_OA.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/libraries/AC_WPNav/AC_WPNav_OA.cpp b/libraries/AC_WPNav/AC_WPNav_OA.cpp index 10e56d51ecfb95..d46e3745010b12 100644 --- a/libraries/AC_WPNav/AC_WPNav_OA.cpp +++ b/libraries/AC_WPNav/AC_WPNav_OA.cpp @@ -91,7 +91,10 @@ bool AC_WPNav_OA::update_wpnav() case AP_OAPathPlanner::OA_NOT_REQUIRED: if (_oa_state != oa_retstate) { // object avoidance has become inactive so reset target to original destination - set_wp_destination(_destination_oabak, _terrain_alt_oabak); + if (!set_wp_destination(_destination_oabak, _terrain_alt_oabak)) { + // trigger terrain failsafe + return false; + } _oa_state = oa_retstate; } break; From 6fed0dbc7aa03419abfe84082299ddb7a788d12a Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 1 Dec 2023 17:14:04 +0900 Subject: [PATCH 0229/1335] AC_WPNav: OA supports fast waypoints with dijkstras --- libraries/AC_WPNav/AC_WPNav_OA.cpp | 51 ++++++++++++++++++++++++++++-- libraries/AC_WPNav/AC_WPNav_OA.h | 2 ++ 2 files changed, 50 insertions(+), 3 deletions(-) diff --git a/libraries/AC_WPNav/AC_WPNav_OA.cpp b/libraries/AC_WPNav/AC_WPNav_OA.cpp index d46e3745010b12..b0ab5502b39a93 100644 --- a/libraries/AC_WPNav/AC_WPNav_OA.cpp +++ b/libraries/AC_WPNav/AC_WPNav_OA.cpp @@ -77,14 +77,25 @@ bool AC_WPNav_OA::update_wpnav() _origin_oabak = _origin; _destination_oabak = _destination; _terrain_alt_oabak = _terrain_alt; + _next_destination_oabak = _next_destination; } - // convert origin and destination to Locations and pass into oa + // convert origin, destination and next_destination to Locations and pass into oa const Location origin_loc(_origin_oabak, _terrain_alt_oabak ? Location::AltFrame::ABOVE_TERRAIN : Location::AltFrame::ABOVE_ORIGIN); const Location destination_loc(_destination_oabak, _terrain_alt_oabak ? Location::AltFrame::ABOVE_TERRAIN : Location::AltFrame::ABOVE_ORIGIN); - Location oa_origin_new, oa_destination_new; + const Location next_destination_loc(_next_destination_oabak, _terrain_alt_oabak ? Location::AltFrame::ABOVE_TERRAIN : Location::AltFrame::ABOVE_ORIGIN); + Location oa_origin_new, oa_destination_new, oa_next_destination_new; + bool dest_to_next_dest_clear = true; AP_OAPathPlanner::OAPathPlannerUsed path_planner_used = AP_OAPathPlanner::OAPathPlannerUsed::None; - const AP_OAPathPlanner::OA_RetState oa_retstate = oa_ptr->mission_avoidance(current_loc, origin_loc, destination_loc, oa_origin_new, oa_destination_new, path_planner_used); + const AP_OAPathPlanner::OA_RetState oa_retstate = oa_ptr->mission_avoidance(current_loc, + origin_loc, + destination_loc, + next_destination_loc, + oa_origin_new, + oa_destination_new, + oa_next_destination_new, + dest_to_next_dest_clear, + path_planner_used); switch (oa_retstate) { @@ -95,11 +106,31 @@ bool AC_WPNav_OA::update_wpnav() // trigger terrain failsafe return false; } + + // if path from destination to next_destination is clear + if (dest_to_next_dest_clear && (oa_ptr->get_options() & AP_OAPathPlanner::OA_OPTION_FAST_WAYPOINTS)) { + // set next destination if non-zero + if (!_next_destination_oabak.is_zero()) { + set_wp_destination_next(_next_destination_oabak); + } + } _oa_state = oa_retstate; } + + // ensure we stop at next waypoint + // Note that this check is run on every iteration even if the path planner is not active + if (!dest_to_next_dest_clear) { + force_stop_at_next_wp(); + } break; case AP_OAPathPlanner::OA_PROCESSING: + if (oa_ptr->get_options() & AP_OAPathPlanner::OA_OPTION_FAST_WAYPOINTS) { + // if fast waypoint option is set, proceed during processing + break; + } + FALLTHROUGH; + case AP_OAPathPlanner::OA_ERROR: // during processing or in case of error stop the vehicle // by setting the oa_destination to a stopping point @@ -108,6 +139,7 @@ bool AC_WPNav_OA::update_wpnav() Vector3f stopping_point; get_wp_stopping_point(stopping_point); _oa_destination = Location(stopping_point, Location::AltFrame::ABOVE_ORIGIN); + _oa_next_destination.zero(); if (set_wp_destination(stopping_point, false)) { _oa_state = oa_retstate; } @@ -130,6 +162,8 @@ bool AC_WPNav_OA::update_wpnav() Location origin_oabak_loc(_origin_oabak, _terrain_alt_oabak ? Location::AltFrame::ABOVE_TERRAIN : Location::AltFrame::ABOVE_ORIGIN); Location destination_oabak_loc(_destination_oabak, _terrain_alt_oabak ? Location::AltFrame::ABOVE_TERRAIN : Location::AltFrame::ABOVE_ORIGIN); oa_destination_new.linearly_interpolate_alt(origin_oabak_loc, destination_oabak_loc); + + // set new OA adjusted destination if (!set_wp_destination_loc(oa_destination_new)) { // trigger terrain failsafe return false; @@ -137,6 +171,17 @@ bool AC_WPNav_OA::update_wpnav() // if new target set successfully, update oa state and destination _oa_state = oa_retstate; _oa_destination = oa_destination_new; + + // if a next destination was provided then use it + if ((oa_ptr->get_options() & AP_OAPathPlanner::OA_OPTION_FAST_WAYPOINTS) && !oa_next_destination_new.is_zero()) { + // calculate oa_next_destination_new's altitude using linear interpolation between original origin and destination + // this "next destination" is still an intermediate point between the origin and destination + Location next_destination_oabak_loc(_next_destination_oabak, _terrain_alt_oabak ? Location::AltFrame::ABOVE_TERRAIN : Location::AltFrame::ABOVE_ORIGIN); + oa_next_destination_new.linearly_interpolate_alt(origin_oabak_loc, destination_oabak_loc); + if (set_wp_destination_next_loc(oa_next_destination_new)) { + _oa_next_destination = oa_next_destination_new; + } + } } break; diff --git a/libraries/AC_WPNav/AC_WPNav_OA.h b/libraries/AC_WPNav/AC_WPNav_OA.h index cf532de016c124..2687c925521fc9 100644 --- a/libraries/AC_WPNav/AC_WPNav_OA.h +++ b/libraries/AC_WPNav/AC_WPNav_OA.h @@ -40,6 +40,8 @@ class AC_WPNav_OA : public AC_WPNav AP_OAPathPlanner::OA_RetState _oa_state; // state of object avoidance, if OA_SUCCESS we use _oa_destination to avoid obstacles Vector3f _origin_oabak; // backup of _origin so it can be restored when oa completes Vector3f _destination_oabak; // backup of _destination so it can be restored when oa completes + Vector3f _next_destination_oabak;// backup of _next_destination so it can be restored when oa completes bool _terrain_alt_oabak; // true if backup origin and destination z-axis are terrain altitudes Location _oa_destination; // intermediate destination during avoidance + Location _oa_next_destination; // intermediate next destination during avoidance }; From 82984577d2d67411acc9c205c553fa50472ab4c4 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 18 Dec 2023 14:39:38 +0900 Subject: [PATCH 0230/1335] AC_Avoidance: path planner avoids timeout when first activated --- libraries/AC_Avoidance/AP_OAPathPlanner.cpp | 8 +++++++- libraries/AC_Avoidance/AP_OAPathPlanner.h | 4 +++- 2 files changed, 10 insertions(+), 2 deletions(-) diff --git a/libraries/AC_Avoidance/AP_OAPathPlanner.cpp b/libraries/AC_Avoidance/AP_OAPathPlanner.cpp index 3913cc71921022..95ad4a1b07b29a 100644 --- a/libraries/AC_Avoidance/AP_OAPathPlanner.cpp +++ b/libraries/AC_Avoidance/AP_OAPathPlanner.cpp @@ -199,7 +199,13 @@ AP_OAPathPlanner::OA_RetState AP_OAPathPlanner::mission_avoidance(const Location return OA_NOT_REQUIRED; } + // check if just activated to avoid initial timeout error const uint32_t now = AP_HAL::millis(); + if (now - _last_update_ms > 200) { + _activated_ms = now; + } + _last_update_ms = now; + WITH_SEMAPHORE(_rsem); // place new request for the thread to work on @@ -213,7 +219,7 @@ AP_OAPathPlanner::OA_RetState AP_OAPathPlanner::mission_avoidance(const Location const bool destination_matches = (destination.lat == avoidance_result.destination.lat) && (destination.lng == avoidance_result.destination.lng); // check results have not timed out - const bool timed_out = now - avoidance_result.result_time_ms > OA_TIMEOUT_MS; + const bool timed_out = (now - avoidance_result.result_time_ms > OA_TIMEOUT_MS) && (now - _activated_ms > OA_TIMEOUT_MS); // return results from background thread's latest checks if (destination_matches && !timed_out) { diff --git a/libraries/AC_Avoidance/AP_OAPathPlanner.h b/libraries/AC_Avoidance/AP_OAPathPlanner.h index ae8b0aff7dc323..3e3e49d370f064 100644 --- a/libraries/AC_Avoidance/AP_OAPathPlanner.h +++ b/libraries/AC_Avoidance/AP_OAPathPlanner.h @@ -115,7 +115,9 @@ class AP_OAPathPlanner { AP_OABendyRuler *_oabendyruler; // Bendy Ruler algorithm AP_OADijkstra *_oadijkstra; // Dijkstra's algorithm AP_OADatabase _oadatabase; // Database of dynamic objects to avoid - uint32_t avoidance_latest_ms; // last time Dijkstra's or BendyRuler algorithms ran + uint32_t avoidance_latest_ms; // last time Dijkstra's or BendyRuler algorithms ran (in the avoidance thread) + uint32_t _last_update_ms; // system time that mission_avoidance was called in main thread + uint32_t _activated_ms; // system time that object avoidance was most recently activated (used to avoid timeout error on first run) bool proximity_only = true; static AP_OAPathPlanner *_singleton; From 5aeabc57793967ddd87247c6ba33a02954a60b1d Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 14 Dec 2023 15:19:51 +0900 Subject: [PATCH 0231/1335] AC_Avoidance: path planner accepts next destination --- libraries/AC_Avoidance/AP_OAPathPlanner.cpp | 49 ++++++++++++++++++--- libraries/AC_Avoidance/AP_OAPathPlanner.h | 10 ++++- 2 files changed, 51 insertions(+), 8 deletions(-) diff --git a/libraries/AC_Avoidance/AP_OAPathPlanner.cpp b/libraries/AC_Avoidance/AP_OAPathPlanner.cpp index 95ad4a1b07b29a..48595b4fb42802 100644 --- a/libraries/AC_Avoidance/AP_OAPathPlanner.cpp +++ b/libraries/AC_Avoidance/AP_OAPathPlanner.cpp @@ -186,12 +186,17 @@ AP_OAPathPlanner::OAPathPlannerUsed AP_OAPathPlanner::map_bendytype_to_pathplann } // provides an alternative target location if path planning around obstacles is required -// returns true and updates result_loc with an intermediate location +// returns true and updates result_origin, result_destination, result_next_destination with an intermediate path +// result_dest_to_next_dest_clear is set to true if the path from result_destination to result_next_destination is clear (only supported by Dijkstras) +// path_planner_used updated with which path planner produced the result AP_OAPathPlanner::OA_RetState AP_OAPathPlanner::mission_avoidance(const Location ¤t_loc, const Location &origin, const Location &destination, + const Location &next_destination, Location &result_origin, Location &result_destination, + Location &result_next_destination, + bool &result_dest_to_next_dest_clear, OAPathPlannerUsed &path_planner_used) { // exit immediately if disabled or thread is not running from a failed init @@ -212,20 +217,25 @@ AP_OAPathPlanner::OA_RetState AP_OAPathPlanner::mission_avoidance(const Location avoidance_request.current_loc = current_loc; avoidance_request.origin = origin; avoidance_request.destination = destination; + avoidance_request.next_destination = next_destination; avoidance_request.ground_speed_vec = AP::ahrs().groundspeed_vector(); avoidance_request.request_time_ms = now; - // check result's destination matches our request - const bool destination_matches = (destination.lat == avoidance_result.destination.lat) && (destination.lng == avoidance_result.destination.lng); + // check result's destination and next_destination matches our request + // e.g. check this result was using our current inputs and not from an old request + const bool destination_matches = destination.same_latlon_as(avoidance_result.destination); + const bool next_destination_matches = next_destination.same_latlon_as(avoidance_result.next_destination); // check results have not timed out const bool timed_out = (now - avoidance_result.result_time_ms > OA_TIMEOUT_MS) && (now - _activated_ms > OA_TIMEOUT_MS); // return results from background thread's latest checks - if (destination_matches && !timed_out) { + if (destination_matches && next_destination_matches && !timed_out) { // we have a result from the thread result_origin = avoidance_result.origin_new; result_destination = avoidance_result.destination_new; + result_next_destination = avoidance_result.next_destination_new; + result_dest_to_next_dest_clear = avoidance_result.dest_to_next_dest_clear; path_planner_used = avoidance_result.path_planner_used; return avoidance_result.ret_state; } @@ -270,8 +280,11 @@ void AP_OAPathPlanner::avoidance_thread() _oadatabase.update(); + // values returned by path planners Location origin_new; Location destination_new; + Location next_destination_new; + bool dest_to_next_dest_clear = false; { WITH_SEMAPHORE(_rsem); if (now - avoidance_request.request_time_ms > OA_TIMEOUT_MS) { @@ -282,9 +295,10 @@ void AP_OAPathPlanner::avoidance_thread() // copy request to avoid conflict with main thread avoidance_request2 = avoidance_request; - // store passed in origin and destination so we can return it if object avoidance is not required + // store passed in origin, destination and next_destination so we can return it if object avoidance is not required origin_new = avoidance_request.origin; destination_new = avoidance_request.destination; + next_destination_new = avoidance_request.next_destination; } // run background task looking for best alternative destination @@ -313,7 +327,13 @@ void AP_OAPathPlanner::avoidance_thread() continue; } _oadijkstra->set_fence_margin(_margin_max); - const AP_OADijkstra::AP_OADijkstra_State dijkstra_state = _oadijkstra->update(avoidance_request2.current_loc, avoidance_request2.destination, origin_new, destination_new); + const AP_OADijkstra::AP_OADijkstra_State dijkstra_state = _oadijkstra->update(avoidance_request2.current_loc, + avoidance_request2.destination, + avoidance_request2.next_destination, + origin_new, + destination_new, + next_destination_new, + dest_to_next_dest_clear); switch (dijkstra_state) { case AP_OADijkstra::DIJKSTRA_STATE_NOT_REQUIRED: res = OA_NOT_REQUIRED; @@ -354,7 +374,13 @@ void AP_OAPathPlanner::avoidance_thread() } #if AP_FENCE_ENABLED _oadijkstra->set_fence_margin(_margin_max); - const AP_OADijkstra::AP_OADijkstra_State dijkstra_state = _oadijkstra->update(avoidance_request2.current_loc, avoidance_request2.destination, origin_new, destination_new); + const AP_OADijkstra::AP_OADijkstra_State dijkstra_state = _oadijkstra->update(avoidance_request2.current_loc, + avoidance_request2.destination, + avoidance_request2.next_destination, + origin_new, + destination_new, + next_destination_new, + dest_to_next_dest_clear); switch (dijkstra_state) { case AP_OADijkstra::DIJKSTRA_STATE_NOT_REQUIRED: res = OA_NOT_REQUIRED; @@ -376,9 +402,18 @@ void AP_OAPathPlanner::avoidance_thread() { // give the main thread the avoidance result WITH_SEMAPHORE(_rsem); + + // place the destination and next destination used into the result (used by the caller to verify the result matches their request) avoidance_result.destination = avoidance_request2.destination; + avoidance_result.next_destination = avoidance_request2.next_destination; + avoidance_result.dest_to_next_dest_clear = dest_to_next_dest_clear; + + // fill the result structure with the intermediate path avoidance_result.origin_new = (res == OA_SUCCESS) ? origin_new : avoidance_result.origin_new; avoidance_result.destination_new = (res == OA_SUCCESS) ? destination_new : avoidance_result.destination; + avoidance_result.next_destination_new = (res == OA_SUCCESS) ? next_destination_new : avoidance_result.next_destination; + + // create new avoidance result.dest_to_next_dest_clear field. fill in with results from dijkstras or leave as unknown avoidance_result.result_time_ms = AP_HAL::millis(); avoidance_result.path_planner_used = path_planner_used; avoidance_result.ret_state = res; diff --git a/libraries/AC_Avoidance/AP_OAPathPlanner.h b/libraries/AC_Avoidance/AP_OAPathPlanner.h index 3e3e49d370f064..b6f57b16e6e5d6 100644 --- a/libraries/AC_Avoidance/AP_OAPathPlanner.h +++ b/libraries/AC_Avoidance/AP_OAPathPlanner.h @@ -48,13 +48,17 @@ class AP_OAPathPlanner { }; // provides an alternative target location if path planning around obstacles is required - // returns true and updates result_origin and result_destination with an intermediate path + // returns true and updates result_origin, result_destination and result_next_destination with an intermediate path + // result_dest_to_next_dest_clear is set to true if the path from result_destination to result_next_destination is clear (only supported by Dijkstras) // path_planner_used updated with which path planner produced the result OA_RetState mission_avoidance(const Location ¤t_loc, const Location &origin, const Location &destination, + const Location &next_destination, Location &result_origin, Location &result_destination, + Location &result_next_destination, + bool &result_dest_to_next_dest_clear, OAPathPlannerUsed &path_planner_used) WARN_IF_UNUSED; // enumerations for _TYPE parameter @@ -90,6 +94,7 @@ class AP_OAPathPlanner { Location current_loc; Location origin; Location destination; + Location next_destination; Vector2f ground_speed_vec; uint32_t request_time_ms; } avoidance_request, avoidance_request2; @@ -97,8 +102,11 @@ class AP_OAPathPlanner { // an avoidance result from the avoidance thread struct { Location destination; // destination vehicle is trying to get to (also used to verify the result matches a recent request) + Location next_destination; // next destination vehicle is trying to get to (also used to verify the result matches a recent request) Location origin_new; // intermediate origin. The start of line segment that vehicle should follow Location destination_new; // intermediate destination vehicle should move towards + Location next_destination_new; // intermediate next destination vehicle should move towards + bool dest_to_next_dest_clear; // true if the path from destination_new to next_destination_new is clear and does not require path planning (only supported by Dijkstras) uint32_t result_time_ms; // system time the result was calculated (used to verify the result is recent) OAPathPlannerUsed path_planner_used; // path planner that produced the result OA_RetState ret_state; // OA_SUCCESS if the vehicle should move along the path from origin_new to destination_new From cb1853b9bb9cf203750c202fc6a146edcca3b18b Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 14 Dec 2023 10:36:14 +0900 Subject: [PATCH 0232/1335] AC_Avoidance: Dijkstra's returns control when clear of obstacles --- libraries/AC_Avoidance/AP_OADijkstra.cpp | 58 +++++++++++++++++++++--- libraries/AC_Avoidance/AP_OADijkstra.h | 17 ++++++- 2 files changed, 67 insertions(+), 8 deletions(-) diff --git a/libraries/AC_Avoidance/AP_OADijkstra.cpp b/libraries/AC_Avoidance/AP_OADijkstra.cpp index 8a0913c63b57e0..0083f64795c82d 100644 --- a/libraries/AC_Avoidance/AP_OADijkstra.cpp +++ b/libraries/AC_Avoidance/AP_OADijkstra.cpp @@ -40,19 +40,30 @@ AP_OADijkstra::AP_OADijkstra(AP_Int16 &options) : } // calculate a destination to avoid fences -// returns DIJKSTRA_STATE_SUCCESS and populates origin_new and destination_new if avoidance is required -AP_OADijkstra::AP_OADijkstra_State AP_OADijkstra::update(const Location ¤t_loc, const Location &destination, Location& origin_new, Location& destination_new) +// returns DIJKSTRA_STATE_SUCCESS and populates origin_new, destination_new and next_destination_new if avoidance is required +// next_destination_new will be non-zero if there is a next destination +// dest_to_next_dest_clear will be set to true if the path from (the input) destination to (input) next_destination is clear +AP_OADijkstra::AP_OADijkstra_State AP_OADijkstra::update(const Location ¤t_loc, + const Location &destination, + const Location &next_destination, + Location& origin_new, + Location& destination_new, + Location& next_destination_new, + bool& dest_to_next_dest_clear) { WITH_SEMAPHORE(AP::fence()->polyfence().get_loaded_fence_semaphore()); // avoidance is not required if no fences if (!some_fences_enabled()) { + dest_to_next_dest_clear = _dest_to_next_dest_clear = true; Write_OADijkstra(DIJKSTRA_STATE_NOT_REQUIRED, 0, 0, 0, destination, destination); return DIJKSTRA_STATE_NOT_REQUIRED; } // no avoidance required if destination is same as current location if (current_loc.same_latlon_as(destination)) { + // we do not check path to next destination so conservatively set to false + dest_to_next_dest_clear = _dest_to_next_dest_clear = false; Write_OADijkstra(DIJKSTRA_STATE_NOT_REQUIRED, 0, 0, 0, destination, destination); return DIJKSTRA_STATE_NOT_REQUIRED; } @@ -83,6 +94,7 @@ AP_OADijkstra::AP_OADijkstra_State AP_OADijkstra::update(const Location ¤t if (!_inclusion_polygon_with_margin_ok) { _inclusion_polygon_with_margin_ok = create_inclusion_polygon_with_margin(_polyfence_margin * 100.0f, error_id); if (!_inclusion_polygon_with_margin_ok) { + dest_to_next_dest_clear = _dest_to_next_dest_clear = false; report_error(error_id); Write_OADijkstra(DIJKSTRA_STATE_ERROR, (uint8_t)error_id, 0, 0, destination, destination); return DIJKSTRA_STATE_ERROR; @@ -93,6 +105,7 @@ AP_OADijkstra::AP_OADijkstra_State AP_OADijkstra::update(const Location ¤t if (!_exclusion_polygon_with_margin_ok) { _exclusion_polygon_with_margin_ok = create_exclusion_polygon_with_margin(_polyfence_margin * 100.0f, error_id); if (!_exclusion_polygon_with_margin_ok) { + dest_to_next_dest_clear = _dest_to_next_dest_clear = false; report_error(error_id); Write_OADijkstra(DIJKSTRA_STATE_ERROR, (uint8_t)error_id, 0, 0, destination, destination); return DIJKSTRA_STATE_ERROR; @@ -103,6 +116,7 @@ AP_OADijkstra::AP_OADijkstra_State AP_OADijkstra::update(const Location ¤t if (!_exclusion_circle_with_margin_ok) { _exclusion_circle_with_margin_ok = create_exclusion_circle_with_margin(_polyfence_margin * 100.0f, error_id); if (!_exclusion_circle_with_margin_ok) { + dest_to_next_dest_clear = _dest_to_next_dest_clear = false; report_error(error_id); Write_OADijkstra(DIJKSTRA_STATE_ERROR, (uint8_t)error_id, 0, 0, destination, destination); return DIJKSTRA_STATE_ERROR; @@ -114,6 +128,7 @@ AP_OADijkstra::AP_OADijkstra_State AP_OADijkstra::update(const Location ¤t _polyfence_visgraph_ok = create_fence_visgraph(error_id); if (!_polyfence_visgraph_ok) { _shortest_path_ok = false; + dest_to_next_dest_clear = _dest_to_next_dest_clear = false; report_error(error_id); Write_OADijkstra(DIJKSTRA_STATE_ERROR, (uint8_t)error_id, 0, 0, destination, destination); return DIJKSTRA_STATE_ERROR; @@ -133,9 +148,10 @@ AP_OADijkstra::AP_OADijkstra_State AP_OADijkstra::update(const Location ¤t } } - // rebuild path if destination has changed - if (!destination.same_latlon_as(_destination_prev)) { + // rebuild path if destination or next_destination has changed + if (!destination.same_latlon_as(_destination_prev) || !next_destination.same_latlon_as(_next_destination_prev)) { _destination_prev = destination; + _next_destination_prev = next_destination; _shortest_path_ok = false; } @@ -143,17 +159,28 @@ AP_OADijkstra::AP_OADijkstra_State AP_OADijkstra::update(const Location ¤t if (!_shortest_path_ok) { _shortest_path_ok = calc_shortest_path(current_loc, destination, error_id); if (!_shortest_path_ok) { + dest_to_next_dest_clear = _dest_to_next_dest_clear = false; report_error(error_id); Write_OADijkstra(DIJKSTRA_STATE_ERROR, (uint8_t)error_id, 0, 0, destination, destination); return DIJKSTRA_STATE_ERROR; } // start from 2nd point on path (first is the original origin) _path_idx_returned = 1; + + // check if path from destination to next_destination intersects with a fence + _dest_to_next_dest_clear = false; + if (!next_destination.is_zero()) { + Vector2f seg_start, seg_end; + if (destination.get_vector_xy_from_origin_NE(seg_start) && next_destination.get_vector_xy_from_origin_NE(seg_end)) { + _dest_to_next_dest_clear = !intersects_fence(seg_start, seg_end); + } + } } // path has been created, return latest point Vector2f dest_pos; - if (get_shortest_path_point(_path_idx_returned, dest_pos)) { + uint8_t path_length = get_shortest_path_numpoints() > 0 ? (get_shortest_path_numpoints() - 1) : 0; + if ((_path_idx_returned < path_length) && get_shortest_path_point(_path_idx_returned, dest_pos)) { // for the first point return origin as current_loc Vector2f origin_pos; @@ -172,6 +199,23 @@ AP_OADijkstra::AP_OADijkstra_State AP_OADijkstra::update(const Location ¤t destination_new.lat = temp_loc.lat; destination_new.lng = temp_loc.lng; + // if present also provide next destination if present to allow smooth cornering + next_destination_new.zero(); + Vector2f next_dest_pos; + if ((_path_idx_returned + 1 < path_length) && get_shortest_path_point(_path_idx_returned + 1, next_dest_pos)) { + // convert offset from ekf origin to Location + Location next_loc(Vector3f{next_dest_pos.x, next_dest_pos.y, 0.0}, Location::AltFrame::ABOVE_ORIGIN); + next_destination_new = destination; + next_destination_new.lat = next_loc.lat; + next_destination_new.lng = next_loc.lng; + } else { + // return destination as next_destination + next_destination_new = destination; + } + + // path to next destination clear state is still valid from previous calcs (was calced along with shortest path) + dest_to_next_dest_clear = _dest_to_next_dest_clear; + // check if we should advance to next point for next iteration const bool near_oa_wp = current_loc.get_distance(destination_new) <= 2.0f; const bool past_oa_wp = current_loc.past_interval_finish_line(origin_new, destination_new); @@ -179,11 +223,13 @@ AP_OADijkstra::AP_OADijkstra_State AP_OADijkstra::update(const Location ¤t _path_idx_returned++; } // log success - Write_OADijkstra(DIJKSTRA_STATE_SUCCESS, 0, _path_idx_returned, _path_numpoints, destination, destination_new); + Write_OADijkstra(DIJKSTRA_STATE_SUCCESS, 0, _path_idx_returned, get_shortest_path_numpoints(), destination, destination_new); return DIJKSTRA_STATE_SUCCESS; } // we have reached the destination so avoidance is no longer required + // path to next destination clear state is still valid from previous calcs + dest_to_next_dest_clear = _dest_to_next_dest_clear; Write_OADijkstra(DIJKSTRA_STATE_NOT_REQUIRED, 0, 0, 0, destination, destination); return DIJKSTRA_STATE_NOT_REQUIRED; } diff --git a/libraries/AC_Avoidance/AP_OADijkstra.h b/libraries/AC_Avoidance/AP_OADijkstra.h index b37b644c44dcf3..97c832a78a2515 100644 --- a/libraries/AC_Avoidance/AP_OADijkstra.h +++ b/libraries/AC_Avoidance/AP_OADijkstra.h @@ -30,8 +30,16 @@ class AP_OADijkstra { }; // calculate a destination to avoid the polygon fence - // returns DIJKSTRA_STATE_SUCCESS and populates origin_new and destination_new if avoidance is required - AP_OADijkstra_State update(const Location ¤t_loc, const Location &destination, Location& origin_new, Location& destination_new); + // returns DIJKSTRA_STATE_SUCCESS and populates origin_new, destination_new and next_destination_new if avoidance is required + // next_destination_new will be non-zero if there is a next destination + // dest_to_next_dest_clear will be set to true if the path from (the input) destination to (input) next_destination is clear + AP_OADijkstra_State update(const Location ¤t_loc, + const Location &destination, + const Location &next_destination, + Location& origin_new, + Location& destination_new, + Location& next_destination_new, + bool& dest_to_next_dest_clear); private: @@ -124,7 +132,9 @@ class AP_OADijkstra { bool _shortest_path_ok; Location _destination_prev; // destination of previous iterations (used to determine if path should be re-calculated) + Location _next_destination_prev;// next_destination of previous iterations (used to determine if path should be re-calculated) uint8_t _path_idx_returned; // index into _path array which gives location vehicle should be currently moving towards + bool _dest_to_next_dest_clear; // true if path from dest to next_dest is clear (i.e. does not intersects a fence) // inclusion polygon (with margin) related variables float _polyfence_margin = 10; // margin around polygon defaults to 10m but is overriden with set_fence_margin @@ -181,6 +191,9 @@ class AP_OADijkstra { Vector2f _path_source; // source point used in shortest path calculations (offset in cm from EKF origin) Vector2f _path_destination; // destination position used in shortest path calculations (offset in cm from EKF origin) + // return number of points on path + uint8_t get_shortest_path_numpoints() const { return _path_numpoints; } + // return point from final path as an offset (in cm) from the ekf origin bool get_shortest_path_point(uint8_t point_num, Vector2f& pos) const; From a1e03cbbe103c4c437d54ca057351d52abe85fd2 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 15 Dec 2023 14:04:48 +0900 Subject: [PATCH 0233/1335] AC_Avoidance: bendy ruler comment update --- libraries/AC_Avoidance/AP_OABendyRuler.cpp | 4 ++-- libraries/AC_Avoidance/AP_OABendyRuler.h | 5 +++-- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/libraries/AC_Avoidance/AP_OABendyRuler.cpp b/libraries/AC_Avoidance/AP_OABendyRuler.cpp index 673dd552766971..de7f42fce20fb4 100644 --- a/libraries/AC_Avoidance/AP_OABendyRuler.cpp +++ b/libraries/AC_Avoidance/AP_OABendyRuler.cpp @@ -78,8 +78,8 @@ AP_OABendyRuler::AP_OABendyRuler() _bearing_prev = FLT_MAX; } -// run background task to find best path and update avoidance_results -// returns true and updates origin_new and destination_new if a best path has been found +// run background task to find best path +// returns true and updates origin_new and destination_new if a best path has been found. returns false if OA is not required // bendy_type is set to the type of BendyRuler used bool AP_OABendyRuler::update(const Location& current_loc, const Location& destination, const Vector2f &ground_speed_vec, Location &origin_new, Location &destination_new, OABendyType &bendy_type, bool proximity_only) { diff --git a/libraries/AC_Avoidance/AP_OABendyRuler.h b/libraries/AC_Avoidance/AP_OABendyRuler.h index e282e647221942..1b480bdbcfcab5 100644 --- a/libraries/AC_Avoidance/AP_OABendyRuler.h +++ b/libraries/AC_Avoidance/AP_OABendyRuler.h @@ -22,8 +22,9 @@ class AP_OABendyRuler { OA_BENDY_VERTICAL = 2, }; - // run background task to find best path and update avoidance_results - // returns true and populates origin_new and destination_new if OA is required. returns false if OA is not required + // run background task to find best path + // returns true and updates origin_new and destination_new if a best path has been found. returns false if OA is not required + // bendy_type is set to the type of BendyRuler used bool update(const Location& current_loc, const Location& destination, const Vector2f &ground_speed_vec, Location &origin_new, Location &destination_new, OABendyType &bendy_type, bool proximity_only); static const struct AP_Param::GroupInfo var_info[]; From 607fa40431e835078803f267499ef462b9f293c3 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 14 Dec 2023 15:40:28 +0900 Subject: [PATCH 0234/1335] AR_WPNav: send next destination to OA --- libraries/AR_WPNav/AR_WPNav.h | 1 + libraries/AR_WPNav/AR_WPNav_OA.cpp | 17 ++++++++++++++--- libraries/AR_WPNav/AR_WPNav_OA.h | 2 ++ 3 files changed, 17 insertions(+), 3 deletions(-) diff --git a/libraries/AR_WPNav/AR_WPNav.h b/libraries/AR_WPNav/AR_WPNav.h index 1bfb2864aaf9b9..64bbeb9a25e057 100644 --- a/libraries/AR_WPNav/AR_WPNav.h +++ b/libraries/AR_WPNav/AR_WPNav.h @@ -168,6 +168,7 @@ class AR_WPNav { uint32_t _last_update_ms; // system time of last call to update Location _origin; // origin Location (vehicle will travel from the origin to the destination) Location _destination; // destination Location when in Guided_WP + Location _next_destination; // next destination Location when in Guided_WP bool _orig_and_dest_valid; // true if the origin and destination have been set bool _reversed; // execute the mission by backing up enum class NavControllerType { diff --git a/libraries/AR_WPNav/AR_WPNav_OA.cpp b/libraries/AR_WPNav/AR_WPNav_OA.cpp index 0ecdc22c95ffe3..f1fd9886ff8810 100644 --- a/libraries/AR_WPNav/AR_WPNav_OA.cpp +++ b/libraries/AR_WPNav/AR_WPNav_OA.cpp @@ -39,17 +39,28 @@ void AR_WPNav_OA::update(float dt) // run path planning around obstacles bool stop_vehicle = false; - // backup _origin and _destination when not doing oa + // backup _origin, _destination and _next_destination when not doing oa if (!_oa_active) { _origin_oabak = _origin; _destination_oabak = _destination; + _next_destination_oabak = _next_destination; } AP_OAPathPlanner *oa = AP_OAPathPlanner::get_singleton(); if (oa != nullptr) { - Location oa_origin_new, oa_destination_new; + Location oa_origin_new, oa_destination_new, oa_next_destination_new; AP_OAPathPlanner::OAPathPlannerUsed path_planner_used; - const AP_OAPathPlanner::OA_RetState oa_retstate = oa->mission_avoidance(current_loc, _origin_oabak, _destination_oabak, oa_origin_new, oa_destination_new, path_planner_used); + bool dest_to_next_dest_clear; + const AP_OAPathPlanner::OA_RetState oa_retstate = oa->mission_avoidance(current_loc, + _origin_oabak, + _destination_oabak, + _next_destination_oabak, + oa_origin_new, + oa_destination_new, + oa_next_destination_new, + dest_to_next_dest_clear, + path_planner_used); + switch (oa_retstate) { case AP_OAPathPlanner::OA_NOT_REQUIRED: diff --git a/libraries/AR_WPNav/AR_WPNav_OA.h b/libraries/AR_WPNav/AR_WPNav_OA.h index 195ed3028f2815..2130579eebaa97 100644 --- a/libraries/AR_WPNav/AR_WPNav_OA.h +++ b/libraries/AR_WPNav/AR_WPNav_OA.h @@ -36,8 +36,10 @@ class AR_WPNav_OA : public AR_WPNav { bool _oa_active; // true if we should use alternative destination to avoid obstacles Location _origin_oabak; // backup of _origin so it can be restored when oa completes Location _destination_oabak; // backup of _desitnation so it can be restored when oa completes + Location _next_destination_oabak; // backup of _next_destination so it can be restored when oa completes Location _oa_origin; // intermediate origin during avoidance Location _oa_destination; // intermediate destination during avoidance + Location _oa_next_destination; // intermediate next destination during avoidance float _oa_distance_to_destination; // OA (object avoidance) distance from vehicle to _oa_destination in meters float _oa_wp_bearing_cd; // OA adjusted heading to _oa_destination in centi-degrees }; From 58b64298934ba60b497c8238eb22856bc516835d Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 18 Dec 2023 16:26:40 +0900 Subject: [PATCH 0235/1335] AC_Avoidance: oapathplanner gets fast-waypoint option --- libraries/AC_Avoidance/AP_OAPathPlanner.cpp | 2 +- libraries/AC_Avoidance/AP_OAPathPlanner.h | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AC_Avoidance/AP_OAPathPlanner.cpp b/libraries/AC_Avoidance/AP_OAPathPlanner.cpp index 48595b4fb42802..5e2b0f7e6c0026 100644 --- a/libraries/AC_Avoidance/AP_OAPathPlanner.cpp +++ b/libraries/AC_Avoidance/AP_OAPathPlanner.cpp @@ -59,7 +59,7 @@ const AP_Param::GroupInfo AP_OAPathPlanner::var_info[] = { // @DisplayName: Options while recovering from Object Avoidance // @Description: Bitmask which will govern vehicles behaviour while recovering from Obstacle Avoidance (i.e Avoidance is turned off after the path ahead is clear). // @Bitmask{Rover}: 0: Reset the origin of the waypoint to the present location, 1: log Dijkstra points - // @Bitmask{Copter}: 1: log Dijkstra points + // @Bitmask{Copter}: 1:log Dijkstra points, 2:Allow fast waypoints (Dijkastras only) // @User: Standard AP_GROUPINFO("OPTIONS", 5, AP_OAPathPlanner, _options, OA_OPTIONS_DEFAULT), diff --git a/libraries/AC_Avoidance/AP_OAPathPlanner.h b/libraries/AC_Avoidance/AP_OAPathPlanner.h index b6f57b16e6e5d6..3c08dc4b7690d8 100644 --- a/libraries/AC_Avoidance/AP_OAPathPlanner.h +++ b/libraries/AC_Avoidance/AP_OAPathPlanner.h @@ -74,6 +74,7 @@ class AP_OAPathPlanner { OA_OPTION_DISABLED = 0, OA_OPTION_WP_RESET = (1 << 0), OA_OPTION_LOG_DIJKSTRA_POINTS = (1 << 1), + OA_OPTION_FAST_WAYPOINTS = (1 << 2), }; uint16_t get_options() const { return _options;} From 6c24f80669e613ac0174dbdca5b577931066e50d Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 27 Dec 2023 11:42:31 +0900 Subject: [PATCH 0236/1335] AC_Avoidance: Dijsktras comment and const fix --- libraries/AC_Avoidance/AP_OADijkstra.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AC_Avoidance/AP_OADijkstra.cpp b/libraries/AC_Avoidance/AP_OADijkstra.cpp index 0083f64795c82d..f5150cd6ea32cb 100644 --- a/libraries/AC_Avoidance/AP_OADijkstra.cpp +++ b/libraries/AC_Avoidance/AP_OADijkstra.cpp @@ -179,7 +179,7 @@ AP_OADijkstra::AP_OADijkstra_State AP_OADijkstra::update(const Location ¤t // path has been created, return latest point Vector2f dest_pos; - uint8_t path_length = get_shortest_path_numpoints() > 0 ? (get_shortest_path_numpoints() - 1) : 0; + const uint8_t path_length = get_shortest_path_numpoints() > 0 ? (get_shortest_path_numpoints() - 1) : 0; if ((_path_idx_returned < path_length) && get_shortest_path_point(_path_idx_returned, dest_pos)) { // for the first point return origin as current_loc @@ -199,7 +199,7 @@ AP_OADijkstra::AP_OADijkstra_State AP_OADijkstra::update(const Location ¤t destination_new.lat = temp_loc.lat; destination_new.lng = temp_loc.lng; - // if present also provide next destination if present to allow smooth cornering + // provide next destination to allow smooth cornering next_destination_new.zero(); Vector2f next_dest_pos; if ((_path_idx_returned + 1 < path_length) && get_shortest_path_point(_path_idx_returned + 1, next_dest_pos)) { From 1d0fc4e87c6cacb782cbbdead6f759e37f411186 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 28 Dec 2023 09:29:57 +1100 Subject: [PATCH 0237/1335] AP_ExternalAHRS: fixed InertialLabs gyro/accel data this fixes a flapping CI test --- libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp index a20beb13c0e920..ebf844f32493bf 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp @@ -438,6 +438,8 @@ bool AP_ExternalAHRS_InertialLabs::check_uart() if (GOT_MSG(ACCEL_DATA_HR) && GOT_MSG(GYRO_DATA_HR)) { AP::ins().handle_external(ins_data); + state.accel = ins_data.accel; + state.gyro = ins_data.gyro; } if (GOT_MSG(GPS_INS_TIME_MS) && GOT_MSG(NUM_SATS) && From 6fb99d6b1ebc5bf3bbd8edef199fd0bc8b34100f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 29 Dec 2023 09:45:38 +1100 Subject: [PATCH 0238/1335] AP_Scripting: fixed use after free bug found with valgrind --- libraries/AP_Scripting/lua_scripts.cpp | 13 ++++++------- 1 file changed, 6 insertions(+), 7 deletions(-) diff --git a/libraries/AP_Scripting/lua_scripts.cpp b/libraries/AP_Scripting/lua_scripts.cpp index d1c8badff71d95..b1b60a29c8a711 100644 --- a/libraries/AP_Scripting/lua_scripts.cpp +++ b/libraries/AP_Scripting/lua_scripts.cpp @@ -402,19 +402,18 @@ void lua_scripts::remove_script(lua_State *L, script_info *script) { } } + { + // Remove from running checksum + WITH_SEMAPHORE(crc_sem); + running_checksum ^= script->crc; + } + if (L != nullptr) { // state could be null if we are force killing all scripts luaL_unref(L, LUA_REGISTRYINDEX, script->lua_ref); } _heap.deallocate(script->name); _heap.deallocate(script); - - { - // Remove from running checksum - WITH_SEMAPHORE(crc_sem); - running_checksum ^= script->crc; - } - } void lua_scripts::reschedule_script(script_info *script) { From e2f82ed9bcbff37c87ca2bc5f5605dc602664bf8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 29 Dec 2023 17:21:09 +1100 Subject: [PATCH 0239/1335] HAL_ESP32: added esp32s3empty target --- libraries/AP_HAL_ESP32/Util.cpp | 18 +--- libraries/AP_HAL_ESP32/Util.h | 4 +- libraries/AP_HAL_ESP32/boards/esp32s3empty.h | 89 +++++++++++++++++++ .../AP_HAL_ESP32/hwdef/esp32s3empty/hwdef.dat | 0 .../targets/esp32/esp-idf/sdkconfig | 30 +------ .../targets/esp32s3/esp-idf/sdkconfig | 28 +----- 6 files changed, 98 insertions(+), 71 deletions(-) create mode 100644 libraries/AP_HAL_ESP32/boards/esp32s3empty.h create mode 100644 libraries/AP_HAL_ESP32/hwdef/esp32s3empty/hwdef.dat diff --git a/libraries/AP_HAL_ESP32/Util.cpp b/libraries/AP_HAL_ESP32/Util.cpp index fa0e6060b62b20..d232ff890765e5 100644 --- a/libraries/AP_HAL_ESP32/Util.cpp +++ b/libraries/AP_HAL_ESP32/Util.cpp @@ -33,6 +33,7 @@ #include "esp_log.h" #include "esp_system.h" #include "esp_heap_caps.h" +#include extern const AP_HAL::HAL& hal; @@ -268,28 +269,17 @@ bool Util::was_watchdog_reset() const || reason == ESP_RST_WDT; } -#if CH_DBG_ENABLE_STACK_CHECK == TRUE /* display stack usage as text buffer for @SYS/threads.txt */ -size_t Util::thread_info(char *buf, size_t bufsize) +void Util::thread_info(ExpandingString &str) { - thread_t *tp; - size_t total = 0; - // a header to allow for machine parsers to determine format - int n = snprintf(buf, bufsize, "ThreadsV1\n"); - if (n <= 0) { - return 0; - } + str.printf("ThreadsV1\n"); // char buffer[1024]; // vTaskGetRunTimeStats(buffer); // snprintf(buf, bufsize,"\n\n%s\n", buffer); - - // total = .. - - return total; } -#endif // CH_DBG_ENABLE_STACK_CHECK == TRUE + diff --git a/libraries/AP_HAL_ESP32/Util.h b/libraries/AP_HAL_ESP32/Util.h index 15cf1a72a25d0b..3360e1ad5a1974 100644 --- a/libraries/AP_HAL_ESP32/Util.h +++ b/libraries/AP_HAL_ESP32/Util.h @@ -62,10 +62,8 @@ class ESP32::Util : public AP_HAL::Util // return true if the reason for the reboot was a watchdog reset bool was_watchdog_reset() const override; -#if CH_DBG_ENABLE_STACK_CHECK == TRUE // request information on running threads - size_t thread_info(char *buf, size_t bufsize) override; -#endif + void thread_info(ExpandingString &str) override; private: #ifdef HAL_PWM_ALARM diff --git a/libraries/AP_HAL_ESP32/boards/esp32s3empty.h b/libraries/AP_HAL_ESP32/boards/esp32s3empty.h new file mode 100644 index 00000000000000..d8f2af7f76cd8a --- /dev/null +++ b/libraries/AP_HAL_ESP32/boards/esp32s3empty.h @@ -0,0 +1,89 @@ +/* + * This file is free software: you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program. If not, see . + */ +#pragma once + +#define CONFIG_HAL_BOARD_SUBTYPE HAL_BOARD_SUBTYPE_ESP32_S3EMPTY +// make sensor selection clearer + +//- these are missing from esp-idf......will not be needed later +#define RTC_WDT_STG_SEL_OFF 0 +#define RTC_WDT_STG_SEL_INT 1 +#define RTC_WDT_STG_SEL_RESET_CPU 2 +#define RTC_WDT_STG_SEL_RESET_SYSTEM 3 +#define RTC_WDT_STG_SEL_RESET_RTC 4 + +#define HAL_ESP32_BOARD_NAME "esp32s3empty" + +#define HAL_ESP32_RMT_RX_PIN_NUMBER GPIO_NUM_14 + +// no sensors +#define HAL_INS_DEFAULT HAL_INS_NONE + +#define HAL_BARO_ALLOW_INIT_NO_BARO 1 + +#define AP_COMPASS_ENABLE_DEFAULT 0 +#define ALLOW_ARM_NO_COMPASS +#define AP_AIRSPEED_ENABLED 0 +#define AP_AIRSPEED_ANALOG_ENABLED 0 +#define AP_AIRSPEED_BACKEND_DEFAULT_ENABLED 0 + +// no ADC +#define HAL_DISABLE_ADC_DRIVER 1 +#define HAL_USE_ADC 0 + +// 2 use udp, 1 use tcp... for udp,client needs to connect as UDPCL in missionplanner etc to 192.168.4.1 port 14550 +#define HAL_ESP32_WIFI 1 + +// see boards.py +#ifndef ENABLE_HEAP +#define ENABLE_HEAP 1 +#endif + +#define WIFI_SSID "ardupilot123" +#define WIFI_PWD "ardupilot123" + +//RCOUT which pins are used? + +#define HAL_ESP32_RCOUT { GPIO_NUM_11,GPIO_NUM_10, GPIO_NUM_9, GPIO_NUM_8, GPIO_NUM_7, GPIO_NUM_6 } + +// SPI BUS setup, including gpio, dma, etc +// note... we use 'vspi' for the bmp280 and mpu9250 +#define HAL_ESP32_SPI_BUSES {} + +// SPI per-device setup, including speeds, etc. +#define HAL_ESP32_SPI_DEVICES {} + +//I2C bus list +#define HAL_ESP32_I2C_BUSES {.port=I2C_NUM_0, .sda=GPIO_NUM_13, .scl=GPIO_NUM_14, .speed=400*KHZ, .internal=true, .soft=true} + +// rcin on what pin? +#define HAL_ESP32_RCIN GPIO_NUM_14 + + +//HARDWARE UARTS +#define HAL_ESP32_UART_DEVICES \ + {.port=UART_NUM_0, .rx=GPIO_NUM_44, .tx=GPIO_NUM_43 },{.port=UART_NUM_1, .rx=GPIO_NUM_17, .tx=GPIO_NUM_18 } + +#define HAL_LOGGING_FILESYSTEM_ENABLED 0 +#define HAL_LOGGING_DATAFLASH_ENABLED 0 +#define HAL_LOGGING_MAVLINK_ENABLED 0 + +#define HAL_BOARD_LOG_DIRECTORY "/SDCARD/APM/LOGS" +#define HAL_BOARD_STORAGE_DIRECTORY "/SDCARD/APM/STORAGE" +#define HAL_BOARD_LOG_DIRECTORY "/SDCARD/APM/LOGS" +#define HAL_BOARD_TERRAIN_DIRECTORY "/SDCARD/APM/TERRAIN" + +#define HAL_LOGGING_BACKENDS_DEFAULT 1 + diff --git a/libraries/AP_HAL_ESP32/hwdef/esp32s3empty/hwdef.dat b/libraries/AP_HAL_ESP32/hwdef/esp32s3empty/hwdef.dat new file mode 100644 index 00000000000000..e69de29bb2d1d6 diff --git a/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/sdkconfig b/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/sdkconfig index 397f554e1c4135..cbdbc78de6d03c 100644 --- a/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/sdkconfig +++ b/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/sdkconfig @@ -203,7 +203,6 @@ CONFIG_SPI_SLAVE_ISR_IN_IRAM=y # CONFIG_TWAI_ERRATA_FIX_TX_INTR_LOST is not set # CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID is not set # CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT is not set -# CONFIG_TWAI_ERRATA_FIX_LISTEN_ONLY_DOM is not set # end of TWAI configuration # @@ -248,16 +247,9 @@ CONFIG_EFUSE_MAX_BLK_LEN=192 # CONFIG_ESP32_REV_MIN_0=y # CONFIG_ESP32_REV_MIN_1 is not set -# CONFIG_ESP32_REV_MIN_1_1 is not set # CONFIG_ESP32_REV_MIN_2 is not set # CONFIG_ESP32_REV_MIN_3 is not set -# CONFIG_ESP32_REV_MIN_3_1 is not set CONFIG_ESP32_REV_MIN=0 -CONFIG_ESP32_REV_MIN_FULL=0 -CONFIG_ESP_REV_MIN_FULL=0 -CONFIG_ESP32_REV_MAX_FULL_STR_OPT=y -CONFIG_ESP32_REV_MAX_FULL=399 -CONFIG_ESP_REV_MAX_FULL=399 CONFIG_ESP32_DPORT_WORKAROUND=y # CONFIG_ESP32_DEFAULT_CPU_FREQ_80 is not set # CONFIG_ESP32_DEFAULT_CPU_FREQ_160 is not set @@ -359,7 +351,6 @@ CONFIG_ESP_MAC_ADDR_UNIVERSE_BT=y CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES_TWO=y # CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES_FOUR is not set CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES=2 -# CONFIG_ESP_MAC_IGNORE_MAC_CRC_ERROR is not set # end of MAC Config # @@ -369,7 +360,6 @@ CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES=2 CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y # CONFIG_ESP_SLEEP_GPIO_RESET_WORKAROUND is not set CONFIG_ESP_SLEEP_FLASH_LEAKAGE_WORKAROUND=y -# CONFIG_ESP_SLEEP_MSPI_NEED_ALL_IO_PU is not set # end of Sleep Config # @@ -414,13 +404,6 @@ CONFIG_PM_ENABLE=y # CONFIG_PM_TRACE is not set # end of Power Management -# -# ESP Ringbuf -# -# CONFIG_RINGBUF_PLACE_FUNCTIONS_INTO_FLASH is not set -# CONFIG_RINGBUF_PLACE_ISR_FUNCTIONS_INTO_FLASH is not set -# end of ESP Ringbuf - # # ESP System Settings # @@ -502,8 +485,6 @@ CONFIG_ESP32_WIFI_ENABLE_WPA3_SAE=y # CONFIG_ESP_WIFI_STA_DISCONNECTED_PM_ENABLE is not set # CONFIG_ESP_WIFI_GMAC_SUPPORT is not set CONFIG_ESP_WIFI_SOFTAP_SUPPORT=y -# CONFIG_ESP_WIFI_SLP_BEACON_LOST_OPT is not set -CONFIG_ESP_WIFI_ESPNOW_MAX_ENCRYPT_NUM=7 # end of Wi-Fi # @@ -519,7 +500,6 @@ CONFIG_ESP_COREDUMP_CHECKSUM_CRC32=y CONFIG_ESP_COREDUMP_ENABLE=y CONFIG_ESP_COREDUMP_MAX_TASKS_NUM=64 CONFIG_ESP_COREDUMP_UART_DELAY=0 -CONFIG_ESP_COREDUMP_STACK_SIZE=0 CONFIG_ESP_COREDUMP_DECODE_INFO=y # CONFIG_ESP_COREDUMP_DECODE_DISABLE is not set CONFIG_ESP_COREDUMP_DECODE="info" @@ -653,7 +633,6 @@ CONFIG_LOG_TIMESTAMP_SOURCE_RTOS=y CONFIG_LWIP_LOCAL_HOSTNAME="espressif" # CONFIG_LWIP_NETIF_API is not set # CONFIG_LWIP_TCPIP_CORE_LOCKING is not set -# CONFIG_LWIP_CHECK_THREAD_SAFETY is not set CONFIG_LWIP_DNS_SUPPORT_MDNS_QUERIES=y # CONFIG_LWIP_L2_TO_L3_COPY is not set # CONFIG_LWIP_IRAM_OPTIMIZATION is not set @@ -674,15 +653,12 @@ CONFIG_LWIP_IP6_FRAG=y # CONFIG_LWIP_ETHARP_TRUST_IP_MAC is not set CONFIG_LWIP_ESP_GRATUITOUS_ARP=y CONFIG_LWIP_GARP_TMR_INTERVAL=60 -CONFIG_LWIP_ESP_MLDV6_REPORT=y -CONFIG_LWIP_MLDV6_TMR_INTERVAL=40 CONFIG_LWIP_TCPIP_RECVMBOX_SIZE=32 CONFIG_LWIP_DHCP_DOES_ARP_CHECK=y # CONFIG_LWIP_DHCP_DISABLE_CLIENT_ID is not set CONFIG_LWIP_DHCP_DISABLE_VENDOR_CLASS_ID=y # CONFIG_LWIP_DHCP_RESTORE_LAST_IP is not set CONFIG_LWIP_DHCP_OPTIONS_LEN=68 -CONFIG_LWIP_DHCP_COARSE_TIMER_SECS=1 # # DHCP server @@ -712,7 +688,6 @@ CONFIG_LWIP_TCP_SYNMAXRTX=6 CONFIG_LWIP_TCP_MSS=1436 CONFIG_LWIP_TCP_TMR_INTERVAL=250 CONFIG_LWIP_TCP_MSL=60000 -CONFIG_LWIP_TCP_FIN_WAIT_TIMEOUT=20000 CONFIG_LWIP_TCP_SND_BUF_DEFAULT=5744 CONFIG_LWIP_TCP_WND_DEFAULT=5744 CONFIG_LWIP_TCP_RECVMBOX_SIZE=6 @@ -828,7 +803,6 @@ CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_FULL=y # CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_CMN is not set # CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_NONE is not set # CONFIG_MBEDTLS_CUSTOM_CERTIFICATE_BUNDLE is not set -CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_MAX_CERTS=200 # end of Certificate Bundle # CONFIG_MBEDTLS_ECP_RESTARTABLE is not set @@ -947,7 +921,6 @@ CONFIG_NEWLIB_STDIN_LINE_ENDING_CR=y # # NVS # -# CONFIG_NVS_ASSERT_ERROR_CHECK is not set # end of NVS # @@ -1016,6 +989,7 @@ CONFIG_VFS_SUPPORT_TERMIOS=y # Host File System I/O (Semihosting) # CONFIG_VFS_SEMIHOSTFS_MAX_MOUNT_POINTS=1 +CONFIG_VFS_SEMIHOSTFS_HOST_PATH_MAX_LEN=128 # end of Host File System I/O (Semihosting) # end of Virtual file system @@ -1157,7 +1131,6 @@ CONFIG_ESP32_COREDUMP_CHECKSUM_CRC32=y CONFIG_ESP32_ENABLE_COREDUMP=y CONFIG_ESP32_CORE_DUMP_MAX_TASKS_NUM=64 CONFIG_ESP32_CORE_DUMP_UART_DELAY=0 -CONFIG_ESP32_CORE_DUMP_STACK_SIZE=0 CONFIG_ESP32_CORE_DUMP_DECODE_INFO=y # CONFIG_ESP32_CORE_DUMP_DECODE_DISABLE is not set CONFIG_ESP32_CORE_DUMP_DECODE="info" @@ -1203,4 +1176,5 @@ CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_ABORTS=y CONFIG_SUPPRESS_SELECT_DEBUG_OUTPUT=y CONFIG_SUPPORT_TERMIOS=y CONFIG_SEMIHOSTFS_MAX_MOUNT_POINTS=1 +CONFIG_SEMIHOSTFS_HOST_PATH_MAX_LEN=128 # End of deprecated options diff --git a/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/sdkconfig b/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/sdkconfig index ecac3313a903da..3c88fb833feaef 100644 --- a/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/sdkconfig +++ b/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/sdkconfig @@ -189,7 +189,6 @@ CONFIG_APPTRACE_LOCK_ENABLE=y # # CONFIG_ADC_FORCE_XPD_FSM is not set CONFIG_ADC_DISABLE_DAC=y -# CONFIG_ADC_CONTINUOUS_FORCE_USE_ADC2_ON_C3_S3 is not set # end of ADC configuration # @@ -211,7 +210,6 @@ CONFIG_SPI_SLAVE_ISR_IN_IRAM=y # TWAI configuration # # CONFIG_TWAI_ISR_IN_IRAM is not set -# CONFIG_TWAI_ERRATA_FIX_LISTEN_ONLY_DOM is not set # end of TWAI configuration # @@ -239,14 +237,6 @@ CONFIG_EFUSE_MAX_BLK_LEN=256 # # ESP32S3-Specific # -CONFIG_ESP32S3_REV_MIN_0=y -# CONFIG_ESP32S3_REV_MIN_1 is not set -# CONFIG_ESP32S3_REV_MIN_2 is not set -CONFIG_ESP32S3_REV_MIN_FULL=0 -CONFIG_ESP_REV_MIN_FULL=0 -CONFIG_ESP32S3_REV_MAX_FULL_STR_OPT=y -CONFIG_ESP32S3_REV_MAX_FULL=99 -CONFIG_ESP_REV_MAX_FULL=99 # CONFIG_ESP32S3_DEFAULT_CPU_FREQ_80 is not set CONFIG_ESP32S3_DEFAULT_CPU_FREQ_160=y # CONFIG_ESP32S3_DEFAULT_CPU_FREQ_240 is not set @@ -411,13 +401,6 @@ CONFIG_PM_POWER_DOWN_CPU_IN_LIGHT_SLEEP=y CONFIG_PM_POWER_DOWN_TAGMEM_IN_LIGHT_SLEEP=y # end of Power Management -# -# ESP Ringbuf -# -# CONFIG_RINGBUF_PLACE_FUNCTIONS_INTO_FLASH is not set -# CONFIG_RINGBUF_PLACE_ISR_FUNCTIONS_INTO_FLASH is not set -# end of ESP Ringbuf - # # ESP System Settings # @@ -507,8 +490,6 @@ CONFIG_ESP32_WIFI_ENABLE_WPA3_SAE=y # CONFIG_ESP_WIFI_GCMP_SUPPORT is not set # CONFIG_ESP_WIFI_GMAC_SUPPORT is not set CONFIG_ESP_WIFI_SOFTAP_SUPPORT=y -# CONFIG_ESP_WIFI_SLP_BEACON_LOST_OPT is not set -CONFIG_ESP_WIFI_ESPNOW_MAX_ENCRYPT_NUM=7 # end of Wi-Fi # @@ -645,7 +626,6 @@ CONFIG_LOG_TIMESTAMP_SOURCE_RTOS=y CONFIG_LWIP_LOCAL_HOSTNAME="espressif" # CONFIG_LWIP_NETIF_API is not set # CONFIG_LWIP_TCPIP_CORE_LOCKING is not set -# CONFIG_LWIP_CHECK_THREAD_SAFETY is not set CONFIG_LWIP_DNS_SUPPORT_MDNS_QUERIES=y # CONFIG_LWIP_L2_TO_L3_COPY is not set # CONFIG_LWIP_IRAM_OPTIMIZATION is not set @@ -666,15 +646,12 @@ CONFIG_LWIP_IP6_FRAG=y # CONFIG_LWIP_ETHARP_TRUST_IP_MAC is not set CONFIG_LWIP_ESP_GRATUITOUS_ARP=y CONFIG_LWIP_GARP_TMR_INTERVAL=60 -CONFIG_LWIP_ESP_MLDV6_REPORT=y -CONFIG_LWIP_MLDV6_TMR_INTERVAL=40 CONFIG_LWIP_TCPIP_RECVMBOX_SIZE=32 CONFIG_LWIP_DHCP_DOES_ARP_CHECK=y # CONFIG_LWIP_DHCP_DISABLE_CLIENT_ID is not set CONFIG_LWIP_DHCP_DISABLE_VENDOR_CLASS_ID=y # CONFIG_LWIP_DHCP_RESTORE_LAST_IP is not set CONFIG_LWIP_DHCP_OPTIONS_LEN=68 -CONFIG_LWIP_DHCP_COARSE_TIMER_SECS=1 # # DHCP server @@ -704,7 +681,6 @@ CONFIG_LWIP_TCP_SYNMAXRTX=12 CONFIG_LWIP_TCP_MSS=1440 CONFIG_LWIP_TCP_TMR_INTERVAL=250 CONFIG_LWIP_TCP_MSL=60000 -CONFIG_LWIP_TCP_FIN_WAIT_TIMEOUT=20000 CONFIG_LWIP_TCP_SND_BUF_DEFAULT=5744 CONFIG_LWIP_TCP_WND_DEFAULT=5744 CONFIG_LWIP_TCP_RECVMBOX_SIZE=6 @@ -815,7 +791,6 @@ CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_FULL=y # CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_CMN is not set # CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_NONE is not set # CONFIG_MBEDTLS_CUSTOM_CERTIFICATE_BUNDLE is not set -CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_MAX_CERTS=200 # end of Certificate Bundle # CONFIG_MBEDTLS_ECP_RESTARTABLE is not set @@ -932,7 +907,6 @@ CONFIG_NEWLIB_STDIN_LINE_ENDING_CR=y # # NVS # -# CONFIG_NVS_ASSERT_ERROR_CHECK is not set # end of NVS # @@ -1003,6 +977,7 @@ CONFIG_VFS_SUPPORT_TERMIOS=y # Host File System I/O (Semihosting) # CONFIG_VFS_SEMIHOSTFS_MAX_MOUNT_POINTS=1 +CONFIG_VFS_SEMIHOSTFS_HOST_PATH_MAX_LEN=128 # end of Host File System I/O (Semihosting) # end of Virtual file system @@ -1156,4 +1131,5 @@ CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_ABORTS=y CONFIG_SUPPRESS_SELECT_DEBUG_OUTPUT=y CONFIG_SUPPORT_TERMIOS=y CONFIG_SEMIHOSTFS_MAX_MOUNT_POINTS=1 +CONFIG_SEMIHOSTFS_HOST_PATH_MAX_LEN=128 # End of deprecated options From e79f0201bd1864e09fd290abb401623cf8c1fc7b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 29 Dec 2023 17:21:43 +1100 Subject: [PATCH 0240/1335] AP_HAL: added esp32s3empty --- libraries/AP_HAL/AP_HAL_Boards.h | 1 + libraries/AP_HAL/board/esp32.h | 4 ++++ 2 files changed, 5 insertions(+) diff --git a/libraries/AP_HAL/AP_HAL_Boards.h b/libraries/AP_HAL/AP_HAL_Boards.h index 4831aeaf91840c..254895827266d3 100644 --- a/libraries/AP_HAL/AP_HAL_Boards.h +++ b/libraries/AP_HAL/AP_HAL_Boards.h @@ -68,6 +68,7 @@ #define HAL_BOARD_SUBTYPE_ESP32_TOMTE76 6005 #define HAL_BOARD_SUBTYPE_ESP32_NICK 6006 #define HAL_BOARD_SUBTYPE_ESP32_S3DEVKIT 6007 +#define HAL_BOARD_SUBTYPE_ESP32_S3EMPTY 6008 /* InertialSensor driver types */ #define HAL_INS_NONE 0 diff --git a/libraries/AP_HAL/board/esp32.h b/libraries/AP_HAL/board/esp32.h index 02a39cfc7ad537..5aa515e6149af0 100644 --- a/libraries/AP_HAL/board/esp32.h +++ b/libraries/AP_HAL/board/esp32.h @@ -15,6 +15,10 @@ #include "esp32nick.h" //Nick K. on discord #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_ESP32_S3DEVKIT #include "esp32s3devkit.h" //Nick K. on discord +#elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_ESP32_S3EMPTY +#include "esp32s3empty.h" +#else +#error "Invalid CONFIG_HAL_BOARD_SUBTYPE for esp32" #endif #define HAL_BOARD_NAME "ESP32" From 990b10bbca9eb4c41fa9963dd0a700d1feb4e4e5 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 29 Dec 2023 17:22:05 +1100 Subject: [PATCH 0241/1335] Tools: added esp32s3empty and gdb startup file for esp32 --- Tools/debug/gdb-openocd-esp32.init | 13 +++++++++++++ Tools/scripts/size_compare_branches.py | 1 + 2 files changed, 14 insertions(+) create mode 100644 Tools/debug/gdb-openocd-esp32.init diff --git a/Tools/debug/gdb-openocd-esp32.init b/Tools/debug/gdb-openocd-esp32.init new file mode 100644 index 00000000000000..b4e10495a0a9e1 --- /dev/null +++ b/Tools/debug/gdb-openocd-esp32.init @@ -0,0 +1,13 @@ +# copy this file to .gdbinit in your Firmware tree + +# this sets up gdb to use openocd. You must start openocd first +target extended-remote :3333 + +set print pretty +set remote hardware-watchpoint-limit 2 +mon reset halt +maintenance flush register-cache +thb app_main +b AP_HAL::panic +set confirm off +c diff --git a/Tools/scripts/size_compare_branches.py b/Tools/scripts/size_compare_branches.py index 08751595854634..9749569d87bb2a 100755 --- a/Tools/scripts/size_compare_branches.py +++ b/Tools/scripts/size_compare_branches.py @@ -208,6 +208,7 @@ def esp32_board_names(self): 'esp32tomte76', 'esp32nick', 'esp32s3devkit', + 'esp32s3empty', 'esp32icarous', 'esp32diy', ] From 4b908077c2efea47274133964631e53384dbad19 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 29 Dec 2023 17:29:32 +1100 Subject: [PATCH 0242/1335] HAL_ESP32: push S3 to 500Hz --- libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/sdkconfig | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/sdkconfig b/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/sdkconfig index 3c88fb833feaef..4ec0f241db1a68 100644 --- a/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/sdkconfig +++ b/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/sdkconfig @@ -544,7 +544,7 @@ CONFIG_FREERTOS_TICK_SUPPORT_SYSTIMER=y CONFIG_FREERTOS_CORETIMER_SYSTIMER_LVL1=y # CONFIG_FREERTOS_CORETIMER_SYSTIMER_LVL3 is not set CONFIG_FREERTOS_SYSTICK_USES_SYSTIMER=y -CONFIG_FREERTOS_HZ=100 +CONFIG_FREERTOS_HZ=500 CONFIG_FREERTOS_ASSERT_ON_UNTESTED_FUNCTION=y # CONFIG_FREERTOS_CHECK_STACKOVERFLOW_NONE is not set # CONFIG_FREERTOS_CHECK_STACKOVERFLOW_PTRVAL is not set From 564041f59229e3720e3de58cbbc4af70811e57eb Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 29 Dec 2023 15:49:40 +1100 Subject: [PATCH 0243/1335] waf: added WAF_BUILD_TARGET for esp32 build --- Tools/ardupilotwaf/esp32.py | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/ardupilotwaf/esp32.py b/Tools/ardupilotwaf/esp32.py index 20a9528860de18..5e30e39ce3a8ef 100644 --- a/Tools/ardupilotwaf/esp32.py +++ b/Tools/ardupilotwaf/esp32.py @@ -62,6 +62,7 @@ def pre_build(self): """Configure esp-idf as lib target""" lib_vars = OrderedDict() lib_vars['ARDUPILOT_CMD'] = self.cmd + lib_vars['WAF_BUILD_TARGET'] = self.targets lib_vars['ARDUPILOT_LIB'] = self.bldnode.find_or_declare('lib/').abspath() lib_vars['ARDUPILOT_BIN'] = self.bldnode.find_or_declare('lib/bin').abspath() target = self.env.ESP32_TARGET From 687c5887af0752016964b85486fdf9b8f0994098 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 29 Dec 2023 15:51:20 +1100 Subject: [PATCH 0244/1335] HAL_ESP32: allow for building of examples and tool firmware on ESP32 use waf build target to find the right library name --- .../targets/esp32/esp-idf/CMakeLists.txt | 26 +++++++++------- .../targets/esp32s3/esp-idf/CMakeLists.txt | 30 +++++++++---------- 2 files changed, 31 insertions(+), 25 deletions(-) diff --git a/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/CMakeLists.txt b/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/CMakeLists.txt index 07f1a4df7e8e77..5c03820e3f827e 100644 --- a/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/CMakeLists.txt +++ b/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/CMakeLists.txt @@ -34,25 +34,31 @@ if(NOT DEFINED ARDUPILOT_CMD) set(ARDUPILOT_CMD "none") endif() -IF(${ARDUPILOT_CMD} STREQUAL "plane") +message("ARDUPILOT_CMD=${ARDUPILOT_CMD}") +message("WAF_BUILD_TARGET=${WAF_BUILD_TARGET}") + +string(REGEX MATCH "^(examples|tool)/" IS_EXAMPLE "${WAF_BUILD_TARGET}") + +if (IS_EXAMPLE) + string(REPLACE "/" ";" A ${WAF_BUILD_TARGET}) + list(GET A 0 EXAMPLE_BASE) + list(GET A 1 EXAMPLE_NAME) + message("Building ${EXAMPLE_BASE} ${EXAMPLE_NAME}") + target_link_libraries(${elf_file} "${ARDUPILOT_LIB}/${EXAMPLE_BASE}/lib${EXAMPLE_NAME}.a") + target_link_libraries(${elf_file} "${ARDUPILOT_LIB}/libap.a") +ELSEIF(${ARDUPILOT_CMD} STREQUAL "plane") message("Building for plane") target_link_libraries(${elf_file} "${ARDUPILOT_BIN}/libarduplane.a") target_link_libraries(${elf_file} "${ARDUPILOT_LIB}/libArduPlane_libs.a") -ENDIF() - -IF(${ARDUPILOT_CMD} STREQUAL "copter") +ELSEIF(${ARDUPILOT_CMD} STREQUAL "copter") message("Building for copter") target_link_libraries(${elf_file} "${ARDUPILOT_BIN}/libarducopter.a") target_link_libraries(${elf_file} "${ARDUPILOT_LIB}/libArduCopter_libs.a") -ENDIF() - -IF(${ARDUPILOT_CMD} STREQUAL "rover") +ELSEIF(${ARDUPILOT_CMD} STREQUAL "rover") message("Building for rover") target_link_libraries(${elf_file} "${ARDUPILOT_BIN}/libardurover.a") target_link_libraries(${elf_file} "${ARDUPILOT_LIB}/libRover_libs.a") -ENDIF() - -IF(${ARDUPILOT_CMD} STREQUAL "sub") +ELSEIF(${ARDUPILOT_CMD} STREQUAL "sub") message("Building for submarine") target_link_libraries(${elf_file} "${ARDUPILOT_BIN}/libardusub.a") target_link_libraries(${elf_file} "${ARDUPILOT_LIB}/libArduSub_libs.a") diff --git a/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/CMakeLists.txt b/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/CMakeLists.txt index 7cf8efb64a3e54..4e0fafb3eac05f 100644 --- a/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/CMakeLists.txt +++ b/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/CMakeLists.txt @@ -34,35 +34,35 @@ if(NOT DEFINED ARDUPILOT_CMD) set(ARDUPILOT_CMD "none") endif() -IF(${ARDUPILOT_CMD} STREQUAL "plane") +message("WAF_BUILD_TARGET=${WAF_BUILD_TARGET}") + +string(REGEX MATCH "^(examples|tool)/" IS_EXAMPLE "${WAF_BUILD_TARGET}") + +if (IS_EXAMPLE) + string(REPLACE "/" ";" A ${WAF_BUILD_TARGET}) + list(GET A 0 EXAMPLE_BASE) + list(GET A 1 EXAMPLE_NAME) + message("Building ${EXAMPLE_BASE} ${EXAMPLE_NAME}") + target_link_libraries(${elf_file} "${ARDUPILOT_LIB}/${EXAMPLE_BASE}/lib${EXAMPLE_NAME}.a") + target_link_libraries(${elf_file} "${ARDUPILOT_LIB}/libap.a") +ELSEIF(${ARDUPILOT_CMD} STREQUAL "plane") message("Building for plane") target_link_libraries(${elf_file} "${ARDUPILOT_BIN}/libarduplane.a") target_link_libraries(${elf_file} "${ARDUPILOT_LIB}/libArduPlane_libs.a") -ENDIF() - -IF(${ARDUPILOT_CMD} STREQUAL "copter") +ELSEIF(${ARDUPILOT_CMD} STREQUAL "copter") message("Building for copter") target_link_libraries(${elf_file} "${ARDUPILOT_BIN}/libarducopter.a") target_link_libraries(${elf_file} "${ARDUPILOT_LIB}/libArduCopter_libs.a") -ENDIF() - -IF(${ARDUPILOT_CMD} STREQUAL "rover") +ELSEIF(${ARDUPILOT_CMD} STREQUAL "rover") message("Building for rover") target_link_libraries(${elf_file} "${ARDUPILOT_BIN}/libardurover.a") target_link_libraries(${elf_file} "${ARDUPILOT_LIB}/libRover_libs.a") -ENDIF() - -IF(${ARDUPILOT_CMD} STREQUAL "sub") +ELSEIF(${ARDUPILOT_CMD} STREQUAL "sub") message("Building for submarine") target_link_libraries(${elf_file} "${ARDUPILOT_BIN}/libardusub.a") target_link_libraries(${elf_file} "${ARDUPILOT_LIB}/libArduSub_libs.a") ENDIF() -IF(${ARDUPILOT_CMD} STREQUAL "antennatracker") - message("Building AntennaTracker") - target_link_libraries(${elf_file} "${ARDUPILOT_BIN}/libantennatracker.a") - target_link_libraries(${elf_file} "${ARDUPILOT_LIB}/libAntennaTracker_libs.a") -ENDIF() add_custom_target(showinc ALL COMMAND echo -e "$" From b13632cc94f9e730231e016a7f0eba58b53b84bc Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sat, 30 Dec 2023 15:47:44 +0000 Subject: [PATCH 0245/1335] Tools: Scripts: decode_ICSR: use decoder_m4_pendsvset function --- Tools/scripts/decode_ICSR.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/scripts/decode_ICSR.py b/Tools/scripts/decode_ICSR.py index 4e705a058b3c6c..0f7e785197527d 100755 --- a/Tools/scripts/decode_ICSR.py +++ b/Tools/scripts/decode_ICSR.py @@ -28,7 +28,7 @@ def __init__(self): ("25", "PENDSTCLR", self.decoder_m4_pendstclr), ("26", "PENDSTSET", self.decoder_m4_pendstset), ("27", "PENDSVCLR", self.decoder_m4_pendsvclr), - ("28", "PENDSVSET", self.decoder_m4_pendstset), + ("28", "PENDSVSET", self.decoder_m4_pendsvset), ("29-30", "RESERVED4", None), ("31", "NMIPENDSET", self.decoder_m4_nmipendset), ] From 81d4804d531fc2099a853c2032d75da629389b3a Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 22 Dec 2023 14:27:40 +0000 Subject: [PATCH 0246/1335] AP_Scripting: examples: update examples for fixed io.open behaviour --- libraries/AP_Scripting/examples/SN-GCJA5-particle-sensor.lua | 3 +++ libraries/AP_Scripting/examples/mission-save.lua | 3 +++ 2 files changed, 6 insertions(+) diff --git a/libraries/AP_Scripting/examples/SN-GCJA5-particle-sensor.lua b/libraries/AP_Scripting/examples/SN-GCJA5-particle-sensor.lua index 08a1f2ad8d27e1..163ae6ca8aa85e 100644 --- a/libraries/AP_Scripting/examples/SN-GCJA5-particle-sensor.lua +++ b/libraries/AP_Scripting/examples/SN-GCJA5-particle-sensor.lua @@ -14,6 +14,9 @@ local file_name while true do file_name = string.format('Particle %i.csv',index) local file = io.open(file_name) + if file == nil then + break + end local first_line = file:read(1) -- try and read the first character io.close(file) if first_line == nil then diff --git a/libraries/AP_Scripting/examples/mission-save.lua b/libraries/AP_Scripting/examples/mission-save.lua index 559d9199923468..84d19da296f49b 100644 --- a/libraries/AP_Scripting/examples/mission-save.lua +++ b/libraries/AP_Scripting/examples/mission-save.lua @@ -14,6 +14,9 @@ local function save_to_SD() while true do file_name = string.format('%i.waypoints',index) local file = io.open(file_name) + if file == nil then + break + end local first_line = file:read(1) -- try and read the first character io.close(file) if first_line == nil then From 03ae94706ebf05934826906e28fef052ab3e3a46 Mon Sep 17 00:00:00 2001 From: njwhite Date: Tue, 5 Dec 2023 10:04:41 +0200 Subject: [PATCH 0247/1335] AP_AHRS: Don't Switch to DCM to get Better GPS if DCM Isn't Using GPS Look at the parameter to see if DCM uses GPS; if not don't prefer DCM for using GPS. --- libraries/AP_AHRS/AP_AHRS.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index efec6b0e9de96c..61255e7b060533 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -1974,6 +1974,7 @@ AP_AHRS::EKFType AP_AHRS::_active_EKF_type(void) const // Handle loss of global position when we still have a GPS fix if (hal.util->get_soft_armed() && + (_gps_use != GPSUse::Disable) && should_use_gps && AP::gps().status() >= AP_GPS::GPS_OK_FIX_3D && (!filt_state.flags.using_gps || !filt_state.flags.horiz_pos_abs)) { From e9f51a96cba242b714e5c7a9ab48d12bd0179751 Mon Sep 17 00:00:00 2001 From: alexklimaj Date: Tue, 26 Dec 2023 23:35:25 -0700 Subject: [PATCH 0248/1335] hwdef: ARKV6X add USART6 to serial list --- libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef.dat | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef.dat index b9f1429dd39fab..f107450d24c8c9 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ARKV6X/hwdef.dat @@ -27,8 +27,11 @@ FLASH_SIZE_KB 2048 env OPTIMIZE -O2 -# order of UARTs (and USB) -SERIAL_ORDER OTG1 UART7 UART5 USART1 UART8 USART2 UART4 USART3 OTG2 +# order of UARTs (and USB) no IO MCU +SERIAL_ORDER OTG1 UART7 UART5 USART1 UART8 USART2 UART4 USART3 USART6 OTG2 + +# order of UARTs (and USB) with IO MCU +# SERIAL_ORDER OTG1 UART7 UART5 USART1 UART8 USART2 UART4 USART3 OTG2 # default to all pins low to avoid ESD issues DEFAULTGPIO OUTPUT LOW PULLDOWN From 319202a2336d3db91243e935d65f0f0af15124c4 Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Sun, 24 Dec 2023 07:13:13 -0600 Subject: [PATCH 0249/1335] AP_ExternalAHRS: add InertialLabs to type parameter --- libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp index 0bb0d0af22acb8..9b15e6135bfe21 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS.cpp @@ -56,7 +56,7 @@ const AP_Param::GroupInfo AP_ExternalAHRS::var_info[] = { // @Param: _TYPE // @DisplayName: AHRS type // @Description: Type of AHRS device - // @Values: 0:None,1:VectorNav,2:MicroStrain5,7:MicroStrain7 + // @Values: 0:None,1:VectorNav,2:MicroStrain5,5:InertialLabs,7:MicroStrain7 // @User: Standard AP_GROUPINFO_FLAGS("_TYPE", 1, AP_ExternalAHRS, devtype, HAL_EXTERNAL_AHRS_DEFAULT, AP_PARAM_FLAG_ENABLE), From 7b5b1ba59f3f0130ca8dfe4f04564d3b53447a33 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 30 Dec 2023 08:29:23 +1100 Subject: [PATCH 0250/1335] AP_HAL: fixed build without MSG_NOSIGNAL for older MacOSX --- libraries/AP_HAL/utility/Socket.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_HAL/utility/Socket.cpp b/libraries/AP_HAL/utility/Socket.cpp index b27a3195d0a661..363b144d6720b3 100644 --- a/libraries/AP_HAL/utility/Socket.cpp +++ b/libraries/AP_HAL/utility/Socket.cpp @@ -29,6 +29,10 @@ #define CALL_PREFIX(x) ::x #endif +#ifndef MSG_NOSIGNAL +#define MSG_NOSIGNAL 0 +#endif + /* constructor */ From 9428e4130116360ef8dd6341a9257c84c6258ff1 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 30 Dec 2023 08:36:18 +1100 Subject: [PATCH 0251/1335] SITL: fixed running example firmwares don't call model update with no sitl instance --- libraries/SITL/SIM_Aircraft.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/libraries/SITL/SIM_Aircraft.cpp b/libraries/SITL/SIM_Aircraft.cpp index 07d0f6064e66ec..c718d76bd0db5f 100644 --- a/libraries/SITL/SIM_Aircraft.cpp +++ b/libraries/SITL/SIM_Aircraft.cpp @@ -607,7 +607,11 @@ void Aircraft::update_home() void Aircraft::update_model(const struct sitl_input &input) { local_ground_level = 0.0f; - update(input); + if (sitl != nullptr) { + update(input); + } else { + time_advance(); + } } /* From ce9c7dfdd15f7454cfc873f215b530ecc99ca08a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 30 Dec 2023 08:32:05 +1100 Subject: [PATCH 0252/1335] AP_ADSB: fixed a crash in ADSB when baro not healthy zero pressure leads to a floating point exception --- libraries/AP_ADSB/AP_ADSB.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/libraries/AP_ADSB/AP_ADSB.cpp b/libraries/AP_ADSB/AP_ADSB.cpp index 2acbd81b62189f..a36a1849b2e090 100644 --- a/libraries/AP_ADSB/AP_ADSB.cpp +++ b/libraries/AP_ADSB/AP_ADSB.cpp @@ -365,7 +365,9 @@ void AP_ADSB::update(void) // Altitude difference between sea level pressure and current // pressure (in metres) - loc.baro_alt_press_diff_sea_level = baro.get_altitude_difference(SSL_AIR_PRESSURE, baro.get_pressure()); + if (loc.baro_is_healthy) { + loc.baro_alt_press_diff_sea_level = baro.get_altitude_difference(SSL_AIR_PRESSURE, baro.get_pressure()); + } update(loc); } From 15d3ec31137b47d2968694fc54903f467c1fb006 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 30 Dec 2023 08:33:06 +1100 Subject: [PATCH 0253/1335] AP_ESC_Telem: allow IOMCU to work in example fw example firmwares don't instantate AP_ESC_Telem --- libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp b/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp index 0048571452f230..46f5aa61459964 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem_Backend.cpp @@ -20,14 +20,19 @@ #if HAL_WITH_ESC_TELEM #include +#include extern const AP_HAL::HAL& hal; AP_ESC_Telem_Backend::AP_ESC_Telem_Backend() { _frontend = AP_ESC_Telem::_singleton; +#if !APM_BUILD_TYPE(APM_BUILD_UNKNOWN) + // we allow for no frontend in example fw and tools to make it + // possible to run them on hardware with IOMCU if (_frontend == nullptr) { AP_HAL::panic("No ESC frontend"); } +#endif } // callback to update the rpm in the frontend, should be called by the driver when new data is available From ac49480f6a90661c1a8303810fd0594e3c444072 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 23 Dec 2023 16:07:26 +1100 Subject: [PATCH 0254/1335] HAL_SITL: disable FG view by default --- libraries/AP_HAL_SITL/SITL_cmdline.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_HAL_SITL/SITL_cmdline.cpp b/libraries/AP_HAL_SITL/SITL_cmdline.cpp index 1daa760e8526ca..96ec46d879d993 100644 --- a/libraries/AP_HAL_SITL/SITL_cmdline.cpp +++ b/libraries/AP_HAL_SITL/SITL_cmdline.cpp @@ -88,7 +88,7 @@ void SITL_State::_usage(void) "\t--model|-M MODEL set simulation model\n" "\t--config string set additional simulation config string\n" "\t--fg|-F ADDRESS set Flight Gear view address, defaults to 127.0.0.1\n" - "\t--disable-fgview disable Flight Gear view\n" + "\t--enable-fgview enable Flight Gear view\n" "\t--gimbal enable simulated MAVLink gimbal\n" "\t--autotest-dir DIR set directory for additional files\n" "\t--defaults path set path to defaults file\n" @@ -213,7 +213,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) const char *home_str = nullptr; const char *model_str = nullptr; const char *vehicle_str = SKETCH; - _use_fg_view = true; + _use_fg_view = false; char *autotest_dir = nullptr; _fg_address = "127.0.0.1"; const char* config = ""; @@ -302,7 +302,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) {"config", true, 0, 'c'}, {"fg", true, 0, 'F'}, {"gimbal", false, 0, CMDLINE_GIMBAL}, - {"disable-fgview", false, 0, CMDLINE_FGVIEW}, + {"enable-fgview", false, 0, CMDLINE_FGVIEW}, {"autotest-dir", true, 0, CMDLINE_AUTOTESTDIR}, {"defaults", true, 0, CMDLINE_DEFAULTS}, {"uartA", true, 0, CMDLINE_UARTA}, @@ -441,7 +441,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) enable_gimbal = true; break; case CMDLINE_FGVIEW: - _use_fg_view = false; + _use_fg_view = true; break; case CMDLINE_AUTOTESTDIR: autotest_dir = strdup(gopt.optarg); From f5bc7f02a8fccebdab0b91f45e992074358a492c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 08:48:58 +1100 Subject: [PATCH 0255/1335] Tools: changed to --enable-fgview --- Tools/autotest/pysim/util.py | 4 ++-- Tools/completion/zsh/_ap_bin | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Tools/autotest/pysim/util.py b/Tools/autotest/pysim/util.py index fb20b0c61a942a..fca158dc844fcc 100644 --- a/Tools/autotest/pysim/util.py +++ b/Tools/autotest/pysim/util.py @@ -540,8 +540,8 @@ def start_SITL(binary, cmd.extend(['--unhide-groups']) # somewhere for MAVProxy to connect to: cmd.append('--serial1=tcp:2') - if not enable_fgview_output: - cmd.append("--disable-fgview") + if enable_fgview_output: + cmd.append("--enable-fgview") if defaults_filepath is not None: if isinstance(defaults_filepath, list): diff --git a/Tools/completion/zsh/_ap_bin b/Tools/completion/zsh/_ap_bin index 87352789163701..543bc72c34ecaf 100644 --- a/Tools/completion/zsh/_ap_bin +++ b/Tools/completion/zsh/_ap_bin @@ -17,7 +17,7 @@ _ap_bin() { '(-M --model)'{-M,--model}'[set simulation model]' \ '--config[set additional simulation config string]:CONFIG' \ '(-F --fg)'{-F,--fg}'[set Flight Gear view address, defaults to 127.0.0.1]:ADDRESS' \ - '--disable-fgview[disable Flight Gear view]' \ + '--enable-fgview[disable Flight Gear view]' \ '--gimbal[enable simulated MAVLink gimbal]' \ '--autotest-dir[set directory for additional files]:DIR:' \ '--defaults[set path to defaults file]:PATH:' \ From c1016ae52ee4de3181b2c0a07369e51f05eb46f7 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 23 Dec 2023 16:07:40 +1100 Subject: [PATCH 0256/1335] HAL_SITL: cope with no _sitl state --- libraries/AP_HAL_SITL/SITL_State.cpp | 34 +++++++++++++--------------- 1 file changed, 16 insertions(+), 18 deletions(-) diff --git a/libraries/AP_HAL_SITL/SITL_State.cpp b/libraries/AP_HAL_SITL/SITL_State.cpp index 361b837cf1dbef..7bc5dab806afdc 100644 --- a/libraries/AP_HAL_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_State.cpp @@ -327,12 +327,13 @@ void SITL_State::_output_to_flightgear(void) */ void SITL_State::_fdm_input_local(void) { + if (_sitl == nullptr) { + return; + } struct sitl_input input; // check for direct RC input - if (_sitl != nullptr) { - _check_rc_input(); - } + _check_rc_input(); // construct servos structure for FDM _simulator_servos(input); @@ -350,19 +351,17 @@ void SITL_State::_fdm_input_local(void) sitl_model->update_model(input); // get FDM output from the model - if (_sitl) { - sitl_model->fill_fdm(_sitl->state); + sitl_model->fill_fdm(_sitl->state); #if HAL_NUM_CAN_IFACES - if (CANIface::num_interfaces() > 0) { - multicast_state_send(); - } + if (CANIface::num_interfaces() > 0) { + multicast_state_send(); + } #endif - if (_sitl->rc_fail == SITL::SIM::SITL_RCFail_None) { - for (uint8_t i=0; i< _sitl->state.rcin_chan_count; i++) { - pwm_input[i] = 1000 + _sitl->state.rcin[i]*1000; - } + if (_sitl->rc_fail == SITL::SIM::SITL_RCFail_None) { + for (uint8_t i=0; i< _sitl->state.rcin_chan_count; i++) { + pwm_input[i] = 1000 + _sitl->state.rcin[i]*1000; } } @@ -373,16 +372,12 @@ void SITL_State::_fdm_input_local(void) sim_update(); - if (_sitl && _use_fg_view) { + if (_use_fg_view) { _output_to_flightgear(); } // update simulation time - if (_sitl) { - hal.scheduler->stop_clock(_sitl->state.timestamp_us); - } else { - hal.scheduler->stop_clock(AP_HAL::micros64()+100); - } + hal.scheduler->stop_clock(_sitl->state.timestamp_us); set_height_agl(); @@ -395,6 +390,9 @@ void SITL_State::_fdm_input_local(void) */ void SITL_State::_simulator_servos(struct sitl_input &input) { + if (_sitl == nullptr) { + return; + } static uint32_t last_update_usec; /* this maps the registers used for PWM outputs. The RC From 0a8faa83d992ba88375913d0ed7957e47ef7f74a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 29 Dec 2023 07:27:02 +1100 Subject: [PATCH 0257/1335] HAL_ChibiOS: allow for up to 12.5MBps on H7 UARTs use 8x oversampling instead of 16x oversampling --- libraries/AP_HAL_ChibiOS/UARTDriver.cpp | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp index 6593dffe7ee3c5..a04537fdbddafb 100644 --- a/libraries/AP_HAL_ChibiOS/UARTDriver.cpp +++ b/libraries/AP_HAL_ChibiOS/UARTDriver.cpp @@ -430,6 +430,18 @@ void UARTDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS) sercfg.cr2 = _cr2_options; sercfg.cr3 = _cr3_options; +#if defined(STM32H7) + /* + H7 defaults to 16x oversampling. To get the highest + possible baudrates we need to drop back to 8x + oversampling. The H7 UART clock is 100MHz. This allows + for up to 12.5MBps on H7 UARTs + */ + if (_baudrate > 100000000UL / 16U) { + sercfg.cr1 |= USART_CR1_OVER8; + } +#endif + #ifndef HAL_UART_NODMA if (rx_dma_enabled) { sercfg.cr1 |= USART_CR1_IDLEIE; From cfa28c52463d56a0b6399915e7ffa6ba7c8c5e99 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 30 Dec 2023 13:34:57 +1100 Subject: [PATCH 0258/1335] HAL_SITL: fixed unbuffered UART writes in SITL this was causing PPP to slow down by about 1000x due to duplicate writes --- libraries/AP_HAL_SITL/UARTDriver.cpp | 1 + libraries/AP_HAL_SITL/UARTDriver.h | 2 ++ 2 files changed, 3 insertions(+) diff --git a/libraries/AP_HAL_SITL/UARTDriver.cpp b/libraries/AP_HAL_SITL/UARTDriver.cpp index 401fb17a0ce395..b30dad3e796021 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.cpp +++ b/libraries/AP_HAL_SITL/UARTDriver.cpp @@ -787,6 +787,7 @@ uint16_t UARTDriver::read_from_async_csv(uint8_t *buffer, uint16_t space) void UARTDriver::handle_writing_from_writebuffer_to_device() { + WITH_SEMAPHORE(write_mtx); if (!_connected) { _check_reconnect(); return; diff --git a/libraries/AP_HAL_SITL/UARTDriver.h b/libraries/AP_HAL_SITL/UARTDriver.h index cac1dc4e7aa2c7..45c00de18b3ac9 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.h +++ b/libraries/AP_HAL_SITL/UARTDriver.h @@ -110,6 +110,8 @@ class HALSITL::UARTDriver : public AP_HAL::UARTDriver { uint32_t last_read_tick_us; uint32_t last_write_tick_us; + HAL_Semaphore write_mtx; + SITL::SerialDevice *_sim_serial_device; struct { From f02973b454e0c4cb8757c03d2c3ce70f5813b948 Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Thu, 21 Dec 2023 15:17:59 -0600 Subject: [PATCH 0259/1335] AC_Fence:expand FENCE_AUTOENABLE description --- libraries/AC_Fence/AC_Fence.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_Fence/AC_Fence.cpp b/libraries/AC_Fence/AC_Fence.cpp index aaec44932bd4ed..b537085e42113f 100644 --- a/libraries/AC_Fence/AC_Fence.cpp +++ b/libraries/AC_Fence/AC_Fence.cpp @@ -128,7 +128,7 @@ const AP_Param::GroupInfo AC_Fence::var_info[] = { // @Param{Plane}: AUTOENABLE // @DisplayName: Fence Auto-Enable - // @Description: Auto-enable of fence + // @Description: Auto-enable of fences. AutoEnableOnTakeoff enables all configured fences after autotakeoffs reach altitude. During autolandings the fences will be disabled. AutoEnableDisableFloorOnLanding enables all configured fences after autotakeoffs reach altitude. During autolandings only the Minimum Altitude fence will be disabled. AutoEnableOnlyWhenArmed enables all configured fences, but no fences are disabled during autolandings. However, fence breaches are ignored while executing prior breach recovery actions which may include autolandings. // @Values: 0:AutoEnableOff,1:AutoEnableOnTakeoff,2:AutoEnableDisableFloorOnLanding,3:AutoEnableOnlyWhenArmed // @Range: 0 3 // @Increment: 1 From 9cd85f2a2fac314ebbc5330bd23e9cd38d504fe2 Mon Sep 17 00:00:00 2001 From: Mirko Denecke Date: Sun, 31 Dec 2023 14:35:12 +0100 Subject: [PATCH 0260/1335] AR_Motors: fix support for omni vehicles --- libraries/AR_Motors/AP_MotorsUGV.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AR_Motors/AP_MotorsUGV.cpp b/libraries/AR_Motors/AP_MotorsUGV.cpp index 061c1b3a25bd90..c9e351b2be03af 100644 --- a/libraries/AR_Motors/AP_MotorsUGV.cpp +++ b/libraries/AR_Motors/AP_MotorsUGV.cpp @@ -142,7 +142,7 @@ void AP_MotorsUGV::init(uint8_t frtype) setup_safety_output(); // setup for omni vehicles - if (is_omni()) { + if (_frame_type != FRAME_TYPE_UNDEFINED) { setup_omni(); } } From 2cc63f52a1d61424584f06c504374e33c8d2c9a0 Mon Sep 17 00:00:00 2001 From: Peter Mullen Date: Sat, 25 Nov 2023 21:03:55 -0800 Subject: [PATCH 0261/1335] AP_RangeFinder: Add LUA interface to access Range Finder state --- .../AP_RangeFinder/AP_RangeFinder_Backend.cpp | 31 +++++++----- .../AP_RangeFinder/AP_RangeFinder_Backend.h | 14 ++++-- .../AP_RangeFinder/AP_RangeFinder_Lua.cpp | 48 +++++++++++++------ libraries/AP_RangeFinder/AP_RangeFinder_Lua.h | 3 +- 4 files changed, 64 insertions(+), 32 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Backend.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Backend.cpp index 0809cd516a49a9..bd0e9be2945ace 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Backend.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Backend.cpp @@ -53,30 +53,39 @@ bool AP_RangeFinder_Backend::has_data() const { } // update status based on distance measurement -void AP_RangeFinder_Backend::update_status() +void AP_RangeFinder_Backend::update_status(RangeFinder::RangeFinder_State &state_arg) const { // check distance - if (state.distance_m > max_distance_cm() * 0.01f) { - set_status(RangeFinder::Status::OutOfRangeHigh); - } else if (state.distance_m < min_distance_cm() * 0.01f) { - set_status(RangeFinder::Status::OutOfRangeLow); + if (state_arg.distance_m > max_distance_cm() * 0.01f) { + set_status(state_arg, RangeFinder::Status::OutOfRangeHigh); + } else if (state_arg.distance_m < min_distance_cm() * 0.01f) { + set_status(state_arg, RangeFinder::Status::OutOfRangeLow); } else { - set_status(RangeFinder::Status::Good); + set_status(state_arg, RangeFinder::Status::Good); } } // set status and update valid count -void AP_RangeFinder_Backend::set_status(RangeFinder::Status _status) +void AP_RangeFinder_Backend::set_status(RangeFinder::RangeFinder_State &state_arg, RangeFinder::Status _status) { - state.status = _status; + state_arg.status = _status; // update valid count if (_status == RangeFinder::Status::Good) { - if (state.range_valid_count < 10) { - state.range_valid_count++; + if (state_arg.range_valid_count < 10) { + state_arg.range_valid_count++; } } else { - state.range_valid_count = 0; + state_arg.range_valid_count = 0; } } +#if AP_SCRIPTING_ENABLED +// get a copy of state structure +void AP_RangeFinder_Backend::get_state(RangeFinder::RangeFinder_State &state_arg) +{ + WITH_SEMAPHORE(_sem); + state_arg = state; +} +#endif + diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Backend.h b/libraries/AP_RangeFinder/AP_RangeFinder_Backend.h index 86f487364ba342..ca2decd044e309 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Backend.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Backend.h @@ -36,9 +36,11 @@ class AP_RangeFinder_Backend virtual void handle_msg(const mavlink_message_t &msg) { return; } #if AP_SCRIPTING_ENABLED - // Returns false if scripting backing hasn't been setup - // Get distance from lua script - virtual bool handle_script_msg(float dist_m) { return false; } + void get_state(RangeFinder::RangeFinder_State &state_arg); + + // Returns false if scripting backing hasn't been setup. + virtual bool handle_script_msg(float dist_m) { return false; } // legacy interface + virtual bool handle_script_msg(const RangeFinder::RangeFinder_State &state_arg) { return false; } #endif #if HAL_MSP_RANGEFINDER_ENABLED @@ -80,10 +82,12 @@ class AP_RangeFinder_Backend protected: // update status based on distance measurement - void update_status(); + void update_status(RangeFinder::RangeFinder_State &state_arg) const; + void update_status() { update_status(state); } // set status and update valid_count - void set_status(RangeFinder::Status status); + static void set_status(RangeFinder::RangeFinder_State &state_arg, RangeFinder::Status status); + void set_status(RangeFinder::Status status) { set_status(state, status); } RangeFinder::RangeFinder_State &state; AP_RangeFinder_Params ¶ms; diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Lua.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_Lua.cpp index cd024575136d27..75e22b2aaba5f4 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Lua.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Lua.cpp @@ -24,31 +24,49 @@ AP_RangeFinder_Lua::AP_RangeFinder_Lua(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) : AP_RangeFinder_Backend(_state, _params) { - set_status(RangeFinder::Status::NoData); } -// Set the distance based on a Lua Script -bool AP_RangeFinder_Lua::handle_script_msg(float dist_m) +// Process range finder data from a lua driver. The state structure needs to be completely +// filled in by the lua script. The data passed to this method is copied to a pending_state +// structure. The update() method periodically copies data from pending_state to state. The get_state() +// method returns data from state. +bool AP_RangeFinder_Lua::handle_script_msg(const RangeFinder::RangeFinder_State &state_arg) { - state.last_reading_ms = AP_HAL::millis(); - _distance_m = dist_m; + WITH_SEMAPHORE(_sem); + _state_pending = state_arg; return true; } +// Process range finder data from a lua driver - legacy interface. This method takes +// a distance measurement and fills in the pending state structure. In this legacy mode +// the lua script only passes in a distance measurement and does not manage the rest +// of the fields in the state structure. +bool AP_RangeFinder_Lua::handle_script_msg(float dist_m) { -// update the state of the sensor -void AP_RangeFinder_Lua::update(void) -{ - //Time out on incoming data; if we don't get new - //data in 500ms, dump it - if (AP_HAL::millis() - state.last_reading_ms > AP_RANGEFINDER_LUA_TIMEOUT_MS) { - set_status(RangeFinder::Status::NoData); - state.distance_m = 0.0f; + const uint32_t now = AP_HAL::millis(); + + WITH_SEMAPHORE(_sem); + + // Time out on incoming data; if we don't get new data in 500ms, dump it + if (now - _state_pending.last_reading_ms > AP_RANGEFINDER_LUA_TIMEOUT_MS) { + set_status(_state_pending, RangeFinder::Status::NoData); } else { - state.distance_m = _distance_m; - update_status(); + _state_pending.last_reading_ms = now; + _state_pending.distance_m = dist_m; + _state_pending.signal_quality_pct = RangeFinder::SIGNAL_QUALITY_UNKNOWN; + _state_pending.voltage_mv = 0; + update_status(_state_pending); } + + return true; +} + +// Update the state of the sensor +void AP_RangeFinder_Lua::update(void) +{ + WITH_SEMAPHORE(_sem); + state = _state_pending; } #endif // AP_RANGEFINDER_LUA_ENABLED diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_Lua.h b/libraries/AP_RangeFinder/AP_RangeFinder_Lua.h index 12e5fad3675a23..0bd7f7a1acb6b7 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_Lua.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_Lua.h @@ -21,6 +21,7 @@ class AP_RangeFinder_Lua : public AP_RangeFinder_Backend // Get update from Lua script bool handle_script_msg(float dist_m) override; + bool handle_script_msg(const RangeFinder::RangeFinder_State &state_arg) override; MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const override { return MAV_DISTANCE_SENSOR_UNKNOWN; @@ -28,7 +29,7 @@ class AP_RangeFinder_Lua : public AP_RangeFinder_Backend private: - float _distance_m; // stored data from lua script: + RangeFinder::RangeFinder_State _state_pending = {}; }; #endif // AP_RANGEFINDER_LUA_ENABLED From 948ee94ceebfe2b13cb993e0ab63c8d82ad33fd7 Mon Sep 17 00:00:00 2001 From: Peter Mullen Date: Sat, 25 Nov 2023 21:05:10 -0800 Subject: [PATCH 0262/1335] Tools/autotest: Add LUA interface to access Range Finder state --- Tools/autotest/ardusub.py | 39 +++++++++++++++++++++++++++++++++++++++ 1 file changed, 39 insertions(+) diff --git a/Tools/autotest/ardusub.py b/Tools/autotest/ardusub.py index 40eb081cfb3825..6d234c8ebfd669 100644 --- a/Tools/autotest/ardusub.py +++ b/Tools/autotest/ardusub.py @@ -166,6 +166,44 @@ def AltitudeHold(self): self.watch_altitude_maintained() self.disarm_vehicle() + def RngfndQuality(self): + """Check lua Range Finder quality information flow""" + self.context_push() + self.context_collect('STATUSTEXT') + + ex = None + try: + self.set_parameters({ + "SCR_ENABLE": 1, + "RNGFND1_TYPE": 36, + "RNGFND1_ORIENT": 25, + "RNGFND1_MIN_CM": 10, + "RNGFND1_MAX_CM": 5000, + }) + + self.install_example_script_context("rangefinder_quality_test.lua") + + # These string must match those sent by the lua test script. + complete_str = "#complete#" + failure_str = "!!failure!!" + + self.reboot_sitl() + + self.wait_statustext(complete_str, timeout=20, check_context=True) + found_failure = self.statustext_in_collections(failure_str) + + if found_failure is not None: + raise NotAchievedException("RngfndQuality test failed: " + found_failure.text) + + except Exception as e: + self.print_exception_caught(e) + ex = e + + self.context_pop() + + if ex: + raise ex + def ModeChanges(self, delta=0.2): """Check if alternating between ALTHOLD, STABILIZE and POSHOLD affects altitude""" self.wait_ready_to_arm() @@ -524,6 +562,7 @@ def tests(self): ret.extend([ self.DiveManual, self.AltitudeHold, + self.RngfndQuality, self.PositionHold, self.ModeChanges, self.DiveMission, From a83ed6b730e6d1e17d715f1f4e734a9a807bce8e Mon Sep 17 00:00:00 2001 From: Peter Mullen Date: Sat, 25 Nov 2023 21:05:45 -0800 Subject: [PATCH 0263/1335] AP_Scripting: Add LUA interface to access Range Finder state --- libraries/AP_Scripting/docs/docs.lua | 77 ++++- .../examples/rangefinder_quality_test.lua | 304 ++++++++++++++++++ .../generator/description/bindings.desc | 19 +- libraries/AP_Scripting/lua_bindings.cpp | 26 ++ libraries/AP_Scripting/lua_bindings.h | 1 + 5 files changed, 423 insertions(+), 4 deletions(-) create mode 100644 libraries/AP_Scripting/examples/rangefinder_quality_test.lua diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index 8bded69e237c33..34ea6336d44169 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -2517,14 +2517,71 @@ function terrain:status() end ---@return boolean function terrain:enabled() end + +-- RangeFinder state structure +---@class RangeFinder_State_ud +local RangeFinder_State_ud = {} + +---@return RangeFinder_State_ud +function RangeFinder_State() end + +-- get system time (ms) of last successful update from sensor +---@return number +function RangeFinder_State_ud:last_reading() end + +-- set system time (ms) of last successful update from sensor +---@param value number +function RangeFinder_State_ud:last_reading(value) end + +-- get sensor status +---@return number +function RangeFinder_State_ud:status() end + +-- set sensor status +---@param value number +function RangeFinder_State_ud:status(value) end + +-- get number of consecutive valid readings (max out at 10) +---@return number +function RangeFinder_State_ud:range_valid_count() end + +-- set number of consecutive valid readings (max out at 10) +---@param value number +function RangeFinder_State_ud:range_valid_count(value) end + +-- get distance in meters +---@return number +function RangeFinder_State_ud:distance() end + +-- set distance in meters +---@param value number +function RangeFinder_State_ud:distance(value) end + +-- get measurement quality in percent 0-100, -1 -> quality is unknown +---@return number +function RangeFinder_State_ud:signal_quality() end + +-- set measurement quality in percent 0-100, -1 -> quality is unknown +---@param value number +function RangeFinder_State_ud:signal_quality(value) end + +-- get voltage in millivolts, if applicable, otherwise 0 +---@return number +function RangeFinder_State_ud:voltage() end + +-- set voltage in millivolts, if applicable, otherwise 0 +---@param value number +function RangeFinder_State_ud:voltage(value) end + + -- RangeFinder backend ---@class AP_RangeFinder_Backend_ud local AP_RangeFinder_Backend_ud = {} --- Send distance to lua rangefinder backend. Returns false if failed ----@param distance number +-- Send range finder measurement to lua rangefinder backend. Returns false if failed +---@param state RangeFinder_State_ud|number ---@return boolean -function AP_RangeFinder_Backend_ud:handle_script_msg(distance) end +function AP_RangeFinder_Backend_ud:handle_script_msg(state) end -- Status of this rangefinder instance ---@return integer @@ -2542,6 +2599,15 @@ function AP_RangeFinder_Backend_ud:orientation() end ---@return number function AP_RangeFinder_Backend_ud:distance() end +-- Current distance measurement signal_quality of the sensor instance +---@return number +function AP_RangeFinder_Backend_ud:signal_quality() end + +-- State of most recent range finder measurment +---@return RangeFinder_State_ud +function AP_RangeFinder_Backend_ud:get_state() end + + -- desc ---@class rangefinder rangefinder = {} @@ -2586,6 +2652,11 @@ function rangefinder:max_distance_cm_orient(orientation) end ---@return integer function rangefinder:distance_cm_orient(orientation) end +-- Current distance measurement signal quality for range finder at this orientation +---@param orientation integer +---@return integer +function rangefinder:signal_quality_pct_orient(orientation) end + -- desc ---@param orientation integer ---@return boolean diff --git a/libraries/AP_Scripting/examples/rangefinder_quality_test.lua b/libraries/AP_Scripting/examples/rangefinder_quality_test.lua new file mode 100644 index 00000000000000..28c78e7ff25156 --- /dev/null +++ b/libraries/AP_Scripting/examples/rangefinder_quality_test.lua @@ -0,0 +1,304 @@ + +-- This test uses the Range Finder driver interface to simulate Range Finder +-- hardware and uses the Range Finder client interface to simulate a +-- client of the driver. The test sends distance data through the driver +-- interface and validates that it can be read through the client interface. + +-- Parameters should be set as follows before this test is loaded. +-- "RNGFND1_TYPE": 36, +-- "RNGFND1_ORIENT": 25, +-- "RNGFND1_MIN_CM": 10, +-- "RNGFND1_MAX_CM": 5000, + +-- UPDATE_PERIOD_MS is the time between when a distance is set and +-- when it is read. There is a periodic task that copies the set distance to +-- the state structure that it is read from. If UPDATE_PERIOD_MS is too short this periodic +-- task might not get a chance to run. A value of 25 seems to be too quick for sub. +local UPDATE_PERIOD_MS = 50 +local TIMEOUT_MS = 5000 + +-- These strings must match the strings used by the test driver for interpreting the output from this test. +local TEST_ID_STR = "RQTL" +local COMPLETE_STR = "#complete#" +local SUCCESS_STR = "!!success!!" +local FAILURE_STR = "!!failure!!" + + +-- Copied from libraries/AP_Math/rotation.h enum Rotation {}. +local RNGFND_ORIENTATION_DOWN = 25 +local RNGFND_ORIENTATION_FORWARD = 0 +-- Copied from libraries/AP_RangeFinder/AP_RanggeFinder.h enum RangeFinder::Type {}. +local RNGFND_TYPE_LUA = 36.0 +-- Copied from libraries/AP_RangeFinder/AP_RangeFinder.h enum RangeFinder::Status {}. +local RNDFND_STATUS_NOT_CONNECTED = 0 +local RNDFND_STATUS_OUT_OF_RANGE_LOW = 2 +local RNDFND_STATUS_OUT_OF_RANGE_HIGH = 3 +local RNDFND_STATUS_GOOD = 4 +-- Copied from libraries/AP_RangeFinder/AP_RangeFinder.h +local SIGNAL_QUALITY_MIN = 0 +local SIGNAL_QUALITY_MAX = 100 +local SIGNAL_QUALITY_UNKNOWN = -1 + +-- Read parameters for min and max valid range finder ranges. +local RNGFND1_MIN_CM = Parameter("RNGFND1_MIN_CM"):get() +local RNGFND1_MAX_CM = Parameter("RNGFND1_MAX_CM"):get() + +local function send(str) + gcs:send_text(3, string.format("%s %s", TEST_ID_STR, str)) +end + + +-- The range finder backend is initialized in the update_prepare function. +---@type AP_RangeFinder_Backend_ud +local rngfnd_backend + + +local function test_dist_equal(dist_m_in, dist_in_factor, dist_out, signal_quality_pct_in, signal_quality_pct_out) + if math.abs(dist_out - dist_m_in * dist_in_factor) > 1.0e-3 then + return false + end + if signal_quality_pct_in < 0 and signal_quality_pct_out == -1 then + return true + end + if signal_quality_pct_in > 100 and signal_quality_pct_out == -1 then + return true + end + if signal_quality_pct_in == signal_quality_pct_out then + return true + end + return false +end + +local function get_and_eval(test_idx, dist_m_in, signal_quality_pct_in, status_expected) + local status_actual = rangefinder:status_orient(RNGFND_ORIENTATION_DOWN) + + -- Check that the status is as expected + if status_expected ~= status_actual then + return string.format("Status test %i status incorrect - expected %i, actual %i", test_idx, status_expected, status_actual) + end + + -- Not more checks if the status is poor + if status_actual ~= RNDFND_STATUS_GOOD then + send(string.format("Status test %i status correct - expected: %i actual: %i", test_idx, status_expected, status_actual)) + return nil + end + + -- L U A I N T E R F A C E T E S T + -- Check that the distance and signal_quality from the frontend are as expected + local distance1_cm_out = rangefinder:distance_cm_orient(RNGFND_ORIENTATION_DOWN) + local signal_quality1_pct_out = rangefinder:signal_quality_pct_orient(RNGFND_ORIENTATION_DOWN) + + -- Make sure data was returned + if not distance1_cm_out or not signal_quality1_pct_out then + return "No data returned from rangefinder:distance_cm_orient()" + end + + send(string.format("Frontend test %i dist in_m: %.2f out_cm: %.2f, signal_quality_pct in: %.1f out: %.1f", + test_idx, dist_m_in, distance1_cm_out, signal_quality_pct_in, signal_quality1_pct_out)) + + if not test_dist_equal(dist_m_in, 100.0, distance1_cm_out, signal_quality_pct_in, signal_quality1_pct_out) then + return "Frontend expected and actual do not match" + end + + -- L U A I N T E R F A C E T E S T + -- Check that the distance and signal_quality from the backend are as expected + local disttance2_m_out = rngfnd_backend:distance() + local signal_quality2_pct_out = rngfnd_backend:signal_quality() + + send(string.format("Backend test %i dist in_m: %.2f out_m: %.2f, signal_quality_pct in: %.1f out: %.1f", + test_idx, dist_m_in, disttance2_m_out, signal_quality_pct_in, signal_quality2_pct_out)) + + if not test_dist_equal(dist_m_in, 1.0, disttance2_m_out, signal_quality_pct_in, signal_quality2_pct_out) then + return "Backend expected and actual do not match" + end + + -- L U A I N T E R F A C E T E S T + -- Check that the state from the backend is as expected + local rf_state = rngfnd_backend:get_state() + local distance3_m_out = rf_state:distance() + local signal_quality3_pct_out = rf_state:signal_quality() + + send(string.format("State test %i dist in_m: %.2f out_m: %.2f, signal_quality_pct in: %.1f out: %.1f", + test_idx, dist_m_in, distance3_m_out, signal_quality_pct_in, signal_quality3_pct_out)) + + if not test_dist_equal(dist_m_in, 1.0, distance3_m_out, signal_quality_pct_in, signal_quality3_pct_out) then + return "State expected and actual do not match" + end + + return nil +end + +-- Test various status states +local function do_status_tests() + send("Test initial status") + local status_actual = rangefinder:status_orient(RNGFND_ORIENTATION_DOWN) + if status_actual ~= RNDFND_STATUS_NOT_CONNECTED then + return string.format("DOWN Status '%i' not NOT_CONNECTED on initialization.", status_actual) + end + status_actual = rangefinder:status_orient(RNGFND_ORIENTATION_FORWARD) + if status_actual ~= RNDFND_STATUS_NOT_CONNECTED then + return string.format("FORWARD Status '%i' not NOT_CONNECTED on initialization.", status_actual) + end + return nil +end + + +local test_data = { + {20.0, -1, RNDFND_STATUS_GOOD}, + {20.5, -2, RNDFND_STATUS_GOOD}, + {21.0, 0, RNDFND_STATUS_GOOD}, + {22.0, 50, RNDFND_STATUS_GOOD}, + {23.0, 100, RNDFND_STATUS_GOOD}, + {24.0, 101, RNDFND_STATUS_GOOD}, + {25.0, -3, RNDFND_STATUS_GOOD}, + {26.0, 127, RNDFND_STATUS_GOOD}, + {27.0, 3, RNDFND_STATUS_GOOD}, + {28.0, 100, RNDFND_STATUS_GOOD}, + {29.0, 99, RNDFND_STATUS_GOOD}, + {100.0, 100, RNDFND_STATUS_OUT_OF_RANGE_HIGH}, + {0.0, 100, RNDFND_STATUS_OUT_OF_RANGE_LOW}, + {100.0, -2, RNDFND_STATUS_OUT_OF_RANGE_HIGH}, + {0.0, -2, RNDFND_STATUS_OUT_OF_RANGE_LOW}, +} + +-- Record the start time so we can timeout if initialization takes too long. +local time_start_ms = millis():tofloat() +local test_idx = 0 + + +-- Called when tests are completed. +local function complete(error_str) + -- Send a message indicating the success or failure of the test + local status_str + if not error_str or #error_str == 0 then + status_str = SUCCESS_STR + else + send(error_str) + status_str = FAILURE_STR + end + send(string.format("%s: %s", COMPLETE_STR, status_str)) + + -- Returning nil will not queue an update routine so the test will stop running. +end + + +-- A state machine of update functions. The states progress: +-- prepare, wait, begin_test, eval_test, begin_test, eval_test, ... complete + +local update_prepare +local update_wait +local update_begin_test +local update_eval_test + +local function _update_prepare() + if Parameter('RNGFND1_TYPE'):get() ~= RNGFND_TYPE_LUA then + return complete("LUA range finder driver not enabled") + end + if rangefinder:num_sensors() < 1 then + return complete("LUA range finder driver not connected") + end + rngfnd_backend = rangefinder:get_backend(0) + if not rngfnd_backend then + return complete("Range Finder 1 does not exist") + end + if (rngfnd_backend:type() ~= RNGFND_TYPE_LUA) then + return complete("Range Finder 1 is not a LUA driver") + end + + return update_wait() +end + +local function _update_wait() + -- Check for timeout while initializing + if millis():tofloat() - time_start_ms > TIMEOUT_MS then + return complete("Timeout while trying to initialize") + end + + -- Wait until the prearm check passes. This ensures that the system is mostly initialized + -- before starting the tests. + if not arming:pre_arm_checks() then + return update_wait, UPDATE_PERIOD_MS + end + + -- Do some one time tests + local error_str = do_status_tests() + if error_str then + return complete(error_str) + end + + -- Continue on to the main list of tests. + return update_begin_test() +end + +local function _update_begin_test() + test_idx = test_idx + 1 + if test_idx > #test_data then + return complete() + end + + local dist_m_in = test_data[test_idx][1] + local signal_quality_pct_in = test_data[test_idx][2] + + -- L U A I N T E R F A C E T E S T + -- Use the driver interface to simulate a data measurement being received and being passed to AP. + local result + -- -2 => use legacy interface + if signal_quality_pct_in == -2 then + result = rngfnd_backend:handle_script_msg(dist_m_in) -- number as arg (compatibility mode) + + else + -- The full state udata must be initialized. + local rf_state = RangeFinder_State() + -- Set the status + if dist_m_in < RNGFND1_MIN_CM * 0.01 then + rf_state:status(RNDFND_STATUS_OUT_OF_RANGE_LOW) + elseif dist_m_in > RNGFND1_MAX_CM * 0.01 then + rf_state:status(RNDFND_STATUS_OUT_OF_RANGE_HIGH) + else + rf_state:status(RNDFND_STATUS_GOOD) + end + -- Sanitize signal_quality_pct_in + if signal_quality_pct_in < SIGNAL_QUALITY_MIN or signal_quality_pct_in > SIGNAL_QUALITY_MAX then + signal_quality_pct_in = SIGNAL_QUALITY_UNKNOWN + end + rf_state:last_reading(millis():toint()) + rf_state:range_valid_count(10) + rf_state:distance(dist_m_in) + rf_state:signal_quality(signal_quality_pct_in) + rf_state:voltage(0) + result = rngfnd_backend:handle_script_msg(rf_state) -- state as arg + end + + if not result then + return complete(string.format("Test %i, dist_m: %.2f, quality_pct: %3i failed to handle_script_msg2", + test_idx, dist_m_in, signal_quality_pct_in)) + end + + return update_eval_test, UPDATE_PERIOD_MS +end + +local function _update_eval_test() + local dist_m_in = test_data[test_idx][1] + local signal_quality_pct_in = test_data[test_idx][2] + local status_expected = test_data[test_idx][3] + + -- Use the client interface to get distance data and ensure it matches the distance data + -- that was sent through the driver interface. + local error_str = get_and_eval(test_idx, dist_m_in, signal_quality_pct_in, status_expected) + if error_str then + return complete(string.format("Test %i, dist_m: %.2f, quality_pct: %3i failed because %s", + test_idx, dist_m_in, signal_quality_pct_in, error_str)) + end + + -- Move to the next test in the list. + return update_begin_test() +end + +update_prepare = _update_prepare +update_wait = _update_wait +update_begin_test = _update_begin_test +update_eval_test = _update_eval_test + +send("Loaded rangefinder_quality_test.lua") + +return update_prepare, 0 diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index 1ce091781525cf..f0608bfcb39265 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -200,18 +200,35 @@ singleton AP_Proximity method get_backend AP_Proximity_Backend uint8_t'skip_chec include AP_RangeFinder/AP_RangeFinder.h include AP_RangeFinder/AP_RangeFinder_Backend.h +userdata RangeFinder::RangeFinder_State depends (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_RANGEFINDER)) +userdata RangeFinder::RangeFinder_State rename RangeFinder_State +userdata RangeFinder::RangeFinder_State field last_reading_ms uint32_t'skip_check read write +userdata RangeFinder::RangeFinder_State field last_reading_ms rename last_reading +userdata RangeFinder::RangeFinder_State field status RangeFinder::Status'enum read write RangeFinder::Status::NotConnected RangeFinder::Status::Good +userdata RangeFinder::RangeFinder_State field range_valid_count uint8_t'skip_check read write +userdata RangeFinder::RangeFinder_State field distance_m float'skip_check read write +userdata RangeFinder::RangeFinder_State field distance_m rename distance +userdata RangeFinder::RangeFinder_State field signal_quality_pct int8_t'skip_check read write +userdata RangeFinder::RangeFinder_State field signal_quality_pct rename signal_quality +userdata RangeFinder::RangeFinder_State field voltage_mv uint16_t'skip_check read write +userdata RangeFinder::RangeFinder_State field voltage_mv rename voltage + ap_object AP_RangeFinder_Backend depends (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_RANGEFINDER)) ap_object AP_RangeFinder_Backend method distance float +ap_object AP_RangeFinder_Backend method signal_quality_pct float +ap_object AP_RangeFinder_Backend method signal_quality_pct rename signal_quality ap_object AP_RangeFinder_Backend method orientation Rotation'enum ap_object AP_RangeFinder_Backend method type uint8_t ap_object AP_RangeFinder_Backend method status uint8_t -ap_object AP_RangeFinder_Backend method handle_script_msg boolean float'skip_check +ap_object AP_RangeFinder_Backend manual handle_script_msg lua_range_finder_handle_script_msg 1 +ap_object AP_RangeFinder_Backend method get_state void RangeFinder::RangeFinder_State'Ref singleton RangeFinder depends (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_RANGEFINDER)) singleton RangeFinder rename rangefinder singleton RangeFinder method num_sensors uint8_t singleton RangeFinder method has_orientation boolean Rotation'enum ROTATION_NONE ROTATION_MAX-1 singleton RangeFinder method distance_cm_orient uint16_t Rotation'enum ROTATION_NONE ROTATION_MAX-1 +singleton RangeFinder method signal_quality_pct_orient int8_t Rotation'enum ROTATION_NONE ROTATION_MAX-1 singleton RangeFinder method max_distance_cm_orient uint16_t Rotation'enum ROTATION_NONE ROTATION_MAX-1 singleton RangeFinder method min_distance_cm_orient uint16_t Rotation'enum ROTATION_NONE ROTATION_MAX-1 singleton RangeFinder method ground_clearance_cm_orient uint16_t Rotation'enum ROTATION_NONE ROTATION_MAX-1 diff --git a/libraries/AP_Scripting/lua_bindings.cpp b/libraries/AP_Scripting/lua_bindings.cpp index a8637ed380547a..eb884eb275cd87 100644 --- a/libraries/AP_Scripting/lua_bindings.cpp +++ b/libraries/AP_Scripting/lua_bindings.cpp @@ -950,4 +950,30 @@ int lua_print(lua_State *L) { return 0; } +#if (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_RANGEFINDER)) +int lua_range_finder_handle_script_msg(lua_State *L) { + // Arg 1 => self (an instance of rangefinder_backend) + // Arg 2 => a float distance or a RangeFinder_State user data + binding_argcheck(L, 2); + + // check_AP_RangeFinder_Backend aborts if not found. No need to check for null + AP_RangeFinder_Backend * ud = *check_AP_RangeFinder_Backend(L, 1); + + bool result = false; + + // Check to see if the first argument is the state structure. + const void *state_arg = luaL_testudata(L, 2, "RangeFinder_State"); + if (state_arg != nullptr) { + result = ud->handle_script_msg(*static_cast(state_arg)); + + } else { + // Otherwise assume the argument is a number and set the measurement. + result = ud->handle_script_msg(luaL_checknumber(L, 2)); + } + + lua_pushboolean(L, result); + return 1; +} +#endif + #endif // AP_SCRIPTING_ENABLED diff --git a/libraries/AP_Scripting/lua_bindings.h b/libraries/AP_Scripting/lua_bindings.h index 99e4f8a3747727..add40faa0a7bd8 100644 --- a/libraries/AP_Scripting/lua_bindings.h +++ b/libraries/AP_Scripting/lua_bindings.h @@ -26,3 +26,4 @@ int lua_mavlink_register_rx_msgid(lua_State *L); int lua_mavlink_send_chan(lua_State *L); int lua_mavlink_block_command(lua_State *L); int lua_print(lua_State *L); +int lua_range_finder_handle_script_msg(lua_State *L); From 816e3fae3e90aba9773ededf2308bed5c1755eef Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 1 Jan 2024 08:37:52 +1100 Subject: [PATCH 0264/1335] autotest: fixed flapping sub log download test the log being downloaded can be very large, and times out. Setting LOG_DISARMED=1 gives us a small log to download --- Tools/autotest/vehicle_test_suite.py | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index 04ce66a804d472..be0cecc95fee4b 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -4273,6 +4273,7 @@ def TestLogDownloadMAVProxyNetwork(self, upload_logs=False): self.context_push() self.set_parameters({ "NET_ENABLED": 1, + "LOG_DISARMED": 1, "LOG_DARM_RATEMAX": 2, # make small logs # UDP client "NET_P1_TYPE": 1, From c9b8be7213c10bf2dfb4c3e56f2ba55c6070833c Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Thu, 28 Dec 2023 16:48:32 -0600 Subject: [PATCH 0265/1335] AP_Parachute:upate metadata in line with new relay functions --- libraries/AP_Parachute/AP_Parachute.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Parachute/AP_Parachute.cpp b/libraries/AP_Parachute/AP_Parachute.cpp index 6ed1618b1904aa..4cdf7ce692443c 100644 --- a/libraries/AP_Parachute/AP_Parachute.cpp +++ b/libraries/AP_Parachute/AP_Parachute.cpp @@ -24,8 +24,9 @@ const AP_Param::GroupInfo AP_Parachute::var_info[] = { // @Param: TYPE // @DisplayName: Parachute release mechanism type (relay or servo) - // @Description: Parachute release mechanism type (relay or servo) - // @Values: 0:First Relay,1:Second Relay,2:Third Relay,3:Fourth Relay,10:Servo + // @Description: Parachute release mechanism type (relay number in versions prior to 4.5, or servo). Values 0-3 all are relay. Relay number used for release is set by RELAYx_FUNCTION in 4.5 or later. + // @Values: 0: Relay,10:Servo + // @User: Standard AP_GROUPINFO("TYPE", 1, AP_Parachute, _release_type, AP_PARACHUTE_TRIGGER_TYPE_RELAY_0), From c53d3ae09babf5323948e4856d022b5dd134b86a Mon Sep 17 00:00:00 2001 From: alexklimaj Date: Wed, 20 Dec 2023 11:49:26 -0700 Subject: [PATCH 0266/1335] hwdef: ARK_CANNODE add rangefinder --- libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat index 8fa2061e0ab906..006fe14d9cf036 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/ARK_CANNODE/hwdef.dat @@ -125,3 +125,8 @@ define CAN_APP_NODE_NAME "org.ardupilot.ARK_CANNODE" define HAL_SUPPORT_RCOUT_SERIAL 1 define HAL_WITH_ESC_TELEM 1 define AP_SERIALLED_ENABLED 1 + +# Rangefinder +define HAL_PERIPH_ENABLE_RANGEFINDER +# disable rangefinder by default +define AP_PERIPH_RANGEFINDER_PORT_DEFAULT -1 From 0a5407a1a785eed1f8a6639944c19d3ce6506fa6 Mon Sep 17 00:00:00 2001 From: Brad Bosch Date: Sun, 3 Dec 2023 14:38:35 -0600 Subject: [PATCH 0267/1335] AP_VideoTX: Restore use of the VTX_MAX_POWER parameter This functionality was lost when a significant rewrite of this code was done in commit 0658f060301c9230c5b170bbad005dee68fbcd8a --- libraries/AP_VideoTX/AP_VideoTX.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_VideoTX/AP_VideoTX.cpp b/libraries/AP_VideoTX/AP_VideoTX.cpp index 8bfa7c14ca6462..ac57aade8319cf 100644 --- a/libraries/AP_VideoTX/AP_VideoTX.cpp +++ b/libraries/AP_VideoTX/AP_VideoTX.cpp @@ -515,7 +515,7 @@ void AP_VideoTX::change_power(int8_t position) // first find out how many possible levels there are uint8_t num_active_levels = 0; for (uint8_t i = 0; i < VTX_MAX_POWER_LEVELS; i++) { - if (_power_levels[i].active != PowerActive::Inactive) { + if (_power_levels[i].active != PowerActive::Inactive && _power_levels[i].mw <= _max_power_mw) { num_active_levels++; } } From 4b692b470f9406488eacf3455caf907299208e6b Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Sun, 24 Dec 2023 12:41:29 -0600 Subject: [PATCH 0268/1335] add note about Qmode FS switches to FS actions) --- ArduPlane/Parameters.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index fd5288223d8f8b..dd55010d46adce 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -417,7 +417,7 @@ const AP_Param::Info Plane::var_info[] = { // @Param: FS_SHORT_ACTN // @DisplayName: Short failsafe action - // @Description: The action to take on a short (FS_SHORT_TIMEOUT) failsafe event. A short failsafe event can be triggered either by loss of RC control (see THR_FS_VALUE) or by loss of GCS control (see FS_GCS_ENABL). If in CIRCLE or RTL mode this parameter is ignored. A short failsafe event in stabilization and manual modes will cause a change to CIRCLE mode if FS_SHORT_ACTN is 0 or 1, a change to FBWA mode with zero throttle if FS_SHORT_ACTN is 2, and a change to FBWB mode if FS_SHORT_ACTN is 4. In all other modes (AUTO, GUIDED and LOITER) a short failsafe event will cause no mode change if FS_SHORT_ACTN is set to 0, will cause a change to CIRCLE mode if set to 1, will change to FBWA mode with zero throttle if set to 2, or will change to FBWB if set to 4. Please see the documentation for FS_LONG_ACTN for the behaviour after FS_LONG_TIMEOUT seconds of failsafe. + // @Description: The action to take on a short (FS_SHORT_TIMEOUT) failsafe event. A short failsafe event can be triggered either by loss of RC control (see THR_FS_VALUE) or by loss of GCS control (see FS_GCS_ENABL). If in CIRCLE or RTL mode this parameter is ignored. A short failsafe event in stabilization and manual modes will cause a change to CIRCLE mode if FS_SHORT_ACTN is 0 or 1, a change to FBWA mode with zero throttle if FS_SHORT_ACTN is 2, and a change to FBWB mode if FS_SHORT_ACTN is 4. In all other modes (AUTO, GUIDED and LOITER) a short failsafe event will cause no mode change if FS_SHORT_ACTN is set to 0, will cause a change to CIRCLE mode if set to 1, will change to FBWA mode with zero throttle if set to 2, or will change to FBWB if set to 4. Please see the documentation for FS_LONG_ACTN for the behaviour after FS_LONG_TIMEOUT seconds of failsafe. This parameter only applies to failsafes during fixed wing modes. Quadplane modes will switch to QLAND unless Q_OPTIONS bit 5(QRTL) or 20(RTL) are set. // @Values: 0:CIRCLE/no change(if already in AUTO|GUIDED|LOITER),1:CIRCLE,2:FBWA at zero throttle,3:Disable,4:FBWB // @User: Standard GSCALAR(fs_action_short, "FS_SHORT_ACTN", FS_ACTION_SHORT_BESTGUESS), @@ -433,7 +433,7 @@ const AP_Param::Info Plane::var_info[] = { // @Param: FS_LONG_ACTN // @DisplayName: Long failsafe action - // @Description: The action to take on a long (FS_LONG_TIMEOUT seconds) failsafe event. If the aircraft was in a stabilization or manual mode when failsafe started and a long failsafe occurs then it will change to RTL mode if FS_LONG_ACTN is 0 or 1, and will change to FBWA if FS_LONG_ACTN is set to 2. If the aircraft was in an auto mode (such as AUTO or GUIDED) when the failsafe started then it will continue in the auto mode if FS_LONG_ACTN is set to 0, will change to RTL mode if FS_LONG_ACTN is set to 1 and will change to FBWA mode if FS_LONG_ACTN is set to 2. If FS_LONG_ACTN is set to 3, the parachute will be deployed (make sure the chute is configured and enabled). If FS_LONG_ACTN is set to 4 the aircraft will switch to mode AUTO with the current waypoint if it is not already in mode AUTO, unless it is in the middle of a landing sequence. + // @Description: The action to take on a long (FS_LONG_TIMEOUT seconds) failsafe event. If the aircraft was in a stabilization or manual mode when failsafe started and a long failsafe occurs then it will change to RTL mode if FS_LONG_ACTN is 0 or 1, and will change to FBWA if FS_LONG_ACTN is set to 2. If the aircraft was in an auto mode (such as AUTO or GUIDED) when the failsafe started then it will continue in the auto mode if FS_LONG_ACTN is set to 0, will change to RTL mode if FS_LONG_ACTN is set to 1 and will change to FBWA mode if FS_LONG_ACTN is set to 2. If FS_LONG_ACTN is set to 3, the parachute will be deployed (make sure the chute is configured and enabled). If FS_LONG_ACTN is set to 4 the aircraft will switch to mode AUTO with the current waypoint if it is not already in mode AUTO, unless it is in the middle of a landing sequence. This parameter only applies to failsafes during fixed wing modes. Quadplane modes will switch to QLAND unless Q_OPTIONS bit 5 (QRTL) or 20(RTL) are set. // @Values: 0:Continue,1:ReturnToLaunch,2:Glide,3:Deploy Parachute,4:Auto // @User: Standard GSCALAR(fs_action_long, "FS_LONG_ACTN", FS_ACTION_LONG_CONTINUE), From 467daeb4a69601e03521c7631260a62dac597465 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 2 Jan 2024 11:00:44 +1100 Subject: [PATCH 0269/1335] hwdef: tidy checking of is-bootloader-build --- .../hwdef/scripts/chibios_hwdef.py | 50 +++++++++---------- 1 file changed, 25 insertions(+), 25 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index cec867a6dc6934..d129a0dcf2b6cc 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -735,7 +735,7 @@ def enable_can(self, f): f.write('#define CAN1_BASE CAN_BASE\n') self.env_vars['HAL_NUM_CAN_IFACES'] = str(len(base_list)) - if self.mcu_series.startswith("STM32H7") and not args.bootloader: + if self.mcu_series.startswith("STM32H7") and not self.is_bootloader_fw(): # set maximum supported canfd bit rate in MBits/sec canfd_supported = int(self.get_config('CANFD_SUPPORTED', 0, default=4, required=False)) f.write('#define HAL_CANFD_SUPPORTED %d\n' % canfd_supported) @@ -756,7 +756,7 @@ def get_ram_map(self): '''get RAM_MAP. May be different for bootloader''' if 'APP_RAM_START' not in self.env_vars: self.env_vars['APP_RAM_START'] = None - if args.bootloader: + if self.is_bootloader_fw(): ram_map = self.get_mcu_config('RAM_MAP_BOOTLOADER', False) if ram_map is not None: app_ram_map = self.get_mcu_config('RAM_MAP', False) @@ -854,7 +854,7 @@ def get_storage_flash_page(self): storage_flash_page = self.get_config('STORAGE_FLASH_PAGE', default=None, type=int, required=False) if storage_flash_page is not None: return storage_flash_page - if args.bootloader and args.hwdef[0].find("-bl") != -1: + if self.is_bootloader_fw() and args.hwdef[0].find("-bl") != -1: hwdefdat = args.hwdef[0].replace("-bl", "") if os.path.exists(hwdefdat): ret = None @@ -1044,7 +1044,7 @@ def write_mcu_config(self, f): f.write('\n// location of loaded firmware\n') f.write('#define FLASH_LOAD_ADDRESS 0x%08x\n' % (0x08000000 + flash_reserve_start*1024)) # can be no persistent parameters if no space allocated for them - if not args.bootloader and flash_reserve_start == 0: + if not self.is_bootloader_fw() and flash_reserve_start == 0: f.write('#define HAL_ENABLE_SAVE_PERSISTENT_PARAMS 0\n') f.write('#define EXT_FLASH_SIZE_MB %u\n' % self.get_config('EXT_FLASH_SIZE_MB', default=0, type=int)) @@ -1053,7 +1053,7 @@ def write_mcu_config(self, f): self.env_vars['EXT_FLASH_SIZE_MB'] = self.get_config('EXT_FLASH_SIZE_MB', default=0, type=int) self.env_vars['INT_FLASH_PRIMARY'] = self.get_config('INT_FLASH_PRIMARY', default=False, type=bool) - if self.env_vars['EXT_FLASH_SIZE_MB'] and not args.bootloader and not self.env_vars['INT_FLASH_PRIMARY']: + if self.env_vars['EXT_FLASH_SIZE_MB'] and not self.is_bootloader_fw() and not self.env_vars['INT_FLASH_PRIMARY']: f.write('#define CRT0_AREAS_NUMBER 4\n') f.write('#define __FASTRAMFUNC__ __attribute__ ((__section__(".fastramfunc")))\n') f.write('#define __RAMFUNC__ __attribute__ ((__section__(".ramfunc")))\n') @@ -1071,7 +1071,7 @@ def write_mcu_config(self, f): storage_flash_page = self.get_storage_flash_page() flash_reserve_end = self.get_config('FLASH_RESERVE_END_KB', default=0, type=int) if storage_flash_page is not None: - if not args.bootloader: + if not self.is_bootloader_fw(): f.write('#define STORAGE_FLASH_PAGE %u\n' % storage_flash_page) self.validate_flash_storage_size() elif self.get_config('FLASH_RESERVE_END_KB', type=int, required=False) is None: @@ -1082,14 +1082,14 @@ def write_mcu_config(self, f): if offset > bl_offset: flash_reserve_end = flash_size - offset - crashdump_enabled = bool(self.intdefines.get('AP_CRASHDUMP_ENABLED', (flash_size >= 2048 and not args.bootloader))) + crashdump_enabled = bool(self.intdefines.get('AP_CRASHDUMP_ENABLED', (flash_size >= 2048 and not self.is_bootloader_fw()))) # noqa # lets pick a flash sector for Crash log f.write('#ifndef AP_CRASHDUMP_ENABLED\n') f.write('#define AP_CRASHDUMP_ENABLED %u\n' % crashdump_enabled) f.write('#endif\n') self.env_vars['ENABLE_CRASHDUMP'] = crashdump_enabled - if args.bootloader: + if self.is_bootloader_fw(): if self.env_vars['EXT_FLASH_SIZE_MB'] and not self.env_vars['INT_FLASH_PRIMARY']: f.write('\n// location of loaded firmware in external flash\n') f.write('#define APP_START_ADDRESS 0x%08x\n' % (0x90000000 + self.get_config( @@ -1188,13 +1188,13 @@ def write_mcu_config(self, f): self.env_vars['CORTEX'] = cortex - if not args.bootloader: + if not self.is_bootloader_fw(): if cortex == 'cortex-m4': self.env_vars['CPU_FLAGS'].append('-DARM_MATH_CM4') elif cortex == 'cortex-m7': self.env_vars['CPU_FLAGS'].append('-DARM_MATH_CM7') - if not self.mcu_series.startswith("STM32F1") and not args.bootloader: + if not self.mcu_series.startswith("STM32F1") and not self.is_bootloader_fw(): self.env_vars['CPU_FLAGS'].append('-u_printf_float') build_info['ENV_UDEFS'] = "-DCHPRINTF_USE_FLOAT=1" @@ -1203,7 +1203,7 @@ def write_mcu_config(self, f): self.build_flags.append('%s=%s' % (v, build_info[v])) # setup for bootloader build - if args.bootloader: + if self.is_bootloader_fw(): if self.get_config('FULL_CHIBIOS_BOOTLOADER', required=False, default=False): # we got enough space to fit everything so we enable almost everything f.write(''' @@ -1283,10 +1283,10 @@ def write_mcu_config(self, f): if self.env_vars.get('ROMFS_UNCOMPRESSED', False): f.write('#define HAL_ROMFS_UNCOMPRESSED\n') - if not args.bootloader: + if not self.is_bootloader_fw(): f.write('''#define STM32_DMA_REQUIRED TRUE\n\n''') - if args.bootloader: + if self.is_bootloader_fw(): # do not enable flash protection in bootloader, even if hwdef # requests it: f.write(''' @@ -1364,7 +1364,7 @@ def write_ldscript(self, fname): ext_flash_size = self.get_config('EXT_FLASH_SIZE_MB', default=0, type=int) int_flash_primary = self.get_config('INT_FLASH_PRIMARY', default=False, type=int) - if not args.bootloader: + if not self.is_bootloader_fw(): flash_length = flash_size - (flash_reserve_start + flash_reserve_end) ext_flash_length = ext_flash_size * 1024 - (ext_flash_reserve_start + ext_flash_reserve_end) else: @@ -1386,7 +1386,7 @@ def write_ldscript(self, fname): ram_reserve_start = self.get_ram_reserve_start() ram0_start += ram_reserve_start ram0_len -= ram_reserve_start - if ext_flash_length == 0 or args.bootloader: + if ext_flash_length == 0 or self.is_bootloader_fw(): self.env_vars['HAS_EXTERNAL_FLASH_SECTIONS'] = 0 f.write('''/* generated ldscript.ld */ MEMORY @@ -1429,7 +1429,7 @@ def write_ldscript(self, fname): def copy_common_linkerscript(self, outdir): dirpath = os.path.dirname(os.path.realpath(__file__)) - if args.bootloader: + if self.is_bootloader_fw(): linker = 'common.ld' else: linker = self.get_mcu_config('LINKER_CONFIG') @@ -1467,10 +1467,10 @@ def write_USB_config(self, f): f.write('#define HAL_USB_STRING_MANUFACTURER %s\n' % self.get_config("USB_STRING_MANUFACTURER", default="\"ArduPilot\"")) default_product = "%BOARD%" - if args.bootloader: + if self.is_bootloader_fw(): default_product += "-BL" product_string = self.get_config("USB_STRING_PRODUCT", default="\"%s\"" % default_product) - if args.bootloader and args.signed_fw: + if self.is_bootloader_fw() and args.signed_fw: product_string = product_string.replace("-BL", "-Secure-BL-v10") f.write('#define HAL_USB_STRING_PRODUCT %s\n' % product_string) @@ -1580,7 +1580,7 @@ def write_WSPI_config(self, f): # only the bootloader must run the hal lld (and QSPI clock) otherwise it is not possible to # bootstrap into external flash for t in list(self.bytype.keys()) + list(self.alttype.keys()): - if (t.startswith('QUADSPI') or t.startswith('OCTOSPI')) and not args.bootloader: + if (t.startswith('QUADSPI') or t.startswith('OCTOSPI')) and not self.is_bootloader_fw(): f.write('#define HAL_XIP_ENABLED TRUE\n') if len(self.wspidev) == 0: @@ -1945,7 +1945,7 @@ def write_UART_config(self, f): ''' % (OTG2_index, OTG2_index)) f.write('#define HAL_SERIAL_DEVICE_LIST %s\n\n' % ','.join(devlist)) - if not need_uart_driver and not args.bootloader: + if not need_uart_driver and not self.is_bootloader_fw(): f.write(''' #ifndef HAL_USE_SERIAL #define HAL_USE_SERIAL HAL_USE_SERIAL_USB @@ -2433,7 +2433,7 @@ def embed_bootloader(self, f): self.error('''Bootloader (%s) does not exist and AP_BOOTLOADER_FLASHING_ENABLED Please run: Tools/scripts/build_bootloaders.py %s ''' % - (bp,os.path.basename(os.path.dirname(args.hwdef[0])))) + (bp, os.path.basename(os.path.dirname(args.hwdef[0])))) bp = os.path.realpath(bp) @@ -2595,7 +2595,7 @@ def write_hwdef_header(self, outfilename): dma_noshare=self.dma_noshare ) - if not args.bootloader: + if not self.is_bootloader_fw(): self.write_PWM_config(f, ordered_timers) self.write_I2C_config(f) self.write_UART_config(f) @@ -2854,7 +2854,7 @@ def romfs_add_dir(self, subdirs): '''add a filesystem directory to ROMFS''' for dirname in subdirs: romfs_dir = os.path.join(os.path.dirname(args.hwdef[0]), dirname) - if not args.bootloader and os.path.exists(romfs_dir): + if not self.is_bootloader_fw() and os.path.exists(romfs_dir): for root, d, files in os.walk(romfs_dir): for f in files: if fnmatch.fnmatch(f, '*~'): @@ -3069,7 +3069,7 @@ def add_apperiph_defaults(self, f): self.add_firmware_defaults_from_file(f, "defaults_periph.h", "AP_Periph") def is_bootloader_fw(self): - return args.bootloader + return self.bootloader def add_bootloader_defaults(self, f): '''add default defines for peripherals''' @@ -3159,7 +3159,7 @@ def run(self): # exist in the same directory as the ldscript.ld file we generate. self.copy_common_linkerscript(self.outdir) - if not args.bootloader: + if not self.is_bootloader_fw(): self.write_processed_defaults_file(os.path.join(self.outdir, "processed_defaults.parm")) self.write_env_py(os.path.join(self.outdir, "env.py")) From e855c9f46a9781af7563a306bb38cdd99471e6f1 Mon Sep 17 00:00:00 2001 From: Oleksiy Protas Date: Mon, 18 Dec 2023 18:09:58 +0200 Subject: [PATCH 0270/1335] AP_HAL_SITL: ensure stdint include --- libraries/AP_HAL_SITL/CANSocketIface.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_HAL_SITL/CANSocketIface.cpp b/libraries/AP_HAL_SITL/CANSocketIface.cpp index abe9330acf1959..ad8b10f37b86cf 100644 --- a/libraries/AP_HAL_SITL/CANSocketIface.cpp +++ b/libraries/AP_HAL_SITL/CANSocketIface.cpp @@ -35,6 +35,7 @@ #include #include #include +#include #include "Scheduler.h" #include #include From 81ab6a946160b29255ed9d4b1c8d38ddc15bf745 Mon Sep 17 00:00:00 2001 From: Aleksey Ploskov Date: Fri, 29 Dec 2023 05:09:50 +0300 Subject: [PATCH 0271/1335] AP_NMEA_Output: fix time format --- libraries/AP_NMEA_Output/AP_NMEA_Output.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_NMEA_Output/AP_NMEA_Output.cpp b/libraries/AP_NMEA_Output/AP_NMEA_Output.cpp index bc7d0ff2ef898d..d114efc3e2d4ac 100644 --- a/libraries/AP_NMEA_Output/AP_NMEA_Output.cpp +++ b/libraries/AP_NMEA_Output/AP_NMEA_Output.cpp @@ -111,8 +111,8 @@ void AP_NMEA_Output::update() struct tm* tm = gmtime(&time_sec); // format time string - char tstring[11]; - snprintf(tstring, sizeof(tstring), "%02u%02u%06.2f", tm->tm_hour, tm->tm_min, tm->tm_sec + (time_usec % 1000000) * 1.0e-6); + char tstring[10]; + snprintf(tstring, sizeof(tstring), "%02u%02u%05.2f", tm->tm_hour, tm->tm_min, tm->tm_sec + (time_usec % 1000000) * 1.0e-6); Location loc; const auto &gps = AP::gps(); From 4dae077787047e0bc9f50a19f720bbb52368dfcf Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 27 Nov 2023 07:56:37 +1100 Subject: [PATCH 0272/1335] GCS_MAVLink: return MAV_RESULT_COMMAND_INT_ONLY if command-long support not compiled in --- libraries/GCS_MAVLink/GCS.h | 6 +- libraries/GCS_MAVLink/GCS_Common.cpp | 106 ++++++++++++++++----------- 2 files changed, 67 insertions(+), 45 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 867ec889031087..ccea42410f86ab 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -657,8 +657,6 @@ class GCS_MAVLINK MAV_RESULT handle_command_mag_cal(const mavlink_command_int_t &packet); MAV_RESULT handle_command_fixed_mag_cal_yaw(const mavlink_command_int_t &packet); - virtual bool mav_frame_for_command_long(MAV_FRAME &fame, MAV_CMD packet_command) const; - MAV_RESULT try_command_long_as_command_int(const mavlink_command_long_t &packet, const mavlink_message_t &msg); MAV_RESULT handle_command_camera(const mavlink_command_int_t &packet); MAV_RESULT handle_command_do_set_roi(const mavlink_command_int_t &packet); virtual MAV_RESULT handle_command_do_set_roi(const Location &roi_loc); @@ -730,12 +728,16 @@ class GCS_MAVLINK */ uint32_t correct_offboard_timestamp_usec_to_ms(uint64_t offboard_usec, uint16_t payload_size); +#if AP_MAVLINK_COMMAND_LONG_ENABLED // converts a COMMAND_LONG packet to a COMMAND_INT packet, where // the command-long packet is assumed to be in the supplied frame. // If location is not present in the command then just omit frame. // this method ensures the passed-in structure is entirely // initialised. virtual void convert_COMMAND_LONG_to_COMMAND_INT(const mavlink_command_long_t &in, mavlink_command_int_t &out, MAV_FRAME frame = MAV_FRAME_GLOBAL_RELATIVE_ALT); + virtual bool mav_frame_for_command_long(MAV_FRAME &fame, MAV_CMD packet_command) const; + MAV_RESULT try_command_long_as_command_int(const mavlink_command_long_t &packet, const mavlink_message_t &msg); +#endif // methods to extract a Location object from a command_int bool location_from_command_t(const mavlink_command_int_t &in, Location &out); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index f2fb1c5bb04c3e..f7ead3489f9830 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -4757,6 +4757,49 @@ MAV_RESULT GCS_MAVLINK::handle_command_component_arm_disarm(const mavlink_comman return MAV_RESULT_UNSUPPORTED; } +bool GCS_MAVLINK::location_from_command_t(const mavlink_command_int_t &in, Location &out) +{ + if (!command_long_stores_location((MAV_CMD)in.command)) { + return false; + } + + // integer storage imposes limits on the altitudes we can accept: + if (isnan(in.z) || fabsf(in.z) > LOCATION_ALT_MAX_M) { + return false; + } + + Location::AltFrame frame; + if (!mavlink_coordinate_frame_to_location_alt_frame((MAV_FRAME)in.frame, frame)) { + // unknown coordinate frame + return false; + } + + out.lat = in.x; + out.lng = in.y; + + out.set_alt_cm(int32_t(in.z * 100), frame); + + return true; +} + +bool GCS_MAVLINK::command_long_stores_location(const MAV_CMD command) +{ + switch(command) { + case MAV_CMD_DO_SET_HOME: + case MAV_CMD_DO_SET_ROI: + case MAV_CMD_DO_SET_ROI_LOCATION: + // case MAV_CMD_NAV_TAKEOFF: // technically yes, but we don't do lat/lng + // case MAV_CMD_NAV_VTOL_TAKEOFF: + case MAV_CMD_DO_REPOSITION: + case MAV_CMD_EXTERNAL_POSITION_ESTIMATE: + return true; + default: + return false; + } + return false; +} + +#if AP_MAVLINK_COMMAND_LONG_ENABLED // when conveyed via COMMAND_LONG, a command doesn't come with an // explicit frame. When conveying a location they do have an assumed // frame in ArduPilot, and this function returns that frame. @@ -4801,49 +4844,6 @@ MAV_RESULT GCS_MAVLINK::try_command_long_as_command_int(const mavlink_command_lo return handle_command_int_packet(command_int, msg); } -bool GCS_MAVLINK::location_from_command_t(const mavlink_command_int_t &in, Location &out) -{ - if (!command_long_stores_location((MAV_CMD)in.command)) { - return false; - } - - // integer storage imposes limits on the altitudes we can accept: - if (isnan(in.z) || fabsf(in.z) > LOCATION_ALT_MAX_M) { - return false; - } - - Location::AltFrame frame; - if (!mavlink_coordinate_frame_to_location_alt_frame((MAV_FRAME)in.frame, frame)) { - // unknown coordinate frame - return false; - } - - out.lat = in.x; - out.lng = in.y; - - out.set_alt_cm(int32_t(in.z * 100), frame); - - return true; -} - -#if AP_MAVLINK_COMMAND_LONG_ENABLED -bool GCS_MAVLINK::command_long_stores_location(const MAV_CMD command) -{ - switch(command) { - case MAV_CMD_DO_SET_HOME: - case MAV_CMD_DO_SET_ROI: - case MAV_CMD_DO_SET_ROI_LOCATION: - // case MAV_CMD_NAV_TAKEOFF: // technically yes, but we don't do lat/lng - // case MAV_CMD_NAV_VTOL_TAKEOFF: - case MAV_CMD_DO_REPOSITION: - case MAV_CMD_EXTERNAL_POSITION_ESTIMATE: - return true; - default: - return false; - } - return false; -} - // returns a value suitable for COMMAND_INT.x or y based on a value // coming in from COMMAND_LONG.p5 or p6: static int32_t convert_COMMAND_LONG_loc_param(float param, bool stores_location) @@ -4909,6 +4909,26 @@ void GCS_MAVLINK::handle_command_long(const mavlink_message_t &msg) hal.util->persistent_data.last_mavlink_cmd = 0; } + +#else +void GCS_MAVLINK::handle_command_long(const mavlink_message_t &msg) +{ + // decode packet + mavlink_command_long_t packet; + mavlink_msg_command_long_decode(&msg, &packet); + + // send ACK or NAK + mavlink_msg_command_ack_send( + chan, + packet.command, + MAV_RESULT_COMMAND_INT_ONLY, + 0, + 0, + msg.sysid, + msg.compid + ); + +} #endif // AP_MAVLINK_COMMAND_LONG_ENABLED MAV_RESULT GCS_MAVLINK::handle_command_do_set_roi(const Location &roi_loc) From 6c105d264949605be6242079468dcbf77aba8e77 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 27 Nov 2023 08:08:23 +1100 Subject: [PATCH 0273/1335] PLane: return MAV_RESULT_COMMAND_INT_ONLY if command-long support not compiled in --- ArduPlane/GCS_Mavlink.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 9427b99e0cdac9..3715776f77ab64 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -1095,6 +1095,7 @@ MAV_RESULT GCS_MAVLINK_Plane::handle_command_DO_CHANGE_SPEED(const mavlink_comma } #if HAL_QUADPLANE_ENABLED +#if AP_MAVLINK_COMMAND_LONG_ENABLED void GCS_MAVLINK_Plane::convert_MAV_CMD_NAV_TAKEOFF_to_COMMAND_INT(const mavlink_command_long_t &in, mavlink_command_int_t &out) { // convert to MAV_FRAME_LOCAL_OFFSET_NED, "NED local tangent frame @@ -1115,7 +1116,6 @@ void GCS_MAVLINK_Plane::convert_MAV_CMD_NAV_TAKEOFF_to_COMMAND_INT(const mavlink out.z = -in.param7; // up -> down } -#if AP_MAVLINK_COMMAND_LONG_ENABLED void GCS_MAVLINK_Plane::convert_COMMAND_LONG_to_COMMAND_INT(const mavlink_command_long_t &in, mavlink_command_int_t &out, MAV_FRAME frame) { switch (in.command) { From 85537c2e9754c331ae527c1ef432297e4c8bfabb Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 2 Jan 2024 17:46:55 +1100 Subject: [PATCH 0274/1335] AP_NMEA_Output: fixed NMEA output altitude the key fix is to multiply hdop by 0.01. It was being passed as a uint16_t which led to it being swallowed by the %f in the format string --- libraries/AP_NMEA_Output/AP_NMEA_Output.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AP_NMEA_Output/AP_NMEA_Output.cpp b/libraries/AP_NMEA_Output/AP_NMEA_Output.cpp index d114efc3e2d4ac..6e2ab5c9d20fdc 100644 --- a/libraries/AP_NMEA_Output/AP_NMEA_Output.cpp +++ b/libraries/AP_NMEA_Output/AP_NMEA_Output.cpp @@ -112,7 +112,7 @@ void AP_NMEA_Output::update() // format time string char tstring[10]; - snprintf(tstring, sizeof(tstring), "%02u%02u%05.2f", tm->tm_hour, tm->tm_min, tm->tm_sec + (time_usec % 1000000) * 1.0e-6); + hal.util->snprintf(tstring, sizeof(tstring), "%02u%02u%05.2f", tm->tm_hour, tm->tm_min, tm->tm_sec + (time_usec % 1000000) * 1.0e-6); Location loc; const auto &gps = AP::gps(); @@ -131,7 +131,7 @@ void AP_NMEA_Output::update() char lat_string[13]; double deg = fabs(loc.lat * 1.0e-7f); double min_dec = ((fabs(loc.lat) - (unsigned)deg * 1.0e7)) * 60 * 1.e-7f; - snprintf(lat_string, + hal.util->snprintf(lat_string, sizeof(lat_string), "%02u%08.5f,%c", (unsigned) deg, @@ -142,7 +142,7 @@ void AP_NMEA_Output::update() char lng_string[14]; deg = fabs(loc.lng * 1.0e-7f); min_dec = ((fabs(loc.lng) - (unsigned)deg * 1.0e7)) * 60 * 1.e-7f; - snprintf(lng_string, + hal.util->snprintf(lng_string, sizeof(lng_string), "%03u%08.5f,%c", (unsigned) deg, @@ -208,7 +208,7 @@ void AP_NMEA_Output::update() lng_string, fix_quality, gps.num_sats(), - gps.get_hdop(), + gps.get_hdop()*0.01, loc.alt * 0.01f); space_required += gga_length; @@ -219,7 +219,7 @@ void AP_NMEA_Output::update() if ((_message_enable_bitmask.get() & static_cast(Enabled_Messages::GPRMC)) != 0) { // format date string char dstring[7]; - snprintf(dstring, sizeof(dstring), "%02u%02u%02u", tm->tm_mday, tm->tm_mon+1, tm->tm_year % 100); + hal.util->snprintf(dstring, sizeof(dstring), "%02u%02u%02u", tm->tm_mday, tm->tm_mon+1, tm->tm_year % 100); // get speed #if AP_AHRS_ENABLED From d1fcb76c9f950ade12c47e7a66b6a0e316013a77 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 2 Jan 2024 17:47:25 +1100 Subject: [PATCH 0275/1335] AP_HAL: ensure all UARTDriver implementations have receive_time_constraint_us this fixes NMEA over network ports --- libraries/AP_HAL/UARTDriver.cpp | 11 +++++++++++ libraries/AP_HAL/UARTDriver.h | 4 +--- 2 files changed, 12 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL/UARTDriver.cpp b/libraries/AP_HAL/UARTDriver.cpp index 40819c9900c41d..b3d06c4f450ff2 100644 --- a/libraries/AP_HAL/UARTDriver.cpp +++ b/libraries/AP_HAL/UARTDriver.cpp @@ -152,3 +152,14 @@ bool AP_HAL::UARTDriver::discard_input() } return _discard_input(); } + +/* + default implementation of receive_time_constraint_us() will be used + for subclasses that don't implement the call (eg. network + sockets). Best we can do is to use the current timestamp as we don't + know the transport delay + */ +uint64_t AP_HAL::UARTDriver::receive_time_constraint_us(uint16_t nbytes) +{ + return AP_HAL::micros64(); +} diff --git a/libraries/AP_HAL/UARTDriver.h b/libraries/AP_HAL/UARTDriver.h index b3e890b7199d11..a7e0c61ef2f628 100644 --- a/libraries/AP_HAL/UARTDriver.h +++ b/libraries/AP_HAL/UARTDriver.h @@ -137,10 +137,8 @@ class AP_HAL::UARTDriver : public AP_HAL::BetterStream { This takes account of the baudrate of the link. For transports that have no baudrate (such as USB) the time estimate may be less accurate. - - A return value of zero means the HAL does not support this API */ - virtual uint64_t receive_time_constraint_us(uint16_t nbytes) { return 0; } + virtual uint64_t receive_time_constraint_us(uint16_t nbytes); virtual uint32_t bw_in_bytes_per_second() const { return 5760; From a52c71f3806f5ea818f362ed47501961fd0b4a29 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 30 Dec 2023 08:29:46 +1100 Subject: [PATCH 0276/1335] AP_HAL: implement BinarySemaphore and removed event handles --- libraries/AP_HAL/AP_HAL.h | 1 - libraries/AP_HAL/AP_HAL_Namespace.h | 3 +- libraries/AP_HAL/CANIface.h | 2 +- libraries/AP_HAL/EventHandle.cpp | 33 ---------------------- libraries/AP_HAL/EventHandle.h | 44 ----------------------------- libraries/AP_HAL/Semaphores.h | 25 ++++++++++++++++ libraries/AP_HAL/board/chibios.h | 4 +-- libraries/AP_HAL/board/empty.h | 1 + libraries/AP_HAL/board/esp32.h | 3 +- libraries/AP_HAL/board/linux.h | 3 +- libraries/AP_HAL/board/sitl.h | 4 +-- 11 files changed, 33 insertions(+), 90 deletions(-) delete mode 100644 libraries/AP_HAL/EventHandle.cpp delete mode 100644 libraries/AP_HAL/EventHandle.h diff --git a/libraries/AP_HAL/AP_HAL.h b/libraries/AP_HAL/AP_HAL.h index 64198b63d00e3e..49aab05996f6b9 100644 --- a/libraries/AP_HAL/AP_HAL.h +++ b/libraries/AP_HAL/AP_HAL.h @@ -16,7 +16,6 @@ #include "RCOutput.h" #include "Scheduler.h" #include "Semaphores.h" -#include "EventHandle.h" #include "Util.h" #include "OpticalFlow.h" #include "Flash.h" diff --git a/libraries/AP_HAL/AP_HAL_Namespace.h b/libraries/AP_HAL/AP_HAL_Namespace.h index aca8e02293763a..9782b9fb2c4e6c 100644 --- a/libraries/AP_HAL/AP_HAL_Namespace.h +++ b/libraries/AP_HAL/AP_HAL_Namespace.h @@ -27,9 +27,8 @@ namespace AP_HAL { class RCInput; class RCOutput; class Scheduler; - class EventHandle; - class EventSource; class Semaphore; + class BinarySemaphore; class OpticalFlow; class DSP; diff --git a/libraries/AP_HAL/CANIface.h b/libraries/AP_HAL/CANIface.h index 06b4f7dffbf848..1b2e88fb33f236 100644 --- a/libraries/AP_HAL/CANIface.h +++ b/libraries/AP_HAL/CANIface.h @@ -187,7 +187,7 @@ class AP_HAL::CANIface return false; } - virtual bool set_event_handle(EventHandle* evt_handle) + virtual bool set_event_handle(AP_HAL::BinarySemaphore *sem_handle) { return true; } diff --git a/libraries/AP_HAL/EventHandle.cpp b/libraries/AP_HAL/EventHandle.cpp deleted file mode 100644 index d0dab77d9245e1..00000000000000 --- a/libraries/AP_HAL/EventHandle.cpp +++ /dev/null @@ -1,33 +0,0 @@ -#include "EventHandle.h" -#include - - -bool AP_HAL::EventHandle::register_event(uint32_t evt_mask) -{ - WITH_SEMAPHORE(sem); - evt_mask_ |= evt_mask; - return true; -} - -bool AP_HAL::EventHandle::unregister_event(uint32_t evt_mask) -{ - WITH_SEMAPHORE(sem); - evt_mask_ &= ~evt_mask; - return true; -} - -bool AP_HAL::EventHandle::wait(uint16_t duration_us) -{ - if (evt_src_ == nullptr) { - return false; - } - return evt_src_->wait(duration_us, this); -} - -bool AP_HAL::EventHandle::set_source(AP_HAL::EventSource* src) -{ - WITH_SEMAPHORE(sem); - evt_src_ = src; - evt_mask_ = 0; - return true; -} diff --git a/libraries/AP_HAL/EventHandle.h b/libraries/AP_HAL/EventHandle.h deleted file mode 100644 index c5c676c389a907..00000000000000 --- a/libraries/AP_HAL/EventHandle.h +++ /dev/null @@ -1,44 +0,0 @@ -#pragma once - -#include "AP_HAL_Namespace.h" -#include -#include "AP_HAL_Boards.h" - -class AP_HAL::EventSource { -public: - // generate event from thread context - virtual void signal(uint32_t evt_mask) = 0; - - // generate event from interrupt context - virtual void signalI(uint32_t evt_mask) { signal(evt_mask); } - - - // Wait on an Event handle, method for internal use by EventHandle - virtual bool wait(uint16_t duration_us, AP_HAL::EventHandle* evt_handle) = 0; -}; - -class AP_HAL::EventHandle { -public: - //Set event source - virtual bool set_source(AP_HAL::EventSource* src); - - AP_HAL::EventSource* get_source() { return evt_src_; } - - // return true if event type was successfully registered - virtual bool register_event(uint32_t evt_mask); - - // return true if event type was successfully unregistered - virtual bool unregister_event(uint32_t evt_mask); - - // return true if event was triggered within the duration - virtual bool wait(uint16_t duration_us); - - virtual uint32_t get_evt_mask() const { return evt_mask_; } - -private: - // Mask of events to be handeled, - // Max 32 events can be handled per event handle - uint32_t evt_mask_; - AP_HAL::EventSource *evt_src_; - HAL_Semaphore sem; -}; diff --git a/libraries/AP_HAL/Semaphores.h b/libraries/AP_HAL/Semaphores.h index 3c5bca94b13bb3..34e8ff93fb86a5 100644 --- a/libraries/AP_HAL/Semaphores.h +++ b/libraries/AP_HAL/Semaphores.h @@ -55,3 +55,28 @@ class WithSemaphore { #define JOIN( sem, line, counter ) _DO_JOIN( sem, line, counter ) #define _DO_JOIN( sem, line, counter ) WithSemaphore _getsem ## counter(sem, line) + +/* + a binary semaphore + */ +class AP_HAL::BinarySemaphore { +public: + /* + create a binary semaphore. initial_state determines if a wait() + immediately after creation would block. If initial_state is true + then it won't block, if initial_state is false it will block + */ + BinarySemaphore(bool initial_state=false) {} + + // do not allow copying + CLASS_NO_COPY(BinarySemaphore); + + virtual bool wait(uint32_t timeout_us) WARN_IF_UNUSED = 0 ; + virtual bool wait_blocking() = 0; + virtual bool wait_nonblocking() { return wait(0); } + + virtual void signal() = 0; + virtual void signal_ISR() { signal(); } + + virtual ~BinarySemaphore(void) {} +}; diff --git a/libraries/AP_HAL/board/chibios.h b/libraries/AP_HAL/board/chibios.h index b06642742d0fb9..9d1b940f310029 100644 --- a/libraries/AP_HAL/board/chibios.h +++ b/libraries/AP_HAL/board/chibios.h @@ -63,9 +63,7 @@ // allow for static semaphores #include #define HAL_Semaphore ChibiOS::Semaphore - -#include -#define HAL_EventHandle AP_HAL::EventHandle +#define HAL_BinarySemaphore ChibiOS::BinarySemaphore #endif /* string names for well known SPI devices */ diff --git a/libraries/AP_HAL/board/empty.h b/libraries/AP_HAL/board/empty.h index 6e33c9a81b103e..0dc26bdf23c149 100644 --- a/libraries/AP_HAL/board/empty.h +++ b/libraries/AP_HAL/board/empty.h @@ -16,3 +16,4 @@ #define HAL_HAVE_SAFETY_SWITCH 1 #define HAL_Semaphore Empty::Semaphore +#define HAL_BinarySemaphore Empty::BinarySemaphore diff --git a/libraries/AP_HAL/board/esp32.h b/libraries/AP_HAL/board/esp32.h index 5aa515e6149af0..1fc82f841bdfa7 100644 --- a/libraries/AP_HAL/board/esp32.h +++ b/libraries/AP_HAL/board/esp32.h @@ -39,6 +39,7 @@ // allow for static semaphores #include #define HAL_Semaphore ESP32::Semaphore +#define HAL_BinarySemaphore ESP32::BinarySemaphore #endif #define HAL_NUM_CAN_IFACES 0 @@ -114,4 +115,4 @@ // other big things.. #define HAL_QUADPLANE_ENABLED 0 -#define HAL_GYROFFT_ENABLED 0 \ No newline at end of file +#define HAL_GYROFFT_ENABLED 0 diff --git a/libraries/AP_HAL/board/linux.h b/libraries/AP_HAL/board/linux.h index 76cea1a112982e..65ce66d2a10e40 100644 --- a/libraries/AP_HAL/board/linux.h +++ b/libraries/AP_HAL/board/linux.h @@ -398,8 +398,7 @@ #ifdef __cplusplus #include #define HAL_Semaphore Linux::Semaphore -#include -#define HAL_EventHandle AP_HAL::EventHandle +#define HAL_BinarySemaphore Linux::BinarySemaphore #endif #ifndef HAL_HAVE_HARDWARE_DOUBLE diff --git a/libraries/AP_HAL/board/sitl.h b/libraries/AP_HAL/board/sitl.h index aa2799f09abc63..a4b3bba71dfbe0 100644 --- a/libraries/AP_HAL/board/sitl.h +++ b/libraries/AP_HAL/board/sitl.h @@ -54,9 +54,7 @@ // allow for static semaphores #include #define HAL_Semaphore HALSITL::Semaphore - -#include -#define HAL_EventHandle AP_HAL::EventHandle +#define HAL_BinarySemaphore HALSITL::BinarySemaphore #endif #ifndef HAL_NUM_CAN_IFACES From c2011570f742ad8d47b523afaa4e04231bd54885 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 30 Dec 2023 08:52:44 +1100 Subject: [PATCH 0277/1335] HAL_ChibiOS: use chSysLock for CAN critical section this avoids an assert in some code paths that combine with hrt functions --- libraries/AP_HAL_ChibiOS/CANFDIface.h | 4 ++-- libraries/AP_HAL_ChibiOS/CANIface.h | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/CANFDIface.h b/libraries/AP_HAL_ChibiOS/CANFDIface.h index 9b214441617207..81815fdaa09ece 100644 --- a/libraries/AP_HAL_ChibiOS/CANFDIface.h +++ b/libraries/AP_HAL_ChibiOS/CANFDIface.h @@ -73,11 +73,11 @@ class ChibiOS::CANIface : public AP_HAL::CANIface struct CriticalSectionLocker { CriticalSectionLocker() { - chSysSuspend(); + chSysLock(); } ~CriticalSectionLocker() { - chSysEnable(); + chSysUnlock(); } }; diff --git a/libraries/AP_HAL_ChibiOS/CANIface.h b/libraries/AP_HAL_ChibiOS/CANIface.h index 47809fa79b35a3..b85ed4e538ac74 100644 --- a/libraries/AP_HAL_ChibiOS/CANIface.h +++ b/libraries/AP_HAL_ChibiOS/CANIface.h @@ -69,11 +69,11 @@ class ChibiOS::CANIface : public AP_HAL::CANIface struct CriticalSectionLocker { CriticalSectionLocker() { - chSysSuspend(); + chSysLock(); } ~CriticalSectionLocker() { - chSysEnable(); + chSysUnlock(); } }; From 8a027eddb0db262967b5048b9fc51f83133e8abb Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 30 Dec 2023 08:30:22 +1100 Subject: [PATCH 0278/1335] HAL_ChibiOS: implement BinarySemaphore and removed event handles --- .../AP_HAL_ChibiOS/AP_HAL_ChibiOS_Namespace.h | 2 +- libraries/AP_HAL_ChibiOS/EventSource.cpp | 35 ------------ libraries/AP_HAL_ChibiOS/EventSource.h | 26 --------- libraries/AP_HAL_ChibiOS/Semaphores.cpp | 55 +++++++++++++++++++ libraries/AP_HAL_ChibiOS/Semaphores.h | 18 ++++++ 5 files changed, 74 insertions(+), 62 deletions(-) delete mode 100644 libraries/AP_HAL_ChibiOS/EventSource.cpp delete mode 100644 libraries/AP_HAL_ChibiOS/EventSource.h diff --git a/libraries/AP_HAL_ChibiOS/AP_HAL_ChibiOS_Namespace.h b/libraries/AP_HAL_ChibiOS/AP_HAL_ChibiOS_Namespace.h index 9d559a561c4e64..4b62fcb9286a0b 100644 --- a/libraries/AP_HAL_ChibiOS/AP_HAL_ChibiOS_Namespace.h +++ b/libraries/AP_HAL_ChibiOS/AP_HAL_ChibiOS_Namespace.h @@ -17,7 +17,7 @@ namespace ChibiOS { class RCOutput; class Scheduler; class Semaphore; - class EventSource; + class BinarySemaphore; class SPIBus; class SPIDesc; class SPIDevice; diff --git a/libraries/AP_HAL_ChibiOS/EventSource.cpp b/libraries/AP_HAL_ChibiOS/EventSource.cpp deleted file mode 100644 index f1821bca000b89..00000000000000 --- a/libraries/AP_HAL_ChibiOS/EventSource.cpp +++ /dev/null @@ -1,35 +0,0 @@ -#include "EventSource.h" -#include - -using namespace ChibiOS; - -#if CH_CFG_USE_EVENTS == TRUE - -bool EventSource::wait(uint16_t duration_us, AP_HAL::EventHandle *evt_handle) -{ - chibios_rt::EventListener evt_listener; - eventmask_t evt_mask = evt_handle->get_evt_mask(); - msg_t ret = msg_t(); - ch_evt_src_.registerMask(&evt_listener, evt_mask); - if (duration_us == 0) { - ret = chEvtWaitAnyTimeout(evt_mask, TIME_IMMEDIATE); - } else { - const sysinterval_t wait_us = MIN(TIME_MAX_INTERVAL, MAX(CH_CFG_ST_TIMEDELTA, chTimeUS2I(duration_us))); - ret = chEvtWaitAnyTimeout(evt_mask, wait_us); - } - ch_evt_src_.unregister(&evt_listener); - return ret == MSG_OK; -} - -void EventSource::signal(uint32_t evt_mask) -{ - ch_evt_src_.broadcastFlags(evt_mask); -} - -__RAMFUNC__ void EventSource::signalI(uint32_t evt_mask) -{ - chSysLockFromISR(); - ch_evt_src_.broadcastFlagsI(evt_mask); - chSysUnlockFromISR(); -} -#endif //#if CH_CFG_USE_EVENTS == TRUE diff --git a/libraries/AP_HAL_ChibiOS/EventSource.h b/libraries/AP_HAL_ChibiOS/EventSource.h deleted file mode 100644 index a1dda78b2e3208..00000000000000 --- a/libraries/AP_HAL_ChibiOS/EventSource.h +++ /dev/null @@ -1,26 +0,0 @@ -#pragma once -#include - -#include -#include -#include -#include -#include "AP_HAL_ChibiOS_Namespace.h" -#include - -#if CH_CFG_USE_EVENTS == TRUE -class ChibiOS::EventSource : public AP_HAL::EventSource { - // Single event source to be shared across multiple users - chibios_rt::EventSource ch_evt_src_; - -public: - // generate event from thread context - void signal(uint32_t evt_mask) override; - - // generate event from interrupt context - void signalI(uint32_t evt_mask) override; - - // Wait on an Event handle, method for internal use by EventHandle - bool wait(uint16_t duration_us, AP_HAL::EventHandle* evt_handle) override; -}; -#endif //#if CH_CFG_USE_EVENTS == TRUE diff --git a/libraries/AP_HAL_ChibiOS/Semaphores.cpp b/libraries/AP_HAL_ChibiOS/Semaphores.cpp index 49493399774eb2..47e24348aff111 100644 --- a/libraries/AP_HAL_ChibiOS/Semaphores.cpp +++ b/libraries/AP_HAL_ChibiOS/Semaphores.cpp @@ -18,7 +18,9 @@ #include #include "Semaphores.h" #include +#include #include "AP_HAL_ChibiOS.h" +#include #if CH_CFG_USE_MUTEXES == TRUE @@ -78,4 +80,57 @@ void Semaphore::assert_owner(void) osalDbgAssert(check_owner(), "owner"); } +#if CH_CFG_USE_SEMAPHORES == TRUE +BinarySemaphore::BinarySemaphore(bool initial_state) : + AP_HAL::BinarySemaphore(initial_state) +{ + static_assert(sizeof(_lock) >= sizeof(semaphore_t), "invalid semaphore_t size"); + auto *sem = (binary_semaphore_t *)_lock; + /* + the initial_state in ChibiOS binary semaphores is 'taken', so we + need to negate it for the ArduPilot semantics + */ + chBSemObjectInit(sem, !initial_state); +} + +bool BinarySemaphore::wait(uint32_t timeout_us) +{ + auto *sem = (binary_semaphore_t *)_lock; + if (timeout_us == 0) { + return chBSemWaitTimeout(sem, TIME_IMMEDIATE) == MSG_OK; + } + // loop waiting for 60ms at a time. This ensures we can wait for + // any amount of time even on systems with a 16 bit timer + while (timeout_us > 0) { + const uint32_t us = MIN(timeout_us, 60000U); + if (chBSemWaitTimeout(sem, TIME_US2I(us)) == MSG_OK) { + return true; + } + timeout_us -= us; + } + return false; +} + +bool BinarySemaphore::wait_blocking(void) +{ + auto *sem = (binary_semaphore_t *)_lock; + return chBSemWait(sem) == MSG_OK; +} + +void BinarySemaphore::signal(void) +{ + auto *sem = (binary_semaphore_t *)_lock; + chBSemSignal(sem); +} + +void BinarySemaphore::signal_ISR(void) +{ + auto *sem = (binary_semaphore_t *)_lock; + chSysLockFromISR(); + chBSemSignalI(sem); + chSysUnlockFromISR(); +} + +#endif // CH_CFG_USE_SEMAPHORES == TRUE + #endif // CH_CFG_USE_MUTEXES diff --git a/libraries/AP_HAL_ChibiOS/Semaphores.h b/libraries/AP_HAL_ChibiOS/Semaphores.h index 484570d0869da4..49f258366bcfff 100644 --- a/libraries/AP_HAL_ChibiOS/Semaphores.h +++ b/libraries/AP_HAL_ChibiOS/Semaphores.h @@ -37,3 +37,21 @@ class ChibiOS::Semaphore : public AP_HAL::Semaphore { // we declare the lock as a uint32_t array, and cast inside the cpp file uint32_t _lock[5]; }; + +/* + BinarySemaphore implementation + */ +class ChibiOS::BinarySemaphore : public AP_HAL::BinarySemaphore { +public: + BinarySemaphore(bool initial_state=false); + + CLASS_NO_COPY(BinarySemaphore); + + bool wait(uint32_t timeout_us) override; + bool wait_blocking(void) override; + void signal(void) override; + void signal_ISR(void) override; + +protected: + uint32_t _lock[5]; +}; From c0d0aeee8686d7df3a3597c01d0c3985c948dd89 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 30 Dec 2023 08:30:41 +1100 Subject: [PATCH 0279/1335] HAL_ChibiOS: reimplement CAN with BinarySemaphore --- libraries/AP_HAL_ChibiOS/CANFDIface.cpp | 31 +++++++++---------------- libraries/AP_HAL_ChibiOS/CANFDIface.h | 11 +++------ libraries/AP_HAL_ChibiOS/CANIface.h | 12 ++++------ libraries/AP_HAL_ChibiOS/CanIface.cpp | 31 ++++++++++--------------- 4 files changed, 30 insertions(+), 55 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/CANFDIface.cpp b/libraries/AP_HAL_ChibiOS/CANFDIface.cpp index eaefd34324c69c..08c532e46d1a56 100644 --- a/libraries/AP_HAL_ChibiOS/CANFDIface.cpp +++ b/libraries/AP_HAL_ChibiOS/CANFDIface.cpp @@ -812,11 +812,9 @@ void CANIface::handleTxCompleteInterrupt(const uint64_t timestamp_us) rx_item.flags = AP_HAL::CANIface::Loopback; add_to_rx_queue(rx_item); } - if (event_handle_ != nullptr) { - stats.num_events++; -#if CH_CFG_USE_EVENTS == TRUE - evt_src_.signalI(1 << self_index_); -#endif + stats.num_events++; + if (sem_handle != nullptr) { + sem_handle->signal_ISR(); } } } @@ -925,11 +923,9 @@ void CANIface::handleRxInterrupt(uint8_t fifo_index) while (readRxFIFO(fifo_index)) { had_activity_ = true; } - if (event_handle_ != nullptr) { - stats.num_events++; -#if CH_CFG_USE_EVENTS == TRUE - evt_src_.signalI(1 << self_index_); -#endif + stats.num_events++; + if (sem_handle != nullptr) { + sem_handle->signal_ISR(); } } @@ -995,16 +991,11 @@ uint32_t CANIface::getErrorCount() const stats.tx_timedout; } -#if CH_CFG_USE_EVENTS == TRUE -ChibiOS::EventSource CANIface::evt_src_; -bool CANIface::set_event_handle(AP_HAL::EventHandle* handle) +bool CANIface::set_event_handle(AP_HAL::BinarySemaphore *handle) { - CriticalSectionLocker lock; - event_handle_ = handle; - event_handle_->set_source(&evt_src_); - return event_handle_->register_event(1 << self_index_); + sem_handle = handle; + return true; } -#endif bool CANIface::isRxBufferEmpty() const { @@ -1075,10 +1066,10 @@ bool CANIface::select(bool &read, bool &write, return true; } while (time < blocking_deadline) { - if (event_handle_ == nullptr) { + if (sem_handle == nullptr) { break; } - event_handle_->wait(blocking_deadline - time); // Block until timeout expires or any iface updates + IGNORE_RETURN(sem_handle->wait(blocking_deadline - time)); // Block until timeout expires or any iface updates checkAvailable(read, write, pending_tx); // Check what we got if ((read && in_read) || (write && in_write)) { return true; diff --git a/libraries/AP_HAL_ChibiOS/CANFDIface.h b/libraries/AP_HAL_ChibiOS/CANFDIface.h index 81815fdaa09ece..f7ff133392bbdb 100644 --- a/libraries/AP_HAL_ChibiOS/CANFDIface.h +++ b/libraries/AP_HAL_ChibiOS/CANFDIface.h @@ -41,7 +41,6 @@ #pragma once #include "AP_HAL_ChibiOS.h" -#include "EventSource.h" #if HAL_NUM_CAN_IFACES @@ -120,10 +119,8 @@ class ChibiOS::CANIface : public AP_HAL::CANIface bool irq_init_; bool initialised_; bool had_activity_; - AP_HAL::EventHandle* event_handle_; -#if CH_CFG_USE_EVENTS == TRUE - static ChibiOS::EventSource evt_src_; -#endif + AP_HAL::BinarySemaphore *sem_handle; + const uint8_t self_index_; bool computeTimings(uint32_t target_bitrate, Timings& out_timings); @@ -224,10 +221,8 @@ class ChibiOS::CANIface : public AP_HAL::CANIface const AP_HAL::CANFrame* const pending_tx, uint64_t blocking_deadline) override; -#if CH_CFG_USE_EVENTS == TRUE // setup event handle for waiting on events - bool set_event_handle(AP_HAL::EventHandle* handle) override; -#endif + bool set_event_handle(AP_HAL::BinarySemaphore *handle) override; #if !defined(HAL_BOOTLOADER_BUILD) // fetch stats text and return the size of the same, diff --git a/libraries/AP_HAL_ChibiOS/CANIface.h b/libraries/AP_HAL_ChibiOS/CANIface.h index b85ed4e538ac74..363c002d491ec8 100644 --- a/libraries/AP_HAL_ChibiOS/CANIface.h +++ b/libraries/AP_HAL_ChibiOS/CANIface.h @@ -46,7 +46,6 @@ # else #if HAL_NUM_CAN_IFACES #include "bxcan.hpp" -#include "EventSource.h" #ifndef HAL_CAN_RX_QUEUE_SIZE #define HAL_CAN_RX_QUEUE_SIZE 128 @@ -109,10 +108,8 @@ class ChibiOS::CANIface : public AP_HAL::CANIface bool irq_init_:1; bool initialised_:1; bool had_activity_:1; -#if CH_CFG_USE_EVENTS == TRUE - AP_HAL::EventHandle* event_handle_; - static ChibiOS::EventSource evt_src_; -#endif + AP_HAL::BinarySemaphore *sem_handle; + const uint8_t self_index_; bool computeTimings(uint32_t target_bitrate, Timings& out_timings); @@ -210,10 +207,9 @@ class ChibiOS::CANIface : public AP_HAL::CANIface const AP_HAL::CANFrame* const pending_tx, uint64_t blocking_deadline) override; -#if CH_CFG_USE_EVENTS == TRUE // setup event handle for waiting on events - bool set_event_handle(AP_HAL::EventHandle* handle) override; -#endif + bool set_event_handle(AP_HAL::BinarySemaphore *handle) override; + #if !defined(HAL_BUILD_AP_PERIPH) && !defined(HAL_BOOTLOADER_BUILD) // fetch stats text and return the size of the same, // results available via @SYS/can0_stats.txt or @SYS/can1_stats.txt diff --git a/libraries/AP_HAL_ChibiOS/CanIface.cpp b/libraries/AP_HAL_ChibiOS/CanIface.cpp index 97cd8acf2ad1be..f6704b6438d09d 100644 --- a/libraries/AP_HAL_ChibiOS/CanIface.cpp +++ b/libraries/AP_HAL_ChibiOS/CanIface.cpp @@ -522,12 +522,11 @@ void CANIface::handleTxInterrupt(const uint64_t utc_usec) handleTxMailboxInterrupt(2, txok, utc_usec); } -#if CH_CFG_USE_EVENTS == TRUE - if (event_handle_ != nullptr) { + if (sem_handle != nullptr) { PERF_STATS(stats.num_events); - evt_src_.signalI(1 << self_index_); + sem_handle->signal_ISR(); } -#endif + pollErrorFlagsFromISR(); } @@ -590,12 +589,11 @@ void CANIface::handleRxInterrupt(uint8_t fifo_index, uint64_t timestamp_us) had_activity_ = true; -#if CH_CFG_USE_EVENTS == TRUE - if (event_handle_ != nullptr) { + if (sem_handle != nullptr) { PERF_STATS(stats.num_events); - evt_src_.signalI(1 << self_index_); + sem_handle->signal_ISR(); } -#endif + pollErrorFlagsFromISR(); } @@ -702,17 +700,12 @@ uint32_t CANIface::getErrorCount() const #endif // #if !defined(HAL_BUILD_AP_PERIPH) && !defined(HAL_BOOTLOADER_BUILD) -#if CH_CFG_USE_EVENTS == TRUE -ChibiOS::EventSource CANIface::evt_src_; -bool CANIface::set_event_handle(AP_HAL::EventHandle* handle) +bool CANIface::set_event_handle(AP_HAL::BinarySemaphore *handle) { - CriticalSectionLocker lock; - event_handle_ = handle; - event_handle_->set_source(&evt_src_); - return event_handle_->register_event(1 << self_index_); + sem_handle = handle; + return true; } -#endif // #if CH_CFG_USE_EVENTS == TRUE void CANIface::checkAvailable(bool& read, bool& write, const AP_HAL::CANFrame* pending_tx) const { @@ -745,13 +738,13 @@ bool CANIface::select(bool &read, bool &write, return true; } -#if CH_CFG_USE_EVENTS == TRUE +#if !defined(HAL_BUILD_AP_PERIPH) && !defined(HAL_BOOTLOADER_BUILD) // we don't support blocking select in AP_Periph and bootloader while (time < blocking_deadline) { - if (event_handle_ == nullptr) { + if (sem_handle == nullptr) { break; } - event_handle_->wait(blocking_deadline - time); // Block until timeout expires or any iface updates + IGNORE_RETURN(sem_handle->wait(blocking_deadline - time)); // Block until timeout expires or any iface updates checkAvailable(read, write, pending_tx); // Check what we got if ((read && in_read) || (write && in_write)) { return true; From bdb8a08724a8654adec75e4bf74c27cbcac46805 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 30 Dec 2023 08:30:57 +1100 Subject: [PATCH 0280/1335] HAL_Linux: implement BinarySemaphore --- libraries/AP_HAL_Linux/Semaphores.cpp | 53 +++++++++++++++++++++++++++ libraries/AP_HAL_Linux/Semaphores.h | 16 ++++++++ 2 files changed, 69 insertions(+) diff --git a/libraries/AP_HAL_Linux/Semaphores.cpp b/libraries/AP_HAL_Linux/Semaphores.cpp index dcc0e7af41d353..502648877d8752 100644 --- a/libraries/AP_HAL_Linux/Semaphores.cpp +++ b/libraries/AP_HAL_Linux/Semaphores.cpp @@ -44,3 +44,56 @@ bool Semaphore::take_nonblocking() return pthread_mutex_trylock(&_lock) == 0; } +/* + binary semaphore using pthread condition variables + */ + +BinarySemaphore::BinarySemaphore(bool initial_state) : + AP_HAL::BinarySemaphore(initial_state) +{ + pthread_cond_init(&cond, NULL); + pending = initial_state; +} + +bool BinarySemaphore::wait(uint32_t timeout_us) +{ + WITH_SEMAPHORE(mtx); + if (!pending) { + struct timespec ts; + if (clock_gettime(CLOCK_REALTIME, &ts) != 0) { + return false; + } + ts.tv_sec += timeout_us/1000000UL; + ts.tv_nsec += (timeout_us % 1000000U) * 1000UL; + if (ts.tv_nsec >= 1000000000L) { + ts.tv_sec++; + ts.tv_nsec -= 1000000000L; + } + if (pthread_cond_timedwait(&cond, &mtx._lock, &ts) != 0) { + return false; + } + } + pending = false; + return true; +} + +bool BinarySemaphore::wait_blocking(void) +{ + WITH_SEMAPHORE(mtx); + if (!pending) { + if (pthread_cond_wait(&cond, &mtx._lock) != 0) { + return false; + } + } + pending = false; + return true; +} + +void BinarySemaphore::signal(void) +{ + WITH_SEMAPHORE(mtx); + if (!pending) { + pending = true; + pthread_cond_signal(&cond); + } +} diff --git a/libraries/AP_HAL_Linux/Semaphores.h b/libraries/AP_HAL_Linux/Semaphores.h index 90655871ec1aa5..e10af8116927b0 100644 --- a/libraries/AP_HAL_Linux/Semaphores.h +++ b/libraries/AP_HAL_Linux/Semaphores.h @@ -10,6 +10,7 @@ namespace Linux { class Semaphore : public AP_HAL::Semaphore { public: + friend class BinarySemaphore; Semaphore(); bool give() override; bool take(uint32_t timeout_ms) override; @@ -18,4 +19,19 @@ class Semaphore : public AP_HAL::Semaphore { pthread_mutex_t _lock; }; + +class BinarySemaphore : public AP_HAL::BinarySemaphore { +public: + BinarySemaphore(bool initial_state=false); + + bool wait(uint32_t timeout_us) override; + bool wait_blocking(void) override; + void signal(void) override; + +protected: + Semaphore mtx; + pthread_cond_t cond; + bool pending; +}; + } From 8f8048e4cd08b1d635d25172612850eb6e16bae9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 30 Dec 2023 08:31:09 +1100 Subject: [PATCH 0281/1335] HAL_Linux: reimplement CAN with BinarySemaphore --- libraries/AP_HAL_Linux/CANSocketIface.cpp | 70 +++-------------------- libraries/AP_HAL_Linux/CANSocketIface.h | 15 +---- 2 files changed, 11 insertions(+), 74 deletions(-) diff --git a/libraries/AP_HAL_Linux/CANSocketIface.cpp b/libraries/AP_HAL_Linux/CANSocketIface.cpp index 03f3be88da8c59..05a02280ce9cec 100644 --- a/libraries/AP_HAL_Linux/CANSocketIface.cpp +++ b/libraries/AP_HAL_Linux/CANSocketIface.cpp @@ -51,8 +51,6 @@ using namespace Linux; #define Debug(fmt, args...) #endif -CANIface::CANSocketEventSource CANIface::evt_can_socket[HAL_NUM_CAN_IFACES]; - static can_frame makeSocketCanFrame(const AP_HAL::CANFrame& uavcan_frame) { can_frame sockcan_frame { uavcan_frame.id& AP_HAL::CANFrame::MaskExtID, uavcan_frame.dlc, { } }; @@ -193,6 +191,9 @@ int16_t CANIface::receive(AP_HAL::CANFrame& out_frame, uint64_t& out_timestamp_u out_flags = rx.flags; } (void)_rx_queue.pop(); + if (sem_handle != nullptr) { + sem_handle->signal(); + } return AP_HAL::CANIface::receive(out_frame, out_timestamp_us, out_flags); } @@ -507,8 +508,9 @@ bool CANIface::select(bool &read_select, bool &write_select, stats.num_tx_poll_req++; } } - if (_evt_handle != nullptr && blocking_deadline > AP_HAL::micros64()) { - _evt_handle->wait(blocking_deadline - AP_HAL::micros64()); + const uint64_t now_us = AP_HAL::micros64(); + if (sem_handle != nullptr && blocking_deadline > now_us) { + IGNORE_RETURN(sem_handle->wait(blocking_deadline - now_us)); } } @@ -528,67 +530,13 @@ bool CANIface::select(bool &read_select, bool &write_select, return true; } -bool CANIface::set_event_handle(AP_HAL::EventHandle* handle) { - _evt_handle = handle; - evt_can_socket[_self_index]._ifaces[_self_index] = this; - _evt_handle->set_source(&evt_can_socket[_self_index]); - return true; -} - - -bool CANIface::CANSocketEventSource::wait(uint16_t duration_us, AP_HAL::EventHandle* evt_handle) +bool CANIface::set_event_handle(AP_HAL::BinarySemaphore *handle) { - if (evt_handle == nullptr) { - return false; - } - pollfd pollfds[HAL_NUM_CAN_IFACES] {}; - uint8_t pollfd_iface_map[HAL_NUM_CAN_IFACES] {}; - unsigned long int num_pollfds = 0; - - // Poll FD set setup - for (unsigned i = 0; i < HAL_NUM_CAN_IFACES; i++) { - if (_ifaces[i] == nullptr) { - continue; - } - if (_ifaces[i]->_down) { - continue; - } - pollfds[num_pollfds] = _ifaces[i]->_pollfd; - pollfd_iface_map[num_pollfds] = i; - num_pollfds++; - _ifaces[i]->stats.num_poll_waits++; - } - - if (num_pollfds == 0) { - return true; - } - - // Timeout conversion - auto ts = timespec(); - ts.tv_sec = 0; - ts.tv_nsec = duration_us * 1000UL; - - // Blocking here - const int res = ppoll(pollfds, num_pollfds, &ts, nullptr); - - if (res < 0) { - return false; - } - - // Handling poll output - for (unsigned i = 0; i < num_pollfds; i++) { - if (_ifaces[pollfd_iface_map[i]] == nullptr) { - continue; - } - _ifaces[pollfd_iface_map[i]]->_updateDownStatusFromPollResult(pollfds[i]); - - const bool poll_read = pollfds[i].revents & POLLIN; - const bool poll_write = pollfds[i].revents & POLLOUT; - _ifaces[pollfd_iface_map[i]]->_poll(poll_read, poll_write); - } + sem_handle = handle; return true; } + void CANIface::get_stats(ExpandingString &str) { str.printf("tx_requests: %u\n" diff --git a/libraries/AP_HAL_Linux/CANSocketIface.h b/libraries/AP_HAL_Linux/CANSocketIface.h index a7e85f45753c6f..1e4d01a7b4666f 100644 --- a/libraries/AP_HAL_Linux/CANSocketIface.h +++ b/libraries/AP_HAL_Linux/CANSocketIface.h @@ -109,22 +109,12 @@ class CANIface: public AP_HAL::CANIface { uint64_t blocking_deadline) override; // setup event handle for waiting on events - bool set_event_handle(AP_HAL::EventHandle* handle) override; + bool set_event_handle(AP_HAL::BinarySemaphore *handle) override; // fetch stats text and return the size of the same, // results available via @SYS/can0_stats.txt or @SYS/can1_stats.txt void get_stats(ExpandingString &str) override; - class CANSocketEventSource : public AP_HAL::EventSource { - friend class CANIface; - CANIface *_ifaces[HAL_NUM_CAN_IFACES]; - - public: - // we just poll fd, no signaling is done - void signal(uint32_t evt_mask) override { return; } - bool wait(uint16_t duration_us, AP_HAL::EventHandle* evt_handle) override; - }; - private: void _pollWrite(); @@ -164,8 +154,7 @@ class CANIface: public AP_HAL::CANIface { const unsigned _max_frames_in_socket_tx_queue; unsigned _frames_in_socket_tx_queue; uint32_t _tx_frame_counter; - AP_HAL::EventHandle *_evt_handle; - static CANSocketEventSource evt_can_socket[HAL_NUM_CAN_IFACES]; + AP_HAL::BinarySemaphore *sem_handle; pollfd _pollfd; std::map _errors; From 5d1eb145cded21b848102fc3b45b58882fb5e9a7 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 30 Dec 2023 08:31:21 +1100 Subject: [PATCH 0282/1335] HAL_ESP32: implement BinarySemaphore --- libraries/AP_HAL_ESP32/HAL_ESP32_Namespace.h | 1 + libraries/AP_HAL_ESP32/Semaphores.cpp | 43 ++++++++++++++++++++ libraries/AP_HAL_ESP32/Semaphores.h | 19 +++++++++ 3 files changed, 63 insertions(+) diff --git a/libraries/AP_HAL_ESP32/HAL_ESP32_Namespace.h b/libraries/AP_HAL_ESP32/HAL_ESP32_Namespace.h index d59f080c0c7249..fbd28b5dc6259e 100644 --- a/libraries/AP_HAL_ESP32/HAL_ESP32_Namespace.h +++ b/libraries/AP_HAL_ESP32/HAL_ESP32_Namespace.h @@ -15,6 +15,7 @@ class RCInput; class Util; class Semaphore; class Semaphore_Recursive; +class BinarySemaphore; class GPIO; class DigitalSource; class Storage; diff --git a/libraries/AP_HAL_ESP32/Semaphores.cpp b/libraries/AP_HAL_ESP32/Semaphores.cpp index a397a53b183b88..d76ca820aeae18 100644 --- a/libraries/AP_HAL_ESP32/Semaphores.cpp +++ b/libraries/AP_HAL_ESP32/Semaphores.cpp @@ -73,3 +73,46 @@ bool Semaphore::check_owner() { return xSemaphoreGetMutexHolder((QueueHandle_t)handle) == xTaskGetCurrentTaskHandle(); } + + +/* + BinarySemaphore implementation + */ +BinarySemaphore::BinarySemaphore(bool initial_state) +{ + _sem = xSemaphoreCreateBinary(); + if (initial_state) { + xSemaphoreGive(_sem); + } +} + +bool BinarySemaphore::wait(uint32_t timeout_us) +{ + TickType_t ticks = pdMS_TO_TICKS(timeout_us / 1000U); + return xSemaphoreTake(_sem, ticks) == pdTRUE; +} + +bool BinarySemaphore::wait_blocking() +{ + return xSemaphoreTake(_sem, portMAX_DELAY) == pdTRUE; +} + +void BinarySemaphore::signal() +{ + xSemaphoreGive(_sem); +} + +void BinarySemaphore::signal_ISR() +{ + BaseType_t xHigherPriorityTaskWoken = pdFALSE; + xSemaphoreGiveFromISR(_sem, &xHigherPriorityTaskWoken); + portYIELD_FROM_ISR(xHigherPriorityTaskWoken); +} + +BinarySemaphore::~BinarySemaphore(void) +{ + if (_sem != nullptr) { + vSemaphoreDelete(_sem); + } + _sem = nullptr; +} diff --git a/libraries/AP_HAL_ESP32/Semaphores.h b/libraries/AP_HAL_ESP32/Semaphores.h index 844fd1b271d7b7..0a950f7a106208 100644 --- a/libraries/AP_HAL_ESP32/Semaphores.h +++ b/libraries/AP_HAL_ESP32/Semaphores.h @@ -20,6 +20,8 @@ #include #include #include "HAL_ESP32_Namespace.h" +#include +#include class ESP32::Semaphore : public AP_HAL::Semaphore { @@ -34,3 +36,20 @@ class ESP32::Semaphore : public AP_HAL::Semaphore protected: void* handle; }; + +class ESP32::BinarySemaphore : public AP_HAL::BinarySemaphore { +public: + BinarySemaphore(bool initial_state=false); + ~BinarySemaphore(void); + + CLASS_NO_COPY(BinarySemaphore); + + bool wait(uint32_t timeout_us) override; + bool wait_blocking(void) override; + void signal(void) override; + void signal_ISR(void) override; + +protected: + SemaphoreHandle_t _sem; +}; + From e22e07fbbd164e93c221f113bec4bd90bcec99f1 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 30 Dec 2023 08:32:20 +1100 Subject: [PATCH 0283/1335] AP_CANManager: reimplement with BinarySemaphore --- libraries/AP_CANManager/AP_CANSensor.cpp | 2 +- libraries/AP_CANManager/AP_CANSensor.h | 2 +- libraries/AP_CANManager/AP_SLCANIface.cpp | 4 ++-- libraries/AP_CANManager/AP_SLCANIface.h | 2 +- 4 files changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AP_CANManager/AP_CANSensor.cpp b/libraries/AP_CANManager/AP_CANSensor.cpp index 025dfd8036e2f8..8e300eba0921bb 100644 --- a/libraries/AP_CANManager/AP_CANSensor.cpp +++ b/libraries/AP_CANManager/AP_CANSensor.cpp @@ -127,7 +127,7 @@ bool CANSensor::add_interface(AP_HAL::CANIface* can_iface) return false; } - if (!_can_iface->set_event_handle(&_event_handle)) { + if (!_can_iface->set_event_handle(&sem_handle)) { debug_can(AP_CANManager::LOG_ERROR, "Cannot add event handle"); return false; } diff --git a/libraries/AP_CANManager/AP_CANSensor.h b/libraries/AP_CANManager/AP_CANSensor.h index e340b71facdd09..2cd775f4c39f78 100644 --- a/libraries/AP_CANManager/AP_CANSensor.h +++ b/libraries/AP_CANManager/AP_CANSensor.h @@ -77,7 +77,7 @@ class CANSensor : public AP_CANDriver { bool is_aux_11bit_driver; AP_CANDriver *_can_driver; - HAL_EventHandle _event_handle; + HAL_BinarySemaphore sem_handle; AP_HAL::CANIface* _can_iface; #ifdef HAL_BUILD_AP_PERIPH diff --git a/libraries/AP_CANManager/AP_SLCANIface.cpp b/libraries/AP_CANManager/AP_SLCANIface.cpp index dcd04dcff12f1a..496e8850ed2c1e 100644 --- a/libraries/AP_CANManager/AP_SLCANIface.cpp +++ b/libraries/AP_CANManager/AP_SLCANIface.cpp @@ -561,11 +561,11 @@ void SLCAN::CANIface::update_slcan_port() } } -bool SLCAN::CANIface::set_event_handle(AP_HAL::EventHandle* evt_handle) +bool SLCAN::CANIface::set_event_handle(AP_HAL::BinarySemaphore *sem_handle) { // When in passthrough mode methods is handled through can iface if (_can_iface) { - return _can_iface->set_event_handle(evt_handle); + return _can_iface->set_event_handle(sem_handle); } return false; } diff --git a/libraries/AP_CANManager/AP_SLCANIface.h b/libraries/AP_CANManager/AP_SLCANIface.h index 2f3f35382cdceb..a15ac4f5886c50 100644 --- a/libraries/AP_CANManager/AP_SLCANIface.h +++ b/libraries/AP_CANManager/AP_SLCANIface.h @@ -111,7 +111,7 @@ class CANIface: public AP_HAL::CANIface void reset_params(); // Overriden methods - bool set_event_handle(AP_HAL::EventHandle* evt_handle) override; + bool set_event_handle(AP_HAL::BinarySemaphore *sem_handle) override; uint16_t getNumFilters() const override; uint32_t getErrorCount() const override; void get_stats(ExpandingString &) override; From 036ae93cbbcb73675a03fb59b344d57cbb659f48 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 30 Dec 2023 08:32:31 +1100 Subject: [PATCH 0284/1335] AP_DroneCAN: reimplement with BinarySemaphore --- libraries/AP_DroneCAN/AP_Canard_iface.cpp | 7 +++---- libraries/AP_DroneCAN/AP_Canard_iface.h | 2 +- 2 files changed, 4 insertions(+), 5 deletions(-) diff --git a/libraries/AP_DroneCAN/AP_Canard_iface.cpp b/libraries/AP_DroneCAN/AP_Canard_iface.cpp index 86bedca40e680d..ebece8962676ac 100644 --- a/libraries/AP_DroneCAN/AP_Canard_iface.cpp +++ b/libraries/AP_DroneCAN/AP_Canard_iface.cpp @@ -406,10 +406,9 @@ void CanardInterface::process(uint32_t duration_ms) { WITH_SEMAPHORE(_sem_tx); canardCleanupStaleTransfers(&canard, AP_HAL::micros64()); } - uint64_t now = AP_HAL::micros64(); + const uint64_t now = AP_HAL::micros64(); if (now < deadline) { - _event_handle.wait(MIN(UINT16_MAX - 2U, deadline - now)); - hal.scheduler->delay_microseconds(50); + IGNORE_RETURN(sem_handle.wait(deadline - now)); } else { break; } @@ -436,7 +435,7 @@ bool CanardInterface::add_interface(AP_HAL::CANIface *can_iface) AP::can().log_text(AP_CANManager::LOG_ERROR, LOG_TAG, "DroneCANIfaceMgr: Can't alloc uavcan::iface\n"); return false; } - if (!can_iface->set_event_handle(&_event_handle)) { + if (!can_iface->set_event_handle(&sem_handle)) { AP::can().log_text(AP_CANManager::LOG_ERROR, LOG_TAG, "DroneCANIfaceMgr: Setting event handle failed\n"); return false; } diff --git a/libraries/AP_DroneCAN/AP_Canard_iface.h b/libraries/AP_DroneCAN/AP_Canard_iface.h index ce9b75ee923d79..43d786639fdf05 100644 --- a/libraries/AP_DroneCAN/AP_Canard_iface.h +++ b/libraries/AP_DroneCAN/AP_Canard_iface.h @@ -72,7 +72,7 @@ class CanardInterface : public Canard::Interface { static CanardInterface test_iface; #endif uint8_t num_ifaces; - HAL_EventHandle _event_handle; + HAL_BinarySemaphore sem_handle; bool initialized; HAL_Semaphore _sem_tx; HAL_Semaphore _sem_rx; From 7059f980b887913596293b095e370408ab8d0cbb Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 30 Dec 2023 08:33:21 +1100 Subject: [PATCH 0285/1335] HAL_SITL: implement BinarySemaphore --- libraries/AP_HAL_SITL/AP_HAL_SITL_Namespace.h | 1 + libraries/AP_HAL_SITL/Semaphores.cpp | 73 +++++++++++++++++++ libraries/AP_HAL_SITL/Semaphores.h | 18 +++++ 3 files changed, 92 insertions(+) diff --git a/libraries/AP_HAL_SITL/AP_HAL_SITL_Namespace.h b/libraries/AP_HAL_SITL/AP_HAL_SITL_Namespace.h index 5a360cbf591140..f5924ebd8de17f 100644 --- a/libraries/AP_HAL_SITL/AP_HAL_SITL_Namespace.h +++ b/libraries/AP_HAL_SITL/AP_HAL_SITL_Namespace.h @@ -15,6 +15,7 @@ class ADCSource; class RCInput; class Util; class Semaphore; +class BinarySemaphore; class GPIO; class DigitalSource; class DSP; diff --git a/libraries/AP_HAL_SITL/Semaphores.cpp b/libraries/AP_HAL_SITL/Semaphores.cpp index 216c1d98ee39df..0067fd9c148f18 100644 --- a/libraries/AP_HAL_SITL/Semaphores.cpp +++ b/libraries/AP_HAL_SITL/Semaphores.cpp @@ -76,4 +76,77 @@ bool Semaphore::take_nonblocking() return false; } + +/* + binary semaphore using pthread condition variables + */ + +BinarySemaphore::BinarySemaphore(bool initial_state) : + AP_HAL::BinarySemaphore(initial_state) +{ + pthread_cond_init(&cond, NULL); + pending = initial_state; +} + +bool BinarySemaphore::wait(uint32_t timeout_us) +{ + WITH_SEMAPHORE(mtx); + if (!pending) { + if (hal.scheduler->in_main_thread() || + Scheduler::from(hal.scheduler)->semaphore_wait_hack_required()) { + /* + when in the main thread we need to do a busy wait to ensure + the clock advances + */ + uint64_t end_us = AP_HAL::micros64() + timeout_us; + struct timespec ts {}; + do { + if (pthread_cond_timedwait(&cond, &mtx._lock, &ts) == 0) { + pending = false; + return true; + } + hal.scheduler->delay_microseconds(10); + } while (AP_HAL::micros64() < end_us); + return false; + } + + struct timespec ts; + if (clock_gettime(CLOCK_REALTIME, &ts) != 0) { + return false; + } + ts.tv_sec += timeout_us/1000000UL; + ts.tv_nsec += (timeout_us % 1000000U) * 1000UL; + if (ts.tv_nsec >= 1000000000L) { + ts.tv_sec++; + ts.tv_nsec -= 1000000000L; + } + if (pthread_cond_timedwait(&cond, &mtx._lock, &ts) != 0) { + return false; + } + } + pending = false; + return true; +} + +bool BinarySemaphore::wait_blocking(void) +{ + WITH_SEMAPHORE(mtx); + if (!pending) { + if (pthread_cond_wait(&cond, &mtx._lock) != 0) { + return false; + } + } + pending = false; + return true; +} + +void BinarySemaphore::signal(void) +{ + WITH_SEMAPHORE(mtx); + if (!pending) { + pending = true; + pthread_cond_signal(&cond); + } +} + #endif // CONFIG_HAL_BOARD diff --git a/libraries/AP_HAL_SITL/Semaphores.h b/libraries/AP_HAL_SITL/Semaphores.h index 63aa57f2f5b6f3..c88d76854f3d8d 100644 --- a/libraries/AP_HAL_SITL/Semaphores.h +++ b/libraries/AP_HAL_SITL/Semaphores.h @@ -9,6 +9,7 @@ class HALSITL::Semaphore : public AP_HAL::Semaphore { public: + friend class HALSITL::BinarySemaphore; Semaphore(); bool give() override; bool take(uint32_t timeout_ms) override; @@ -24,3 +25,20 @@ class HALSITL::Semaphore : public AP_HAL::Semaphore { // semaphore once we're done with it uint8_t take_count; }; + + +class HALSITL::BinarySemaphore : public AP_HAL::BinarySemaphore { +public: + BinarySemaphore(bool initial_state=false); + + CLASS_NO_COPY(BinarySemaphore); + + bool wait(uint32_t timeout_us) override; + bool wait_blocking(void) override; + void signal(void) override; + +private: + HALSITL::Semaphore mtx; + pthread_cond_t cond; + bool pending; +}; From f0aa2a65e466001d0725aaabd819c598790643b5 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 30 Dec 2023 08:33:48 +1100 Subject: [PATCH 0286/1335] HAL_SITL: reimplement CAN with BinarySemaphore --- libraries/AP_HAL_SITL/CANSocketIface.cpp | 74 ++++-------------------- libraries/AP_HAL_SITL/CANSocketIface.h | 15 +---- libraries/AP_HAL_SITL/CAN_Multicast.cpp | 4 ++ libraries/AP_HAL_SITL/CAN_Multicast.h | 1 + libraries/AP_HAL_SITL/CAN_SocketCAN.cpp | 4 ++ libraries/AP_HAL_SITL/CAN_Transport.h | 7 +++ libraries/AP_HAL_SITL/SITL_State.cpp | 8 ++- 7 files changed, 35 insertions(+), 78 deletions(-) diff --git a/libraries/AP_HAL_SITL/CANSocketIface.cpp b/libraries/AP_HAL_SITL/CANSocketIface.cpp index ad8b10f37b86cf..af8fc068759256 100644 --- a/libraries/AP_HAL_SITL/CANSocketIface.cpp +++ b/libraries/AP_HAL_SITL/CANSocketIface.cpp @@ -52,8 +52,6 @@ using namespace HALSITL; #define Debug(fmt, args...) #endif -CANIface::CANSocketEventSource CANIface::evt_can_socket[HAL_NUM_CAN_IFACES]; - uint8_t CANIface::_num_interfaces; bool CANIface::is_initialized() const @@ -233,6 +231,9 @@ bool CANIface::init(const uint32_t bitrate, const OperatingMode mode) transport = nullptr; return false; } + if (sem_handle != nullptr) { + transport->set_event_handle(sem_handle); + } return true; } @@ -256,8 +257,9 @@ bool CANIface::select(bool &read_select, bool &write_select, _pollfd.fd = transport->get_read_fd(); _pollfd.events |= POLLIN; } - if (_evt_handle != nullptr && blocking_deadline > AP_HAL::micros64()) { - _evt_handle->wait(blocking_deadline - AP_HAL::micros64()); + const uint64_t now_us = AP_HAL::micros64(); + if (sem_handle != nullptr && blocking_deadline > now_us) { + IGNORE_RETURN(sem_handle->wait(blocking_deadline - now_us)); } // Writing the output masks @@ -267,70 +269,16 @@ bool CANIface::select(bool &read_select, bool &write_select, return true; } -bool CANIface::set_event_handle(AP_HAL::EventHandle* handle) -{ - _evt_handle = handle; - evt_can_socket[_self_index]._ifaces[_self_index] = this; - _evt_handle->set_source(&evt_can_socket[_self_index]); - return true; -} - - -bool CANIface::CANSocketEventSource::wait(uint16_t duration_us, AP_HAL::EventHandle* evt_handle) +bool CANIface::set_event_handle(AP_HAL::BinarySemaphore *handle) { - if (evt_handle == nullptr) { - return false; - } - pollfd pollfds[HAL_NUM_CAN_IFACES] {}; - uint8_t pollfd_iface_map[HAL_NUM_CAN_IFACES] {}; - unsigned long int num_pollfds = 0; - - // Poll FD set setup - for (unsigned i = 0; i < HAL_NUM_CAN_IFACES; i++) { - if (_ifaces[i] == nullptr) { - continue; - } - pollfds[num_pollfds] = _ifaces[i]->_pollfd; - pollfd_iface_map[num_pollfds] = i; - num_pollfds++; - } - - if (num_pollfds == 0) { - return true; - } - - const uint32_t start_us = AP_HAL::micros(); - do { - uint16_t wait_us = MIN(100, duration_us); - - // check FD for input - const int res = poll(pollfds, num_pollfds, wait_us/1000U); - - if (res < 0) { - return false; - } - if (res > 0) { - break; - } - - // ensure simulator runs - hal.scheduler->delay_microseconds(wait_us); - } while (AP_HAL::micros() - start_us < duration_us); - - - // Handling poll output - for (unsigned i = 0; i < num_pollfds; i++) { - if (_ifaces[pollfd_iface_map[i]] == nullptr) { - continue; - } - - const bool poll_read = pollfds[i].revents & POLLIN; - const bool poll_write = pollfds[i].revents & POLLOUT; - _ifaces[pollfd_iface_map[i]]->_poll(poll_read, poll_write); + sem_handle = handle; + if (transport != nullptr) { + transport->set_event_handle(handle); } return true; } + void CANIface::get_stats(ExpandingString &str) { str.printf("tx_requests: %u\n" diff --git a/libraries/AP_HAL_SITL/CANSocketIface.h b/libraries/AP_HAL_SITL/CANSocketIface.h index c6f012a38d19da..5876217ecc4c4b 100644 --- a/libraries/AP_HAL_SITL/CANSocketIface.h +++ b/libraries/AP_HAL_SITL/CANSocketIface.h @@ -88,7 +88,7 @@ class CANIface: public AP_HAL::CANIface { uint64_t blocking_deadline) override; // setup event handle for waiting on events - bool set_event_handle(AP_HAL::EventHandle* handle) override; + bool set_event_handle(AP_HAL::BinarySemaphore *handle) override; // fetch stats text and return the size of the same, // results available via @SYS/can0_stats.txt or @SYS/can1_stats.txt @@ -101,16 +101,6 @@ class CANIface: public AP_HAL::CANIface { return &stats; } - class CANSocketEventSource : public AP_HAL::EventSource { - friend class CANIface; - CANIface *_ifaces[HAL_NUM_CAN_IFACES]; - - public: - // we just poll fd, no signaling is done - void signal(uint32_t evt_mask) override { return; } - bool wait(uint16_t duration_us, AP_HAL::EventHandle* evt_handle) override; - }; - private: void _pollWrite(); @@ -134,8 +124,7 @@ class CANIface: public AP_HAL::CANIface { unsigned _frames_in_socket_tx_queue; uint32_t _tx_frame_counter; - AP_HAL::EventHandle *_evt_handle; - static CANSocketEventSource evt_can_socket[HAL_NUM_CAN_IFACES]; + AP_HAL::BinarySemaphore *sem_handle; pollfd _pollfd; std::priority_queue _tx_queue; diff --git a/libraries/AP_HAL_SITL/CAN_Multicast.cpp b/libraries/AP_HAL_SITL/CAN_Multicast.cpp index fe843473241a37..8b7b7652167095 100644 --- a/libraries/AP_HAL_SITL/CAN_Multicast.cpp +++ b/libraries/AP_HAL_SITL/CAN_Multicast.cpp @@ -84,6 +84,10 @@ bool CAN_Multicast::receive(AP_HAL::CANFrame &frame) // run constructor to initialise new(&frame) AP_HAL::CANFrame(pkt.message_id, pkt.data, ret-10, (pkt.flags & MCAST_FLAG_CANFD) != 0); + if (sem_handle != nullptr) { + sem_handle->signal(); + } + return true; } diff --git a/libraries/AP_HAL_SITL/CAN_Multicast.h b/libraries/AP_HAL_SITL/CAN_Multicast.h index d3725458e3d4fc..07b39982a7640c 100644 --- a/libraries/AP_HAL_SITL/CAN_Multicast.h +++ b/libraries/AP_HAL_SITL/CAN_Multicast.h @@ -9,6 +9,7 @@ class CAN_Multicast : public CAN_Transport { public: + bool init(uint8_t instance) override; bool send(const AP_HAL::CANFrame &frame) override; bool receive(AP_HAL::CANFrame &frame) override; diff --git a/libraries/AP_HAL_SITL/CAN_SocketCAN.cpp b/libraries/AP_HAL_SITL/CAN_SocketCAN.cpp index 09df128ba374be..44c3447d8c8b9d 100644 --- a/libraries/AP_HAL_SITL/CAN_SocketCAN.cpp +++ b/libraries/AP_HAL_SITL/CAN_SocketCAN.cpp @@ -85,6 +85,10 @@ bool CAN_SocketCAN::receive(AP_HAL::CANFrame &frame) // run constructor to initialise new(&frame) AP_HAL::CANFrame(receive_frame.can_id, receive_frame.data, receive_frame.can_dlc, false); + + if (sem_handle != nullptr) { + sem_handle->signal(); + } return true; } diff --git a/libraries/AP_HAL_SITL/CAN_Transport.h b/libraries/AP_HAL_SITL/CAN_Transport.h index 52307c4c95799f..76346109e30e6b 100644 --- a/libraries/AP_HAL_SITL/CAN_Transport.h +++ b/libraries/AP_HAL_SITL/CAN_Transport.h @@ -16,6 +16,13 @@ class CAN_Transport { virtual bool send(const AP_HAL::CANFrame &frame) = 0; virtual bool receive(AP_HAL::CANFrame &frame) = 0; virtual int get_read_fd(void) const = 0; + + void set_event_handle(AP_HAL::BinarySemaphore *handle) { + sem_handle = handle; + } + +protected: + AP_HAL::BinarySemaphore *sem_handle; }; #endif // HAL_NUM_CAN_IFACES diff --git a/libraries/AP_HAL_SITL/SITL_State.cpp b/libraries/AP_HAL_SITL/SITL_State.cpp index 7bc5dab806afdc..19fce2e7e78402 100644 --- a/libraries/AP_HAL_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_State.cpp @@ -336,7 +336,9 @@ void SITL_State::_fdm_input_local(void) _check_rc_input(); // construct servos structure for FDM - _simulator_servos(input); + if (_sitl != nullptr) { + _simulator_servos(input); + } #if HAL_SIM_JSON_MASTER_ENABLED // read servo inputs from ride along flight controllers @@ -344,7 +346,9 @@ void SITL_State::_fdm_input_local(void) #endif // replace outputs from multicast - multicast_servo_update(input); + if (_sitl != nullptr) { + multicast_servo_update(input); + } // update the model sitl_model->update_home(); From 9c1e145c8fff1e27df24f84d734fc0fc6b623a0d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 30 Dec 2023 08:34:00 +1100 Subject: [PATCH 0287/1335] AP_PiccoloCAN: reimplement with BinarySemaphore --- libraries/AP_PiccoloCAN/AP_PiccoloCAN.cpp | 2 +- libraries/AP_PiccoloCAN/AP_PiccoloCAN.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_PiccoloCAN/AP_PiccoloCAN.cpp b/libraries/AP_PiccoloCAN/AP_PiccoloCAN.cpp index 1cd68ac08aa0a2..ef07781772cec2 100644 --- a/libraries/AP_PiccoloCAN/AP_PiccoloCAN.cpp +++ b/libraries/AP_PiccoloCAN/AP_PiccoloCAN.cpp @@ -140,7 +140,7 @@ bool AP_PiccoloCAN::add_interface(AP_HAL::CANIface* can_iface) { return false; } - if (!_can_iface->set_event_handle(&_event_handle)) { + if (!_can_iface->set_event_handle(&sem_handle)) { debug_can(AP_CANManager::LOG_ERROR, "PiccoloCAN: Cannot add event handle\n\r"); return false; } diff --git a/libraries/AP_PiccoloCAN/AP_PiccoloCAN.h b/libraries/AP_PiccoloCAN/AP_PiccoloCAN.h index 906cb772d09b6b..770f05dcf53bf6 100644 --- a/libraries/AP_PiccoloCAN/AP_PiccoloCAN.h +++ b/libraries/AP_PiccoloCAN/AP_PiccoloCAN.h @@ -114,7 +114,7 @@ class AP_PiccoloCAN : public AP_CANDriver, public AP_ESC_Telem_Backend char _thread_name[16]; uint8_t _driver_index; AP_HAL::CANIface* _can_iface; - HAL_EventHandle _event_handle; + HAL_BinarySemaphore sem_handle; AP_PiccoloCAN_Servo _servos[PICCOLO_CAN_MAX_NUM_SERVO]; AP_PiccoloCAN_ESC _escs[PICCOLO_CAN_MAX_NUM_ESC]; From 635c764c6fccb16334ad0075b5a23b96c1b94bda Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 30 Dec 2023 08:56:24 +1100 Subject: [PATCH 0288/1335] AP_HAL: added BinarySemaphore test --- .../AP_HAL/examples/BinarySem/BinarySem.cpp | 91 +++++++++++++++++++ libraries/AP_HAL/examples/BinarySem/wscript | 7 ++ 2 files changed, 98 insertions(+) create mode 100644 libraries/AP_HAL/examples/BinarySem/BinarySem.cpp create mode 100644 libraries/AP_HAL/examples/BinarySem/wscript diff --git a/libraries/AP_HAL/examples/BinarySem/BinarySem.cpp b/libraries/AP_HAL/examples/BinarySem/BinarySem.cpp new file mode 100644 index 00000000000000..885933ded9fa9d --- /dev/null +++ b/libraries/AP_HAL/examples/BinarySem/BinarySem.cpp @@ -0,0 +1,91 @@ +/* + test of HAL_BinarySemaphore + */ + +#include +#include + +#include + +void setup(); +void loop(); + +const AP_HAL::HAL& hal = AP_HAL::get_HAL(); + +class BinarySemTest { +public: + HAL_BinarySemaphore sem1{1}; + HAL_BinarySemaphore sem2{0}; + + void setup(void); + void thread1(void); + void thread2(void); + void update(bool ok); + + uint32_t ops, timeouts; + uint32_t last_print_us; + HAL_Semaphore mtx; +}; + +void BinarySemTest::setup(void) +{ + hal.scheduler->thread_create( + FUNCTOR_BIND_MEMBER(&BinarySemTest::thread1, void), "thd1", 2048, AP_HAL::Scheduler::PRIORITY_IO, 0); + hal.scheduler->thread_create( + FUNCTOR_BIND_MEMBER(&BinarySemTest::thread2, void), "thd2", 2048, AP_HAL::Scheduler::PRIORITY_IO, 0); + ::printf("Setup threads\n"); +} + +void BinarySemTest::thread2(void) +{ + while (true) { + bool ok = sem2.wait(50000); + sem1.signal(); + update(ok); + } +} + +void BinarySemTest::thread1(void) +{ + while (true) { + bool ok = sem1.wait(50000); + sem2.signal(); + update(ok); + } +} + +void BinarySemTest::update(bool ok) +{ + WITH_SEMAPHORE(mtx); + if (ok) { + ops++; + } else { + timeouts++; + } + uint32_t now_us = AP_HAL::micros(); + float dt = (now_us - last_print_us)*1.0e-6; + if (dt >= 1.0) { + last_print_us = now_us; + ::printf("tick %u %.3f ops/s %.3f timeouts/s\n", + unsigned(AP_HAL::millis()), + ops/dt, + timeouts/dt); + ops = 0; + timeouts = 0; + } +} + +static BinarySemTest *ct; + +void setup(void) +{ + ct = new BinarySemTest; + ct->setup(); +} + +void loop(void) +{ + hal.scheduler->delay(1000); +} + +AP_HAL_MAIN(); diff --git a/libraries/AP_HAL/examples/BinarySem/wscript b/libraries/AP_HAL/examples/BinarySem/wscript new file mode 100644 index 00000000000000..719ec151ba9d4b --- /dev/null +++ b/libraries/AP_HAL/examples/BinarySem/wscript @@ -0,0 +1,7 @@ +#!/usr/bin/env python +# encoding: utf-8 + +def build(bld): + bld.ap_example( + use='ap', + ) From 3bd8f1a3dfb5b548d62ec760e4158f30a7a7df4d Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 4 Sep 2023 17:01:18 +1000 Subject: [PATCH 0289/1335] AP_Periph: rename rx-protocol-stats ins local to avoid conflict with ins singleton --- Tools/AP_Periph/can.cpp | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/Tools/AP_Periph/can.cpp b/Tools/AP_Periph/can.cpp index 4cb0d495ed90c3..dc3aa334ed0c5e 100644 --- a/Tools/AP_Periph/can.cpp +++ b/Tools/AP_Periph/can.cpp @@ -1225,19 +1225,19 @@ void AP_Periph_FW::update_rx_protocol_stats(int16_t res) void AP_Periph_FW::processRx(void) { AP_HAL::CANFrame rxmsg; - for (auto &ins : instances) { - if (ins.iface == NULL) { + for (auto &instance : instances) { + if (instance.iface == NULL) { continue; } #if HAL_NUM_CAN_IFACES >= 2 - if (can_protocol_cached[ins.index] != AP_CAN::Protocol::DroneCAN) { + if (can_protocol_cached[instance.index] != AP_CAN::Protocol::DroneCAN) { continue; } #endif while (true) { bool read_select = true; bool write_select = false; - ins.iface->select(read_select, write_select, nullptr, 0); + instance.iface->select(read_select, write_select, nullptr, 0); if (!read_select) { // No data pending break; } @@ -1246,7 +1246,7 @@ void AP_Periph_FW::processRx(void) //palToggleLine(HAL_GPIO_PIN_LED); uint64_t timestamp; AP_HAL::CANIface::CanIOFlags flags; - if (ins.iface->receive(rxmsg, timestamp, flags) <= 0) { + if (instance.iface->receive(rxmsg, timestamp, flags) <= 0) { break; } #if HAL_PERIPH_CAN_MIRROR @@ -1267,7 +1267,7 @@ void AP_Periph_FW::processRx(void) #endif rx_frame.id = rxmsg.id; #if CANARD_MULTI_IFACE - rx_frame.iface_id = ins.index; + rx_frame.iface_id = instance.index; #endif const int16_t res = canardHandleRxFrame(&dronecan.canard, &rx_frame, timestamp); @@ -1362,14 +1362,14 @@ void AP_Periph_FW::node_status_send(void) buffer, len); } - for (auto &ins : instances) { + for (auto &instance : instances) { uint8_t buffer[DRONECAN_PROTOCOL_CANSTATS_MAX_SIZE]; dronecan_protocol_CanStats can_stats; - const AP_HAL::CANIface::bus_stats_t *bus_stats = ins.iface->get_statistics(); + const AP_HAL::CANIface::bus_stats_t *bus_stats = instance.iface->get_statistics(); if (bus_stats == nullptr) { return; } - can_stats.interface = ins.index; + can_stats.interface = instance.index; can_stats.tx_requests = bus_stats->tx_requests; can_stats.tx_rejected = bus_stats->tx_rejected; can_stats.tx_overflow = bus_stats->tx_overflow; From f83b56156653ae79f9551a74da53aa2b5faca462 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 14 Sep 2023 21:05:58 +1000 Subject: [PATCH 0290/1335] AP_HAL_SITL: guard against DSP being compiled out of code --- libraries/AP_HAL_SITL/DSP.cpp | 4 ++++ libraries/AP_HAL_SITL/DSP.h | 5 +++++ libraries/AP_HAL_SITL/HAL_SITL_Class.cpp | 4 ++++ 3 files changed, 13 insertions(+) diff --git a/libraries/AP_HAL_SITL/DSP.cpp b/libraries/AP_HAL_SITL/DSP.cpp index c67223bfe7ec4b..2bb4d8131ad34a 100644 --- a/libraries/AP_HAL_SITL/DSP.cpp +++ b/libraries/AP_HAL_SITL/DSP.cpp @@ -17,6 +17,8 @@ #include +#if HAL_WITH_DSP + #include "AP_HAL_SITL.h" #include #include @@ -209,3 +211,5 @@ void DSP::calculate_fft(complexf *samples, uint16_t fftlen) istep <<= 1; } } + +#endif diff --git a/libraries/AP_HAL_SITL/DSP.h b/libraries/AP_HAL_SITL/DSP.h index 9813fe4bfe5fb2..c8acab8ed416d5 100644 --- a/libraries/AP_HAL_SITL/DSP.h +++ b/libraries/AP_HAL_SITL/DSP.h @@ -17,6 +17,9 @@ #pragma once #include + +#if HAL_WITH_DSP + #include "AP_HAL_SITL.h" #include @@ -55,3 +58,5 @@ class HALSITL::DSP : public AP_HAL::DSP { void vector_add_float(const float* vin1, const float* vin2, float* vout, uint16_t len) const override; void calculate_fft(complexf* f, uint16_t length); }; + +#endif diff --git a/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp b/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp index 0d79624ee6bcf3..88b19026f7785a 100644 --- a/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp +++ b/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp @@ -46,7 +46,9 @@ static Empty::RCInput sitlRCInput; static RCOutput sitlRCOutput(&sitlState); static GPIO sitlGPIO(&sitlState); static AnalogIn sitlAnalogIn(&sitlState); +#if HAL_WITH_DSP static DSP dspDriver; +#endif // use the Empty HAL for hardware we don't emulate @@ -104,7 +106,9 @@ HAL_SITL::HAL_SITL() : &utilInstance, /* util */ &emptyOpticalFlow, /* onboard optical flow */ &emptyFlash, /* flash driver */ +#if HAL_WITH_DSP &dspDriver, /* dsp driver */ +#endif #if HAL_NUM_CAN_IFACES (AP_HAL::CANIface**)canDrivers #else From 9e5edefc4a86aa77d920f765af5ce2fd2da60bf3 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 14 Sep 2023 21:21:37 +1000 Subject: [PATCH 0291/1335] AP_HAL: guard against DSP being compiled out of code --- libraries/AP_HAL/HAL.h | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL/HAL.h b/libraries/AP_HAL/HAL.h index fdaee2c43357b8..cb71ca5ec833f3 100644 --- a/libraries/AP_HAL/HAL.h +++ b/libraries/AP_HAL/HAL.h @@ -46,7 +46,9 @@ class AP_HAL::HAL { #if AP_SIM_ENABLED && CONFIG_HAL_BOARD != HAL_BOARD_SITL class AP_HAL::SIMState* _simstate, #endif +#if HAL_WITH_DSP AP_HAL::DSP* _dsp, +#endif #if HAL_NUM_CAN_IFACES > 0 AP_HAL::CANIface* _can_ifaces[HAL_NUM_CAN_IFACES]) #else @@ -76,11 +78,13 @@ class AP_HAL::HAL { scheduler(_scheduler), util(_util), opticalflow(_opticalflow), - flash(_flash), +#if HAL_WITH_DSP + dsp(_dsp), +#endif #if AP_SIM_ENABLED && CONFIG_HAL_BOARD != HAL_BOARD_SITL simstate(_simstate), #endif - dsp(_dsp) + flash(_flash) { #if HAL_NUM_CAN_IFACES > 0 if (_can_ifaces == nullptr) { From d5ddbad27f0c606571d54427a5f1cab04b05aa85 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 1 Oct 2023 08:17:34 +1100 Subject: [PATCH 0292/1335] HAL_ChibiOS_Class: adjust for dsp disappearing from HAL constructor --- libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp b/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp index 65ebdfafdaace5..2355fe4be5815e 100644 --- a/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp +++ b/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp @@ -110,8 +110,6 @@ static AP_HAL::SIMState xsimstate; #if HAL_WITH_DSP static ChibiOS::DSP dspDriver; -#else -static Empty::DSP dspDriver; #endif #ifndef HAL_NO_FLASH_SUPPORT @@ -166,7 +164,9 @@ HAL_ChibiOS::HAL_ChibiOS() : #if AP_SIM_ENABLED &xsimstate, #endif +#if HAL_WITH_DSP &dspDriver, +#endif #if HAL_NUM_CAN_IFACES (AP_HAL::CANIface**)canDrivers #else From 75ebef32cf66027cf5b4dd1815683d7a0a2bb221 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 2 Jan 2024 12:49:00 +1100 Subject: [PATCH 0293/1335] AP_HAL_ESP32: cope with HAL_WITH_DSP being false --- libraries/AP_HAL_ESP32/HAL_ESP32_Class.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_HAL_ESP32/HAL_ESP32_Class.cpp b/libraries/AP_HAL_ESP32/HAL_ESP32_Class.cpp index bedff42e98b7de..d4057a9af3422d 100644 --- a/libraries/AP_HAL_ESP32/HAL_ESP32_Class.cpp +++ b/libraries/AP_HAL_ESP32/HAL_ESP32_Class.cpp @@ -49,7 +49,9 @@ static Empty::UARTDriver serial7Driver; static Empty::UARTDriver serial8Driver; static Empty::UARTDriver serial9Driver; +#if HAL_WITH_DSP static Empty::DSP dspDriver; +#endif static ESP32::I2CDeviceManager i2cDeviceManager; static ESP32::SPIDeviceManager spiDeviceManager; @@ -94,7 +96,9 @@ HAL_ESP32::HAL_ESP32() : &utilInstance, &opticalFlowDriver, &flashDriver, +#if HAL_WITH_DSP &dspDriver, +#endif nullptr ) {} From 7e51811a24362f34e72f39552122f4254acc0593 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 2 Jan 2024 12:49:00 +1100 Subject: [PATCH 0294/1335] AP_HAL_Linux: cope with HAL_WITH_DSP being false --- libraries/AP_HAL_Linux/HAL_Linux_Class.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp b/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp index d89296b6a0feca..4b2cd90e28fa68 100644 --- a/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp +++ b/libraries/AP_HAL_Linux/HAL_Linux_Class.cpp @@ -251,7 +251,9 @@ static OpticalFlow_Onboard opticalFlow; static Empty::OpticalFlow opticalFlow; #endif +#if HAL_WITH_DSP static Empty::DSP dspDriver; +#endif static Empty::Flash flashDriver; static Empty::WSPIDeviceManager wspi_mgr_instance; @@ -284,7 +286,9 @@ HAL_Linux::HAL_Linux() : &utilInstance, &opticalFlow, &flashDriver, +#if HAL_WITH_DSP &dspDriver, +#endif #if HAL_NUM_CAN_IFACES (AP_HAL::CANIface**)canDrivers #else From f8fcc9610345d43501dc79eebf811ba3d0a1adcf Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 2 Jan 2024 09:59:57 +1100 Subject: [PATCH 0295/1335] Tools: don't check all files if no files-to-check supplied --- Tools/scripts/run_flake8.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Tools/scripts/run_flake8.py b/Tools/scripts/run_flake8.py index acfde4e4e52f63..22df522e00199d 100755 --- a/Tools/scripts/run_flake8.py +++ b/Tools/scripts/run_flake8.py @@ -25,6 +25,8 @@ def progress(self, string): print("****** %s" % (string,)) def check(self): + if len(self.files_to_check) == 0: + return for path in self.files_to_check: self.progress("Checking (%s)" % path) ret = subprocess.run(["flake8", "--show-source"] + self.files_to_check, From a5fee135b0dcca4242ea2646427b8b18fc03166d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 10 Dec 2023 07:10:41 +1100 Subject: [PATCH 0296/1335] waf: added paths for PPP build --- Tools/ardupilotwaf/chibios.py | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/ardupilotwaf/chibios.py b/Tools/ardupilotwaf/chibios.py index dbc6c9b18779e8..c31479c270c904 100644 --- a/Tools/ardupilotwaf/chibios.py +++ b/Tools/ardupilotwaf/chibios.py @@ -692,6 +692,7 @@ def build(bld): common_src += bld.path.ant_glob('modules/ChibiOS/os/hal/**/*.[ch]') common_src += bld.path.ant_glob('modules/ChibiOS/os/hal/**/*.mk') common_src += bld.path.ant_glob('modules/ChibiOS/ext/lwip/src/**/*.[ch]') + common_src += bld.path.ant_glob('modules/ChibiOS/ext/lwip/src/netif/**/*.[ch]') common_src += bld.path.ant_glob('modules/ChibiOS/ext/lwip/src/core/**/*.[ch]') if bld.env.ROMFS_FILES: common_src += [bld.bldnode.find_or_declare('ap_romfs_embedded.h')] From 2cb177ef7260d5877bbe6c79c8112c677a076c3b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 10 Dec 2023 07:11:24 +1100 Subject: [PATCH 0297/1335] AP_SerialManager: added PPP serial type --- libraries/AP_SerialManager/AP_SerialManager.cpp | 9 ++++++++- libraries/AP_SerialManager/AP_SerialManager.h | 1 + libraries/AP_SerialManager/AP_SerialManager_config.h | 5 +++++ 3 files changed, 14 insertions(+), 1 deletion(-) diff --git a/libraries/AP_SerialManager/AP_SerialManager.cpp b/libraries/AP_SerialManager/AP_SerialManager.cpp index 24a694e2d074b4..3d2ed06f5a061d 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.cpp +++ b/libraries/AP_SerialManager/AP_SerialManager.cpp @@ -580,7 +580,14 @@ void AP_SerialManager::init() uart->set_unbuffered_writes(true); break; #endif - +#if AP_NETWORKING_BACKEND_PPP + case SerialProtocol_PPP: + uart->begin(state[i].baudrate(), + AP_SERIALMANAGER_PPP_BUFSIZE_RX, + AP_SERIALMANAGER_PPP_BUFSIZE_TX); + break; +#endif + default: uart->begin(state[i].baudrate()); } diff --git a/libraries/AP_SerialManager/AP_SerialManager.h b/libraries/AP_SerialManager/AP_SerialManager.h index 30bae549f6b879..d569d1f066d43a 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.h +++ b/libraries/AP_SerialManager/AP_SerialManager.h @@ -81,6 +81,7 @@ class AP_SerialManager { SerialProtocol_DDS_XRCE = 45, SerialProtocol_IMUOUT = 46, // Reserving Serial Protocol 47 for SerialProtocol_IQ + SerialProtocol_PPP = 48, SerialProtocol_NumProtocols // must be the last value }; diff --git a/libraries/AP_SerialManager/AP_SerialManager_config.h b/libraries/AP_SerialManager/AP_SerialManager_config.h index 88bf3ccaa3c7db..a09a2995a09f2e 100644 --- a/libraries/AP_SerialManager/AP_SerialManager_config.h +++ b/libraries/AP_SerialManager/AP_SerialManager_config.h @@ -137,6 +137,11 @@ #define AP_SERIALMANAGER_IMUOUT_BUFSIZE_RX 128 #define AP_SERIALMANAGER_IMUOUT_BUFSIZE_TX 2048 +// PPP protocol +#define AP_SERIALMANAGER_PPP_BAUD 921600 +#define AP_SERIALMANAGER_PPP_BUFSIZE_RX 4096 +#define AP_SERIALMANAGER_PPP_BUFSIZE_TX 4096 + #ifndef HAL_HAVE_SERIAL0 #define HAL_HAVE_SERIAL0 HAL_NUM_SERIAL_PORTS > 0 #endif From 1627f7f61aa842542b4ab97370e6ccc57b0998dc Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 10 Dec 2023 07:11:35 +1100 Subject: [PATCH 0298/1335] AP_OSD: added PPP --- libraries/AP_OSD/AP_OSD_ParamSetting.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_OSD/AP_OSD_ParamSetting.cpp b/libraries/AP_OSD/AP_OSD_ParamSetting.cpp index 6c3d7723a67b92..9efdef9b3659a9 100644 --- a/libraries/AP_OSD/AP_OSD_ParamSetting.cpp +++ b/libraries/AP_OSD/AP_OSD_ParamSetting.cpp @@ -117,7 +117,7 @@ static const char* SERIAL_PROTOCOL_VALUES[] = { "FSKY_TX", "LID360", "", "BEACN", "VOLZ", "SBUS", "ESC_TLM", "DEV_TLM", "OPTFLW", "RBTSRV", "NMEA", "WNDVNE", "SLCAN", "RCIN", "MGSQRT", "LTM", "RUNCAM", "HOT_TLM", "SCRIPT", "CRSF", "GEN", "WNCH", "MSP", "DJI", "AIRSPD", "ADSB", "AHRS", "AUDIO", "FETTEC", "TORQ", - "AIS", "CD_ESC", "MSP_DP", "MAV_HL", "TRAMP", "DDS", "IMUOUT", + "AIS", "CD_ESC", "MSP_DP", "MAV_HL", "TRAMP", "DDS", "IMUOUT", "IQ", "PPP", }; static_assert(AP_SerialManager::SerialProtocol_NumProtocols == ARRAY_SIZE(SERIAL_PROTOCOL_VALUES), "Wrong size SerialProtocol_NumProtocols"); From e2dac53fca8e58419e6c0746d222e671c3cf1d2f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 9 Dec 2023 20:23:15 +1100 Subject: [PATCH 0299/1335] AP_Networking: added SLIP support --- libraries/AP_Networking/AP_Networking.cpp | 24 ++++- .../AP_Networking/AP_Networking_Backend.h | 2 +- .../AP_Networking/AP_Networking_Config.h | 5 + libraries/AP_Networking/AP_Networking_SITL.h | 1 - .../AP_Networking/AP_Networking_SLIP.cpp | 99 +++++++++++++++++++ libraries/AP_Networking/AP_Networking_SLIP.h | 27 +++++ 6 files changed, 152 insertions(+), 6 deletions(-) create mode 100644 libraries/AP_Networking/AP_Networking_SLIP.cpp create mode 100644 libraries/AP_Networking/AP_Networking_SLIP.h diff --git a/libraries/AP_Networking/AP_Networking.cpp b/libraries/AP_Networking/AP_Networking.cpp index 95856166fd17f5..c4cca2e6bd60d1 100644 --- a/libraries/AP_Networking/AP_Networking.cpp +++ b/libraries/AP_Networking/AP_Networking.cpp @@ -14,6 +14,7 @@ extern const AP_HAL::HAL& hal; #if AP_NETWORKING_BACKEND_CHIBIOS #include "AP_Networking_ChibiOS.h" +#include "AP_Networking_SLIP.h" #include #include #else @@ -22,6 +23,10 @@ extern const AP_HAL::HAL& hal; #include +#if AP_NETWORKING_BACKEND_SLIP +#include "AP_Networking_SLIP.h" +#endif + #if AP_NETWORKING_BACKEND_SITL #include "AP_Networking_SITL.h" #endif @@ -124,11 +129,21 @@ void AP_Networking::init() } #endif +#if AP_NETWORKING_BACKEND_SLIP + if (AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_SLIP, 0)) { + backend = new AP_Networking_SLIP(*this); + } +#endif + #if AP_NETWORKING_BACKEND_CHIBIOS - backend = new AP_Networking_ChibiOS(*this); + if (backend == nullptr) { + backend = new AP_Networking_ChibiOS(*this); + } #endif #if AP_NETWORKING_BACKEND_SITL - backend = new AP_Networking_SITL(*this); + if (backend == nullptr) { + backend = new AP_Networking_SITL(*this); + } #endif if (backend == nullptr) { @@ -374,15 +389,16 @@ AP_Networking &network() */ int ap_networking_printf(const char *fmt, ...) { -#ifdef AP_NETWORKING_LWIP_DEBUG_PORT +#if AP_NETWORKING_LWIP_DEBUG_PORT >= 0 static AP_HAL::UARTDriver *uart; if (uart == nullptr) { uart = hal.serial(AP_NETWORKING_LWIP_DEBUG_PORT); if (uart == nullptr) { return -1; } - uart->begin(921600, 0, 50000); + uart->begin(AP_NETWORKING_LWIP_DEBUG_BAUD, 1000, 50000); } + uart->begin(0); va_list ap; va_start(ap, fmt); uart->vprintf(fmt, ap); diff --git a/libraries/AP_Networking/AP_Networking_Backend.h b/libraries/AP_Networking/AP_Networking_Backend.h index 9233442c44da67..7fe0d21322802d 100644 --- a/libraries/AP_Networking/AP_Networking_Backend.h +++ b/libraries/AP_Networking/AP_Networking_Backend.h @@ -19,7 +19,7 @@ class AP_Networking_Backend CLASS_NO_COPY(AP_Networking_Backend); virtual bool init() = 0; - virtual void update() = 0; + virtual void update() {}; protected: AP_Networking &frontend; diff --git a/libraries/AP_Networking/AP_Networking_Config.h b/libraries/AP_Networking/AP_Networking_Config.h index 00ba6d50c1e60e..bbdbf5b37b729b 100644 --- a/libraries/AP_Networking/AP_Networking_Config.h +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -22,6 +22,11 @@ // --------------------------- #ifndef AP_NETWORKING_BACKEND_CHIBIOS #define AP_NETWORKING_BACKEND_CHIBIOS (AP_NETWORKING_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS)) +#define AP_NETWORKING_BACKEND_SLIP (AP_NETWORKING_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS)) +#endif + +#ifndef AP_NETWORKING_BACKEND_SLIP +#define AP_NETWORKING_BACKEND_SLIP (AP_NETWORKING_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS)) #endif #ifndef AP_NETWORKING_BACKEND_SITL diff --git a/libraries/AP_Networking/AP_Networking_SITL.h b/libraries/AP_Networking/AP_Networking_SITL.h index 915e43f5f73413..d4e9a8c65be536 100644 --- a/libraries/AP_Networking/AP_Networking_SITL.h +++ b/libraries/AP_Networking/AP_Networking_SITL.h @@ -16,7 +16,6 @@ class AP_Networking_SITL : public AP_Networking_Backend bool init() override { return true; } - void update() override {} }; #endif // AP_NETWORKING_BACKEND_SITL diff --git a/libraries/AP_Networking/AP_Networking_SLIP.cpp b/libraries/AP_Networking/AP_Networking_SLIP.cpp new file mode 100644 index 00000000000000..088bd024c810ae --- /dev/null +++ b/libraries/AP_Networking/AP_Networking_SLIP.cpp @@ -0,0 +1,99 @@ + +#include "AP_Networking_Config.h" + +#if AP_NETWORKING_BACKEND_SLIP + +#include "AP_Networking_SLIP.h" +#include + +#include +#include +#include +#include +#include + +#include + +extern const AP_HAL::HAL& hal; +AP_HAL::UARTDriver *AP_Networking_SLIP::uart; + +/* + initialise SLIP network backend using LWIP + */ +bool AP_Networking_SLIP::init() +{ + uart = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_SLIP, 0); + if (uart == nullptr) { + return false; + } + uart->set_unbuffered_writes(true); + + slipif = new netif; + if (slipif == nullptr) { + return false; + } + + // no dynamic IPs for SLIP + activeSettings.ip = frontend.get_ip_param(); + activeSettings.gw = frontend.get_gateway_param(); + activeSettings.nm = frontend.get_netmask_param(); + activeSettings.last_change_ms = AP_HAL::millis(); + + const ip4_addr_t ipaddr {htonl(activeSettings.ip)}; + const ip4_addr_t netmask {htonl(activeSettings.nm)}; + const ip4_addr_t gw {htonl(activeSettings.gw)}; + + tcpip_init(NULL, NULL); + hal.scheduler->delay(100); + + netif_add(slipif, + &ipaddr, &netmask, &gw, + &num_slip, slipif_init, ip_input); + netif_set_default(slipif); + slipif->mtu = 296; + netif_set_link_up(slipif); + netif_set_up(slipif); + + hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking_SLIP::slip_loop, void), + "slip", + 8192, AP_HAL::Scheduler::PRIORITY_UART, -1); + + return true; +} + +/* + main loop for SLIP + */ +void AP_Networking_SLIP::slip_loop(void) +{ + uart->begin(0); + hal.scheduler->delay(100); + while (true) { + slipif_poll(slipif); + hal.scheduler->delay_microseconds(100); + } +} + +void sio_send(uint8_t c, void *fd) +{ + auto *uart = (AP_HAL::UARTDriver *)fd; + uart->write(c); +} + +sio_fd_t sio_open(uint8_t dev) +{ + return AP_Networking_SLIP::uart; +} + +u32_t sio_tryread(sio_fd_t fd, u8_t *data, u32_t len) +{ + auto *uart = (AP_HAL::UARTDriver *)fd; + uart->begin(0); + const auto ret = uart->read(data, len); + if (ret <= 0) { + return 0; + } + return ret; +} + +#endif // AP_NETWORKING_BACKEND_SLIP diff --git a/libraries/AP_Networking/AP_Networking_SLIP.h b/libraries/AP_Networking/AP_Networking_SLIP.h new file mode 100644 index 00000000000000..a6c61d4f32ff01 --- /dev/null +++ b/libraries/AP_Networking/AP_Networking_SLIP.h @@ -0,0 +1,27 @@ +#pragma once + +#include "AP_Networking_Config.h" + +#ifdef AP_NETWORKING_BACKEND_SLIP +#include "AP_Networking_Backend.h" + +class AP_Networking_SLIP : public AP_Networking_Backend +{ +public: + using AP_Networking_Backend::AP_Networking_Backend; + + /* Do not allow copies */ + CLASS_NO_COPY(AP_Networking_SLIP); + + bool init() override; + + static AP_HAL::UARTDriver *uart; + +private: + void slip_loop(void); + + struct netif *slipif; + uint8_t num_slip; +}; + +#endif // AP_NETWORKING_BACKEND_SLIP From 896b95654cbf58211f1d77be8cd3c3f6b9cb2d78 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 10 Dec 2023 07:10:16 +1100 Subject: [PATCH 0300/1335] AP_Networking: added PPP support --- libraries/AP_Networking/AP_Networking.cpp | 13 +- .../AP_Networking/AP_Networking_Config.h | 5 +- libraries/AP_Networking/AP_Networking_PPP.cpp | 181 ++++++++++++++++++ libraries/AP_Networking/AP_Networking_PPP.h | 29 +++ 4 files changed, 226 insertions(+), 2 deletions(-) create mode 100644 libraries/AP_Networking/AP_Networking_PPP.cpp create mode 100644 libraries/AP_Networking/AP_Networking_PPP.h diff --git a/libraries/AP_Networking/AP_Networking.cpp b/libraries/AP_Networking/AP_Networking.cpp index c4cca2e6bd60d1..66786f92fa23a2 100644 --- a/libraries/AP_Networking/AP_Networking.cpp +++ b/libraries/AP_Networking/AP_Networking.cpp @@ -15,6 +15,7 @@ extern const AP_HAL::HAL& hal; #if AP_NETWORKING_BACKEND_CHIBIOS #include "AP_Networking_ChibiOS.h" #include "AP_Networking_SLIP.h" +#include "AP_Networking_PPP.h" #include #include #else @@ -27,6 +28,10 @@ extern const AP_HAL::HAL& hal; #include "AP_Networking_SLIP.h" #endif +#if AP_NETWORKING_BACKEND_PPP +#include "AP_Networking_PPP.h" +#endif + #if AP_NETWORKING_BACKEND_SITL #include "AP_Networking_SITL.h" #endif @@ -129,8 +134,14 @@ void AP_Networking::init() } #endif +#if AP_NETWORKING_BACKEND_PPP + if (AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_PPP, 0)) { + backend = new AP_Networking_PPP(*this); + } +#endif + #if AP_NETWORKING_BACKEND_SLIP - if (AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_SLIP, 0)) { + if (backend == nullptr && AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_SLIP, 0)) { backend = new AP_Networking_SLIP(*this); } #endif diff --git a/libraries/AP_Networking/AP_Networking_Config.h b/libraries/AP_Networking/AP_Networking_Config.h index bbdbf5b37b729b..d3567709555e2c 100644 --- a/libraries/AP_Networking/AP_Networking_Config.h +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -22,7 +22,10 @@ // --------------------------- #ifndef AP_NETWORKING_BACKEND_CHIBIOS #define AP_NETWORKING_BACKEND_CHIBIOS (AP_NETWORKING_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS)) -#define AP_NETWORKING_BACKEND_SLIP (AP_NETWORKING_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS)) +#endif + +#ifndef AP_NETWORKING_BACKEND_PPP +#define AP_NETWORKING_BACKEND_PPP (AP_NETWORKING_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS)) #endif #ifndef AP_NETWORKING_BACKEND_SLIP diff --git a/libraries/AP_Networking/AP_Networking_PPP.cpp b/libraries/AP_Networking/AP_Networking_PPP.cpp new file mode 100644 index 00000000000000..ef4128871ff600 --- /dev/null +++ b/libraries/AP_Networking/AP_Networking_PPP.cpp @@ -0,0 +1,181 @@ + +#include "AP_Networking_Config.h" + +#if AP_NETWORKING_BACKEND_PPP + +#include "AP_Networking_PPP.h" +#include + +#include +#include +#include +#include +#include +#include +#include + + +extern const AP_HAL::HAL& hal; + +/* + uint32_t timestamp in smallest available units + */ +uint32_t sys_jiffies(void) +{ + return AP_HAL::micros(); +} + +/* + output some data to the uart + */ +uint32_t AP_Networking_PPP::ppp_output_cb(ppp_pcb *pcb, const void *data, uint32_t len, void *ctx) +{ + auto &driver = *(AP_Networking_PPP *)ctx; + LWIP_UNUSED_ARG(pcb); + uint32_t remaining = len; + uint8_t *ptr = const_cast((const uint8_t *)data); + while (remaining > 0) { + auto n = driver.uart->write(ptr, remaining); + if (n > 0) { + remaining -= n; + ptr += n; + } else { + hal.scheduler->delay_microseconds(100); + } + } + return len; +} + +/* + callback on link status change + */ +void AP_Networking_PPP::ppp_status_callback(struct ppp_pcb_s *pcb, int code, void *ctx) +{ + auto &driver = *(AP_Networking_PPP *)ctx; + struct netif *pppif = ppp_netif(pcb); + const char *msg = nullptr; + + switch (code) { + case PPPERR_NONE: { + // got addresses + driver.activeSettings.ip = ntohl(netif_ip4_addr(pppif)->addr); + driver.activeSettings.gw = ntohl(netif_ip4_gw(pppif)->addr); + driver.activeSettings.nm = ntohl(netif_ip4_netmask(pppif)->addr); + driver.activeSettings.last_change_ms = AP_HAL::millis(); + + break; + } + case PPPERR_PARAM: { /* Invalid parameter. */ + msg = "PPPERR_PARAM"; + break; + } + case PPPERR_OPEN: { /* Unable to open PPP session. */ + msg = "PPPERR_OPEN"; + break; + } + case PPPERR_DEVICE: { /* Invalid I/O device for PPP. */ + msg = "PPPERR_DEVICE"; + break; + } + case PPPERR_ALLOC: { /* Unable to allocate resources. */ + msg = "PPPERR_ALLOC"; + break; + } + case PPPERR_USER: { /* User interrupt. */ + msg = "PPPERR_USER"; + break; + } + case PPPERR_CONNECT: { /* Connection lost. */ + msg = "PPPERR_CONNECT"; + break; + } + case PPPERR_AUTHFAIL: { /* Failed authentication challenge. */ + msg = "PPPERR_AUTHFAIL"; + break; + } + case PPPERR_PROTOCOL: { /* Failed to meet protocol. */ + msg = "PPPERR_PROTOCOL"; + break; + } + case PPPERR_PEERDEAD: { /* Connection timeout */ + msg = "PPPERR_PEERDEAD"; + break; + } + case PPPERR_IDLETIMEOUT: { /* Idle Timeout */ + msg = "PPPERR_IDLETIMEOUT"; + break; + } + case PPPERR_CONNECTTIME: { /* Max connect time reached */ + msg = "PPPERR_CONNECTTIME"; + break; + } + case PPPERR_LOOPBACK: { /* Loopback detected */ + msg = "PPPERR_LOOPBACK"; + break; + } + } + if (msg != nullptr) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "PPP: %s", msg); + } +} + + +/* + initialise PPP network backend using LWIP + */ +bool AP_Networking_PPP::init() +{ + uart = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_PPP, 0); + if (uart == nullptr) { + return false; + } + uart->set_unbuffered_writes(true); + + pppif = new netif; + if (pppif == nullptr) { + return false; + } + + // initialise TCP/IP thread + tcpip_init(NULL, NULL); + hal.scheduler->delay(100); + + // create ppp connection + ppp = pppos_create(pppif, ppp_output_cb, ppp_status_callback, this); + if (ppp == nullptr) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "PPP: failed to create link"); + return false; + } + + // connect and set as default route + ppp_connect(ppp, 0); + netif_set_default(pppif); + + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "PPP: started"); + hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking_PPP::ppp_loop, void), + "ppp", + 8192, AP_HAL::Scheduler::PRIORITY_UART, 0); + + return true; +} + +/* + main loop for PPP + */ +void AP_Networking_PPP::ppp_loop(void) +{ + // ensure this thread owns the uart + uart->begin(0); + + while (true) { + uint8_t buf[1024]; + auto n = uart->read(buf, sizeof(buf)); + if (n > 0) { + pppos_input(ppp, buf, n); + } else { + hal.scheduler->delay_microseconds(100); + } + } +} + +#endif // AP_NETWORKING_BACKEND_PPP diff --git a/libraries/AP_Networking/AP_Networking_PPP.h b/libraries/AP_Networking/AP_Networking_PPP.h new file mode 100644 index 00000000000000..e04b9ec2345a36 --- /dev/null +++ b/libraries/AP_Networking/AP_Networking_PPP.h @@ -0,0 +1,29 @@ +#pragma once + +#include "AP_Networking_Config.h" + +#ifdef AP_NETWORKING_BACKEND_PPP +#include "AP_Networking_Backend.h" + +class AP_Networking_PPP : public AP_Networking_Backend +{ +public: + using AP_Networking_Backend::AP_Networking_Backend; + + /* Do not allow copies */ + CLASS_NO_COPY(AP_Networking_PPP); + + bool init() override; + +private: + void ppp_loop(void); + + AP_HAL::UARTDriver *uart; + struct netif *pppif; + struct ppp_pcb_s *ppp; + + static void ppp_status_callback(struct ppp_pcb_s *pcb, int code, void *ctx); + static uint32_t ppp_output_cb(struct ppp_pcb_s *pcb, const void *data, uint32_t len, void *ctx); +}; + +#endif // AP_NETWORKING_BACKEND_PPP From e53729f33133b27e6ba4988b97cc27dd99935a80 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 12 Dec 2023 19:02:42 +1100 Subject: [PATCH 0301/1335] AP_HAL: make Socket.cpp safe for lwip and SITL usage --- libraries/AP_HAL/utility/Socket.cpp | 43 ++++++++++++++++++++--------- libraries/AP_HAL/utility/Socket.h | 23 +++++++-------- 2 files changed, 40 insertions(+), 26 deletions(-) diff --git a/libraries/AP_HAL/utility/Socket.cpp b/libraries/AP_HAL/utility/Socket.cpp index 363b144d6720b3..0bad1ba6a99f29 100644 --- a/libraries/AP_HAL/utility/Socket.cpp +++ b/libraries/AP_HAL/utility/Socket.cpp @@ -21,9 +21,23 @@ #if AP_NETWORKING_SOCKETS_ENABLED #include "Socket.h" +#if AP_NETWORKING_BACKEND_CHIBIOS || AP_NETWORKING_BACKEND_PPP +#include +#else +// SITL or Linux +#include +#include +#include +#include +#include +#include +#include +#include +#endif + #include -#if AP_NETWORKING_BACKEND_CHIBIOS +#if AP_NETWORKING_BACKEND_CHIBIOS || AP_NETWORKING_BACKEND_PPP #define CALL_PREFIX(x) ::lwip_##x #else #define CALL_PREFIX(x) ::x @@ -33,6 +47,8 @@ #define MSG_NOSIGNAL 0 #endif +static_assert(sizeof(last_in_addr) == sizeof(struct sockaddr_in), "last_in_addr must match sockaddr_in size"); + /* constructor */ @@ -185,7 +201,7 @@ bool SocketAPM::connect_timeout(const char *address, uint16_t port, uint32_t tim } int sock_error = 0; socklen_t len = sizeof(sock_error); - if (getsockopt(fd, SOL_SOCKET, SO_ERROR, (void*)&sock_error, &len) != 0) { + if (CALL_PREFIX(getsockopt)(fd, SOL_SOCKET, SO_ERROR, (void*)&sock_error, &len) != 0) { return false; } connected = sock_error == 0; @@ -294,10 +310,10 @@ ssize_t SocketAPM::recv(void *buf, size_t size, uint32_t timeout_ms) errno = EWOULDBLOCK; return -1; } - socklen_t len = sizeof(in_addr); + socklen_t len = sizeof(last_in_addr); int fin = get_read_fd(); ssize_t ret; - ret = CALL_PREFIX(recvfrom)(fin, buf, size, MSG_DONTWAIT, (sockaddr *)&in_addr, &len); + ret = CALL_PREFIX(recvfrom)(fin, buf, size, MSG_DONTWAIT, (sockaddr *)&last_in_addr, &len); if (ret <= 0) { if (!datagram && connected && ret == 0) { // remote host has closed connection @@ -314,9 +330,9 @@ ssize_t SocketAPM::recv(void *buf, size_t size, uint32_t timeout_ms) if (CALL_PREFIX(getsockname)(fd, (struct sockaddr *)&send_addr, &send_len) != 0) { return -1; } - if (in_addr.sin_port == send_addr.sin_port && - in_addr.sin_family == send_addr.sin_family && - in_addr.sin_addr.s_addr == send_addr.sin_addr.s_addr) { + if (last_in_addr.sin_port == send_addr.sin_port && + last_in_addr.sin_family == send_addr.sin_family && + last_in_addr.sin_addr.s_addr == send_addr.sin_addr.s_addr) { // discard packets from ourselves return -1; } @@ -329,8 +345,9 @@ ssize_t SocketAPM::recv(void *buf, size_t size, uint32_t timeout_ms) */ void SocketAPM::last_recv_address(const char *&ip_addr, uint16_t &port) const { - ip_addr = inet_ntoa(in_addr.sin_addr); - port = ntohs(in_addr.sin_port); + static char buf[16]; + auto *str = last_recv_address(buf, sizeof(buf), port); + ip_addr = str; } /* @@ -338,11 +355,11 @@ void SocketAPM::last_recv_address(const char *&ip_addr, uint16_t &port) const */ const char *SocketAPM::last_recv_address(char *ip_addr_buf, uint8_t buflen, uint16_t &port) const { - const char *ret = inet_ntop(AF_INET, (void*)&in_addr.sin_addr, ip_addr_buf, buflen); + const char *ret = CALL_PREFIX(inet_ntop)(AF_INET, (void*)&last_in_addr.sin_addr, ip_addr_buf, buflen); if (ret == nullptr) { return nullptr; } - port = ntohs(in_addr.sin_port); + port = ntohs(last_in_addr.sin_port); return ret; } @@ -427,8 +444,8 @@ SocketAPM *SocketAPM::accept(uint32_t timeout_ms) return nullptr; } - socklen_t len = sizeof(in_addr); - int newfd = CALL_PREFIX(accept)(fd, (sockaddr *)&in_addr, &len); + socklen_t len = sizeof(last_in_addr); + int newfd = CALL_PREFIX(accept)(fd, (sockaddr *)&last_in_addr, &len); if (newfd == -1) { return nullptr; } diff --git a/libraries/AP_HAL/utility/Socket.h b/libraries/AP_HAL/utility/Socket.h index a7bbf45e5ba1cf..480281b5d7af96 100644 --- a/libraries/AP_HAL/utility/Socket.h +++ b/libraries/AP_HAL/utility/Socket.h @@ -19,22 +19,12 @@ #include #include + #if AP_NETWORKING_SOCKETS_ENABLED #if HAL_OS_SOCKETS -#include -#include -#include -#include -#include -#include -#include -#include -#elif AP_NETWORKING_BACKEND_CHIBIOS -#include -#include -#endif +struct sockaddr_in; class SocketAPM { public: @@ -91,7 +81,13 @@ class SocketAPM { private: bool datagram; - struct sockaddr_in in_addr {}; + struct { + uint16_t sin_family; + uint16_t sin_port; + struct { + uint32_t s_addr; + } sin_addr; + } last_in_addr; bool is_multicast_address(struct sockaddr_in &addr) const; int fd = -1; @@ -104,4 +100,5 @@ class SocketAPM { void make_sockaddr(const char *address, uint16_t port, struct sockaddr_in &sockaddr); }; +#endif // HAL_OS_SOCKETS #endif // AP_NETWORKING_SOCKETS_ENABLED From 671bcdad18ae06de427f606553ab0dc4b812ab61 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 12 Dec 2023 19:04:09 +1100 Subject: [PATCH 0302/1335] HAL_SITL: avoid socket headers in .h files this makes mixing SITL and lwip sockets possible --- libraries/AP_HAL_SITL/HAL_SITL_Class.cpp | 3 +++ libraries/AP_HAL_SITL/SITL_State.cpp | 31 +++++++++++++---------- libraries/AP_HAL_SITL/SITL_State.h | 3 ++- libraries/AP_HAL_SITL/SITL_State_common.h | 4 --- libraries/AP_HAL_SITL/Scheduler.cpp | 5 ++++ libraries/AP_HAL_SITL/UARTDriver.cpp | 12 +++++++++ libraries/AP_HAL_SITL/UARTDriver.h | 1 - libraries/AP_HAL_SITL/Util.cpp | 3 +++ 8 files changed, 43 insertions(+), 19 deletions(-) diff --git a/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp b/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp index 88b19026f7785a..ab4a67dd83fe26 100644 --- a/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp +++ b/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp @@ -6,6 +6,9 @@ #include #include #include +#include +#include +#include #include "AP_HAL_SITL.h" #include "AP_HAL_SITL_Namespace.h" diff --git a/libraries/AP_HAL_SITL/SITL_State.cpp b/libraries/AP_HAL_SITL/SITL_State.cpp index 19fce2e7e78402..29cc02156ce7fd 100644 --- a/libraries/AP_HAL_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_State.cpp @@ -14,7 +14,12 @@ #include #include #include +#include #include +#include +#include +#include +#include #include #include @@ -108,28 +113,25 @@ void SITL_State::_sitl_setup() /* setup a SITL FDM listening UDP port */ -void SITL_State::_setup_fdm(void) +bool SITL_State::_setup_fdm(void) { + if (_rc_in_started) { + return true; + } if (!_sitl_rc_in.reuseaddress()) { - fprintf(stderr, "SITL: socket reuseaddress failed on RC in port: %d - %s\n", _rcin_port, strerror(errno)); - fprintf(stderr, "Aborting launch...\n"); - exit(1); + return false; } if (!_sitl_rc_in.bind("0.0.0.0", _rcin_port)) { - fprintf(stderr, "SITL: socket bind failed on RC in port : %d - %s\n", _rcin_port, strerror(errno)); - fprintf(stderr, "Aborting launch...\n"); - exit(1); + return false; } if (!_sitl_rc_in.set_blocking(false)) { - fprintf(stderr, "SITL: socket set_blocking(false) failed on RC in port: %d - %s\n", _rcin_port, strerror(errno)); - fprintf(stderr, "Aborting launch...\n"); - exit(1); + return false; } if (!_sitl_rc_in.set_cloexec()) { - fprintf(stderr, "SITL: socket set_cloexec() failed on RC in port: %d - %s\n", _rcin_port, strerror(errno)); - fprintf(stderr, "Aborting launch...\n"); - exit(1); + return false; } + _rc_in_started = true; + return true; } @@ -244,6 +246,9 @@ bool SITL_State::_read_rc_sitl_input() uint16_t pwm[16]; } pwm_pkt; + if (!_setup_fdm()) { + return false; + } const ssize_t size = _sitl_rc_in.recv(&pwm_pkt, sizeof(pwm_pkt), 0); // if we are simulating no pulses RC failure, do not update pwm_input diff --git a/libraries/AP_HAL_SITL/SITL_State.h b/libraries/AP_HAL_SITL/SITL_State.h index 461ff51d600bed..5e5ce885b1f11b 100644 --- a/libraries/AP_HAL_SITL/SITL_State.h +++ b/libraries/AP_HAL_SITL/SITL_State.h @@ -59,7 +59,7 @@ class HALSITL::SITL_State : public SITL_State_Common { void _set_param_default(const char *parm); void _usage(void); void _sitl_setup(); - void _setup_fdm(void); + bool _setup_fdm(void); void _setup_timer(void); void _setup_adc(void); @@ -86,6 +86,7 @@ class HALSITL::SITL_State : public SITL_State_Common { Scheduler *_scheduler; SocketAPM _sitl_rc_in{true}; + bool _rc_in_started; uint16_t _rcin_port; uint16_t _fg_view_port; uint16_t _irlock_port; diff --git a/libraries/AP_HAL_SITL/SITL_State_common.h b/libraries/AP_HAL_SITL/SITL_State_common.h index 5d5ea6999db603..509391760cd312 100644 --- a/libraries/AP_HAL_SITL/SITL_State_common.h +++ b/libraries/AP_HAL_SITL/SITL_State_common.h @@ -56,10 +56,6 @@ #include "RCInput.h" #include -#include -#include -#include -#include #include #include diff --git a/libraries/AP_HAL_SITL/Scheduler.cpp b/libraries/AP_HAL_SITL/Scheduler.cpp index 2531722d710142..93fed42129d0b5 100644 --- a/libraries/AP_HAL_SITL/Scheduler.cpp +++ b/libraries/AP_HAL_SITL/Scheduler.cpp @@ -377,6 +377,11 @@ bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_ if (pthread_create(&thread, &a->attr, thread_create_trampoline, a) != 0) { goto failed; } + +#if !defined(__APPLE__) + pthread_setname_np(thread, name); +#endif + a->next = threads; threads = a; return true; diff --git a/libraries/AP_HAL_SITL/UARTDriver.cpp b/libraries/AP_HAL_SITL/UARTDriver.cpp index b30dad3e796021..9b7516af6938bb 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.cpp +++ b/libraries/AP_HAL_SITL/UARTDriver.cpp @@ -36,6 +36,7 @@ #include #include #include +#include #include "UARTDriver.h" #include "SITL_State.h" @@ -161,6 +162,16 @@ void UARTDriver::_begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace) AP_HAL::panic("Failed to open (%s): %m", args1); } _connected = true; + } else if (strcmp(devtype, "outfile") == 0) { + if (_connected) { + AP::FS().close(_fd); + } + ::printf("FILE output connection %s\n", args1); + _fd = AP::FS().open(args1, O_WRONLY|O_CREAT|O_TRUNC, 0644); + if (_fd == -1) { + AP_HAL::panic("Failed to open (%s): %m", args1); + } + _connected = true; } else if (strcmp(devtype, "logic_async_csv") == 0) { if (_connected) { AP::FS().close(_fd); @@ -290,6 +301,7 @@ void UARTDriver::_tcp_start_connection(uint16_t port, bool wait_for_connection) { int one=1; int ret; + struct sockaddr_in _listen_sockaddr {}; if (_connected) { return; diff --git a/libraries/AP_HAL_SITL/UARTDriver.h b/libraries/AP_HAL_SITL/UARTDriver.h index 45c00de18b3ac9..bf875b7abf3bcd 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.h +++ b/libraries/AP_HAL_SITL/UARTDriver.h @@ -76,7 +76,6 @@ class HALSITL::UARTDriver : public AP_HAL::UARTDriver { bool _connected = false; // true if a client has connected bool _use_send_recv = false; int _listen_fd; // socket we are listening on - struct sockaddr_in _listen_sockaddr; int _serial_port; static bool _console; ByteBuffer _readbuffer{16384}; diff --git a/libraries/AP_HAL_SITL/Util.cpp b/libraries/AP_HAL_SITL/Util.cpp index 5404bf35ff6951..958f2809564f0b 100644 --- a/libraries/AP_HAL_SITL/Util.cpp +++ b/libraries/AP_HAL_SITL/Util.cpp @@ -2,6 +2,9 @@ #include #include #include "RCOutput.h" +#include +#include +#include extern const AP_HAL::HAL& hal; From da7c556f77e1a749d7c1c9773fa3d47a8e7765e2 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 12 Dec 2023 19:04:45 +1100 Subject: [PATCH 0303/1335] AP_InertialSensor: avoid fcntl.h allows mixing of lwip and sockets --- libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp index 49a691b6061eb7..583ad75a42a953 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp @@ -2,7 +2,7 @@ #include "AP_InertialSensor_SITL.h" #include #include -#include +#include #if AP_SIM_INS_ENABLED @@ -410,7 +410,7 @@ void AP_InertialSensor_SITL::read_gyro_from_file() if (gyro_fd == -1) { char namebuf[32]; snprintf(namebuf, 32, "/tmp/gyro%d.dat", gyro_instance); - gyro_fd = open(namebuf, O_RDONLY|O_CLOEXEC); + gyro_fd = AP::FS().open(namebuf, O_RDONLY); if (gyro_fd == -1) { AP_HAL::panic("gyro data file %s not found", namebuf); } From b72b4b5bc0b47a278f4a52bb1fcc8b31344ef85b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 12 Dec 2023 19:05:16 +1100 Subject: [PATCH 0304/1335] SITL: added required headers with new SITL header structure --- libraries/SITL/SIM_GPS_FILE.cpp | 3 +++ libraries/SITL/SIM_JEDEC.cpp | 3 +++ libraries/SITL/SIM_RAMTRON.cpp | 3 +++ 3 files changed, 9 insertions(+) diff --git a/libraries/SITL/SIM_GPS_FILE.cpp b/libraries/SITL/SIM_GPS_FILE.cpp index e4c096f1eba7c8..60868d4355cb6a 100644 --- a/libraries/SITL/SIM_GPS_FILE.cpp +++ b/libraries/SITL/SIM_GPS_FILE.cpp @@ -6,6 +6,9 @@ #include #include +#include +#include +#include extern const AP_HAL::HAL& hal; diff --git a/libraries/SITL/SIM_JEDEC.cpp b/libraries/SITL/SIM_JEDEC.cpp index 9b4255f78139c1..9db090b7b665e8 100644 --- a/libraries/SITL/SIM_JEDEC.cpp +++ b/libraries/SITL/SIM_JEDEC.cpp @@ -4,6 +4,9 @@ #include #include +#include +#include +#include #include diff --git a/libraries/SITL/SIM_RAMTRON.cpp b/libraries/SITL/SIM_RAMTRON.cpp index dee0fca6b784a0..9706dee62a318e 100644 --- a/libraries/SITL/SIM_RAMTRON.cpp +++ b/libraries/SITL/SIM_RAMTRON.cpp @@ -4,6 +4,9 @@ #include #include +#include +#include +#include #include From 1bceee18633dd801842af295d0483b0fa9391020 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 12 Dec 2023 19:05:46 +1100 Subject: [PATCH 0305/1335] AP_Scripting: added WEB_SENDFILE_MIN parameter allows for sendfile tuning and disable --- libraries/AP_Scripting/applets/net_webserver.lua | 14 +++++++++++++- 1 file changed, 13 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Scripting/applets/net_webserver.lua b/libraries/AP_Scripting/applets/net_webserver.lua index 4355fa6006e878..cccbc6eb0c36fc 100644 --- a/libraries/AP_Scripting/applets/net_webserver.lua +++ b/libraries/AP_Scripting/applets/net_webserver.lua @@ -62,6 +62,15 @@ local WEB_BLOCK_SIZE = bind_add_param('BLOCK_SIZE', 4, 10240) --]] local WEB_TIMEOUT = bind_add_param('TIMEOUT', 5, 2.0) +--[[ + // @Param: WEB_SENDFILE_MIN + // @DisplayName: web server minimum file size for sendfile + // @Description: sendfile is an offloading mechanism for faster file download. If this is non-zero and the file is larger than this size then sendfile will be used for file download + // @Range: 0 10000000 + // @User: Advanced +--]] +local WEB_SENDFILE_MIN = bind_add_param('SENDFILE_MIN', 6, 100000) + if WEB_ENABLE:get() ~= 1 then gcs:send_text(MAV_SEVERITY.INFO, "WebServer: disabled") return @@ -775,7 +784,10 @@ local function Client(_sock, _idx) elseif cgi_processing then DEBUG(string.format("%u: CGI processing %s", idx, path)) run = self.send_cgi - elseif sock:sendfile(file) then + elseif stat and + WEB_SENDFILE_MIN:get() > 0 and + stat:size() >= WEB_SENDFILE_MIN:get() and + sock:sendfile(file) then return true else run = self.send_file From 8e132e44cf78f1eb075e960bf4a8b92c40481d3b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 17 Dec 2023 14:40:46 +1100 Subject: [PATCH 0306/1335] AP_HAL: improved sockaddr_in compatibility --- libraries/AP_HAL/utility/Socket.cpp | 31 +++++++++++++++++++---------- libraries/AP_HAL/utility/Socket.h | 18 ++++++----------- 2 files changed, 27 insertions(+), 22 deletions(-) diff --git a/libraries/AP_HAL/utility/Socket.cpp b/libraries/AP_HAL/utility/Socket.cpp index 0bad1ba6a99f29..57aa2bd74f6a2e 100644 --- a/libraries/AP_HAL/utility/Socket.cpp +++ b/libraries/AP_HAL/utility/Socket.cpp @@ -55,7 +55,9 @@ static_assert(sizeof(last_in_addr) == sizeof(struct sockaddr_in), "last_in_addr SocketAPM::SocketAPM(bool _datagram) : SocketAPM(_datagram, CALL_PREFIX(socket)(AF_INET, _datagram?SOCK_DGRAM:SOCK_STREAM, 0)) -{} +{ + static_assert(sizeof(SocketAPM::last_in_addr) >= sizeof(struct sockaddr_in), "last_in_addr must be at least sockaddr_in size"); +} SocketAPM::SocketAPM(bool _datagram, int _fd) : datagram(_datagram), @@ -310,10 +312,10 @@ ssize_t SocketAPM::recv(void *buf, size_t size, uint32_t timeout_ms) errno = EWOULDBLOCK; return -1; } - socklen_t len = sizeof(last_in_addr); + socklen_t len = sizeof(struct sockaddr_in); int fin = get_read_fd(); ssize_t ret; - ret = CALL_PREFIX(recvfrom)(fin, buf, size, MSG_DONTWAIT, (sockaddr *)&last_in_addr, &len); + ret = CALL_PREFIX(recvfrom)(fin, buf, size, MSG_DONTWAIT, (sockaddr *)&last_in_addr[0], &len); if (ret <= 0) { if (!datagram && connected && ret == 0) { // remote host has closed connection @@ -330,9 +332,10 @@ ssize_t SocketAPM::recv(void *buf, size_t size, uint32_t timeout_ms) if (CALL_PREFIX(getsockname)(fd, (struct sockaddr *)&send_addr, &send_len) != 0) { return -1; } - if (last_in_addr.sin_port == send_addr.sin_port && - last_in_addr.sin_family == send_addr.sin_family && - last_in_addr.sin_addr.s_addr == send_addr.sin_addr.s_addr) { + const struct sockaddr_in &sin = *(struct sockaddr_in *)&last_in_addr[0]; + if (sin.sin_port == send_addr.sin_port && + sin.sin_family == send_addr.sin_family && + sin.sin_addr.s_addr == send_addr.sin_addr.s_addr) { // discard packets from ourselves return -1; } @@ -355,11 +358,13 @@ void SocketAPM::last_recv_address(const char *&ip_addr, uint16_t &port) const */ const char *SocketAPM::last_recv_address(char *ip_addr_buf, uint8_t buflen, uint16_t &port) const { - const char *ret = CALL_PREFIX(inet_ntop)(AF_INET, (void*)&last_in_addr.sin_addr, ip_addr_buf, buflen); + const struct sockaddr_in &sin = *(struct sockaddr_in *)&last_in_addr[0]; + + const char *ret = inet_addr_to_str((void*)&sin.sin_addr, ip_addr_buf, buflen); if (ret == nullptr) { return nullptr; } - port = ntohs(last_in_addr.sin_port); + port = ntohs(sin.sin_port); return ret; } @@ -444,8 +449,9 @@ SocketAPM *SocketAPM::accept(uint32_t timeout_ms) return nullptr; } - socklen_t len = sizeof(last_in_addr); - int newfd = CALL_PREFIX(accept)(fd, (sockaddr *)&last_in_addr, &len); + struct sockaddr_in &sin = *(struct sockaddr_in *)&last_in_addr[0]; + socklen_t len = sizeof(sin); + int newfd = CALL_PREFIX(accept)(fd, (sockaddr *)&sin, &len); if (newfd == -1) { return nullptr; } @@ -497,4 +503,9 @@ SocketAPM *SocketAPM::duplicate(void) return ret; } +const char *SocketAPM::inet_addr_to_str(const void *src, char *dst, uint16_t len) +{ + return CALL_PREFIX(inet_ntop)(AF_INET, src, dst, len); +} + #endif // AP_NETWORKING_BACKEND_ANY diff --git a/libraries/AP_HAL/utility/Socket.h b/libraries/AP_HAL/utility/Socket.h index 480281b5d7af96..82c0ee2604c4c5 100644 --- a/libraries/AP_HAL/utility/Socket.h +++ b/libraries/AP_HAL/utility/Socket.h @@ -22,10 +22,6 @@ #if AP_NETWORKING_SOCKETS_ENABLED -#if HAL_OS_SOCKETS - -struct sockaddr_in; - class SocketAPM { public: SocketAPM(bool _datagram); @@ -79,15 +75,14 @@ class SocketAPM { return connected; } + // access to inet_ntop + static const char *inet_addr_to_str(const void *src, char *dst, uint16_t len); + private: bool datagram; - struct { - uint16_t sin_family; - uint16_t sin_port; - struct { - uint32_t s_addr; - } sin_addr; - } last_in_addr; + // we avoid using struct sockaddr_in here to keep support for + // mixing native sockets and lwip sockets in SITL + uint32_t last_in_addr[4]; bool is_multicast_address(struct sockaddr_in &addr) const; int fd = -1; @@ -100,5 +95,4 @@ class SocketAPM { void make_sockaddr(const char *address, uint16_t port, struct sockaddr_in &sockaddr); }; -#endif // HAL_OS_SOCKETS #endif // AP_NETWORKING_SOCKETS_ENABLED From 94ea22d16f455cb75f250e7f1cbd942d3042bf94 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 06:26:47 +1100 Subject: [PATCH 0307/1335] AP_Networking: separate thread for sendfile --- libraries/AP_Networking/AP_Networking.cpp | 103 ++++++++++++---------- libraries/AP_Networking/AP_Networking.h | 6 ++ 2 files changed, 63 insertions(+), 46 deletions(-) diff --git a/libraries/AP_Networking/AP_Networking.cpp b/libraries/AP_Networking/AP_Networking.cpp index 66786f92fa23a2..32bbf51de50c96 100644 --- a/libraries/AP_Networking/AP_Networking.cpp +++ b/libraries/AP_Networking/AP_Networking.cpp @@ -14,14 +14,14 @@ extern const AP_HAL::HAL& hal; #if AP_NETWORKING_BACKEND_CHIBIOS #include "AP_Networking_ChibiOS.h" -#include "AP_Networking_SLIP.h" -#include "AP_Networking_PPP.h" #include -#include -#else -#include #endif +#include +#include +#include + + #include #if AP_NETWORKING_BACKEND_SLIP @@ -179,9 +179,6 @@ void AP_Networking::init() // init network mapped serialmanager ports ports_init(); - - // register sendfile handler - hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_Networking::sendfile_check, void)); } /* @@ -239,7 +236,7 @@ uint8_t AP_Networking::convert_netmask_ip_to_bitcount(const uint32_t netmask_ip) uint32_t AP_Networking::convert_str_to_ip(const char* ip_str) { uint32_t ip = 0; - inet_pton(AF_INET, ip_str, &ip); + lwip_inet_pton(AF_INET, ip_str, &ip); return ntohl(ip); } @@ -247,7 +244,7 @@ const char* AP_Networking::convert_ip_to_str(uint32_t ip) { ip = htonl(ip); static char _str_buffer[20]; - inet_ntop(AF_INET, &ip, _str_buffer, sizeof(_str_buffer)); + lwip_inet_ntop(AF_INET, &ip, _str_buffer, sizeof(_str_buffer)); return _str_buffer; } @@ -326,6 +323,14 @@ bool AP_Networking::sendfile(SocketAPM *sock, int fd) return false; } } + if (!sendfile_thread_started) { + if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking::sendfile_check, void), + "sendfile", + 2048, AP_HAL::Scheduler::PRIORITY_UART, 0)) { + return false; + } + sendfile_thread_started = true; + } for (auto &s : sendfiles) { if (s.sock == nullptr) { s.sock = sock->duplicate(); @@ -352,37 +357,37 @@ void AP_Networking::SendFile::close(void) */ void AP_Networking::sendfile_check(void) { - if (sendfile_buf == nullptr) { - return; - } - WITH_SEMAPHORE(sem); - bool none_active = true; - for (auto &s : sendfiles) { - if (s.sock == nullptr) { - continue; - } - none_active = false; - if (!s.sock->pollout(0)) { - continue; - } - const auto nread = AP::FS().read(s.fd, sendfile_buf, AP_NETWORKING_SENDFILE_BUFSIZE); - if (nread <= 0) { - s.close(); - continue; - } - const auto nsent = s.sock->send(sendfile_buf, nread); - if (nsent <= 0) { - s.close(); - continue; + while (true) { + hal.scheduler->delay(1); + WITH_SEMAPHORE(sem); + bool none_active = true; + for (auto &s : sendfiles) { + if (s.sock == nullptr) { + continue; + } + none_active = false; + if (!s.sock->pollout(0)) { + continue; + } + const auto nread = AP::FS().read(s.fd, sendfile_buf, AP_NETWORKING_SENDFILE_BUFSIZE); + if (nread <= 0) { + s.close(); + continue; + } + const auto nsent = s.sock->send(sendfile_buf, nread); + if (nsent <= 0) { + s.close(); + continue; + } + if (nsent < nread) { + AP::FS().lseek(s.fd, nsent - nread, SEEK_CUR); + } } - if (nsent < nread) { - AP::FS().lseek(s.fd, nsent - nread, SEEK_CUR); + if (none_active) { + free(sendfile_buf); + sendfile_buf = nullptr; } } - if (none_active) { - free(sendfile_buf); - sendfile_buf = nullptr; - } } AP_Networking *AP_Networking::singleton; @@ -400,19 +405,18 @@ AP_Networking &network() */ int ap_networking_printf(const char *fmt, ...) { -#if AP_NETWORKING_LWIP_DEBUG_PORT >= 0 - static AP_HAL::UARTDriver *uart; - if (uart == nullptr) { - uart = hal.serial(AP_NETWORKING_LWIP_DEBUG_PORT); - if (uart == nullptr) { + WITH_SEMAPHORE(AP::network().get_semaphore()); +#ifdef AP_NETWORKING_LWIP_DEBUG_FILE + static int fd = -1; + if (fd == -1) { + fd = AP::FS().open(AP_NETWORKING_LWIP_DEBUG_FILE, O_WRONLY|O_CREAT|O_TRUNC, 0644); + if (fd == -1) { return -1; } - uart->begin(AP_NETWORKING_LWIP_DEBUG_BAUD, 1000, 50000); } - uart->begin(0); va_list ap; va_start(ap, fmt); - uart->vprintf(fmt, ap); + vdprintf(fd, fmt, ap); va_end(ap); #else va_list ap; @@ -423,4 +427,11 @@ int ap_networking_printf(const char *fmt, ...) return 0; } +#ifdef LWIP_PLATFORM_ASSERT +void ap_networking_platform_assert(const char *msg, int line, const char *file) +{ + AP_HAL::panic("LWIP: %s: %s:%u", msg, file, line); +} +#endif + #endif // AP_NETWORKING_ENABLED diff --git a/libraries/AP_Networking/AP_Networking.h b/libraries/AP_Networking/AP_Networking.h index 5ed32329244073..005a521997833e 100644 --- a/libraries/AP_Networking/AP_Networking.h +++ b/libraries/AP_Networking/AP_Networking.h @@ -45,6 +45,11 @@ class AP_Networking return singleton; } + HAL_Semaphore &get_semaphore(void) + { + return sem; + } + // Networking interface is enabled and initialized bool is_healthy() const { @@ -325,6 +330,7 @@ class AP_Networking uint8_t *sendfile_buf; void sendfile_check(void); + bool sendfile_thread_started; void ports_init(void); }; From 1d9d599bb051958e93abfe9930e0768e6db87e90 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 06:27:13 +1100 Subject: [PATCH 0308/1335] AP_Networking: allow for PPP on ChibiOS --- .../AP_Networking/AP_Networking_Config.h | 11 +++-- libraries/AP_Networking/AP_Networking_PPP.cpp | 41 +++++++++++++++---- .../AP_Networking/AP_Networking_SLIP.cpp | 1 - .../AP_Networking/AP_Networking_address.cpp | 4 +- 4 files changed, 41 insertions(+), 16 deletions(-) diff --git a/libraries/AP_Networking/AP_Networking_Config.h b/libraries/AP_Networking/AP_Networking_Config.h index d3567709555e2c..dcecd2be3a9333 100644 --- a/libraries/AP_Networking/AP_Networking_Config.h +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -21,22 +21,25 @@ // Backends // --------------------------- #ifndef AP_NETWORKING_BACKEND_CHIBIOS -#define AP_NETWORKING_BACKEND_CHIBIOS (AP_NETWORKING_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS)) +#ifndef HAL_USE_MAC +#define HAL_USE_MAC 0 +#endif +#define AP_NETWORKING_BACKEND_CHIBIOS (AP_NETWORKING_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS) && HAL_USE_MAC) #endif #ifndef AP_NETWORKING_BACKEND_PPP -#define AP_NETWORKING_BACKEND_PPP (AP_NETWORKING_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS)) +#define AP_NETWORKING_BACKEND_PPP (AP_NETWORKING_BACKEND_DEFAULT_ENABLED) #endif #ifndef AP_NETWORKING_BACKEND_SLIP -#define AP_NETWORKING_BACKEND_SLIP (AP_NETWORKING_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS)) +#define AP_NETWORKING_BACKEND_SLIP 0 #endif #ifndef AP_NETWORKING_BACKEND_SITL #define AP_NETWORKING_BACKEND_SITL (AP_NETWORKING_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_SITL)) #endif -#define AP_NETWORKING_SOCKETS_ENABLED (HAL_OS_SOCKETS || AP_NETWORKING_BACKEND_CHIBIOS) +#define AP_NETWORKING_SOCKETS_ENABLED AP_NETWORKING_ENABLED // --------------------------- // IP Features diff --git a/libraries/AP_Networking/AP_Networking_PPP.cpp b/libraries/AP_Networking/AP_Networking_PPP.cpp index ef4128871ff600..8e296a1abbfa20 100644 --- a/libraries/AP_Networking/AP_Networking_PPP.cpp +++ b/libraries/AP_Networking/AP_Networking_PPP.cpp @@ -6,7 +6,6 @@ #include "AP_Networking_PPP.h" #include -#include #include #include #include @@ -17,6 +16,7 @@ extern const AP_HAL::HAL& hal; +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS /* uint32_t timestamp in smallest available units */ @@ -24,6 +24,15 @@ uint32_t sys_jiffies(void) { return AP_HAL::micros(); } +#endif + +#if LWIP_TCPIP_CORE_LOCKING +#define LWIP_TCPIP_LOCK() sys_lock_tcpip_core() +#define LWIP_TCPIP_UNLOCK() sys_unlock_tcpip_core() +#else +#define LWIP_TCPIP_LOCK() +#define LWIP_TCPIP_UNLOCK() +#endif /* output some data to the uart @@ -39,8 +48,6 @@ uint32_t AP_Networking_PPP::ppp_output_cb(ppp_pcb *pcb, const void *data, uint32 if (n > 0) { remaining -= n; ptr += n; - } else { - hal.scheduler->delay_microseconds(100); } } return len; @@ -137,24 +144,26 @@ bool AP_Networking_PPP::init() } // initialise TCP/IP thread + LWIP_TCPIP_LOCK(); tcpip_init(NULL, NULL); + LWIP_TCPIP_UNLOCK(); + hal.scheduler->delay(100); // create ppp connection + LWIP_TCPIP_LOCK(); + ppp = pppos_create(pppif, ppp_output_cb, ppp_status_callback, this); if (ppp == nullptr) { GCS_SEND_TEXT(MAV_SEVERITY_INFO, "PPP: failed to create link"); return false; } - - // connect and set as default route - ppp_connect(ppp, 0); - netif_set_default(pppif); + LWIP_TCPIP_UNLOCK(); GCS_SEND_TEXT(MAV_SEVERITY_INFO, "PPP: started"); hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking_PPP::ppp_loop, void), "ppp", - 8192, AP_HAL::Scheduler::PRIORITY_UART, 0); + 2048, AP_HAL::Scheduler::PRIORITY_UART, 0); return true; } @@ -164,6 +173,17 @@ bool AP_Networking_PPP::init() */ void AP_Networking_PPP::ppp_loop(void) { + while (!hal.scheduler->is_system_initialized()) { + hal.scheduler->delay_microseconds(1000); + } + + // connect and set as default route + LWIP_TCPIP_LOCK(); + ppp_connect(ppp, 0); + + netif_set_default(pppif); + LWIP_TCPIP_UNLOCK(); + // ensure this thread owns the uart uart->begin(0); @@ -171,9 +191,12 @@ void AP_Networking_PPP::ppp_loop(void) uint8_t buf[1024]; auto n = uart->read(buf, sizeof(buf)); if (n > 0) { + LWIP_TCPIP_LOCK(); pppos_input(ppp, buf, n); - } else { + LWIP_TCPIP_UNLOCK(); hal.scheduler->delay_microseconds(100); + } else { + hal.scheduler->delay_microseconds(1000); } } } diff --git a/libraries/AP_Networking/AP_Networking_SLIP.cpp b/libraries/AP_Networking/AP_Networking_SLIP.cpp index 088bd024c810ae..b1e5085b5d64cf 100644 --- a/libraries/AP_Networking/AP_Networking_SLIP.cpp +++ b/libraries/AP_Networking/AP_Networking_SLIP.cpp @@ -6,7 +6,6 @@ #include "AP_Networking_SLIP.h" #include -#include #include #include #include diff --git a/libraries/AP_Networking/AP_Networking_address.cpp b/libraries/AP_Networking/AP_Networking_address.cpp index 28900e387b2673..a1c1cdc59ca49c 100644 --- a/libraries/AP_Networking/AP_Networking_address.cpp +++ b/libraries/AP_Networking/AP_Networking_address.cpp @@ -8,6 +8,7 @@ #include #include "AP_Networking.h" +#include const AP_Param::GroupInfo AP_Networking_IPV4::var_info[] = { // @Param: 0 @@ -72,8 +73,7 @@ void AP_Networking_IPV4::set_default_uint32(uint32_t v) const char* AP_Networking_IPV4::get_str() { const auto ip = ntohl(get_uint32()); - inet_ntop(AF_INET, &ip, strbuf, sizeof(strbuf)); - return strbuf; + return SocketAPM::inet_addr_to_str(&ip, strbuf, sizeof(strbuf)); } #endif // AP_NETWORKING_ENABLED From 5748adbf44bd6ed8734bb701572c9acde80dada6 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 06:28:24 +1100 Subject: [PATCH 0309/1335] HAL_ChibiOS: allow for networking without ethernet --- .../hwdef/scripts/chibios_hwdef.py | 24 +++++++++++++------ 1 file changed, 17 insertions(+), 7 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index d129a0dcf2b6cc..3d8a906365bf54 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -903,6 +903,16 @@ def get_numeric_board_id(self): raise ValueError("Unable to map (%s) to a board ID using %s" % (some_id, board_types_filepath)) + def enable_networking(self, f): + f.write(''' +#ifndef AP_NETWORKING_ENABLED +#define AP_NETWORKING_ENABLED 1 +#endif +#define CH_CFG_USE_MAILBOXES 1 +''') + self.env_vars['USE_LWIP'] = 'yes' + self.build_flags.append('USE_LWIP=yes') + def write_mcu_config(self, f): '''write MCU config defines''' f.write('#define CHIBIOS_BOARD_NAME "%s"\n' % os.path.basename(os.path.dirname(args.hwdef[0]))) @@ -965,17 +975,12 @@ def write_mcu_config(self, f): f.write('#define STM32_USB_USE_OTG2 TRUE\n') if 'ETH1' in self.bytype: - self.build_flags.append('USE_LWIP=yes') + self.enable_networking(f) f.write(''' -#ifndef AP_NETWORKING_ENABLED -// Configure for Ethernet support -#define AP_NETWORKING_ENABLED 1 -#define CH_CFG_USE_MAILBOXES TRUE #define HAL_USE_MAC TRUE #define MAC_USE_EVENTS TRUE #define STM32_ETH_BUFFERS_EXTERN -#endif ''') @@ -1028,7 +1033,12 @@ def write_mcu_config(self, f): # extract numerical defines for processing by other parts of the script result = re.match(r'define\s*([A-Z_]+)\s*([0-9]+)', d) if result: - self.intdefines[result.group(1)] = int(result.group(2)) + define = result.group(1) + value = int(result.group(2)) + self.intdefines[define] = value + if define == 'AP_NETWORKING_ENABLED' and value == 1: + self.enable_networking(f) + if self.intdefines.get('HAL_USE_USB_MSD', 0) == 1: self.build_flags.append('USE_USB_MSD=yes') From a53be122db376902f7aeb6f8fdf8273979e93aea Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 06:29:05 +1100 Subject: [PATCH 0310/1335] waf: removed lwip source paths in chibios class --- Tools/ardupilotwaf/chibios.py | 3 --- 1 file changed, 3 deletions(-) diff --git a/Tools/ardupilotwaf/chibios.py b/Tools/ardupilotwaf/chibios.py index c31479c270c904..b84d6e89514e4b 100644 --- a/Tools/ardupilotwaf/chibios.py +++ b/Tools/ardupilotwaf/chibios.py @@ -691,9 +691,6 @@ def build(bld): common_src += bld.path.ant_glob('libraries/AP_HAL_ChibiOS/hwdef/common/*.mk') common_src += bld.path.ant_glob('modules/ChibiOS/os/hal/**/*.[ch]') common_src += bld.path.ant_glob('modules/ChibiOS/os/hal/**/*.mk') - common_src += bld.path.ant_glob('modules/ChibiOS/ext/lwip/src/**/*.[ch]') - common_src += bld.path.ant_glob('modules/ChibiOS/ext/lwip/src/netif/**/*.[ch]') - common_src += bld.path.ant_glob('modules/ChibiOS/ext/lwip/src/core/**/*.[ch]') if bld.env.ROMFS_FILES: common_src += [bld.bldnode.find_or_declare('ap_romfs_embedded.h')] From 468c532290857f41be5dedc16e0696f40eed7153 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 21 Dec 2023 09:26:49 +1100 Subject: [PATCH 0311/1335] waf: recurse info AP_Networking --- wscript | 2 ++ 1 file changed, 2 insertions(+) diff --git a/wscript b/wscript index 19630462ecdd70..31da3e0ba2e344 100644 --- a/wscript +++ b/wscript @@ -548,6 +548,8 @@ def configure(cfg): cfg.recurse('libraries/AP_HAL_SITL') cfg.recurse('libraries/SITL') + cfg.recurse('libraries/AP_Networking') + cfg.start_msg('Scripting runtime checks') if cfg.options.scripting_checks: cfg.end_msg('enabled') From b28912c35157bd60ec14f7ca37500558a28f6724 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 23 Dec 2023 16:07:40 +1100 Subject: [PATCH 0312/1335] HAL_SITL: cope with no _sitl state --- libraries/AP_HAL_SITL/SITL_State.cpp | 8 ++------ 1 file changed, 2 insertions(+), 6 deletions(-) diff --git a/libraries/AP_HAL_SITL/SITL_State.cpp b/libraries/AP_HAL_SITL/SITL_State.cpp index 29cc02156ce7fd..4b08727d8ec1f0 100644 --- a/libraries/AP_HAL_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_State.cpp @@ -341,9 +341,7 @@ void SITL_State::_fdm_input_local(void) _check_rc_input(); // construct servos structure for FDM - if (_sitl != nullptr) { - _simulator_servos(input); - } + _simulator_servos(input); #if HAL_SIM_JSON_MASTER_ENABLED // read servo inputs from ride along flight controllers @@ -351,9 +349,7 @@ void SITL_State::_fdm_input_local(void) #endif // replace outputs from multicast - if (_sitl != nullptr) { - multicast_servo_update(input); - } + multicast_servo_update(input); // update the model sitl_model->update_home(); From 22938e99ea6fcdf0325925a9d54ffcf184b24356 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 06:31:16 +1100 Subject: [PATCH 0313/1335] AP_Networking: added ArduPilot HAL port of lwip --- .../AP_Networking/AP_Networking_ChibiOS.cpp | 292 +++++++++- .../AP_Networking/AP_Networking_ChibiOS.h | 9 +- libraries/AP_Networking/AP_Networking_PPP.cpp | 25 +- libraries/AP_Networking/config/lwipopts.h | 365 ++++++++++++ .../AP_Networking/lwip_hal/arch/sys_arch.cpp | 538 ++++++++++++++++++ .../AP_Networking/lwip_hal/include/arch/cc.h | 21 + .../lwip_hal/include/arch/sys_arch.h | 49 ++ libraries/AP_Networking/wscript | 36 ++ 8 files changed, 1290 insertions(+), 45 deletions(-) create mode 100644 libraries/AP_Networking/config/lwipopts.h create mode 100644 libraries/AP_Networking/lwip_hal/arch/sys_arch.cpp create mode 100644 libraries/AP_Networking/lwip_hal/include/arch/cc.h create mode 100644 libraries/AP_Networking/lwip_hal/include/arch/sys_arch.h create mode 100644 libraries/AP_Networking/wscript diff --git a/libraries/AP_Networking/AP_Networking_ChibiOS.cpp b/libraries/AP_Networking/AP_Networking_ChibiOS.cpp index ea5e4f42a6b0e1..ed5c5ea8908bae 100644 --- a/libraries/AP_Networking/AP_Networking_ChibiOS.cpp +++ b/libraries/AP_Networking/AP_Networking_ChibiOS.cpp @@ -6,9 +6,16 @@ #include "AP_Networking_ChibiOS.h" #include -#include #include #include +#include +#include +#if LWIP_DHCP +#include +#endif +#include +#include "../../modules/ChibiOS/os/various/evtimer.h" +#include extern const AP_HAL::HAL& hal; @@ -18,23 +25,34 @@ extern const AP_HAL::HAL& hal; /* these are referenced as globals inside lwip - */ +*/ stm32_eth_rx_descriptor_t *__eth_rd; stm32_eth_tx_descriptor_t *__eth_td; uint32_t *__eth_rb[STM32_MAC_RECEIVE_BUFFERS]; uint32_t *__eth_tb[STM32_MAC_TRANSMIT_BUFFERS]; +#define LWIP_SEND_TIMEOUT_MS 50 +#define LWIP_NETIF_MTU 1500 +#define LWIP_LINK_POLL_INTERVAL TIME_S2I(5) + +#define PERIODIC_TIMER_ID 1 +#define FRAME_RECEIVED_ID 2 + +#if CH_CFG_ST_RESOLUTION != 32 +#error "ethernet requires 32 bit timer" +#endif + /* allocate buffers for LWIP - */ +*/ bool AP_Networking_ChibiOS::allocate_buffers() { - #define AP_NETWORKING_EXTERN_MAC_BUFFER_SIZE ((((STM32_MAC_BUFFERS_SIZE - 1) | 3) + 1) / 4) // typically == 381 +#define AP_NETWORKING_EXTERN_MAC_BUFFER_SIZE ((((STM32_MAC_BUFFERS_SIZE - 1) | 3) + 1) / 4) // typically == 381 // check total size of buffers const uint32_t total_size = sizeof(stm32_eth_rx_descriptor_t)*STM32_MAC_RECEIVE_BUFFERS + - sizeof(stm32_eth_tx_descriptor_t)*STM32_MAC_TRANSMIT_BUFFERS + - sizeof(uint32_t)*STM32_MAC_RECEIVE_BUFFERS*AP_NETWORKING_EXTERN_MAC_BUFFER_SIZE + - sizeof(uint32_t)*STM32_MAC_TRANSMIT_BUFFERS*AP_NETWORKING_EXTERN_MAC_BUFFER_SIZE; // typically == 9240 + sizeof(stm32_eth_tx_descriptor_t)*STM32_MAC_TRANSMIT_BUFFERS + + sizeof(uint32_t)*STM32_MAC_RECEIVE_BUFFERS*AP_NETWORKING_EXTERN_MAC_BUFFER_SIZE + + sizeof(uint32_t)*STM32_MAC_TRANSMIT_BUFFERS*AP_NETWORKING_EXTERN_MAC_BUFFER_SIZE; // typically == 9240 // ensure that we allocate 32-bit aligned memory, and mark it non-cacheable uint32_t size = 1; @@ -84,7 +102,7 @@ bool AP_Networking_ChibiOS::allocate_buffers() /* initialise ChibiOS network backend using LWIP - */ +*/ bool AP_Networking_ChibiOS::init() { #ifdef HAL_GPIO_ETH_ENABLE @@ -102,21 +120,6 @@ bool AP_Networking_ChibiOS::init() return false; } - lwip_options = new lwipthread_opts; - - if (frontend.get_dhcp_enabled()) { - lwip_options->addrMode = NET_ADDRESS_DHCP; - } else { - lwip_options->addrMode = NET_ADDRESS_STATIC; - lwip_options->address = htonl(frontend.get_ip_param()); - lwip_options->netmask = htonl(frontend.get_netmask_param()); - lwip_options->gateway = htonl(frontend.get_gateway_param()); - } - frontend.param.macaddr.get_address(macaddr); - lwip_options->macaddress = macaddr; - - lwipInit(lwip_options); - #if LWIP_IGMP if (ETH != nullptr) { // enbale "permit multicast" so we can receive multicast packets @@ -124,17 +127,252 @@ bool AP_Networking_ChibiOS::init() } #endif + thisif = new netif; + if (thisif == nullptr) { + return false; + } + + if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking_ChibiOS::thread, void), + "network", + 2048, AP_HAL::Scheduler::PRIORITY_NET, 0)) { + return false; + } + return true; } +void AP_Networking_ChibiOS::link_up_cb(void *p) +{ + auto *driver = (AP_Networking_ChibiOS *)p; +#if LWIP_DHCP + if (driver->frontend.get_dhcp_enabled()) { + dhcp_start(driver->thisif); + } +#endif +} + +void AP_Networking_ChibiOS::link_down_cb(void *p) +{ + auto *driver = (AP_Networking_ChibiOS *)p; +#if LWIP_DHCP + if (driver->frontend.get_dhcp_enabled()) { + dhcp_stop(driver->thisif); + } +#endif +} + /* - update called at 10Hz + * This function does the actual transmission of the packet. The packet is + * contained in the pbuf that is passed to the function. This pbuf + * might be chained. + * + * @param netif the lwip network interface structure for this ethernetif + * @param p the MAC packet to send (e.g. IP packet including MAC addresses and type) + * @return ERR_OK if the packet could be sent + * an err_t value if the packet couldn't be sent + * + * @note Returning ERR_MEM here if a DMA queue of your MAC is full can lead to + * strange results. You might consider waiting for space in the DMA queue + * to become available since the stack doesn't retry to send a packet + * dropped because of memory failure (except for the TCP timers). */ +int8_t AP_Networking_ChibiOS::low_level_output(struct netif *netif, struct pbuf *p) +{ + struct pbuf *q; + MACTransmitDescriptor td; + (void)netif; + + if (macWaitTransmitDescriptor(ÐD1, &td, TIME_MS2I(LWIP_SEND_TIMEOUT_MS)) != MSG_OK) { + return ERR_TIMEOUT; + } + +#if ETH_PAD_SIZE + pbuf_header(p, -ETH_PAD_SIZE); /* drop the padding word */ +#endif + + /* Iterates through the pbuf chain. */ + for(q = p; q != NULL; q = q->next) { + macWriteTransmitDescriptor(&td, (uint8_t *)q->payload, (size_t)q->len); + } + macReleaseTransmitDescriptorX(&td); + +#if ETH_PAD_SIZE + pbuf_header(p, ETH_PAD_SIZE); /* reclaim the padding word */ +#endif + + return ERR_OK; +} + +/* + * Receives a frame. + * Allocates a pbuf and transfers the bytes of the incoming + * packet from the interface into the pbuf. + * + * @param netif the lwip network interface structure for this ethernetif + * @return a pbuf filled with the received packet (including MAC header) + * NULL on memory error + */ +bool AP_Networking_ChibiOS::low_level_input(struct netif *netif, struct pbuf **pbuf) +{ + MACReceiveDescriptor rd; + struct pbuf *q; + u16_t len; + + (void)netif; + + if (macWaitReceiveDescriptor(ÐD1, &rd, TIME_IMMEDIATE) != MSG_OK) { + return false; + } + + len = (u16_t)rd.size; + +#if ETH_PAD_SIZE + len += ETH_PAD_SIZE; /* allow room for Ethernet padding */ +#endif + + /* We allocate a pbuf chain of pbufs from the pool. */ + *pbuf = pbuf_alloc(PBUF_RAW, len, PBUF_POOL); + + if (*pbuf != nullptr) { +#if ETH_PAD_SIZE + pbuf_header(*pbuf, -ETH_PAD_SIZE); /* drop the padding word */ +#endif + + /* Iterates through the pbuf chain. */ + for(q = *pbuf; q != NULL; q = q->next) { + macReadReceiveDescriptor(&rd, (uint8_t *)q->payload, (size_t)q->len); + } + macReleaseReceiveDescriptorX(&rd); + +#if ETH_PAD_SIZE + pbuf_header(*pbuf, ETH_PAD_SIZE); /* reclaim the padding word */ +#endif + } else { + macReleaseReceiveDescriptorX(&rd); // Drop packet + } + + return true; +} + +int8_t AP_Networking_ChibiOS::ethernetif_init(struct netif *netif) +{ + netif->state = NULL; + netif->name[0] = 'm'; + netif->name[1] = 's'; + netif->output = etharp_output; + netif->linkoutput = low_level_output; + + /* set MAC hardware address length */ + netif->hwaddr_len = ETHARP_HWADDR_LEN; + + /* maximum transfer unit */ + netif->mtu = LWIP_NETIF_MTU; + + /* device capabilities */ + netif->flags = NETIF_FLAG_BROADCAST | NETIF_FLAG_ETHARP; + +#if LWIP_IGMP + // also enable multicast + netif->flags |= NETIF_FLAG_IGMP; +#endif + + return ERR_OK; +} + +/* + networking thread +*/ +void AP_Networking_ChibiOS::thread() +{ + while (!hal.scheduler->is_system_initialized()) { + hal.scheduler->delay_microseconds(1000); + } + + /* start tcpip thread */ + tcpip_init(NULL, NULL); + + frontend.param.macaddr.get_address(thisif->hwaddr); + + struct { + ip4_addr_t ip, gateway, netmask; + } addr {}; + + if (!frontend.get_dhcp_enabled()) { + addr.ip.addr = htonl(frontend.get_ip_param()); + addr.gateway.addr = htonl(frontend.get_gateway_param()); + addr.netmask.addr = htonl(frontend.get_netmask_param()); + } + + const MACConfig mac_config = {thisif->hwaddr}; + macStart(ÐD1, &mac_config); + + /* Add interface. */ + auto result = netifapi_netif_add(thisif, &addr.ip, &addr.netmask, &addr.gateway, NULL, ethernetif_init, tcpip_input); + if (result != ERR_OK) { + AP_HAL::panic("Failed to initialise netif"); + } + + netifapi_netif_set_default(thisif); + netifapi_netif_set_up(thisif); + + /* Setup event sources.*/ + event_timer_t evt; + event_listener_t el0, el1; + + evtObjectInit(&evt, LWIP_LINK_POLL_INTERVAL); + evtStart(&evt); + chEvtRegisterMask(&evt.et_es, &el0, PERIODIC_TIMER_ID); + chEvtRegisterMaskWithFlags(macGetEventSource(ÐD1), &el1, + FRAME_RECEIVED_ID, MAC_FLAGS_RX); + chEvtAddEvents(PERIODIC_TIMER_ID | FRAME_RECEIVED_ID); + + while (true) { + eventmask_t mask = chEvtWaitAny(ALL_EVENTS); + if (mask & PERIODIC_TIMER_ID) { + bool current_link_status = macPollLinkStatus(ÐD1); + if (current_link_status != netif_is_link_up(thisif)) { + if (current_link_status) { + tcpip_callback_with_block((tcpip_callback_fn) netif_set_link_up, thisif, 0); + tcpip_callback_with_block(link_up_cb, this, 0); + } + else { + tcpip_callback_with_block((tcpip_callback_fn) netif_set_link_down, thisif, 0); + tcpip_callback_with_block(link_down_cb, this, 0); + } + } + } + + if (mask & FRAME_RECEIVED_ID) { + struct pbuf *p; + while (low_level_input(thisif, &p)) { + if (p != NULL) { + struct eth_hdr *ethhdr = (struct eth_hdr *)p->payload; + switch (htons(ethhdr->type)) { + /* IP or ARP packet? */ + case ETHTYPE_IP: + case ETHTYPE_ARP: + /* full packet send to tcpip_thread to process */ + if (thisif->input(p, thisif) == ERR_OK) { + break; + } + /* Falls through */ + default: + pbuf_free(p); + } + } + } + } + } +} + +/* + update called at 10Hz +*/ void AP_Networking_ChibiOS::update() { - const uint32_t ip = ntohl(lwipGetIp()); - const uint32_t nm = ntohl(lwipGetNetmask()); - const uint32_t gw = ntohl(lwipGetGateway()); + const uint32_t ip = ntohl(thisif->ip_addr.addr); + const uint32_t nm = ntohl(thisif->netmask.addr); + const uint32_t gw = ntohl(thisif->gw.addr); if (ip != activeSettings.ip || nm != activeSettings.nm || diff --git a/libraries/AP_Networking/AP_Networking_ChibiOS.h b/libraries/AP_Networking/AP_Networking_ChibiOS.h index 71ebfb57a62504..96bd7977ec0538 100644 --- a/libraries/AP_Networking/AP_Networking_ChibiOS.h +++ b/libraries/AP_Networking/AP_Networking_ChibiOS.h @@ -18,10 +18,17 @@ class AP_Networking_ChibiOS : public AP_Networking_Backend private: bool allocate_buffers(void); + void thread(void); + static void link_up_cb(void*); + static void link_down_cb(void*); + static int8_t ethernetif_init(struct netif *netif); + static int8_t low_level_output(struct netif *netif, struct pbuf *p); + static bool low_level_input(struct netif *netif, struct pbuf **pbuf); -private: struct lwipthread_opts *lwip_options; uint8_t macaddr[6]; + + struct netif *thisif; }; #endif // AP_NETWORKING_BACKEND_CHIBIOS diff --git a/libraries/AP_Networking/AP_Networking_PPP.cpp b/libraries/AP_Networking/AP_Networking_PPP.cpp index 8e296a1abbfa20..d421c9b4e0a9ea 100644 --- a/libraries/AP_Networking/AP_Networking_PPP.cpp +++ b/libraries/AP_Networking/AP_Networking_PPP.cpp @@ -12,20 +12,11 @@ #include #include #include +#include extern const AP_HAL::HAL& hal; -#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS -/* - uint32_t timestamp in smallest available units - */ -uint32_t sys_jiffies(void) -{ - return AP_HAL::micros(); -} -#endif - #if LWIP_TCPIP_CORE_LOCKING #define LWIP_TCPIP_LOCK() sys_lock_tcpip_core() #define LWIP_TCPIP_UNLOCK() sys_unlock_tcpip_core() @@ -42,7 +33,7 @@ uint32_t AP_Networking_PPP::ppp_output_cb(ppp_pcb *pcb, const void *data, uint32 auto &driver = *(AP_Networking_PPP *)ctx; LWIP_UNUSED_ARG(pcb); uint32_t remaining = len; - uint8_t *ptr = const_cast((const uint8_t *)data); + const uint8_t *ptr = (const uint8_t *)data; while (remaining > 0) { auto n = driver.uart->write(ptr, remaining); if (n > 0) { @@ -132,12 +123,12 @@ void AP_Networking_PPP::ppp_status_callback(struct ppp_pcb_s *pcb, int code, voi */ bool AP_Networking_PPP::init() { - uart = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_PPP, 0); + auto &sm = AP::serialmanager(); + uart = sm.find_serial(AP_SerialManager::SerialProtocol_PPP, 0); if (uart == nullptr) { return false; } - uart->set_unbuffered_writes(true); - + pppif = new netif; if (pppif == nullptr) { return false; @@ -163,7 +154,7 @@ bool AP_Networking_PPP::init() GCS_SEND_TEXT(MAV_SEVERITY_INFO, "PPP: started"); hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking_PPP::ppp_loop, void), "ppp", - 2048, AP_HAL::Scheduler::PRIORITY_UART, 0); + 2048, AP_HAL::Scheduler::PRIORITY_NET, 0); return true; } @@ -186,6 +177,7 @@ void AP_Networking_PPP::ppp_loop(void) // ensure this thread owns the uart uart->begin(0); + uart->set_unbuffered_writes(true); while (true) { uint8_t buf[1024]; @@ -194,9 +186,8 @@ void AP_Networking_PPP::ppp_loop(void) LWIP_TCPIP_LOCK(); pppos_input(ppp, buf, n); LWIP_TCPIP_UNLOCK(); - hal.scheduler->delay_microseconds(100); } else { - hal.scheduler->delay_microseconds(1000); + hal.scheduler->delay_microseconds(200); } } } diff --git a/libraries/AP_Networking/config/lwipopts.h b/libraries/AP_Networking/config/lwipopts.h new file mode 100644 index 00000000000000..8c6789f1ad841c --- /dev/null +++ b/libraries/AP_Networking/config/lwipopts.h @@ -0,0 +1,365 @@ +/* + * Copyright (c) 2001-2003 Swedish Institute of Computer Science. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without modification, + * are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * 3. The name of the author may not be used to endorse or promote products + * derived from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR IMPLIED + * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF + * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT + * SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, + * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT + * OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING + * IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY + * OF SUCH DAMAGE. + * + * This file is part of the lwIP TCP/IP stack. + * + * Author: Adam Dunkels + * + */ +#pragma once + +#ifdef __cplusplus +extern "C" +{ +#endif + +#ifdef LWIP_OPTTEST_FILE +#include "lwipopts_test.h" +#else /* LWIP_OPTTEST_FILE */ + +#define LWIP_IPV4 1 +#define LWIP_IPV6 0 + +#define MEM_LIBC_MALLOC 1 +#define MEMP_MEM_MALLOC 1 +#define LWIP_NETCONN_SEM_PER_THREAD 0 + + +#define NO_SYS 0 +#define LWIP_SOCKET (NO_SYS==0) +#define LWIP_NETCONN (NO_SYS==0) +#define LWIP_NETIF_API (NO_SYS==0) + +#define LWIP_IGMP LWIP_IPV4 +#define LWIP_ICMP LWIP_IPV4 + +#define LWIP_SNMP LWIP_UDP +#define MIB2_STATS LWIP_SNMP +#ifdef LWIP_HAVE_MBEDTLS +#define LWIP_SNMP_V3 (LWIP_SNMP) +#endif + +#define LWIP_DNS LWIP_UDP +#define LWIP_MDNS_RESPONDER LWIP_UDP + +#define LWIP_NUM_NETIF_CLIENT_DATA (LWIP_MDNS_RESPONDER) + +#define LWIP_HAVE_LOOPIF 1 +#define LWIP_NETIF_LOOPBACK 1 +#define LWIP_LOOPBACK_MAX_PBUFS 10 + +#define TCP_LISTEN_BACKLOG 1 + +#define LWIP_COMPAT_SOCKETS 0 +#define LWIP_SO_RCVTIMEO 1 +#define LWIP_SO_RCVBUF 1 + +#define LWIP_TCPIP_CORE_LOCKING 1 + +#define LWIP_NETIF_LINK_CALLBACK 1 +#define LWIP_NETIF_STATUS_CALLBACK 1 +#define LWIP_NETIF_EXT_STATUS_CALLBACK 1 + +#define USE_PPP 1 + +#define LWIP_TIMEVAL_PRIVATE 0 +#define LWIP_FD_SET_PRIVATE 0 + +#define TCP_WND 12000 +#define TCP_SND_BUF 12000 + +// #define LWIP_DEBUG +#ifdef LWIP_DEBUG +#define LWIP_DBG_MIN_LEVEL 0 +#define PPP_DEBUG LWIP_DBG_ON +#define MEM_DEBUG LWIP_DBG_ON +#define MEMP_DEBUG LWIP_DBG_ON +#define PBUF_DEBUG LWIP_DBG_OFF +#define API_LIB_DEBUG LWIP_DBG_OFF +#define API_MSG_DEBUG LWIP_DBG_OFF +#define TCPIP_DEBUG LWIP_DBG_ON +#define NETIF_DEBUG LWIP_DBG_ON +#define SOCKETS_DEBUG LWIP_DBG_OFF +#define DNS_DEBUG LWIP_DBG_OFF +#define AUTOIP_DEBUG LWIP_DBG_OFF +#define DHCP_DEBUG LWIP_DBG_OFF +#define IP_DEBUG LWIP_DBG_OFF +#define IP_REASS_DEBUG LWIP_DBG_OFF +#define ICMP_DEBUG LWIP_DBG_OFF +#define IGMP_DEBUG LWIP_DBG_OFF +#define UDP_DEBUG LWIP_DBG_OFF +#define TCP_DEBUG LWIP_DBG_ON +#define TCP_INPUT_DEBUG LWIP_DBG_ON +#define TCP_OUTPUT_DEBUG LWIP_DBG_ON +#define TCP_RTO_DEBUG LWIP_DBG_OFF +#define TCP_CWND_DEBUG LWIP_DBG_OFF +#define TCP_WND_DEBUG LWIP_DBG_OFF +#define TCP_FR_DEBUG LWIP_DBG_OFF +#define TCP_QLEN_DEBUG LWIP_DBG_OFF +#define TCP_RST_DEBUG LWIP_DBG_OFF +#endif + +#define LWIP_DBG_TYPES_ON (LWIP_DBG_ON|LWIP_DBG_TRACE|LWIP_DBG_STATE|LWIP_DBG_FRESH|LWIP_DBG_HALT) + + +/* ---------- Memory options ---------- */ +/* MEM_ALIGNMENT: should be set to the alignment of the CPU for which + lwIP is compiled. 4 byte alignment -> define MEM_ALIGNMENT to 4, 2 + byte alignment -> define MEM_ALIGNMENT to 2. */ +/* MSVC port: intel processors don't need 4-byte alignment, + but are faster that way! */ +#define MEM_ALIGNMENT 4U + +/* MEM_SIZE: the size of the heap memory. If the application will send +a lot of data that needs to be copied, this should be set high. */ +#define MEM_SIZE 10240 + +/* MEMP_NUM_PBUF: the number of memp struct pbufs. If the application + sends a lot of data out of ROM (or other static memory), this + should be set high. */ +#define MEMP_NUM_PBUF 100 +/* MEMP_NUM_RAW_PCB: the number of UDP protocol control blocks. One + per active RAW "connection". */ +#define MEMP_NUM_RAW_PCB 3 +/* MEMP_NUM_UDP_PCB: the number of UDP protocol control blocks. One + per active UDP "connection". */ +#define MEMP_NUM_UDP_PCB 8 +/* MEMP_NUM_TCP_PCB: the number of simultaneously active TCP + connections. */ +#define MEMP_NUM_TCP_PCB 5 +/* MEMP_NUM_TCP_PCB_LISTEN: the number of listening TCP + connections. */ +#define MEMP_NUM_TCP_PCB_LISTEN 8 +/* MEMP_NUM_TCP_SEG: the number of simultaneously queued TCP + segments. */ +#define MEMP_NUM_TCP_SEG 16 +/* MEMP_NUM_SYS_TIMEOUT: the number of simultaneously active + timeouts. */ +#define MEMP_NUM_SYS_TIMEOUT 17 + +/* The following four are used only with the sequential API and can be + set to 0 if the application only will use the raw API. */ +/* MEMP_NUM_NETBUF: the number of struct netbufs. */ +#define MEMP_NUM_NETBUF 100 +/* MEMP_NUM_NETCONN: the number of struct netconns. */ +#define MEMP_NUM_NETCONN 64 +/* MEMP_NUM_TCPIP_MSG_*: the number of struct tcpip_msg, which is used + for sequential API communication and incoming packets. Used in + src/api/tcpip.c. */ +#define MEMP_NUM_TCPIP_MSG_API 16 +#define MEMP_NUM_TCPIP_MSG_INPKT 16 + + +/* ---------- Pbuf options ---------- */ +/* PBUF_POOL_SIZE: the number of buffers in the pbuf pool. */ +#define PBUF_POOL_SIZE 120 + +/* PBUF_POOL_BUFSIZE: the size of each pbuf in the pbuf pool. */ +#define PBUF_POOL_BUFSIZE 256 + +/** SYS_LIGHTWEIGHT_PROT + * define SYS_LIGHTWEIGHT_PROT in lwipopts.h if you want inter-task protection + * for certain critical regions during buffer allocation, deallocation and memory + * allocation and deallocation. + */ +#define SYS_LIGHTWEIGHT_PROT (NO_SYS==0) + + +/* ---------- TCP options ---------- */ +#define LWIP_TCP 1 +#define TCP_TTL 255 + +#define LWIP_ALTCP (LWIP_TCP) +#ifdef LWIP_HAVE_MBEDTLS +#define LWIP_ALTCP_TLS (LWIP_TCP) +#define LWIP_ALTCP_TLS_MBEDTLS (LWIP_TCP) +#endif + + +/* Controls if TCP should queue segments that arrive out of + order. Define to 0 if your device is low on memory. */ +#define TCP_QUEUE_OOSEQ 1 + +/* TCP Maximum segment size. */ +#define TCP_MSS 1024 + +/* TCP sender buffer space (bytes). */ +#ifndef TCP_SND_BUF +#define TCP_SND_BUF 2048 +#endif + +/* TCP sender buffer space (pbufs). This must be at least = 2 * + TCP_SND_BUF/TCP_MSS for things to work. */ +#define TCP_SND_QUEUELEN (4 * TCP_SND_BUF/TCP_MSS) + +/* TCP writable space (bytes). This must be less than or equal + to TCP_SND_BUF. It is the amount of space which must be + available in the tcp snd_buf for select to return writable */ +#define TCP_SNDLOWAT (TCP_SND_BUF/2) + +/* TCP receive window. */ +#ifndef TCP_WND +#define TCP_WND (20 * 1024) +#endif + +/* Maximum number of retransmissions of data segments. */ +#define TCP_MAXRTX 12 + +/* Maximum number of retransmissions of SYN segments. */ +#define TCP_SYNMAXRTX 4 + + +/* ---------- ARP options ---------- */ +#define LWIP_ARP 1 +#define ARP_TABLE_SIZE 10 +#define ARP_QUEUEING 1 + + +/* ---------- IP options ---------- */ +/* Define IP_FORWARD to 1 if you wish to have the ability to forward + IP packets across network interfaces. If you are going to run lwIP + on a device with only one network interface, define this to 0. */ +#define IP_FORWARD 1 + +/* IP reassembly and segmentation.These are orthogonal even + * if they both deal with IP fragments */ +#define IP_REASSEMBLY 1 +#define IP_REASS_MAX_PBUFS (10 * ((1500 + PBUF_POOL_BUFSIZE - 1) / PBUF_POOL_BUFSIZE)) +#define MEMP_NUM_REASSDATA IP_REASS_MAX_PBUFS +#define IP_FRAG 1 +#define IPV6_FRAG_COPYHEADER 1 + +/* ---------- ICMP options ---------- */ +#define ICMP_TTL 255 + + +/* ---------- DHCP options ---------- */ +/* Define LWIP_DHCP to 1 if you want DHCP configuration of + interfaces. */ +#define LWIP_DHCP 1 + +/* 1 if you want to do an ARP check on the offered address + (recommended). */ +#define DHCP_DOES_ARP_CHECK (LWIP_DHCP) + + +/* ---------- AUTOIP options ------- */ +#define LWIP_AUTOIP (LWIP_DHCP) +#define LWIP_DHCP_AUTOIP_COOP (LWIP_DHCP && LWIP_AUTOIP) + + +/* ---------- UDP options ---------- */ +#define LWIP_UDP 1 +#define LWIP_UDPLITE LWIP_UDP +#define UDP_TTL 255 + + +/* ---------- RAW options ---------- */ +#define LWIP_RAW 1 + + +/* ---------- Statistics options ---------- */ + +#define LWIP_STATS 1 +#define LWIP_STATS_DISPLAY 1 + +#if LWIP_STATS +#define LINK_STATS 1 +#define IP_STATS 1 +#define ICMP_STATS 1 +#define IGMP_STATS 1 +#define IPFRAG_STATS 1 +#define UDP_STATS 1 +#define TCP_STATS 1 +#define MEM_STATS 1 +#define MEMP_STATS 1 +#define PBUF_STATS 1 +#define SYS_STATS 1 +#endif /* LWIP_STATS */ + +/* ---------- NETBIOS options ---------- */ +#define LWIP_NETBIOS_RESPOND_NAME_QUERY 1 + +/* ---------- PPP options ---------- */ + +#define PPP_SUPPORT 1 /* Set > 0 for PPP */ + +#if PPP_SUPPORT + +#define NUM_PPP 1 /* Max PPP sessions. */ + + +/* Select modules to enable. Ideally these would be set in the makefile but + * we're limited by the command line length so you need to modify the settings + * in this file. + */ +#define PPPOE_SUPPORT 0 +#define PPPOS_SUPPORT 1 + +#define PAP_SUPPORT 0 /* Set > 0 for PAP. */ +#define CHAP_SUPPORT 0 /* Set > 0 for CHAP. */ +#define MSCHAP_SUPPORT 0 /* Set > 0 for MSCHAP */ +#define CBCP_SUPPORT 0 /* Set > 0 for CBCP (NOT FUNCTIONAL!) */ +#define CCP_SUPPORT 0 /* Set > 0 for CCP */ +#define VJ_SUPPORT 1 /* Set > 0 for VJ header compression. */ +#define MD5_SUPPORT 0 /* Set > 0 for MD5 (see also CHAP) */ + +#endif /* PPP_SUPPORT */ + +#endif /* LWIP_OPTTEST_FILE */ + +/* The following defines must be done even in OPTTEST mode: */ + +#if !defined(NO_SYS) || !NO_SYS /* default is 0 */ +void sys_check_core_locking(void); +#define LWIP_ASSERT_CORE_LOCKED() sys_check_core_locking() +#endif + +#ifndef LWIP_PLATFORM_ASSERT +/* Define LWIP_PLATFORM_ASSERT to something to catch missing stdio.h includes */ +void ap_networking_platform_assert(const char *msg, int line, const char *file); +#define LWIP_PLATFORM_ASSERT(x) ap_networking_platform_assert(x, __LINE__, __FILE__) +#endif + +/* + map LWIP debugging onto ap_networking_printf to allow for easier + redirection to a file or dedicated serial port + */ +#ifdef __cplusplus +extern "C" { +#endif +int ap_networking_printf(const char *fmt, ...); +#ifdef __cplusplus +} +#endif +#define LWIP_PLATFORM_DIAG(x) do {ap_networking_printf x; } while(0) + +// #define AP_NETWORKING_LWIP_DEBUG_FILE "lwip.log" + +#ifdef __cplusplus +} +#endif + diff --git a/libraries/AP_Networking/lwip_hal/arch/sys_arch.cpp b/libraries/AP_Networking/lwip_hal/arch/sys_arch.cpp new file mode 100644 index 00000000000000..ad9c8675881753 --- /dev/null +++ b/libraries/AP_Networking/lwip_hal/arch/sys_arch.cpp @@ -0,0 +1,538 @@ +/* + port of lwip to ArduPilot AP_HAL + */ + +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +extern "C" { +#include "lwip/debug.h" +#include "lwip/def.h" +#include "lwip/sys.h" +#include "lwip/opt.h" +#include "lwip/stats.h" +#include "lwip/tcpip.h" +} + +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#include +#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +#include "hal.h" +#include "../../../libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h" +#endif + +extern const AP_HAL::HAL &hal; + +unsigned int +lwip_port_rand(void) +{ + return (u32_t)rand(); +} + +static HAL_Semaphore lwprot_mutex; +static HAL_Semaphore tcpip_mutex; + +struct sys_mbox_msg { + struct sys_mbox_msg *next; + void *msg; +}; + +#define SYS_MBOX_SIZE 128 + +struct sys_mbox { + int first, last; + void *msgs[SYS_MBOX_SIZE]; + struct sys_sem *not_empty; + struct sys_sem *not_full; + struct sys_sem *mutex; + int wait_send; +}; + +struct sys_sem { +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + sem_t sem; +#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS + semaphore_t sem; +#else +#error "Need sys_sem implementation" +#endif +}; + +static struct sys_sem *sys_sem_new_internal(u8_t count); +static void sys_sem_free_internal(struct sys_sem *sem); + +/* Threads */ + +struct thread_wrapper_data { + lwip_thread_fn function; + void *arg; +}; + +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +static void * +thread_wrapper(void *arg) +{ + auto *thread_data = (struct thread_wrapper_data *)arg; + thread_data->function(thread_data->arg); + return NULL; +} +#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +static void +thread_wrapper(void *arg) +{ + auto *thread_data = (struct thread_wrapper_data *)arg; + thread_data->function(thread_data->arg); +} +#endif + +sys_thread_t +sys_thread_new(const char *name, lwip_thread_fn function, void *arg, int stacksize, int prio) +{ + sys_thread_t ret = nullptr; + struct thread_wrapper_data *thread_data; + + thread_data = new thread_wrapper_data; + thread_data->arg = arg; + thread_data->function = function; + +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + pthread_t t; + if (pthread_create(&t, NULL, thread_wrapper, thread_data) == 0) { + pthread_setname_np(t, name); + ret = (void*)t; + } +#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS + ret = thread_create_alloc(THD_WORKING_AREA_SIZE(stacksize+1024), + name, + prio+60, // need to use HAL thread call + thread_wrapper, + thread_data); +#endif + if (ret == nullptr) { + AP_HAL::panic("Failed to create thread %s", name); + } + return ret; +} + +void sys_lock_tcpip_core(void) +{ + if (hal.scheduler != nullptr) { + tcpip_mutex.take_blocking(); + } +} + +void sys_unlock_tcpip_core(void) +{ + if (hal.scheduler != nullptr) { + tcpip_mutex.give(); + } +} + +void sys_mark_tcpip_thread(void) +{ +} + +void sys_check_core_locking(void) +{ + /* Embedded systems should check we are NOT in an interrupt + * context here */ +} + +/*-----------------------------------------------------------------------------------*/ +/* Mailbox */ +err_t +sys_mbox_new(struct sys_mbox **mb, int size) +{ + struct sys_mbox *mbox; + LWIP_UNUSED_ARG(size); + + mbox = new sys_mbox; + if (mbox == NULL) { + return ERR_MEM; + } + mbox->first = mbox->last = 0; + mbox->not_empty = sys_sem_new_internal(0); + mbox->not_full = sys_sem_new_internal(0); + mbox->mutex = sys_sem_new_internal(1); + mbox->wait_send = 0; + + *mb = mbox; + return ERR_OK; +} + +void +sys_mbox_free(struct sys_mbox **mb) +{ + if ((mb != NULL) && (*mb != SYS_MBOX_NULL)) { + struct sys_mbox *mbox = *mb; + sys_arch_sem_wait(&mbox->mutex, 0); + + sys_sem_free_internal(mbox->not_empty); + sys_sem_free_internal(mbox->not_full); + sys_sem_free_internal(mbox->mutex); + mbox->not_empty = mbox->not_full = mbox->mutex = NULL; + /* LWIP_DEBUGF("sys_mbox_free: mbox 0x%lx\n", mbox); */ + delete mbox; + } +} + +err_t +sys_mbox_trypost(struct sys_mbox **mb, void *msg) +{ + u8_t first; + struct sys_mbox *mbox; + LWIP_ASSERT("invalid mbox", (mb != NULL) && (*mb != NULL)); + mbox = *mb; + + sys_arch_sem_wait(&mbox->mutex, 0); + + LWIP_DEBUGF(SYS_DEBUG, ("sys_mbox_trypost: mbox %p msg %p\n", + (void *)mbox, (void *)msg)); + + if ((mbox->last + 1) >= (mbox->first + SYS_MBOX_SIZE)) { + sys_sem_signal(&mbox->mutex); + return ERR_MEM; + } + + mbox->msgs[mbox->last % SYS_MBOX_SIZE] = msg; + + if (mbox->last == mbox->first) { + first = 1; + } else { + first = 0; + } + + mbox->last++; + + if (first) { + sys_sem_signal(&mbox->not_empty); + } + + sys_sem_signal(&mbox->mutex); + + return ERR_OK; +} + +void +sys_mbox_post(struct sys_mbox **mb, void *msg) +{ + u8_t first; + struct sys_mbox *mbox; + LWIP_ASSERT("invalid mbox", (mb != NULL) && (*mb != NULL)); + mbox = *mb; + + sys_arch_sem_wait(&mbox->mutex, 0); + + LWIP_DEBUGF(SYS_DEBUG, ("sys_mbox_post: mbox %p msg %p\n", (void *)mbox, (void *)msg)); + + while ((mbox->last + 1) >= (mbox->first + SYS_MBOX_SIZE)) { + mbox->wait_send++; + sys_sem_signal(&mbox->mutex); + sys_arch_sem_wait(&mbox->not_full, 0); + sys_arch_sem_wait(&mbox->mutex, 0); + mbox->wait_send--; + } + + mbox->msgs[mbox->last % SYS_MBOX_SIZE] = msg; + + if (mbox->last == mbox->first) { + first = 1; + } else { + first = 0; + } + + mbox->last++; + + if (first) { + sys_sem_signal(&mbox->not_empty); + } + + sys_sem_signal(&mbox->mutex); +} + +u32_t +sys_arch_mbox_tryfetch(struct sys_mbox **mb, void **msg) +{ + struct sys_mbox *mbox = *mb; + + sys_arch_sem_wait(&mbox->mutex, 0); + + if (mbox->first == mbox->last) { + sys_sem_signal(&mbox->mutex); + return SYS_MBOX_EMPTY; + } + + if (msg != NULL) { + LWIP_DEBUGF(SYS_DEBUG, ("sys_mbox_tryfetch: mbox %p msg %p\n", (void *)mbox, *msg)); + *msg = mbox->msgs[mbox->first % SYS_MBOX_SIZE]; + } else { + LWIP_DEBUGF(SYS_DEBUG, ("sys_mbox_tryfetch: mbox %p, null msg\n", (void *)mbox)); + } + + mbox->first++; + + if (mbox->wait_send) { + sys_sem_signal(&mbox->not_full); + } + + sys_sem_signal(&mbox->mutex); + + return 0; +} + +u32_t +sys_arch_mbox_fetch(struct sys_mbox **mb, void **msg, u32_t timeout) +{ + struct sys_mbox *mbox; + LWIP_ASSERT("invalid mbox", (mb != NULL) && (*mb != NULL)); + mbox = *mb; + + /* The mutex lock is quick so we don't bother with the timeout + stuff here. */ + sys_arch_sem_wait(&mbox->mutex, 0); + + while (mbox->first == mbox->last) { + sys_sem_signal(&mbox->mutex); + + /* We block while waiting for a mail to arrive in the mailbox. We + must be prepared to timeout. */ + if (timeout != 0) { + u32_t time_needed = sys_arch_sem_wait(&mbox->not_empty, timeout); + + if (time_needed == SYS_ARCH_TIMEOUT) { + return SYS_ARCH_TIMEOUT; + } + } else { + sys_arch_sem_wait(&mbox->not_empty, 0); + } + + sys_arch_sem_wait(&mbox->mutex, 0); + } + + if (msg != NULL) { + LWIP_DEBUGF(SYS_DEBUG, ("sys_mbox_fetch: mbox %p msg %p\n", (void *)mbox, *msg)); + *msg = mbox->msgs[mbox->first % SYS_MBOX_SIZE]; + } else { + LWIP_DEBUGF(SYS_DEBUG, ("sys_mbox_fetch: mbox %p, null msg\n", (void *)mbox)); + } + + mbox->first++; + + if (mbox->wait_send) { + sys_sem_signal(&mbox->not_full); + } + + sys_sem_signal(&mbox->mutex); + + return 0; +} + +/*-----------------------------------------------------------------------------------*/ +/* Semaphore */ +static struct sys_sem * +sys_sem_new_internal(u8_t count) +{ + auto *ret = new sys_sem; + if (ret != nullptr) { +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + sem_init(&ret->sem, 0, count); +#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS + chSemObjectInit(&ret->sem, (cnt_t)count); +#endif + } + return ret; +} + +err_t +sys_sem_new(struct sys_sem **sem, u8_t count) +{ + *sem = sys_sem_new_internal(count); + if (*sem == NULL) { + return ERR_MEM; + } + return ERR_OK; +} + +u32_t +sys_arch_sem_wait(struct sys_sem **s, u32_t timeout_ms) +{ + struct sys_sem *sem = *s; +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + if (timeout_ms == 0) { + sem_wait(&sem->sem); + return 0; + } + struct timespec ts; + if (clock_gettime(CLOCK_REALTIME, &ts) != 0) { + return SYS_ARCH_TIMEOUT; + } + ts.tv_sec += timeout_ms/1000UL; + ts.tv_nsec += (timeout_ms % 1000U) * 1000000UL; + if (ts.tv_nsec >= 1000000000L) { + ts.tv_sec++; + ts.tv_nsec -= 1000000000L; + } + auto ret = sem_timedwait(&sem->sem, &ts); + if (ret != 0) { + return SYS_ARCH_TIMEOUT; + } +#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS + chSysLock(); + sysinterval_t tmo = timeout_ms > 0 ? MIN(TIME_MAX_INTERVAL, TIME_MS2I((time_msecs_t)timeout_ms)) : TIME_INFINITE; + if (chSemWaitTimeoutS(&sem->sem, tmo) != MSG_OK) { + chSysUnlock(); + return SYS_ARCH_TIMEOUT; + } + chSysUnlock(); +#endif + return 0; +} + +void +sys_sem_signal(struct sys_sem **s) +{ + struct sys_sem *sem = *s; +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + sem_post(&sem->sem); +#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS + chSemSignal(&sem->sem); +#endif +} + +static void +sys_sem_free_internal(struct sys_sem *sem) +{ + delete sem; +} + +void +sys_sem_free(struct sys_sem **sem) +{ + if ((sem != NULL) && (*sem != SYS_SEM_NULL)) { + sys_sem_free_internal(*sem); + } +} + +/*-----------------------------------------------------------------------------------*/ +/* Mutex */ +/** Create a new mutex + * @param mutex pointer to the mutex to create + * @return a new mutex */ +err_t +sys_mutex_new(struct sys_mutex **mutex) +{ + auto *sem = new HAL_Semaphore; + if (sem == nullptr) { + return ERR_MEM; + } + *mutex = (struct sys_mutex *)sem; + return ERR_OK; +} + +/** Lock a mutex + * @param mutex the mutex to lock */ +void +sys_mutex_lock(struct sys_mutex **mutex) +{ + auto *sem = (HAL_Semaphore *)*mutex; + if (hal.scheduler != nullptr) { + sem->take_blocking(); + } +} + +/** Unlock a mutex + * @param mutex the mutex to unlock */ +void +sys_mutex_unlock(struct sys_mutex **mutex) +{ + auto *sem = (HAL_Semaphore *)*mutex; + if (hal.scheduler != nullptr) { + sem->give(); + } +} + +/** Delete a mutex + * @param mutex the mutex to delete */ +void +sys_mutex_free(struct sys_mutex **mutex) +{ + auto *sem = (HAL_Semaphore *)*mutex; + delete sem; +} + + +/*-----------------------------------------------------------------------------------*/ +/* Time */ +u32_t +sys_now(void) +{ + return AP_HAL::millis(); +} + +u32_t +sys_jiffies(void) +{ + return AP_HAL::micros(); +} + +/*-----------------------------------------------------------------------------------*/ +/* Init */ + +void +sys_init(void) +{ +} + +/*-----------------------------------------------------------------------------------*/ +/* Critical section */ +/** sys_prot_t sys_arch_protect(void) + +This optional function does a "fast" critical region protection and returns +the previous protection level. This function is only called during very short +critical regions. An embedded system which supports ISR-based drivers might +want to implement this function by disabling interrupts. Task-based systems +might want to implement this by using a mutex or disabling tasking. This +function should support recursive calls from the same task or interrupt. In +other words, sys_arch_protect() could be called while already protected. In +that case the return value indicates that it is already protected. + +sys_arch_protect() is only required if your port is supporting an operating +system. +*/ +sys_prot_t +sys_arch_protect(void) +{ + if (hal.scheduler != nullptr) { + lwprot_mutex.take_blocking(); + } + return 0; +} + +/** void sys_arch_unprotect(sys_prot_t pval) + +This optional function does a "fast" set of critical region protection to the +value specified by pval. See the documentation for sys_arch_protect() for +more information. This function is only required if your port is supporting +an operating system. +*/ +void +sys_arch_unprotect(sys_prot_t pval) +{ + LWIP_UNUSED_ARG(pval); + if (hal.scheduler != nullptr) { + lwprot_mutex.give(); + } +} + diff --git a/libraries/AP_Networking/lwip_hal/include/arch/cc.h b/libraries/AP_Networking/lwip_hal/include/arch/cc.h new file mode 100644 index 00000000000000..56747da1ffef0f --- /dev/null +++ b/libraries/AP_Networking/lwip_hal/include/arch/cc.h @@ -0,0 +1,21 @@ +#pragma once + +#include +#include + +#ifdef __cplusplus +extern "C" +{ +#endif + +#define LWIP_ERRNO_STDINCLUDE 1 + +extern unsigned int lwip_port_rand(void); +#define LWIP_RAND() (lwip_port_rand()) + +typedef uint32_t sys_prot_t; + +#ifdef __cplusplus +} +#endif + diff --git a/libraries/AP_Networking/lwip_hal/include/arch/sys_arch.h b/libraries/AP_Networking/lwip_hal/include/arch/sys_arch.h new file mode 100644 index 00000000000000..da48ac6b81820f --- /dev/null +++ b/libraries/AP_Networking/lwip_hal/include/arch/sys_arch.h @@ -0,0 +1,49 @@ +#pragma once + +#ifdef __cplusplus +extern "C" +{ +#endif + +#define SYS_MBOX_NULL NULL +#define SYS_SEM_NULL NULL + +/*typedef u32_t sys_prot_t;*/ + +struct sys_sem; +typedef struct sys_sem * sys_sem_t; +#define sys_sem_valid(sem) (((sem) != NULL) && (*(sem) != NULL)) +#define sys_sem_valid_val(sem) ((sem) != NULL) +#define sys_sem_set_invalid(sem) do { if((sem) != NULL) { *(sem) = NULL; }}while(0) +#define sys_sem_set_invalid_val(sem) do { (sem) = NULL; }while(0) + +struct sys_mutex; +typedef struct sys_mutex * sys_mutex_t; +#define sys_mutex_valid(mutex) sys_sem_valid(mutex) +#define sys_mutex_set_invalid(mutex) sys_sem_set_invalid(mutex) + +struct sys_mbox; +typedef struct sys_mbox * sys_mbox_t; +#define sys_mbox_valid(mbox) sys_sem_valid(mbox) +#define sys_mbox_valid_val(mbox) sys_sem_valid_val(mbox) +#define sys_mbox_set_invalid(mbox) sys_sem_set_invalid(mbox) +#define sys_mbox_set_invalid_val(mbox) sys_sem_set_invalid_val(mbox) + +typedef void *sys_thread_t; + +void sys_mark_tcpip_thread(void); +#define LWIP_MARK_TCPIP_THREAD() sys_mark_tcpip_thread() + +#if LWIP_TCPIP_CORE_LOCKING +void sys_lock_tcpip_core(void); +#define LOCK_TCPIP_CORE() sys_lock_tcpip_core() +void sys_unlock_tcpip_core(void); +#define UNLOCK_TCPIP_CORE() sys_unlock_tcpip_core() +#endif + +struct timeval; + +#ifdef __cplusplus +} +#endif + diff --git a/libraries/AP_Networking/wscript b/libraries/AP_Networking/wscript new file mode 100644 index 00000000000000..64d985c6ce0e0d --- /dev/null +++ b/libraries/AP_Networking/wscript @@ -0,0 +1,36 @@ +#!/usr/bin/env python3 + +import pathlib + + +def configure(cfg): + extra_src = [ + 'modules/ChibiOS/ext/lwip/src/core/*c', + 'modules/ChibiOS/ext/lwip/src/core/ipv4/*c', + 'modules/ChibiOS/ext/lwip/src/api/*c', + 'modules/ChibiOS/ext/lwip/src/netif/*c', + 'modules/ChibiOS/ext/lwip/src/netif/ppp/*c', + ] + + extra_src_inc = [ + 'modules/ChibiOS/ext/lwip/src/include', + ] + + if cfg.env.BOARD_CLASS == "SITL": + extra_src.extend(['libraries/AP_Networking/lwip_hal/arch/*cpp']) + extra_src_inc.extend(['libraries/AP_Networking/config', + 'libraries/AP_Networking/lwip_hal/include']) + + if cfg.env.BOARD_CLASS == "ChibiOS": + extra_src.extend(['libraries/AP_Networking/lwip_hal/arch/*cpp']) + extra_src_inc.extend(['libraries/AP_Networking/config', + 'libraries/AP_Networking/lwip_hal/include']) + + cfg.env.AP_LIB_EXTRA_SOURCES['AP_Networking'] = [] + for pattern in extra_src: + s = cfg.srcnode.ant_glob(pattern, dir=False, src=True) + for x in s: + cfg.env.AP_LIB_EXTRA_SOURCES['AP_Networking'].append(str(x)) + + for inc in extra_src_inc: + cfg.env.INCLUDES += [str(cfg.srcnode.make_node(inc))] From d289ba0181f82a8e91ec513d24ba90b9b613559f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 06:38:56 +1100 Subject: [PATCH 0314/1335] AP_Networking: removed SLIP PPP is the better choice --- libraries/AP_Networking/AP_Networking.cpp | 10 -- .../AP_Networking/AP_Networking_Config.h | 4 - .../AP_Networking/AP_Networking_SLIP.cpp | 98 ------------------- libraries/AP_Networking/AP_Networking_SLIP.h | 27 ----- 4 files changed, 139 deletions(-) delete mode 100644 libraries/AP_Networking/AP_Networking_SLIP.cpp delete mode 100644 libraries/AP_Networking/AP_Networking_SLIP.h diff --git a/libraries/AP_Networking/AP_Networking.cpp b/libraries/AP_Networking/AP_Networking.cpp index 32bbf51de50c96..2eaee5dfde61c7 100644 --- a/libraries/AP_Networking/AP_Networking.cpp +++ b/libraries/AP_Networking/AP_Networking.cpp @@ -24,10 +24,6 @@ extern const AP_HAL::HAL& hal; #include -#if AP_NETWORKING_BACKEND_SLIP -#include "AP_Networking_SLIP.h" -#endif - #if AP_NETWORKING_BACKEND_PPP #include "AP_Networking_PPP.h" #endif @@ -140,12 +136,6 @@ void AP_Networking::init() } #endif -#if AP_NETWORKING_BACKEND_SLIP - if (backend == nullptr && AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_SLIP, 0)) { - backend = new AP_Networking_SLIP(*this); - } -#endif - #if AP_NETWORKING_BACKEND_CHIBIOS if (backend == nullptr) { backend = new AP_Networking_ChibiOS(*this); diff --git a/libraries/AP_Networking/AP_Networking_Config.h b/libraries/AP_Networking/AP_Networking_Config.h index dcecd2be3a9333..b08b936e3b9ff0 100644 --- a/libraries/AP_Networking/AP_Networking_Config.h +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -31,10 +31,6 @@ #define AP_NETWORKING_BACKEND_PPP (AP_NETWORKING_BACKEND_DEFAULT_ENABLED) #endif -#ifndef AP_NETWORKING_BACKEND_SLIP -#define AP_NETWORKING_BACKEND_SLIP 0 -#endif - #ifndef AP_NETWORKING_BACKEND_SITL #define AP_NETWORKING_BACKEND_SITL (AP_NETWORKING_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_SITL)) #endif diff --git a/libraries/AP_Networking/AP_Networking_SLIP.cpp b/libraries/AP_Networking/AP_Networking_SLIP.cpp deleted file mode 100644 index b1e5085b5d64cf..00000000000000 --- a/libraries/AP_Networking/AP_Networking_SLIP.cpp +++ /dev/null @@ -1,98 +0,0 @@ - -#include "AP_Networking_Config.h" - -#if AP_NETWORKING_BACKEND_SLIP - -#include "AP_Networking_SLIP.h" -#include - -#include -#include -#include -#include - -#include - -extern const AP_HAL::HAL& hal; -AP_HAL::UARTDriver *AP_Networking_SLIP::uart; - -/* - initialise SLIP network backend using LWIP - */ -bool AP_Networking_SLIP::init() -{ - uart = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_SLIP, 0); - if (uart == nullptr) { - return false; - } - uart->set_unbuffered_writes(true); - - slipif = new netif; - if (slipif == nullptr) { - return false; - } - - // no dynamic IPs for SLIP - activeSettings.ip = frontend.get_ip_param(); - activeSettings.gw = frontend.get_gateway_param(); - activeSettings.nm = frontend.get_netmask_param(); - activeSettings.last_change_ms = AP_HAL::millis(); - - const ip4_addr_t ipaddr {htonl(activeSettings.ip)}; - const ip4_addr_t netmask {htonl(activeSettings.nm)}; - const ip4_addr_t gw {htonl(activeSettings.gw)}; - - tcpip_init(NULL, NULL); - hal.scheduler->delay(100); - - netif_add(slipif, - &ipaddr, &netmask, &gw, - &num_slip, slipif_init, ip_input); - netif_set_default(slipif); - slipif->mtu = 296; - netif_set_link_up(slipif); - netif_set_up(slipif); - - hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_Networking_SLIP::slip_loop, void), - "slip", - 8192, AP_HAL::Scheduler::PRIORITY_UART, -1); - - return true; -} - -/* - main loop for SLIP - */ -void AP_Networking_SLIP::slip_loop(void) -{ - uart->begin(0); - hal.scheduler->delay(100); - while (true) { - slipif_poll(slipif); - hal.scheduler->delay_microseconds(100); - } -} - -void sio_send(uint8_t c, void *fd) -{ - auto *uart = (AP_HAL::UARTDriver *)fd; - uart->write(c); -} - -sio_fd_t sio_open(uint8_t dev) -{ - return AP_Networking_SLIP::uart; -} - -u32_t sio_tryread(sio_fd_t fd, u8_t *data, u32_t len) -{ - auto *uart = (AP_HAL::UARTDriver *)fd; - uart->begin(0); - const auto ret = uart->read(data, len); - if (ret <= 0) { - return 0; - } - return ret; -} - -#endif // AP_NETWORKING_BACKEND_SLIP diff --git a/libraries/AP_Networking/AP_Networking_SLIP.h b/libraries/AP_Networking/AP_Networking_SLIP.h deleted file mode 100644 index a6c61d4f32ff01..00000000000000 --- a/libraries/AP_Networking/AP_Networking_SLIP.h +++ /dev/null @@ -1,27 +0,0 @@ -#pragma once - -#include "AP_Networking_Config.h" - -#ifdef AP_NETWORKING_BACKEND_SLIP -#include "AP_Networking_Backend.h" - -class AP_Networking_SLIP : public AP_Networking_Backend -{ -public: - using AP_Networking_Backend::AP_Networking_Backend; - - /* Do not allow copies */ - CLASS_NO_COPY(AP_Networking_SLIP); - - bool init() override; - - static AP_HAL::UARTDriver *uart; - -private: - void slip_loop(void); - - struct netif *slipif; - uint8_t num_slip; -}; - -#endif // AP_NETWORKING_BACKEND_SLIP From fb0a0de2f2893b42fa40ec873bf43adff9d7ea85 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 24 Dec 2023 13:53:38 +1100 Subject: [PATCH 0315/1335] waf: added env.BOARD_CLASS --- Tools/ardupilotwaf/boards.py | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index 2c9432d85eb652..dc78c9f54ba8eb 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -646,6 +646,8 @@ def configure_env(self, cfg, env): AP_BARO_PROBE_EXTERNAL_I2C_BUSES = 1, ) + env.BOARD_CLASS = "SITL" + cfg.define('AP_SIM_ENABLED', 1) cfg.define('HAL_WITH_SPI', 1) cfg.define('HAL_WITH_RAMTRON', 1) @@ -897,6 +899,8 @@ class esp32(Board): abstract = True toolchain = 'xtensa-esp32-elf' def configure_env(self, cfg, env): + env.BOARD_CLASS = "ESP32" + def expand_path(p): print("USING EXPRESSIF IDF:"+str(env.idf)) return cfg.root.find_dir(env.IDF+p).abspath() @@ -988,6 +992,7 @@ def configure_env(self, cfg, env): cfg.load('chibios') env.BOARD = self.name + env.BOARD_CLASS = "ChibiOS" env.DEFINES.update( CONFIG_HAL_BOARD = 'HAL_BOARD_CHIBIOS', @@ -1229,6 +1234,8 @@ def configure_env(self, cfg, env): self.with_can = True super(linux, self).configure_env(cfg, env) + env.BOARD_CLASS = "LINUX" + env.DEFINES.update( CONFIG_HAL_BOARD = 'HAL_BOARD_LINUX', CONFIG_HAL_BOARD_SUBTYPE = 'HAL_BOARD_SUBTYPE_LINUX_NONE', From 9456b585fae4e5d18f8c38779266a088fead583a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 24 Dec 2023 14:04:42 +1100 Subject: [PATCH 0316/1335] HAL_ChibiOS: don't link lwip bindings from ChibiOS --- libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk | 7 +------ libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py | 2 -- 2 files changed, 1 insertion(+), 8 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk b/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk index 821fcf0981229a..7d9f8a67a6550c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk @@ -68,10 +68,6 @@ ifeq ($(USE_FATFS),yes) include $(CHIBIOS)/os/various/fatfs_bindings/fatfs.mk endif -ifeq ($(USE_LWIP),yes) -include $(CHIBIOS)/os/various/lwip_bindings/lwip.mk -endif - # # Build global options ############################################################################## @@ -149,9 +145,8 @@ CSRC += $(CHIBIOS)/os/various/scsi_bindings/lib_scsi.c \ $(CHIBIOS)/os/hal/src/hal_usb_msd.c endif -ifeq ($(USE_LWIP),yes) +# evtimer used by networking CSRC += $(CHIBIOS)/os/various/evtimer.c -endif # $(TESTSRC) \ # test.c diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index 3d8a906365bf54..751ca37fc4f35f 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -910,8 +910,6 @@ def enable_networking(self, f): #endif #define CH_CFG_USE_MAILBOXES 1 ''') - self.env_vars['USE_LWIP'] = 'yes' - self.build_flags.append('USE_LWIP=yes') def write_mcu_config(self, f): '''write MCU config defines''' From 936bbeda881dea899704ec9b1cfa0e16a279e67f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 25 Dec 2023 14:25:19 +1100 Subject: [PATCH 0317/1335] AP_HAL_ChibiOS: added PRIORITY_NET --- libraries/AP_HAL_ChibiOS/Scheduler.cpp | 1 + libraries/AP_HAL_ChibiOS/Scheduler.h | 1 + 2 files changed, 2 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/Scheduler.cpp b/libraries/AP_HAL_ChibiOS/Scheduler.cpp index 5993be2e99c2a7..2f6fb5504dad02 100644 --- a/libraries/AP_HAL_ChibiOS/Scheduler.cpp +++ b/libraries/AP_HAL_ChibiOS/Scheduler.cpp @@ -697,6 +697,7 @@ uint8_t Scheduler::calculate_thread_priority(priority_base base, int8_t priority { PRIORITY_UART, APM_UART_PRIORITY}, { PRIORITY_STORAGE, APM_STORAGE_PRIORITY}, { PRIORITY_SCRIPTING, APM_SCRIPTING_PRIORITY}, + { PRIORITY_NET, APM_NET_PRIORITY}, }; for (uint8_t i=0; i Date: Mon, 25 Dec 2023 14:25:19 +1100 Subject: [PATCH 0318/1335] AP_HAL_ESP32: added PRIORITY_NET --- libraries/AP_HAL_ESP32/Scheduler.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ESP32/Scheduler.cpp b/libraries/AP_HAL_ESP32/Scheduler.cpp index f4d26dde3ae0ed..9b940f9c9f2adb 100644 --- a/libraries/AP_HAL_ESP32/Scheduler.cpp +++ b/libraries/AP_HAL_ESP32/Scheduler.cpp @@ -164,8 +164,9 @@ bool Scheduler::thread_create(AP_HAL::MemberProc proc, const char *name, uint32_ { PRIORITY_RCIN, RCIN_PRIO}, { PRIORITY_IO, IO_PRIO}, { PRIORITY_UART, UART_PRIO}, + { PRIORITY_NET, WIFI_PRIO1}, { PRIORITY_STORAGE, STORAGE_PRIO}, - { PRIORITY_SCRIPTING, IO_PRIO}, + { PRIORITY_SCRIPTING, UART_PRIO}, }; for (uint8_t i=0; i Date: Mon, 25 Dec 2023 14:25:19 +1100 Subject: [PATCH 0319/1335] AP_HAL: added PRIORITY_NET --- libraries/AP_HAL/Scheduler.h | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_HAL/Scheduler.h b/libraries/AP_HAL/Scheduler.h index eb580ebe0dd714..0f047617f0e408 100644 --- a/libraries/AP_HAL/Scheduler.h +++ b/libraries/AP_HAL/Scheduler.h @@ -115,6 +115,7 @@ class AP_HAL::Scheduler { PRIORITY_UART, PRIORITY_STORAGE, PRIORITY_SCRIPTING, + PRIORITY_NET, }; /* From ce6adcfe833c8123bbd8b76425679a38d816adb7 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 25 Dec 2023 14:25:19 +1100 Subject: [PATCH 0320/1335] AP_HAL_Linux: added PRIORITY_NET --- libraries/AP_HAL_Linux/Scheduler.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_HAL_Linux/Scheduler.cpp b/libraries/AP_HAL_Linux/Scheduler.cpp index d196ef9796b1ea..7c2cce5d2bfb3c 100644 --- a/libraries/AP_HAL_Linux/Scheduler.cpp +++ b/libraries/AP_HAL_Linux/Scheduler.cpp @@ -26,6 +26,7 @@ extern const AP_HAL::HAL& hal; #define APM_LINUX_MAX_PRIORITY 20 #define APM_LINUX_TIMER_PRIORITY 15 #define APM_LINUX_UART_PRIORITY 14 +#define APM_LINUX_NET_PRIORITY 14 #define APM_LINUX_RCIN_PRIORITY 13 #define APM_LINUX_MAIN_PRIORITY 12 #define APM_LINUX_IO_PRIORITY 10 @@ -385,6 +386,7 @@ uint8_t Scheduler::calculate_thread_priority(priority_base base, int8_t priority { PRIORITY_UART, APM_LINUX_UART_PRIORITY}, { PRIORITY_STORAGE, APM_LINUX_IO_PRIORITY}, { PRIORITY_SCRIPTING, APM_LINUX_SCRIPTING_PRIORITY}, + { PRIORITY_NET, APM_LINUX_NET_PRIORITY}, }; for (uint8_t i=0; i Date: Thu, 14 Dec 2023 15:30:54 +1100 Subject: [PATCH 0321/1335] HAL_ChibiOS: removed old lwip options --- .../AP_HAL_ChibiOS/hwdef/common/lwipopts.h | 2170 ----------------- 1 file changed, 2170 deletions(-) delete mode 100644 libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h b/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h deleted file mode 100644 index 94f839feaa0f7d..00000000000000 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/lwipopts.h +++ /dev/null @@ -1,2170 +0,0 @@ -/** - * @file - * - * lwIP Options Configuration - */ - -/* - * Copyright (c) 2001-2004 Swedish Institute of Computer Science. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without modification, - * are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. The name of the author may not be used to endorse or promote products - * derived from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR IMPLIED - * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF - * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT - * SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, - * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT - * OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING - * IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY - * OF SUCH DAMAGE. - * - * This file is part of the lwIP TCP/IP stack. - * - * Author: Adam Dunkels - * - */ -#ifndef __LWIPOPT_H__ -#define __LWIPOPT_H__ - -#include "stdio.h" -#include "stm32_util.h" - -#define LWIP_ERRNO_STDINCLUDE - -/* - ----------------------------------------------- - ---------- Platform specific locking ---------- - ----------------------------------------------- -*/ - -// #define LWIP_DEBUG -#define U16_F "u" -#define X8_F "x" -#define X16_F "x" -#define LWIP_STATS_DISPLAY 1 -#define ETHARP_STATS 1 -#define LWIP_IGMP 1 -#define MEMP_NUM_NETCONN 50 // up to 50 sockets -#define MEMP_NUM_TCP_PCB 200 -#define MEM_LIBC_MALLOC 1 -#define MEMP_MEM_MALLOC 1 -#define SO_REUSE 1 -#define SO_REUSE_RXTOALL 1 -#define DEFAULT_ACCEPTMBOX_SIZE 20 -#define MEMP_NUM_PBUF 64 -#define TCP_WND 12000 -#define TCP_SND_BUF 12000 - -/* - map LWIP debugging onto ap_networking_printf to allow for easier - redirection to a file or dedicated serial port - */ -#ifdef __cplusplus -extern "C" { -#endif -int ap_networking_printf(const char *fmt, ...); -#ifdef __cplusplus -} -#endif -#define LWIP_PLATFORM_DIAG(x) do {ap_networking_printf x; } while(0) - -#ifndef LWIP_IPV6 - // This uses an additional 18KB Flash - #define LWIP_IPV6 0 -#endif - -/** - * SYS_LIGHTWEIGHT_PROT==1: if you want inter-task protection for certain - * critical regions during buffer allocation, deallocation and memory - * allocation and deallocation. - */ -#ifndef SYS_LIGHTWEIGHT_PROT -#define SYS_LIGHTWEIGHT_PROT 0 -#endif - -/** - * NO_SYS==1: Provides VERY minimal functionality. Otherwise, - * use lwIP facilities. - */ -#ifndef NO_SYS -#define NO_SYS 0 -#endif - -/** - * NO_SYS_NO_TIMERS==1: Drop support for sys_timeout when NO_SYS==1 - * Mainly for compatibility to old versions. - */ -#ifndef NO_SYS_NO_TIMERS -#define NO_SYS_NO_TIMERS 0 -#endif - -/** - * MEMCPY: override this if you have a faster implementation at hand than the - * one included in your C library - */ -#ifndef MEMCPY -#define MEMCPY(dst,src,len) memcpy(dst,src,len) -#endif - -/** - * SMEMCPY: override this with care! Some compilers (e.g. gcc) can inline a - * call to memcpy() if the length is known at compile time and is small. - */ -#ifndef SMEMCPY -#define SMEMCPY(dst,src,len) memcpy(dst,src,len) -#endif - -/* - ------------------------------------ - ---------- Memory options ---------- - ------------------------------------ -*/ -/** - * MEM_LIBC_MALLOC==1: Use malloc/free/realloc provided by your C-library - * instead of the lwip internal allocator. Can save code size if you - * already use it. - */ -#ifndef MEM_LIBC_MALLOC -#define MEM_LIBC_MALLOC 0 -#endif - -/** -* MEMP_MEM_MALLOC==1: Use mem_malloc/mem_free instead of the lwip pool allocator. -* Especially useful with MEM_LIBC_MALLOC but handle with care regarding execution -* speed and usage from interrupts! -*/ -#ifndef MEMP_MEM_MALLOC -#define MEMP_MEM_MALLOC 0 -#endif - -/** - * MEM_ALIGNMENT: should be set to the alignment of the CPU - * 4 byte alignment -> #define MEM_ALIGNMENT 4 - * 2 byte alignment -> #define MEM_ALIGNMENT 2 - */ -#ifndef MEM_ALIGNMENT -#define MEM_ALIGNMENT 4 -#endif - -/** - * MEM_SIZE: the size of the heap memory. If the application will send - * a lot of data that needs to be copied, this should be set high. - */ -#ifndef MEM_SIZE -#define MEM_SIZE 16000 -#endif - -/** - * MEMP_SEPARATE_POOLS: if defined to 1, each pool is placed in its own array. - * This can be used to individually change the location of each pool. - * Default is one big array for all pools - */ -#ifndef MEMP_SEPARATE_POOLS -#define MEMP_SEPARATE_POOLS 0 -#endif - -/** - * MEMP_OVERFLOW_CHECK: memp overflow protection reserves a configurable - * amount of bytes before and after each memp element in every pool and fills - * it with a prominent default value. - * MEMP_OVERFLOW_CHECK == 0 no checking - * MEMP_OVERFLOW_CHECK == 1 checks each element when it is freed - * MEMP_OVERFLOW_CHECK >= 2 checks each element in every pool every time - * memp_malloc() or memp_free() is called (useful but slow!) - */ -#ifndef MEMP_OVERFLOW_CHECK -#define MEMP_OVERFLOW_CHECK 0 -#endif - -/** - * MEMP_SANITY_CHECK==1: run a sanity check after each memp_free() to make - * sure that there are no cycles in the linked lists. - */ -#ifndef MEMP_SANITY_CHECK -#define MEMP_SANITY_CHECK 0 -#endif - -/** - * MEM_USE_POOLS==1: Use an alternative to malloc() by allocating from a set - * of memory pools of various sizes. When mem_malloc is called, an element of - * the smallest pool that can provide the length needed is returned. - * To use this, MEMP_USE_CUSTOM_POOLS also has to be enabled. - */ -#ifndef MEM_USE_POOLS -#define MEM_USE_POOLS 0 -#endif - -/** - * MEM_USE_POOLS_TRY_BIGGER_POOL==1: if one malloc-pool is empty, try the next - * bigger pool - WARNING: THIS MIGHT WASTE MEMORY but it can make a system more - * reliable. */ -#ifndef MEM_USE_POOLS_TRY_BIGGER_POOL -#define MEM_USE_POOLS_TRY_BIGGER_POOL 0 -#endif - -/** - * MEMP_USE_CUSTOM_POOLS==1: whether to include a user file lwippools.h - * that defines additional pools beyond the "standard" ones required - * by lwIP. If you set this to 1, you must have lwippools.h in your - * inlude path somewhere. - */ -#ifndef MEMP_USE_CUSTOM_POOLS -#define MEMP_USE_CUSTOM_POOLS 0 -#endif - -/** - * Set this to 1 if you want to free PBUF_RAM pbufs (or call mem_free()) from - * interrupt context (or another context that doesn't allow waiting for a - * semaphore). - * If set to 1, mem_malloc will be protected by a semaphore and SYS_ARCH_PROTECT, - * while mem_free will only use SYS_ARCH_PROTECT. mem_malloc SYS_ARCH_UNPROTECTs - * with each loop so that mem_free can run. - * - * ATTENTION: As you can see from the above description, this leads to dis-/ - * enabling interrupts often, which can be slow! Also, on low memory, mem_malloc - * can need longer. - * - * If you don't want that, at least for NO_SYS=0, you can still use the following - * functions to enqueue a deallocation call which then runs in the tcpip_thread - * context: - * - pbuf_free_callback(p); - * - mem_free_callback(m); - */ -#ifndef LWIP_ALLOW_MEM_FREE_FROM_OTHER_CONTEXT -#define LWIP_ALLOW_MEM_FREE_FROM_OTHER_CONTEXT 0 -#endif - -/* - ------------------------------------------------ - ---------- Internal Memory Pool Sizes ---------- - ------------------------------------------------ -*/ -/** - * MEMP_NUM_PBUF: the number of memp struct pbufs (used for PBUF_ROM and PBUF_REF). - * If the application sends a lot of data out of ROM (or other static memory), - * this should be set high. - */ -#ifndef MEMP_NUM_PBUF -#define MEMP_NUM_PBUF 16 -#endif - -/** - * MEMP_NUM_RAW_PCB: Number of raw connection PCBs - * (requires the LWIP_RAW option) - */ -#ifndef MEMP_NUM_RAW_PCB -#define MEMP_NUM_RAW_PCB 4 -#endif - -/** - * MEMP_NUM_UDP_PCB: the number of UDP protocol control blocks. One - * per active UDP "connection". - * (requires the LWIP_UDP option) - */ -#ifndef MEMP_NUM_UDP_PCB -#define MEMP_NUM_UDP_PCB 4 -#endif - -/** - * MEMP_NUM_TCP_PCB: the number of simulatenously active TCP connections. - * (requires the LWIP_TCP option) - */ -#ifndef MEMP_NUM_TCP_PCB -#define MEMP_NUM_TCP_PCB 5 -#endif - -/** - * MEMP_NUM_TCP_PCB_LISTEN: the number of listening TCP connections. - * (requires the LWIP_TCP option) - */ -#ifndef MEMP_NUM_TCP_PCB_LISTEN -#define MEMP_NUM_TCP_PCB_LISTEN 8 -#endif - -/** - * MEMP_NUM_TCP_SEG: the number of simultaneously queued TCP segments. - * (requires the LWIP_TCP option) - */ -#ifndef MEMP_NUM_TCP_SEG -#define MEMP_NUM_TCP_SEG 16 -#endif - -/** - * MEMP_NUM_REASSDATA: the number of IP packets simultaneously queued for - * reassembly (whole packets, not fragments!) - */ -#ifndef MEMP_NUM_REASSDATA -#define MEMP_NUM_REASSDATA 5 -#endif - -/** - * MEMP_NUM_FRAG_PBUF: the number of IP fragments simultaneously sent - * (fragments, not whole packets!). - * This is only used with IP_FRAG_USES_STATIC_BUF==0 and - * LWIP_NETIF_TX_SINGLE_PBUF==0 and only has to be > 1 with DMA-enabled MACs - * where the packet is not yet sent when netif->output returns. - */ -#ifndef MEMP_NUM_FRAG_PBUF -#define MEMP_NUM_FRAG_PBUF 15 -#endif - -/** - * MEMP_NUM_ARP_QUEUE: the number of simulateously queued outgoing - * packets (pbufs) that are waiting for an ARP request (to resolve - * their destination address) to finish. - * (requires the ARP_QUEUEING option) - */ -#ifndef MEMP_NUM_ARP_QUEUE -#define MEMP_NUM_ARP_QUEUE 30 -#endif - -/** - * MEMP_NUM_IGMP_GROUP: The number of multicast groups whose network interfaces - * can be members et the same time (one per netif - allsystems group -, plus one - * per netif membership). - * (requires the LWIP_IGMP option) - */ -#ifndef MEMP_NUM_IGMP_GROUP -#define MEMP_NUM_IGMP_GROUP 8 -#endif - -/** - * MEMP_NUM_SYS_TIMEOUT: the number of simulateously active timeouts. - * (requires NO_SYS==0) - * The default number of timeouts is calculated here for all enabled modules. - * The formula expects settings to be either '0' or '1'. - */ -#ifndef MEMP_NUM_SYS_TIMEOUT -#define MEMP_NUM_SYS_TIMEOUT (LWIP_TCP + IP_REASSEMBLY + LWIP_ARP + (2*LWIP_DHCP) + LWIP_AUTOIP + LWIP_IGMP + LWIP_DNS + PPP_SUPPORT + (LWIP_IPV6 * (1 + LWIP_IPV6_REASS + LWIP_IPV6_MLD))) + 2 -#endif - -/** - * MEMP_NUM_NETBUF: the number of struct netbufs. - * (only needed if you use the sequential API, like api_lib.c) - */ -#ifndef MEMP_NUM_NETBUF -#define MEMP_NUM_NETBUF 2 -#endif - -/** - * MEMP_NUM_NETCONN: the number of struct netconns. - * (only needed if you use the sequential API, like api_lib.c) - */ -#ifndef MEMP_NUM_NETCONN -#define MEMP_NUM_NETCONN 4 -#endif - -/** - * MEMP_NUM_TCPIP_MSG_API: the number of struct tcpip_msg, which are used - * for callback/timeout API communication. - * (only needed if you use tcpip.c) - */ -#ifndef MEMP_NUM_TCPIP_MSG_API -#define MEMP_NUM_TCPIP_MSG_API 8 -#endif - -/** - * MEMP_NUM_TCPIP_MSG_INPKT: the number of struct tcpip_msg, which are used - * for incoming packets. - * (only needed if you use tcpip.c) - */ -#ifndef MEMP_NUM_TCPIP_MSG_INPKT -#define MEMP_NUM_TCPIP_MSG_INPKT 8 -#endif - -/** - * MEMP_NUM_SNMP_NODE: the number of leafs in the SNMP tree. - */ -#ifndef MEMP_NUM_SNMP_NODE -#define MEMP_NUM_SNMP_NODE 50 -#endif - -/** - * MEMP_NUM_SNMP_ROOTNODE: the number of branches in the SNMP tree. - * Every branch has one leaf (MEMP_NUM_SNMP_NODE) at least! - */ -#ifndef MEMP_NUM_SNMP_ROOTNODE -#define MEMP_NUM_SNMP_ROOTNODE 30 -#endif - -/** - * MEMP_NUM_SNMP_VARBIND: the number of concurrent requests (does not have to - * be changed normally) - 2 of these are used per request (1 for input, - * 1 for output) - */ -#ifndef MEMP_NUM_SNMP_VARBIND -#define MEMP_NUM_SNMP_VARBIND 2 -#endif - -/** - * MEMP_NUM_SNMP_VALUE: the number of OID or values concurrently used - * (does not have to be changed normally) - 3 of these are used per request - * (1 for the value read and 2 for OIDs - input and output) - */ -#ifndef MEMP_NUM_SNMP_VALUE -#define MEMP_NUM_SNMP_VALUE 3 -#endif - -/** - * MEMP_NUM_NETDB: the number of concurrently running lwip_addrinfo() calls - * (before freeing the corresponding memory using lwip_freeaddrinfo()). - */ -#ifndef MEMP_NUM_NETDB -#define MEMP_NUM_NETDB 1 -#endif - -/** - * MEMP_NUM_LOCALHOSTLIST: the number of host entries in the local host list - * if DNS_LOCAL_HOSTLIST_IS_DYNAMIC==1. - */ -#ifndef MEMP_NUM_LOCALHOSTLIST -#define MEMP_NUM_LOCALHOSTLIST 1 -#endif - -/** - * MEMP_NUM_PPPOE_INTERFACES: the number of concurrently active PPPoE - * interfaces (only used with PPPOE_SUPPORT==1) - */ -#ifndef MEMP_NUM_PPPOE_INTERFACES -#define MEMP_NUM_PPPOE_INTERFACES 1 -#endif - -/** - * PBUF_POOL_SIZE: the number of buffers in the pbuf pool. - */ -#ifndef PBUF_POOL_SIZE -#define PBUF_POOL_SIZE 16 -#endif - -/* - --------------------------------- - ---------- ARP options ---------- - --------------------------------- -*/ -/** - * LWIP_ARP==1: Enable ARP functionality. - */ -#ifndef LWIP_ARP -#define LWIP_ARP 1 -#endif - -/** - * ARP_TABLE_SIZE: Number of active MAC-IP address pairs cached. - */ -#ifndef ARP_TABLE_SIZE -#define ARP_TABLE_SIZE 10 -#endif - -/** - * ARP_QUEUEING==1: Multiple outgoing packets are queued during hardware address - * resolution. By default, only the most recent packet is queued per IP address. - * This is sufficient for most protocols and mainly reduces TCP connection - * startup time. Set this to 1 if you know your application sends more than one - * packet in a row to an IP address that is not in the ARP cache. - */ -#ifndef ARP_QUEUEING -#define ARP_QUEUEING 0 -#endif - -/** - * ETHARP_TRUST_IP_MAC==1: Incoming IP packets cause the ARP table to be - * updated with the source MAC and IP addresses supplied in the packet. - * You may want to disable this if you do not trust LAN peers to have the - * correct addresses, or as a limited approach to attempt to handle - * spoofing. If disabled, lwIP will need to make a new ARP request if - * the peer is not already in the ARP table, adding a little latency. - * The peer *is* in the ARP table if it requested our address before. - * Also notice that this slows down input processing of every IP packet! - */ -#ifndef ETHARP_TRUST_IP_MAC -#define ETHARP_TRUST_IP_MAC 0 -#endif - -/** - * ETHARP_SUPPORT_VLAN==1: support receiving ethernet packets with VLAN header. - * Additionally, you can define ETHARP_VLAN_CHECK to an u16_t VLAN ID to check. - * If ETHARP_VLAN_CHECK is defined, only VLAN-traffic for this VLAN is accepted. - * If ETHARP_VLAN_CHECK is not defined, all traffic is accepted. - * Alternatively, define a function/define ETHARP_VLAN_CHECK_FN(eth_hdr, vlan) - * that returns 1 to accept a packet or 0 to drop a packet. - */ -#ifndef ETHARP_SUPPORT_VLAN -#define ETHARP_SUPPORT_VLAN 0 -#endif - -/** LWIP_ETHERNET==1: enable ethernet support for PPPoE even though ARP - * might be disabled - */ -#ifndef LWIP_ETHERNET -#define LWIP_ETHERNET (LWIP_ARP || PPPOE_SUPPORT) -#endif - -/** ETH_PAD_SIZE: number of bytes added before the ethernet header to ensure - * alignment of payload after that header. Since the header is 14 bytes long, - * without this padding e.g. addresses in the IP header will not be aligned - * on a 32-bit boundary, so setting this to 2 can speed up 32-bit-platforms. - */ -#ifndef ETH_PAD_SIZE -#define ETH_PAD_SIZE 0 -#endif - -/** ETHARP_SUPPORT_STATIC_ENTRIES==1: enable code to support static ARP table - * entries (using etharp_add_static_entry/etharp_remove_static_entry). - */ -#ifndef ETHARP_SUPPORT_STATIC_ENTRIES -#define ETHARP_SUPPORT_STATIC_ENTRIES 0 -#endif - - -/* - -------------------------------- - ---------- IP options ---------- - -------------------------------- -*/ -/** - * IP_FORWARD==1: Enables the ability to forward IP packets across network - * interfaces. If you are going to run lwIP on a device with only one network - * interface, define this to 0. - */ -#ifndef IP_FORWARD -#define IP_FORWARD 0 -#endif - -/** - * IP_OPTIONS_ALLOWED: Defines the behavior for IP options. - * IP_OPTIONS_ALLOWED==0: All packets with IP options are dropped. - * IP_OPTIONS_ALLOWED==1: IP options are allowed (but not parsed). - */ -#ifndef IP_OPTIONS_ALLOWED -#define IP_OPTIONS_ALLOWED 1 -#endif - -/** - * IP_REASSEMBLY==1: Reassemble incoming fragmented IP packets. Note that - * this option does not affect outgoing packet sizes, which can be controlled - * via IP_FRAG. - */ -#ifndef IP_REASSEMBLY -#define IP_REASSEMBLY 1 -#endif - -/** - * IP_FRAG==1: Fragment outgoing IP packets if their size exceeds MTU. Note - * that this option does not affect incoming packet sizes, which can be - * controlled via IP_REASSEMBLY. - */ -#ifndef IP_FRAG -#define IP_FRAG 1 -#endif - -/** - * IP_REASS_MAXAGE: Maximum time (in multiples of IP_TMR_INTERVAL - so seconds, normally) - * a fragmented IP packet waits for all fragments to arrive. If not all fragments arrived - * in this time, the whole packet is discarded. - */ -#ifndef IP_REASS_MAXAGE -#define IP_REASS_MAXAGE 3 -#endif - -/** - * IP_REASS_MAX_PBUFS: Total maximum amount of pbufs waiting to be reassembled. - * Since the received pbufs are enqueued, be sure to configure - * PBUF_POOL_SIZE > IP_REASS_MAX_PBUFS so that the stack is still able to receive - * packets even if the maximum amount of fragments is enqueued for reassembly! - */ -#ifndef IP_REASS_MAX_PBUFS -#define IP_REASS_MAX_PBUFS 10 -#endif - -/** - * IP_FRAG_USES_STATIC_BUF==1: Use a static MTU-sized buffer for IP - * fragmentation. Otherwise pbufs are allocated and reference the original - * packet data to be fragmented (or with LWIP_NETIF_TX_SINGLE_PBUF==1, - * new PBUF_RAM pbufs are used for fragments). - * ATTENTION: IP_FRAG_USES_STATIC_BUF==1 may not be used for DMA-enabled MACs! - */ -#ifndef IP_FRAG_USES_STATIC_BUF -#define IP_FRAG_USES_STATIC_BUF 0 -#endif - -/** - * IP_FRAG_MAX_MTU: Assumed max MTU on any interface for IP frag buffer - * (requires IP_FRAG_USES_STATIC_BUF==1) - */ -#if IP_FRAG_USES_STATIC_BUF && !defined(IP_FRAG_MAX_MTU) -#define IP_FRAG_MAX_MTU 1500 -#endif - -/** - * IP_DEFAULT_TTL: Default value for Time-To-Live used by transport layers. - */ -#ifndef IP_DEFAULT_TTL -#define IP_DEFAULT_TTL 255 -#endif - -/** - * IP_SOF_BROADCAST=1: Use the SOF_BROADCAST field to enable broadcast - * filter per pcb on udp and raw send operations. To enable broadcast filter - * on recv operations, you also have to set IP_SOF_BROADCAST_RECV=1. - */ -#ifndef IP_SOF_BROADCAST -#define IP_SOF_BROADCAST 1 -#endif - -/** - * IP_SOF_BROADCAST_RECV (requires IP_SOF_BROADCAST=1) enable the broadcast - * filter on recv operations. - */ -#ifndef IP_SOF_BROADCAST_RECV -#define IP_SOF_BROADCAST_RECV 1 -#endif - -/** - * IP_FORWARD_ALLOW_TX_ON_RX_NETIF==1: allow ip_forward() to send packets back - * out on the netif where it was received. This should only be used for - * wireless networks. - * ATTENTION: When this is 1, make sure your netif driver correctly marks incoming - * link-layer-broadcast/multicast packets as such using the corresponding pbuf flags! - */ -#ifndef IP_FORWARD_ALLOW_TX_ON_RX_NETIF -#define IP_FORWARD_ALLOW_TX_ON_RX_NETIF 0 -#endif - -/** - * LWIP_RANDOMIZE_INITIAL_LOCAL_PORTS==1: randomize the local port for the first - * local TCP/UDP pcb (default==0). This can prevent creating predictable port - * numbers after booting a device. - */ -#ifndef LWIP_RANDOMIZE_INITIAL_LOCAL_PORTS -#define LWIP_RANDOMIZE_INITIAL_LOCAL_PORTS 0 -#endif - -/* - ---------------------------------- - ---------- ICMP options ---------- - ---------------------------------- -*/ -/** - * LWIP_ICMP==1: Enable ICMP module inside the IP stack. - * Be careful, disable that make your product non-compliant to RFC1122 - */ -#ifndef LWIP_ICMP -#define LWIP_ICMP 1 -#endif - -/** - * ICMP_TTL: Default value for Time-To-Live used by ICMP packets. - */ -#ifndef ICMP_TTL -#define ICMP_TTL (IP_DEFAULT_TTL) -#endif - -/** - * LWIP_BROADCAST_PING==1: respond to broadcast pings (default is unicast only) - */ -#ifndef LWIP_BROADCAST_PING -#define LWIP_BROADCAST_PING 0 -#endif - -/** - * LWIP_MULTICAST_PING==1: respond to multicast pings (default is unicast only) - */ -#ifndef LWIP_MULTICAST_PING -#define LWIP_MULTICAST_PING 0 -#endif - -/* - --------------------------------- - ---------- RAW options ---------- - --------------------------------- -*/ -/** - * LWIP_RAW==1: Enable application layer to hook into the IP layer itself. - */ -#ifndef LWIP_RAW -#define LWIP_RAW 1 -#endif - -/** - * LWIP_RAW==1: Enable application layer to hook into the IP layer itself. - */ -#ifndef RAW_TTL -#define RAW_TTL (IP_DEFAULT_TTL) -#endif - -/* - ---------------------------------- - ---------- DHCP options ---------- - ---------------------------------- -*/ -/** - * LWIP_DHCP==1: Enable DHCP module. - */ -#ifndef LWIP_DHCP -// Flash use: 7960 Bytes (9100 on IPv6) -#define LWIP_DHCP 1 -#endif - -/** - * DHCP_DOES_ARP_CHECK==1: Do an ARP check on the offered address. - */ -#ifndef DHCP_DOES_ARP_CHECK -#define DHCP_DOES_ARP_CHECK ((LWIP_DHCP) && (LWIP_ARP)) -#endif - -/* - ------------------------------------ - ---------- AUTOIP options ---------- - ------------------------------------ -*/ -/** - * LWIP_AUTOIP==1: Enable AUTOIP module. - */ -#ifndef LWIP_AUTOIP -#define LWIP_AUTOIP 0 -#endif - -/** - * LWIP_DHCP_AUTOIP_COOP==1: Allow DHCP and AUTOIP to be both enabled on - * the same interface at the same time. - */ -#ifndef LWIP_DHCP_AUTOIP_COOP -#define LWIP_DHCP_AUTOIP_COOP 0 -#endif - -/** - * LWIP_DHCP_AUTOIP_COOP_TRIES: Set to the number of DHCP DISCOVER probes - * that should be sent before falling back on AUTOIP. This can be set - * as low as 1 to get an AutoIP address very quickly, but you should - * be prepared to handle a changing IP address when DHCP overrides - * AutoIP. - */ -#ifndef LWIP_DHCP_AUTOIP_COOP_TRIES -#define LWIP_DHCP_AUTOIP_COOP_TRIES 9 -#endif - -/* - ---------------------------------- - ---------- SNMP options ---------- - ---------------------------------- -*/ -/** - * LWIP_SNMP==1: Turn on SNMP module. UDP must be available for SNMP - * transport. - */ -#ifndef LWIP_SNMP -#define LWIP_SNMP 0 -#endif - -/** - * SNMP_CONCURRENT_REQUESTS: Number of concurrent requests the module will - * allow. At least one request buffer is required. - * Does not have to be changed unless external MIBs answer request asynchronously - */ -#ifndef SNMP_CONCURRENT_REQUESTS -#define SNMP_CONCURRENT_REQUESTS 1 -#endif - -/** - * SNMP_TRAP_DESTINATIONS: Number of trap destinations. At least one trap - * destination is required - */ -#ifndef SNMP_TRAP_DESTINATIONS -#define SNMP_TRAP_DESTINATIONS 1 -#endif - -/** - * SNMP_PRIVATE_MIB: - * When using a private MIB, you have to create a file 'private_mib.h' that contains - * a 'struct mib_array_node mib_private' which contains your MIB. - */ -#ifndef SNMP_PRIVATE_MIB -#define SNMP_PRIVATE_MIB 0 -#endif - -/** - * Only allow SNMP write actions that are 'safe' (e.g. disabeling netifs is not - * a safe action and disabled when SNMP_SAFE_REQUESTS = 1). - * Unsafe requests are disabled by default! - */ -#ifndef SNMP_SAFE_REQUESTS -#define SNMP_SAFE_REQUESTS 1 -#endif - -/** - * The maximum length of strings used. This affects the size of - * MEMP_SNMP_VALUE elements. - */ -#ifndef SNMP_MAX_OCTET_STRING_LEN -#define SNMP_MAX_OCTET_STRING_LEN 127 -#endif - -/** - * The maximum depth of the SNMP tree. - * With private MIBs enabled, this depends on your MIB! - * This affects the size of MEMP_SNMP_VALUE elements. - */ -#ifndef SNMP_MAX_TREE_DEPTH -#define SNMP_MAX_TREE_DEPTH 15 -#endif - -/** - * The size of the MEMP_SNMP_VALUE elements, normally calculated from - * SNMP_MAX_OCTET_STRING_LEN and SNMP_MAX_TREE_DEPTH. - */ -#ifndef SNMP_MAX_VALUE_SIZE -#define SNMP_MAX_VALUE_SIZE LWIP_MAX((SNMP_MAX_OCTET_STRING_LEN)+1, sizeof(s32_t)*(SNMP_MAX_TREE_DEPTH)) -#endif - -/* - ---------------------------------- - ---------- IGMP options ---------- - ---------------------------------- -*/ -/** - * LWIP_IGMP==1: Turn on IGMP module. - */ -#ifndef LWIP_IGMP -#define LWIP_IGMP 0 -#endif - -/* - ---------------------------------- - ---------- DNS options ----------- - ---------------------------------- -*/ -/** - * LWIP_DNS==1: Turn on DNS module. UDP must be available for DNS - * transport. - */ -#ifndef LWIP_DNS -#define LWIP_DNS 1 -#endif - -/** DNS maximum number of entries to maintain locally. */ -#ifndef DNS_TABLE_SIZE -#define DNS_TABLE_SIZE 4 -#endif - -/** DNS maximum host name length supported in the name table. */ -#ifndef DNS_MAX_NAME_LENGTH -#define DNS_MAX_NAME_LENGTH 256 -#endif - -/** The maximum of DNS servers */ -#ifndef DNS_MAX_SERVERS -#define DNS_MAX_SERVERS 2 -#endif - -/** DNS do a name checking between the query and the response. */ -#ifndef DNS_DOES_NAME_CHECK -#define DNS_DOES_NAME_CHECK 1 -#endif - -/** DNS message max. size. Default value is RFC compliant. */ -#ifndef DNS_MSG_SIZE -#define DNS_MSG_SIZE 512 -#endif - -/** DNS_LOCAL_HOSTLIST: Implements a local host-to-address list. If enabled, - * you have to define - * #define DNS_LOCAL_HOSTLIST_INIT {{"host1", 0x123}, {"host2", 0x234}} - * (an array of structs name/address, where address is an u32_t in network - * byte order). - * - * Instead, you can also use an external function: - * #define DNS_LOOKUP_LOCAL_EXTERN(x) extern u32_t my_lookup_function(const char *name) - * that returns the IP address or INADDR_NONE if not found. - */ -#ifndef DNS_LOCAL_HOSTLIST -#define DNS_LOCAL_HOSTLIST 0 -#endif /* DNS_LOCAL_HOSTLIST */ - -/** If this is turned on, the local host-list can be dynamically changed - * at runtime. */ -#ifndef DNS_LOCAL_HOSTLIST_IS_DYNAMIC -#define DNS_LOCAL_HOSTLIST_IS_DYNAMIC 0 -#endif /* DNS_LOCAL_HOSTLIST_IS_DYNAMIC */ - -/* - --------------------------------- - ---------- UDP options ---------- - --------------------------------- -*/ -/** - * LWIP_UDP==1: Turn on UDP. - */ -#ifndef LWIP_UDP -#define LWIP_UDP 1 -#endif - -/** - * LWIP_UDPLITE==1: Turn on UDP-Lite. (Requires LWIP_UDP) - */ -#ifndef LWIP_UDPLITE -#define LWIP_UDPLITE 0 -#endif - -/** - * UDP_TTL: Default Time-To-Live value. - */ -#ifndef UDP_TTL -#define UDP_TTL (IP_DEFAULT_TTL) -#endif - -/** - * LWIP_NETBUF_RECVINFO==1: append destination addr and port to every netbuf. - */ -#ifndef LWIP_NETBUF_RECVINFO -#define LWIP_NETBUF_RECVINFO 0 -#endif - -/* - --------------------------------- - ---------- TCP options ---------- - --------------------------------- -*/ -/** - * LWIP_TCP==1: Turn on TCP. - */ -#ifndef LWIP_TCP -#define LWIP_TCP 1 -#endif - -/** - * TCP_TTL: Default Time-To-Live value. - */ -#ifndef TCP_TTL -#define TCP_TTL (IP_DEFAULT_TTL) -#endif - -/** - * TCP_WND: The size of a TCP window. This must be at least - * (2 * TCP_MSS) for things to work well - */ -#ifndef TCP_WND -#define TCP_WND (4 * TCP_MSS) -#endif - -/** - * TCP_MAXRTX: Maximum number of retransmissions of data segments. - */ -#ifndef TCP_MAXRTX -#define TCP_MAXRTX 12 -#endif - -/** - * TCP_SYNMAXRTX: Maximum number of retransmissions of SYN segments. - */ -#ifndef TCP_SYNMAXRTX -#define TCP_SYNMAXRTX 6 -#endif - -/** - * TCP_QUEUE_OOSEQ==1: TCP will queue segments that arrive out of order. - * Define to 0 if your device is low on memory. - */ -#ifndef TCP_QUEUE_OOSEQ -#define TCP_QUEUE_OOSEQ (LWIP_TCP) -#endif - -/** - * TCP_MSS: TCP Maximum segment size. (default is 536, a conservative default, - * you might want to increase this.) - * For the receive side, this MSS is advertised to the remote side - * when opening a connection. For the transmit size, this MSS sets - * an upper limit on the MSS advertised by the remote host. - */ -#ifndef TCP_MSS -#define TCP_MSS 1480 -#endif - -/** - * TCP_CALCULATE_EFF_SEND_MSS: "The maximum size of a segment that TCP really - * sends, the 'effective send MSS,' MUST be the smaller of the send MSS (which - * reflects the available reassembly buffer size at the remote host) and the - * largest size permitted by the IP layer" (RFC 1122) - * Setting this to 1 enables code that checks TCP_MSS against the MTU of the - * netif used for a connection and limits the MSS if it would be too big otherwise. - */ -#ifndef TCP_CALCULATE_EFF_SEND_MSS -#define TCP_CALCULATE_EFF_SEND_MSS 1 -#endif - - -/** - * TCP_SND_BUF: TCP sender buffer space (bytes). - * To achieve good performance, this should be at least 2 * TCP_MSS. - */ -#ifndef TCP_SND_BUF -#define TCP_SND_BUF (2 * TCP_MSS) -#endif - -/** - * TCP_SND_QUEUELEN: TCP sender buffer space (pbufs). This must be at least - * as much as (2 * TCP_SND_BUF/TCP_MSS) for things to work. - */ -#ifndef TCP_SND_QUEUELEN -#define TCP_SND_QUEUELEN ((4 * (TCP_SND_BUF) + (TCP_MSS - 1))/(TCP_MSS)) -#endif - -/** - * TCP_SNDLOWAT: TCP writable space (bytes). This must be less than - * TCP_SND_BUF. It is the amount of space which must be available in the - * TCP snd_buf for select to return writable (combined with TCP_SNDQUEUELOWAT). - */ -#ifndef TCP_SNDLOWAT -#define TCP_SNDLOWAT LWIP_MIN(LWIP_MAX(((TCP_SND_BUF)/2), (2 * TCP_MSS) + 1), (TCP_SND_BUF) - 1) -#endif - -/** - * TCP_SNDQUEUELOWAT: TCP writable bufs (pbuf count). This must be less - * than TCP_SND_QUEUELEN. If the number of pbufs queued on a pcb drops below - * this number, select returns writable (combined with TCP_SNDLOWAT). - */ -#ifndef TCP_SNDQUEUELOWAT -#define TCP_SNDQUEUELOWAT LWIP_MAX(((TCP_SND_QUEUELEN)/2), 5) -#endif - -/** - * TCP_OOSEQ_MAX_BYTES: The maximum number of bytes queued on ooseq per pcb. - * Default is 0 (no limit). Only valid for TCP_QUEUE_OOSEQ==0. - */ -#ifndef TCP_OOSEQ_MAX_BYTES -#define TCP_OOSEQ_MAX_BYTES 0 -#endif - -/** - * TCP_OOSEQ_MAX_PBUFS: The maximum number of pbufs queued on ooseq per pcb. - * Default is 0 (no limit). Only valid for TCP_QUEUE_OOSEQ==0. - */ -#ifndef TCP_OOSEQ_MAX_PBUFS -#define TCP_OOSEQ_MAX_PBUFS 0 -#endif - -/** - * TCP_LISTEN_BACKLOG: Enable the backlog option for tcp listen pcb. - */ -#ifndef TCP_LISTEN_BACKLOG -#define TCP_LISTEN_BACKLOG 0 -#endif - -/** - * The maximum allowed backlog for TCP listen netconns. - * This backlog is used unless another is explicitly specified. - * 0xff is the maximum (u8_t). - */ -#ifndef TCP_DEFAULT_LISTEN_BACKLOG -#define TCP_DEFAULT_LISTEN_BACKLOG 0xff -#endif - -/** - * TCP_OVERSIZE: The maximum number of bytes that tcp_write may - * allocate ahead of time in an attempt to create shorter pbuf chains - * for transmission. The meaningful range is 0 to TCP_MSS. Some - * suggested values are: - * - * 0: Disable oversized allocation. Each tcp_write() allocates a new - pbuf (old behaviour). - * 1: Allocate size-aligned pbufs with minimal excess. Use this if your - * scatter-gather DMA requires aligned fragments. - * 128: Limit the pbuf/memory overhead to 20%. - * TCP_MSS: Try to create unfragmented TCP packets. - * TCP_MSS/4: Try to create 4 fragments or less per TCP packet. - */ -#ifndef TCP_OVERSIZE -#define TCP_OVERSIZE TCP_MSS -#endif - -/** - * LWIP_TCP_TIMESTAMPS==1: support the TCP timestamp option. - */ -#ifndef LWIP_TCP_TIMESTAMPS -#define LWIP_TCP_TIMESTAMPS 0 -#endif - -/** - * TCP_WND_UPDATE_THRESHOLD: difference in window to trigger an - * explicit window update - */ -#ifndef TCP_WND_UPDATE_THRESHOLD -#define TCP_WND_UPDATE_THRESHOLD (TCP_WND / 4) -#endif - -/** - * LWIP_EVENT_API and LWIP_CALLBACK_API: Only one of these should be set to 1. - * LWIP_EVENT_API==1: The user defines lwip_tcp_event() to receive all - * events (accept, sent, etc) that happen in the system. - * LWIP_CALLBACK_API==1: The PCB callback function is called directly - * for the event. This is the default. - */ -#if !defined(LWIP_EVENT_API) && !defined(LWIP_CALLBACK_API) -#define LWIP_EVENT_API 0 -#define LWIP_CALLBACK_API 1 -#endif - - -/* - ---------------------------------- - ---------- Pbuf options ---------- - ---------------------------------- -*/ -/** - * PBUF_LINK_HLEN: the number of bytes that should be allocated for a - * link level header. The default is 14, the standard value for - * Ethernet. - */ -#ifndef PBUF_LINK_HLEN -#define PBUF_LINK_HLEN (14 + ETH_PAD_SIZE) -#endif - -/** - * PBUF_POOL_BUFSIZE: the size of each pbuf in the pbuf pool. The default is - * designed to accomodate single full size TCP frame in one pbuf, including - * TCP_MSS, IP header, and link header. - */ -#ifndef PBUF_POOL_BUFSIZE -#define PBUF_POOL_BUFSIZE LWIP_MEM_ALIGN_SIZE(TCP_MSS+40+PBUF_LINK_HLEN) -#endif - -/* - ------------------------------------------------ - ---------- Network Interfaces options ---------- - ------------------------------------------------ -*/ -/** - * LWIP_NETIF_HOSTNAME==1: use DHCP_OPTION_HOSTNAME with netif's hostname - * field. - */ -#ifndef LWIP_NETIF_HOSTNAME -#define LWIP_NETIF_HOSTNAME 0 -#endif - -/** - * LWIP_NETIF_API==1: Support netif api (in netifapi.c) - */ -#ifndef LWIP_NETIF_API -#define LWIP_NETIF_API 0 -#endif - -/** - * LWIP_NETIF_STATUS_CALLBACK==1: Support a callback function whenever an interface - * changes its up/down status (i.e., due to DHCP IP acquistion) - */ -#ifndef LWIP_NETIF_STATUS_CALLBACK -#define LWIP_NETIF_STATUS_CALLBACK 0 -#endif - -/** - * LWIP_NETIF_LINK_CALLBACK==1: Support a callback function from an interface - * whenever the link changes (i.e., link down) - */ -#ifndef LWIP_NETIF_LINK_CALLBACK -#define LWIP_NETIF_LINK_CALLBACK 0 -#endif - -/** - * LWIP_NETIF_REMOVE_CALLBACK==1: Support a callback function that is called - * when a netif has been removed - */ -#ifndef LWIP_NETIF_REMOVE_CALLBACK -#define LWIP_NETIF_REMOVE_CALLBACK 0 -#endif - -/** - * LWIP_NETIF_HWADDRHINT==1: Cache link-layer-address hints (e.g. table - * indices) in struct netif. TCP and UDP can make use of this to prevent - * scanning the ARP table for every sent packet. While this is faster for big - * ARP tables or many concurrent connections, it might be counterproductive - * if you have a tiny ARP table or if there never are concurrent connections. - */ -#ifndef LWIP_NETIF_HWADDRHINT -#define LWIP_NETIF_HWADDRHINT 0 -#endif - -/** - * LWIP_NETIF_LOOPBACK==1: Support sending packets with a destination IP - * address equal to the netif IP address, looping them back up the stack. - */ -#ifndef LWIP_NETIF_LOOPBACK -#define LWIP_NETIF_LOOPBACK 0 -#endif - -/** - * LWIP_LOOPBACK_MAX_PBUFS: Maximum number of pbufs on queue for loopback - * sending for each netif (0 = disabled) - */ -#ifndef LWIP_LOOPBACK_MAX_PBUFS -#define LWIP_LOOPBACK_MAX_PBUFS 0 -#endif - -/** - * LWIP_NETIF_LOOPBACK_MULTITHREADING: Indicates whether threading is enabled in - * the system, as netifs must change how they behave depending on this setting - * for the LWIP_NETIF_LOOPBACK option to work. - * Setting this is needed to avoid reentering non-reentrant functions like - * tcp_input(). - * LWIP_NETIF_LOOPBACK_MULTITHREADING==1: Indicates that the user is using a - * multithreaded environment like tcpip.c. In this case, netif->input() - * is called directly. - * LWIP_NETIF_LOOPBACK_MULTITHREADING==0: Indicates a polling (or NO_SYS) setup. - * The packets are put on a list and netif_poll() must be called in - * the main application loop. - */ -#ifndef LWIP_NETIF_LOOPBACK_MULTITHREADING -#define LWIP_NETIF_LOOPBACK_MULTITHREADING (!NO_SYS) -#endif - -/** - * LWIP_NETIF_TX_SINGLE_PBUF: if this is set to 1, lwIP tries to put all data - * to be sent into one single pbuf. This is for compatibility with DMA-enabled - * MACs that do not support scatter-gather. - * Beware that this might involve CPU-memcpy before transmitting that would not - * be needed without this flag! Use this only if you need to! - * - * @todo: TCP and IP-frag do not work with this, yet: - */ -#ifndef LWIP_NETIF_TX_SINGLE_PBUF -#define LWIP_NETIF_TX_SINGLE_PBUF 0 -#endif /* LWIP_NETIF_TX_SINGLE_PBUF */ - -/* - ------------------------------------ - ---------- LOOPIF options ---------- - ------------------------------------ -*/ -/** - * LWIP_HAVE_LOOPIF==1: Support loop interface (127.0.0.1) and loopif.c - */ -#ifndef LWIP_HAVE_LOOPIF -#define LWIP_HAVE_LOOPIF 0 -#endif - -/* - ------------------------------------ - ---------- SLIPIF options ---------- - ------------------------------------ -*/ -/** - * LWIP_HAVE_SLIPIF==1: Support slip interface and slipif.c - */ -#ifndef LWIP_HAVE_SLIPIF -#define LWIP_HAVE_SLIPIF 0 -#endif - -/* - ------------------------------------ - ---------- Thread options ---------- - ------------------------------------ -*/ -/** - * TCPIP_THREAD_NAME: The name assigned to the main tcpip thread. - */ -#ifndef TCPIP_THREAD_NAME -#define TCPIP_THREAD_NAME "tcpip_thread" -#endif - -/** - * TCPIP_THREAD_STACKSIZE: The stack size used by the main tcpip thread. - * The stack size value itself is platform-dependent, but is passed to - * sys_thread_new() when the thread is created. - */ -#ifndef TCPIP_THREAD_STACKSIZE -#define TCPIP_THREAD_STACKSIZE 1024 -#endif - -/** - * TCPIP_THREAD_PRIO: The priority assigned to the main tcpip thread. - * The priority value itself is platform-dependent, but is passed to - * sys_thread_new() when the thread is created. - */ -#ifndef TCPIP_THREAD_PRIO -#define TCPIP_THREAD_PRIO (LOWPRIO + 1) -#endif - -/** - * TCPIP_MBOX_SIZE: The mailbox size for the tcpip thread messages - * The queue size value itself is platform-dependent, but is passed to - * sys_mbox_new() when tcpip_init is called. - */ -#ifndef TCPIP_MBOX_SIZE -#define TCPIP_MBOX_SIZE MEMP_NUM_PBUF -#endif - -/** - * SLIPIF_THREAD_NAME: The name assigned to the slipif_loop thread. - */ -#ifndef SLIPIF_THREAD_NAME -#define SLIPIF_THREAD_NAME "slipif_loop" -#endif - -/** - * SLIP_THREAD_STACKSIZE: The stack size used by the slipif_loop thread. - * The stack size value itself is platform-dependent, but is passed to - * sys_thread_new() when the thread is created. - */ -#ifndef SLIPIF_THREAD_STACKSIZE -#define SLIPIF_THREAD_STACKSIZE 1024 -#endif - -/** - * SLIPIF_THREAD_PRIO: The priority assigned to the slipif_loop thread. - * The priority value itself is platform-dependent, but is passed to - * sys_thread_new() when the thread is created. - */ -#ifndef SLIPIF_THREAD_PRIO -#define SLIPIF_THREAD_PRIO (LOWPRIO + 1) -#endif - -/** - * PPP_THREAD_NAME: The name assigned to the pppInputThread. - */ -#ifndef PPP_THREAD_NAME -#define PPP_THREAD_NAME "pppInputThread" -#endif - -/** - * PPP_THREAD_STACKSIZE: The stack size used by the pppInputThread. - * The stack size value itself is platform-dependent, but is passed to - * sys_thread_new() when the thread is created. - */ -#ifndef PPP_THREAD_STACKSIZE -#define PPP_THREAD_STACKSIZE 1024 -#endif - -/** - * PPP_THREAD_PRIO: The priority assigned to the pppInputThread. - * The priority value itself is platform-dependent, but is passed to - * sys_thread_new() when the thread is created. - */ -#ifndef PPP_THREAD_PRIO -#define PPP_THREAD_PRIO (LOWPRIO + 1) -#endif - -/** - * DEFAULT_THREAD_NAME: The name assigned to any other lwIP thread. - */ -#ifndef DEFAULT_THREAD_NAME -#define DEFAULT_THREAD_NAME "lwIP" -#endif - -/** - * DEFAULT_THREAD_STACKSIZE: The stack size used by any other lwIP thread. - * The stack size value itself is platform-dependent, but is passed to - * sys_thread_new() when the thread is created. - */ -#ifndef DEFAULT_THREAD_STACKSIZE -#define DEFAULT_THREAD_STACKSIZE 1024 -#endif - -/** - * DEFAULT_THREAD_PRIO: The priority assigned to any other lwIP thread. - * The priority value itself is platform-dependent, but is passed to - * sys_thread_new() when the thread is created. - */ -#ifndef DEFAULT_THREAD_PRIO -#define DEFAULT_THREAD_PRIO (LOWPRIO + 1) -#endif - -/** - * DEFAULT_RAW_RECVMBOX_SIZE: The mailbox size for the incoming packets on a - * NETCONN_RAW. The queue size value itself is platform-dependent, but is passed - * to sys_mbox_new() when the recvmbox is created. - */ -#ifndef DEFAULT_RAW_RECVMBOX_SIZE -#define DEFAULT_RAW_RECVMBOX_SIZE 4 -#endif - -/** - * DEFAULT_UDP_RECVMBOX_SIZE: The mailbox size for the incoming packets on a - * NETCONN_UDP. The queue size value itself is platform-dependent, but is passed - * to sys_mbox_new() when the recvmbox is created. - */ -#ifndef DEFAULT_UDP_RECVMBOX_SIZE -#define DEFAULT_UDP_RECVMBOX_SIZE 4 -#endif - -/** - * DEFAULT_TCP_RECVMBOX_SIZE: The mailbox size for the incoming packets on a - * NETCONN_TCP. The queue size value itself is platform-dependent, but is passed - * to sys_mbox_new() when the recvmbox is created. - */ -#ifndef DEFAULT_TCP_RECVMBOX_SIZE -#define DEFAULT_TCP_RECVMBOX_SIZE 40 -#endif - -/** - * DEFAULT_ACCEPTMBOX_SIZE: The mailbox size for the incoming connections. - * The queue size value itself is platform-dependent, but is passed to - * sys_mbox_new() when the acceptmbox is created. - */ -#ifndef DEFAULT_ACCEPTMBOX_SIZE -#define DEFAULT_ACCEPTMBOX_SIZE 4 -#endif - -/* - ---------------------------------------------- - ---------- Sequential layer options ---------- - ---------------------------------------------- -*/ -/** - * LWIP_TCPIP_CORE_LOCKING: (EXPERIMENTAL!) - * Don't use it if you're not an active lwIP project member - */ -#ifndef LWIP_TCPIP_CORE_LOCKING -#define LWIP_TCPIP_CORE_LOCKING 0 -#endif - -/** - * LWIP_TCPIP_CORE_LOCKING_INPUT: (EXPERIMENTAL!) - * Don't use it if you're not an active lwIP project member - */ -#ifndef LWIP_TCPIP_CORE_LOCKING_INPUT -#define LWIP_TCPIP_CORE_LOCKING_INPUT 0 -#endif - -/** - * LWIP_NETCONN==1: Enable Netconn API (require to use api_lib.c) - */ -#ifndef LWIP_NETCONN -#define LWIP_NETCONN 1 -#endif - -/** LWIP_TCPIP_TIMEOUT==1: Enable tcpip_timeout/tcpip_untimeout tod create - * timers running in tcpip_thread from another thread. - */ -#ifndef LWIP_TCPIP_TIMEOUT -#define LWIP_TCPIP_TIMEOUT 1 -#endif - -/* - ------------------------------------ - ---------- Socket options ---------- - ------------------------------------ -*/ -/** - * LWIP_SOCKET==1: Enable Socket API (require to use sockets.c) - */ -#ifndef LWIP_SOCKET -#define LWIP_SOCKET 1 -#endif - -/** - * LWIP_COMPAT_SOCKETS==1: Enable BSD-style sockets functions names. - * (only used if you use sockets.c) - */ -#ifndef LWIP_COMPAT_SOCKETS -#define LWIP_COMPAT_SOCKETS 2 -#endif - -/** - * LWIP_POSIX_SOCKETS_IO_NAMES==1: Enable POSIX-style sockets functions names. - * Disable this option if you use a POSIX operating system that uses the same - * names (read, write & close). (only used if you use sockets.c) - */ -#ifndef LWIP_POSIX_SOCKETS_IO_NAMES -#define LWIP_POSIX_SOCKETS_IO_NAMES 1 -#endif - -/** - * LWIP_TCP_KEEPALIVE==1: Enable TCP_KEEPIDLE, TCP_KEEPINTVL and TCP_KEEPCNT - * options processing. Note that TCP_KEEPIDLE and TCP_KEEPINTVL have to be set - * in seconds. (does not require sockets.c, and will affect tcp.c) - */ -#ifndef LWIP_TCP_KEEPALIVE -#define LWIP_TCP_KEEPALIVE 0 -#endif - -/** - * LWIP_SO_SNDTIMEO==1: Enable send timeout for sockets/netconns and - * SO_SNDTIMEO processing. - */ -#ifndef LWIP_SO_SNDTIMEO -#define LWIP_SO_SNDTIMEO 0 -#endif - -/** - * LWIP_SO_RCVTIMEO==1: Enable receive timeout for sockets/netconns and - * SO_RCVTIMEO processing. - */ -#ifndef LWIP_SO_RCVTIMEO -#define LWIP_SO_RCVTIMEO 0 -#endif - -/** - * LWIP_SO_RCVBUF==1: Enable SO_RCVBUF processing. - */ -#ifndef LWIP_SO_RCVBUF -#define LWIP_SO_RCVBUF 0 -#endif - -/** - * If LWIP_SO_RCVBUF is used, this is the default value for recv_bufsize. - */ -#ifndef RECV_BUFSIZE_DEFAULT -#define RECV_BUFSIZE_DEFAULT INT_MAX -#endif - -/** - * SO_REUSE==1: Enable SO_REUSEADDR option. - */ -#ifndef SO_REUSE -#define SO_REUSE 0 -#endif - -/** - * SO_REUSE_RXTOALL==1: Pass a copy of incoming broadcast/multicast packets - * to all local matches if SO_REUSEADDR is turned on. - * WARNING: Adds a memcpy for every packet if passing to more than one pcb! - */ -#ifndef SO_REUSE_RXTOALL -#define SO_REUSE_RXTOALL 0 -#endif - -/* - ---------------------------------------- - ---------- Statistics options ---------- - ---------------------------------------- -*/ -/** - * LWIP_STATS==1: Enable statistics collection in lwip_stats. - */ -#ifndef LWIP_STATS -#define LWIP_STATS 1 -#endif - -#if LWIP_STATS - -/** - * LWIP_STATS_DISPLAY==1: Compile in the statistics output functions. - */ -#ifndef LWIP_STATS_DISPLAY -#define LWIP_STATS_DISPLAY 0 -#endif - -/** - * LINK_STATS==1: Enable link stats. - */ -#ifndef LINK_STATS -#define LINK_STATS 1 -#endif - -/** - * ETHARP_STATS==1: Enable etharp stats. - */ -#ifndef ETHARP_STATS -#define ETHARP_STATS (LWIP_ARP) -#endif - -/** - * IP_STATS==1: Enable IP stats. - */ -#ifndef IP_STATS -#define IP_STATS 1 -#endif - -/** - * IPFRAG_STATS==1: Enable IP fragmentation stats. Default is - * on if using either frag or reass. - */ -#ifndef IPFRAG_STATS -#define IPFRAG_STATS (IP_REASSEMBLY || IP_FRAG) -#endif - -/** - * ICMP_STATS==1: Enable ICMP stats. - */ -#ifndef ICMP_STATS -#define ICMP_STATS 1 -#endif - -/** - * IGMP_STATS==1: Enable IGMP stats. - */ -#ifndef IGMP_STATS -#define IGMP_STATS (LWIP_IGMP) -#endif - -/** - * UDP_STATS==1: Enable UDP stats. Default is on if - * UDP enabled, otherwise off. - */ -#ifndef UDP_STATS -#define UDP_STATS (LWIP_UDP) -#endif - -/** - * TCP_STATS==1: Enable TCP stats. Default is on if TCP - * enabled, otherwise off. - */ -#ifndef TCP_STATS -#define TCP_STATS (LWIP_TCP) -#endif - -/** - * MEM_STATS==1: Enable mem.c stats. - */ -#ifndef MEM_STATS -#define MEM_STATS ((MEM_LIBC_MALLOC == 0) && (MEM_USE_POOLS == 0)) -#endif - -/** - * MEMP_STATS==1: Enable memp.c pool stats. - */ -#ifndef MEMP_STATS -#define MEMP_STATS (MEMP_MEM_MALLOC == 0) -#endif - -/** - * SYS_STATS==1: Enable system stats (sem and mbox counts, etc). - */ -#ifndef SYS_STATS -#define SYS_STATS (NO_SYS == 0) -#endif - -#else - -#define LINK_STATS 0 -#define IP_STATS 0 -#define IPFRAG_STATS 0 -#define ICMP_STATS 0 -#define IGMP_STATS 0 -#define UDP_STATS 0 -#define TCP_STATS 0 -#define MEM_STATS 0 -#define MEMP_STATS 0 -#define SYS_STATS 0 -#define LWIP_STATS_DISPLAY 0 - -#endif /* LWIP_STATS */ - -/* - --------------------------------- - ---------- PPP options ---------- - --------------------------------- -*/ -/** - * PPP_SUPPORT==1: Enable PPP. - */ -#ifndef PPP_SUPPORT -#define PPP_SUPPORT 0 -#endif - -/** - * PPPOE_SUPPORT==1: Enable PPP Over Ethernet - */ -#ifndef PPPOE_SUPPORT -#define PPPOE_SUPPORT 0 -#endif - -/** - * PPPOS_SUPPORT==1: Enable PPP Over Serial - */ -#ifndef PPPOS_SUPPORT -#define PPPOS_SUPPORT PPP_SUPPORT -#endif - -#if PPP_SUPPORT - -/** - * NUM_PPP: Max PPP sessions. - */ -#ifndef NUM_PPP -#define NUM_PPP 1 -#endif - -/** - * PAP_SUPPORT==1: Support PAP. - */ -#ifndef PAP_SUPPORT -#define PAP_SUPPORT 0 -#endif - -/** - * CHAP_SUPPORT==1: Support CHAP. - */ -#ifndef CHAP_SUPPORT -#define CHAP_SUPPORT 0 -#endif - -/** - * MSCHAP_SUPPORT==1: Support MSCHAP. CURRENTLY NOT SUPPORTED! DO NOT SET! - */ -#ifndef MSCHAP_SUPPORT -#define MSCHAP_SUPPORT 0 -#endif - -/** - * CBCP_SUPPORT==1: Support CBCP. CURRENTLY NOT SUPPORTED! DO NOT SET! - */ -#ifndef CBCP_SUPPORT -#define CBCP_SUPPORT 0 -#endif - -/** - * CCP_SUPPORT==1: Support CCP. CURRENTLY NOT SUPPORTED! DO NOT SET! - */ -#ifndef CCP_SUPPORT -#define CCP_SUPPORT 0 -#endif - -/** - * VJ_SUPPORT==1: Support VJ header compression. - */ -#ifndef VJ_SUPPORT -#define VJ_SUPPORT 0 -#endif - -/** - * MD5_SUPPORT==1: Support MD5 (see also CHAP). - */ -#ifndef MD5_SUPPORT -#define MD5_SUPPORT 0 -#endif - -/* - * Timeouts - */ -#ifndef FSM_DEFTIMEOUT -#define FSM_DEFTIMEOUT 6 /* Timeout time in seconds */ -#endif - -#ifndef FSM_DEFMAXTERMREQS -#define FSM_DEFMAXTERMREQS 2 /* Maximum Terminate-Request transmissions */ -#endif - -#ifndef FSM_DEFMAXCONFREQS -#define FSM_DEFMAXCONFREQS 10 /* Maximum Configure-Request transmissions */ -#endif - -#ifndef FSM_DEFMAXNAKLOOPS -#define FSM_DEFMAXNAKLOOPS 5 /* Maximum number of nak loops */ -#endif - -#ifndef UPAP_DEFTIMEOUT -#define UPAP_DEFTIMEOUT 6 /* Timeout (seconds) for retransmitting req */ -#endif - -#ifndef UPAP_DEFREQTIME -#define UPAP_DEFREQTIME 30 /* Time to wait for auth-req from peer */ -#endif - -#ifndef CHAP_DEFTIMEOUT -#define CHAP_DEFTIMEOUT 6 /* Timeout time in seconds */ -#endif - -#ifndef CHAP_DEFTRANSMITS -#define CHAP_DEFTRANSMITS 10 /* max # times to send challenge */ -#endif - -/* Interval in seconds between keepalive echo requests, 0 to disable. */ -#ifndef LCP_ECHOINTERVAL -#define LCP_ECHOINTERVAL 0 -#endif - -/* Number of unanswered echo requests before failure. */ -#ifndef LCP_MAXECHOFAILS -#define LCP_MAXECHOFAILS 3 -#endif - -/* Max Xmit idle time (in jiffies) before resend flag char. */ -#ifndef PPP_MAXIDLEFLAG -#define PPP_MAXIDLEFLAG 100 -#endif - -/* - * Packet sizes - * - * Note - lcp shouldn't be allowed to negotiate stuff outside these - * limits. See lcp.h in the pppd directory. - * (XXX - these constants should simply be shared by lcp.c instead - * of living in lcp.h) - */ -#define PPP_MTU 1500 /* Default MTU (size of Info field) */ -#ifndef PPP_MAXMTU -/* #define PPP_MAXMTU 65535 - (PPP_HDRLEN + PPP_FCSLEN) */ -#define PPP_MAXMTU 1500 /* Largest MTU we allow */ -#endif -#define PPP_MINMTU 64 -#define PPP_MRU 1500 /* default MRU = max length of info field */ -#define PPP_MAXMRU 1500 /* Largest MRU we allow */ -#ifndef PPP_DEFMRU -#define PPP_DEFMRU 296 /* Try for this */ -#endif -#define PPP_MINMRU 128 /* No MRUs below this */ - -#ifndef MAXNAMELEN -#define MAXNAMELEN 256 /* max length of hostname or name for auth */ -#endif -#ifndef MAXSECRETLEN -#define MAXSECRETLEN 256 /* max length of password or secret */ -#endif - -#endif /* PPP_SUPPORT */ - -/* - -------------------------------------- - ---------- Checksum options ---------- - -------------------------------------- -*/ -/** - * CHECKSUM_GEN_IP==1: Generate checksums in software for outgoing IP packets. - */ -#ifndef CHECKSUM_GEN_IP -#define CHECKSUM_GEN_IP 1 -#endif - -/** - * CHECKSUM_GEN_UDP==1: Generate checksums in software for outgoing UDP packets. - */ -#ifndef CHECKSUM_GEN_UDP -#define CHECKSUM_GEN_UDP 1 -#endif - -/** - * CHECKSUM_GEN_TCP==1: Generate checksums in software for outgoing TCP packets. - */ -#ifndef CHECKSUM_GEN_TCP -#define CHECKSUM_GEN_TCP 1 -#endif - -/** - * CHECKSUM_GEN_ICMP==1: Generate checksums in software for outgoing ICMP packets. - */ -#ifndef CHECKSUM_GEN_ICMP -#define CHECKSUM_GEN_ICMP 1 -#endif - -/** - * CHECKSUM_CHECK_IP==1: Check checksums in software for incoming IP packets. - */ -#ifndef CHECKSUM_CHECK_IP -#define CHECKSUM_CHECK_IP 1 -#endif - -/** - * CHECKSUM_CHECK_UDP==1: Check checksums in software for incoming UDP packets. - */ -#ifndef CHECKSUM_CHECK_UDP -#define CHECKSUM_CHECK_UDP 1 -#endif - -/** - * CHECKSUM_CHECK_TCP==1: Check checksums in software for incoming TCP packets. - */ -#ifndef CHECKSUM_CHECK_TCP -#define CHECKSUM_CHECK_TCP 1 -#endif - -/** - * LWIP_CHECKSUM_ON_COPY==1: Calculate checksum when copying data from - * application buffers to pbufs. - */ -#ifndef LWIP_CHECKSUM_ON_COPY -#define LWIP_CHECKSUM_ON_COPY 0 -#endif - -/* - --------------------------------------- - ---------- Hook options --------------- - --------------------------------------- -*/ - -/* Hooks are undefined by default, define them to a function if you need them. */ - -/** - * LWIP_HOOK_IP4_INPUT(pbuf, input_netif): - * - called from ip_input() (IPv4) - * - pbuf: received struct pbuf passed to ip_input() - * - input_netif: struct netif on which the packet has been received - * Return values: - * - 0: Hook has not consumed the packet, packet is processed as normal - * - != 0: Hook has consumed the packet. - * If the hook consumed the packet, 'pbuf' is in the responsibility of the hook - * (i.e. free it when done). - */ - -/** - * LWIP_HOOK_IP4_ROUTE(dest): - * - called from ip_route() (IPv4) - * - dest: destination IPv4 address - * Returns the destination netif or NULL if no destination netif is found. In - * that case, ip_route() continues as normal. - */ - -/* - --------------------------------------- - ---------- Debugging options ---------- - --------------------------------------- -*/ -/** - * LWIP_DBG_MIN_LEVEL: After masking, the value of the debug is - * compared against this value. If it is smaller, then debugging - * messages are written. - */ -#ifndef LWIP_DBG_MIN_LEVEL -#define LWIP_DBG_MIN_LEVEL LWIP_DBG_LEVEL_ALL -#endif - -/** - * LWIP_DBG_TYPES_ON: A mask that can be used to globally enable/disable - * debug messages of certain types. - */ -#ifndef LWIP_DBG_TYPES_ON -#define LWIP_DBG_TYPES_ON LWIP_DBG_ON -#endif - -/** - * ETHARP_DEBUG: Enable debugging in etharp.c. - */ -#ifndef ETHARP_DEBUG -#define ETHARP_DEBUG LWIP_DBG_ON -#endif - -/** - * NETIF_DEBUG: Enable debugging in netif.c. - */ -#ifndef NETIF_DEBUG -#define NETIF_DEBUG LWIP_DBG_OFF -#endif - -/** - * PBUF_DEBUG: Enable debugging in pbuf.c. - */ -#ifndef PBUF_DEBUG -#define PBUF_DEBUG LWIP_DBG_OFF -#endif - -/** - * API_LIB_DEBUG: Enable debugging in api_lib.c. - */ -#ifndef API_LIB_DEBUG -#define API_LIB_DEBUG LWIP_DBG_OFF -#endif - -/** - * API_MSG_DEBUG: Enable debugging in api_msg.c. - */ -#ifndef API_MSG_DEBUG -#define API_MSG_DEBUG LWIP_DBG_OFF -#endif - -/** - * SOCKETS_DEBUG: Enable debugging in sockets.c. - */ -#ifndef SOCKETS_DEBUG -#define SOCKETS_DEBUG LWIP_DBG_OFF -#endif - -/** - * ICMP_DEBUG: Enable debugging in icmp.c. - */ -#ifndef ICMP_DEBUG -#define ICMP_DEBUG LWIP_DBG_OFF -#endif - -/** - * IGMP_DEBUG: Enable debugging in igmp.c. - */ -#ifndef IGMP_DEBUG -#define IGMP_DEBUG LWIP_DBG_OFF -#endif - -/** - * INET_DEBUG: Enable debugging in inet.c. - */ -#ifndef INET_DEBUG -#define INET_DEBUG LWIP_DBG_OFF -#endif - -/** - * IP_DEBUG: Enable debugging for IP. - */ -#ifndef IP_DEBUG -#define IP_DEBUG LWIP_DBG_OFF -#endif - -/** - * IP_REASS_DEBUG: Enable debugging in ip_frag.c for both frag & reass. - */ -#ifndef IP_REASS_DEBUG -#define IP_REASS_DEBUG LWIP_DBG_OFF -#endif - -/** - * RAW_DEBUG: Enable debugging in raw.c. - */ -#ifndef RAW_DEBUG -#define RAW_DEBUG LWIP_DBG_ON -#endif - -/** - * MEM_DEBUG: Enable debugging in mem.c. - */ -#ifndef MEM_DEBUG -#define MEM_DEBUG LWIP_DBG_ON -#endif - -/** - * MEMP_DEBUG: Enable debugging in memp.c. - */ -#ifndef MEMP_DEBUG -#define MEMP_DEBUG LWIP_DBG_OFF -#endif - -/** - * SYS_DEBUG: Enable debugging in sys.c. - */ -#ifndef SYS_DEBUG -#define SYS_DEBUG LWIP_DBG_ON -#endif - -/** - * TIMERS_DEBUG: Enable debugging in timers.c. - */ -#ifndef TIMERS_DEBUG -#define TIMERS_DEBUG LWIP_DBG_OFF -#endif - -/** - * TCP_DEBUG: Enable debugging for TCP. - */ -#ifndef TCP_DEBUG -#define TCP_DEBUG LWIP_DBG_OFF -#endif - -/** - * TCP_INPUT_DEBUG: Enable debugging in tcp_in.c for incoming debug. - */ -#ifndef TCP_INPUT_DEBUG -#define TCP_INPUT_DEBUG LWIP_DBG_OFF -#endif - -/** - * TCP_FR_DEBUG: Enable debugging in tcp_in.c for fast retransmit. - */ -#ifndef TCP_FR_DEBUG -#define TCP_FR_DEBUG LWIP_DBG_OFF -#endif - -/** - * TCP_RTO_DEBUG: Enable debugging in TCP for retransmit - * timeout. - */ -#ifndef TCP_RTO_DEBUG -#define TCP_RTO_DEBUG LWIP_DBG_OFF -#endif - -/** - * TCP_CWND_DEBUG: Enable debugging for TCP congestion window. - */ -#ifndef TCP_CWND_DEBUG -#define TCP_CWND_DEBUG LWIP_DBG_OFF -#endif - -/** - * TCP_WND_DEBUG: Enable debugging in tcp_in.c for window updating. - */ -#ifndef TCP_WND_DEBUG -#define TCP_WND_DEBUG LWIP_DBG_OFF -#endif - -/** - * TCP_OUTPUT_DEBUG: Enable debugging in tcp_out.c output functions. - */ -#ifndef TCP_OUTPUT_DEBUG -#define TCP_OUTPUT_DEBUG LWIP_DBG_OFF -#endif - -/** - * TCP_RST_DEBUG: Enable debugging for TCP with the RST message. - */ -#ifndef TCP_RST_DEBUG -#define TCP_RST_DEBUG LWIP_DBG_OFF -#endif - -/** - * TCP_QLEN_DEBUG: Enable debugging for TCP queue lengths. - */ -#ifndef TCP_QLEN_DEBUG -#define TCP_QLEN_DEBUG LWIP_DBG_OFF -#endif - -/** - * UDP_DEBUG: Enable debugging in UDP. - */ -#ifndef UDP_DEBUG -#define UDP_DEBUG LWIP_DBG_OFF -#endif - -/** - * TCPIP_DEBUG: Enable debugging in tcpip.c. - */ -#ifndef TCPIP_DEBUG -#define TCPIP_DEBUG LWIP_DBG_ON -#endif - -/** - * PPP_DEBUG: Enable debugging for PPP. - */ -#ifndef PPP_DEBUG -#define PPP_DEBUG LWIP_DBG_OFF -#endif - -/** - * SLIP_DEBUG: Enable debugging in slipif.c. - */ -#ifndef SLIP_DEBUG -#define SLIP_DEBUG LWIP_DBG_OFF -#endif - -/** - * DHCP_DEBUG: Enable debugging in dhcp.c. - */ -#ifndef DHCP_DEBUG -#define DHCP_DEBUG LWIP_DBG_OFF -#endif - -/** - * AUTOIP_DEBUG: Enable debugging in autoip.c. - */ -#ifndef AUTOIP_DEBUG -#define AUTOIP_DEBUG LWIP_DBG_OFF -#endif - -/** - * SNMP_MSG_DEBUG: Enable debugging for SNMP messages. - */ -#ifndef SNMP_MSG_DEBUG -#define SNMP_MSG_DEBUG LWIP_DBG_OFF -#endif - -/** - * SNMP_MIB_DEBUG: Enable debugging for SNMP MIBs. - */ -#ifndef SNMP_MIB_DEBUG -#define SNMP_MIB_DEBUG LWIP_DBG_OFF -#endif - -/** - * DNS_DEBUG: Enable debugging for DNS. - */ -#ifndef DNS_DEBUG -#define DNS_DEBUG LWIP_DBG_OFF -#endif - -#define LWIP_RAND chibios_rand_generate - -#endif /* __LWIPOPT_H__ */ From 4dc513e78c68d648c9ec0875887e40b5948a72a8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 25 Dec 2023 14:33:38 +1100 Subject: [PATCH 0322/1335] lwip: remove ext/lwip and add as modules/lwip --- .gitmodules | 3 +++ modules/ChibiOS | 2 +- modules/lwip | 1 + 3 files changed, 5 insertions(+), 1 deletion(-) create mode 160000 modules/lwip diff --git a/.gitmodules b/.gitmodules index fbfe76753a51d6..6a900f5fbaad67 100644 --- a/.gitmodules +++ b/.gitmodules @@ -39,3 +39,6 @@ path = modules/Micro-CDR url = https://github.com/ardupilot/Micro-CDR.git branch = master +[submodule "modules/lwip"] + path = modules/lwip + url = https://github.com/ArduPilot/lwip.git diff --git a/modules/ChibiOS b/modules/ChibiOS index d8c45abde5fb39..6a85082c715457 160000 --- a/modules/ChibiOS +++ b/modules/ChibiOS @@ -1 +1 @@ -Subproject commit d8c45abde5fb398ef9da6fc8fc36992f2ae7b15c +Subproject commit 6a85082c715457d1e0cc9627f9939f349de1143e diff --git a/modules/lwip b/modules/lwip new file mode 160000 index 00000000000000..0a0452b2c39bdd --- /dev/null +++ b/modules/lwip @@ -0,0 +1 @@ +Subproject commit 0a0452b2c39bdd91e252aef045c115f88f6ca773 From 8b3f3bc2d2783bae80333a66c647dd9ccf1a79cd Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 25 Dec 2023 14:40:22 +1100 Subject: [PATCH 0323/1335] waf: new location for lwip --- Tools/ardupilotwaf/boards.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index dc78c9f54ba8eb..8cb43ddacf43c4 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -1158,7 +1158,7 @@ def configure_env(self, cfg, env): env.INCLUDES += [ cfg.srcnode.find_dir('libraries/AP_GyroFFT/CMSIS_5/include').abspath(), - cfg.srcnode.find_dir('modules/ChibiOS/ext/lwip/src/include/compat/posix').abspath() + cfg.srcnode.find_dir('modules/lwip/src/include/compat/posix').abspath() ] # whitelist of compilers which we should build with -Werror From 9d5a54259e60cb0ade2da3a3444189a8e3924021 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 25 Dec 2023 14:40:32 +1100 Subject: [PATCH 0324/1335] AP_Networking: new location for lwip --- libraries/AP_Networking/wscript | 24 +++++++++--------------- 1 file changed, 9 insertions(+), 15 deletions(-) diff --git a/libraries/AP_Networking/wscript b/libraries/AP_Networking/wscript index 64d985c6ce0e0d..e1ed0c9af2cbd0 100644 --- a/libraries/AP_Networking/wscript +++ b/libraries/AP_Networking/wscript @@ -5,26 +5,20 @@ import pathlib def configure(cfg): extra_src = [ - 'modules/ChibiOS/ext/lwip/src/core/*c', - 'modules/ChibiOS/ext/lwip/src/core/ipv4/*c', - 'modules/ChibiOS/ext/lwip/src/api/*c', - 'modules/ChibiOS/ext/lwip/src/netif/*c', - 'modules/ChibiOS/ext/lwip/src/netif/ppp/*c', + 'modules/lwip/src/core/*c', + 'modules/lwip/src/core/ipv4/*c', + 'modules/lwip/src/api/*c', + 'modules/lwip/src/netif/*c', + 'modules/lwip/src/netif/ppp/*c', ] extra_src_inc = [ - 'modules/ChibiOS/ext/lwip/src/include', + 'modules/lwip/src/include', ] - if cfg.env.BOARD_CLASS == "SITL": - extra_src.extend(['libraries/AP_Networking/lwip_hal/arch/*cpp']) - extra_src_inc.extend(['libraries/AP_Networking/config', - 'libraries/AP_Networking/lwip_hal/include']) - - if cfg.env.BOARD_CLASS == "ChibiOS": - extra_src.extend(['libraries/AP_Networking/lwip_hal/arch/*cpp']) - extra_src_inc.extend(['libraries/AP_Networking/config', - 'libraries/AP_Networking/lwip_hal/include']) + extra_src.extend(['libraries/AP_Networking/lwip_hal/arch/*cpp']) + extra_src_inc.extend(['libraries/AP_Networking/config', + 'libraries/AP_Networking/lwip_hal/include']) cfg.env.AP_LIB_EXTRA_SOURCES['AP_Networking'] = [] for pattern in extra_src: From d26530c892658560411110d5fbcf6a492a934961 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 06:46:41 +1100 Subject: [PATCH 0325/1335] waf: added --enable-ppp option --- Tools/ardupilotwaf/boards.py | 3 +++ wscript | 5 +++++ 2 files changed, 8 insertions(+) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index 8cb43ddacf43c4..efcb8782ebcbab 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -148,6 +148,9 @@ def srcpath(path): ) cfg.msg("Enabled custom controller", 'no', color='YELLOW') + if cfg.options.enable_ppp: + env.CXXFLAGS += ['-DAP_NETWORKING_BACKEND_PPP=1'] + if cfg.options.disable_networking: env.CXXFLAGS += ['-DAP_NETWORKING_ENABLED=0'] diff --git a/wscript b/wscript index 31da3e0ba2e344..8d2c2a68b2b299 100644 --- a/wscript +++ b/wscript @@ -180,6 +180,11 @@ def options(opt): action='store_true', default=False, help='enable OS level thread statistics.') + + g.add_option('--enable-ppp', + action='store_true', + default=False, + help='enable PPP networking.') g.add_option('--bootloader', action='store_true', From 812ac6bc0a1c840f87b992f3170ef80f2854b19a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 06:51:40 +1100 Subject: [PATCH 0326/1335] AP_Networking: allow for --enable-ppp to enable networking --- libraries/AP_Networking/AP_Networking_Config.h | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/libraries/AP_Networking/AP_Networking_Config.h b/libraries/AP_Networking/AP_Networking_Config.h index b08b936e3b9ff0..c55ef506245e1a 100644 --- a/libraries/AP_Networking/AP_Networking_Config.h +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -1,5 +1,10 @@ #include +#if defined(AP_NETWORKING_BACKEND_PPP) && !defined(AP_NETWORKING_ENABLED) +// allow --enable-ppp to enable networking +#define AP_NETWORKING_ENABLED AP_NETWORKING_BACKEND_PPP +#endif + #ifndef AP_NETWORKING_ENABLED #define AP_NETWORKING_ENABLED 0 #endif From 799b01c6c6eb7522f2326b99477cd5d64835bbfb Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 08:17:22 +1100 Subject: [PATCH 0327/1335] Tools: added --enable-ppp to sim_vehicle.py --- Tools/autotest/sim_vehicle.py | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/Tools/autotest/sim_vehicle.py b/Tools/autotest/sim_vehicle.py index 5a0ccb5c5ddf3b..0d623e8c8f3e9d 100755 --- a/Tools/autotest/sim_vehicle.py +++ b/Tools/autotest/sim_vehicle.py @@ -414,6 +414,9 @@ def do_build(opts, frame_options): if opts.disable_networking: cmd_configure.append("--disable-networking") + if opts.enable_ppp: + cmd_configure.append("--enable-ppp") + if opts.enable_networking_tests: cmd_configure.append("--enable-networking-tests") @@ -1333,6 +1336,8 @@ def generate_frame_help(): help="Enable the dds client to connect with ROS2/DDS") group_sim.add_option("--disable-networking", action='store_true', help="Disable networking APIs") +group_sim.add_option("--enable-ppp", action='store_true', + help="Enable PPP networking") group_sim.add_option("--enable-networking-tests", action='store_true', help="Enable networking tests") From 3d5251dfe82035baf54020d9888dbde68beac8cd Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 08:18:41 +1100 Subject: [PATCH 0328/1335] AP_HAL: added inet_str_to_addr to SocketAPM --- libraries/AP_HAL/utility/Socket.cpp | 26 +++++++++++++++++++++----- libraries/AP_HAL/utility/Socket.h | 5 ++++- 2 files changed, 25 insertions(+), 6 deletions(-) diff --git a/libraries/AP_HAL/utility/Socket.cpp b/libraries/AP_HAL/utility/Socket.cpp index 57aa2bd74f6a2e..8881bb074f8a6e 100644 --- a/libraries/AP_HAL/utility/Socket.cpp +++ b/libraries/AP_HAL/utility/Socket.cpp @@ -74,7 +74,12 @@ SocketAPM::SocketAPM(bool _datagram, int _fd) : SocketAPM::~SocketAPM() { - close(); + if (fd != -1) { + CALL_PREFIX(close)(fd); + } + if (fd_in != -1) { + CALL_PREFIX(close)(fd_in); + } } void SocketAPM::make_sockaddr(const char *address, uint16_t port, struct sockaddr_in &sockaddr) @@ -86,7 +91,7 @@ void SocketAPM::make_sockaddr(const char *address, uint16_t port, struct sockadd #endif sockaddr.sin_port = htons(port); sockaddr.sin_family = AF_INET; - sockaddr.sin_addr.s_addr = inet_addr(address); + sockaddr.sin_addr.s_addr = htonl(inet_str_to_addr(address)); } /* @@ -360,7 +365,7 @@ const char *SocketAPM::last_recv_address(char *ip_addr_buf, uint8_t buflen, uint { const struct sockaddr_in &sin = *(struct sockaddr_in *)&last_in_addr[0]; - const char *ret = inet_addr_to_str((void*)&sin.sin_addr, ip_addr_buf, buflen); + const char *ret = inet_addr_to_str(ntohl(sin.sin_addr.s_addr), ip_addr_buf, buflen); if (ret == nullptr) { return nullptr; } @@ -503,9 +508,20 @@ SocketAPM *SocketAPM::duplicate(void) return ret; } -const char *SocketAPM::inet_addr_to_str(const void *src, char *dst, uint16_t len) +// access to inet_ntop, takes host order ipv4 as uint32_t +const char *SocketAPM::inet_addr_to_str(uint32_t addr, char *dst, uint16_t len) { - return CALL_PREFIX(inet_ntop)(AF_INET, src, dst, len); + addr = htonl(addr); + return CALL_PREFIX(inet_ntop)(AF_INET, (void*)&addr, dst, len); +} + +// access to inet_pton, returns host order ipv4 as uint32_t +uint32_t SocketAPM::inet_str_to_addr(const char *ipstr) +{ + uint32_t ret = 0; + CALL_PREFIX(inet_pton)(AF_INET, ipstr, &ret); + return ntohl(ret); + } #endif // AP_NETWORKING_BACKEND_ANY diff --git a/libraries/AP_HAL/utility/Socket.h b/libraries/AP_HAL/utility/Socket.h index 82c0ee2604c4c5..0efba9ebd7a59b 100644 --- a/libraries/AP_HAL/utility/Socket.h +++ b/libraries/AP_HAL/utility/Socket.h @@ -76,8 +76,11 @@ class SocketAPM { } // access to inet_ntop - static const char *inet_addr_to_str(const void *src, char *dst, uint16_t len); + static const char *inet_addr_to_str(uint32_t addr, char *dst, uint16_t len); + // access to inet_pton + static uint32_t inet_str_to_addr(const char *ipstr); + private: bool datagram; // we avoid using struct sockaddr_in here to keep support for From ec5ff94f3e19561856d130111f655c28ce916b43 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 08:19:15 +1100 Subject: [PATCH 0329/1335] AP_Networking: cleanup string to IP handling use SocketAPM methods --- libraries/AP_Networking/AP_Networking.cpp | 23 ++------- libraries/AP_Networking/AP_Networking.h | 51 ------------------- .../AP_Networking/AP_Networking_address.cpp | 4 +- 3 files changed, 6 insertions(+), 72 deletions(-) diff --git a/libraries/AP_Networking/AP_Networking.cpp b/libraries/AP_Networking/AP_Networking.cpp index 2eaee5dfde61c7..87ca70bd94ad71 100644 --- a/libraries/AP_Networking/AP_Networking.cpp +++ b/libraries/AP_Networking/AP_Networking.cpp @@ -19,7 +19,6 @@ extern const AP_HAL::HAL& hal; #include #include -#include #include @@ -183,9 +182,10 @@ void AP_Networking::announce_address_changes() return; } - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: IP %s", get_ip_active_str()); - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: Mask %s", get_netmask_active_str()); - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: Gateway %s", get_gateway_active_str()); + char ipstr[16]; + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: IP %s", SocketAPM::inet_addr_to_str(get_ip_active(), ipstr, sizeof(ipstr))); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: Mask %s", SocketAPM::inet_addr_to_str(get_netmask_active(), ipstr, sizeof(ipstr))); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: Gateway %s", SocketAPM::inet_addr_to_str(get_gateway_active(), ipstr, sizeof(ipstr))); announce_ms = as.last_change_ms; } @@ -223,21 +223,6 @@ uint8_t AP_Networking::convert_netmask_ip_to_bitcount(const uint32_t netmask_ip) return netmask_bitcount; } -uint32_t AP_Networking::convert_str_to_ip(const char* ip_str) -{ - uint32_t ip = 0; - lwip_inet_pton(AF_INET, ip_str, &ip); - return ntohl(ip); -} - -const char* AP_Networking::convert_ip_to_str(uint32_t ip) -{ - ip = htonl(ip); - static char _str_buffer[20]; - lwip_inet_ntop(AF_INET, &ip, _str_buffer, sizeof(_str_buffer)); - return _str_buffer; -} - /* convert a string to an ethernet MAC address */ diff --git a/libraries/AP_Networking/AP_Networking.h b/libraries/AP_Networking/AP_Networking.h index 005a521997833e..3b18072593b70f 100644 --- a/libraries/AP_Networking/AP_Networking.h +++ b/libraries/AP_Networking/AP_Networking.h @@ -91,15 +91,6 @@ class AP_Networking #endif } - /* - returns a null terminated string of the active IP address. Example: "192.168.12.13" - Note that the returned - */ - const char *get_ip_active_str() const - { - return convert_ip_to_str(get_ip_active()); - } - // sets the user-parameter static IP address from a 32bit value void set_ip_param(const uint32_t ip) { @@ -122,29 +113,6 @@ class AP_Networking #endif } - // returns a null terminated string of the active Netmask address. Example: "192.168.12.13" - const char *get_netmask_active_str() - { - return convert_ip_to_str(get_netmask_active()); - } - - const char *get_netmask_param_str() - { - return convert_ip_to_str(get_netmask_param()); - } - - void set_netmask_param_str(const char* nm_str) - { - set_netmask_param(convert_str_to_ip((char*)nm_str)); - } - - void set_netmask_param(const uint32_t nm) - { -#if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED - param.netmask.set(convert_netmask_ip_to_bitcount(nm)); -#endif - } - uint32_t get_gateway_active() const; uint32_t get_gateway_param() const @@ -157,21 +125,6 @@ class AP_Networking #endif } - const char *get_gateway_active_str() - { - return convert_ip_to_str(get_gateway_active()); - } - - const char *get_gateway_param_str() - { - return convert_ip_to_str(get_gateway_param()); - } - - void set_gateway_param_str(const char* gw_str) - { - set_gateway_param(convert_str_to_ip((char*)gw_str)); - } - void set_gateway_param(const uint32_t gw) { #if AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED @@ -182,10 +135,6 @@ class AP_Networking // wait in a thread for network startup void startup_wait(void) const; - // helper functions to convert between 32bit IP addresses and null terminated strings and back - static uint32_t convert_str_to_ip(const char* ip_str); - static const char* convert_ip_to_str(uint32_t ip); - // convert string to ethernet mac address static bool convert_str_to_macaddr(const char *mac_str, uint8_t addr[6]); diff --git a/libraries/AP_Networking/AP_Networking_address.cpp b/libraries/AP_Networking/AP_Networking_address.cpp index a1c1cdc59ca49c..ddb36428e19f34 100644 --- a/libraries/AP_Networking/AP_Networking_address.cpp +++ b/libraries/AP_Networking/AP_Networking_address.cpp @@ -49,7 +49,7 @@ const AP_Param::GroupInfo AP_Networking_IPV4::var_info[] = { AP_Networking_IPV4::AP_Networking_IPV4(const char *default_addr) { AP_Param::setup_object_defaults(this, var_info); - set_default_uint32(AP_Networking::convert_str_to_ip(default_addr)); + set_default_uint32(SocketAPM::inet_str_to_addr(default_addr)); } uint32_t AP_Networking_IPV4::get_uint32(void) const @@ -73,7 +73,7 @@ void AP_Networking_IPV4::set_default_uint32(uint32_t v) const char* AP_Networking_IPV4::get_str() { const auto ip = ntohl(get_uint32()); - return SocketAPM::inet_addr_to_str(&ip, strbuf, sizeof(strbuf)); + return SocketAPM::inet_addr_to_str(ip, strbuf, sizeof(strbuf)); } #endif // AP_NETWORKING_ENABLED From 985816ebc2bc2b4abe3297fa13dd4c570e36a6ec Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 08:19:28 +1100 Subject: [PATCH 0330/1335] AP_Networking: don't enable PPP by default --- libraries/AP_Networking/AP_Networking_Config.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Networking/AP_Networking_Config.h b/libraries/AP_Networking/AP_Networking_Config.h index c55ef506245e1a..b6aa08af30b1c0 100644 --- a/libraries/AP_Networking/AP_Networking_Config.h +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -33,7 +33,7 @@ #endif #ifndef AP_NETWORKING_BACKEND_PPP -#define AP_NETWORKING_BACKEND_PPP (AP_NETWORKING_BACKEND_DEFAULT_ENABLED) +#define AP_NETWORKING_BACKEND_PPP 0 #endif #ifndef AP_NETWORKING_BACKEND_SITL From 7e29452082e4172e7ce6d69fd51d1f656e6bffe9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 13:41:28 +1100 Subject: [PATCH 0331/1335] AP_Networking: fix for linux build --- libraries/AP_Networking/AP_Networking_Config.h | 4 +++- libraries/AP_Networking/lwip_hal/arch/sys_arch.cpp | 14 +++++++------- 2 files changed, 10 insertions(+), 8 deletions(-) diff --git a/libraries/AP_Networking/AP_Networking_Config.h b/libraries/AP_Networking/AP_Networking_Config.h index b6aa08af30b1c0..803b06e1b7126d 100644 --- a/libraries/AP_Networking/AP_Networking_Config.h +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -6,7 +6,7 @@ #endif #ifndef AP_NETWORKING_ENABLED -#define AP_NETWORKING_ENABLED 0 +#define AP_NETWORKING_ENABLED ((CONFIG_HAL_BOARD == HAL_BOARD_LINUX) || (CONFIG_HAL_BOARD == HAL_BOARD_SITL)) #endif #ifndef AP_NETWORKING_BACKEND_DEFAULT_ENABLED @@ -40,7 +40,9 @@ #define AP_NETWORKING_BACKEND_SITL (AP_NETWORKING_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_SITL)) #endif +#ifndef AP_NETWORKING_SOCKETS_ENABLED #define AP_NETWORKING_SOCKETS_ENABLED AP_NETWORKING_ENABLED +#endif // --------------------------- // IP Features diff --git a/libraries/AP_Networking/lwip_hal/arch/sys_arch.cpp b/libraries/AP_Networking/lwip_hal/arch/sys_arch.cpp index ad9c8675881753..811ec76754782c 100644 --- a/libraries/AP_Networking/lwip_hal/arch/sys_arch.cpp +++ b/libraries/AP_Networking/lwip_hal/arch/sys_arch.cpp @@ -26,7 +26,7 @@ extern "C" { #include "lwip/tcpip.h" } -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX #include #elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS #include "hal.h" @@ -61,7 +61,7 @@ struct sys_mbox { }; struct sys_sem { -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX sem_t sem; #elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS semaphore_t sem; @@ -80,7 +80,7 @@ struct thread_wrapper_data { void *arg; }; -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX static void * thread_wrapper(void *arg) { @@ -107,7 +107,7 @@ sys_thread_new(const char *name, lwip_thread_fn function, void *arg, int stacksi thread_data->arg = arg; thread_data->function = function; -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX pthread_t t; if (pthread_create(&t, NULL, thread_wrapper, thread_data) == 0) { pthread_setname_np(t, name); @@ -346,7 +346,7 @@ sys_sem_new_internal(u8_t count) { auto *ret = new sys_sem; if (ret != nullptr) { -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX sem_init(&ret->sem, 0, count); #elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS chSemObjectInit(&ret->sem, (cnt_t)count); @@ -369,7 +369,7 @@ u32_t sys_arch_sem_wait(struct sys_sem **s, u32_t timeout_ms) { struct sys_sem *sem = *s; -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX if (timeout_ms == 0) { sem_wait(&sem->sem); return 0; @@ -404,7 +404,7 @@ void sys_sem_signal(struct sys_sem **s) { struct sys_sem *sem = *s; -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX sem_post(&sem->sem); #elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS chSemSignal(&sem->sem); From 20486315264147188bab03b8073323fdc840722c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 18:43:20 +1100 Subject: [PATCH 0332/1335] AP_Networking: ensure PPP does not dominate the CPU --- libraries/AP_Networking/AP_Networking_PPP.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_Networking/AP_Networking_PPP.cpp b/libraries/AP_Networking/AP_Networking_PPP.cpp index d421c9b4e0a9ea..b906743020b68d 100644 --- a/libraries/AP_Networking/AP_Networking_PPP.cpp +++ b/libraries/AP_Networking/AP_Networking_PPP.cpp @@ -39,6 +39,8 @@ uint32_t AP_Networking_PPP::ppp_output_cb(ppp_pcb *pcb, const void *data, uint32 if (n > 0) { remaining -= n; ptr += n; + } else { + hal.scheduler->delay_microseconds(100); } } return len; From c85f4f875c1674bb6177d102f0a24d207e2cf8b1 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 08:50:23 +1100 Subject: [PATCH 0333/1335] Tools: disable lwip with clang --- Tools/ardupilotwaf/boards.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index efcb8782ebcbab..c6c85784639473 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -687,7 +687,8 @@ def configure_env(self, cfg, env): '-Werror=missing-declarations', ] - if not cfg.options.disable_networking: + if not cfg.options.disable_networking and not 'clang' in cfg.env.COMPILER_CC: + # lwip doesn't build with clang env.CXXFLAGS += ['-DAP_NETWORKING_ENABLED=1'] if cfg.options.ubsan or cfg.options.ubsan_abort: From cbb3e2751913286b4cab785207451d0e0ae4ca5e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 13:20:15 +1100 Subject: [PATCH 0334/1335] AP_HAL: added SocketAPM_native this is a varient of SocketAPM that always uses native sockets (ie. doesn't go via AP_Networking lwip) --- libraries/AP_HAL/utility/Socket.cpp | 69 +++++++------- libraries/AP_HAL/utility/Socket.h | 99 ++------------------ libraries/AP_HAL/utility/Socket.hpp | 104 +++++++++++++++++++++ libraries/AP_HAL/utility/Socket_native.cpp | 11 +++ libraries/AP_HAL/utility/Socket_native.h | 22 +++++ 5 files changed, 180 insertions(+), 125 deletions(-) create mode 100644 libraries/AP_HAL/utility/Socket.hpp create mode 100644 libraries/AP_HAL/utility/Socket_native.cpp create mode 100644 libraries/AP_HAL/utility/Socket_native.h diff --git a/libraries/AP_HAL/utility/Socket.cpp b/libraries/AP_HAL/utility/Socket.cpp index 8881bb074f8a6e..2c33462b55124d 100644 --- a/libraries/AP_HAL/utility/Socket.cpp +++ b/libraries/AP_HAL/utility/Socket.cpp @@ -20,7 +20,14 @@ #include #if AP_NETWORKING_SOCKETS_ENABLED -#include "Socket.h" +#ifndef SOCKET_CLASS_NAME +#define SOCKET_CLASS_NAME SocketAPM +#endif + +#ifndef IN_SOCKET_NATIVE_CPP +#include "Socket.hpp" +#endif + #if AP_NETWORKING_BACKEND_CHIBIOS || AP_NETWORKING_BACKEND_PPP #include #else @@ -47,19 +54,17 @@ #define MSG_NOSIGNAL 0 #endif -static_assert(sizeof(last_in_addr) == sizeof(struct sockaddr_in), "last_in_addr must match sockaddr_in size"); - /* constructor */ -SocketAPM::SocketAPM(bool _datagram) : - SocketAPM(_datagram, +SOCKET_CLASS_NAME::SOCKET_CLASS_NAME(bool _datagram) : + SOCKET_CLASS_NAME(_datagram, CALL_PREFIX(socket)(AF_INET, _datagram?SOCK_DGRAM:SOCK_STREAM, 0)) { - static_assert(sizeof(SocketAPM::last_in_addr) >= sizeof(struct sockaddr_in), "last_in_addr must be at least sockaddr_in size"); + static_assert(sizeof(SOCKET_CLASS_NAME::last_in_addr) >= sizeof(struct sockaddr_in), "last_in_addr must be at least sockaddr_in size"); } -SocketAPM::SocketAPM(bool _datagram, int _fd) : +SOCKET_CLASS_NAME::SOCKET_CLASS_NAME(bool _datagram, int _fd) : datagram(_datagram), fd(_fd) { @@ -72,7 +77,7 @@ SocketAPM::SocketAPM(bool _datagram, int _fd) : } } -SocketAPM::~SocketAPM() +SOCKET_CLASS_NAME::~SOCKET_CLASS_NAME() { if (fd != -1) { CALL_PREFIX(close)(fd); @@ -82,7 +87,7 @@ SocketAPM::~SocketAPM() } } -void SocketAPM::make_sockaddr(const char *address, uint16_t port, struct sockaddr_in &sockaddr) +void SOCKET_CLASS_NAME::make_sockaddr(const char *address, uint16_t port, struct sockaddr_in &sockaddr) { memset(&sockaddr, 0, sizeof(sockaddr)); @@ -97,7 +102,7 @@ void SocketAPM::make_sockaddr(const char *address, uint16_t port, struct sockadd /* connect the socket */ -bool SocketAPM::connect(const char *address, uint16_t port) +bool SOCKET_CLASS_NAME::connect(const char *address, uint16_t port) { if (fd == -1) { return false; @@ -184,7 +189,7 @@ bool SocketAPM::connect(const char *address, uint16_t port) /* connect the socket with a timeout */ -bool SocketAPM::connect_timeout(const char *address, uint16_t port, uint32_t timeout_ms) +bool SOCKET_CLASS_NAME::connect_timeout(const char *address, uint16_t port, uint32_t timeout_ms) { if (fd == -1) { return false; @@ -218,7 +223,7 @@ bool SocketAPM::connect_timeout(const char *address, uint16_t port, uint32_t tim /* bind the socket */ -bool SocketAPM::bind(const char *address, uint16_t port) +bool SOCKET_CLASS_NAME::bind(const char *address, uint16_t port) { if (fd == -1) { return false; @@ -237,7 +242,7 @@ bool SocketAPM::bind(const char *address, uint16_t port) /* set SO_REUSEADDR */ -bool SocketAPM::reuseaddress(void) const +bool SOCKET_CLASS_NAME::reuseaddress(void) const { if (fd == -1) { return false; @@ -249,7 +254,7 @@ bool SocketAPM::reuseaddress(void) const /* set blocking state */ -bool SocketAPM::set_blocking(bool blocking) const +bool SOCKET_CLASS_NAME::set_blocking(bool blocking) const { if (fd == -1) { return false; @@ -272,7 +277,7 @@ bool SocketAPM::set_blocking(bool blocking) const /* set cloexec state */ -bool SocketAPM::set_cloexec() const +bool SOCKET_CLASS_NAME::set_cloexec() const { if (fd == -1) { return false; @@ -287,7 +292,7 @@ bool SocketAPM::set_cloexec() const /* send some data */ -ssize_t SocketAPM::send(const void *buf, size_t size) const +ssize_t SOCKET_CLASS_NAME::send(const void *buf, size_t size) const { if (fd == -1) { return -1; @@ -298,7 +303,7 @@ ssize_t SocketAPM::send(const void *buf, size_t size) const /* send some data */ -ssize_t SocketAPM::sendto(const void *buf, size_t size, const char *address, uint16_t port) +ssize_t SOCKET_CLASS_NAME::sendto(const void *buf, size_t size, const char *address, uint16_t port) { if (fd == -1) { return -1; @@ -311,7 +316,7 @@ ssize_t SocketAPM::sendto(const void *buf, size_t size, const char *address, uin /* receive some data */ -ssize_t SocketAPM::recv(void *buf, size_t size, uint32_t timeout_ms) +ssize_t SOCKET_CLASS_NAME::recv(void *buf, size_t size, uint32_t timeout_ms) { if (!pollin(timeout_ms)) { errno = EWOULDBLOCK; @@ -351,7 +356,7 @@ ssize_t SocketAPM::recv(void *buf, size_t size, uint32_t timeout_ms) /* return the IP address and port of the last received packet */ -void SocketAPM::last_recv_address(const char *&ip_addr, uint16_t &port) const +void SOCKET_CLASS_NAME::last_recv_address(const char *&ip_addr, uint16_t &port) const { static char buf[16]; auto *str = last_recv_address(buf, sizeof(buf), port); @@ -361,7 +366,7 @@ void SocketAPM::last_recv_address(const char *&ip_addr, uint16_t &port) const /* return the IP address and port of the last received packet, using caller supplied buffer */ -const char *SocketAPM::last_recv_address(char *ip_addr_buf, uint8_t buflen, uint16_t &port) const +const char *SOCKET_CLASS_NAME::last_recv_address(char *ip_addr_buf, uint8_t buflen, uint16_t &port) const { const struct sockaddr_in &sin = *(struct sockaddr_in *)&last_in_addr[0]; @@ -373,7 +378,7 @@ const char *SocketAPM::last_recv_address(char *ip_addr_buf, uint8_t buflen, uint return ret; } -void SocketAPM::set_broadcast(void) const +void SOCKET_CLASS_NAME::set_broadcast(void) const { if (fd == -1) { return; @@ -385,7 +390,7 @@ void SocketAPM::set_broadcast(void) const /* return true if there is pending data for input */ -bool SocketAPM::pollin(uint32_t timeout_ms) +bool SOCKET_CLASS_NAME::pollin(uint32_t timeout_ms) { fd_set fds; struct timeval tv; @@ -410,7 +415,7 @@ bool SocketAPM::pollin(uint32_t timeout_ms) /* return true if there is room for output data */ -bool SocketAPM::pollout(uint32_t timeout_ms) +bool SOCKET_CLASS_NAME::pollout(uint32_t timeout_ms) { if (fd == -1) { return false; @@ -433,7 +438,7 @@ bool SocketAPM::pollout(uint32_t timeout_ms) /* start listening for new tcp connections */ -bool SocketAPM::listen(uint16_t backlog) const +bool SOCKET_CLASS_NAME::listen(uint16_t backlog) const { if (fd == -1) { return false; @@ -445,7 +450,7 @@ bool SocketAPM::listen(uint16_t backlog) const accept a new connection. Only valid for TCP connections after listen has been used. A new socket is returned */ -SocketAPM *SocketAPM::accept(uint32_t timeout_ms) +SOCKET_CLASS_NAME *SOCKET_CLASS_NAME::accept(uint32_t timeout_ms) { if (fd == -1) { return nullptr; @@ -460,7 +465,7 @@ SocketAPM *SocketAPM::accept(uint32_t timeout_ms) if (newfd == -1) { return nullptr; } - auto *ret = new SocketAPM(false, newfd); + auto *ret = new SOCKET_CLASS_NAME(false, newfd); if (ret != nullptr) { ret->connected = true; ret->reuseaddress(); @@ -471,7 +476,7 @@ SocketAPM *SocketAPM::accept(uint32_t timeout_ms) /* return true if an address is in the multicast range */ -bool SocketAPM::is_multicast_address(struct sockaddr_in &addr) const +bool SOCKET_CLASS_NAME::is_multicast_address(struct sockaddr_in &addr) const { const uint32_t mc_lower = 0xE0000000; // 224.0.0.0 const uint32_t mc_upper = 0xEFFFFFFF; // 239.255.255.255 @@ -479,7 +484,7 @@ bool SocketAPM::is_multicast_address(struct sockaddr_in &addr) const return haddr >= mc_lower && haddr <= mc_upper; } -void SocketAPM::close(void) +void SOCKET_CLASS_NAME::close(void) { if (fd != -1) { CALL_PREFIX(close)(fd); @@ -495,9 +500,9 @@ void SocketAPM::close(void) duplicate a socket, giving a new object with the same contents, the fd in the old object is set to -1 */ -SocketAPM *SocketAPM::duplicate(void) +SOCKET_CLASS_NAME *SOCKET_CLASS_NAME::duplicate(void) { - auto *ret = new SocketAPM(datagram, fd); + auto *ret = new SOCKET_CLASS_NAME(datagram, fd); if (ret == nullptr) { return nullptr; } @@ -509,14 +514,14 @@ SocketAPM *SocketAPM::duplicate(void) } // access to inet_ntop, takes host order ipv4 as uint32_t -const char *SocketAPM::inet_addr_to_str(uint32_t addr, char *dst, uint16_t len) +const char *SOCKET_CLASS_NAME::inet_addr_to_str(uint32_t addr, char *dst, uint16_t len) { addr = htonl(addr); return CALL_PREFIX(inet_ntop)(AF_INET, (void*)&addr, dst, len); } // access to inet_pton, returns host order ipv4 as uint32_t -uint32_t SocketAPM::inet_str_to_addr(const char *ipstr) +uint32_t SOCKET_CLASS_NAME::inet_str_to_addr(const char *ipstr) { uint32_t ret = 0; CALL_PREFIX(inet_pton)(AF_INET, ipstr, &ret); diff --git a/libraries/AP_HAL/utility/Socket.h b/libraries/AP_HAL/utility/Socket.h index 0efba9ebd7a59b..61f5ee7ecf6a3d 100644 --- a/libraries/AP_HAL/utility/Socket.h +++ b/libraries/AP_HAL/utility/Socket.h @@ -1,101 +1,14 @@ /* - This program is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - This program is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with this program. If not, see . - */ -/* - simple socket handling class for systems with BSD socket API + variant of SocketAPM using either lwip or native sockets */ #pragma once #include -#include - -#if AP_NETWORKING_SOCKETS_ENABLED - -class SocketAPM { -public: - SocketAPM(bool _datagram); - SocketAPM(bool _datagram, int _fd); - ~SocketAPM(); - - bool connect(const char *address, uint16_t port); - bool connect_timeout(const char *address, uint16_t port, uint32_t timeout_ms); - bool bind(const char *address, uint16_t port); - bool reuseaddress() const; - bool set_blocking(bool blocking) const; - bool set_cloexec() const; - void set_broadcast(void) const; - - ssize_t send(const void *pkt, size_t size) const; - ssize_t sendto(const void *buf, size_t size, const char *address, uint16_t port); - ssize_t recv(void *pkt, size_t size, uint32_t timeout_ms); - - // return the IP address and port of the last received packet - void last_recv_address(const char *&ip_addr, uint16_t &port) const; - - // return the IP address and port of the last received packet, using caller supplied buffer - const char *last_recv_address(char *ip_addr_buf, uint8_t buflen, uint16_t &port) const; - - // return true if there is pending data for input - bool pollin(uint32_t timeout_ms); - - // return true if there is room for output data - bool pollout(uint32_t timeout_ms); - - // start listening for new tcp connections - bool listen(uint16_t backlog) const; - - // close socket - void close(void); - - // accept a new connection. Only valid for TCP connections after - // listen has been used. A new socket is returned - SocketAPM *accept(uint32_t timeout_ms); - - // get a FD suitable for read selection - int get_read_fd(void) const { - return fd_in != -1? fd_in : fd; - } - - // create a new socket with same fd, but new memory - // the old socket gets fd of -1 - SocketAPM *duplicate(void); - - bool is_connected(void) const { - return connected; - } - - // access to inet_ntop - static const char *inet_addr_to_str(uint32_t addr, char *dst, uint16_t len); - - // access to inet_pton - static uint32_t inet_str_to_addr(const char *ipstr); - -private: - bool datagram; - // we avoid using struct sockaddr_in here to keep support for - // mixing native sockets and lwip sockets in SITL - uint32_t last_in_addr[4]; - bool is_multicast_address(struct sockaddr_in &addr) const; - - int fd = -1; - - // fd_in is used for multicast UDP - int fd_in = -1; - bool connected; +#ifndef SOCKET_CLASS_NAME +#define SOCKET_CLASS_NAME SocketAPM +#endif - void make_sockaddr(const char *address, uint16_t port, struct sockaddr_in &sockaddr); -}; +#include "Socket.hpp" -#endif // AP_NETWORKING_SOCKETS_ENABLED +#undef SOCKET_CLASS_NAME diff --git a/libraries/AP_HAL/utility/Socket.hpp b/libraries/AP_HAL/utility/Socket.hpp new file mode 100644 index 00000000000000..ae4ae6cebe331c --- /dev/null +++ b/libraries/AP_HAL/utility/Socket.hpp @@ -0,0 +1,104 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ +/* + simple socket handling class for systems with BSD socket API + */ + +#include +#include + +#if AP_NETWORKING_SOCKETS_ENABLED || defined(AP_SOCKET_NATIVE_ENABLED) + +#ifndef SOCKET_CLASS_NAME +#error "Don't include Socket.hpp directly" +#endif + +class SOCKET_CLASS_NAME { +public: + SOCKET_CLASS_NAME(bool _datagram); + SOCKET_CLASS_NAME(bool _datagram, int _fd); + ~SOCKET_CLASS_NAME(); + + bool connect(const char *address, uint16_t port); + bool connect_timeout(const char *address, uint16_t port, uint32_t timeout_ms); + bool bind(const char *address, uint16_t port); + bool reuseaddress() const; + bool set_blocking(bool blocking) const; + bool set_cloexec() const; + void set_broadcast(void) const; + + ssize_t send(const void *pkt, size_t size) const; + ssize_t sendto(const void *buf, size_t size, const char *address, uint16_t port); + ssize_t recv(void *pkt, size_t size, uint32_t timeout_ms); + + // return the IP address and port of the last received packet + void last_recv_address(const char *&ip_addr, uint16_t &port) const; + + // return the IP address and port of the last received packet, using caller supplied buffer + const char *last_recv_address(char *ip_addr_buf, uint8_t buflen, uint16_t &port) const; + + // return true if there is pending data for input + bool pollin(uint32_t timeout_ms); + + // return true if there is room for output data + bool pollout(uint32_t timeout_ms); + + // start listening for new tcp connections + bool listen(uint16_t backlog) const; + + // close socket + void close(void); + + // accept a new connection. Only valid for TCP connections after + // listen has been used. A new socket is returned + SOCKET_CLASS_NAME *accept(uint32_t timeout_ms); + + // get a FD suitable for read selection + int get_read_fd(void) const { + return fd_in != -1? fd_in : fd; + } + + // create a new socket with same fd, but new memory + // the old socket gets fd of -1 + SOCKET_CLASS_NAME *duplicate(void); + + bool is_connected(void) const { + return connected; + } + + // access to inet_ntop + static const char *inet_addr_to_str(uint32_t addr, char *dst, uint16_t len); + + // access to inet_pton + static uint32_t inet_str_to_addr(const char *ipstr); + +private: + bool datagram; + // we avoid using struct sockaddr_in here to keep support for + // mixing native sockets and lwip sockets in SITL + uint32_t last_in_addr[4]; + bool is_multicast_address(struct sockaddr_in &addr) const; + + int fd = -1; + + // fd_in is used for multicast UDP + int fd_in = -1; + + bool connected; + + void make_sockaddr(const char *address, uint16_t port, struct sockaddr_in &sockaddr); +}; + +#endif // AP_NETWORKING_SOCKETS_ENABLED diff --git a/libraries/AP_HAL/utility/Socket_native.cpp b/libraries/AP_HAL/utility/Socket_native.cpp new file mode 100644 index 00000000000000..d0d21bb8cd32aa --- /dev/null +++ b/libraries/AP_HAL/utility/Socket_native.cpp @@ -0,0 +1,11 @@ +/* + variant of SocketAPM using native sockets (not via lwip) + */ +#include "Socket_native.h" + +#if AP_SOCKET_NATIVE_ENABLED +#undef AP_NETWORKING_BACKEND_PPP +#define IN_SOCKET_NATIVE_CPP +#define SOCKET_CLASS_NAME SocketAPM_native +#include "Socket.cpp" +#endif diff --git a/libraries/AP_HAL/utility/Socket_native.h b/libraries/AP_HAL/utility/Socket_native.h new file mode 100644 index 00000000000000..e3514ded0c59b7 --- /dev/null +++ b/libraries/AP_HAL/utility/Socket_native.h @@ -0,0 +1,22 @@ +/* + variant of SocketAPM using native sockets (not via lwip) + */ +#pragma once + +#include + +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX +#define AP_SOCKET_NATIVE_ENABLED 1 +#define SOCKET_CLASS_NAME SocketAPM_native +#ifndef AP_NETWORKING_SOCKETS_ENABLED +#define AP_NETWORKING_SOCKETS_ENABLED 1 +#endif +#include "Socket.hpp" +#else +#error "attempt to use Socket_native.h without native sockets" +#endif + +#undef SOCKET_CLASS_NAME + + + From ef67fa4293eef59796b67aa090910a27575557ef Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 13:20:40 +1100 Subject: [PATCH 0335/1335] AP_HAL: use SocketAPM_native --- libraries/AP_HAL/SIMState.h | 6 +++--- libraries/AP_HAL/utility/Socket.cpp | 1 + 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL/SIMState.h b/libraries/AP_HAL/SIMState.h index 4c8350371a70b0..50589eb85aab24 100644 --- a/libraries/AP_HAL/SIMState.h +++ b/libraries/AP_HAL/SIMState.h @@ -44,7 +44,7 @@ #include #include -#include +#include #include @@ -93,7 +93,7 @@ class AP_HAL::SIMState { uint32_t _update_count; #if CONFIG_HAL_BOARD == HAL_BOARD_SITL - SocketAPM _sitl_rc_in{true}; + SocketAPM_native _sitl_rc_in{true}; #endif SITL::SIM *_sitl; uint16_t _rcin_port; @@ -220,7 +220,7 @@ class AP_HAL::SIMState { #if CONFIG_HAL_BOARD == HAL_BOARD_SITL // output socket for flightgear viewing - SocketAPM fg_socket{true}; + SocketAPM_native fg_socket{true}; #endif const char *defaults_path = HAL_PARAM_DEFAULTS_PATH; diff --git a/libraries/AP_HAL/utility/Socket.cpp b/libraries/AP_HAL/utility/Socket.cpp index 2c33462b55124d..ccb8cb3f394d57 100644 --- a/libraries/AP_HAL/utility/Socket.cpp +++ b/libraries/AP_HAL/utility/Socket.cpp @@ -358,6 +358,7 @@ ssize_t SOCKET_CLASS_NAME::recv(void *buf, size_t size, uint32_t timeout_ms) */ void SOCKET_CLASS_NAME::last_recv_address(const char *&ip_addr, uint16_t &port) const { + // 16 bytes for aaa.bbb.ccc.ddd with null term static char buf[16]; auto *str = last_recv_address(buf, sizeof(buf), port); ip_addr = str; From 931bae5b88e42b8a46481f6a3d42284cad8e946a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 13:21:11 +1100 Subject: [PATCH 0336/1335] AP_HAL_Linux: use SocketAPM_native --- libraries/AP_HAL_Linux/ConsoleDevice.h | 2 +- libraries/AP_HAL_Linux/RCInput_SoloLink.h | 6 +++++- libraries/AP_HAL_Linux/RCInput_UDP.h | 2 +- libraries/AP_HAL_Linux/TCPServerDevice.h | 6 +++++- libraries/AP_HAL_Linux/UARTDevice.h | 2 +- libraries/AP_HAL_Linux/UDPDevice.h | 2 +- 6 files changed, 14 insertions(+), 6 deletions(-) diff --git a/libraries/AP_HAL_Linux/ConsoleDevice.h b/libraries/AP_HAL_Linux/ConsoleDevice.h index 7782434a3c37b3..940c6fc2740785 100644 --- a/libraries/AP_HAL_Linux/ConsoleDevice.h +++ b/libraries/AP_HAL_Linux/ConsoleDevice.h @@ -1,7 +1,7 @@ #pragma once #include "SerialDevice.h" -#include +#include class ConsoleDevice: public SerialDevice { public: diff --git a/libraries/AP_HAL_Linux/RCInput_SoloLink.h b/libraries/AP_HAL_Linux/RCInput_SoloLink.h index 29538a30abc603..d56ae8f277dfae 100644 --- a/libraries/AP_HAL_Linux/RCInput_SoloLink.h +++ b/libraries/AP_HAL_Linux/RCInput_SoloLink.h @@ -18,11 +18,15 @@ #include -#include +#include #include #include "RCInput.h" +#ifndef AP_SOCKET_NATIVE_ENABLED +#error "need native" +#endif + namespace Linux { class RCInput_SoloLink : public RCInput diff --git a/libraries/AP_HAL_Linux/RCInput_UDP.h b/libraries/AP_HAL_Linux/RCInput_UDP.h index 2154a26a65af92..0431a2be7f1fde 100644 --- a/libraries/AP_HAL_Linux/RCInput_UDP.h +++ b/libraries/AP_HAL_Linux/RCInput_UDP.h @@ -1,7 +1,7 @@ #pragma once #include "RCInput.h" -#include +#include #include "RCInput_UDP_Protocol.h" #define RCINPUT_UDP_DEF_PORT 777 diff --git a/libraries/AP_HAL_Linux/TCPServerDevice.h b/libraries/AP_HAL_Linux/TCPServerDevice.h index 757e336df2e4a3..0a268145a8acf5 100644 --- a/libraries/AP_HAL_Linux/TCPServerDevice.h +++ b/libraries/AP_HAL_Linux/TCPServerDevice.h @@ -1,7 +1,11 @@ #pragma once +#include #include "SerialDevice.h" -#include + +#ifndef AP_SOCKET_NATIVE_ENABLED +#error "need native" +#endif class TCPServerDevice: public SerialDevice { public: diff --git a/libraries/AP_HAL_Linux/UARTDevice.h b/libraries/AP_HAL_Linux/UARTDevice.h index b6dcae6ed6cd39..582089d47028cc 100644 --- a/libraries/AP_HAL_Linux/UARTDevice.h +++ b/libraries/AP_HAL_Linux/UARTDevice.h @@ -1,7 +1,7 @@ #pragma once #include "SerialDevice.h" -#include +#include class UARTDevice: public SerialDevice { public: diff --git a/libraries/AP_HAL_Linux/UDPDevice.h b/libraries/AP_HAL_Linux/UDPDevice.h index a51e2ddc5b5b1b..4d3ad4d6f753d4 100644 --- a/libraries/AP_HAL_Linux/UDPDevice.h +++ b/libraries/AP_HAL_Linux/UDPDevice.h @@ -1,7 +1,7 @@ #pragma once +#include #include "SerialDevice.h" -#include class UDPDevice: public SerialDevice { public: From 69df468b88a465aaf0e29868927fa4f04b2f8b16 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 13:21:11 +1100 Subject: [PATCH 0337/1335] AP_HAL_SITL: use SocketAPM_native --- libraries/AP_HAL_SITL/CAN_Multicast.h | 2 +- libraries/AP_HAL_SITL/SITL_Periph_State.cpp | 2 +- libraries/AP_HAL_SITL/SITL_Periph_State.h | 6 +++--- libraries/AP_HAL_SITL/SITL_State.cpp | 2 +- libraries/AP_HAL_SITL/SITL_State.h | 2 +- libraries/AP_HAL_SITL/SITL_State_common.cpp | 2 +- libraries/AP_HAL_SITL/SITL_State_common.h | 4 ++-- libraries/AP_HAL_SITL/UARTDriver.h | 2 +- 8 files changed, 11 insertions(+), 11 deletions(-) diff --git a/libraries/AP_HAL_SITL/CAN_Multicast.h b/libraries/AP_HAL_SITL/CAN_Multicast.h index 07b39982a7640c..4bff83d4c7a765 100644 --- a/libraries/AP_HAL_SITL/CAN_Multicast.h +++ b/libraries/AP_HAL_SITL/CAN_Multicast.h @@ -18,7 +18,7 @@ class CAN_Multicast : public CAN_Transport { } private: - SocketAPM sock{true}; + SocketAPM_native sock{true}; }; #endif // HAL_NUM_CAN_IFACES diff --git a/libraries/AP_HAL_SITL/SITL_Periph_State.cpp b/libraries/AP_HAL_SITL/SITL_Periph_State.cpp index 618f26a1aeabd7..a65e56310e5b8e 100644 --- a/libraries/AP_HAL_SITL/SITL_Periph_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_Periph_State.cpp @@ -17,7 +17,7 @@ #include #include -#include +#include #include #include diff --git a/libraries/AP_HAL_SITL/SITL_Periph_State.h b/libraries/AP_HAL_SITL/SITL_Periph_State.h index 47bb61ee79639f..61453d4a0fae54 100644 --- a/libraries/AP_HAL_SITL/SITL_Periph_State.h +++ b/libraries/AP_HAL_SITL/SITL_Periph_State.h @@ -22,7 +22,7 @@ #include #include #include -#include +#include class SimMCast : public SITL::Aircraft { public: @@ -30,8 +30,8 @@ class SimMCast : public SITL::Aircraft { void update(const struct sitl_input &input) override; private: - SocketAPM sock{true}; - SocketAPM servo_sock{true}; + SocketAPM_native sock{true}; + SocketAPM_native servo_sock{true}; // offset between multicast timestamp and local timestamp uint64_t base_time_us; diff --git a/libraries/AP_HAL_SITL/SITL_State.cpp b/libraries/AP_HAL_SITL/SITL_State.cpp index 4b08727d8ec1f0..e2e27e1fa0df2b 100644 --- a/libraries/AP_HAL_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_State.cpp @@ -23,7 +23,7 @@ #include #include -#include +#include extern const AP_HAL::HAL& hal; diff --git a/libraries/AP_HAL_SITL/SITL_State.h b/libraries/AP_HAL_SITL/SITL_State.h index 5e5ce885b1f11b..4aa73d4a11fd6e 100644 --- a/libraries/AP_HAL_SITL/SITL_State.h +++ b/libraries/AP_HAL_SITL/SITL_State.h @@ -85,7 +85,7 @@ class HALSITL::SITL_State : public SITL_State_Common { Scheduler *_scheduler; - SocketAPM _sitl_rc_in{true}; + SocketAPM_native _sitl_rc_in{true}; bool _rc_in_started; uint16_t _rcin_port; uint16_t _fg_view_port; diff --git a/libraries/AP_HAL_SITL/SITL_State_common.cpp b/libraries/AP_HAL_SITL/SITL_State_common.cpp index f05bbf20b1fc79..ae2603e6dd38ea 100644 --- a/libraries/AP_HAL_SITL/SITL_State_common.cpp +++ b/libraries/AP_HAL_SITL/SITL_State_common.cpp @@ -18,7 +18,7 @@ #include #include -#include +#include extern const AP_HAL::HAL& hal; diff --git a/libraries/AP_HAL_SITL/SITL_State_common.h b/libraries/AP_HAL_SITL/SITL_State_common.h index 509391760cd312..4b59268ef8922b 100644 --- a/libraries/AP_HAL_SITL/SITL_State_common.h +++ b/libraries/AP_HAL_SITL/SITL_State_common.h @@ -8,6 +8,7 @@ #define SITL_MCAST_PORT 20721 #define SITL_SERVO_PORT 20722 +#include #include #include #include @@ -64,7 +65,6 @@ #include #include #include -#include class HAL_SITL; @@ -220,7 +220,7 @@ class HALSITL::SITL_State_Common { SITL::EFI_Hirth *efi_hirth; // output socket for flightgear viewing - SocketAPM fg_socket{true}; + SocketAPM_native fg_socket{true}; const char *defaults_path = HAL_PARAM_DEFAULTS_PATH; diff --git a/libraries/AP_HAL_SITL/UARTDriver.h b/libraries/AP_HAL_SITL/UARTDriver.h index bf875b7abf3bcd..70d1fa332f4b27 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.h +++ b/libraries/AP_HAL_SITL/UARTDriver.h @@ -6,7 +6,7 @@ #include #include #include "AP_HAL_SITL_Namespace.h" -#include +#include #include #include From f8d64afc6992aa8f2e7f3f8c4841532566844903 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 13:21:11 +1100 Subject: [PATCH 0338/1335] AP_IRLock: use SocketAPM_native --- libraries/AP_IRLock/AP_IRLock_SITL_Gazebo.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_IRLock/AP_IRLock_SITL_Gazebo.h b/libraries/AP_IRLock/AP_IRLock_SITL_Gazebo.h index b20e9f62418495..21ee5ff5653326 100644 --- a/libraries/AP_IRLock/AP_IRLock_SITL_Gazebo.h +++ b/libraries/AP_IRLock/AP_IRLock_SITL_Gazebo.h @@ -6,7 +6,7 @@ */ #pragma once -#include +#include #if CONFIG_HAL_BOARD == HAL_BOARD_SITL #include "IRLock.h" @@ -24,6 +24,6 @@ class AP_IRLock_SITL_Gazebo : public IRLock private: uint32_t _last_timestamp; - SocketAPM sock; + SocketAPM_native sock; }; #endif // CONFIG_HAL_BOARD From b3fbc7edb075d4497d3b2caa86858a3d99b6f76a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 13:21:11 +1100 Subject: [PATCH 0339/1335] AP_RCProtocol: use SocketAPM_native --- .../examples/RCProtocolDecoder/RCProtocolDecoder.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_RCProtocol/examples/RCProtocolDecoder/RCProtocolDecoder.cpp b/libraries/AP_RCProtocol/examples/RCProtocolDecoder/RCProtocolDecoder.cpp index 04836e01d8ef74..2a394a10f559f1 100644 --- a/libraries/AP_RCProtocol/examples/RCProtocolDecoder/RCProtocolDecoder.cpp +++ b/libraries/AP_RCProtocol/examples/RCProtocolDecoder/RCProtocolDecoder.cpp @@ -34,7 +34,7 @@ void loop(); #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_SITL -#include +#include #include #include #include From 213cdcef4b12d1cbab96566bab83357707ef3c28 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 13:21:11 +1100 Subject: [PATCH 0340/1335] AP_Scripting: use SocketAPM_native --- libraries/AP_Scripting/lua_bindings.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Scripting/lua_bindings.cpp b/libraries/AP_Scripting/lua_bindings.cpp index eb884eb275cd87..e84a68786c8a04 100644 --- a/libraries/AP_Scripting/lua_bindings.cpp +++ b/libraries/AP_Scripting/lua_bindings.cpp @@ -4,6 +4,10 @@ #include #include +#include +#if AP_NETWORKING_ENABLED +#include +#endif #include #include @@ -15,10 +19,6 @@ #include #include -#include -#if AP_NETWORKING_ENABLED -#include -#endif #include "lua/src/lauxlib.h" extern const AP_HAL::HAL& hal; From adffd938946db734ed260a9b1f726712de769e0e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 13:21:11 +1100 Subject: [PATCH 0341/1335] SITL: use SocketAPM_native --- libraries/SITL/SIM_ADSB.h | 2 +- libraries/SITL/SIM_AirSim.h | 4 ++-- libraries/SITL/SIM_CRRCSim.h | 4 ++-- libraries/SITL/SIM_EFI_Hirth.h | 2 +- libraries/SITL/SIM_EFI_MegaSquirt.h | 2 +- libraries/SITL/SIM_FlightAxis.cpp | 2 +- libraries/SITL/SIM_FlightAxis.h | 6 +++--- libraries/SITL/SIM_Gazebo.h | 4 ++-- libraries/SITL/SIM_Gimbal.h | 4 ++-- libraries/SITL/SIM_JSBSim.h | 6 +++--- libraries/SITL/SIM_JSON.h | 4 ++-- libraries/SITL/SIM_JSON_Master.h | 6 +++--- libraries/SITL/SIM_Morse.cpp | 4 ++-- libraries/SITL/SIM_Morse.h | 8 ++++---- libraries/SITL/SIM_Scrimmage.h | 6 +++--- libraries/SITL/SIM_Ship.h | 4 ++-- libraries/SITL/SIM_SilentWings.h | 4 ++-- libraries/SITL/SIM_Webots.cpp | 2 +- libraries/SITL/SIM_Webots.h | 4 ++-- libraries/SITL/SIM_Webots_Python.h | 4 ++-- libraries/SITL/SIM_XPlane.h | 6 +++--- libraries/SITL/SIM_last_letter.h | 4 ++-- 22 files changed, 46 insertions(+), 46 deletions(-) diff --git a/libraries/SITL/SIM_ADSB.h b/libraries/SITL/SIM_ADSB.h index 9b9682c15b515a..c80cf2668e0dbd 100644 --- a/libraries/SITL/SIM_ADSB.h +++ b/libraries/SITL/SIM_ADSB.h @@ -22,7 +22,7 @@ #if HAL_SIM_ADSB_ENABLED -#include +#include #include "SIM_Aircraft.h" diff --git a/libraries/SITL/SIM_AirSim.h b/libraries/SITL/SIM_AirSim.h index 7e3b447817dee1..1e9b75c0e648ae 100644 --- a/libraries/SITL/SIM_AirSim.h +++ b/libraries/SITL/SIM_AirSim.h @@ -26,7 +26,7 @@ #if HAL_SIM_AIRSIM_ENABLED -#include +#include #include "SIM_Aircraft.h" namespace SITL { @@ -78,7 +78,7 @@ class AirSim : public Aircraft { // connection_info_.sitl_ip_port uint16_t airsim_control_port = 9002; - SocketAPM sock; + SocketAPM_native sock; double average_frame_time; uint64_t frame_counter; diff --git a/libraries/SITL/SIM_CRRCSim.h b/libraries/SITL/SIM_CRRCSim.h index eb6d01c3b4a98a..b3a5699f99156e 100644 --- a/libraries/SITL/SIM_CRRCSim.h +++ b/libraries/SITL/SIM_CRRCSim.h @@ -26,7 +26,7 @@ #if HAL_SIM_CRRCSIM_ENABLED -#include +#include #include "SIM_Aircraft.h" @@ -81,7 +81,7 @@ class CRRCSim : public Aircraft { bool heli_servos; double last_timestamp; - SocketAPM sock; + SocketAPM_native sock; }; } // namespace SITL diff --git a/libraries/SITL/SIM_EFI_Hirth.h b/libraries/SITL/SIM_EFI_Hirth.h index 8ccbb8286a8ad2..0aec264f765a9c 100644 --- a/libraries/SITL/SIM_EFI_Hirth.h +++ b/libraries/SITL/SIM_EFI_Hirth.h @@ -29,7 +29,7 @@ status EFI_STATUS #pragma once #include -#include +#include #include "SIM_SerialDevice.h" namespace SITL { diff --git a/libraries/SITL/SIM_EFI_MegaSquirt.h b/libraries/SITL/SIM_EFI_MegaSquirt.h index 352fbd44589eb3..7c0151a1657198 100644 --- a/libraries/SITL/SIM_EFI_MegaSquirt.h +++ b/libraries/SITL/SIM_EFI_MegaSquirt.h @@ -28,8 +28,8 @@ status EFI_STATUS #pragma once +#include #include -#include #include "SIM_SerialDevice.h" namespace SITL { diff --git a/libraries/SITL/SIM_FlightAxis.cpp b/libraries/SITL/SIM_FlightAxis.cpp index afd89d2be125e2..36d63e0d67cdc3 100644 --- a/libraries/SITL/SIM_FlightAxis.cpp +++ b/libraries/SITL/SIM_FlightAxis.cpp @@ -590,7 +590,7 @@ void FlightAxis::socket_creator(void) pthread_cond_wait(&sockcond2, &sockmtx); } pthread_mutex_unlock(&sockmtx); - auto *sck = new SocketAPM(false); + auto *sck = new SocketAPM_native(false); if (sck == nullptr) { usleep(500); continue; diff --git a/libraries/SITL/SIM_FlightAxis.h b/libraries/SITL/SIM_FlightAxis.h index 592cc741a52848..0567997e1fee5f 100644 --- a/libraries/SITL/SIM_FlightAxis.h +++ b/libraries/SITL/SIM_FlightAxis.h @@ -26,7 +26,7 @@ #if HAL_SIM_FLIGHTAXIS_ENABLED -#include +#include #include "SIM_Aircraft.h" @@ -193,8 +193,8 @@ class FlightAxis : public Aircraft { const char *controller_ip = "127.0.0.1"; uint16_t controller_port = 18083; - SocketAPM *socknext; - SocketAPM *sock; + SocketAPM_native *socknext; + SocketAPM_native *sock; char replybuf[10000]; pid_t socket_pid; uint32_t sock_error_count; diff --git a/libraries/SITL/SIM_Gazebo.h b/libraries/SITL/SIM_Gazebo.h index 4da05353bae182..6a13d8b8e51441 100644 --- a/libraries/SITL/SIM_Gazebo.h +++ b/libraries/SITL/SIM_Gazebo.h @@ -27,7 +27,7 @@ #if HAL_SIM_GAZEBO_ENABLED #include "SIM_Aircraft.h" -#include +#include namespace SITL { @@ -76,7 +76,7 @@ class Gazebo : public Aircraft { double last_timestamp; - SocketAPM socket_sitl; + SocketAPM_native socket_sitl; const char *_gazebo_address = "127.0.0.1"; int _gazebo_port = 9002; static const uint64_t GAZEBO_TIMEOUT_US = 5000000; diff --git a/libraries/SITL/SIM_Gimbal.h b/libraries/SITL/SIM_Gimbal.h index 53a2212a29f028..2cedd3a1cf9c3f 100644 --- a/libraries/SITL/SIM_Gimbal.h +++ b/libraries/SITL/SIM_Gimbal.h @@ -26,7 +26,7 @@ #if HAL_SIM_GIMBAL_ENABLED -#include +#include #include "SIM_Aircraft.h" @@ -101,7 +101,7 @@ class Gimbal { uint8_t vehicle_system_id; uint8_t vehicle_component_id; - SocketAPM mav_socket; + SocketAPM_native mav_socket; struct { // socket to telem2 on aircraft bool connected; diff --git a/libraries/SITL/SIM_JSBSim.h b/libraries/SITL/SIM_JSBSim.h index fda323e943f294..bbb2c1a46a0f4b 100644 --- a/libraries/SITL/SIM_JSBSim.h +++ b/libraries/SITL/SIM_JSBSim.h @@ -26,7 +26,7 @@ #if HAL_SIM_JSBSIM_ENABLED -#include +#include #include "SIM_Aircraft.h" @@ -49,10 +49,10 @@ class JSBSim : public Aircraft { private: // tcp input control socket to JSBSIm - SocketAPM sock_control; + SocketAPM_native sock_control; // UDP packets from JSBSim in fgFDM format - SocketAPM sock_fgfdm; + SocketAPM_native sock_fgfdm; bool initialised; diff --git a/libraries/SITL/SIM_JSON.h b/libraries/SITL/SIM_JSON.h index 22582f0ae48083..b168219d9d351f 100644 --- a/libraries/SITL/SIM_JSON.h +++ b/libraries/SITL/SIM_JSON.h @@ -22,7 +22,7 @@ #if HAL_SIM_JSON_ENABLED -#include +#include #include "SIM_Aircraft.h" namespace SITL { @@ -64,7 +64,7 @@ class JSON : public Aircraft { // default connection_info_.sitl_ip_port uint16_t control_port = 9002; - SocketAPM sock; + SocketAPM_native sock; uint32_t frame_counter; double last_timestamp_s; diff --git a/libraries/SITL/SIM_JSON_Master.h b/libraries/SITL/SIM_JSON_Master.h index 9a568f6ed14466..f4bcc1399417c4 100644 --- a/libraries/SITL/SIM_JSON_Master.h +++ b/libraries/SITL/SIM_JSON_Master.h @@ -27,7 +27,7 @@ #if HAL_SIM_JSON_MASTER_ENABLED #include "SITL_Input.h" -#include +#include #include namespace SITL { @@ -48,8 +48,8 @@ class JSON_Master { private: struct socket_list { - SocketAPM sock_in{true}; - SocketAPM sock_out{true}; + SocketAPM_native sock_in{true}; + SocketAPM_native sock_out{true}; uint8_t instance; bool connected; socket_list *next; diff --git a/libraries/SITL/SIM_Morse.cpp b/libraries/SITL/SIM_Morse.cpp index 221c6c1abe011c..c4c62498697301 100644 --- a/libraries/SITL/SIM_Morse.cpp +++ b/libraries/SITL/SIM_Morse.cpp @@ -261,7 +261,7 @@ bool Morse::parse_sensors(const char *json) bool Morse::connect_sockets(void) { if (!sensors_sock) { - sensors_sock = new SocketAPM(false); + sensors_sock = new SocketAPM_native(false); if (!sensors_sock) { AP_HAL::panic("Out of memory for sensors socket"); } @@ -280,7 +280,7 @@ bool Morse::connect_sockets(void) printf("Sensors connected\n"); } if (!control_sock) { - control_sock = new SocketAPM(false); + control_sock = new SocketAPM_native(false); if (!control_sock) { AP_HAL::panic("Out of memory for control socket"); } diff --git a/libraries/SITL/SIM_Morse.h b/libraries/SITL/SIM_Morse.h index 5e45ab9f93095a..9445c26d5817a3 100644 --- a/libraries/SITL/SIM_Morse.h +++ b/libraries/SITL/SIM_Morse.h @@ -26,7 +26,7 @@ #if HAL_SIM_MORSE_ENABLED -#include +#include #include "SIM_Aircraft.h" namespace SITL { @@ -51,7 +51,7 @@ class Morse : public Aircraft { // loopback to convert inbound Morse lidar data into inbound mavlink msgs const char *mavlink_loopback_address = "127.0.0.1"; const uint16_t mavlink_loopback_port = 5762; - SocketAPM mav_socket { false }; + SocketAPM_native mav_socket { false }; struct { // socket to telem2 on aircraft bool connected; @@ -91,8 +91,8 @@ class Morse : public Aircraft { uint8_t sensor_buffer[50000]; uint32_t sensor_buffer_len; - SocketAPM *sensors_sock; - SocketAPM *control_sock; + SocketAPM_native *sensors_sock; + SocketAPM_native *control_sock; uint32_t no_data_counter; uint32_t connect_counter; diff --git a/libraries/SITL/SIM_Scrimmage.h b/libraries/SITL/SIM_Scrimmage.h index e6228cb281a79d..2fa8dfcbaf3ddd 100644 --- a/libraries/SITL/SIM_Scrimmage.h +++ b/libraries/SITL/SIM_Scrimmage.h @@ -28,7 +28,7 @@ #include -#include +#include #include "SIM_Aircraft.h" @@ -84,8 +84,8 @@ class Scrimmage : public Aircraft { void send_servos(const struct sitl_input &input); uint64_t prev_timestamp_us; - SocketAPM recv_sock; - SocketAPM send_sock; + SocketAPM_native recv_sock; + SocketAPM_native send_sock; }; } // namespace SITL diff --git a/libraries/SITL/SIM_Ship.h b/libraries/SITL/SIM_Ship.h index cbb91ccba40554..afdff43b37c877 100644 --- a/libraries/SITL/SIM_Ship.h +++ b/libraries/SITL/SIM_Ship.h @@ -22,7 +22,7 @@ #if AP_SIM_SHIP_ENABLED -#include +#include #include #include #include @@ -83,7 +83,7 @@ class ShipSim { uint32_t last_report_ms; uint32_t last_heartbeat_ms; - SocketAPM mav_socket { false }; + SocketAPM_native mav_socket { false }; bool mavlink_connected; mavlink_status_t mav_status; diff --git a/libraries/SITL/SIM_SilentWings.h b/libraries/SITL/SIM_SilentWings.h index 50739387a36952..75fdd3984fff32 100644 --- a/libraries/SITL/SIM_SilentWings.h +++ b/libraries/SITL/SIM_SilentWings.h @@ -23,7 +23,7 @@ #if HAL_SIM_SILENTWINGS_ENABLED -#include +#include #include "SIM_Aircraft.h" @@ -109,7 +109,7 @@ class SilentWings : public Aircraft { /* ArduPlane's internal time when the first packet from Silent Wings is received. */ uint64_t time_base_us; - SocketAPM sock; + SocketAPM_native sock; const char *_sw_address = "127.0.0.1"; int _port_in = 6060; int _sw_port = 6070; diff --git a/libraries/SITL/SIM_Webots.cpp b/libraries/SITL/SIM_Webots.cpp index ac6c4655e9b81b..134fdc62369791 100644 --- a/libraries/SITL/SIM_Webots.cpp +++ b/libraries/SITL/SIM_Webots.cpp @@ -291,7 +291,7 @@ bool Webots::parse_sensors(const char *json) bool Webots::connect_sockets(void) { if (!sim_sock) { - sim_sock = new SocketAPM(false); + sim_sock = new SocketAPM_native(false); if (!sim_sock) { AP_HAL::panic("Out of memory for sensors socket"); } diff --git a/libraries/SITL/SIM_Webots.h b/libraries/SITL/SIM_Webots.h index ef6ea1454ab7f3..5457d6cd962a66 100644 --- a/libraries/SITL/SIM_Webots.h +++ b/libraries/SITL/SIM_Webots.h @@ -27,7 +27,7 @@ #if HAL_SIM_WEBOTS_ENABLED #include -#include +#include #include "SIM_Aircraft.h" namespace SITL { @@ -79,7 +79,7 @@ class Webots : public Aircraft { uint8_t sensor_buffer[50000]; uint32_t sensor_buffer_len; - SocketAPM *sim_sock; + SocketAPM_native *sim_sock; uint32_t connect_counter; diff --git a/libraries/SITL/SIM_Webots_Python.h b/libraries/SITL/SIM_Webots_Python.h index 194d8cd648884f..ec3e8ba4b56274 100644 --- a/libraries/SITL/SIM_Webots_Python.h +++ b/libraries/SITL/SIM_Webots_Python.h @@ -27,7 +27,7 @@ #if HAL_SIM_WEBOTSPYTHON_ENABLED #include "SIM_Aircraft.h" -#include +#include namespace SITL { @@ -78,7 +78,7 @@ class WebotsPython : public Aircraft { double last_timestamp; - SocketAPM socket_sitl; + SocketAPM_native socket_sitl; const char* _webots_address = "127.0.0.1"; int _webots_port = 9002; static const uint64_t WEBOTS_TIMEOUT_US = 5000000; diff --git a/libraries/SITL/SIM_XPlane.h b/libraries/SITL/SIM_XPlane.h index 84051439328d47..8c90ea6c2172e3 100644 --- a/libraries/SITL/SIM_XPlane.h +++ b/libraries/SITL/SIM_XPlane.h @@ -26,7 +26,7 @@ #if HAL_SIM_XPLANE_ENABLED -#include +#include #include #include "SIM_Aircraft.h" @@ -70,8 +70,8 @@ class XPlane : public Aircraft { uint16_t xplane_port = 49000; uint16_t bind_port = 49001; // udp socket, input and output - SocketAPM socket_in{true}; - SocketAPM socket_out{true}; + SocketAPM_native socket_in{true}; + SocketAPM_native socket_out{true}; uint64_t time_base_us; uint32_t last_data_time_ms; diff --git a/libraries/SITL/SIM_last_letter.h b/libraries/SITL/SIM_last_letter.h index ae7cae5ecf8c22..d8afa83ba0c694 100644 --- a/libraries/SITL/SIM_last_letter.h +++ b/libraries/SITL/SIM_last_letter.h @@ -26,7 +26,7 @@ #if HAL_SIM_LAST_LETTER_ENABLED -#include +#include #include "SIM_Aircraft.h" @@ -77,7 +77,7 @@ class last_letter : public Aircraft { void start_last_letter(void); uint64_t last_timestamp_us; - SocketAPM sock; + SocketAPM_native sock; }; } // namespace SITL From 60bfcf3cdcb890c88e3836ea74ccf6446c4177b9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 13:21:43 +1100 Subject: [PATCH 0342/1335] autotest: added a web server test both native sockets and PPP --- Tools/autotest/pysim/util.py | 14 +++++ Tools/autotest/rover.py | 102 ++++++++++++++++++++++++++++++++++ Tools/autotest/sim_vehicle.py | 2 +- 3 files changed, 117 insertions(+), 1 deletion(-) diff --git a/Tools/autotest/pysim/util.py b/Tools/autotest/pysim/util.py index fca158dc844fcc..6a0f6c9dff7ebd 100644 --- a/Tools/autotest/pysim/util.py +++ b/Tools/autotest/pysim/util.py @@ -675,6 +675,20 @@ def start_MAVProxy_SITL(atype, return ret +def start_PPP_daemon(ips, sockaddr): + """Start pppd for networking""" + + global close_list + cmd = "sudo pppd socket %s debug noauth nodetach %s" % (sockaddr, ips) + cmd = cmd.split() + print("Running: %s" % cmd_as_shell(cmd)) + + ret = pexpect.spawn(cmd[0], cmd[1:], logfile=sys.stdout, encoding=ENCODING, timeout=30) + ret.delaybeforesend = 0 + pexpect_autoclose(ret) + return ret + + def expect_setup_callback(e, callback): """Setup a callback that is called once a second while waiting for patterns.""" diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index 8df67796676461..eb398452bf0fc9 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -6625,6 +6625,106 @@ def MAV_CMD_BATTERY_RESET(self): "poll": True, }) + def TestWebServer(self, url): + '''test active web server''' + self.progress("Accessing webserver main page") + import urllib.request + + main_page = urllib.request.urlopen(url).read().decode('utf-8') + if main_page.find('ArduPilot Web Server') == -1: + raise NotAchievedException("Expected banner on main page") + + board_status = urllib.request.urlopen(url + '/@DYNAMIC/board_status.shtml').read().decode('utf-8') + if board_status.find('0 hours') == -1: + raise NotAchievedException("Expected uptime in board status") + if board_status.find('40.713') == -1: + raise NotAchievedException("Expected lattitude in board status") + + self.progress("WebServer tests OK") + + def NetworkingWebServer(self): + '''web server''' + applet_script = "net_webserver.lua" + + self.install_applet_script(applet_script) + + self.set_parameters({ + "SCR_ENABLE": 1, + "SCR_VM_I_COUNT": 1000000, + "SIM_SPEEDUP": 20, + "NET_ENABLED": 1, + }) + + self.reboot_sitl() + + self.context_push() + self.context_collect('STATUSTEXT') + + self.set_parameters({ + "WEB_BIND_PORT": 8081, + }) + + self.scripting_restart() + self.wait_text("WebServer: starting on port 8081", check_context=True) + + self.wait_ready_to_arm() + + self.TestWebServer("http://127.0.0.1:8081") + + self.context_pop() + self.remove_installed_script(applet_script) + self.reboot_sitl() + + def NetworkingWebServerPPP(self): + '''web server over PPP''' + applet_script = "net_webserver.lua" + + self.install_applet_script(applet_script) + + self.set_parameters({ + "SCR_ENABLE": 1, + "SCR_VM_I_COUNT": 1000000, + "SIM_SPEEDUP": 20, + "NET_ENABLED": 1, + "SERIAL5_PROTOCOL": 48, + }) + + self.progress('rebuilding rover with ppp enabled') + import shutil + shutil.copy('build/sitl/bin/ardurover', 'build/sitl/bin/ardurover.noppp') + util.build_SITL('bin/ardurover', clean=False, configure=True, extra_configure_args=['--enable-ppp', '--debug']) + + self.reboot_sitl() + + self.progress("Starting PPP daemon") + pppd = util.start_PPP_daemon("192.168.14.15:192.168.14.13", '127.0.0.1:5765') + + self.context_push() + self.context_collect('STATUSTEXT') + + pppd.expect("remote IP address 192.168.14.13") + + self.progress("PPP daemon started") + + self.set_parameters({ + "WEB_BIND_PORT": 8081, + }) + + self.scripting_restart() + self.wait_text("WebServer: starting on port 8081", check_context=True) + + self.wait_ready_to_arm() + + self.TestWebServer("http://192.168.14.13:8081") + + self.context_pop() + self.remove_installed_script(applet_script) + + # restore rover without ppp enabled for next test + os.unlink('build/sitl/bin/ardurover') + shutil.copy('build/sitl/bin/ardurover.noppp', 'build/sitl/bin/ardurover') + self.reboot_sitl() + def tests(self): '''return list of all tests''' ret = super(AutoTestRover, self).tests() @@ -6709,6 +6809,8 @@ def tests(self): self.MAV_CMD_GET_HOME_POSITION, self.MAV_CMD_DO_FENCE_ENABLE, self.MAV_CMD_BATTERY_RESET, + self.NetworkingWebServer, + self.NetworkingWebServerPPP, ]) return ret diff --git a/Tools/autotest/sim_vehicle.py b/Tools/autotest/sim_vehicle.py index 0d623e8c8f3e9d..1b46b85a87e31d 100755 --- a/Tools/autotest/sim_vehicle.py +++ b/Tools/autotest/sim_vehicle.py @@ -416,7 +416,7 @@ def do_build(opts, frame_options): if opts.enable_ppp: cmd_configure.append("--enable-ppp") - + if opts.enable_networking_tests: cmd_configure.append("--enable-networking-tests") From 39f029d60bf288f92ac996a04044d005424a1fc2 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 13:23:45 +1100 Subject: [PATCH 0343/1335] CI: install ppp for rover test --- .github/workflows/test_sitl_rover.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/test_sitl_rover.yml b/.github/workflows/test_sitl_rover.yml index d17c0d154e16e2..74c6c0f93d733d 100644 --- a/.github/workflows/test_sitl_rover.yml +++ b/.github/workflows/test_sitl_rover.yml @@ -192,6 +192,7 @@ jobs: - name: build rover ${{ matrix.toolchain }} shell: bash run: | + sudo apt-get -y install ppp git config --global --add safe.directory ${GITHUB_WORKSPACE} if [[ ${{ matrix.toolchain }} == "clang" ]]; then export CC=clang From 8aaedccacc1dbbb21be880bdf19bc053f0acad7d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 13:24:53 +1100 Subject: [PATCH 0344/1335] Tools: install ppp in ubuntu --- Tools/environment_install/install-prereqs-ubuntu.sh | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Tools/environment_install/install-prereqs-ubuntu.sh b/Tools/environment_install/install-prereqs-ubuntu.sh index 9a865a52c13f9d..594aa33708e456 100755 --- a/Tools/environment_install/install-prereqs-ubuntu.sh +++ b/Tools/environment_install/install-prereqs-ubuntu.sh @@ -323,6 +323,8 @@ if [ -n "$LBTBIN" ]; then SITL_PKGS+=" libtool-bin" fi +SITL_PKGS+=" ppp" + # Install all packages $APT_GET install $BASE_PKGS $SITL_PKGS $PX4_PKGS $ARM_LINUX_PKGS $COVERAGE_PKGS From 34c737de36491d54e2244b16ab864de0e55a625f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 13:41:12 +1100 Subject: [PATCH 0345/1335] HAL_Linux: use SocketAPM_native --- libraries/AP_HAL_Linux/RCInput_SoloLink.h | 2 +- libraries/AP_HAL_Linux/RCInput_UDP.h | 2 +- libraries/AP_HAL_Linux/TCPServerDevice.h | 4 ++-- libraries/AP_HAL_Linux/UDPDevice.h | 2 +- 4 files changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AP_HAL_Linux/RCInput_SoloLink.h b/libraries/AP_HAL_Linux/RCInput_SoloLink.h index d56ae8f277dfae..e9638df79fa11a 100644 --- a/libraries/AP_HAL_Linux/RCInput_SoloLink.h +++ b/libraries/AP_HAL_Linux/RCInput_SoloLink.h @@ -52,7 +52,7 @@ class RCInput_SoloLink : public RCInput bool _check_hdr(ssize_t len); - SocketAPM _socket{true}; + SocketAPM_native _socket{true}; uint64_t _last_usec = 0; uint16_t _last_seq = 0; union packet _packet; diff --git a/libraries/AP_HAL_Linux/RCInput_UDP.h b/libraries/AP_HAL_Linux/RCInput_UDP.h index 0431a2be7f1fde..9f87af9b5ce76f 100644 --- a/libraries/AP_HAL_Linux/RCInput_UDP.h +++ b/libraries/AP_HAL_Linux/RCInput_UDP.h @@ -15,7 +15,7 @@ class RCInput_UDP : public RCInput void init() override; void _timer_tick(void) override; private: - SocketAPM _socket{true}; + SocketAPM_native _socket{true}; uint16_t _port; struct rc_udp_packet_v3 _buf; uint64_t _last_buf_ts; diff --git a/libraries/AP_HAL_Linux/TCPServerDevice.h b/libraries/AP_HAL_Linux/TCPServerDevice.h index 0a268145a8acf5..2dd5d401a7dfc9 100644 --- a/libraries/AP_HAL_Linux/TCPServerDevice.h +++ b/libraries/AP_HAL_Linux/TCPServerDevice.h @@ -20,8 +20,8 @@ class TCPServerDevice: public SerialDevice { virtual ssize_t read(uint8_t *buf, uint16_t n) override; private: - SocketAPM listener{false}; - SocketAPM *sock = nullptr; + SocketAPM_native listener{false}; + SocketAPM_native *sock = nullptr; const char *_ip; uint16_t _port; bool _wait; diff --git a/libraries/AP_HAL_Linux/UDPDevice.h b/libraries/AP_HAL_Linux/UDPDevice.h index 4d3ad4d6f753d4..9f8e31336f3fee 100644 --- a/libraries/AP_HAL_Linux/UDPDevice.h +++ b/libraries/AP_HAL_Linux/UDPDevice.h @@ -15,7 +15,7 @@ class UDPDevice: public SerialDevice { virtual ssize_t write(const uint8_t *buf, uint16_t n) override; virtual ssize_t read(uint8_t *buf, uint16_t n) override; private: - SocketAPM socket{true}; + SocketAPM_native socket{true}; const char *_ip; uint16_t _port; bool _bcast; From 1e7ca3453136859b1b7090baed2e81c0d0e1d11f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 17:22:23 +1100 Subject: [PATCH 0346/1335] AP_HAL: socket native fix --- libraries/AP_HAL/utility/Socket_native.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/libraries/AP_HAL/utility/Socket_native.cpp b/libraries/AP_HAL/utility/Socket_native.cpp index d0d21bb8cd32aa..cd6bf2c93715ce 100644 --- a/libraries/AP_HAL/utility/Socket_native.cpp +++ b/libraries/AP_HAL/utility/Socket_native.cpp @@ -1,6 +1,9 @@ /* variant of SocketAPM using native sockets (not via lwip) */ +#include + +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX #include "Socket_native.h" #if AP_SOCKET_NATIVE_ENABLED @@ -9,3 +12,5 @@ #define SOCKET_CLASS_NAME SocketAPM_native #include "Socket.cpp" #endif + +#endif From 229a527fede198eed585243ea17f903128fafd5b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 17:23:16 +1100 Subject: [PATCH 0347/1335] AP_Networking: use BinarySemaphore --- .../AP_Networking/lwip_hal/arch/sys_arch.cpp | 186 +++--------------- 1 file changed, 32 insertions(+), 154 deletions(-) diff --git a/libraries/AP_Networking/lwip_hal/arch/sys_arch.cpp b/libraries/AP_Networking/lwip_hal/arch/sys_arch.cpp index 811ec76754782c..27636afaec73a3 100644 --- a/libraries/AP_Networking/lwip_hal/arch/sys_arch.cpp +++ b/libraries/AP_Networking/lwip_hal/arch/sys_arch.cpp @@ -1,5 +1,6 @@ /* port of lwip to ArduPilot AP_HAL + This is partly based on ChibiOS/os/various/lwip_bindings */ #include @@ -12,7 +13,6 @@ #include #include #include -#include #include #include @@ -26,13 +26,6 @@ extern "C" { #include "lwip/tcpip.h" } -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX -#include -#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS -#include "hal.h" -#include "../../../libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h" -#endif - extern const AP_HAL::HAL &hal; unsigned int @@ -61,69 +54,35 @@ struct sys_mbox { }; struct sys_sem { -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX - sem_t sem; -#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS - semaphore_t sem; -#else -#error "Need sys_sem implementation" -#endif + HAL_BinarySemaphore sem; }; -static struct sys_sem *sys_sem_new_internal(u8_t count); -static void sys_sem_free_internal(struct sys_sem *sem); - -/* Threads */ - -struct thread_wrapper_data { +class ThreadWrapper { +public: + ThreadWrapper(lwip_thread_fn fn, void *_arg) : + function(fn), + arg(_arg) + {} + bool create(const char *name, int stacksize, int prio) { + return hal.scheduler->thread_create( + FUNCTOR_BIND_MEMBER(&ThreadWrapper::run, void), name, MAX(stacksize,2048), AP_HAL::Scheduler::PRIORITY_NET, prio); + } +private: + void run(void) { + function(arg); + } lwip_thread_fn function; void *arg; }; -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX -static void * -thread_wrapper(void *arg) -{ - auto *thread_data = (struct thread_wrapper_data *)arg; - thread_data->function(thread_data->arg); - return NULL; -} -#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS -static void -thread_wrapper(void *arg) -{ - auto *thread_data = (struct thread_wrapper_data *)arg; - thread_data->function(thread_data->arg); -} -#endif - sys_thread_t sys_thread_new(const char *name, lwip_thread_fn function, void *arg, int stacksize, int prio) { - sys_thread_t ret = nullptr; - struct thread_wrapper_data *thread_data; - - thread_data = new thread_wrapper_data; - thread_data->arg = arg; - thread_data->function = function; - -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX - pthread_t t; - if (pthread_create(&t, NULL, thread_wrapper, thread_data) == 0) { - pthread_setname_np(t, name); - ret = (void*)t; + auto *thread_data = new ThreadWrapper(function, arg); + if (!thread_data->create(name, stacksize, prio)) { + AP_HAL::panic("lwip: Failed to start thread %s", name); } -#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS - ret = thread_create_alloc(THD_WORKING_AREA_SIZE(stacksize+1024), - name, - prio+60, // need to use HAL thread call - thread_wrapper, - thread_data); -#endif - if (ret == nullptr) { - AP_HAL::panic("Failed to create thread %s", name); - } - return ret; + return (sys_thread_t)thread_data; } void sys_lock_tcpip_core(void) @@ -163,9 +122,9 @@ sys_mbox_new(struct sys_mbox **mb, int size) return ERR_MEM; } mbox->first = mbox->last = 0; - mbox->not_empty = sys_sem_new_internal(0); - mbox->not_full = sys_sem_new_internal(0); - mbox->mutex = sys_sem_new_internal(1); + sys_sem_new(&mbox->not_empty, 0); + sys_sem_new(&mbox->not_full, 0); + sys_sem_new(&mbox->mutex, 1); mbox->wait_send = 0; *mb = mbox; @@ -179,9 +138,9 @@ sys_mbox_free(struct sys_mbox **mb) struct sys_mbox *mbox = *mb; sys_arch_sem_wait(&mbox->mutex, 0); - sys_sem_free_internal(mbox->not_empty); - sys_sem_free_internal(mbox->not_full); - sys_sem_free_internal(mbox->mutex); + sys_sem_free(&mbox->not_empty); + sys_sem_free(&mbox->not_full); + sys_sem_free(&mbox->mutex); mbox->not_empty = mbox->not_full = mbox->mutex = NULL; /* LWIP_DEBUGF("sys_mbox_free: mbox 0x%lx\n", mbox); */ delete mbox; @@ -339,26 +298,11 @@ sys_arch_mbox_fetch(struct sys_mbox **mb, void **msg, u32_t timeout) return 0; } -/*-----------------------------------------------------------------------------------*/ -/* Semaphore */ -static struct sys_sem * -sys_sem_new_internal(u8_t count) -{ - auto *ret = new sys_sem; - if (ret != nullptr) { -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX - sem_init(&ret->sem, 0, count); -#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS - chSemObjectInit(&ret->sem, (cnt_t)count); -#endif - } - return ret; -} - err_t sys_sem_new(struct sys_sem **sem, u8_t count) { - *sem = sys_sem_new_internal(count); + auto *s = new HAL_BinarySemaphore(count); + *sem = (struct sys_sem *)s; if (*sem == NULL) { return ERR_MEM; } @@ -369,60 +313,23 @@ u32_t sys_arch_sem_wait(struct sys_sem **s, u32_t timeout_ms) { struct sys_sem *sem = *s; -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX if (timeout_ms == 0) { - sem_wait(&sem->sem); - return 0; + return sem->sem.wait_blocking()?0:SYS_ARCH_TIMEOUT; } - struct timespec ts; - if (clock_gettime(CLOCK_REALTIME, &ts) != 0) { - return SYS_ARCH_TIMEOUT; - } - ts.tv_sec += timeout_ms/1000UL; - ts.tv_nsec += (timeout_ms % 1000U) * 1000000UL; - if (ts.tv_nsec >= 1000000000L) { - ts.tv_sec++; - ts.tv_nsec -= 1000000000L; - } - auto ret = sem_timedwait(&sem->sem, &ts); - if (ret != 0) { - return SYS_ARCH_TIMEOUT; - } -#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS - chSysLock(); - sysinterval_t tmo = timeout_ms > 0 ? MIN(TIME_MAX_INTERVAL, TIME_MS2I((time_msecs_t)timeout_ms)) : TIME_INFINITE; - if (chSemWaitTimeoutS(&sem->sem, tmo) != MSG_OK) { - chSysUnlock(); - return SYS_ARCH_TIMEOUT; - } - chSysUnlock(); -#endif - return 0; + return sem->sem.wait(timeout_ms*1000U)?0:SYS_ARCH_TIMEOUT; } void sys_sem_signal(struct sys_sem **s) { struct sys_sem *sem = *s; -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX - sem_post(&sem->sem); -#elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS - chSemSignal(&sem->sem); -#endif -} - -static void -sys_sem_free_internal(struct sys_sem *sem) -{ - delete sem; + sem->sem.signal(); } void sys_sem_free(struct sys_sem **sem) { - if ((sem != NULL) && (*sem != SYS_SEM_NULL)) { - sys_sem_free_internal(*sem); - } + delete *sem; } /*-----------------------------------------------------------------------------------*/ @@ -472,9 +379,6 @@ sys_mutex_free(struct sys_mutex **mutex) delete sem; } - -/*-----------------------------------------------------------------------------------*/ -/* Time */ u32_t sys_now(void) { @@ -487,30 +391,11 @@ sys_jiffies(void) return AP_HAL::micros(); } -/*-----------------------------------------------------------------------------------*/ -/* Init */ - void sys_init(void) { } -/*-----------------------------------------------------------------------------------*/ -/* Critical section */ -/** sys_prot_t sys_arch_protect(void) - -This optional function does a "fast" critical region protection and returns -the previous protection level. This function is only called during very short -critical regions. An embedded system which supports ISR-based drivers might -want to implement this function by disabling interrupts. Task-based systems -might want to implement this by using a mutex or disabling tasking. This -function should support recursive calls from the same task or interrupt. In -other words, sys_arch_protect() could be called while already protected. In -that case the return value indicates that it is already protected. - -sys_arch_protect() is only required if your port is supporting an operating -system. -*/ sys_prot_t sys_arch_protect(void) { @@ -520,13 +405,6 @@ sys_arch_protect(void) return 0; } -/** void sys_arch_unprotect(sys_prot_t pval) - -This optional function does a "fast" set of critical region protection to the -value specified by pval. See the documentation for sys_arch_protect() for -more information. This function is only required if your port is supporting -an operating system. -*/ void sys_arch_unprotect(sys_prot_t pval) { From eb6c62f319edb8c148e235d533ab3d24e6ace798 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 18:49:49 +1100 Subject: [PATCH 0348/1335] CI: added CubeOrange-PPP build test --- .github/workflows/test_chibios.yml | 3 ++- Tools/scripts/build_ci.sh | 8 ++++++++ 2 files changed, 10 insertions(+), 1 deletion(-) diff --git a/.github/workflows/test_chibios.yml b/.github/workflows/test_chibios.yml index 3fe7c730eac021..9e4cb96785f477 100644 --- a/.github/workflows/test_chibios.yml +++ b/.github/workflows/test_chibios.yml @@ -155,7 +155,8 @@ jobs: CubeRedPrimary-bootloader, configure-all, build-options-defaults-test, - signing + signing, + CubeOrange-PPP, ] toolchain: [ chibios, diff --git a/Tools/scripts/build_ci.sh b/Tools/scripts/build_ci.sh index 6223c2c0b09cf3..e0dbd68b2522eb 100755 --- a/Tools/scripts/build_ci.sh +++ b/Tools/scripts/build_ci.sh @@ -325,6 +325,14 @@ for t in $CI_BUILD_TARGET; do continue fi + if [ "$t" == "CubeOrange-PPP" ]; then + echo "Building CubeOrange-PPP" + $waf configure --board CubeOrange --enable-ppp + $waf clean + $waf copter + continue + fi + if [ "$t" == "dds-stm32h7" ]; then echo "Building with DDS support on a STM32H7" $waf configure --board Durandal --enable-dds From b340b5f8cabb1615dfdd1512d7d3ac15beb1eaaa Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 26 Dec 2023 19:04:43 +1100 Subject: [PATCH 0349/1335] Tools: added PPP as a build option --- Tools/scripts/build_options.py | 2 ++ Tools/scripts/extract_features.py | 1 + 2 files changed, 3 insertions(+) diff --git a/Tools/scripts/build_options.py b/Tools/scripts/build_options.py index 7dc8f69cfe6a8d..01bb18cfad60ea 100644 --- a/Tools/scripts/build_options.py +++ b/Tools/scripts/build_options.py @@ -373,6 +373,8 @@ def __init__(self, # Feature('Filesystem', 'FILESYSTEM_POSIX', 'AP_FILESYSTEM_POSIX_ENABLED', 'Enable POSIX filesystem', 0, None), Feature('Filesystem', 'FILESYSTEM_ROMFS', 'AP_FILESYSTEM_ROMFS_ENABLED', 'Enable @ROMFS/ filesystem', 0, None), Feature('Filesystem', 'FILESYSTEM_SYS', 'AP_FILESYSTEM_SYS_ENABLED', 'Enable @SYS/ filesystem', 0, None), + + Feature('Networking', 'PPP Support', 'AP_NETWORKING_BACKEND_PPP', 'Enable PPP networking', 0, None), ] BUILD_OPTIONS.sort(key=lambda x: (x.category + x.label)) diff --git a/Tools/scripts/extract_features.py b/Tools/scripts/extract_features.py index fa2b0378710eb6..8fe5436843064d 100755 --- a/Tools/scripts/extract_features.py +++ b/Tools/scripts/extract_features.py @@ -237,6 +237,7 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"): ('AP_TUNING_ENABLED', 'AP_Tuning::check_input'), ('AP_DRONECAN_SERIAL_ENABLED', 'AP_DroneCAN_Serial::update'), ('AP_SERIALMANAGER_IMUOUT_ENABLED', 'AP_InertialSensor::send_uart_data'), + ('AP_NETWORKING_BACKEND_PPP', 'AP_Networking_PPP::init'), ] def progress(self, msg): From 8fcc7d5a51f177b1f2fcc14a240a626812efe491 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 27 Dec 2023 12:06:15 +1100 Subject: [PATCH 0350/1335] AP_Networking: fixed ChibiOS backend with 16 bit timer --- libraries/AP_Networking/AP_Networking_ChibiOS.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/libraries/AP_Networking/AP_Networking_ChibiOS.cpp b/libraries/AP_Networking/AP_Networking_ChibiOS.cpp index ed5c5ea8908bae..3b330425164969 100644 --- a/libraries/AP_Networking/AP_Networking_ChibiOS.cpp +++ b/libraries/AP_Networking/AP_Networking_ChibiOS.cpp @@ -38,10 +38,6 @@ uint32_t *__eth_tb[STM32_MAC_TRANSMIT_BUFFERS]; #define PERIODIC_TIMER_ID 1 #define FRAME_RECEIVED_ID 2 -#if CH_CFG_ST_RESOLUTION != 32 -#error "ethernet requires 32 bit timer" -#endif - /* allocate buffers for LWIP */ From af47beebfcd4821b6b627f8aea453fd58e5d44c5 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 27 Dec 2023 14:22:51 +1100 Subject: [PATCH 0351/1335] AP_Networking: fixed discard test on PPP and fixed byte order bug --- libraries/AP_Networking/AP_Networking_address.cpp | 2 +- libraries/AP_Networking/AP_Networking_tests.cpp | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Networking/AP_Networking_address.cpp b/libraries/AP_Networking/AP_Networking_address.cpp index ddb36428e19f34..93997479f198b0 100644 --- a/libraries/AP_Networking/AP_Networking_address.cpp +++ b/libraries/AP_Networking/AP_Networking_address.cpp @@ -72,7 +72,7 @@ void AP_Networking_IPV4::set_default_uint32(uint32_t v) const char* AP_Networking_IPV4::get_str() { - const auto ip = ntohl(get_uint32()); + const auto ip = get_uint32(); return SocketAPM::inet_addr_to_str(ip, strbuf, sizeof(strbuf)); } diff --git a/libraries/AP_Networking/AP_Networking_tests.cpp b/libraries/AP_Networking/AP_Networking_tests.cpp index d4c33f980630c6..5630126105fcd9 100644 --- a/libraries/AP_Networking/AP_Networking_tests.cpp +++ b/libraries/AP_Networking/AP_Networking_tests.cpp @@ -113,10 +113,10 @@ void AP_Networking::test_TCP_discard(void) return; } // connect to the discard service, which is port 9 - if (!sock->connect(dest, 9)) { - GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "TCP_discard: connect failed"); - return; + while (!sock->connect(dest, 9)) { + hal.scheduler->delay(10); } + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "TCP_discard: connected"); const uint32_t bufsize = 1024; uint8_t *buf = (uint8_t*)malloc(bufsize); for (uint32_t i=0; i Date: Wed, 27 Dec 2023 15:13:29 +1100 Subject: [PATCH 0352/1335] AP_Networking: small improvement to ethernet throughput --- libraries/AP_Networking/config/lwipopts.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Networking/config/lwipopts.h b/libraries/AP_Networking/config/lwipopts.h index 8c6789f1ad841c..d3ff36a44cb1c2 100644 --- a/libraries/AP_Networking/config/lwipopts.h +++ b/libraries/AP_Networking/config/lwipopts.h @@ -90,6 +90,8 @@ extern "C" #define TCP_WND 12000 #define TCP_SND_BUF 12000 +#define DEFAULT_ACCEPTMBOX_SIZE 20 + // #define LWIP_DEBUG #ifdef LWIP_DEBUG @@ -140,7 +142,7 @@ a lot of data that needs to be copied, this should be set high. */ /* MEMP_NUM_PBUF: the number of memp struct pbufs. If the application sends a lot of data out of ROM (or other static memory), this should be set high. */ -#define MEMP_NUM_PBUF 100 +#define MEMP_NUM_PBUF 64 /* MEMP_NUM_RAW_PCB: the number of UDP protocol control blocks. One per active RAW "connection". */ #define MEMP_NUM_RAW_PCB 3 From 702fe9c18d50094e31d54499da550066a44f002b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 27 Dec 2023 17:11:19 +1100 Subject: [PATCH 0353/1335] AP_Networking: only enable networking on Linux, ChibiOS and SITL --- libraries/AP_Networking/AP_Networking_Config.h | 2 +- libraries/AP_Networking/AP_Networking_PPP.cpp | 2 +- libraries/AP_Networking/wscript | 4 ++++ 3 files changed, 6 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Networking/AP_Networking_Config.h b/libraries/AP_Networking/AP_Networking_Config.h index 803b06e1b7126d..b0f174618fd120 100644 --- a/libraries/AP_Networking/AP_Networking_Config.h +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -6,7 +6,7 @@ #endif #ifndef AP_NETWORKING_ENABLED -#define AP_NETWORKING_ENABLED ((CONFIG_HAL_BOARD == HAL_BOARD_LINUX) || (CONFIG_HAL_BOARD == HAL_BOARD_SITL)) +#define AP_NETWORKING_ENABLED (((CONFIG_HAL_BOARD == HAL_BOARD_LINUX) || (CONFIG_HAL_BOARD == HAL_BOARD_SITL)) && !defined(__APPLE__)) #endif #ifndef AP_NETWORKING_BACKEND_DEFAULT_ENABLED diff --git a/libraries/AP_Networking/AP_Networking_PPP.cpp b/libraries/AP_Networking/AP_Networking_PPP.cpp index b906743020b68d..b5437de9e4a71f 100644 --- a/libraries/AP_Networking/AP_Networking_PPP.cpp +++ b/libraries/AP_Networking/AP_Networking_PPP.cpp @@ -35,7 +35,7 @@ uint32_t AP_Networking_PPP::ppp_output_cb(ppp_pcb *pcb, const void *data, uint32 uint32_t remaining = len; const uint8_t *ptr = (const uint8_t *)data; while (remaining > 0) { - auto n = driver.uart->write(ptr, remaining); + const auto n = driver.uart->write(ptr, remaining); if (n > 0) { remaining -= n; ptr += n; diff --git a/libraries/AP_Networking/wscript b/libraries/AP_Networking/wscript index e1ed0c9af2cbd0..f48864d3cced67 100644 --- a/libraries/AP_Networking/wscript +++ b/libraries/AP_Networking/wscript @@ -4,6 +4,10 @@ import pathlib def configure(cfg): + + if not cfg.env.BOARD_CLASS in ['SITL', 'LINUX', 'ChibiOS']: + return + extra_src = [ 'modules/lwip/src/core/*c', 'modules/lwip/src/core/ipv4/*c', From f96810bb22fadd42a24156fec1b72963a9abda55 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 27 Dec 2023 17:11:30 +1100 Subject: [PATCH 0354/1335] AP_RCProtocol: fixed example build --- .../examples/RCProtocolDecoder/RCProtocolDecoder.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_RCProtocol/examples/RCProtocolDecoder/RCProtocolDecoder.cpp b/libraries/AP_RCProtocol/examples/RCProtocolDecoder/RCProtocolDecoder.cpp index 2a394a10f559f1..0d7ce675d2a71b 100644 --- a/libraries/AP_RCProtocol/examples/RCProtocolDecoder/RCProtocolDecoder.cpp +++ b/libraries/AP_RCProtocol/examples/RCProtocolDecoder/RCProtocolDecoder.cpp @@ -73,7 +73,7 @@ class RC_Channels_RC : public RC_Channels #include RC_Channels_RC _rc; -SocketAPM rc_socket{true}; +SocketAPM_native rc_socket{true}; // change this to the device being tested. const char *devicename = "/dev/serial/by-id/usb-FTDI_FT232R_USB_UART_A10596TP-if00-port0"; From f4e731781d1cc89bde70df18e0c79a6323bec190 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 28 Dec 2023 08:21:47 +1100 Subject: [PATCH 0355/1335] CI: debug ppp install --- .github/workflows/test_sitl_rover.yml | 3 ++- Tools/scripts/build_ci.sh | 2 ++ 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/.github/workflows/test_sitl_rover.yml b/.github/workflows/test_sitl_rover.yml index 74c6c0f93d733d..444ad7f2118c64 100644 --- a/.github/workflows/test_sitl_rover.yml +++ b/.github/workflows/test_sitl_rover.yml @@ -192,7 +192,8 @@ jobs: - name: build rover ${{ matrix.toolchain }} shell: bash run: | - sudo apt-get -y install ppp + sudo apt-get update || true + sudo apt-get -y install ppp || true git config --global --add safe.directory ${GITHUB_WORKSPACE} if [[ ${{ matrix.toolchain }} == "clang" ]]; then export CC=clang diff --git a/Tools/scripts/build_ci.sh b/Tools/scripts/build_ci.sh index e0dbd68b2522eb..1b52fba38021e4 100755 --- a/Tools/scripts/build_ci.sh +++ b/Tools/scripts/build_ci.sh @@ -144,6 +144,8 @@ for t in $CI_BUILD_TARGET; do continue fi if [ "$t" == "sitltest-rover" ]; then + sudo apt-get update || /bin/true + sudo apt-get install -y ppp || /bin/true run_autotest "Rover" "build.Rover" "test.Rover" continue fi From ab24d8768f684e36a3249c4d92cc258b6fab0202 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 28 Dec 2023 09:08:19 +1100 Subject: [PATCH 0356/1335] AP_Networking: disable on MacOSX --- libraries/AP_Networking/AP_Networking_Config.h | 8 +++++++- libraries/AP_Networking/wscript | 6 +++++- 2 files changed, 12 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Networking/AP_Networking_Config.h b/libraries/AP_Networking/AP_Networking_Config.h index b0f174618fd120..ea77791a2b91b5 100644 --- a/libraries/AP_Networking/AP_Networking_Config.h +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -5,8 +5,14 @@ #define AP_NETWORKING_ENABLED AP_NETWORKING_BACKEND_PPP #endif + #ifndef AP_NETWORKING_ENABLED -#define AP_NETWORKING_ENABLED (((CONFIG_HAL_BOARD == HAL_BOARD_LINUX) || (CONFIG_HAL_BOARD == HAL_BOARD_SITL)) && !defined(__APPLE__)) +#if defined(__APPLE__) || defined(__clang__) +// MacOS can't build lwip, and clang fails on linux +#define AP_NETWORKING_ENABLED 0 +#else +#define AP_NETWORKING_ENABLED ((CONFIG_HAL_BOARD == HAL_BOARD_LINUX) || (CONFIG_HAL_BOARD == HAL_BOARD_SITL)) +#endif #endif #ifndef AP_NETWORKING_BACKEND_DEFAULT_ENABLED diff --git a/libraries/AP_Networking/wscript b/libraries/AP_Networking/wscript index f48864d3cced67..4094b6aeaff8fb 100644 --- a/libraries/AP_Networking/wscript +++ b/libraries/AP_Networking/wscript @@ -1,13 +1,17 @@ #!/usr/bin/env python3 import pathlib - +import platform def configure(cfg): if not cfg.env.BOARD_CLASS in ['SITL', 'LINUX', 'ChibiOS']: return + # networking doesn't build on MacOSX or clang + if platform.system() == 'Darwin' or 'clang++' in cfg.env.COMPILER_CXX: + return + extra_src = [ 'modules/lwip/src/core/*c', 'modules/lwip/src/core/ipv4/*c', From f0a1a19f8b14f0f5c860e94e4d5be19c1257988c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 29 Dec 2023 07:29:31 +1100 Subject: [PATCH 0357/1335] AP_Networking: allow discard test to be paused --- libraries/AP_Networking/AP_Networking_tests.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_Networking/AP_Networking_tests.cpp b/libraries/AP_Networking/AP_Networking_tests.cpp index 5630126105fcd9..839f17f74647ad 100644 --- a/libraries/AP_Networking/AP_Networking_tests.cpp +++ b/libraries/AP_Networking/AP_Networking_tests.cpp @@ -125,6 +125,10 @@ void AP_Networking::test_TCP_discard(void) uint32_t last_report_ms = AP_HAL::millis(); uint32_t total_sent = 0; while (true) { + if ((param.tests & TEST_TCP_DISCARD) == 0) { + hal.scheduler->delay(1); + continue; + } total_sent += sock->send(buf, bufsize); const uint32_t now = AP_HAL::millis(); if (now - last_report_ms >= 1000) { From cc8c671cb7b3124ec04665f79d0a873a89859942 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 29 Dec 2023 08:13:54 +1100 Subject: [PATCH 0358/1335] HAL_ChibiOS: don't link evtimer in chibios_board.mk --- libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk | 3 --- 1 file changed, 3 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk b/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk index 7d9f8a67a6550c..893b358f549685 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/chibios_board.mk @@ -145,9 +145,6 @@ CSRC += $(CHIBIOS)/os/various/scsi_bindings/lib_scsi.c \ $(CHIBIOS)/os/hal/src/hal_usb_msd.c endif -# evtimer used by networking -CSRC += $(CHIBIOS)/os/various/evtimer.c - # $(TESTSRC) \ # test.c ifneq ($(CRASHCATCHER),) From f5bee94cba120138f45e1da2c29f831855ee8659 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 29 Dec 2023 08:14:13 +1100 Subject: [PATCH 0359/1335] AP_Networking: added evtimer wrapper --- libraries/AP_Networking/lwip_hal/arch/evtimer.c | 10 ++++++++++ libraries/AP_Networking/wscript | 4 ++++ 2 files changed, 14 insertions(+) create mode 100644 libraries/AP_Networking/lwip_hal/arch/evtimer.c diff --git a/libraries/AP_Networking/lwip_hal/arch/evtimer.c b/libraries/AP_Networking/lwip_hal/arch/evtimer.c new file mode 100644 index 00000000000000..53da0413f82109 --- /dev/null +++ b/libraries/AP_Networking/lwip_hal/arch/evtimer.c @@ -0,0 +1,10 @@ +/* + wrapper around evtimer.c so we only build when events are + enabled. This prevents a complex check in the ChibiOS mk layer + */ +#include + +#if CH_CFG_USE_EVENTS +#include "../../modules/ChibiOS/os/various/evtimer.c" +#endif + diff --git a/libraries/AP_Networking/wscript b/libraries/AP_Networking/wscript index 4094b6aeaff8fb..97554622a79f80 100644 --- a/libraries/AP_Networking/wscript +++ b/libraries/AP_Networking/wscript @@ -25,6 +25,10 @@ def configure(cfg): ] extra_src.extend(['libraries/AP_Networking/lwip_hal/arch/*cpp']) + + if cfg.env.BOARD_CLASS == 'ChibiOS': + extra_src.extend(['libraries/AP_Networking/lwip_hal/arch/evtimer.c']) + extra_src_inc.extend(['libraries/AP_Networking/config', 'libraries/AP_Networking/lwip_hal/include']) From 791a0a3230da8462f49edbce56da5109da322985 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 2 Jan 2024 08:04:41 +1100 Subject: [PATCH 0360/1335] AP_Networking: use HAL objects more directly and fix a ms/us bug --- .../AP_Networking/lwip_hal/arch/sys_arch.cpp | 129 +++++++----------- .../lwip_hal/include/arch/sys_arch.h | 2 - 2 files changed, 50 insertions(+), 81 deletions(-) diff --git a/libraries/AP_Networking/lwip_hal/arch/sys_arch.cpp b/libraries/AP_Networking/lwip_hal/arch/sys_arch.cpp index 27636afaec73a3..d9b517b47fbf54 100644 --- a/libraries/AP_Networking/lwip_hal/arch/sys_arch.cpp +++ b/libraries/AP_Networking/lwip_hal/arch/sys_arch.cpp @@ -47,16 +47,12 @@ struct sys_mbox_msg { struct sys_mbox { int first, last; void *msgs[SYS_MBOX_SIZE]; - struct sys_sem *not_empty; - struct sys_sem *not_full; - struct sys_sem *mutex; + HAL_BinarySemaphore not_empty; + HAL_BinarySemaphore not_full; + HAL_BinarySemaphore mutex; int wait_send; }; -struct sys_sem { - HAL_BinarySemaphore sem; -}; - class ThreadWrapper { public: ThreadWrapper(lwip_thread_fn fn, void *_arg) : @@ -87,16 +83,12 @@ sys_thread_new(const char *name, lwip_thread_fn function, void *arg, int stacksi void sys_lock_tcpip_core(void) { - if (hal.scheduler != nullptr) { - tcpip_mutex.take_blocking(); - } + tcpip_mutex.take_blocking(); } void sys_unlock_tcpip_core(void) { - if (hal.scheduler != nullptr) { - tcpip_mutex.give(); - } + tcpip_mutex.give(); } void sys_mark_tcpip_thread(void) @@ -122,9 +114,7 @@ sys_mbox_new(struct sys_mbox **mb, int size) return ERR_MEM; } mbox->first = mbox->last = 0; - sys_sem_new(&mbox->not_empty, 0); - sys_sem_new(&mbox->not_full, 0); - sys_sem_new(&mbox->mutex, 1); + mbox->mutex.signal(); mbox->wait_send = 0; *mb = mbox; @@ -136,13 +126,7 @@ sys_mbox_free(struct sys_mbox **mb) { if ((mb != NULL) && (*mb != SYS_MBOX_NULL)) { struct sys_mbox *mbox = *mb; - sys_arch_sem_wait(&mbox->mutex, 0); - - sys_sem_free(&mbox->not_empty); - sys_sem_free(&mbox->not_full); - sys_sem_free(&mbox->mutex); - mbox->not_empty = mbox->not_full = mbox->mutex = NULL; - /* LWIP_DEBUGF("sys_mbox_free: mbox 0x%lx\n", mbox); */ + mbox->mutex.wait_blocking(); delete mbox; } } @@ -155,13 +139,13 @@ sys_mbox_trypost(struct sys_mbox **mb, void *msg) LWIP_ASSERT("invalid mbox", (mb != NULL) && (*mb != NULL)); mbox = *mb; - sys_arch_sem_wait(&mbox->mutex, 0); + mbox->mutex.wait_blocking(); LWIP_DEBUGF(SYS_DEBUG, ("sys_mbox_trypost: mbox %p msg %p\n", (void *)mbox, (void *)msg)); if ((mbox->last + 1) >= (mbox->first + SYS_MBOX_SIZE)) { - sys_sem_signal(&mbox->mutex); + mbox->mutex.signal(); return ERR_MEM; } @@ -176,10 +160,10 @@ sys_mbox_trypost(struct sys_mbox **mb, void *msg) mbox->last++; if (first) { - sys_sem_signal(&mbox->not_empty); + mbox->not_empty.signal(); } - sys_sem_signal(&mbox->mutex); + mbox->mutex.signal(); return ERR_OK; } @@ -192,15 +176,15 @@ sys_mbox_post(struct sys_mbox **mb, void *msg) LWIP_ASSERT("invalid mbox", (mb != NULL) && (*mb != NULL)); mbox = *mb; - sys_arch_sem_wait(&mbox->mutex, 0); + mbox->mutex.wait_blocking(); LWIP_DEBUGF(SYS_DEBUG, ("sys_mbox_post: mbox %p msg %p\n", (void *)mbox, (void *)msg)); while ((mbox->last + 1) >= (mbox->first + SYS_MBOX_SIZE)) { mbox->wait_send++; - sys_sem_signal(&mbox->mutex); - sys_arch_sem_wait(&mbox->not_full, 0); - sys_arch_sem_wait(&mbox->mutex, 0); + mbox->mutex.signal(); + mbox->not_full.wait_blocking(); + mbox->mutex.wait_blocking(); mbox->wait_send--; } @@ -215,10 +199,10 @@ sys_mbox_post(struct sys_mbox **mb, void *msg) mbox->last++; if (first) { - sys_sem_signal(&mbox->not_empty); + mbox->not_empty.signal(); } - sys_sem_signal(&mbox->mutex); + mbox->mutex.signal(); } u32_t @@ -226,10 +210,10 @@ sys_arch_mbox_tryfetch(struct sys_mbox **mb, void **msg) { struct sys_mbox *mbox = *mb; - sys_arch_sem_wait(&mbox->mutex, 0); + mbox->mutex.wait_blocking(); if (mbox->first == mbox->last) { - sys_sem_signal(&mbox->mutex); + mbox->mutex.signal(); return SYS_MBOX_EMPTY; } @@ -243,41 +227,37 @@ sys_arch_mbox_tryfetch(struct sys_mbox **mb, void **msg) mbox->first++; if (mbox->wait_send) { - sys_sem_signal(&mbox->not_full); + mbox->not_full.signal(); } - sys_sem_signal(&mbox->mutex); + mbox->mutex.signal(); return 0; } u32_t -sys_arch_mbox_fetch(struct sys_mbox **mb, void **msg, u32_t timeout) +sys_arch_mbox_fetch(struct sys_mbox **mb, void **msg, u32_t timeout_ms) { struct sys_mbox *mbox; LWIP_ASSERT("invalid mbox", (mb != NULL) && (*mb != NULL)); mbox = *mb; - /* The mutex lock is quick so we don't bother with the timeout - stuff here. */ - sys_arch_sem_wait(&mbox->mutex, 0); + mbox->mutex.wait_blocking(); while (mbox->first == mbox->last) { - sys_sem_signal(&mbox->mutex); + mbox->mutex.signal(); /* We block while waiting for a mail to arrive in the mailbox. We must be prepared to timeout. */ - if (timeout != 0) { - u32_t time_needed = sys_arch_sem_wait(&mbox->not_empty, timeout); - - if (time_needed == SYS_ARCH_TIMEOUT) { + if (timeout_ms != 0) { + if (!mbox->not_empty.wait(timeout_ms*1000U)) { return SYS_ARCH_TIMEOUT; } } else { - sys_arch_sem_wait(&mbox->not_empty, 0); + mbox->not_empty.wait_blocking(); } - sys_arch_sem_wait(&mbox->mutex, 0); + mbox->mutex.wait_blocking(); } if (msg != NULL) { @@ -290,19 +270,18 @@ sys_arch_mbox_fetch(struct sys_mbox **mb, void **msg, u32_t timeout) mbox->first++; if (mbox->wait_send) { - sys_sem_signal(&mbox->not_full); + mbox->not_full.signal(); } - sys_sem_signal(&mbox->mutex); + mbox->mutex.signal(); return 0; } err_t -sys_sem_new(struct sys_sem **sem, u8_t count) +sys_sem_new(sys_sem_t *sem, u8_t count) { - auto *s = new HAL_BinarySemaphore(count); - *sem = (struct sys_sem *)s; + *sem = (sys_sem_t)new HAL_BinarySemaphore(count); if (*sem == NULL) { return ERR_MEM; } @@ -310,26 +289,26 @@ sys_sem_new(struct sys_sem **sem, u8_t count) } u32_t -sys_arch_sem_wait(struct sys_sem **s, u32_t timeout_ms) +sys_arch_sem_wait(sys_sem_t *s, u32_t timeout_ms) { - struct sys_sem *sem = *s; + HAL_BinarySemaphore *sem = (HAL_BinarySemaphore *)*s; if (timeout_ms == 0) { - return sem->sem.wait_blocking()?0:SYS_ARCH_TIMEOUT; + return sem->wait_blocking()?0:SYS_ARCH_TIMEOUT; } - return sem->sem.wait(timeout_ms*1000U)?0:SYS_ARCH_TIMEOUT; + return sem->wait(timeout_ms*1000U)?0:SYS_ARCH_TIMEOUT; } void -sys_sem_signal(struct sys_sem **s) +sys_sem_signal(sys_sem_t *s) { - struct sys_sem *sem = *s; - sem->sem.signal(); + HAL_BinarySemaphore *sem = (HAL_BinarySemaphore *)*s; + sem->signal(); } void -sys_sem_free(struct sys_sem **sem) +sys_sem_free(sys_sem_t *sem) { - delete *sem; + delete ((HAL_BinarySemaphore *)*sem); } /*-----------------------------------------------------------------------------------*/ @@ -338,45 +317,37 @@ sys_sem_free(struct sys_sem **sem) * @param mutex pointer to the mutex to create * @return a new mutex */ err_t -sys_mutex_new(struct sys_mutex **mutex) +sys_mutex_new(sys_mutex_t *mutex) { - auto *sem = new HAL_Semaphore; - if (sem == nullptr) { + *mutex = (sys_mutex_t)new HAL_Semaphore; + if (*mutex == nullptr) { return ERR_MEM; } - *mutex = (struct sys_mutex *)sem; return ERR_OK; } /** Lock a mutex * @param mutex the mutex to lock */ void -sys_mutex_lock(struct sys_mutex **mutex) +sys_mutex_lock(sys_mutex_t *mutex) { - auto *sem = (HAL_Semaphore *)*mutex; - if (hal.scheduler != nullptr) { - sem->take_blocking(); - } + ((HAL_Semaphore*)*mutex)->take_blocking(); } /** Unlock a mutex * @param mutex the mutex to unlock */ void -sys_mutex_unlock(struct sys_mutex **mutex) +sys_mutex_unlock(sys_mutex_t *mutex) { - auto *sem = (HAL_Semaphore *)*mutex; - if (hal.scheduler != nullptr) { - sem->give(); - } + ((HAL_Semaphore*)*mutex)->give(); } /** Delete a mutex * @param mutex the mutex to delete */ void -sys_mutex_free(struct sys_mutex **mutex) +sys_mutex_free(sys_mutex_t *mutex) { - auto *sem = (HAL_Semaphore *)*mutex; - delete sem; + delete (HAL_Semaphore*)*mutex; } u32_t diff --git a/libraries/AP_Networking/lwip_hal/include/arch/sys_arch.h b/libraries/AP_Networking/lwip_hal/include/arch/sys_arch.h index da48ac6b81820f..f376b2f8c42f88 100644 --- a/libraries/AP_Networking/lwip_hal/include/arch/sys_arch.h +++ b/libraries/AP_Networking/lwip_hal/include/arch/sys_arch.h @@ -8,8 +8,6 @@ extern "C" #define SYS_MBOX_NULL NULL #define SYS_SEM_NULL NULL -/*typedef u32_t sys_prot_t;*/ - struct sys_sem; typedef struct sys_sem * sys_sem_t; #define sys_sem_valid(sem) (((sem) != NULL) && (*(sem) != NULL)) From a841e9c109473f4ec2819a7a6bafb4e7550cdd62 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 2 Jan 2024 08:49:09 +1100 Subject: [PATCH 0361/1335] AP_Scripting: don't throw an exception on out of sockets in accept() normal lua sockets don't throw an exception on accept, it just returns nil --- libraries/AP_Scripting/lua_bindings.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Scripting/lua_bindings.cpp b/libraries/AP_Scripting/lua_bindings.cpp index e84a68786c8a04..f1ae9a99875678 100644 --- a/libraries/AP_Scripting/lua_bindings.cpp +++ b/libraries/AP_Scripting/lua_bindings.cpp @@ -913,7 +913,7 @@ int SocketAPM_accept(lua_State *L) { auto *scripting = AP::scripting(); if (scripting->num_net_sockets >= SCRIPTING_MAX_NUM_NET_SOCKET) { - return luaL_argerror(L, 1, "no sockets available"); + return 0; } auto *sock = ud->accept(0); From 5065770e30f91060cc98336bcf8d807504161002 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sun, 10 Dec 2023 20:03:38 +0000 Subject: [PATCH 0362/1335] AC_PID: tidy interface --- libraries/AC_PID/AC_PID.cpp | 2 +- libraries/AC_PID/AC_PID.h | 31 ++++++++++++++++--------------- 2 files changed, 17 insertions(+), 16 deletions(-) diff --git a/libraries/AC_PID/AC_PID.cpp b/libraries/AC_PID/AC_PID.cpp index 557b6b5bfbf146..358535592f3adf 100644 --- a/libraries/AC_PID/AC_PID.cpp +++ b/libraries/AC_PID/AC_PID.cpp @@ -336,7 +336,7 @@ float AC_PID::get_d() const return _kd * _derivative; } -float AC_PID::get_ff() +float AC_PID::get_ff() const { return _pid_info.FF + _pid_info.DFF; } diff --git a/libraries/AC_PID/AC_PID.h b/libraries/AC_PID/AC_PID.h index 0aa7e35e2c9508..8f9b7704c9b79b 100644 --- a/libraries/AC_PID/AC_PID.h +++ b/libraries/AC_PID/AC_PID.h @@ -72,17 +72,11 @@ class AC_PID { // todo: remove function when it is no longer used. float update_error(float error, float dt, bool limit = false); - // update_i - update the integral - // if the limit flag is set the integral is only allowed to shrink - void update_i(float dt, bool limit); - // get_pid - get results from pid controller - float get_pid() const; - float get_pi() const; float get_p() const; float get_i() const; float get_d() const; - float get_ff(); + float get_ff() const; // reset_I - reset the integrator void reset_I(); @@ -113,9 +107,11 @@ class AC_PID { AP_Float &filt_E_hz() { return _filt_E_hz; } AP_Float &filt_D_hz() { return _filt_D_hz; } AP_Float &slew_limit() { return _slew_rate_max; } + AP_Float &kDff() { return _kdff; } float imax() const { return _kimax.get(); } float pdmax() const { return _kpdmax.get(); } + float get_filt_T_alpha(float dt) const; float get_filt_E_alpha(float dt) const; float get_filt_D_alpha(float dt) const; @@ -131,6 +127,7 @@ class AC_PID { void filt_E_hz(const float v); void filt_D_hz(const float v); void slew_limit(const float v); + void kDff(const float v) { _kdff.set(v); } // set the desired and actual rates (for logging purposes) void set_target_rate(float target) { _pid_info.target = target; } @@ -150,20 +147,17 @@ class AC_PID { const AP_PIDInfo& get_pid_info(void) const { return _pid_info; } - AP_Float &kDff() { return _kdff; } - void kDff(const float v) { _kdff.set(v); } void set_notch_sample_rate(float); + // parameter var table static const struct AP_Param::GroupInfo var_info[]; - // the time constant tau is not currently configurable, but is set - // as an AP_Float to make it easy to make it configurable for a - // single user of AC_PID by adding the parameter in the param - // table of the parent class. It is made public for this reason - AP_Float _slew_rate_tau; - protected: + // update_i - update the integral + // if the limit flag is set the integral is only allowed to shrink + void update_i(float dt, bool limit); + // parameters AP_Float _kp; AP_Float _ki; @@ -180,6 +174,13 @@ class AC_PID { AP_Int8 _notch_T_filter; AP_Int8 _notch_E_filter; #endif + + // the time constant tau is not currently configurable, but is set + // as an AP_Float to make it easy to make it configurable for a + // single user of AC_PID by adding the parameter in the param + // table of the parent class. It is made public for this reason + AP_Float _slew_rate_tau; + SlewLimiter _slew_limiter{_slew_rate_max, _slew_rate_tau}; // flags From 2d75b0312ebda6edd4ae47763c0d5aa5c1a32908 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Mon, 11 Dec 2023 18:27:45 +0000 Subject: [PATCH 0363/1335] AC_PID: return P and D as output with slew limit and sum limit applyed --- libraries/AC_PID/AC_PID.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AC_PID/AC_PID.cpp b/libraries/AC_PID/AC_PID.cpp index 358535592f3adf..aa19e44a5f5fc6 100644 --- a/libraries/AC_PID/AC_PID.cpp +++ b/libraries/AC_PID/AC_PID.cpp @@ -323,7 +323,7 @@ void AC_PID::update_i(float dt, bool limit) float AC_PID::get_p() const { - return _error * _kp; + return _pid_info.P; } float AC_PID::get_i() const @@ -333,7 +333,7 @@ float AC_PID::get_i() const float AC_PID::get_d() const { - return _kd * _derivative; + return _pid_info.D; } float AC_PID::get_ff() const From 9146458d4a632dde7a8f3806c4281eb49b986bb4 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Mon, 11 Dec 2023 18:31:02 +0000 Subject: [PATCH 0364/1335] AC_PID: remove unused set_integrator methods --- libraries/AC_PID/AC_PID.cpp | 10 ---------- libraries/AC_PID/AC_PID.h | 2 -- 2 files changed, 12 deletions(-) diff --git a/libraries/AC_PID/AC_PID.cpp b/libraries/AC_PID/AC_PID.cpp index aa19e44a5f5fc6..6864072a3012c7 100644 --- a/libraries/AC_PID/AC_PID.cpp +++ b/libraries/AC_PID/AC_PID.cpp @@ -402,16 +402,6 @@ float AC_PID::get_filt_D_alpha(float dt) const return calc_lowpass_alpha_dt(dt, _filt_D_hz); } -void AC_PID::set_integrator(float target, float measurement, float integrator) -{ - set_integrator(target - measurement, integrator); -} - -void AC_PID::set_integrator(float error, float integrator) -{ - _integrator = constrain_float(integrator - error * _kp, -_kimax, _kimax); -} - void AC_PID::set_integrator(float integrator) { _integrator = constrain_float(integrator, -_kimax, _kimax); diff --git a/libraries/AC_PID/AC_PID.h b/libraries/AC_PID/AC_PID.h index 8f9b7704c9b79b..dce00821430cf0 100644 --- a/libraries/AC_PID/AC_PID.h +++ b/libraries/AC_PID/AC_PID.h @@ -134,8 +134,6 @@ class AC_PID { void set_actual_rate(float actual) { _pid_info.actual = actual; } // integrator setting functions - void set_integrator(float target, float measurement, float i); - void set_integrator(float error, float i); void set_integrator(float i); void relax_integrator(float integrator, float dt, float time_constant); From d53b73468bbf7a2820419239e7a34044182337b8 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Mon, 11 Dec 2023 18:44:30 +0000 Subject: [PATCH 0365/1335] AC_PID: add reset and I term set flags to PIDInfo --- libraries/AC_PID/AC_PID.cpp | 8 ++++++++ libraries/AC_PID/AC_PID.h | 1 + libraries/AC_PID/AP_PIDInfo.h | 2 ++ 3 files changed, 11 insertions(+) diff --git a/libraries/AC_PID/AC_PID.cpp b/libraries/AC_PID/AC_PID.cpp index 6864072a3012c7..166be7b7b3122b 100644 --- a/libraries/AC_PID/AC_PID.cpp +++ b/libraries/AC_PID/AC_PID.cpp @@ -198,6 +198,7 @@ float AC_PID::update_all(float target, float measurement, float dt, bool limit, } // reset input filter to value received + _pid_info.reset = _flags._reset_filter; if (_flags._reset_filter) { _flags._reset_filter = false; _target = target; @@ -319,6 +320,10 @@ void AC_PID::update_i(float dt, bool limit) } _pid_info.I = _integrator; _pid_info.limit = limit; + + // Set I set flag for logging and clear + _pid_info.I_term_set = _flags._I_set; + _flags._I_set = false; } float AC_PID::get_p() const @@ -343,6 +348,7 @@ float AC_PID::get_ff() const void AC_PID::reset_I() { + _flags._I_set = true; _integrator = 0.0; } @@ -404,6 +410,7 @@ float AC_PID::get_filt_D_alpha(float dt) const void AC_PID::set_integrator(float integrator) { + _flags._I_set = true; _integrator = constrain_float(integrator, -_kimax, _kimax); } @@ -411,6 +418,7 @@ void AC_PID::relax_integrator(float integrator, float dt, float time_constant) { integrator = constrain_float(integrator, -_kimax, _kimax); if (is_positive(dt)) { + _flags._I_set = true; _integrator = _integrator + (integrator - _integrator) * (dt / (dt + time_constant)); } } diff --git a/libraries/AC_PID/AC_PID.h b/libraries/AC_PID/AC_PID.h index dce00821430cf0..fbbebcac7db783 100644 --- a/libraries/AC_PID/AC_PID.h +++ b/libraries/AC_PID/AC_PID.h @@ -184,6 +184,7 @@ class AC_PID { // flags struct ac_pid_flags { bool _reset_filter :1; // true when input filter should be reset during next call to set_input + bool _I_set :1; // true if if the I terms has been set externally including zeroing } _flags; // internal variables diff --git a/libraries/AC_PID/AP_PIDInfo.h b/libraries/AC_PID/AP_PIDInfo.h index 70afb0974e01ce..992a287ec8bc5c 100644 --- a/libraries/AC_PID/AP_PIDInfo.h +++ b/libraries/AC_PID/AP_PIDInfo.h @@ -19,4 +19,6 @@ struct AP_PIDInfo { float slew_rate; bool limit; bool PD_limit; + bool reset; + bool I_term_set; }; From a44cba03efefe38c3b45e1fa288824e892f6ece2 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Mon, 11 Dec 2023 18:45:20 +0000 Subject: [PATCH 0366/1335] AP_Logger: Write_PID: add reset and I terms set flags --- libraries/AP_Logger/LogFile.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/libraries/AP_Logger/LogFile.cpp b/libraries/AP_Logger/LogFile.cpp index e4d3f1ff895b79..2febb3577fba0d 100644 --- a/libraries/AP_Logger/LogFile.cpp +++ b/libraries/AP_Logger/LogFile.cpp @@ -478,6 +478,8 @@ void AP_Logger::Write_PID(uint8_t msg_type, const AP_PIDInfo &info) enum class log_PID_Flags : uint8_t { LIMIT = 1U<<0, // true if the output is saturated, I term anti windup is active PD_SUM_LIMIT = 1U<<1, // true if the PD sum limit is active + RESET = 1U<<2, // true if the controller was reset + I_TERM_SET = 1U<<3, // true if the I term has been set externally including reseting to 0 }; uint8_t flags = 0; @@ -487,6 +489,12 @@ void AP_Logger::Write_PID(uint8_t msg_type, const AP_PIDInfo &info) if (info.PD_limit) { flags |= (uint8_t)log_PID_Flags::PD_SUM_LIMIT; } + if (info.reset) { + flags |= (uint8_t)log_PID_Flags::RESET; + } + if (info.I_term_set) { + flags |= (uint8_t)log_PID_Flags::I_TERM_SET; + } const struct log_PID pkt{ LOG_PACKET_HEADER_INIT(msg_type), From 368593c2c6452ebaa88b95383d6dffd5739323b4 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 9 Dec 2023 15:05:08 +1100 Subject: [PATCH 0367/1335] AP_Mission: correct compilation when AP_MISSION_ENABLED is false --- libraries/AP_Mission/AP_Mission.cpp | 24 +++++++++++++++++--- libraries/AP_Mission/AP_Mission_Commands.cpp | 6 +++++ 2 files changed, 27 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Mission/AP_Mission.cpp b/libraries/AP_Mission/AP_Mission.cpp index 22d6f60c364fa3..c8fabcdd8c7db1 100644 --- a/libraries/AP_Mission/AP_Mission.cpp +++ b/libraries/AP_Mission/AP_Mission.cpp @@ -1,13 +1,17 @@ /// @file AP_Mission.cpp /// @brief Handles the MAVLINK command mission stack. Reads and writes mission to storage. +#include "AP_Mission_config.h" +#include +#include +#include + +#if AP_MISSION_ENABLED + #include "AP_Mission.h" #include -#include #include #include -#include -#include #include #include #include @@ -828,6 +832,8 @@ bool AP_Mission::read_cmd_from_storage(uint16_t index, Mission_Command& cmd) con return true; } +#endif // AP_MISSION_ENABLED + bool AP_Mission::stored_in_location(uint16_t id) { switch (id) { @@ -854,6 +860,8 @@ bool AP_Mission::stored_in_location(uint16_t id) } } +#if AP_MISSION_ENABLED + /// write_cmd_to_storage - write a command to storage /// index is used to calculate the storage location /// true is returned if successful @@ -926,6 +934,8 @@ void AP_Mission::write_home_to_storage() write_cmd_to_storage(0,home_cmd); } +#endif // AP_MISSION_ENABLED + MAV_MISSION_RESULT AP_Mission::sanity_check_params(const mavlink_mission_item_int_t& packet) { uint8_t nan_mask; @@ -1486,6 +1496,8 @@ MAV_MISSION_RESULT AP_Mission::convert_MISSION_ITEM_INT_to_MISSION_ITEM(const ma return MAV_MISSION_ACCEPTED; } +#if AP_MISSION_ENABLED + // mission_cmd_to_mavlink_int - converts an AP_Mission::Mission_Command object to a mavlink message which can be sent to the GCS // return true on success, false on failure // NOTE: callers to this method current fill parts of "packet" in before calling this method, so do NOT attempt to zero the entire packet in here @@ -2717,6 +2729,8 @@ bool AP_Mission::contains_item(MAV_CMD command) const return false; } +#endif // AP_MISSION_ENABLED + /* return true if the mission item has a location */ @@ -2726,6 +2740,8 @@ bool AP_Mission::cmd_has_location(const uint16_t command) return stored_in_location(command); } +#if AP_MISSION_ENABLED + /* return true if the mission has a terrain relative item. ~2200us for 530 items on H7 */ @@ -2901,3 +2917,5 @@ AP_Mission *mission() } } + +#endif // AP_MISSION_ENABLED diff --git a/libraries/AP_Mission/AP_Mission_Commands.cpp b/libraries/AP_Mission/AP_Mission_Commands.cpp index 9d82550e482326..21d6731b733b07 100644 --- a/libraries/AP_Mission/AP_Mission_Commands.cpp +++ b/libraries/AP_Mission/AP_Mission_Commands.cpp @@ -1,3 +1,7 @@ +#include "AP_Mission_config.h" + +#if AP_MISSION_ENABLED + #include "AP_Mission.h" #include @@ -332,3 +336,5 @@ bool AP_Mission::start_command_do_gimbal_manager_pitchyaw(const AP_Mission::Miss // if we got this far then message is not handled return false; } + +#endif // AP_MISSION_ENABLED From 17f311ef320240f56d906ed40b8c6e938ecc4264 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 9 Dec 2023 15:05:08 +1100 Subject: [PATCH 0368/1335] AP_Vehicle: correct compilation when AP_MISSION_ENABLED is false --- libraries/AP_Vehicle/AP_Vehicle.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_Vehicle/AP_Vehicle.cpp b/libraries/AP_Vehicle/AP_Vehicle.cpp index 9908cf767d60fe..2833a39fc293b1 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.cpp +++ b/libraries/AP_Vehicle/AP_Vehicle.cpp @@ -850,6 +850,7 @@ void AP_Vehicle::reboot(bool hold_in_bootloader) #if OSD_ENABLED void AP_Vehicle::publish_osd_info() { +#if AP_MISSION_ENABLED AP_Mission *mission = AP::mission(); if (mission == nullptr) { return; @@ -872,6 +873,7 @@ void AP_Vehicle::publish_osd_info() } nav_info.wp_number = mission->get_current_nav_index(); osd->set_nav_info(nav_info); +#endif } #endif From 6d2c857db92a8bfc15f12a55e5fe8aaf51457489 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 9 Dec 2023 15:09:55 +1100 Subject: [PATCH 0369/1335] AP_Arming: correct compilation when AP_MISSION_ENABLED is false --- libraries/AP_Arming/AP_Arming.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index 6a8bae36ccb1f8..209dbdefe13118 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -1125,6 +1125,7 @@ bool AP_Arming::system_checks(bool report) bool AP_Arming::terrain_database_required() const { +#if AP_MISSION_ENABLED AP_Mission *mission = AP::mission(); if (mission == nullptr) { // no mission support? @@ -1133,6 +1134,7 @@ bool AP_Arming::terrain_database_required() const if (mission->contains_terrain_alt_items()) { return true; } +#endif return false; } From 78087da03ca3703d4b2e114e4013094e5e069395 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 9 Dec 2023 15:09:55 +1100 Subject: [PATCH 0370/1335] GCS_MAVLink: correct compilation when AP_MISSION_ENABLED is false --- libraries/GCS_MAVLink/GCS.h | 3 ++- libraries/GCS_MAVLink/GCS_Common.cpp | 10 +++++++++- libraries/GCS_MAVLink/GCS_config.h | 3 ++- 3 files changed, 13 insertions(+), 3 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index ccea42410f86ab..d477ea2977365f 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -643,9 +643,10 @@ class GCS_MAVLINK virtual MAV_RESULT _handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg); virtual MAV_RESULT _handle_command_preflight_calibration_baro(const mavlink_message_t &msg); +#if AP_MISSION_ENABLED virtual MAV_RESULT handle_command_do_set_mission_current(const mavlink_command_int_t &packet); MAV_RESULT handle_command_do_jump_tag(const mavlink_command_int_t &packet); - +#endif MAV_RESULT handle_command_battery_reset(const mavlink_command_int_t &packet); void handle_command_long(const mavlink_message_t &msg); MAV_RESULT handle_command_accelcal_vehicle_pos(const mavlink_command_int_t &packet); diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index f7ead3489f9830..9981cb5e594368 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -4497,6 +4497,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_run_prearm_checks(const mavlink_command_i return MAV_RESULT_ACCEPTED; } +#if AP_MISSION_ENABLED // changes the current waypoint; at time of writing GCS // implementations use the mavlink message MISSION_SET_CURRENT to set // the current waypoint, rather than this DO command. It is hoped we @@ -4555,6 +4556,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_jump_tag(const mavlink_command_int_t & return MAV_RESULT_ACCEPTED; } +#endif #if AP_BATTERY_ENABLED MAV_RESULT GCS_MAVLINK::handle_command_battery_reset(const mavlink_command_int_t &packet) @@ -5116,11 +5118,13 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p return handle_command_do_gripper(packet); #endif +#if AP_MISSION_ENABLED case MAV_CMD_DO_JUMP_TAG: return handle_command_do_jump_tag(packet); case MAV_CMD_DO_SET_MISSION_CURRENT: return handle_command_do_set_mission_current(packet); +#endif case MAV_CMD_DO_SET_MODE: return handle_command_do_set_mode(packet); @@ -5304,6 +5308,7 @@ void GCS::try_send_queued_message_for_type(MAV_MISSION_TYPE type) const { bool GCS_MAVLINK::try_send_mission_message(const enum ap_message id) { switch (id) { +#if AP_MISSION_ENABLED case MSG_CURRENT_WAYPOINT: { CHECK_PAYLOAD_SIZE(MISSION_CURRENT); @@ -5321,6 +5326,7 @@ bool GCS_MAVLINK::try_send_mission_message(const enum ap_message id) CHECK_PAYLOAD_SIZE(MISSION_REQUEST); gcs().try_send_queued_message_for_type(MAV_MISSION_TYPE_MISSION); break; +#endif #if HAL_RALLY_ENABLED case MSG_NEXT_MISSION_REQUEST_RALLY: CHECK_PAYLOAD_SIZE(MISSION_REQUEST); @@ -6721,11 +6727,13 @@ void GCS_MAVLINK::send_high_latency2() const const int8_t battery_remaining = battery_remaining_pct(AP_BATT_PRIMARY_INSTANCE); #endif - AP_Mission *mission = AP::mission(); uint16_t current_waypoint = 0; +#if AP_MISSION_ENABLED + AP_Mission *mission = AP::mission(); if (mission != nullptr) { current_waypoint = mission->get_current_nav_index(); } +#endif uint32_t present; uint32_t enabled; diff --git a/libraries/GCS_MAVLink/GCS_config.h b/libraries/GCS_MAVLink/GCS_config.h index 7a9e38b51922f6..8960a881ab45cb 100644 --- a/libraries/GCS_MAVLink/GCS_config.h +++ b/libraries/GCS_MAVLink/GCS_config.h @@ -2,6 +2,7 @@ #include #include +#include #ifndef HAL_GCS_ENABLED #define HAL_GCS_ENABLED 1 @@ -25,7 +26,7 @@ // The command was added to the spec in January 2019 and to MAVLink in // ArduPilot in 4.1.x #ifndef AP_MAVLINK_MISSION_SET_CURRENT_ENABLED -#define AP_MAVLINK_MISSION_SET_CURRENT_ENABLED 1 +#define AP_MAVLINK_MISSION_SET_CURRENT_ENABLED AP_MISSION_ENABLED #endif // AUTOPILOT_VERSION_REQUEST is slated to be removed; an instance of From eec43c204f5fceca169c6e4a0f09a65746e7ebec Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 12 Jul 2023 15:40:32 +1000 Subject: [PATCH 0371/1335] AP_Compass: cope with AP_INERTIAL_SENSOR being 0 --- libraries/AP_Compass/AP_Compass_HMC5843.cpp | 6 ++++-- libraries/AP_Compass/AP_Compass_HMC5843.h | 5 +++++ 2 files changed, 9 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Compass/AP_Compass_HMC5843.cpp b/libraries/AP_Compass/AP_Compass_HMC5843.cpp index a9c3d4b10c1e67..6c8f91764598bc 100644 --- a/libraries/AP_Compass/AP_Compass_HMC5843.cpp +++ b/libraries/AP_Compass/AP_Compass_HMC5843.cpp @@ -126,6 +126,7 @@ AP_Compass_Backend *AP_Compass_HMC5843::probe(AP_HAL::OwnPtr dev return sensor; } +#if AP_INERTIALSENSOR_ENABLED AP_Compass_Backend *AP_Compass_HMC5843::probe_mpu6000(enum Rotation rotation) { AP_InertialSensor &ins = *AP_InertialSensor::get_singleton(); @@ -145,6 +146,7 @@ AP_Compass_Backend *AP_Compass_HMC5843::probe_mpu6000(enum Rotation rotation) return sensor; } +#endif bool AP_Compass_HMC5843::init() { @@ -488,6 +490,7 @@ AP_HAL::Device::PeriodicHandle AP_HMC5843_BusDriver_HALDevice::register_periodic } +#if AP_INERTIALSENSOR_ENABLED /* HMC5843 on an auxiliary bus of IMU driver */ AP_HMC5843_BusDriver_Auxiliary::AP_HMC5843_BusDriver_Auxiliary(AP_InertialSensor &ins, uint8_t backend_id, uint8_t addr) @@ -496,14 +499,12 @@ AP_HMC5843_BusDriver_Auxiliary::AP_HMC5843_BusDriver_Auxiliary(AP_InertialSensor * Only initialize members. Fails are handled by configure or while * getting the semaphore */ -#if AP_INERTIALSENSOR_ENABLED _bus = ins.get_auxiliary_bus(backend_id); if (!_bus) { return; } _slave = _bus->request_next_slave(addr); -#endif } AP_HMC5843_BusDriver_Auxiliary::~AP_HMC5843_BusDriver_Auxiliary() @@ -585,5 +586,6 @@ uint32_t AP_HMC5843_BusDriver_Auxiliary::get_bus_id(void) const { return _bus->get_bus_id(); } +#endif // AP_INERTIALSENSOR_ENABLED #endif // AP_COMPASS_HMC5843_ENABLED diff --git a/libraries/AP_Compass/AP_Compass_HMC5843.h b/libraries/AP_Compass/AP_Compass_HMC5843.h index e3427c2d3d529a..a2750c6ceffff2 100644 --- a/libraries/AP_Compass/AP_Compass_HMC5843.h +++ b/libraries/AP_Compass/AP_Compass_HMC5843.h @@ -13,6 +13,7 @@ #include #include "AP_Compass_Backend.h" +#include class AuxiliaryBus; class AuxiliaryBusSlave; @@ -26,7 +27,9 @@ class AP_Compass_HMC5843 : public AP_Compass_Backend bool force_external, enum Rotation rotation); +#if AP_INERTIALSENSOR_ENABLED static AP_Compass_Backend *probe_mpu6000(enum Rotation rotation); +#endif static constexpr const char *name = "HMC5843"; @@ -124,6 +127,7 @@ class AP_HMC5843_BusDriver_HALDevice : public AP_HMC5843_BusDriver AP_HAL::OwnPtr _dev; }; +#if AP_INERTIALSENSOR_ENABLED class AP_HMC5843_BusDriver_Auxiliary : public AP_HMC5843_BusDriver { public: @@ -153,5 +157,6 @@ class AP_HMC5843_BusDriver_Auxiliary : public AP_HMC5843_BusDriver AuxiliaryBusSlave *_slave; bool _started; }; +#endif // AP_INERTIALSENSOR_ENABLED #endif // AP_COMPASS_HMC5843_ENABLED From 1e410301675bd2bc3ea1d9011fd9962777fba28a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 12 Jul 2023 15:40:32 +1000 Subject: [PATCH 0372/1335] AP_AHRS: cope with AP_INERTIAL_SENSOR being 0 --- libraries/AP_AHRS/AP_AHRS_Backend.h | 8 ++++++++ libraries/AP_AHRS/AP_AHRS_config.h | 4 ++-- 2 files changed, 10 insertions(+), 2 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS_Backend.h b/libraries/AP_AHRS/AP_AHRS_Backend.h index 0fb02eae9b2761..ae71df9c0a0124 100644 --- a/libraries/AP_AHRS/AP_AHRS_Backend.h +++ b/libraries/AP_AHRS/AP_AHRS_Backend.h @@ -76,12 +76,20 @@ class AP_AHRS_Backend // get the index of the current primary accelerometer sensor virtual uint8_t get_primary_accel_index(void) const { +#if AP_INERTIALSENSOR_ENABLED return AP::ins().get_primary_accel(); +#else + return 0; +#endif } // get the index of the current primary gyro sensor virtual uint8_t get_primary_gyro_index(void) const { +#if AP_INERTIALSENSOR_ENABLED return AP::ins().get_primary_gyro(); +#else + return 0; +#endif } // Methods diff --git a/libraries/AP_AHRS/AP_AHRS_config.h b/libraries/AP_AHRS/AP_AHRS_config.h index 559d0403b0566e..7338a02787a875 100644 --- a/libraries/AP_AHRS/AP_AHRS_config.h +++ b/libraries/AP_AHRS/AP_AHRS_config.h @@ -21,11 +21,11 @@ #endif #ifndef HAL_NAVEKF3_AVAILABLE -#define HAL_NAVEKF3_AVAILABLE 1 +#define HAL_NAVEKF3_AVAILABLE AP_INERTIALSENSOR_ENABLED #endif #ifndef AP_AHRS_SIM_ENABLED -#define AP_AHRS_SIM_ENABLED AP_SIM_ENABLED +#define AP_AHRS_SIM_ENABLED AP_SIM_ENABLED && AP_INERTIALSENSOR_ENABLED #endif #ifndef AP_AHRS_POSITION_RESET_ENABLED From f4d51fd8f5867b06daf6dc7035d4d445fee534c1 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 12 Jul 2023 16:23:58 +1000 Subject: [PATCH 0373/1335] AP_OpticalFlow: cope if AP_AHRS_ENABLED is 0 --- libraries/AP_OpticalFlow/AP_OpticalFlow.cpp | 2 ++ libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.cpp | 4 ++++ 2 files changed, 6 insertions(+) diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp index 137a5778b55c8f..be86676d59ac56 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp @@ -267,6 +267,7 @@ void AP_OpticalFlow::update_state(const OpticalFlow_state &state) _state = state; _last_update_ms = AP_HAL::millis(); +#if AP_AHRS_ENABLED // write to log and send to EKF if new data has arrived AP::ahrs().writeOptFlowMeas(quality(), _state.flowRate, @@ -274,6 +275,7 @@ void AP_OpticalFlow::update_state(const OpticalFlow_state &state) _last_update_ms, get_pos_offset(), get_height_override()); +#endif #if HAL_LOGGING_ENABLED Log_Write_Optflow(); #endif diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.cpp index 1095e44227293b..5a976c8a3eb2f4 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_Pixart.cpp @@ -287,7 +287,11 @@ void AP_OpticalFlow_Pixart::timer(void) uint32_t dt_us = last_burst_us - integral.last_frame_us; float dt = dt_us * 1.0e-6; +#if AP_AHRS_ENABLED const Vector3f &gyro = AP::ahrs().get_gyro(); +#else + const Vector3f &gyro = AP::ins().get_gyro(); +#endif { WITH_SEMAPHORE(_sem); From dd0a7a551ba3e4d0834a2e60c4b1aa203fb783a6 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 3 Jan 2024 11:41:04 +1100 Subject: [PATCH 0374/1335] AP_AHRS: do not compile AP_AHRS.cpp if AP_AHRS_ENABLED is 0 on Periph we end up not having a default backend, which is a compilation failure --- libraries/AP_AHRS/AP_AHRS.cpp | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index 61255e7b060533..93591c20263eaa 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -18,6 +18,11 @@ * ArduPilot * */ + +#include "AP_AHRS_config.h" + +#if AP_AHRS_ENABLED + #include #include "AP_AHRS.h" #include "AP_AHRS_View.h" @@ -3544,3 +3549,5 @@ AP_AHRS &ahrs() } } + +#endif // AP_AHRS_ENABLED From 24f7ff7b61d8c3a24e912aa044a2467545cf9454 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 3 Jan 2024 13:24:13 +1100 Subject: [PATCH 0375/1335] autotest: Use contexts to control script lifetimes in networking tests this way if the test gets an exception part-way through the scripts are removed from the directories appropriately --- Tools/autotest/rover.py | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index eb398452bf0fc9..8fbf383e10ee41 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -6646,7 +6646,8 @@ def NetworkingWebServer(self): '''web server''' applet_script = "net_webserver.lua" - self.install_applet_script(applet_script) + self.context_push() + self.install_applet_script_context(applet_script) self.set_parameters({ "SCR_ENABLE": 1, @@ -6672,14 +6673,15 @@ def NetworkingWebServer(self): self.TestWebServer("http://127.0.0.1:8081") self.context_pop() - self.remove_installed_script(applet_script) + self.context_pop() self.reboot_sitl() def NetworkingWebServerPPP(self): '''web server over PPP''' applet_script = "net_webserver.lua" - self.install_applet_script(applet_script) + self.context_push() + self.install_applet_script_context(applet_script) self.set_parameters({ "SCR_ENABLE": 1, @@ -6718,7 +6720,7 @@ def NetworkingWebServerPPP(self): self.TestWebServer("http://192.168.14.13:8081") self.context_pop() - self.remove_installed_script(applet_script) + self.context_pop() # restore rover without ppp enabled for next test os.unlink('build/sitl/bin/ardurover') From ed1ae3b5f1c8bce6fb16192f384ca05ed1d60b51 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 25 May 2023 11:27:45 +1000 Subject: [PATCH 0376/1335] chibios_hwdef.py: add quiet option to remove parsing debug output --- .../hwdef/scripts/chibios_hwdef.py | 51 +++++++++++-------- .../hwdef/scripts/dma_resolver.py | 5 +- 2 files changed, 33 insertions(+), 23 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index 751ca37fc4f35f..bac4ff41e34dc6 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -25,12 +25,13 @@ class ChibiOSHWDef(object): f1_vtypes = ['CRL', 'CRH', 'ODR'] af_labels = ['USART', 'UART', 'SPI', 'I2C', 'SDIO', 'SDMMC', 'OTG', 'JT', 'TIM', 'CAN', 'QUADSPI', 'OCTOSPI', 'ETH', 'MCO'] - def __init__(self, bootloader=False, signed_fw=False, outdir=None, hwdef=[], default_params_filepath=None): + def __init__(self, quiet=False, bootloader=False, signed_fw=False, outdir=None, hwdef=[], default_params_filepath=None): self.outdir = outdir self.hwdef = hwdef self.bootloader = bootloader self.signed_fw = signed_fw self.default_params_filepath = default_params_filepath + self.quiet = quiet self.default_gpio = ['INPUT', 'FLOATING'] @@ -771,7 +772,7 @@ def get_ram_map(self): if ram_map is not None: return ram_map elif int(self.env_vars.get('USE_ALT_RAM_MAP', 0)) == 1: - print("Using ALT_RAM_MAP") + self.progress("Using ALT_RAM_MAP") return self.get_mcu_config('ALT_RAM_MAP', True) return self.get_mcu_config('RAM_MAP', True) @@ -1037,7 +1038,6 @@ def write_mcu_config(self, f): if define == 'AP_NETWORKING_ENABLED' and value == 1: self.enable_networking(f) - if self.intdefines.get('HAL_USE_USB_MSD', 0) == 1: self.build_flags.append('USE_USB_MSD=yes') @@ -1163,7 +1163,7 @@ def write_mcu_config(self, f): cortex = self.get_mcu_config('CORTEX') self.env_vars['CPU_FLAGS'] = self.get_mcu_config('CPU_FLAGS').split() build_info['MCU'] = cortex - print("MCU Flags: %s %s" % (cortex, self.env_vars['CPU_FLAGS'])) + self.progress("MCU Flags: %s %s" % (cortex, self.env_vars['CPU_FLAGS'])) elif self.mcu_series.startswith("STM32F1"): cortex = "cortex-m3" self.env_vars['CPU_FLAGS'] = ["-mcpu=%s" % cortex] @@ -1381,7 +1381,7 @@ def write_ldscript(self, fname): self.env_vars['FLASH_TOTAL'] = flash_length * 1024 - print("Generating ldscript.ld") + self.progress("Generating ldscript.ld") f = open(fname, 'w') ram0_start = ram_map[0][0] ram0_len = ram_map[0][1] * 1024 @@ -1555,7 +1555,7 @@ def write_WSPI_table(self, f): devlist = [] for dev in self.wspidev: if len(dev) != 6: - print("Badly formed WSPIDEV line %s" % dev) + self.progress("Badly formed WSPIDEV line %s" % dev) name = '"' + dev[0] + '"' bus = dev[1] mode = dev[2] @@ -1596,7 +1596,7 @@ def write_WSPI_config(self, f): return for t in list(self.bytype.keys()) + list(self.alttype.keys()): - print(t) + self.progress(t) if t.startswith('QUADSPI') or t.startswith('OCTOSPI'): self.wspi_list.append(t) @@ -1999,7 +1999,7 @@ def write_UART_config_bootloader(self, f): def write_I2C_config(self, f): '''write I2C config defines''' if not self.have_type_prefix('I2C'): - print("No I2C peripherals") + self.progress("No I2C peripherals") f.write(''' #ifndef HAL_USE_I2C #define HAL_USE_I2C FALSE @@ -2076,7 +2076,7 @@ def write_PWM_config(self, f, ordered_timers): f.write('#define HAL_PWM_COUNT %u\n' % len(pwm_out)) if not pwm_out and not alarm: - print("No PWM output defined") + self.progress("No PWM output defined") f.write(''' #ifndef HAL_USE_PWM #define HAL_USE_PWM FALSE @@ -2527,7 +2527,7 @@ def write_all_lines(self, hwdat): def write_hwdef_header(self, outfilename): '''write hwdef header file''' - print("Writing hwdef setup in %s" % outfilename) + self.progress("Writing hwdef setup in %s" % outfilename) tmpfile = outfilename + ".tmp" f = open(tmpfile, 'w') @@ -2600,7 +2600,8 @@ def write_hwdef_header(self, outfilename): self.mcu_type, dma_exclude=self.get_dma_exclude(self.periph_list), dma_priority=self.get_config('DMA_PRIORITY', default='TIM* SPI*', spaces=True), - dma_noshare=self.dma_noshare + dma_noshare=self.dma_noshare, + quiet=self.quiet, ) if not self.is_bootloader_fw(): @@ -2720,7 +2721,7 @@ def write_hwdef_header(self, outfilename): # see if we ended up with the same file, on an unnecessary reconfigure try: if filecmp.cmp(outfilename, tmpfile): - print("No change in hwdef.h") + self.progress("No change in hwdef.h") os.unlink(tmpfile) return except Exception: @@ -2824,13 +2825,13 @@ def write_processed_defaults_file(self, filepath): defaults_abspath = None if os.path.exists(defaults_path): defaults_abspath = os.path.abspath(self.default_params_filepath) - print("Default parameters path from command line: %s" % self.default_params_filepath) + self.progress("Default parameters path from command line: %s" % self.default_params_filepath) elif os.path.exists(defaults_filename): defaults_abspath = os.path.abspath(defaults_filename) - print("Default parameters path from hwdef: %s" % defaults_filename) + self.progress("Default parameters path from hwdef: %s" % defaults_filename) if defaults_abspath is None: - print("No default parameter file found") + self.progress("No default parameter file found") return content = self.get_processed_defaults_file(defaults_abspath) @@ -3002,7 +3003,7 @@ def process_line(self, line): self.romfs_wildcard(a[1]) elif a[0] == 'undef': for u in a[1:]: - print("Removing %s" % u) + self.progress("Removing %s" % u) self.config.pop(u, '') self.bytype.pop(u, '') self.bylabel.pop(u, '') @@ -3034,7 +3035,7 @@ def process_line(self, line): if u == 'AIRSPEED': self.airspeed_list = [] elif a[0] == 'env': - print("Adding environment %s" % ' '.join(a[1:])) + self.progress("Adding environment %s" % ' '.join(a[1:])) if len(a[1:]) < 2: self.error("Bad env line for %s" % a[0]) name = a[1] @@ -3045,6 +3046,11 @@ def process_line(self, line): value = int(value, 0) self.env_vars[name] = value + def progress(self, message): + if self.quiet: + return + print(message) + def process_file(self, filename): '''process a hwdef.dat file''' try: @@ -3063,7 +3069,7 @@ def process_file(self, filename): dir = os.path.dirname(filename) include_file = os.path.normpath( os.path.join(dir, include_file)) - print("Including %s" % include_file) + self.progress("Including %s" % include_file) self.process_file(include_file) else: self.process_line(line) @@ -3087,7 +3093,7 @@ def add_bootloader_defaults(self, f): self.add_firmware_defaults_from_file(f, "defaults_bootloader.h", "bootloader") def add_firmware_defaults_from_file(self, f, filename, description): - print("Setting up as %s" % description) + self.progress("Setting up as %s" % description) dirpath = os.path.dirname(os.path.realpath(__file__)) filepath = os.path.join(dirpath, filename) @@ -3144,7 +3150,7 @@ def run(self): self.error("Missing MCU type in config") self.mcu_type = self.get_config('MCU', 1) - print("Setup for MCU %s" % self.mcu_type) + self.progress("Setup for MCU %s" % self.mcu_type) # build a list for peripherals for DMA resolver self.periph_list = self.build_peripheral_list() @@ -3186,6 +3192,8 @@ def run(self): 'hwdef', type=str, nargs='+', default=None, help='hardware definition file') parser.add_argument( '--params', type=str, default=None, help='user default params path') + parser.add_argument( + '--quiet', action='store_true', default=False, help='quiet running') args = parser.parse_args() @@ -3194,6 +3202,7 @@ def run(self): bootloader=args.bootloader, signed_fw=args.signed_fw, hwdef=args.hwdef, - default_params_filepath=args.params + default_params_filepath=args.params, + quiet=args.quiet, ) c.run() diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/dma_resolver.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/dma_resolver.py index 4f78382deb3c56..96a3673148afe9 100755 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/dma_resolver.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/dma_resolver.py @@ -293,7 +293,7 @@ def forbidden_list(p, peripheral_list): def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[], - dma_priority='', dma_noshare=[]): + dma_priority='', dma_noshare=[], quiet=False): '''write out a DMA resolver header file''' global dma_map, have_DMAMUX, has_bdshot timer_ch_periph = [] @@ -331,7 +331,8 @@ def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[], dma_map = generate_DMAMUX_map(peripheral_list, noshare_list, dma_exclude, stream_ofs) - print("Writing DMA map") + if not quiet: + print("Writing DMA map") unassigned = [] curr_dict = {} From 8fb1f6f02c0ee03a9203c8152185142222e1ff53 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 3 Jan 2024 11:59:44 +1100 Subject: [PATCH 0377/1335] AP_Camera: correct compilation when AP_CAMERA_RELAY_ENABLED is 0 ... like on skyviper-v2450 --- libraries/AP_Camera/AP_Camera.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_Camera/AP_Camera.cpp b/libraries/AP_Camera/AP_Camera.cpp index 76f3524e22e2b0..d16d29e441e89a 100644 --- a/libraries/AP_Camera/AP_Camera.cpp +++ b/libraries/AP_Camera/AP_Camera.cpp @@ -781,11 +781,13 @@ bool AP_Camera::get_legacy_relay_index(int8_t &index) const // Copter, Plane, Sub and Rover all have both relay and camera and all init relay first // This will only be a issue if the relay and camera conversion were done at once, if the user skipped 4.4 for (uint8_t i = 0; i < AP_CAMERA_MAX_INSTANCES; i++) { +#if AP_CAMERA_RELAY_ENABLED if ((CameraType)_params[i].type.get() == CameraType::RELAY) { // Camera was hard coded to relay 0 index = 0; return true; } +#endif } return false; } From b43f4f78a3bb5757abf2330f34047a7846d625c0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 14 Sep 2023 21:05:59 +1000 Subject: [PATCH 0378/1335] SITL: add missing includes for SITL object --- libraries/SITL/SIM_JSON_Master.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/SITL/SIM_JSON_Master.cpp b/libraries/SITL/SIM_JSON_Master.cpp index 835dae013644b5..885e469564c168 100644 --- a/libraries/SITL/SIM_JSON_Master.cpp +++ b/libraries/SITL/SIM_JSON_Master.cpp @@ -22,6 +22,8 @@ #include #include +#include +#include using namespace SITL; From c22794d0788625b1503ff5dd8ab99c0d04fb1596 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 14 Sep 2023 21:22:45 +1000 Subject: [PATCH 0379/1335] AP_Periph: add missing SITL includes these are required for compilation when other things are introduced --- Tools/AP_Periph/AP_Periph.h | 3 +++ Tools/AP_Periph/hwing_esc.cpp | 2 ++ 2 files changed, 5 insertions(+) diff --git a/Tools/AP_Periph/AP_Periph.h b/Tools/AP_Periph/AP_Periph.h index 97c89cdd3b5b24..a025883ad7347c 100644 --- a/Tools/AP_Periph/AP_Periph.h +++ b/Tools/AP_Periph/AP_Periph.h @@ -37,6 +37,9 @@ #include "batt_balance.h" #include "networking.h" #include "serial_options.h" +#if AP_SIM_ENABLED +#include +#endif #include #if HAL_NMEA_OUTPUT_ENABLED && !(HAL_GCS_ENABLED && defined(HAL_PERIPH_ENABLE_GPS)) diff --git a/Tools/AP_Periph/hwing_esc.cpp b/Tools/AP_Periph/hwing_esc.cpp index 871c2e0517c45f..a1e2d4a4721078 100644 --- a/Tools/AP_Periph/hwing_esc.cpp +++ b/Tools/AP_Periph/hwing_esc.cpp @@ -14,6 +14,8 @@ #ifdef HAL_PERIPH_ENABLE_HWESC +#include + extern const AP_HAL::HAL& hal; #define TELEM_HEADER 0x9B From 3ed8a434cef8859770fa84a687392ba65e5365b6 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 14 Sep 2023 21:05:58 +1000 Subject: [PATCH 0380/1335] AP_AHRS: add missing SITL header include the singleton is used in this file --- libraries/AP_AHRS/AP_AHRS.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index 93591c20263eaa..d0985bd80315bd 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -39,6 +39,9 @@ #include #include #include +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#include +#endif #define ATTITUDE_CHECK_THRESH_ROLL_PITCH_RAD radians(10) #define ATTITUDE_CHECK_THRESH_YAW_RAD radians(20) From 68d8a2606d26d1dfb13f7834585990328f837cca Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 1 Aug 2023 07:32:58 +1000 Subject: [PATCH 0381/1335] AP_InertialSensor: SITL: call logging singleton methods only if available --- libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp index 583ad75a42a953..d72014fde4acc1 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp @@ -426,10 +426,12 @@ void AP_InertialSensor_SITL::read_gyro_from_file() if (ret <= 0) { if (sitl->gyro_file_rw == SITL::SIM::INSFileMode::INS_FILE_READ_STOP_ON_EOF) { +#if HAL_LOGGING_ENABLED //stop logging if (AP_Logger::get_singleton()) { AP::logger().StopLogging(); } +#endif exit(0); } lseek(gyro_fd, 0, SEEK_SET); @@ -492,10 +494,12 @@ void AP_InertialSensor_SITL::read_accel_from_file() if (ret <= 0) { if (sitl->accel_file_rw == SITL::SIM::INSFileMode::INS_FILE_READ_STOP_ON_EOF) { +#if HAL_LOGGING_ENABLED //stop logging if (AP_Logger::get_singleton()) { AP::logger().StopLogging(); } +#endif exit(0); } lseek(accel_fd, 0, SEEK_SET); From 6fe7a1408ec158fc194716d4c2ae4d995e30f0a3 Mon Sep 17 00:00:00 2001 From: jamming Date: Tue, 19 Dec 2023 10:19:22 +0800 Subject: [PATCH 0382/1335] hwdef: Add support for BMI088 on Pixhawk6c --- libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat index a4b8e930d0f682..4677c93b2ab37a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6C/hwdef.dat @@ -239,6 +239,9 @@ SPIDEV ramtron SPI2 DEVID1 FRAM_CS MODE3 8*MHZ 8*MHZ # 2 IMUs IMU Invensensev3 SPI:icm42688 ROTATION_PITCH_180_YAW_90 IMU BMI055 SPI:bmi055_a SPI:bmi055_g ROTATION_PITCH_180 +# BMI055 is replaced by BMI088 on the lastest hardware revision +# They use the same CPU signal pins +IMU BMI088 SPI:bmi055_a SPI:bmi055_g ROTATION_PITCH_180 define HAL_DEFAULT_INS_FAST_SAMPLE 3 From f9fdd152ee8fc62aa76b582b9788844863527186 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Wed, 3 Jan 2024 12:36:16 -0700 Subject: [PATCH 0383/1335] AP_Relay: allow hwdef to provide more then 6 relays --- libraries/AP_Relay/AP_Relay.cpp | 72 +++++++++++++++++++++++++++++++++ libraries/AP_Relay/AP_Relay.h | 8 +++- 2 files changed, 79 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Relay/AP_Relay.cpp b/libraries/AP_Relay/AP_Relay.cpp index 921163fbd6262f..e16d0248c20fe8 100644 --- a/libraries/AP_Relay/AP_Relay.cpp +++ b/libraries/AP_Relay/AP_Relay.cpp @@ -81,25 +81,95 @@ const AP_Param::GroupInfo AP_Relay::var_info[] = { // @Path: AP_Relay_Params.cpp AP_SUBGROUPINFO(_params[0], "1_", 7, AP_Relay, AP_Relay_Params), +#if AP_RELAY_NUM_RELAYS > 1 // @Group: 2_ // @Path: AP_Relay_Params.cpp AP_SUBGROUPINFO(_params[1], "2_", 8, AP_Relay, AP_Relay_Params), +#endif +#if AP_RELAY_NUM_RELAYS > 2 // @Group: 3_ // @Path: AP_Relay_Params.cpp AP_SUBGROUPINFO(_params[2], "3_", 9, AP_Relay, AP_Relay_Params), +#endif +#if AP_RELAY_NUM_RELAYS > 3 // @Group: 4_ // @Path: AP_Relay_Params.cpp AP_SUBGROUPINFO(_params[3], "4_", 10, AP_Relay, AP_Relay_Params), +#endif +#if AP_RELAY_NUM_RELAYS > 4 // @Group: 5_ // @Path: AP_Relay_Params.cpp AP_SUBGROUPINFO(_params[4], "5_", 11, AP_Relay, AP_Relay_Params), +#endif +#if AP_RELAY_NUM_RELAYS > 5 // @Group: 6_ // @Path: AP_Relay_Params.cpp AP_SUBGROUPINFO(_params[5], "6_", 12, AP_Relay, AP_Relay_Params), +#endif + +#if AP_RELAY_NUM_RELAYS > 6 + // @Group: 7_ + // @Path: AP_Relay_Params.cpp + AP_SUBGROUPINFO(_params[6], "7_", 13, AP_Relay, AP_Relay_Params), +#endif + +#if AP_RELAY_NUM_RELAYS > 7 + // @Group: 8_ + // @Path: AP_Relay_Params.cpp + AP_SUBGROUPINFO(_params[7], "8_", 14, AP_Relay, AP_Relay_Params), +#endif + +#if AP_RELAY_NUM_RELAYS > 8 + // @Group: 9_ + // @Path: AP_Relay_Params.cpp + AP_SUBGROUPINFO(_params[8], "9_", 15, AP_Relay, AP_Relay_Params), +#endif + +#if AP_RELAY_NUM_RELAYS > 9 + // @Group: 10_ + // @Path: AP_Relay_Params.cpp + AP_SUBGROUPINFO(_params[9], "10_", 16, AP_Relay, AP_Relay_Params), +#endif + +#if AP_RELAY_NUM_RELAYS > 10 + // @Group: 11_ + // @Path: AP_Relay_Params.cpp + AP_SUBGROUPINFO(_params[10], "11_", 17, AP_Relay, AP_Relay_Params), +#endif + +#if AP_RELAY_NUM_RELAYS > 11 + // @Group: 12_ + // @Path: AP_Relay_Params.cpp + AP_SUBGROUPINFO(_params[11], "12_", 18, AP_Relay, AP_Relay_Params), +#endif + +#if AP_RELAY_NUM_RELAYS > 12 + // @Group: 13_ + // @Path: AP_Relay_Params.cpp + AP_SUBGROUPINFO(_params[12], "13_", 19, AP_Relay, AP_Relay_Params), +#endif + +#if AP_RELAY_NUM_RELAYS > 13 + // @Group: 14_ + // @Path: AP_Relay_Params.cpp + AP_SUBGROUPINFO(_params[13], "14_", 20, AP_Relay, AP_Relay_Params), +#endif + +#if AP_RELAY_NUM_RELAYS > 14 + // @Group: 15_ + // @Path: AP_Relay_Params.cpp + AP_SUBGROUPINFO(_params[14], "15_", 21, AP_Relay, AP_Relay_Params), +#endif + +#if AP_RELAY_NUM_RELAYS > 15 + // @Group: 16_ + // @Path: AP_Relay_Params.cpp + AP_SUBGROUPINFO(_params[15], "16_", 22, AP_Relay, AP_Relay_Params), +#endif AP_GROUPEND }; @@ -402,6 +472,8 @@ bool AP_Relay::enabled(AP_Relay_Params::FUNCTION function) const // supplied link for the message. bool AP_Relay::send_relay_status(const GCS_MAVLINK &link) const { + static_assert(AP_RELAY_NUM_RELAYS <= 16, "Too many relays for MAVLink status reporting to work."); + if (!HAVE_PAYLOAD_SPACE(link.get_chan(), RELAY_STATUS)) { return false; } diff --git a/libraries/AP_Relay/AP_Relay.h b/libraries/AP_Relay/AP_Relay.h index 51e08a4015a01d..d53bdb408c080b 100644 --- a/libraries/AP_Relay/AP_Relay.h +++ b/libraries/AP_Relay/AP_Relay.h @@ -17,7 +17,13 @@ #include #include -#define AP_RELAY_NUM_RELAYS 6 +#ifndef AP_RELAY_NUM_RELAYS + #define AP_RELAY_NUM_RELAYS 6 +#endif + +#if AP_RELAY_NUM_RELAYS < 1 + #error There must be at least one relay instance if using AP_Relay +#endif /// @class AP_Relay /// @brief Class to manage the ArduPilot relay From 4765ba821840c3a5807ed110f0f62e230e39b8fc Mon Sep 17 00:00:00 2001 From: muramura Date: Wed, 3 Jan 2024 19:07:35 +0900 Subject: [PATCH 0384/1335] AP_InertialSensor: Specify the number of arrays by sizeof --- libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp index d72014fde4acc1..c6b994413a8bb9 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp @@ -409,7 +409,7 @@ void AP_InertialSensor_SITL::read_gyro_from_file() { if (gyro_fd == -1) { char namebuf[32]; - snprintf(namebuf, 32, "/tmp/gyro%d.dat", gyro_instance); + snprintf(namebuf, sizeof(namebuf), "/tmp/gyro%d.dat", gyro_instance); gyro_fd = AP::FS().open(namebuf, O_RDONLY); if (gyro_fd == -1) { AP_HAL::panic("gyro data file %s not found", namebuf); @@ -462,7 +462,7 @@ void AP_InertialSensor_SITL::write_gyro_to_file(const Vector3f& gyro) { if (gyro_fd == -1) { char namebuf[32]; - snprintf(namebuf, 32, "/tmp/gyro%d.dat", gyro_instance); + snprintf(namebuf, sizeof(namebuf), "/tmp/gyro%d.dat", gyro_instance); gyro_fd = open(namebuf, O_WRONLY|O_TRUNC|O_CREAT, S_IRWXU|S_IRGRP|S_IROTH); } @@ -477,7 +477,7 @@ void AP_InertialSensor_SITL::read_accel_from_file() { if (accel_fd == -1) { char namebuf[32]; - snprintf(namebuf, 32, "/tmp/accel%d.dat", accel_instance); + snprintf(namebuf, sizeof(namebuf), "/tmp/accel%d.dat", accel_instance); accel_fd = open(namebuf, O_RDONLY|O_CLOEXEC); if (accel_fd == -1) { AP_HAL::panic("accel data file %s not found", namebuf); @@ -534,7 +534,7 @@ void AP_InertialSensor_SITL::write_accel_to_file(const Vector3f& accel) if (accel_fd == -1) { char namebuf[32]; - snprintf(namebuf, 32, "/tmp/accel%d.dat", accel_instance); + snprintf(namebuf, sizeof(namebuf), "/tmp/accel%d.dat", accel_instance); accel_fd = open(namebuf, O_WRONLY|O_TRUNC|O_CREAT, S_IRWXU|S_IRGRP|S_IROTH); } From e55702fe3c90f5de2f84a0b305c2336588b63b3a Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Wed, 3 Jan 2024 07:12:12 -0600 Subject: [PATCH 0385/1335] AP_Camera:fix OPTIONS bitmask --- libraries/AP_Camera/AP_Camera_Backend.h | 3 +-- libraries/AP_Camera/AP_Camera_Params.cpp | 2 +- 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Camera/AP_Camera_Backend.h b/libraries/AP_Camera/AP_Camera_Backend.h index 067fa15a080eaa..a6b4c8a60a3200 100644 --- a/libraries/AP_Camera/AP_Camera_Backend.h +++ b/libraries/AP_Camera/AP_Camera_Backend.h @@ -37,8 +37,7 @@ class AP_Camera_Backend CLASS_NO_COPY(AP_Camera_Backend); enum CAMOPTIONS { - NONE = 0, - REC_ARM_DISARM = 1, // Recording start/stop on Arm/Disarm + REC_ARM_DISARM = 0, // Recording start/stop on Arm/Disarm }; // init - performs any required initialisation diff --git a/libraries/AP_Camera/AP_Camera_Params.cpp b/libraries/AP_Camera/AP_Camera_Params.cpp index 7b32ca60cf1bb8..7fb915082c991e 100644 --- a/libraries/AP_Camera/AP_Camera_Params.cpp +++ b/libraries/AP_Camera/AP_Camera_Params.cpp @@ -77,7 +77,7 @@ const AP_Param::GroupInfo AP_Camera_Params::var_info[] = { // @Param: _OPTIONS // @DisplayName: Camera options // @Description: Camera options bitmask - // @Bitmask: 0:None,1: Recording Starts at arming and stops at disarming + // @Bitmask: 0:Recording Starts at arming and stops at disarming // @User: Standard AP_GROUPINFO("_OPTIONS", 10, AP_Camera_Params, options, 0), From b1f1ea7859bf57aa2c81782c41dbe5866f5598f5 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 4 Jan 2024 08:46:59 +1100 Subject: [PATCH 0386/1335] AP_Networking: don't build lwip code if not needed this saves a bit of compile time, but also means devs not doing networking don't need to update the submodules --- libraries/AP_Networking/AP_Networking_Config.h | 2 ++ libraries/AP_Networking/lwip_hal/arch/sys_arch.cpp | 5 +++++ 2 files changed, 7 insertions(+) diff --git a/libraries/AP_Networking/AP_Networking_Config.h b/libraries/AP_Networking/AP_Networking_Config.h index ea77791a2b91b5..b9fdbd6fd3fb20 100644 --- a/libraries/AP_Networking/AP_Networking_Config.h +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -50,6 +50,8 @@ #define AP_NETWORKING_SOCKETS_ENABLED AP_NETWORKING_ENABLED #endif +#define AP_NETWORKING_NEED_LWIP (AP_NETWORKING_BACKEND_CHIBIOS || AP_NETWORKING_BACKEND_PPP) + // --------------------------- // IP Features // --------------------------- diff --git a/libraries/AP_Networking/lwip_hal/arch/sys_arch.cpp b/libraries/AP_Networking/lwip_hal/arch/sys_arch.cpp index d9b517b47fbf54..83053a9ee2629e 100644 --- a/libraries/AP_Networking/lwip_hal/arch/sys_arch.cpp +++ b/libraries/AP_Networking/lwip_hal/arch/sys_arch.cpp @@ -4,6 +4,9 @@ */ #include +#include + +#if AP_NETWORKING_NEED_LWIP #include #include @@ -385,3 +388,5 @@ sys_arch_unprotect(sys_prot_t pval) } } +#endif // AP_NETWORKING_NEED_LWIP + From c557e67aff87df7398cfb9d6c53a7db9b93b0d32 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 25 May 2023 11:28:19 +1000 Subject: [PATCH 0387/1335] chibios_hwdef.py: populate intdefines as part of parsing, not output --- .../hwdef/scripts/chibios_hwdef.py | 17 +++++++++-------- 1 file changed, 9 insertions(+), 8 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index bac4ff41e34dc6..7f248d2d358efe 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -1029,14 +1029,9 @@ def write_mcu_config(self, f): if 'HAL_USE_CAN' in d: using_chibios_can = True f.write('#define %s\n' % d[7:]) - # extract numerical defines for processing by other parts of the script - result = re.match(r'define\s*([A-Z_]+)\s*([0-9]+)', d) - if result: - define = result.group(1) - value = int(result.group(2)) - self.intdefines[define] = value - if define == 'AP_NETWORKING_ENABLED' and value == 1: - self.enable_networking(f) + + if self.intdefines.get('AP_NETWORKING_ENABLED', 0) == 1: + self.enable_networking(f) if self.intdefines.get('HAL_USE_USB_MSD', 0) == 1: self.build_flags.append('USE_USB_MSD=yes') @@ -3045,6 +3040,12 @@ def process_line(self, line): if name == 'APP_RAM_START': value = int(value, 0) self.env_vars[name] = value + elif a[0] == 'define': + # extract numerical defines for processing by other parts of the script + result = re.match(r'define\s*([A-Z_]+)\s*([0-9]+)', line) + if result: + self.intdefines[result.group(1)] = int(result.group(2)) + def progress(self, message): if self.quiet: From 82fe13bc003b20c3a97b6028c84a3b767cde4091 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 4 Jan 2024 11:58:42 +1100 Subject: [PATCH 0388/1335] AP_Generator: correct compilation if GCS_SEND_TEXT not available --- libraries/AP_Generator/AP_Generator_IE_2400.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Generator/AP_Generator_IE_2400.cpp b/libraries/AP_Generator/AP_Generator_IE_2400.cpp index 84d6a497bfe35a..85ef02dee5bf20 100644 --- a/libraries/AP_Generator/AP_Generator_IE_2400.cpp +++ b/libraries/AP_Generator/AP_Generator_IE_2400.cpp @@ -90,7 +90,7 @@ void AP_Generator_IE_2400::assign_measurements(const uint32_t now) // If received 20 valid packets for a single protocol version then lock on if (_last_version_packet_count > 20) { _version = new_version; - gcs().send_text(MAV_SEVERITY_INFO, "Generator: IE using %s protocol", (_version == ProtocolVersion::V2) ? "V2" : "legacy" ); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Generator: IE using %s protocol", (_version == ProtocolVersion::V2) ? "V2" : "legacy" ); } else { // Don't record any data during version detection From c443d19ab11ff74c11b261784a01be05d2302890 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 4 Jan 2024 12:00:06 +1100 Subject: [PATCH 0389/1335] AP_Mount: correct compilation when GCS_SEND_TEXT not available --- libraries/AP_Mount/AP_Mount_Siyi.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_Mount/AP_Mount_Siyi.cpp b/libraries/AP_Mount/AP_Mount_Siyi.cpp index 0cdc907f9dee8d..5cc1330bfb7670 100644 --- a/libraries/AP_Mount/AP_Mount_Siyi.cpp +++ b/libraries/AP_Mount/AP_Mount_Siyi.cpp @@ -479,6 +479,8 @@ void AP_Mount_Siyi::process_packet() sev = MAV_SEVERITY_WARNING; break; } + (void)msg; // in case GCS_SEND_TEXT not available + (void)sev; // in case GCS_SEND_TEXT not available GCS_SEND_TEXT(sev, "Siyi: recording %s", msg); } From 18adc77979dfb5d30a38f1774d74434eb9ea7b26 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 4 Jan 2024 15:41:11 +1100 Subject: [PATCH 0390/1335] autotest: add flight test for OpticalFlow --- Tools/autotest/arducopter.py | 75 +++++++++++++++++++++++++++++++++++- 1 file changed, 73 insertions(+), 2 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 991f088098d9c5..fac5a81f1c09c3 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -2160,8 +2160,10 @@ def configure_EKFs_to_use_optical_flow_instead_of_GPS(self): "EK3_SRC1_VELZ": 0, }) - def OpticalFlow(self): - '''test optical flow works''' + def OpticalFlowLocation(self): + '''test optical flow doesn't supply location''' + + self.context_push() self.assert_sensor_state(mavutil.mavlink.MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW, False, False, False, verbose=True) @@ -2179,6 +2181,65 @@ def OpticalFlow(self): self.delay_sim_time(5) self.wait_statustext("Need Position Estimate", timeout=300) + self.context_pop() + + self.reboot_sitl() + + def OpticalFlow(self): + '''test OpticalFlow in flight''' + self.start_subtest("Make sure no crash if no rangefinder") + + self.context_push() + + self.set_parameter("SIM_FLOW_ENABLE", 1) + self.set_parameter("FLOW_TYPE", 10) + + self.set_analog_rangefinder_parameters() + + self.reboot_sitl() + + self.change_mode('LOITER') + + # ensure OPTICAL_FLOW message is reasonable: + global flow_rate_rads + global rangefinder_distance + global gps_speed + global last_debug_time + flow_rate_rads = 0 + rangefinder_distance = 0 + gps_speed = 0 + last_debug_time = 0 + + def check_optical_flow(mav, m): + global flow_rate_rads + global rangefinder_distance + global gps_speed + global last_debug_time + m_type = m.get_type() + if m_type == "OPTICAL_FLOW": + flow_rate_rads = math.sqrt(m.flow_comp_m_x**2+m.flow_comp_m_y**2) + elif m_type == "RANGEFINDER": + rangefinder_distance = m.distance + elif m_type == "GPS_RAW_INT": + gps_speed = m.vel/100.0 # cm/s -> m/s + of_speed = flow_rate_rads * rangefinder_distance + if abs(of_speed - gps_speed) > 3: + raise NotAchievedException("gps=%f vs of=%f mismatch" % + (gps_speed, of_speed)) + + now = self.get_sim_time_cached() + if now - last_debug_time > 5: + last_debug_time = now + self.progress("gps=%f of=%f" % (gps_speed, of_speed)) + + self.install_message_hook_context(check_optical_flow) + + self.fly_generic_mission("CMAC-copter-navtest.txt") + + self.context_pop() + + self.reboot_sitl() + def OpticalFlowLimits(self): '''test EKF navigation limiting''' ex = None @@ -3623,6 +3684,15 @@ def fly_mission(self, filename, strict=True): self.wait_waypoint(num_wp-1, num_wp-1) self.wait_disarmed() + def fly_generic_mission(self, filename, strict=True): + num_wp = self.load_generic_mission(filename, strict=strict) + self.set_parameter("AUTO_OPTIONS", 3) + self.change_mode('AUTO') + self.wait_ready_to_arm() + self.arm_vehicle() + self.wait_waypoint(num_wp-1, num_wp-1) + self.wait_disarmed() + def SurfaceTracking(self): '''Test Surface Tracking''' ex = None @@ -10067,6 +10137,7 @@ def tests1d(self): self.ModeCircle, self.MagFail, self.OpticalFlow, + self.OpticalFlowLocation, self.OpticalFlowLimits, self.OpticalFlowCalibration, self.MotorFail, From f8c3b494d1c6094c5743dce9012cfd664e4c6635 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 5 Jan 2024 07:37:41 +1100 Subject: [PATCH 0391/1335] autotest: fixed missing Blimp for enum parsing --- Tools/autotest/logger_metadata/enum_parse.py | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/autotest/logger_metadata/enum_parse.py b/Tools/autotest/logger_metadata/enum_parse.py index 50c026a21651f3..3826160de20048 100755 --- a/Tools/autotest/logger_metadata/enum_parse.py +++ b/Tools/autotest/logger_metadata/enum_parse.py @@ -18,6 +18,7 @@ class EnumDocco(object): "Copter": "ArduCopter", "Plane": "ArduPlane", "Tracker": "AntennaTracker", + "Blimp": "Blimp", } def __init__(self, vehicle): From 2cfbd2598821058fa24e352d4dd7c830f7f062dd Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 4 Jan 2024 10:55:59 +1100 Subject: [PATCH 0392/1335] Tools: improve diagnostics from failed check_replay --- Tools/autotest/arducopter.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index fac5a81f1c09c3..6be401624fca11 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -8903,7 +8903,7 @@ def test_replay_bit(self, bit): ok = check_replay.check_log(replay_log_filepath, self.progress, verbose=True) if not ok: - raise NotAchievedException("check_replay failed") + raise NotAchievedException("check_replay (%s) failed" % current_log_filepath) def DefaultIntervalsFromFiles(self): '''Test setting default mavlink message intervals from files''' From c48f5c09db501f5c8e5cdee7c7284978e76dd635 Mon Sep 17 00:00:00 2001 From: freenamegit Date: Thu, 4 Jan 2024 20:59:41 +0200 Subject: [PATCH 0393/1335] Tools: added name to GIT_Success.txt --- Tools/GIT_Test/GIT_Success.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/GIT_Test/GIT_Success.txt b/Tools/GIT_Test/GIT_Success.txt index 2b89570700cd59..abada8657bd71a 100644 --- a/Tools/GIT_Test/GIT_Success.txt +++ b/Tools/GIT_Test/GIT_Success.txt @@ -179,3 +179,4 @@ Ramy Gad Matthew R. Cunningham prathap devendran (Tamil) india, 11-23 Taqwaisneeded +FreeName \ No newline at end of file From c54aa0241af331b3932f3acfa91a6de94ae45d2a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 5 Jan 2024 13:34:37 +1100 Subject: [PATCH 0394/1335] HAL_ChibiOS: added mem_is_dma_safe() function used for bouncebuffer code and in FATFS code --- libraries/AP_HAL_ChibiOS/Util.cpp | 6 +++ .../hwdef/common/bouncebuffer.c | 21 +--------- .../AP_HAL_ChibiOS/hwdef/common/malloc.c | 41 +++++++++++++++++++ .../AP_HAL_ChibiOS/hwdef/common/stm32_util.h | 1 + libraries/AP_HAL_ChibiOS/sdcard.cpp | 4 ++ 5 files changed, 54 insertions(+), 19 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/Util.cpp b/libraries/AP_HAL_ChibiOS/Util.cpp index 7d56981c5c4c39..3f11aa6696eafa 100644 --- a/libraries/AP_HAL_ChibiOS/Util.cpp +++ b/libraries/AP_HAL_ChibiOS/Util.cpp @@ -76,6 +76,12 @@ void* Util::malloc_type(size_t size, AP_HAL::Util::Memory_Type mem_type) return malloc_dma(size); } else if (mem_type == AP_HAL::Util::MEM_FAST) { return malloc_fastmem(size); + } else if (mem_type == AP_HAL::Util::MEM_FILESYSTEM) { +#if defined(STM32H7) + return malloc_axi_sram(size); +#else + return malloc_dma(size); +#endif } else { return calloc(1, size); } diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/bouncebuffer.c b/libraries/AP_HAL_ChibiOS/hwdef/common/bouncebuffer.c index 590855bd59ed46..f1f735ab8f3532 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/bouncebuffer.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/bouncebuffer.c @@ -21,23 +21,6 @@ #include #include "bouncebuffer.h" -#if defined(STM32H7) -// always use a bouncebuffer on H7, to ensure alignment and padding -#define IS_DMA_SAFE(addr) false -#elif defined(STM32F732xx) -// always use bounce buffer on F732 -#define IS_DMA_SAFE(addr) false -#elif defined(STM32F7) -// on F76x we only consider first half of DTCM memory as DMA safe, 2nd half is used as fast memory for EKF -// on F74x we only have 64k of DTCM -#define IS_DMA_SAFE(addr) ((((uint32_t)(addr)) & ((0xFFFFFFFF & ~(64*1024U-1)) | 1U)) == 0x20000000) -#elif defined(STM32F1) -#define IS_DMA_SAFE(addr) true -#else -// this checks an address is in main memory and 16 bit aligned -#define IS_DMA_SAFE(addr) ((((uint32_t)(addr)) & 0xF0000001) == 0x20000000) -#endif - // Enable when trying to check if you are not just listening yourself #define ENABLE_ECHO_SAFE 0 @@ -64,7 +47,7 @@ void bouncebuffer_init(struct bouncebuffer_t **bouncebuffer, uint32_t prealloc_b */ bool bouncebuffer_setup_read(struct bouncebuffer_t *bouncebuffer, uint8_t **buf, uint32_t size) { - if (!bouncebuffer || IS_DMA_SAFE(*buf)) { + if (!bouncebuffer || mem_is_dma_safe(*buf, size, bouncebuffer->on_axi_sram)) { // nothing needs to be done return true; } @@ -113,7 +96,7 @@ void bouncebuffer_finish_read(struct bouncebuffer_t *bouncebuffer, const uint8_t */ bool bouncebuffer_setup_write(struct bouncebuffer_t *bouncebuffer, const uint8_t **buf, uint32_t size) { - if (!bouncebuffer || IS_DMA_SAFE(*buf)) { + if (!bouncebuffer || mem_is_dma_safe(*buf, size, bouncebuffer->on_axi_sram)) { // nothing needs to be done return true; } diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c b/libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c index d9b30d5a69379b..dada2e1c433c6e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c @@ -616,3 +616,44 @@ void ff_memfree(void* mblock) free(mblock); } #endif // USE_POSIX + +/* + return true if a memory region is safe for a DMA operation + */ +bool mem_is_dma_safe(const void *addr, uint32_t size, bool filesystem_op) +{ + (void)filesystem_op; +#if defined(STM32F1) + // F1 is always OK + (void)addr; + (void)size; + return true; +#else + uint32_t flags = MEM_REGION_FLAG_DMA_OK; +#if defined(STM32H7) + if (((uint32_t)addr) & 0x1F) { + return false; + } + if (filesystem_op) { + flags = MEM_REGION_FLAG_AXI_BUS; + } +#elif defined(STM32F4) + if (((uint32_t)addr) & 0x01) { + return false; + } +#else + if (((uint32_t)addr) & 0x07) { + return false; + } +#endif + for (uint8_t i=0; i= (uint32_t)memory_regions[i].address && + ((uint32_t)addr + size) <= ((uint32_t)memory_regions[i].address + memory_regions[i].size)) { + return true; + } + } + } + return false; +#endif // STM32F1 +} diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h index 0a56342d256fdb..5a24edd59fe97c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h @@ -43,6 +43,7 @@ void *malloc_axi_sram(size_t size); void *malloc_fastmem(size_t size); void *malloc_eth_safe(size_t size); thread_t *thread_create_alloc(size_t size, const char *name, tprio_t prio, tfunc_t pf, void *arg); +bool mem_is_dma_safe(const void *addr, uint32_t size, bool filesystem_op); struct memory_region { void *address; diff --git a/libraries/AP_HAL_ChibiOS/sdcard.cpp b/libraries/AP_HAL_ChibiOS/sdcard.cpp index c8cc8dcf7eba8f..922440826b06dd 100644 --- a/libraries/AP_HAL_ChibiOS/sdcard.cpp +++ b/libraries/AP_HAL_ChibiOS/sdcard.cpp @@ -73,7 +73,11 @@ bool sdcard_init() if (sdcd.bouncebuffer == nullptr) { // allocate 4k bouncebuffer for microSD to match size in // AP_Logger +#if defined(STM32H7) bouncebuffer_init(&sdcd.bouncebuffer, 4096, true); +#else + bouncebuffer_init(&sdcd.bouncebuffer, 4096, false); +#endif } if (sdcard_running) { From f2a1c80652c7a28584344c8a431c727ad0d704c4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 5 Jan 2024 13:34:55 +1100 Subject: [PATCH 0395/1335] AP_HAL: added MEM_FILESYSTEM memory type --- libraries/AP_HAL/Util.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL/Util.h b/libraries/AP_HAL/Util.h index b605fecabad95e..d5bd6bb95cf4ea 100644 --- a/libraries/AP_HAL/Util.h +++ b/libraries/AP_HAL/Util.h @@ -147,7 +147,8 @@ class AP_HAL::Util { // allocate and free DMA-capable memory if possible. Otherwise return normal memory enum Memory_Type { MEM_DMA_SAFE, - MEM_FAST + MEM_FAST, + MEM_FILESYSTEM }; virtual void *malloc_type(size_t size, Memory_Type mem_type) { return calloc(1, size); } virtual void free_type(void *ptr, size_t size, Memory_Type mem_type) { return free(ptr); } From c5f295e8527baad6e776d007962f0ec37f80a376 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 5 Jan 2024 13:36:32 +1100 Subject: [PATCH 0396/1335] AP_Filesystem: allow for large file IOs this allows for larger IOs on FATFS if the memoory is OK for DMA --- libraries/AP_Filesystem/AP_Filesystem_FATFS.cpp | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Filesystem/AP_Filesystem_FATFS.cpp b/libraries/AP_Filesystem/AP_Filesystem_FATFS.cpp index 59cbd357624114..df47485a307218 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_FATFS.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem_FATFS.cpp @@ -14,6 +14,7 @@ #include #include #include +#include #if 0 #define debug(fmt, args ...) do {printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0) @@ -416,7 +417,10 @@ int32_t AP_Filesystem_FATFS::read(int fd, void *buf, uint32_t count) UINT total = 0; do { UINT size = 0; - UINT n = MIN(bytes, MAX_IO_SIZE); + UINT n = bytes; + if (!mem_is_dma_safe(buf, count, true)) { + n = MIN(bytes, MAX_IO_SIZE); + } res = f_read(fh, (void *)buf, n, &size); if (res != FR_OK) { errno = fatfs_to_errno((FRESULT)res); @@ -460,7 +464,10 @@ int32_t AP_Filesystem_FATFS::write(int fd, const void *buf, uint32_t count) UINT total = 0; do { - UINT n = MIN(bytes, MAX_IO_SIZE); + UINT n = bytes; + if (!mem_is_dma_safe(buf, count, true)) { + n = MIN(bytes, MAX_IO_SIZE); + } UINT size = 0; res = f_write(fh, buf, n, &size); if (res == FR_DISK_ERR && RETRY_ALLOWED()) { From b0bbed01c637dbe75a214f5c77c1d58058392cd4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 5 Jan 2024 13:37:02 +1100 Subject: [PATCH 0397/1335] AP_Networking: speed up sendfile download use a multiple of sector size and DMA safe memory --- libraries/AP_Networking/AP_Networking.cpp | 12 ++++++++++-- libraries/AP_Networking/AP_Networking.h | 1 + libraries/AP_Networking/AP_Networking_Config.h | 2 +- 3 files changed, 12 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Networking/AP_Networking.cpp b/libraries/AP_Networking/AP_Networking.cpp index 87ca70bd94ad71..87b5147b75f241 100644 --- a/libraries/AP_Networking/AP_Networking.cpp +++ b/libraries/AP_Networking/AP_Networking.cpp @@ -293,7 +293,15 @@ bool AP_Networking::sendfile(SocketAPM *sock, int fd) { WITH_SEMAPHORE(sem); if (sendfile_buf == nullptr) { - sendfile_buf = (uint8_t *)malloc(AP_NETWORKING_SENDFILE_BUFSIZE); + uint32_t bufsize = AP_NETWORKING_SENDFILE_BUFSIZE; + do { + sendfile_buf = (uint8_t *)hal.util->malloc_type(bufsize, AP_HAL::Util::MEM_FILESYSTEM); + if (sendfile_buf != nullptr) { + sendfile_bufsize = bufsize; + break; + } + bufsize /= 2; + } while (bufsize >= 4096); if (sendfile_buf == nullptr) { return false; } @@ -344,7 +352,7 @@ void AP_Networking::sendfile_check(void) if (!s.sock->pollout(0)) { continue; } - const auto nread = AP::FS().read(s.fd, sendfile_buf, AP_NETWORKING_SENDFILE_BUFSIZE); + const auto nread = AP::FS().read(s.fd, sendfile_buf, sendfile_bufsize); if (nread <= 0) { s.close(); continue; diff --git a/libraries/AP_Networking/AP_Networking.h b/libraries/AP_Networking/AP_Networking.h index 3b18072593b70f..63936f025b2c50 100644 --- a/libraries/AP_Networking/AP_Networking.h +++ b/libraries/AP_Networking/AP_Networking.h @@ -278,6 +278,7 @@ class AP_Networking } sendfiles[AP_NETWORKING_NUM_SENDFILES]; uint8_t *sendfile_buf; + uint32_t sendfile_bufsize; void sendfile_check(void); bool sendfile_thread_started; diff --git a/libraries/AP_Networking/AP_Networking_Config.h b/libraries/AP_Networking/AP_Networking_Config.h index b9fdbd6fd3fb20..2fbf9d70b15c5f 100644 --- a/libraries/AP_Networking/AP_Networking_Config.h +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -117,5 +117,5 @@ #endif #ifndef AP_NETWORKING_SENDFILE_BUFSIZE -#define AP_NETWORKING_SENDFILE_BUFSIZE 10000 +#define AP_NETWORKING_SENDFILE_BUFSIZE (64*512) #endif From fa2b87b05a5fe2a0cef40e8c71ce0bbdb650e443 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 5 Jan 2024 13:39:30 +1100 Subject: [PATCH 0398/1335] AP_Networking: hide unused params for PPP --- libraries/AP_Networking/AP_Networking_Config.h | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/libraries/AP_Networking/AP_Networking_Config.h b/libraries/AP_Networking/AP_Networking_Config.h index 2fbf9d70b15c5f..b54a8e399f7831 100644 --- a/libraries/AP_Networking/AP_Networking_Config.h +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -19,15 +19,6 @@ #define AP_NETWORKING_BACKEND_DEFAULT_ENABLED AP_NETWORKING_ENABLED #endif -#ifndef AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED -// AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED should only be true if we have the ability to -// change the IP address. If not then the IP, GW, NetMask, MAC and DHCP params are hidden. -// This does not mean that the system/OS does not have the ability to set the IP, just that -// we have no control from this scope. For example, Linux systems (including SITL) have -// their own DHCP client running but we have no control over it. -#define AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS) -#endif - // --------------------------- // Backends // --------------------------- @@ -50,6 +41,15 @@ #define AP_NETWORKING_SOCKETS_ENABLED AP_NETWORKING_ENABLED #endif +#ifndef AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED +// AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED should only be true if we have the ability to +// change the IP address. If not then the IP, GW, NetMask, MAC and DHCP params are hidden. +// This does not mean that the system/OS does not have the ability to set the IP, just that +// we have no control from this scope. For example, Linux systems (including SITL) have +// their own DHCP client running but we have no control over it. +#define AP_NETWORKING_CONTROLS_HOST_IP_SETTINGS_ENABLED AP_NETWORKING_BACKEND_CHIBIOS +#endif + #define AP_NETWORKING_NEED_LWIP (AP_NETWORKING_BACKEND_CHIBIOS || AP_NETWORKING_BACKEND_PPP) // --------------------------- From 535a6a331626aed9401f2802545f0332fef73a4e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 6 Jan 2024 07:51:04 +1100 Subject: [PATCH 0399/1335] AP_Networking: fixed build of evtimer.c on firmware server the firmware server uses --out option to waf configure which changes the include paths --- libraries/AP_Networking/lwip_hal/arch/evtimer.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Networking/lwip_hal/arch/evtimer.c b/libraries/AP_Networking/lwip_hal/arch/evtimer.c index 53da0413f82109..56657904ed7619 100644 --- a/libraries/AP_Networking/lwip_hal/arch/evtimer.c +++ b/libraries/AP_Networking/lwip_hal/arch/evtimer.c @@ -5,6 +5,7 @@ #include #if CH_CFG_USE_EVENTS -#include "../../modules/ChibiOS/os/various/evtimer.c" +// this include relies on -I for modules/ChibiOS/os/various/cpp_wrappers +#include <../evtimer.c> #endif From 6d4747a38c1eecb734cf813eb3fded90fdf4732d Mon Sep 17 00:00:00 2001 From: David 'Buzz' Bussenschutt Date: Sat, 6 Jan 2024 09:33:45 +1000 Subject: [PATCH 0400/1335] Tools: fix esp32 CI build install gevent as a package first seems to allow it to avoid issues. also 3.11 is reqd, and 3.10 usn't good enough. --- .github/workflows/esp32_build.yml | 21 ++++++++++++++++++--- Tools/scripts/esp32_get_idf.sh | 14 ++++++++++---- 2 files changed, 28 insertions(+), 7 deletions(-) diff --git a/.github/workflows/esp32_build.yml b/.github/workflows/esp32_build.yml index 47ada972560a46..7f2a11bf060ca8 100644 --- a/.github/workflows/esp32_build.yml +++ b/.github/workflows/esp32_build.yml @@ -161,11 +161,26 @@ jobs: - name: Install Prerequisites shell: bash run: | - sudo apt-get install git wget libncurses-dev flex bison gperf python3 python3-pip python3-setuptools python3-serial python3-cryptography python3-future python3-pyparsing python3-pyelftools cmake ninja-build ccache libffi-dev libssl-dev dfu-util libusb-1.0-0 + sudo apt-get install git wget libncurses-dev flex bison gperf python3 python3-pip python3-venv python3-setuptools python3-serial python3-gevent python3-cryptography python3-future python3-pyparsing python3-pyelftools cmake ninja-build ccache libffi-dev libssl-dev dfu-util libusb-1.0-0 sudo update-alternatives --install /usr/bin/python python /usr/bin/python3 10 + update-alternatives --query python + python --version + pip3 install gevent - rm -rf /usr/local/bin/cmake + # we actualy want 3.11 .. but the above only gave us 3.10, not ok with esp32 builds. + sudo add-apt-repository ppa:deadsnakes/ppa + sudo apt update + sudo apt install python3.11 python3.11-venv python3.11-distutils -y + sudo apt-get install python3 python3-pip python3-venv python3-setuptools python3-serial python3-cryptography python3-future python3-pyparsing python3-pyelftools + update-alternatives --query python + pip3 install gevent + python --version + python3.11 --version + which python3.11 + sudo update-alternatives --install /usr/bin/python python /usr/bin/python3.11 11 + update-alternatives --query python + rm -rf /usr/local/bin/cmake sudo apt remove --purge --auto-remove cmake sudo apt update && \ sudo apt install -y software-properties-common lsb-release && \ @@ -183,7 +198,7 @@ jobs: cd modules/esp_idf echo "Installing ESP-IDF tools...." - ./install.sh 2>&1 > /dev/null + ./install.sh esp32,esp32s3 2>&1 > /dev/null cd ../.. diff --git a/Tools/scripts/esp32_get_idf.sh b/Tools/scripts/esp32_get_idf.sh index 39bf8dae7dcc65..4ad61e15e9d360 100755 --- a/Tools/scripts/esp32_get_idf.sh +++ b/Tools/scripts/esp32_get_idf.sh @@ -1,4 +1,5 @@ -#!/bin/bash +#!/bin/bash + # if you have modules/esp_idf setup as a submodule, then leave it as a submodule and switch branches if [ ! -d modules ]; then echo "this script needs to be run from the root of your repo, sorry, giving up." @@ -25,26 +26,31 @@ else # add esp_idf as almost submodule, depths uses less space #git clone -b v4.4 --single-branch --depth 10 https://github.com/espressif/esp-idf.git esp_idf git clone -b 'release/v4.4' https://github.com/espressif/esp-idf.git esp_idf + git checkout 6d853f # check if we've got v4.4 checked out, only this version of esp_idf is tested and works? fi fi + + echo "inspecting possible IDF... " cd esp_idf echo `git rev-parse HEAD` # these are a selection of possible specific commit/s that represent v4.4 branch of the esp_idf -if [ `git rev-parse HEAD` == 'f98ec313f2a9bc50151349c404a8f2f10ed99649' ]; then +if [ `git rev-parse HEAD` == '6d853f0525b003afaeaed4fb59a265c8522c2da9' ]; then echo "IDF version 'release/4.4' found OK, great."; else - echo "looks like an idf, but not v4.4 branch, trying to switch branch and reflect upstream"; + echo "looks like an idf, but not v4.4 branch, or wrong commit , trying to switch branch and reflect upstream"; ../../Tools/gittools/submodule-sync.sh >/dev/null git fetch ; git checkout -f release/v4.4 + git checkout 6d853f # retry same as above echo `git rev-parse HEAD` - if [ `git rev-parse HEAD` == 'f98ec313f2a9bc50151349c404a8f2f10ed99649' ]; then + if [ `git rev-parse HEAD` == '6d853f0525b003afaeaed4fb59a265c8522c2da9' ]; then echo "IDF version 'release/4.4' found OK, great."; + git checkout 6d853f fi fi cd ../.. From 9a4a3bf5517c630b90c73879c0f340dc6a2ac5c5 Mon Sep 17 00:00:00 2001 From: David Buzz Date: Tue, 2 May 2023 09:53:22 +1000 Subject: [PATCH 0401/1335] Tools: on esp32 force constants to single-precision like chibios port does. --- Tools/ardupilotwaf/boards.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index c6c85784639473..386727a203437e 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -936,6 +936,7 @@ def expand_path(p): env.CFLAGS += [ '-fno-inline-functions', '-mlongcalls', + '-fsingle-precision-constant', ] env.CFLAGS.remove('-Werror=undef') @@ -951,6 +952,7 @@ def expand_path(p): '-Wno-sign-compare', '-fno-inline-functions', '-mlongcalls', + '-fsingle-precision-constant', # force const vals to be float , not double. so 100.0 means 100.0f '-fno-threadsafe-statics', '-DCYGWIN_BUILD'] env.CXXFLAGS.remove('-Werror=undef') From 03d25708ff645dc90053ff403ac5c51b9b14889c Mon Sep 17 00:00:00 2001 From: David 'Buzz' Bussenschutt Date: Sat, 6 Jan 2024 09:33:45 +1000 Subject: [PATCH 0402/1335] Tools: fix esp32 build to use python 3.11 --- .github/workflows/esp32_build.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/esp32_build.yml b/.github/workflows/esp32_build.yml index 7f2a11bf060ca8..d1eb1c8c456ada 100644 --- a/.github/workflows/esp32_build.yml +++ b/.github/workflows/esp32_build.yml @@ -145,7 +145,7 @@ concurrency: jobs: build: - runs-on: ubuntu-22.04 + runs-on: ubuntu-23.04 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: From b9ac504d0daa4e370e5b8660b618005b31a16796 Mon Sep 17 00:00:00 2001 From: David Buzz Date: Sat, 6 Jan 2024 13:38:57 +1000 Subject: [PATCH 0403/1335] AP_HAL_ESP32: prevent watchdog while booting with slow things like sdcards --- libraries/AP_HAL_ESP32/README.md | 6 +- libraries/AP_HAL_ESP32/Scheduler.cpp | 81 ++++++++++++------- libraries/AP_HAL_ESP32/SdCard.cpp | 7 +- libraries/AP_HAL_ESP32/WiFiDriver.cpp | 11 ++- libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp | 16 +++- .../targets/esp32/esp-idf/sdkconfig | 43 +++++++++- 6 files changed, 125 insertions(+), 39 deletions(-) diff --git a/libraries/AP_HAL_ESP32/README.md b/libraries/AP_HAL_ESP32/README.md index de2fbe7e70d9ac..e891fa9571edad 100644 --- a/libraries/AP_HAL_ESP32/README.md +++ b/libraries/AP_HAL_ESP32/README.md @@ -96,8 +96,10 @@ ESPBAUD=921600 ./waf plane --upload You can use your default build system (make or ninja) to build other esp-idf target. For example : -- ninja flash -- ninja monitor + source modules/esp_idf/export.sh + cd /home/buzz2/ardupilot/build/esp32buzz/esp-idf_build + ninja flash + ninja monitor If you want to specify the port, specify before any command: ``` diff --git a/libraries/AP_HAL_ESP32/Scheduler.cpp b/libraries/AP_HAL_ESP32/Scheduler.cpp index 9b940f9c9f2adb..8a30f612eb81e9 100644 --- a/libraries/AP_HAL_ESP32/Scheduler.cpp +++ b/libraries/AP_HAL_ESP32/Scheduler.cpp @@ -38,6 +38,8 @@ using namespace ESP32; extern const AP_HAL::HAL& hal; bool Scheduler::_initialized = true; +TaskHandle_t idle_0 = NULL; +TaskHandle_t idle_1 = NULL; Scheduler::Scheduler() { @@ -46,7 +48,7 @@ Scheduler::Scheduler() void disableCore0WDT() { - TaskHandle_t idle_0 = xTaskGetIdleTaskHandleForCPU(0); + idle_0 = xTaskGetIdleTaskHandleForCPU(0); if (idle_0 == NULL || esp_task_wdt_delete(idle_0) != ESP_OK) { //print("Failed to remove Core 0 IDLE task from WDT"); } @@ -54,11 +56,23 @@ void disableCore0WDT() void disableCore1WDT() { - TaskHandle_t idle_1 = xTaskGetIdleTaskHandleForCPU(1); + idle_1 = xTaskGetIdleTaskHandleForCPU(1); if (idle_1 == NULL || esp_task_wdt_delete(idle_1) != ESP_OK) { //print("Failed to remove Core 1 IDLE task from WDT"); } } +void enableCore0WDT() +{ + if (idle_0 != NULL && esp_task_wdt_add(idle_0) != ESP_OK) { + //print("Failed to add Core 0 IDLE task to WDT"); + } +} +void enableCore1WDT() +{ + if (idle_1 != NULL && esp_task_wdt_add(idle_1) != ESP_OK) { + //print("Failed to add Core 1 IDLE task to WDT"); + } +} void Scheduler::init() { @@ -67,57 +81,69 @@ void Scheduler::init() printf("%s:%d \n", __PRETTY_FUNCTION__, __LINE__); #endif + // disable wd while booting, as things like mounting the sd-card in the io thread can take a while, especially if there isn't hardware attached. + disableCore0WDT(); //FASTCPU + disableCore1WDT(); //SLOWCPU + + hal.console->printf("%s:%d running with CONFIG_FREERTOS_HZ=%d\n", __PRETTY_FUNCTION__, __LINE__,CONFIG_FREERTOS_HZ); + // keep main tasks that need speed on CPU 0 + // pin potentially slow stuff to CPU 1, as we have disabled the WDT on that core. + #define FASTCPU 0 + #define SLOWCPU 1 + // pin main thread to Core 0, and we'll also pin other heavy-tasks to core 1, like wifi-related. - if (xTaskCreatePinnedToCore(_main_thread, "APM_MAIN", Scheduler::MAIN_SS, this, Scheduler::MAIN_PRIO, &_main_task_handle,1) != pdPASS) { + if (xTaskCreatePinnedToCore(_main_thread, "APM_MAIN", Scheduler::MAIN_SS, this, Scheduler::MAIN_PRIO, &_main_task_handle,FASTCPU) != pdPASS) { //if (xTaskCreate(_main_thread, "APM_MAIN", Scheduler::MAIN_SS, this, Scheduler::MAIN_PRIO, &_main_task_handle) != pdPASS) { - hal.console->printf("FAILED to create task _main_thread\n"); + hal.console->printf("FAILED to create task _main_thread on FASTCPU\n"); } else { - hal.console->printf("OK created task _main_thread\n"); + hal.console->printf("OK created task _main_thread on FASTCPU\n"); } - if (xTaskCreate(_timer_thread, "APM_TIMER", TIMER_SS, this, TIMER_PRIO, &_timer_task_handle) != pdPASS) { - hal.console->printf("FAILED to create task _timer_thread\n"); + if (xTaskCreatePinnedToCore(_timer_thread, "APM_TIMER", TIMER_SS, this, TIMER_PRIO, &_timer_task_handle,FASTCPU) != pdPASS) { + hal.console->printf("FAILED to create task _timer_thread on FASTCPU\n"); } else { - hal.console->printf("OK created task _timer_thread\n"); + hal.console->printf("OK created task _timer_thread on FASTCPU\n"); } - if (xTaskCreatePinnedToCore(_rcout_thread, "APM_RCOUT", RCOUT_SS, this, RCOUT_PRIO, &_rcout_task_handle,0) != pdPASS) { - hal.console->printf("FAILED to create task _rcout_thread\n"); + if (xTaskCreatePinnedToCore(_rcout_thread, "APM_RCOUT", RCOUT_SS, this, RCOUT_PRIO, &_rcout_task_handle,SLOWCPU) != pdPASS) { + hal.console->printf("FAILED to create task _rcout_thread on SLOWCPU\n"); } else { - hal.console->printf("OK created task _rcout_thread\n"); + hal.console->printf("OK created task _rcout_thread on SLOWCPU\n"); } - if (xTaskCreatePinnedToCore(_rcin_thread, "APM_RCIN", RCIN_SS, this, RCIN_PRIO, &_rcin_task_handle,0) != pdPASS) { - hal.console->printf("FAILED to create task _rcin_thread\n"); + if (xTaskCreatePinnedToCore(_rcin_thread, "APM_RCIN", RCIN_SS, this, RCIN_PRIO, &_rcin_task_handle,SLOWCPU) != pdPASS) { + hal.console->printf("FAILED to create task _rcin_thread on SLOWCPU\n"); } else { - hal.console->printf("OK created task _rcin_thread\n"); + hal.console->printf("OK created task _rcin_thread on SLOWCPU\n"); } - // pin this thread to Core 1 - if (xTaskCreatePinnedToCore(_uart_thread, "APM_UART", UART_SS, this, UART_PRIO, &_uart_task_handle,0) != pdPASS) { - hal.console->printf("FAILED to create task _uart_thread\n"); + // pin this thread to Core 1 as it keeps all teh uart/s feed data, and we need that quick. + if (xTaskCreatePinnedToCore(_uart_thread, "APM_UART", UART_SS, this, UART_PRIO, &_uart_task_handle,FASTCPU) != pdPASS) { + hal.console->printf("FAILED to create task _uart_thread on FASTCPU\n"); } else { - hal.console->printf("OK created task _uart_thread\n"); + hal.console->printf("OK created task _uart_thread on FASTCPU\n"); } - if (xTaskCreate(_io_thread, "SchedulerIO:APM_IO", IO_SS, this, IO_PRIO, &_io_task_handle) != pdPASS) { - hal.console->printf("FAILED to create task _io_thread\n"); + // we put thos on the SLOW core as it mounts the sd card, and that often isn't conencted. + if (xTaskCreatePinnedToCore(_io_thread, "SchedulerIO:APM_IO", IO_SS, this, IO_PRIO, &_io_task_handle,SLOWCPU) != pdPASS) { + hal.console->printf("FAILED to create task _io_thread on SLOWCPU\n"); } else { - hal.console->printf("OK created task _io_thread\n"); + hal.console->printf("OK created task _io_thread on SLOWCPU\n"); } - if (xTaskCreate(_storage_thread, "APM_STORAGE", STORAGE_SS, this, STORAGE_PRIO, &_storage_task_handle) != pdPASS) { //no actual flash writes without this, storage kinda appears to work, but does an erase on every boot and params don't persist over reset etc. + if (xTaskCreatePinnedToCore(_storage_thread, "APM_STORAGE", STORAGE_SS, this, STORAGE_PRIO, &_storage_task_handle,SLOWCPU) != pdPASS) { //no actual flash writes without this, storage kinda appears to work, but does an erase on every boot and params don't persist over reset etc. hal.console->printf("FAILED to create task _storage_thread\n"); } else { hal.console->printf("OK created task _storage_thread\n"); } - // xTaskCreate(_print_profile, "APM_PROFILE", IO_SS, this, IO_PRIO, nullptr); + // xTaskCreatePinnedToCore(_print_profile, "APM_PROFILE", IO_SS, this, IO_PRIO, nullptr,SLOWCPU); - //disableCore0WDT(); - //disableCore1WDT(); + hal.console->printf("OK Sched Init, enabling WD\n"); + enableCore0WDT(); //FASTCPU + //enableCore1WDT(); //we don't enable WD on SLOWCPU right now. } @@ -209,6 +235,7 @@ void Scheduler::delay_microseconds(uint16_t us) ets_delay_us(us); } else { // Minimum delay for FreeRTOS is 1ms uint32_t tick = portTICK_PERIOD_MS * 1000; + rtc_wdt_feed(); vTaskDelay((us+tick-1)/tick); } } @@ -441,7 +468,7 @@ void Scheduler::_storage_thread(void* arg) printf("%s:%d start \n", __PRETTY_FUNCTION__, __LINE__); #endif Scheduler *sched = (Scheduler *)arg; - while (!_initialized) { + while (!sched->_initialized) { sched->delay_microseconds(10000); } #ifdef SCHEDDEBUG @@ -475,7 +502,7 @@ void Scheduler::_uart_thread(void *arg) printf("%s:%d start \n", __PRETTY_FUNCTION__, __LINE__); #endif Scheduler *sched = (Scheduler *)arg; - while (!_initialized) { + while (!sched->_initialized) { sched->delay_microseconds(2000); } #ifdef SCHEDDEBUG diff --git a/libraries/AP_HAL_ESP32/SdCard.cpp b/libraries/AP_HAL_ESP32/SdCard.cpp index f652e865fd5fc9..725235fba9e098 100644 --- a/libraries/AP_HAL_ESP32/SdCard.cpp +++ b/libraries/AP_HAL_ESP32/SdCard.cpp @@ -32,6 +32,8 @@ #include #include "SPIDevice.h" +#include "soc/rtc_wdt.h" + #ifdef HAL_ESP32_SDCARD #if CONFIG_IDF_TARGET_ESP32S2 ||CONFIG_IDF_TARGET_ESP32C3 @@ -163,8 +165,9 @@ void mount_sdcard_mmc() // Please check its source code and implement error recovery when developing // production applications. sdmmc_card_t* card; + rtc_wdt_feed(); esp_err_t ret = esp_vfs_fat_sdmmc_mount("/SDCARD", &host, &slot_config, &mount_config, &card); - + rtc_wdt_feed(); if (ret == ESP_OK) { mkdir("/SDCARD/APM", 0777); @@ -234,7 +237,9 @@ void mount_sdcard_spi() //host.flags = SDMMC_HOST_FLAG_1BIT | SDMMC_HOST_FLAG_DDR; host.max_freq_khz = SDMMC_FREQ_PROBING; + rtc_wdt_feed(); ret = esp_vfs_fat_sdspi_mount("/SDCARD", &host, &slot_config, &mount_config, &card); + rtc_wdt_feed(); if (ret == ESP_OK) { // Card has been initialized, print its properties diff --git a/libraries/AP_HAL_ESP32/WiFiDriver.cpp b/libraries/AP_HAL_ESP32/WiFiDriver.cpp index b11c6b978c266e..43c9135e15d876 100644 --- a/libraries/AP_HAL_ESP32/WiFiDriver.cpp +++ b/libraries/AP_HAL_ESP32/WiFiDriver.cpp @@ -50,10 +50,15 @@ void WiFiDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS) if (_state == NOT_INITIALIZED) { initialize_wifi(); - if (xTaskCreatePinnedToCore(_wifi_thread, "APM_WIFI1", Scheduler::WIFI_SS1, this, Scheduler::WIFI_PRIO1, &_wifi_task_handle,0) != pdPASS) { - hal.console->printf("FAILED to create task _wifi_thread\n"); + // keep main tasks that need speed on CPU 0 + // pin potentially slow stuff to CPU 1, as we have disabled the WDT on that core. + #define FASTCPU 0 + #define SLOWCPU 1 + + if (xTaskCreatePinnedToCore(_wifi_thread, "APM_WIFI1", Scheduler::WIFI_SS1, this, Scheduler::WIFI_PRIO1, &_wifi_task_handle,FASTCPU) != pdPASS) { + hal.console->printf("FAILED to create task _wifi_thread on FASTCPU\n"); } else { - hal.console->printf("OK created task _wifi_thread\n"); + hal.console->printf("OK created task _wifi_thread on FASTCPU\n"); } _readbuf.set_size(RX_BUF_SIZE); diff --git a/libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp b/libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp index 6e08cabfb2a4d0..eb2fbdbec2cb6a 100644 --- a/libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp +++ b/libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp @@ -32,6 +32,8 @@ #include "lwip/sys.h" #include "lwip/netdb.h" +#include "soc/rtc_wdt.h" + using namespace ESP32; extern const AP_HAL::HAL& hal; @@ -52,10 +54,15 @@ void WiFiUdpDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS) return; } - if (xTaskCreatePinnedToCore(_wifi_thread2, "APM_WIFI2", Scheduler::WIFI_SS2, this, Scheduler::WIFI_PRIO2, &_wifi_task_handle,0) != pdPASS) { - hal.console->printf("FAILED to create task _wifi_thread2\n"); + // keep main tasks that need speed on CPU 0 + // pin potentially slow stuff to CPU 1, as we have disabled the WDT on that core. + #define FASTCPU 0 + #define SLOWCPU 1 + + if (xTaskCreatePinnedToCore(_wifi_thread2, "APM_WIFI2", Scheduler::WIFI_SS2, this, Scheduler::WIFI_PRIO2, &_wifi_task_handle,FASTCPU) != pdPASS) { + hal.console->printf("FAILED to create task _wifi_thread2 on FASTCPU\n"); } else { - hal.console->printf("OK created task _wifi_thread2\n"); + hal.console->printf("OK created task _wifi_thread2 on FASTCPU\n"); } _readbuf.set_size(RX_BUF_SIZE); @@ -219,9 +226,10 @@ void WiFiUdpDriver::_wifi_thread2(void *arg) .tv_usec = 100*1000, // 10 times a sec, we try to write-all even if we read nothing , at just 1000, it floggs the APM_WIFI2 task cpu usage unecessarily, slowing APM_WIFI1 response }; fd_set rfds; + rtc_wdt_feed(); FD_ZERO(&rfds); FD_SET(self->accept_socket, &rfds); - + rtc_wdt_feed(); int s = select(self->accept_socket + 1, &rfds, NULL, NULL, &tv); if (s > 0 && FD_ISSET(self->accept_socket, &rfds)) { self->read_all(); diff --git a/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/sdkconfig b/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/sdkconfig index cbdbc78de6d03c..725b24a4a3b6e6 100644 --- a/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/sdkconfig +++ b/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/sdkconfig @@ -203,6 +203,7 @@ CONFIG_SPI_SLAVE_ISR_IN_IRAM=y # CONFIG_TWAI_ERRATA_FIX_TX_INTR_LOST is not set # CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID is not set # CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT is not set +# CONFIG_TWAI_ERRATA_FIX_LISTEN_ONLY_DOM is not set # end of TWAI configuration # @@ -247,9 +248,16 @@ CONFIG_EFUSE_MAX_BLK_LEN=192 # CONFIG_ESP32_REV_MIN_0=y # CONFIG_ESP32_REV_MIN_1 is not set +# CONFIG_ESP32_REV_MIN_1_1 is not set # CONFIG_ESP32_REV_MIN_2 is not set # CONFIG_ESP32_REV_MIN_3 is not set +# CONFIG_ESP32_REV_MIN_3_1 is not set CONFIG_ESP32_REV_MIN=0 +CONFIG_ESP32_REV_MIN_FULL=0 +CONFIG_ESP_REV_MIN_FULL=0 +CONFIG_ESP32_REV_MAX_FULL_STR_OPT=y +CONFIG_ESP32_REV_MAX_FULL=399 +CONFIG_ESP_REV_MAX_FULL=399 CONFIG_ESP32_DPORT_WORKAROUND=y # CONFIG_ESP32_DEFAULT_CPU_FREQ_80 is not set # CONFIG_ESP32_DEFAULT_CPU_FREQ_160 is not set @@ -351,6 +359,7 @@ CONFIG_ESP_MAC_ADDR_UNIVERSE_BT=y CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES_TWO=y # CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES_FOUR is not set CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES=2 +# CONFIG_ESP_MAC_IGNORE_MAC_CRC_ERROR is not set # end of MAC Config # @@ -360,6 +369,8 @@ CONFIG_ESP32_UNIVERSAL_MAC_ADDRESSES=2 CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y # CONFIG_ESP_SLEEP_GPIO_RESET_WORKAROUND is not set CONFIG_ESP_SLEEP_FLASH_LEAKAGE_WORKAROUND=y +# CONFIG_ESP_SLEEP_MSPI_NEED_ALL_IO_PU is not set +CONFIG_ESP_SLEEP_GPIO_ENABLE_INTERNAL_RESISTORS=y # end of Sleep Config # @@ -393,6 +404,10 @@ CONFIG_ESP_PHY_CALIBRATION_AND_DATA_STORAGE=y CONFIG_ESP_PHY_MAX_WIFI_TX_POWER=20 CONFIG_ESP_PHY_MAX_TX_POWER=20 CONFIG_ESP_PHY_REDUCE_TX_POWER=y +CONFIG_ESP_PHY_RF_CAL_PARTIAL=y +# CONFIG_ESP_PHY_RF_CAL_NONE is not set +# CONFIG_ESP_PHY_RF_CAL_FULL is not set +CONFIG_ESP_PHY_CALIBRATION_MODE=0 # end of PHY # @@ -404,6 +419,13 @@ CONFIG_PM_ENABLE=y # CONFIG_PM_TRACE is not set # end of Power Management +# +# ESP Ringbuf +# +# CONFIG_RINGBUF_PLACE_FUNCTIONS_INTO_FLASH is not set +# CONFIG_RINGBUF_PLACE_ISR_FUNCTIONS_INTO_FLASH is not set +# end of ESP Ringbuf + # # ESP System Settings # @@ -470,6 +492,10 @@ CONFIG_ESP32_WIFI_DYNAMIC_RX_BUFFER_NUM=16 CONFIG_ESP32_WIFI_DYNAMIC_TX_BUFFER=y CONFIG_ESP32_WIFI_TX_BUFFER_TYPE=1 CONFIG_ESP32_WIFI_DYNAMIC_TX_BUFFER_NUM=16 +CONFIG_ESP_WIFI_STATIC_RX_MGMT_BUFFER=y +# CONFIG_ESP_WIFI_DYNAMIC_RX_MGMT_BUFFER is not set +CONFIG_ESP_WIFI_DYNAMIC_RX_MGMT_BUF=0 +CONFIG_ESP_WIFI_RX_MGMT_BUF_NUM_DEF=5 # CONFIG_ESP32_WIFI_CSI_ENABLED is not set # CONFIG_ESP32_WIFI_AMPDU_TX_ENABLED is not set # CONFIG_ESP32_WIFI_AMPDU_RX_ENABLED is not set @@ -485,6 +511,8 @@ CONFIG_ESP32_WIFI_ENABLE_WPA3_SAE=y # CONFIG_ESP_WIFI_STA_DISCONNECTED_PM_ENABLE is not set # CONFIG_ESP_WIFI_GMAC_SUPPORT is not set CONFIG_ESP_WIFI_SOFTAP_SUPPORT=y +# CONFIG_ESP_WIFI_SLP_BEACON_LOST_OPT is not set +CONFIG_ESP_WIFI_ESPNOW_MAX_ENCRYPT_NUM=7 # end of Wi-Fi # @@ -498,8 +526,10 @@ CONFIG_ESP_COREDUMP_DATA_FORMAT_ELF=y CONFIG_ESP_COREDUMP_CHECKSUM_CRC32=y # CONFIG_ESP_COREDUMP_CHECKSUM_SHA256 is not set CONFIG_ESP_COREDUMP_ENABLE=y +CONFIG_ESP_COREDUMP_LOGS=y CONFIG_ESP_COREDUMP_MAX_TASKS_NUM=64 CONFIG_ESP_COREDUMP_UART_DELAY=0 +CONFIG_ESP_COREDUMP_STACK_SIZE=0 CONFIG_ESP_COREDUMP_DECODE_INFO=y # CONFIG_ESP_COREDUMP_DECODE_DISABLE is not set CONFIG_ESP_COREDUMP_DECODE="info" @@ -632,7 +662,9 @@ CONFIG_LOG_TIMESTAMP_SOURCE_RTOS=y # CONFIG_LWIP_LOCAL_HOSTNAME="espressif" # CONFIG_LWIP_NETIF_API is not set +CONFIG_LWIP_TCPIP_TASK_PRIO=18 # CONFIG_LWIP_TCPIP_CORE_LOCKING is not set +# CONFIG_LWIP_CHECK_THREAD_SAFETY is not set CONFIG_LWIP_DNS_SUPPORT_MDNS_QUERIES=y # CONFIG_LWIP_L2_TO_L3_COPY is not set # CONFIG_LWIP_IRAM_OPTIMIZATION is not set @@ -653,12 +685,15 @@ CONFIG_LWIP_IP6_FRAG=y # CONFIG_LWIP_ETHARP_TRUST_IP_MAC is not set CONFIG_LWIP_ESP_GRATUITOUS_ARP=y CONFIG_LWIP_GARP_TMR_INTERVAL=60 +CONFIG_LWIP_ESP_MLDV6_REPORT=y +CONFIG_LWIP_MLDV6_TMR_INTERVAL=40 CONFIG_LWIP_TCPIP_RECVMBOX_SIZE=32 CONFIG_LWIP_DHCP_DOES_ARP_CHECK=y # CONFIG_LWIP_DHCP_DISABLE_CLIENT_ID is not set CONFIG_LWIP_DHCP_DISABLE_VENDOR_CLASS_ID=y # CONFIG_LWIP_DHCP_RESTORE_LAST_IP is not set CONFIG_LWIP_DHCP_OPTIONS_LEN=68 +CONFIG_LWIP_DHCP_COARSE_TIMER_SECS=1 # # DHCP server @@ -688,10 +723,13 @@ CONFIG_LWIP_TCP_SYNMAXRTX=6 CONFIG_LWIP_TCP_MSS=1436 CONFIG_LWIP_TCP_TMR_INTERVAL=250 CONFIG_LWIP_TCP_MSL=60000 +CONFIG_LWIP_TCP_FIN_WAIT_TIMEOUT=20000 CONFIG_LWIP_TCP_SND_BUF_DEFAULT=5744 CONFIG_LWIP_TCP_WND_DEFAULT=5744 CONFIG_LWIP_TCP_RECVMBOX_SIZE=6 CONFIG_LWIP_TCP_QUEUE_OOSEQ=y +CONFIG_LWIP_TCP_OOSEQ_TIMEOUT=6 +CONFIG_LWIP_TCP_OOSEQ_MAX_PBUFS=4 # CONFIG_LWIP_TCP_SACK_OUT is not set # CONFIG_LWIP_TCP_KEEP_CONNECTION_WHEN_IP_CHANGES is not set CONFIG_LWIP_TCP_OVERSIZE_MSS=y @@ -803,6 +841,7 @@ CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_FULL=y # CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_CMN is not set # CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_DEFAULT_NONE is not set # CONFIG_MBEDTLS_CUSTOM_CERTIFICATE_BUNDLE is not set +CONFIG_MBEDTLS_CERTIFICATE_BUNDLE_MAX_CERTS=200 # end of Certificate Bundle # CONFIG_MBEDTLS_ECP_RESTARTABLE is not set @@ -921,6 +960,7 @@ CONFIG_NEWLIB_STDIN_LINE_ENDING_CR=y # # NVS # +# CONFIG_NVS_ASSERT_ERROR_CHECK is not set # end of NVS # @@ -989,7 +1029,6 @@ CONFIG_VFS_SUPPORT_TERMIOS=y # Host File System I/O (Semihosting) # CONFIG_VFS_SEMIHOSTFS_MAX_MOUNT_POINTS=1 -CONFIG_VFS_SEMIHOSTFS_HOST_PATH_MAX_LEN=128 # end of Host File System I/O (Semihosting) # end of Virtual file system @@ -1131,6 +1170,7 @@ CONFIG_ESP32_COREDUMP_CHECKSUM_CRC32=y CONFIG_ESP32_ENABLE_COREDUMP=y CONFIG_ESP32_CORE_DUMP_MAX_TASKS_NUM=64 CONFIG_ESP32_CORE_DUMP_UART_DELAY=0 +CONFIG_ESP32_CORE_DUMP_STACK_SIZE=0 CONFIG_ESP32_CORE_DUMP_DECODE_INFO=y # CONFIG_ESP32_CORE_DUMP_DECODE_DISABLE is not set CONFIG_ESP32_CORE_DUMP_DECODE="info" @@ -1176,5 +1216,4 @@ CONFIG_SPI_FLASH_WRITING_DANGEROUS_REGIONS_ABORTS=y CONFIG_SUPPRESS_SELECT_DEBUG_OUTPUT=y CONFIG_SUPPORT_TERMIOS=y CONFIG_SEMIHOSTFS_MAX_MOUNT_POINTS=1 -CONFIG_SEMIHOSTFS_HOST_PATH_MAX_LEN=128 # End of deprecated options From b03728853ed8ebeed23d6f8bb6cc7a6f1e8bcd4a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 7 Jan 2024 08:31:15 +1100 Subject: [PATCH 0404/1335] Tools: allow CPUInfo to build on systems without ESC telem --- Tools/CPUInfo/CPUInfo.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Tools/CPUInfo/CPUInfo.cpp b/Tools/CPUInfo/CPUInfo.cpp index 05409f1418df5e..3e99d61982abad 100644 --- a/Tools/CPUInfo/CPUInfo.cpp +++ b/Tools/CPUInfo/CPUInfo.cpp @@ -46,7 +46,9 @@ static uint32_t sysclk = 0; static EKF_Maths ekf; HAL_Semaphore sem; +#if HAL_WITH_ESC_TELEM AP_ESC_Telem telem; +#endif void setup() { #ifdef DISABLE_CACHES From 977b5dfe33f48f1b16ea07cbaad032d05fad085e Mon Sep 17 00:00:00 2001 From: David Buzz Date: Sat, 6 Jan 2024 13:56:46 +1000 Subject: [PATCH 0405/1335] Tools: DynamicRpmNotches is mostly within 5% but 10% prevents the test from flapping as much --- Tools/autotest/arducopter.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index 6be401624fca11..d89ffa43f5ea63 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -5928,8 +5928,8 @@ def DynamicRpmNotches(self): freq, hover_throttle, peakdb2 = self.hover_and_check_matched_frequency_with_fft(-15, 20, 350, reverse=True) - # notch-per-motor should do better, but check for within 5% - if peakdb2 * 1.05 > peakdb1: + # notch-per-motor should do better, but check for within 10%. ( its mostly within 5%, but does vary a bit) + if peakdb2 * 1.10 > peakdb1: raise NotAchievedException( "Notch-per-motor peak was higher than single-notch peak %fdB > %fdB" % (peakdb2, peakdb1)) From dff9a7742e4a00fcfbb8867501eb53ebec98ae49 Mon Sep 17 00:00:00 2001 From: Michelle Rossouw Date: Fri, 5 Jan 2024 17:07:40 +1100 Subject: [PATCH 0406/1335] AP_Scripting: Add CAN_Logger example script Co-authored-by: Andrew Tridgell --- .../AP_Scripting/examples/CAN_logger.lua | 52 +++++++++++++++++++ 1 file changed, 52 insertions(+) create mode 100644 libraries/AP_Scripting/examples/CAN_logger.lua diff --git a/libraries/AP_Scripting/examples/CAN_logger.lua b/libraries/AP_Scripting/examples/CAN_logger.lua new file mode 100644 index 00000000000000..aa3c5ff990a643 --- /dev/null +++ b/libraries/AP_Scripting/examples/CAN_logger.lua @@ -0,0 +1,52 @@ +--[[ + This script captures raw packets to a log file for later playback using Tools/scripts/CAN/CAN_playback.py onto a CAN bus. + Set CAN_D1_PROTOCOL to 10 for scripting. + Also need LOG_DISARMED set to 1 if running this while disarmed. +--]] + +local can_driver = CAN:get_device(25) + +if not can_driver then + gcs:send_text(0,"No scripting CAN interface found") + return +end + +local last_print_ms = millis() +local frame_count = 0 +local last_frame_count = 0 + +function update() + + local more_frames = true + for _ = 1, 25 do + local frame = can_driver:read_frame() + if not frame then + more_frames = false + break + end + local id = frame:id() + logger.write("CANF",'Id,DLC,FC,B0,B1,B2,B3,B4,B5,B6,B7','IBIBBBBBBBB', + id, + frame:dlc(), + frame_count, + frame:data(0), frame:data(1), frame:data(2), frame:data(3), + frame:data(4), frame:data(5), frame:data(6), frame:data(7)) + frame_count = frame_count + 1 + end + + local now = millis() + if now - last_print_ms >= 1000 then + local dt = (now - last_print_ms):tofloat()*0.001 + gcs:send_text(0, string.format("CAN: %.2f fps", (frame_count-last_frame_count)/dt)) + last_print_ms = now + last_frame_count = frame_count + end + + if more_frames then + -- sleep for min possible time to try not to lose frames + return update, 0 + end + return update, 2 +end + +return update() From 30ad0560f459eb281b680d64150d605925cab15f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 6 Jan 2024 12:37:58 +1100 Subject: [PATCH 0407/1335] Tools: added CAN playback tool uses frames from lua CAN bus capture and plays back for driver development --- Tools/scripts/CAN/CAN_playback.py | 52 +++++++++++++++++++++++++++++++ 1 file changed, 52 insertions(+) create mode 100755 Tools/scripts/CAN/CAN_playback.py diff --git a/Tools/scripts/CAN/CAN_playback.py b/Tools/scripts/CAN/CAN_playback.py new file mode 100755 index 00000000000000..bdd4825f4fa221 --- /dev/null +++ b/Tools/scripts/CAN/CAN_playback.py @@ -0,0 +1,52 @@ +#!/usr/bin/env python3 +''' +playback a set of CAN frames from libraries/AP_Scripting/examples/CAN_logger.lua onto a CAN bus +''' + +import dronecan +import time +import sys +import threading +from pymavlink import mavutil +from dronecan.driver.common import CANFrame + + +# get command line arguments +from argparse import ArgumentParser +parser = ArgumentParser(description='CAN playback') +parser.add_argument("logfile", default=None, type=str, help="logfile") +parser.add_argument("canport", default=None, type=str, help="CAN port") + +args = parser.parse_args() + +print("Connecting to %s" % args.canport) +driver = dronecan.driver.make_driver(args.canport) + +print("Opening %s" % args.logfile) +mlog = mavutil.mavlink_connection(args.logfile) + +tstart = time.time() +first_tstamp = None + +while True: + m = mlog.recv_match(type='CANF') + + if m is None: + print("Rewinding") + mlog.rewind() + tstart = time.time() + first_tstamp = None + continue + + if first_tstamp is None: + first_tstamp = m.TimeUS + dt = time.time() - tstart + dt2 = (m.TimeUS - first_tstamp)*1.0e-6 + if dt2 > dt: + time.sleep(dt2 - dt) + data = [m.B0, m.B1, m.B2, m.B3, m.B4, m.B5, m.B6, m.B7] + data = data[:m.DLC] + fid = m.Id + is_extended = (fid & (1<<31)) != 0 + driver.send(fid, data, extended=is_extended, canfd=False) + print(m) From 5560bd8ed862c5ba961eaf8bc4702ad51f14dca2 Mon Sep 17 00:00:00 2001 From: David Buzz Date: Sun, 7 Jan 2024 15:29:39 +1000 Subject: [PATCH 0408/1335] esp32 CI typo, sorry tridge --- .github/workflows/esp32_build.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/esp32_build.yml b/.github/workflows/esp32_build.yml index d1eb1c8c456ada..7f2a11bf060ca8 100644 --- a/.github/workflows/esp32_build.yml +++ b/.github/workflows/esp32_build.yml @@ -145,7 +145,7 @@ concurrency: jobs: build: - runs-on: ubuntu-23.04 + runs-on: ubuntu-22.04 strategy: fail-fast: false # don't cancel if a job from the matrix fails matrix: From 678474614f0d5a65cc5fe1a7ba7e35536e68c24e Mon Sep 17 00:00:00 2001 From: David Buzz Date: Sun, 7 Jan 2024 16:57:43 +1000 Subject: [PATCH 0409/1335] AP_HAL_ESP32: Update the WiFi init code to the newer ESP-IDF (4.2+) and mostly by TByte007 from here, but fixed and re-tested. https://github.com/ArduPilot/ardupilot/pull/24527/commits --- libraries/AP_HAL_ESP32/WiFiDriver.cpp | 164 ++++++++++++++++++++--- libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp | 161 +++++++++++++++++++--- libraries/AP_HAL_ESP32/WiFiUdpDriver.h | 3 + 3 files changed, 292 insertions(+), 36 deletions(-) diff --git a/libraries/AP_HAL_ESP32/WiFiDriver.cpp b/libraries/AP_HAL_ESP32/WiFiDriver.cpp index 43c9135e15d876..bc57391f009311 100644 --- a/libraries/AP_HAL_ESP32/WiFiDriver.cpp +++ b/libraries/AP_HAL_ESP32/WiFiDriver.cpp @@ -24,6 +24,7 @@ #include "esp_system.h" #include "esp_wifi.h" #include "esp_event.h" +#include "esp_log.h" #include "nvs_flash.h" #include "lwip/err.h" @@ -208,31 +209,158 @@ bool WiFiDriver::write_data() return true; } +#if WIFI_STATION + +#define WIFI_CONNECTED_BIT BIT0 +#define WIFI_FAIL_BIT BIT1 + +#ifndef ESP_STATION_MAXIMUM_RETRY +#define ESP_STATION_MAXIMUM_RETRY 10 +#endif + +static const char *TAG = "wifi station"; +static int s_retry_num = 0; +static EventGroupHandle_t s_wifi_event_group; + +static void _sta_event_handler(void* arg, esp_event_base_t event_base, + int32_t event_id, void* event_data) +{ + if (event_base == WIFI_EVENT && event_id == WIFI_EVENT_STA_START) { + esp_wifi_connect(); + } else if (event_base == WIFI_EVENT && event_id == WIFI_EVENT_STA_DISCONNECTED) { + if (s_retry_num < ESP_STATION_MAXIMUM_RETRY) { + esp_wifi_connect(); + s_retry_num++; + ESP_LOGI(TAG, "retry to connect to the AP"); + } else { + xEventGroupSetBits(s_wifi_event_group, WIFI_FAIL_BIT); + } + ESP_LOGI(TAG,"connect to the AP fail"); + } else if (event_base == IP_EVENT && event_id == IP_EVENT_STA_GOT_IP) { + s_retry_num = 0; + xEventGroupSetBits(s_wifi_event_group, WIFI_CONNECTED_BIT); + } +} +#endif + void WiFiDriver::initialize_wifi() { - tcpip_adapter_init(); - nvs_flash_init(); - esp_event_loop_init(nullptr, nullptr); - wifi_init_config_t cfg = WIFI_INIT_CONFIG_DEFAULT(); - esp_wifi_init(&cfg); - esp_wifi_set_storage(WIFI_STORAGE_FLASH); +#ifndef WIFI_PWD + #default WIFI_PWD "ardupilot1" +#endif + //Initialize NVS + esp_err_t ret = nvs_flash_init(); + if (ret == ESP_ERR_NVS_NO_FREE_PAGES || ret == ESP_ERR_NVS_NEW_VERSION_FOUND) { + ESP_ERROR_CHECK(nvs_flash_erase()); + ret = nvs_flash_init(); + } + ESP_ERROR_CHECK(ret); + + ESP_ERROR_CHECK(esp_netif_init()); + ESP_ERROR_CHECK(esp_event_loop_create_default()); + wifi_config_t wifi_config; - memset(&wifi_config, 0, sizeof(wifi_config)); -#ifdef WIFI_SSID - strcpy((char *)wifi_config.ap.ssid, WIFI_SSID); -#else - strcpy((char *)wifi_config.ap.ssid, "ardupilot"); + bzero(&wifi_config, sizeof(wifi_config)); + +/* + Acting as an Access Point (softAP) +*/ +#if !WIFI_STATION +#ifndef WIFI_SSID + #define WIFI_SSID "ardupilot" #endif -#ifdef WIFI_PWD +#ifndef WIFI_CHANNEL + #define WIFI_CHANNEL 1 +#endif + + esp_netif_create_default_wifi_ap(); + + wifi_init_config_t cfg = WIFI_INIT_CONFIG_DEFAULT(); + ESP_ERROR_CHECK(esp_wifi_init(&cfg)); + + + strcpy((char *)wifi_config.ap.ssid, WIFI_SSID); strcpy((char *)wifi_config.ap.password, WIFI_PWD); + wifi_config.ap.ssid_len = strlen(WIFI_SSID), + wifi_config.ap.max_connection = WIFI_MAX_CONNECTION, + wifi_config.ap.authmode = WIFI_AUTH_WPA2_PSK; + wifi_config.ap.channel = WIFI_CHANNEL; + + if (strlen(WIFI_PWD) == 0) { + wifi_config.ap.authmode = WIFI_AUTH_OPEN; + } + + ESP_ERROR_CHECK(esp_wifi_set_mode(WIFI_MODE_AP)); + ESP_ERROR_CHECK(esp_wifi_set_config(WIFI_IF_AP, &wifi_config)); + ESP_ERROR_CHECK(esp_wifi_start()); + + hal.console->printf("WiFi softAP init finished. SSID: %s password: %s channel: %d\n", + wifi_config.ap.ssid, wifi_config.ap.password, wifi_config.ap.channel); + +/* + Acting as a Station (WiFi Client) +*/ #else - strcpy((char *)wifi_config.ap.password, "ardupilot1"); +#ifndef WIFI_SSID_STATION + #define WIFI_SSID_STATION "ardupilot" +#endif +#ifndef WIFI_HOSTNAME + #define WIFI_HOSTNAME "ArduPilotESP32" +#endif + s_wifi_event_group = xEventGroupCreate(); + esp_netif_t *netif = esp_netif_create_default_wifi_sta(); + esp_netif_set_hostname(netif, WIFI_HOSTNAME); + + wifi_init_config_t cfg = WIFI_INIT_CONFIG_DEFAULT(); + ESP_ERROR_CHECK(esp_wifi_init(&cfg)); + + esp_event_handler_instance_t instance_any_id; + esp_event_handler_instance_t instance_got_ip; + ESP_ERROR_CHECK(esp_event_handler_instance_register(WIFI_EVENT, + ESP_EVENT_ANY_ID, + &_sta_event_handler, + NULL, + &instance_any_id)); + ESP_ERROR_CHECK(esp_event_handler_instance_register(IP_EVENT, + IP_EVENT_STA_GOT_IP, + &_sta_event_handler, + NULL, + &instance_got_ip)); + + strcpy((char *)wifi_config.sta.ssid, WIFI_SSID_STATION); + strcpy((char *)wifi_config.sta.password, WIFI_PWD); + wifi_config.sta.threshold.authmode = WIFI_AUTH_OPEN; + wifi_config.sta.sae_pwe_h2e = WPA3_SAE_PWE_BOTH; + + ESP_ERROR_CHECK(esp_wifi_set_mode(WIFI_MODE_STA) ); + ESP_ERROR_CHECK(esp_wifi_set_config(WIFI_IF_STA, &wifi_config) ); + ESP_ERROR_CHECK(esp_wifi_start() ); + + hal.console->printf("WiFi Station init finished. Connecting:\n"); + + /* Waiting until either the connection is established (WIFI_CONNECTED_BIT) or connection failed for the maximum + * number of re-tries (WIFI_FAIL_BIT). The bits are set by event_handler() (see above) */ + EventBits_t bits = xEventGroupWaitBits(s_wifi_event_group, + WIFI_CONNECTED_BIT | WIFI_FAIL_BIT, + pdFALSE, pdFALSE, portMAX_DELAY); + + /* xEventGroupWaitBits() returns the bits before the call returned, hence we can test which event actually + * happened. */ + if (bits & WIFI_CONNECTED_BIT) { + ESP_LOGI(TAG, "connected to ap SSID: %s password: %s", + wifi_config.sta.ssid, wifi_config.sta.password); + } else if (bits & WIFI_FAIL_BIT) { + ESP_LOGI(TAG, "Failed to connect to SSID: %s, password: %s", + wifi_config.sta.ssid, wifi_config.sta.password); + } else { + ESP_LOGE(TAG, "UNEXPECTED EVENT"); + } + + /* The event will not be processed after unregister */ + ESP_ERROR_CHECK(esp_event_handler_instance_unregister(IP_EVENT, IP_EVENT_STA_GOT_IP, instance_got_ip)); + ESP_ERROR_CHECK(esp_event_handler_instance_unregister(WIFI_EVENT, ESP_EVENT_ANY_ID, instance_any_id)); + vEventGroupDelete(s_wifi_event_group); #endif - wifi_config.ap.authmode = WIFI_AUTH_WPA_WPA2_PSK; - wifi_config.ap.max_connection = WIFI_MAX_CONNECTION; - esp_wifi_set_mode(WIFI_MODE_AP); - esp_wifi_set_config(WIFI_IF_AP, &wifi_config); - esp_wifi_start(); } size_t WiFiDriver::_write(const uint8_t *buffer, size_t size) diff --git a/libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp b/libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp index eb2fbdbec2cb6a..b7a48f4f949cd2 100644 --- a/libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp +++ b/libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp @@ -178,33 +178,158 @@ bool WiFiUdpDriver::write_data() return true; } +#if WIFI_STATION + +#define WIFI_CONNECTED_BIT BIT0 +#define WIFI_FAIL_BIT BIT1 + +#ifndef ESP_STATION_MAXIMUM_RETRY +#define ESP_STATION_MAXIMUM_RETRY 10 +#endif + +static const char *TAG = "wifi station"; +static int s_retry_num = 0; +static EventGroupHandle_t s_wifi_event_group; + +static void _sta_event_handler(void* arg, esp_event_base_t event_base, + int32_t event_id, void* event_data) +{ + if (event_base == WIFI_EVENT && event_id == WIFI_EVENT_STA_START) { + esp_wifi_connect(); + } else if (event_base == WIFI_EVENT && event_id == WIFI_EVENT_STA_DISCONNECTED) { + if (s_retry_num < ESP_STATION_MAXIMUM_RETRY) { + esp_wifi_connect(); + s_retry_num++; + ESP_LOGI(TAG, "retry to connect to the AP"); + } else { + xEventGroupSetBits(s_wifi_event_group, WIFI_FAIL_BIT); + } + ESP_LOGI(TAG,"connect to the AP fail"); + } else if (event_base == IP_EVENT && event_id == IP_EVENT_STA_GOT_IP) { + s_retry_num = 0; + xEventGroupSetBits(s_wifi_event_group, WIFI_CONNECTED_BIT); + } +} +#endif + void WiFiUdpDriver::initialize_wifi() { - esp_event_loop_init(nullptr, nullptr); +#ifndef WIFI_PWD + #default WIFI_PWD "ardupilot1" +#endif + //Initialize NVS + esp_err_t ret = nvs_flash_init(); + if (ret == ESP_ERR_NVS_NO_FREE_PAGES || ret == ESP_ERR_NVS_NEW_VERSION_FOUND) { + ESP_ERROR_CHECK(nvs_flash_erase()); + ret = nvs_flash_init(); + } + ESP_ERROR_CHECK(ret); - tcpip_adapter_init(); - nvs_flash_init(); + ESP_ERROR_CHECK(esp_netif_init()); + ESP_ERROR_CHECK(esp_event_loop_create_default()); - wifi_init_config_t cfg = WIFI_INIT_CONFIG_DEFAULT(); - esp_wifi_init(&cfg); - esp_wifi_set_storage(WIFI_STORAGE_FLASH); wifi_config_t wifi_config; - memset(&wifi_config, 0, sizeof(wifi_config)); -#ifdef WIFI_SSID - strcpy((char *)wifi_config.ap.ssid, WIFI_SSID); -#else - strcpy((char *)wifi_config.ap.ssid, "ardupilot"); + bzero(&wifi_config, sizeof(wifi_config)); + +/* + Acting as an Access Point (softAP) +*/ +#if !WIFI_STATION +#ifndef WIFI_SSID + #define WIFI_SSID "ardupilot" +#endif +#ifndef WIFI_CHANNEL + #define WIFI_CHANNEL 1 #endif -#ifdef WIFI_PWD + + esp_netif_create_default_wifi_ap(); + + wifi_init_config_t cfg = WIFI_INIT_CONFIG_DEFAULT(); + ESP_ERROR_CHECK(esp_wifi_init(&cfg)); + + + strcpy((char *)wifi_config.ap.ssid, WIFI_SSID); strcpy((char *)wifi_config.ap.password, WIFI_PWD); + wifi_config.ap.ssid_len = strlen(WIFI_SSID), + wifi_config.ap.max_connection = WIFI_MAX_CONNECTION, + wifi_config.ap.authmode = WIFI_AUTH_WPA2_PSK; + wifi_config.ap.channel = WIFI_CHANNEL; + + if (strlen(WIFI_PWD) == 0) { + wifi_config.ap.authmode = WIFI_AUTH_OPEN; + } + + ESP_ERROR_CHECK(esp_wifi_set_mode(WIFI_MODE_AP)); + ESP_ERROR_CHECK(esp_wifi_set_config(WIFI_IF_AP, &wifi_config)); + ESP_ERROR_CHECK(esp_wifi_start()); + + hal.console->printf("WiFi softAP init finished. SSID: %s password: %s channel: %d\n", + wifi_config.ap.ssid, wifi_config.ap.password, wifi_config.ap.channel); + +/* + Acting as a Station (WiFi Client) +*/ #else - strcpy((char *)wifi_config.ap.password, "ardupilot1"); +#ifndef WIFI_SSID_STATION + #define WIFI_SSID_STATION "ardupilot" +#endif +#ifndef WIFI_HOSTNAME + #define WIFI_HOSTNAME "ArduPilotESP32" +#endif + s_wifi_event_group = xEventGroupCreate(); + esp_netif_t *netif = esp_netif_create_default_wifi_sta(); + esp_netif_set_hostname(netif, WIFI_HOSTNAME); + + wifi_init_config_t cfg = WIFI_INIT_CONFIG_DEFAULT(); + ESP_ERROR_CHECK(esp_wifi_init(&cfg)); + + esp_event_handler_instance_t instance_any_id; + esp_event_handler_instance_t instance_got_ip; + ESP_ERROR_CHECK(esp_event_handler_instance_register(WIFI_EVENT, + ESP_EVENT_ANY_ID, + &_sta_event_handler, + NULL, + &instance_any_id)); + ESP_ERROR_CHECK(esp_event_handler_instance_register(IP_EVENT, + IP_EVENT_STA_GOT_IP, + &_sta_event_handler, + NULL, + &instance_got_ip)); + + strcpy((char *)wifi_config.sta.ssid, WIFI_SSID_STATION); + strcpy((char *)wifi_config.sta.password, WIFI_PWD); + wifi_config.sta.threshold.authmode = WIFI_AUTH_OPEN; + wifi_config.sta.sae_pwe_h2e = WPA3_SAE_PWE_BOTH; + + ESP_ERROR_CHECK(esp_wifi_set_mode(WIFI_MODE_STA) ); + ESP_ERROR_CHECK(esp_wifi_set_config(WIFI_IF_STA, &wifi_config) ); + ESP_ERROR_CHECK(esp_wifi_start() ); + + hal.console->printf("WiFi Station init finished. Connecting:\n"); + + /* Waiting until either the connection is established (WIFI_CONNECTED_BIT) or connection failed for the maximum + * number of re-tries (WIFI_FAIL_BIT). The bits are set by event_handler() (see above) */ + EventBits_t bits = xEventGroupWaitBits(s_wifi_event_group, + WIFI_CONNECTED_BIT | WIFI_FAIL_BIT, + pdFALSE, pdFALSE, portMAX_DELAY); + + /* xEventGroupWaitBits() returns the bits before the call returned, hence we can test which event actually + * happened. */ + if (bits & WIFI_CONNECTED_BIT) { + ESP_LOGI(TAG, "connected to ap SSID: %s password: %s", + wifi_config.sta.ssid, wifi_config.sta.password); + } else if (bits & WIFI_FAIL_BIT) { + ESP_LOGI(TAG, "Failed to connect to SSID: %s, password: %s", + wifi_config.sta.ssid, wifi_config.sta.password); + } else { + ESP_LOGE(TAG, "UNEXPECTED EVENT"); + } + + /* The event will not be processed after unregister */ + ESP_ERROR_CHECK(esp_event_handler_instance_unregister(IP_EVENT, IP_EVENT_STA_GOT_IP, instance_got_ip)); + ESP_ERROR_CHECK(esp_event_handler_instance_unregister(WIFI_EVENT, ESP_EVENT_ANY_ID, instance_any_id)); + vEventGroupDelete(s_wifi_event_group); #endif - wifi_config.ap.authmode = WIFI_AUTH_WPA_WPA2_PSK; - wifi_config.ap.max_connection = 4; - esp_wifi_set_mode(WIFI_MODE_AP); - esp_wifi_set_config(WIFI_IF_AP, &wifi_config); - esp_wifi_start(); } size_t WiFiUdpDriver::_write(const uint8_t *buffer, size_t size) diff --git a/libraries/AP_HAL_ESP32/WiFiUdpDriver.h b/libraries/AP_HAL_ESP32/WiFiUdpDriver.h index 9b11464e35aba5..e59b4d1b1104b0 100644 --- a/libraries/AP_HAL_ESP32/WiFiUdpDriver.h +++ b/libraries/AP_HAL_ESP32/WiFiUdpDriver.h @@ -22,6 +22,9 @@ #include "lwip/sockets.h" #include "esp_event.h" +#ifndef WIFI_MAX_CONNECTION +#define WIFI_MAX_CONNECTION 5 +#endif class ESP32::WiFiUdpDriver : public AP_HAL::UARTDriver { From 9e8c16d15e6e57be90a1033251c86e98a9ab4c4a Mon Sep 17 00:00:00 2001 From: David Buzz Date: Sun, 7 Jan 2024 16:45:48 +1000 Subject: [PATCH 0410/1335] AP_HAL_ESP32: S3 also needs change to storage sector size to 128K just completing this PR for the S3.. https://github.com/ArduPilot/ardupilot/commit/fa70a56a65533caa6c509eaf9ebfdd521568c3c3 --- libraries/AP_HAL_ESP32/targets/esp32s3/partitions.csv | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ESP32/targets/esp32s3/partitions.csv b/libraries/AP_HAL_ESP32/targets/esp32s3/partitions.csv index 70f23f3af89566..8a292ba165f517 100644 --- a/libraries/AP_HAL_ESP32/targets/esp32s3/partitions.csv +++ b/libraries/AP_HAL_ESP32/targets/esp32s3/partitions.csv @@ -2,4 +2,4 @@ nvs, data, nvs, , 0x6000 phy_init, data, phy, , 0x1000 factory, app, factory, , 3M -storage, 0x45, 0x0, , 128K +storage, 0x45, 0x0, , 256K From 08a09d04dc091336253e31fd9365f75f27644878 Mon Sep 17 00:00:00 2001 From: David Buzz Date: Tue, 2 Jan 2024 09:46:09 +1000 Subject: [PATCH 0411/1335] HAL_ESP32: bring S3's sdkconfig closer to classic , and optimise wifi on classic --- .../targets/esp32/esp-idf/sdkconfig | 2 +- .../targets/esp32s3/esp-idf/sdkconfig | 79 ++++++++++++------- 2 files changed, 51 insertions(+), 30 deletions(-) diff --git a/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/sdkconfig b/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/sdkconfig index 725b24a4a3b6e6..e1a5a3b0da288b 100644 --- a/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/sdkconfig +++ b/libraries/AP_HAL_ESP32/targets/esp32/esp-idf/sdkconfig @@ -504,7 +504,7 @@ CONFIG_ESP32_WIFI_TASK_PINNED_TO_CORE_0=y # CONFIG_ESP32_WIFI_TASK_PINNED_TO_CORE_1 is not set CONFIG_ESP32_WIFI_SOFTAP_BEACON_MAX_LEN=752 CONFIG_ESP32_WIFI_MGMT_SBUF_NUM=32 -# CONFIG_ESP32_WIFI_IRAM_OPT is not set +CONFIG_ESP32_WIFI_IRAM_OPT=y CONFIG_ESP32_WIFI_RX_IRAM_OPT=y CONFIG_ESP32_WIFI_ENABLE_WPA3_SAE=y # CONFIG_ESP_WIFI_SLP_IRAM_OPT is not set diff --git a/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/sdkconfig b/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/sdkconfig index 4ec0f241db1a68..3d841f1251b122 100644 --- a/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/sdkconfig +++ b/libraries/AP_HAL_ESP32/targets/esp32s3/esp-idf/sdkconfig @@ -28,9 +28,9 @@ CONFIG_APP_BUILD_USE_FLASH_SECTIONS=y # # Application manager # -CONFIG_APP_COMPILE_TIME_DATE=y -# CONFIG_APP_EXCLUDE_PROJECT_VER_VAR is not set -# CONFIG_APP_EXCLUDE_PROJECT_NAME_VAR is not set +# CONFIG_APP_COMPILE_TIME_DATE is not set +CONFIG_APP_EXCLUDE_PROJECT_VER_VAR=y +CONFIG_APP_EXCLUDE_PROJECT_NAME_VAR=y # CONFIG_APP_PROJECT_VER_FROM_CONFIG is not set CONFIG_APP_RETRIEVE_LEN_ELF_SHA=16 # end of Application manager @@ -70,8 +70,6 @@ CONFIG_BOOTLOADER_FLASH_XMC_SUPPORT=y # # Security features # -CONFIG_SECURE_BOOT_SUPPORTS_RSA=y -CONFIG_SECURE_TARGET_HAS_SECURE_ROM_DL_MODE=y # CONFIG_SECURE_SIGNED_APPS_NO_SECURE_BOOT is not set # CONFIG_SECURE_BOOT is not set # CONFIG_SECURE_FLASH_ENC_ENABLED is not set @@ -98,11 +96,11 @@ CONFIG_ESPTOOLPY_FLASHMODE_DIO=y # CONFIG_ESPTOOLPY_FLASHMODE_DOUT is not set CONFIG_ESPTOOLPY_FLASH_SAMPLE_MODE_STR=y CONFIG_ESPTOOLPY_FLASHMODE="dio" -# CONFIG_ESPTOOLPY_FLASHFREQ_120M is not set -# CONFIG_ESPTOOLPY_FLASHFREQ_80M is not set -CONFIG_ESPTOOLPY_FLASHFREQ_40M=y +CONFIG_ESPTOOLPY_FLASHFREQ_80M=y +# CONFIG_ESPTOOLPY_FLASHFREQ_40M is not set +# CONFIG_ESPTOOLPY_FLASHFREQ_26M is not set # CONFIG_ESPTOOLPY_FLASHFREQ_20M is not set -CONFIG_ESPTOOLPY_FLASHFREQ="40m" +CONFIG_ESPTOOLPY_FLASHFREQ="80m" # CONFIG_ESPTOOLPY_FLASHSIZE_1MB is not set # CONFIG_ESPTOOLPY_FLASHSIZE_2MB is not set # CONFIG_ESPTOOLPY_FLASHSIZE_4MB is not set @@ -147,9 +145,9 @@ CONFIG_PARTITION_TABLE_MD5=y # # Compiler options # -CONFIG_COMPILER_OPTIMIZATION_DEFAULT=y +# CONFIG_COMPILER_OPTIMIZATION_DEFAULT is not set # CONFIG_COMPILER_OPTIMIZATION_SIZE is not set -# CONFIG_COMPILER_OPTIMIZATION_PERF is not set +CONFIG_COMPILER_OPTIMIZATION_PERF=y # CONFIG_COMPILER_OPTIMIZATION_NONE is not set CONFIG_COMPILER_OPTIMIZATION_ASSERTIONS_ENABLE=y # CONFIG_COMPILER_OPTIMIZATION_ASSERTIONS_SILENT is not set @@ -200,7 +198,7 @@ CONFIG_ADC_DISABLE_DAC=y # # SPI configuration # -# CONFIG_SPI_MASTER_IN_IRAM is not set +CONFIG_SPI_MASTER_IN_IRAM=y CONFIG_SPI_MASTER_ISR_IN_IRAM=y # CONFIG_SPI_SLAVE_IN_IRAM is not set CONFIG_SPI_SLAVE_ISR_IN_IRAM=y @@ -238,9 +236,9 @@ CONFIG_EFUSE_MAX_BLK_LEN=256 # ESP32S3-Specific # # CONFIG_ESP32S3_DEFAULT_CPU_FREQ_80 is not set -CONFIG_ESP32S3_DEFAULT_CPU_FREQ_160=y -# CONFIG_ESP32S3_DEFAULT_CPU_FREQ_240 is not set -CONFIG_ESP32S3_DEFAULT_CPU_FREQ_MHZ=160 +#CONFIG_ESP32S3_DEFAULT_CPU_FREQ_160 is not set +CONFIG_ESP32S3_DEFAULT_CPU_FREQ_240=y +CONFIG_ESP32S3_DEFAULT_CPU_FREQ_MHZ=240 # # Cache config @@ -302,6 +300,9 @@ CONFIG_ESP32S3_DEEP_SLEEP_WAKEUP_DELAY=2000 # # ADC-Calibration # +CONFIG_ADC_CAL_EFUSE_TP_ENABLE=y +CONFIG_ADC_CAL_EFUSE_VREF_ENABLE=y +CONFIG_ADC_CAL_LUT_ENABLE=y # end of ADC-Calibration # @@ -345,15 +346,15 @@ CONFIG_ESP_MAC_ADDR_UNIVERSE_WIFI_STA=y CONFIG_ESP_MAC_ADDR_UNIVERSE_WIFI_AP=y CONFIG_ESP_MAC_ADDR_UNIVERSE_BT=y CONFIG_ESP_MAC_ADDR_UNIVERSE_ETH=y -# CONFIG_ESP32S3_UNIVERSAL_MAC_ADDRESSES_TWO is not set -CONFIG_ESP32S3_UNIVERSAL_MAC_ADDRESSES_FOUR=y -CONFIG_ESP32S3_UNIVERSAL_MAC_ADDRESSES=4 +CONFIG_ESP32S3_UNIVERSAL_MAC_ADDRESSES_TWO=y +#CONFIG_ESP32S3_UNIVERSAL_MAC_ADDRESSES_FOUR is not set +CONFIG_ESP32S3_UNIVERSAL_MAC_ADDRESSES=2 # end of MAC Config # # Sleep Config # -CONFIG_ESP_SLEEP_POWER_DOWN_FLASH=y +# CONFIG_ESP_SLEEP_POWER_DOWN_FLASH is not set CONFIG_ESP_SLEEP_RTC_BUS_ISO_WORKAROUND=y # CONFIG_ESP_SLEEP_GPIO_RESET_WORKAROUND is not set # CONFIG_ESP_SLEEP_FLASH_LEAKAGE_WORKAROUND is not set @@ -437,7 +438,7 @@ CONFIG_ESP_CONSOLE_MULTIPLE_UART=y CONFIG_ESP_CONSOLE_UART_NUM=0 CONFIG_ESP_CONSOLE_UART_BAUDRATE=115200 CONFIG_ESP_INT_WDT=y -CONFIG_ESP_INT_WDT_TIMEOUT_MS=300 +CONFIG_ESP_INT_WDT_TIMEOUT_MS=1000 CONFIG_ESP_INT_WDT_CHECK_CPU1=y CONFIG_ESP_TASK_WDT=y # CONFIG_ESP_TASK_WDT_PANIC is not set @@ -496,8 +497,18 @@ CONFIG_ESP_WIFI_SOFTAP_SUPPORT=y # Core dump # # CONFIG_ESP_COREDUMP_ENABLE_TO_FLASH is not set -# CONFIG_ESP_COREDUMP_ENABLE_TO_UART is not set -CONFIG_ESP_COREDUMP_ENABLE_TO_NONE=y +CONFIG_ESP_COREDUMP_ENABLE_TO_UART=y +# CONFIG_ESP_COREDUMP_ENABLE_TO_NONE is not set +# CONFIG_ESP_COREDUMP_DATA_FORMAT_BIN is not set +CONFIG_ESP_COREDUMP_DATA_FORMAT_ELF=y +CONFIG_ESP_COREDUMP_CHECKSUM_CRC32=y +# CONFIG_ESP_COREDUMP_CHECKSUM_SHA256 is not set +CONFIG_ESP_COREDUMP_ENABLE=y +CONFIG_ESP_COREDUMP_MAX_TASKS_NUM=64 +CONFIG_ESP_COREDUMP_UART_DELAY=0 +CONFIG_ESP_COREDUMP_DECODE_INFO=y +# CONFIG_ESP_COREDUMP_DECODE_DISABLE is not set +CONFIG_ESP_COREDUMP_DECODE="info" # end of Core dump # @@ -556,7 +567,7 @@ CONFIG_FREERTOS_ASSERT_FAIL_ABORT=y # CONFIG_FREERTOS_ASSERT_FAIL_PRINT_CONTINUE is not set # CONFIG_FREERTOS_ASSERT_DISABLE is not set CONFIG_FREERTOS_IDLE_TASK_STACKSIZE=1536 -CONFIG_FREERTOS_ISR_STACKSIZE=1536 +CONFIG_FREERTOS_ISR_STACKSIZE=2100 # CONFIG_FREERTOS_LEGACY_HOOKS is not set CONFIG_FREERTOS_MAX_TASK_NAME_LEN=16 CONFIG_FREERTOS_SUPPORT_STATIC_ALLOCATION=y @@ -1021,9 +1032,9 @@ CONFIG_LOG_BOOTLOADER_LEVEL_ERROR=y CONFIG_LOG_BOOTLOADER_LEVEL=1 # CONFIG_APP_ROLLBACK_ENABLE is not set # CONFIG_FLASH_ENCRYPTION_ENABLED is not set -# CONFIG_FLASHMODE_QIO is not set +CONFIG_FLASHMODE_QIO=y # CONFIG_FLASHMODE_QOUT is not set -CONFIG_FLASHMODE_DIO=y +# CONFIG_FLASHMODE_DIO is not set # CONFIG_FLASHMODE_DOUT is not set # CONFIG_MONITOR_BAUD_9600B is not set # CONFIG_MONITOR_BAUD_57600B is not set @@ -1034,7 +1045,7 @@ CONFIG_MONITOR_BAUD_115200B=y # CONFIG_MONITOR_BAUD_OTHER is not set CONFIG_MONITOR_BAUD_OTHER_VAL=115200 CONFIG_MONITOR_BAUD=115200 -CONFIG_COMPILER_OPTIMIZATION_LEVEL_DEBUG=y +# CONFIG_COMPILER_OPTIMIZATION_LEVEL_DEBUG is not set # CONFIG_COMPILER_OPTIMIZATION_LEVEL_RELEASE is not set CONFIG_OPTIMIZATION_ASSERTIONS_ENABLED=y # CONFIG_OPTIMIZATION_ASSERTIONS_SILENT is not set @@ -1077,7 +1088,7 @@ CONFIG_CONSOLE_UART=y CONFIG_CONSOLE_UART_NUM=0 CONFIG_CONSOLE_UART_BAUDRATE=115200 CONFIG_INT_WDT=y -CONFIG_INT_WDT_TIMEOUT_MS=300 +CONFIG_INT_WDT_TIMEOUT_MS=1000 CONFIG_INT_WDT_CHECK_CPU1=y CONFIG_TASK_WDT=y # CONFIG_TASK_WDT_PANIC is not set @@ -1087,8 +1098,18 @@ CONFIG_TASK_WDT_CHECK_IDLE_TASK_CPU1=y # CONFIG_ESP32_DEBUG_STUBS_ENABLE is not set CONFIG_TIMER_TASK_STACK_SIZE=3584 # CONFIG_ESP32_ENABLE_COREDUMP_TO_FLASH is not set -# CONFIG_ESP32_ENABLE_COREDUMP_TO_UART is not set -CONFIG_ESP32_ENABLE_COREDUMP_TO_NONE=y +CONFIG_ESP32_ENABLE_COREDUMP_TO_UART=y +# CONFIG_ESP32_ENABLE_COREDUMP_TO_NONE is not set +# CONFIG_ESP32_COREDUMP_DATA_FORMAT_BIN is not set +CONFIG_ESP32_COREDUMP_DATA_FORMAT_ELF=y +CONFIG_ESP32_COREDUMP_CHECKSUM_CRC32=y +# CONFIG_ESP32_COREDUMP_CHECKSUM_SHA256 is not set +CONFIG_ESP32_ENABLE_COREDUMP=y +CONFIG_ESP32_CORE_DUMP_MAX_TASKS_NUM=64 +CONFIG_ESP32_CORE_DUMP_UART_DELAY=0 +CONFIG_ESP32_CORE_DUMP_DECODE_INFO=y +# CONFIG_ESP32_CORE_DUMP_DECODE_DISABLE is not set +CONFIG_ESP32_CORE_DUMP_DECODE="info" # CONFIG_ENABLE_STATIC_TASK_CLEAN_UP_HOOK is not set CONFIG_TIMER_TASK_PRIORITY=1 CONFIG_TIMER_TASK_STACK_DEPTH=2048 From 6ea2c28a4d85bbb894225e230f118ca6d6d9ed22 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 7 Jan 2024 16:20:42 +1100 Subject: [PATCH 0412/1335] HAL_ChibiOS: fixed DMA on SPI on H743 this fixes DMA failures affecting IMUs on H743. The reason for the failure is not yet clear, but this reverts back to our old stragegy of always using the bouncebuffer on H7 as a quick workaround --- libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c b/libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c index dada2e1c433c6e..bf39aa6d448072 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c @@ -631,6 +631,10 @@ bool mem_is_dma_safe(const void *addr, uint32_t size, bool filesystem_op) #else uint32_t flags = MEM_REGION_FLAG_DMA_OK; #if defined(STM32H7) + if (!filesystem_op) { + // use bouncebuffer for all non FS ops on H7 + return false; + } if (((uint32_t)addr) & 0x1F) { return false; } From ce4a450d3aa8d679d1cda8599cc0e76631a11596 Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Fri, 5 Jan 2024 15:25:07 -0600 Subject: [PATCH 0413/1335] AP_Network:add reboot req'd metadata to params missing it --- libraries/AP_Networking/AP_Networking_port.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Networking/AP_Networking_port.cpp b/libraries/AP_Networking/AP_Networking_port.cpp index 4c0e384ad6ea0b..b68c01c0c045d8 100644 --- a/libraries/AP_Networking/AP_Networking_port.cpp +++ b/libraries/AP_Networking/AP_Networking_port.cpp @@ -38,14 +38,16 @@ const AP_Param::GroupInfo AP_Networking::Port::var_info[] = { AP_GROUPINFO_FLAGS("TYPE", 1, AP_Networking::Port, type, 0, AP_PARAM_FLAG_ENABLE), // @Param: PROTOCOL - // @DisplayName: protocol - // @Description: protocol + // @DisplayName: Protocol + // @Description: Networked serial port protocol // @User: Advanced + // @RebootRequired: True // @CopyFieldsFrom: SERIAL1_PROTOCOL AP_GROUPINFO("PROTOCOL", 2, AP_Networking::Port, state.protocol, 0), // @Group: IP // @Path: AP_Networking_address.cpp + // @RebootRequired : True AP_SUBGROUPINFO(ip, "IP", 3, AP_Networking::Port, AP_Networking_IPV4), // @Param: PORT From 40e9b94f580f577d6c190aa02aa2f2141d1b9cd3 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 7 Jan 2024 12:59:13 +1100 Subject: [PATCH 0414/1335] CI: test sim-on-hw build in CI --- .github/workflows/test_chibios.yml | 1 + Tools/scripts/build_ci.sh | 6 ++++++ 2 files changed, 7 insertions(+) diff --git a/.github/workflows/test_chibios.yml b/.github/workflows/test_chibios.yml index 9e4cb96785f477..f3c2861050d6ba 100644 --- a/.github/workflows/test_chibios.yml +++ b/.github/workflows/test_chibios.yml @@ -157,6 +157,7 @@ jobs: build-options-defaults-test, signing, CubeOrange-PPP, + CubeOrange-SOHW, ] toolchain: [ chibios, diff --git a/Tools/scripts/build_ci.sh b/Tools/scripts/build_ci.sh index 1b52fba38021e4..f4a8700d01ded0 100755 --- a/Tools/scripts/build_ci.sh +++ b/Tools/scripts/build_ci.sh @@ -334,6 +334,12 @@ for t in $CI_BUILD_TARGET; do $waf copter continue fi + + if [ "$t" == "CubeOrange-SOHW" ]; then + echo "Building CubeOrange-SOHW" + Tools/scripts/sitl-on-hardware/sitl-on-hw.py --vehicle plane --simclass Plane --board CubeOrange + continue + fi if [ "$t" == "dds-stm32h7" ]; then echo "Building with DDS support on a STM32H7" From c7c0680352f3cad3c7b1fb0c4375862d9ad71554 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 7 Jan 2024 12:59:50 +1100 Subject: [PATCH 0415/1335] waf: enable sim on hw for esp32 empty builds --- Tools/ardupilotwaf/boards.py | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index 386727a203437e..9330bb6e02804f 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -917,7 +917,6 @@ def expand_path(p): cfg.load('esp32') env.DEFINES.update( CONFIG_HAL_BOARD = 'HAL_BOARD_ESP32', - AP_SIM_ENABLED = 0, ) tt = self.name[5:] #leave off 'esp32' so we just get 'buzz','diy','icarus, etc @@ -929,6 +928,15 @@ def expand_path(p): HAL_HAVE_HARDWARE_DOUBLE = '1', ) + if self.name.endswith("empty"): + # for empty targets build as SIM-on-HW + env.DEFINES.update(AP_SIM_ENABLED = 1) + env.AP_LIBRARIES += [ + 'SITL', + ] + else: + env.DEFINES.update(AP_SIM_ENABLED = 0) + env.AP_LIBRARIES += [ 'AP_HAL_ESP32', ] From e6528eaaae495ea4d90475a9cfba7388fb3e4da1 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 7 Jan 2024 13:00:17 +1100 Subject: [PATCH 0416/1335] AP_FrskyTelem: fixed warning on ESP32 --- libraries/AP_Frsky_Telem/AP_Frsky_SPort.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_SPort.cpp b/libraries/AP_Frsky_Telem/AP_Frsky_SPort.cpp index 371aeffb85bbee..c4dd68e481dcc5 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_SPort.cpp +++ b/libraries/AP_Frsky_Telem/AP_Frsky_SPort.cpp @@ -369,6 +369,7 @@ bool AP_Frsky_SPortParser::get_packet(AP_Frsky_SPort::sport_packet_t &sport_pack 0x1B // Physical ID 27 - ArduPilot/Betaflight DEFAULT DOWNLINK * for FrSky SPort Passthrough (OpenTX) protocol (X-receivers) */ +#undef BIT #define BIT(x, index) (((x) >> index) & 0x01) uint8_t AP_Frsky_SPort::calc_sensor_id(const uint8_t physical_id) { From 7d1cc14b1e7621b01063a6ab48ffd3b2cdb6afcd Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 7 Jan 2024 13:00:37 +1100 Subject: [PATCH 0417/1335] AP_HAL: fixed build with AP_SIM_ENABLED --- libraries/AP_HAL/AP_HAL_Macros.h | 2 +- libraries/AP_HAL/utility/Socket_native.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL/AP_HAL_Macros.h b/libraries/AP_HAL/AP_HAL_Macros.h index 25e124af6665b4..20039cdb2f6a58 100644 --- a/libraries/AP_HAL/AP_HAL_Macros.h +++ b/libraries/AP_HAL/AP_HAL_Macros.h @@ -6,7 +6,7 @@ macros to allow code to build on multiple platforms more easily */ -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX || HAL_WITH_EKF_DOUBLE || (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && AP_SIM_ENABLED) +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX || HAL_WITH_EKF_DOUBLE || AP_SIM_ENABLED /* allow double maths on Linux and SITL to avoid problems with system headers */ diff --git a/libraries/AP_HAL/utility/Socket_native.h b/libraries/AP_HAL/utility/Socket_native.h index e3514ded0c59b7..43708cd51b9b18 100644 --- a/libraries/AP_HAL/utility/Socket_native.h +++ b/libraries/AP_HAL/utility/Socket_native.h @@ -12,7 +12,7 @@ #define AP_NETWORKING_SOCKETS_ENABLED 1 #endif #include "Socket.hpp" -#else +#elif !AP_SIM_ENABLED #error "attempt to use Socket_native.h without native sockets" #endif From 9c8fa7f58cb4939c88d6b13a03f0896a8d6af11d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 7 Jan 2024 13:01:53 +1100 Subject: [PATCH 0418/1335] AP_InertialSensor: fixed build of NONE backend conflict with rand_float() --- .../AP_InertialSensor_NONE.cpp | 28 +++++++++---------- 1 file changed, 14 insertions(+), 14 deletions(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_NONE.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_NONE.cpp index b64a06b9358f59..1d4ff5f19887bc 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_NONE.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_NONE.cpp @@ -7,7 +7,7 @@ #if CONFIG_HAL_BOARD == HAL_BOARD_ESP32 -float rand_float(void) +static float sim_rand_float(void) { return ((((unsigned)random()) % 2000000) - 1.0e6) / 1.0e6; } @@ -56,7 +56,7 @@ void AP_InertialSensor_NONE::accumulate() // calculate a noisy noise component static float calculate_noise(float noise, float noise_variation) { - return noise * (1.0f + noise_variation * rand_float()); + return noise * (1.0f + noise_variation * sim_rand_float()); } /* @@ -81,9 +81,9 @@ void AP_InertialSensor_NONE::generate_accel() // this smears the individual motor peaks somewhat emulating physical motors //float freq_variation = 0.12f; // add in sensor noise - xAccel += accel_noise * rand_float(); - yAccel += accel_noise * rand_float(); - zAccel += accel_noise * rand_float(); + xAccel += accel_noise * sim_rand_float(); + yAccel += accel_noise * sim_rand_float(); + zAccel += accel_noise * sim_rand_float(); bool motors_on = 1; @@ -99,9 +99,9 @@ void AP_InertialSensor_NONE::generate_accel() if (vibe_freq.is_zero()) { // no rpm noise, so add in background noise if any - xAccel += accel_noise * rand_float(); - yAccel += accel_noise * rand_float(); - zAccel += accel_noise * rand_float(); + xAccel += accel_noise * sim_rand_float(); + yAccel += accel_noise * sim_rand_float(); + zAccel += accel_noise * sim_rand_float(); } if (!vibe_freq.is_zero() && motors_on) { @@ -189,9 +189,9 @@ void AP_InertialSensor_NONE::generate_gyro() // this smears the individual motor peaks somewhat emulating physical motors float freq_variation = 0.12f; // add in sensor noise - p += gyro_noise * rand_float(); - q += gyro_noise * rand_float(); - r += gyro_noise * rand_float(); + p += gyro_noise * sim_rand_float(); + q += gyro_noise * sim_rand_float(); + r += gyro_noise * sim_rand_float(); bool motors_on = 1; // on a real 180mm copter gyro noise varies between 0.2-0.4 rad/s for throttle 0.2-0.8 @@ -206,9 +206,9 @@ void AP_InertialSensor_NONE::generate_gyro() if ( vibe_freq.is_zero() ) { // no rpm noise, so add in background noise if any - p += gyro_noise * rand_float(); - q += gyro_noise * rand_float(); - r += gyro_noise * rand_float(); + p += gyro_noise * sim_rand_float(); + q += gyro_noise * sim_rand_float(); + r += gyro_noise * sim_rand_float(); } if (!vibe_freq.is_zero() && motors_on) { From 6c88111267f2bcbd68ffff2901d01d80fa6d7e8d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 7 Jan 2024 13:02:19 +1100 Subject: [PATCH 0419/1335] SITL: fixed build with sim on hw --- libraries/SITL/SIM_Blimp.h | 2 +- libraries/SITL/SIM_Plane.cpp | 5 ++++- 2 files changed, 5 insertions(+), 2 deletions(-) diff --git a/libraries/SITL/SIM_Blimp.h b/libraries/SITL/SIM_Blimp.h index 042341c5a1bc52..1cdfc504df2c82 100644 --- a/libraries/SITL/SIM_Blimp.h +++ b/libraries/SITL/SIM_Blimp.h @@ -68,7 +68,7 @@ class Blimp : public Aircraft { float drag_gyr_constant; void calculate_forces(const struct sitl_input &input, Vector3f &rot_accel, Vector3f &body_accel); - float sq(float a) {return pow(a,2);} + float sq(float a) {return powf(a,2);} }; } diff --git a/libraries/SITL/SIM_Plane.cpp b/libraries/SITL/SIM_Plane.cpp index 4b32c10406267b..8dbdfc6fc4a872 100644 --- a/libraries/SITL/SIM_Plane.cpp +++ b/libraries/SITL/SIM_Plane.cpp @@ -20,6 +20,7 @@ #include "SIM_Plane.h" #include +#include using namespace SITL; @@ -80,6 +81,7 @@ Plane::Plane(const char *frame_str) : thrust_scale *= 1.5; } +#if AP_FILESYSTEM_FILE_READING_ENABLED if (strstr(frame_str, "-3d")) { aerobatic = true; thrust_scale *= 1.5; @@ -87,7 +89,8 @@ Plane::Plane(const char *frame_str) : AP_Param::load_defaults_file("@ROMFS/models/plane.parm", false); AP_Param::load_defaults_file("@ROMFS/models/plane-3d.parm", false); } - +#endif + if (strstr(frame_str, "-ice")) { ice_engine = true; } From d90a4654a71f5a8930a85660d877f9ea754f5619 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 7 Jan 2024 13:02:48 +1100 Subject: [PATCH 0420/1335] HAL_ESP32: allow for building with sim on hw --- libraries/AP_HAL_ESP32/HAL_ESP32_Class.cpp | 18 ++++++++++++++++++ libraries/AP_HAL_ESP32/RCInput.cpp | 3 ++- libraries/AP_HAL_ESP32/boards/esp32empty.h | 1 + libraries/AP_HAL_ESP32/boards/esp32s3empty.h | 8 +++++++- 4 files changed, 28 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ESP32/HAL_ESP32_Class.cpp b/libraries/AP_HAL_ESP32/HAL_ESP32_Class.cpp index d4057a9af3422d..b00af1bc543c09 100644 --- a/libraries/AP_HAL_ESP32/HAL_ESP32_Class.cpp +++ b/libraries/AP_HAL_ESP32/HAL_ESP32_Class.cpp @@ -28,6 +28,9 @@ #include "Storage.h" #include "AnalogIn.h" #include "Util.h" +#if AP_SIM_ENABLED +#include +#endif static ESP32::UARTDriver cons(0); @@ -60,15 +63,27 @@ static ESP32::AnalogIn analogIn; #else static Empty::AnalogIn analogIn; #endif +#ifdef HAL_USE_EMPTY_STORAGE +static Empty::Storage storageDriver; +#else static ESP32::Storage storageDriver; +#endif static Empty::GPIO gpioDriver; +#if AP_SIM_ENABLED +static Empty::RCOutput rcoutDriver; +#else static ESP32::RCOutput rcoutDriver; +#endif static ESP32::RCInput rcinDriver; static ESP32::Scheduler schedulerInstance; static ESP32::Util utilInstance; static Empty::OpticalFlow opticalFlowDriver; static Empty::Flash flashDriver; +#if AP_SIM_ENABLED +static AP_HAL::SIMState xsimstate; +#endif + extern const AP_HAL::HAL& hal; HAL_ESP32::HAL_ESP32() : @@ -96,6 +111,9 @@ HAL_ESP32::HAL_ESP32() : &utilInstance, &opticalFlowDriver, &flashDriver, +#if AP_SIM_ENABLED + &xsimstate, +#endif #if HAL_WITH_DSP &dspDriver, #endif diff --git a/libraries/AP_HAL_ESP32/RCInput.cpp b/libraries/AP_HAL_ESP32/RCInput.cpp index 2923872dbd2a88..704877962d4e08 100644 --- a/libraries/AP_HAL_ESP32/RCInput.cpp +++ b/libraries/AP_HAL_ESP32/RCInput.cpp @@ -89,10 +89,10 @@ uint8_t RCInput::read(uint16_t* periods, uint8_t len) void RCInput::_timer_tick(void) { +#if AP_RCPROTOCOL_ENABLED if (!_init) { return; } - AP_RCProtocol &rcprot = AP::RC(); #ifdef HAL_ESP32_RCIN @@ -126,4 +126,5 @@ void RCInput::_timer_tick(void) #endif #endif +#endif // AP_RCPROTOCOL_ENABLED } diff --git a/libraries/AP_HAL_ESP32/boards/esp32empty.h b/libraries/AP_HAL_ESP32/boards/esp32empty.h index 33f5d7c219ca99..d95e30f9b2af95 100644 --- a/libraries/AP_HAL_ESP32/boards/esp32empty.h +++ b/libraries/AP_HAL_ESP32/boards/esp32empty.h @@ -148,3 +148,4 @@ #define HAL_LOGGING_BACKENDS_DEFAULT 1 +#define AP_RCPROTOCOL_ENABLED 0 diff --git a/libraries/AP_HAL_ESP32/boards/esp32s3empty.h b/libraries/AP_HAL_ESP32/boards/esp32s3empty.h index d8f2af7f76cd8a..37c40f9a6419a6 100644 --- a/libraries/AP_HAL_ESP32/boards/esp32s3empty.h +++ b/libraries/AP_HAL_ESP32/boards/esp32s3empty.h @@ -44,7 +44,7 @@ #define HAL_USE_ADC 0 // 2 use udp, 1 use tcp... for udp,client needs to connect as UDPCL in missionplanner etc to 192.168.4.1 port 14550 -#define HAL_ESP32_WIFI 1 +#define HAL_ESP32_WIFI 2 // see boards.py #ifndef ENABLE_HEAP @@ -87,3 +87,9 @@ #define HAL_LOGGING_BACKENDS_DEFAULT 1 +#define AP_RCPROTOCOL_ENABLED 0 + +#define AP_FILESYSTEM_ESP32_ENABLED 0 +#define AP_SCRIPTING_ENABLED 0 +#define HAL_USE_EMPTY_STORAGE 1 + From 3fd907ddce9ad473d7b989189324dae07171f545 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 7 Jan 2024 13:03:31 +1100 Subject: [PATCH 0421/1335] HAL_ESP32: use faster div1000 --- libraries/AP_HAL_ESP32/system.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ESP32/system.cpp b/libraries/AP_HAL_ESP32/system.cpp index 4ee607c5617b72..021b921dc1e60d 100644 --- a/libraries/AP_HAL_ESP32/system.cpp +++ b/libraries/AP_HAL_ESP32/system.cpp @@ -15,6 +15,7 @@ #include #include +#include #include "SdCard.h" #include @@ -51,7 +52,7 @@ uint64_t micros64() uint64_t millis64() { - return micros64()/1000; + return uint64_div1000(micros64()); } } // namespace AP_HAL From 8ddfa0257529edf6fccd0b1d4bbfc336a2947cac Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 7 Jan 2024 13:03:54 +1100 Subject: [PATCH 0422/1335] Tools: fixed est32 gdb init --- Tools/debug/gdb-openocd-esp32.init | 3 --- 1 file changed, 3 deletions(-) diff --git a/Tools/debug/gdb-openocd-esp32.init b/Tools/debug/gdb-openocd-esp32.init index b4e10495a0a9e1..c024f050785aff 100644 --- a/Tools/debug/gdb-openocd-esp32.init +++ b/Tools/debug/gdb-openocd-esp32.init @@ -7,7 +7,4 @@ set print pretty set remote hardware-watchpoint-limit 2 mon reset halt maintenance flush register-cache -thb app_main -b AP_HAL::panic set confirm off -c From bea8b25c5d3cb68c5e6a3b5a000de441f9f97569 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Wed, 15 Nov 2023 15:41:27 +1100 Subject: [PATCH 0423/1335] AP_HAL_ChibiOS: add support for early initialisation of WATCHDOG This is needed for Ardupilot Vehicle builds running on AP_Periph bootloaders --- libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp b/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp index 2355fe4be5815e..e362804b91a966 100644 --- a/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp +++ b/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp @@ -268,10 +268,12 @@ static void main_loop() #ifdef IOMCU_FW stm32_watchdog_init(); #elif !defined(HAL_BOOTLOADER_BUILD) +#if !defined(HAL_EARLY_WATCHDOG_INIT) // setup watchdog to reset if main loop stops if (AP_BoardConfig::watchdog_enabled()) { stm32_watchdog_init(); } +#endif if (hal.util->was_watchdog_reset()) { INTERNAL_ERROR(AP_InternalError::error_t::watchdog_reset); @@ -314,6 +316,10 @@ static void main_loop() void HAL_ChibiOS::run(int argc, char * const argv[], Callbacks* callbacks) const { +#if defined(HAL_EARLY_WATCHDOG_INIT) && !defined(DISABLE_WATCHDOG) + stm32_watchdog_init(); + stm32_watchdog_pat(); +#endif /* * System initializations. * - ChibiOS HAL initialization, this also initializes the configured device drivers From ec15951b06da670a1575f7b7ce79518f6bb65691 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Wed, 15 Nov 2023 15:43:39 +1100 Subject: [PATCH 0424/1335] AP_HAL_ChibiOS: add hwdef for Here4FC --- .../hwdef/Here4FC/defaults.parm | 12 ++ .../AP_HAL_ChibiOS/hwdef/Here4FC/hwdef-bl.dat | 68 +++++++++ .../AP_HAL_ChibiOS/hwdef/Here4FC/hwdef.dat | 131 ++++++++++++++++++ 3 files changed, 211 insertions(+) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/Here4FC/defaults.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/Here4FC/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/Here4FC/hwdef.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Here4FC/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/Here4FC/defaults.parm new file mode 100644 index 00000000000000..3cbd92be7659ee --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Here4FC/defaults.parm @@ -0,0 +1,12 @@ +# setup for ProfiLED +SERVO9_FUNCTION 132 +SERVO10_FUNCTION 129 +NTF_LED_TYPES 512 +NTF_LED_BRIGHT 2 +NTF_LED_LEN 4 + +# Disable Logging by default +LOG_BACKEND_TYPE 0 + +# make node id to not conflict with ardupilot default +CAN_D1_UC_NODE 8 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Here4FC/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Here4FC/hwdef-bl.dat new file mode 100644 index 00000000000000..0236dbff1c3a1e --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Here4FC/hwdef-bl.dat @@ -0,0 +1,68 @@ +# hw definition file for processing by chibios_hwdef.py +# for H757 bootloader + +# MCU class and specific type +MCU STM32H7xx STM32H757xx + +define CORE_CM7 +define SMPS_PWR + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +# crystal frequency +OSCILLATOR_HZ 24000000 + +# board ID for firmware load +APJ_BOARD_ID 1043 + +FLASH_SIZE_KB 2048 + +# bootloader is installed at zero offset +FLASH_RESERVE_START_KB 0 + +# reserve space for flash storage in last 2 sectors +FLASH_RESERVE_END_KB 256 + +# the location where the bootloader will put the firmware +# the H757 has 128k sectors +FLASH_BOOTLOADER_LOAD_KB 256 + +# enable CAN support +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 +PD2 SLEEPCAN1 OUTPUT PUSHPULL SPEED_LOW LOW +PD3 TERMCAN1 OUTPUT LOW + +PB12 CAN2_RX CAN2 +PB13 CAN2_TX CAN2 +PB10 SLEEPCAN2 OUTPUT PUSHPULL SPEED_LOW LOW +PB11 TERMCAN2 OUTPUT LOW + +# board voltage +STM32_VDD 330U + +PB8 LED_SCK OUTPUT LOW +PB9 LED_DI OUTPUT HIGH + +define HAL_NO_LOGGING TRUE +define HAL_NO_MONITOR_THREAD + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +define AP_PERIPH_HAVE_LED + +define CAN_APP_NODE_NAME "com.cubepilot.here4fc" + +PB6 USART1_TX USART1 +PB7 USART1_RX USART1 + +PE0 UART8_RX UART8 +PE1 UART8_TX UART8 + +# order of UARTs +SERIAL_ORDER USART1 UART8 + +# setup for blanking LEDs in bootloader +define AP_BOOTLOADER_CUSTOM_HERE4 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Here4FC/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Here4FC/hwdef.dat new file mode 100644 index 00000000000000..94d07648d6b5ee --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Here4FC/hwdef.dat @@ -0,0 +1,131 @@ +# hw definition file for processing by chibios_hwdef.py +# for H757 + +# MCU class and specific type +MCU STM32H7xx STM32H757xx + +define CORE_CM7 +define SMPS_PWR + +FLASH_SIZE_KB 2048 +APJ_BOARD_ID 1043 + + +# the location where the bootloader will put the firmware +# the H757 has 128k sectors +FLASH_BOOTLOADER_LOAD_KB 256 +FLASH_RESERVE_START_KB 256 + +# use last 2 pages for flash storage +# H757 has 16 pages of 128k each +STORAGE_FLASH_PAGE 14 +define HAL_STORAGE_SIZE 32768 + + +# crystal frequency +OSCILLATOR_HZ 24000000 + +CANFD_SUPPORTED 8 + +STDOUT_SERIAL SD6 +STDOUT_BAUDRATE 57600 + +PC6 USART6_TX USART6 + +PB6 USART1_TX USART1 GPIO(7) +PB7 USART1_RX USART1 GPIO(8) + +PD5 USART2_TX USART2 GPIO(9) +PD6 USART2_RX USART2 GPIO(10) + +PA11 UART4_RX UART4 +PA12 UART4_TX UART4 + +define GPIO_USART1_TX 7 +define GPIO_USART1_RX 8 +define GPIO_USART2_TX 9 +define GPIO_USART2_RX 10 + +PE0 UART8_RX UART8 +PE1 UART8_TX UART8 + +SERIAL_ORDER USART1 UART4 UART8 USART2 + +define DRONEID_MODULE_PORT 2 +define DRONEID_MODULE_CHAN MAVLINK_COMM_0 + +define AP_UART_MONITOR_ENABLED 1 + +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + + +# RCInput +PB15 TIM12_CH2 TIM12 RCININT PULLDOWN LOW + +# RCOutput +PE9 TIM1_CH1 TIM1 PWM(1) GPIO(50) BIDIR +PE11 TIM1_CH2 TIM1 PWM(2) GPIO(51) # shared with channel 1 +PE13 TIM1_CH3 TIM1 PWM(3) GPIO(52) BIDIR +PE14 TIM1_CH4 TIM1 PWM(4) GPIO(53) # shared with channel 3 +PC7 TIM3_CH2 TIM3 PWM(5) GPIO(54) BIDIR +PC8 TIM3_CH3 TIM3 PWM(6) GPIO(55) BIDIR +PC9 TIM3_CH4 TIM3 PWM(7) GPIO(56) BIDIR +PA3 TIM2_CH4 TIM2 PWM(8) GPIO(57) BIDIR + +# enable CAN support +PD0 CAN1_RX CAN1 +PD1 CAN1_TX CAN1 +PD2 SLEEPCAN1 OUTPUT PUSHPULL SPEED_LOW LOW +PD3 TERMCAN1 OUTPUT HIGH GPIO(3) + +PE7 UART7_RX UART7 +PE8 UART7_TX UART7 + +PB12 CAN2_RX CAN2 +PB13 CAN2_TX CAN2 +PB10 SLEEPCAN2 OUTPUT PUSHPULL SPEED_LOW LOW +PB11 TERMCAN2 OUTPUT HIGH GPIO(4) + +define AP_OPENDRONEID_ENABLED 1 + +PB3 SPI3_SCK SPI3 +PB4 SPI3_MISO SPI3 +PB2 SPI3_MOSI SPI3 +PB1 MAG_CS CS + +SPIDEV rm3100 SPI3 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ +COMPASS RM3100 SPI:rm3100 false ROTATION_YAW_180 +define AP_RM3100_REVERSAL_MASK 4 + +# HOTSHOE pin repurposed for BATT Voltage Sens +PA1 BATT_VOLTAGE_SENS ADC1 SCALE(1) + +PA8 ICM_CS CS +PA9 BARO_CS CS +PA5 SPI1_SCK SPI1 +PA6 SPI1_MISO SPI1 +PA7 SPI1_MOSI SPI1 +SPIDEV icm42688 SPI1 DEVID4 ICM_CS MODE3 2*MHZ 8*MHZ +SPIDEV ms5611 SPI1 DEVID3 BARO_CS MODE3 20*MHZ 20*MHZ + +BARO MS56XX SPI:ms5611 + +IMU Invensensev3 SPI:icm42688 ROTATION_YAW_270 + +define HAL_DEFAULT_INS_FAST_SAMPLE 5 + +# WS2812 LED +PB8 TIM4_CH3 TIM4 PWM(9) +PB9 TIM4_CH4 TIM4 PWM(10) + +PD11 GPS_TP1 OUTPUT LOW GPIO(5) +PD7 GPS_PPS INPUT PULLUP GPIO(6) +define CONFIGURE_PPS_PIN TRUE +define HAL_GPIO_PPS 6 + +PD12 GPS_SAFEBOOT_N INPUT FLOATING GPIO(11) +define GPIO_UBX_SAFEBOOT 11 +PD13 GPS_RESET_N INPUT FLOATING GPIO(12) +define GPIO_UBX_RESET 12 +define HAL_EARLY_WATCHDOG_INIT From c693d4f0e4ae7432cbb03242dd0f200e385c1c02 Mon Sep 17 00:00:00 2001 From: bugobliterator Date: Wed, 15 Nov 2023 15:44:38 +1100 Subject: [PATCH 0425/1335] Tools: add Here4FC bootloaders --- Tools/bootloaders/Here4FC_bl.bin | Bin 0 -> 25472 bytes Tools/bootloaders/Here4FC_bl.hex | 1594 ++++++++++++++++++++++++++++++ 2 files changed, 1594 insertions(+) create mode 100755 Tools/bootloaders/Here4FC_bl.bin create mode 100644 Tools/bootloaders/Here4FC_bl.hex diff --git a/Tools/bootloaders/Here4FC_bl.bin b/Tools/bootloaders/Here4FC_bl.bin new file mode 100755 index 0000000000000000000000000000000000000000..72a593edecc45152abcfe20b724f01684e5edd7b GIT binary patch literal 25472 zcmd433sh7`)<0V3(cOo4E2s!4hi+69)D|?7m`Bsy91v8DCK;odNduZRXd-GdLt-Yj zpcA4dqhb<;JWMo+iFpWyjKnx?#AK4m&}04V?R{2J)Ey{O|ql zUF)uUd#&nIRi|p#u3c5TcJ00E5G@gVG(?y%hY06p6JY>>K6?=S$p3XX<&Z>y%Gq#6HFs z-pBT5wR4es%mwWUxk=%F4=7g?`*!$+z}Sn(w`v1A-#$xdYeEOdX??26DJO2;XEAps zY-VpPwylUeSbsF2$U;D$VQc4XB%t%Z94yWA#HVIB<izkyO z)SWdGA^z zRTcq#VHnP*X0m6h0QF<1RSH2rP*TE##h!U7n{*y`3ev%j zNZ#DenVJOh%#3w}Vn>H)a7|dawOwmP%U7SZ@O^AIr3A;J^~{-Pp0!Lz>&3R(_(w7J z{;Rsc*bK~+ENvjNYx^*DF;gD;k+%W{Z|Z6h*K2EFUw zo}26J5~{Aje+d4snJ?JQorHXXu;}XSb)R(-MzFiO3jXTqTKiY}=47XgH&r+P_Dz9I z$TvUgLl<4Wez=ZSbaus5(OMcgPSMB-y#?~Ero{R2dAlsvyRsBMtj{}Pe(bMOad;P> zUt_t^bu->t5EL&FV}DadBc}sad2h^uF$-U_aOZDP`1q=vUN4a?%BTgSf0KuHj}h!` z#DGAEApAhu@DyoYTM>8y^7ju1VJ-4lB7FC&fOTIm{RjQF_mptA8{x$F`fXTce9d6KG=czKVik&Yb~^PjWKb~73De~PTK z6VS(W&kV`ZslQLDC-OR#$oH#49Z8-nF|uJmM2r)Oyiu7f&8dqq3qQ!12$$`!RQyS(ar9Cv**2oufH6i8=JT!kZZRv0m=T?-f3f* zU;7T5PYlcLWjVAQEl=tFXuqlM#(d5YS4Ipsa2W{RI_H^%DA=T?~Yr0 zeogDjY9d&aM-S-bD<+O_N7E|A-dO^UGa>=nX~td8WoQ_2=SO)V`kb~`hc z7Si|`#c8r$ZTn+W*GHPBu0(3u zLjZ>uPbrJjM{FYNP93%_lW+_E%7o zOU0ZtMwh*qx73ccA4;BXmTr?g5(7HU=}oSCEhkQzyZ>L{iir>lg@y(gCxZ)_iiS&Y?9{CJ3bO6xDv3AMrXXP z#6VIQP`7(Acgu);Ue!(PxIpXNiaM9v%uSk^r1PuIUtiYATxf(o`WlUq2MkR$k-t^P zwed-}=JtB|q~*C+@qc@6m$yJp5X_R`;{`^JQc!lM<`9uTQIGl3FdrBZv<)HHeRA5v z!tU(b9$@6l%H+B*IgATSg#?qV`o%#TVCCd~>LoK?bPv6G-a~N;8`Mc8rPj@eWHOPz zQfc1JgNc2AQOw{LmsDOlQpfExOUyOT`^@akmYcJP+@+F~A3X0!Jne5Z?f;F^P_HXg zy>}AESM|>vOvWlYY|*u*0M1(~V=~KkZ|3K8dC4S0{yWl*(uA_a{NLLT0i&C`?|5?v zr%m0zdy`_IA4~^tyFoqTBZ7K$;hV8Cr`yy$|IMg8p+m#%c2rw#x@vjzSdVklP5v9- z9G!nGo2fQ_IYe)Rig{E+rm0tFy~))ubD3IBVN!qa5*Ov=?}8uvJ1^lWKS2nm?-4!( z2Ac*bU2f`*dNXnQsFwGAA{%;mlFX4U^DWu2wiK5|Vs;bxbCs!4lQ!iN`J!6Teu(?9 z>k;;$`6&_;97}Bw!aZ*?wVIAfO@^2DZ0P`n`rR8uE&>&A>i+r-GUb?523j4r#I`2R z9Muw9%Vb1i58$}buSVOJD&qB;YO}-}G_UY;G5&o{$?MGoO+!`9&Q9;AN{o}v9wMI} zWWB_=GKoLLqxGYhYn!@{yg}O>A8hm0H~76oo`71HepT+dV7aG*L#jJ*S&EZqjv8b znR&X7kl|6gJJ^yt2&3=~^io$~Ys|i>`^7hMr4Sz$6R_x zdic^@>7h$>&d|BF|1S&)$(!Ff^&nfXT3RE-s9=Yw}|q74;;X39uyA?yN7% zi9vZit(T-X=o@&zJ~hbYb03TLLVK)Zzg>R<^YyYX5qvr8^`1q4j*v)_x%2+fYhKey zk%uC75&6}@g6`AnNfO=F4-Q87W(%x*itd-|C+8mtbjq>z>dQL98n@s-qUTDPu|oBK zsAhHY8Hw|Chm2b^@+f7DF{1OLA;OmyzC}r&r8_)P64JTP?#i|(LO5irgbb<2V{&9k zdb=oPJP^H(F%Y?PkQklyS03i74?oOSYkcE5rkXL5YTbe6E5!Ke72cUCvGTmZ2w)BB zZzircyNL7I($h(sw@E*Ki1jDfi9q|6w&45`rxYO>A6#*K$}5yloWX1&DHhK&$}{#4 zXWZDrNCn+57117MptsHq=~9I6S?08&%qr+68+cy`nQS|)gl80Vn>UkTeM%Y@_+Tdue6a&Y26X|geV2Pi504s^W^5~5)tIJNnCiQV&p^ywAO#%_E}i4nP1_c_cC?o_8~_IEMO-`6ddevF10GAhl~%;Yg|<_ zy^hZA_tg~0`{9G4bg<{8TZnu@Wo8hMa)O!c^^)5ms}8M;g1;WoNZ}HBla;#zBxSzG z_%NFq@42{*NsaZevRlzgs{dn*XhHXfW!j#xfBafGS#dNVce2n6jP0xJ`cNUJiw|cs z9)KJiS9bl}6ZG8wSDi1Jp)2VtaQSYJ&KE-<#|}KDOg1CV=zLR%0oa|x+iyKlX+q1M z{DiU=KswMfb_0cY-usl2tWUuxJs&vhy|^tUHPx+eVN#85P3k8>skCbTqxt`Iu-$D% z(bkWH=Rx8c@S0Ljc(yG1=Hc`QcUg{k><`b9h+&uV#p10NBERTl(wUxZ>-cFso>#p| zII*h!zYM%M9Q$Elzqelbe(^@T#>a&ewC_WBl=V#bNI2B-9!HX%kvgPh=+UHp-uELj z4e?nvB8T^HbVN5oo{|3)cv3lo6<8VIB~znmJ&_LuCe@b6&WhJH()VvGX_G1} zOpEGQ2Wjp!+a8N>X50m=X zP|ofoa(-ZQc1SbciO45RI*I=a;&?~Y=}|2tc{VU94q`GnfIVgKhWyygLZj+G-21*X z#d{o3TS;huD+)NyDBtNTl*=Zj$60tvX)~QdTJ^gIRDZ-EN{LK5D|75$5PKUt<+cY! zDKxHGB-F4F!c*o#ONA(V8k)PR6Ae(QA$u~G^EJ>cCKa)wL^GD~#m3?F|{yD@nYCchz z>*;g^%}2XSnCh|l zV{-}qS=rY+Hh+BisJhYMaM68?tPb*+$9(~;&kaWcU09dV9N#mxOy5^2hv&!IIk^TW z`6y%RX6}dye1q~qN(;&hTk!n-Xd+M^SrSbIiYuiJ<>@4O`VZ{(>Lb{%g#wug{aT5s zSN+03=$_Y=+2*i4A1b{0xgQ?bP9{IRaITcFl!Tp>XHRrP3Q3B@9#qkn>JVNHedW%Q6zsASxnns|hYO^=mpM|2@QgCs6#2?B zz_OV_Ya^?_ydoG``L=#-&r5gFUEyu)0`Ggs%#$8FsIa#eQlsY&i*SY<%y8_rT-(gZ z_YG=5m9;^tJf@_SjZj82Oc|4X>7u#i;~E(w-kSd5(`zCR(ejapf2fb}O(m`4wbN5v z+DX$S%Ad#gg(5#Ym#dC7@=vhU+4)0K$h_g*`Zyf$Yf4}H2#85VBVH8rfOOWWDe&D~WA-DSTnkdQ%A!=X=S z!fA;gJ_pg!`DVJaZ%g0u1jc>9GTL*yl1!#Sugy7{74gVCsU>HtMd#7w zGh!uVlM|PfzcR_+c}ZHpUC`Z!b|&``vCA8dKF2~PPe6do(ZEVfQiM-O9#eECs`C-+ zo>6pUNbg1M0njLtP@H~*2Gw7uI%S5OtT$VrE6Wd+OmB@Z*XA!(lFW=`bcoWIC4ByC zlIdML_#179wn5JeWexfTWRiXnCm#%mPLsn}RcQ%tA(O-^CXd34HfCN!k8`Hc z+1*@rf|GXyG91Xupm`bge>GqBMgrc47*|eS{4VhkJLz$X!~sr<_-;Z|oa{MHh$cVI zp~;W0s*S6(u&sI;8z zT+sbZhIYQ_2(z>DqpID(&8MrFl`CDuMdw&I>W1WFRwvO@W-K`H{I@KtNfCMSlXV9^7uVS3Q8bqW|PG;p! zrFa5oFd)Us-zx_YpA?K=Qh1D^-jEVZeT|f!6AYQbR0~q0kTM5T9;8Mil^aa`6R8+Z zG%OCLnvja+%!aaH>RqHnlspnlH6WFQ)Ujad4P}-jTr*D+4A8^OW#yNYw|n+)>h_Q+ zye}h^_obucEcA($_bGdnbW=h5KSG|fg!CNzEj+GaKZZtj#@jQjuJ3={DwkkT2J%Sl)^fyFG{3e}& z>>4j=z{UFpHzY6yT@tCr8NKyIv!tNUTqoGtec&> z>Cm?CgyW4{EPGs7p(2NKv%U518E*2{r zXO&?bpfelB;TUi@-H0^W(&w8xCV{VWJ~U?5dW8HW1^;F^*(n86s=AmoSDnbOAiX%ALgM&PC- z_jq-_5RPJRl7{HDTK(SZZ{RmYN@N#fq%syAtK{I=gc$V0V>2FO6Nj-`Uv)gb#xknq ze>XOIjEx>+v%z`UJ8!}-R2pilci@+?F*StRgoV2-5$;h6GjEw$Fq*pv&&*3RN6RX= zrF}8E>iNlQIw4jb`@!FknYUWfJ8pKAN?em*oHPHLTu%ND(kn^H@Ptmv_|4l{^Jn1g zx!~LRZm#5LPg`Pk%Ms-+y}2{mvdeOlXKEg6V|{lp+ad4WG0zBz;@LRW|F+8eRx&y% z9d;?z|E7At@tkF<=OUy+=%yznw+%s>(vr1(2#)9(7lfk+oY-dlJjnXuGk~)jaAFy) zG%W~cJK#KPVS{iOcf=&wBH*x=~>81cVG|rLXC&4#0#qs--)Y)WMGMIcn1qXVfhg z9#&?Pw8wRigG^HWAE{|J5%n`0!ZFuX|33g*-#k?7xXRlcK|J0H$UYJnWn;wGf;bMH zZm3R;?o<(|_dXz}xOnMo-7#sI6297uyjs;{OR<}!haIZ_2{j|`X$#lFh->Ur%XKh* zwSAsLv>mozwzFanY{OmN5geWy#vvS-Kky%L`2IIIs99A~39wj$7T;FMByBz4@qzX& zOQ^fZ0qs2_I)vG(|Jr_7Wv`!L>-0{QGEwp)sv8;7w_%-A8b=}5qEZ?U(F(d(i%F_- ztpWDefU=o(u`Vr0^O>q>gM>&nG{i_$HdOs-=smNO_Wz4I<`qimb1GAt(U|Ud{|cJ{ zjS^HL;cZV_QtX*7W)HJ>i^XB@Y0YpX$FbsJ`}cPCNLf&`M#%IlYE~5bLwoaIDyb)v z`HqvC*DN9KvkLD#HvSexh_^_RP4&A2U9g{z^nvPeHp4s&Oq2T|H;C~hVsXQwHA9}8YuBpd)^VTDY(k^AmY>l*2 zI-z9ltgZ7X<+GWL_wa9Y)DZ1i<3=GhthH!kXkApQuGIsW^zB2lsVp4TruuiO9i`36 zX>oKni3@dm6erFRw1gAm{iv!5Y5@(70y#GfrR-$d>e3IocnBz2VX zzHm}!Zc^O(!?8&c*Hf{y=?eddrbCLR@z@Ob9DKalV#R;2C!}hcEkzpd%<6P-pD$)X z`w-Y{b}MW2R$0#_$%#yuHA$*a)|f1q2_fn{2|840heoT6Snj3r6{vn2FFmO&xrIzO z%gko(Aug4A)nNCLW=ePVRrc@6)}LoOK8d_px&Gw4kWKgtUnzVr#$Ld#obkPvF$KJ; z|Low!Qn|5NaT2r4k|sPC8QV(9%zHggE%*u;EoiR{KdDrmL@yU}9XTACLVD5`e}*^jN=~xBu&s26 zBH=-boW-d#P+w!&Q(|*ei+yDx;KF9z`zi$hrHjGRtL*eqf95PinKo$bQ+ZD7-$Oi z=SeR!=`WZCyRnBMxDs#{>u(_DGVE7`sJiF|%#>T0UG_DqzqLOxCA3vEF#BjKcVNUr zBPbiDG&H~z>N1#_Mf;cm{tEjPY?rZuh?v{SJ=TP4D=*)5_)xFS>l~@Uc}Is<9nvn$-hJBK(|^*^P)4DSsMur26z zF4goLxE=E_baFA7eD_LCPv!4IeEJaNgz4vADn5NB;u^-dMKPPUD7mJWeX&HGn{!2f zSoPnl<|rv^3bMOB$9zoG7G>F%gUa%i2bDVz{;+b3V#l)xVI{&{NIO=tty-)cc0iM# zA}xi^s-uW%7Kn@L@%JDcLE!WC4dcssDK8+z}K_c zvcnZBjuNdC8v=4a2_!83qF$_HQ)8u`7NCd~sLsKOe{K4i(;cTnsHHo^$8iPi7lo#- ze{cf$+rbVl5?UtV&c4U5F7JDM@K|7Q@b5i^o8rGn?0dX>S;B37PB}b4`u`T_?=Q?g z>tW_ysEzloTbj3^FI?dk%-DPHjx${r!n@YzlXj0x4b%v(WCgnrX;CQdJnpnF} z8sAg)n^6#dR7=-TJ?KbhaGd@owMo$H(MY*zLR$M*!|hG704kuip0+@|$Eq1-%sHR>hy zKbl8dYrdnSj!8{+GsdlW0~>q4>L1lVwAS?;UF-b;y4Ig987m9gac%-z4qfd%;9gw+ zYhErX8rt~20WN6_o>vFXBPRwiA9BV*{;Dal4D-O2Ae@>Kw@!1G$etjStF0GM0w>y@ ziWL@_Wy5^>u$sb)rFX8vUJ!6#W$x>vCv}H3=zmgWp+{8*N~N$4Ef?X7jnqE1M-npL zg;uva+lqCH{VbtK>h^r0!13*xSo_&~63rlW>9z8C7tFn0ZR%I!A zyB~J*osGZdY+D1GVNSiN=SEmR{~WLedppWKvWg~RZ5fbW?7gmQOG zJoCO%w&mMWYdd3XP*%p^X>GP&EG3gg3G>m8v&Z08<@S|pWwYgCY22#Vyo;sFR~5*t z;bLhGo@)9<%-1%NLwZ;C`BgV{UwGr!J&Xwq?L|YpJ0dW|-~Vxm&VVJePs6^U$GVP1 zAU1Z{A*}sdS;EqJs=*xHDeaTU6vzspbl0bHQi~~IZqY3|r|HNUUC^Erzr+^(z<8Z> z_H$(mq?!-#ujzRa@&|b|`hgm)rX!5ab$zb9HG7H8=A!T4njQUsRTjADbr*ETb5CMi zxTBh$3UF-IA34Asj-7pn4f=y{DsMy9PKc9MW^<>arK=v%Q38v8iu6KNjgv9H4o;lv z_!RA2SiLvrbLE!V#=6gyLqQzyKUbXjvS(;L(Y{1Uk72zL`LBHy(xVcYxx#Z1ec2D0 zZ!n63&MG3f@|u-{;%+9(1q;f}9%XMbll~t5Y3^;>@7;JVzEtvlmu6C~@v=lYGZ)a@ zMNcTN^`|>-CV4Ic_S{ol+pKiY-A!^`R@rGK)f*hq-6T5R#b8c4mprCKm}r>jI-?u| zwx{slRmI6s++#|(=@}&)mcJ+a;1AWc*D|TKGdBE{Fdq{(`oS<8r=+F*=w;9^iu;iu z?#~0Ox5Ov@1I}-Wi?zGy+r^VhDb5GIKQ+>sa%eGsNcXzxU)I0(aum_MpXww=QQ}{D zU5ParVLx}?a$z;>`LFEFSyp#e*$E6!$WIMSNc(sj?3BLxSYm6J?}J?$_;UAMt5%l8;@T@>tTLrsCNCd z^4e@-%o$HQtfT+HOtX!8V3f>8jd9P{MW1cF{e#kQ_@aLfscBSuWK^gdmP!4n2eM?I z8MW@LvIC=an*L{qsb6_yw3C`&)-dt5_&b zZnTVc7dV)wq8v|InCJe~A?QNSG%088Myz(8Gp_qWslr_Pg#OPFXNl8WJRDtfR@MLC z$Ea`dL}&q{pgV{zi@}O|DrlF;ESm@q1l3=mie(Cw@d~yc*@u&|QyPmiA35^nmB<5Z zb#yrc&#@PjRLCn)(2Zo2lT?e_AkCBL+I$jzRm%__R`a3DnTni`RQT`K9S85`;6FHY zzRM_&u4CZ4dDSC;Qe5>d*=+5f;LSeq3|HH%+`_x-ILE6UJafVEX#L)tAxISZ0l<*-C7r4wL+&m z>%Ky+sRid{YTm0iNr!T1nX(gd!(SYa2K_+(P>0jFX@xG7mYhpV8l?B?Go>Ra83KJ5 zmF5{}Nx;D&&xgVjQ!sId^$sC@3AlcORBz!<8^QJU4$;25>IEmYRq?-YedfaI67ZV6 zIsfeyQpUB0q=dUe5yB9{5h4&GQ(|0Z(F6@cID#G_1|b$fL3w4uevF8tlzhxQcdBzgu ziLig=jh24&z6?tpD?4qcx}57R*VEPHXMXU0q7Z$U{ZsE-7RLRSvyy>Oio{@|5`I*;T-Cm z^E%rZQ7~q8Cb3LCGtW%ORA>D$*W#d-wFh=2syllu_C*WvWS)qDElKrXQvJZw;>fFu zc5HssYPUYhWYpI0vsgE0x+*v8CFp+|s<5|;h6u?49rvKWu@C#n6RQ7TDl6IRR%1;I zZzM><9PX31EZLCTvN66!oUimaJ(Yns{XZQ)S`TC0sz-=Hh(!<)Oes5DQDP*7$qc0vEuknb=y{&QP#R|xyh3jGPbB+ijw=L(y) zG4q-#^6Wna$66_vAbq?oO4=+nb%ijyCC$_@$po*kSL=1YIR4rC#6G9O&xmT-na%ka zPTL%63v4Uu3gKW)tB7lhQ;3~0UAm>+yEEH&=6RncEW!AY<2XDuxWMS+iGACzlC*43 zE;vmJ^mmz!<@UAEs?f6?_AlX*mrT~$%k8h%Q^_SeTi+VmA#jEX(HLc%!vrjBv|pvf zPfc}aXKQ^79Qgvt)gtq}}yK_`dggRwstp5|WMvd|h-l)L5F&P=4wT zwti($Y&;F_?D8@OulFQke~?5wFTLl@&OX;l@oO0r8b$k?!FP~z@$T)RwNQ`{v{+Jq zk;)@0O5m#uKl>V|aYt(1w8uyGFs79IGNs}Y!;bj!X|NzCa>epZ zT=e=9JKZOK8ek@Q;KdFvbzeAFAUi`BNed<6NBwoNxDBNG?;os$#o_Pnp%!oKB{Qz` zFtx1VFgRJ5Pl!zHtLRVK0i6qZ*Qbqg)-x@STTabWOq*bv|+1Q?qKi%OVGX3psH z_&%qPF|l$YJH6i0K7aJ1*mLvR*-&6^*{lfrZ;*TFXG0D*3M*@B=H&_#)vDAZ_KYJsUNx+ zYSSg8yevln&-kcBCyi<}?jWgiJ(C_zoIblHvpnUvVTW#7TFc~Z*FeLV>Y=Me^?x=X z!sB2TOWQQ_S?!uab9h#}d6E%(Gu5c~!&6%KWl;%s^^6PkiK$gCdKW`Ek+f~PHoKjf zq_K)9H38l*|3V*e-Hi5>{0Q928n%HCjRg-%!Ol1Vy}eJNdr%3^X0I!HQ&g>{`Wa|Y z9)qMis#aHh0-6+ftgd=p5uwd_S`7s^0zb}bE}?#mW2Lah=p8GL&wV&?W=hKw3USiY z-efn`%6~PGQJ%!I*nhIxn`UKf%W4;xtae=?z2TN2WywwkIurCG^vjHL2KR#2|66b9 zenYYD3-*BWSGi$3aF3A24P!qM*pE@3Q5Kk}FWB;lOD#*YO5w#sa6&MfXm3UZdy^aN zO-!&ix6t1Fai}-7Y8c&PiMf>2@uspIYiXRrQpA?T{mhescR#b-is+01tzs8t;hY!J zNHO!^Zs-eft04V6X&IJ*O1E1gVD;ZIz?DK1Tf~)w*}>TgnR!fUQ$>~ZEp)jL4}>|W zZuOUUO%>3^>d$(sq!5P(vWaucM7rM zYyoXZ>Vxhn(--3YLyDFdr%HdbkZR#@iz1LT*VXzPrI$Ojp>u5M(DrWYQ~fveQ`jj< zoR2Kk%)3DNY6_97=5Q;B>V4BZfJw~3xW+9UULuvmktbDuQh#PWnc3*ROBd=6JzQkr zI?ghztYb$h!u8Qv4E}|*8(Q^g=FSGEi2uJiX^)8fv=cVVws#~l`IMKhZA(pYwHdY5 zVYb5-P4$@8u&1uuzg%eNvlGuarcYp`ps>wLVX@J8d)EZ?SZ~a&|>KtP@2;Yd)xN*!P*MJf) zn8U0~EX5sGF5Q}H#T+nF?>(x8CBZd6aA~b9kiJVo+Vi0DTdiW+k1eNzeSX7@`vbw) zyKdeH{z#Z9T88$Nc#H*U9w z6>k4uq=A3hWiO{);5ylL(!@d{fdmeoa#dwhw4SBfQ(aLagA)XN?@pZR(wPI)=7KwJ zlsmw4&lu{^qx9D(T_MG|PIYM~lgVV7v$JdSX!+!Pv;5QMkd0(2wDguRG?$9>WF=cD9Ws^5dpGABR8MOy>+tA1@@^~U3WWNYU&2L9aCwS{HUi@N^8 z1@3oyOE(^WxW;lJh{YWD(GWH@9avK-A>z<+J6{{H5BR4HaJ8YJYiKoJ`?_-Dk+AC2 z36Ck}{o&QAxY>~9q+0IRmFrE~+Q$@&NrQi@X^)a-s)W^s`m!E?Pj9eYj>({MOD!9y zc)=U^^9Nn#(e)k8iDtRm39LA4wps3UvNdmqq;4eB7P>oizds9WU1x`rt9@g_wZSnw zZcmpeR;e2~v=oQHOX&;oh4_RJ z9x`(>RyLKIM_H-d{6TM{&m6@`S3JimW=YdFa@UKOd_&4{h1W(M4VVhz{Iu z_5P)C#sp^G5Kb5B)6x1}z~r3^(>BhMj%{O5?^|y#!r`;u^{y{I>Y0`rOKs~|c*KPGpn<{jCvd(HvLBo;lstp~Fj9m62=WyEBgr28 zN0D97=~AC;y5B-iP^p>kfJ+RuP39F>;wJo%{T|ZWPo&L+o9v^iir$XMkIZXzBz41{ z!H0y0TEpg_w>K;OB5d5SGxUoB?*AT19OcN88D^ASG@SoaC4BGz1NsKS^=WSX?6voa z9`InHqc>_J^H)%{((aM2~B>$ zOY6b!B&frnxLI{XkPwJblQ&*sGW4mZu8>hIJQWq3REaA&Xpiz2U|oiu>S~I{$vfm! z*L%XLuB?f_!)=WMIVy~){#ciB4*Z;Bo@OT92CL0GJ~j$_PY>V6_1hd_*lUv8HT>Fk zj=Od*IRk}e8J!@XrCX#q!+YT2?gzsN4m)0z1hR%tVQi!jYBt$M|-w*9nae}EqtkQ z7)G1dHXOGW!KxCJZU|u=R>vqSW9RB(gMJolUNr7Ho#dkJpn#q+|0ewqG0$y?TM)O9 z-X1v92R}qY_7Eeqoa@KVhwi(V#>UL&eVNFQ$;VxTzUchZSH{hWhF>+28;5EH%SX*e zP5F<#k@>Vv<-}Go6T1mu*97Oa;7%SkUr|G+h_zltzm7)yr z;vOq0RsDgyh$(fro~r26y1;Gw$yAwWqzCjNf~2GPZk3ArXT8!u@jE z52~N};2w=M*U?>)q?=t7=Z=vDCe~E|Kk{#Nxi0FtaX?ofn>ZRbGxlJflc94tWdiJO zxU)y&-)ch74f)WZW+8nudiV|MQY&w0j4TS7o_X4_kfBT=8ee9psMVi)6m=J4Z0^R* zglo>jHxe~_2B*kQF2g)^468ea^~9WH%Q z8+-26d!tJZ*DZz?L(YlKp)G7EO@S?PrGC7b$nM^4$muS5+k2#_Dj0jmOSMo0S4WA@ zZe`W{?;RgIq^d2ZlwH+u-kq$Uk#2>&ZGraZ9_*iIY2mFupLdW7T*#`U-y%!zxY#rXA zIvbJt7i76g+@pq%qBKULkk4M>?bie$Q@AC)#eiGigV7P|M?oxC%XMLG!&+ zls?R1YPSQz4{;N16w(*o_v}rDq_)CN`>q)^%0?-`6w>je^50+lHL+9F1nK!8=n2htkfIfZ3FTbL z5H%}7O%J~Qp&zE^|Fr)<4gS*q=h5o_o&Ntjzm0)r!0IA|@)a7t0r5;c8;A2~{3zn| zUC2=0EE?yA%M}mhrPFf1N1T}&<60|669Ty(db$&QK8KZQwV#B4A7kY1qx)Jcc#u9g zZ|JO1{e=Up5&mWO(Vbck+GRF0mC(_MZ^RuAc*MP^PK6vt??t`_Ia+&OoB*C(c;a%V z8FmyGJP?c(4(@)gB;K*lvC9%Tv)sYiEq1+q8QnvE`>y5J@2J&cXuQMz%%y7Fd}@R{ zwUOc^oY-E1JDNdmTUiL54tQCo*K>uWN86X%@vQ{la@wWIZ*>Uw$2wTYQhS`8F|^p( z`vd+{?>g7OUq9c}@TDU^;Sro`qTH!cNFH>@@*0db^*^QGZ9u+zYQNbU8~ zdN(YjzA15z3yz(RTKM7)d4iYa(02lSRuUX7FpCVe_l4a6IsI{!!AhXF1p@vp!M2C$ z??!#hKln9VbPd(d#JvRE2%n^#ugf)-!RuCT>1U0`GP?SxAIIf;iD<*v1lwv@|2Cf= z3)`UZ15W`gFzf=IU-AqKXr|Aiul)5nhX_y0ct}}Y@#_^PIn1>Ox@6kQh(De zcu#$9x7%5xP$)>-E6Q>z9S3|{SgR6~#+FzWTbc#`=CqJJtCE~{3hzW>Rbtav+%5@E zBlr(XKHF z@dEAz-Qn0~53?_@C)sbe?{jR6s~MU(_*%f|_;?5PWe=U2=?YCM3v!vz$@cN^H|!^J zUx1H)5#GM{C-Bk?c=m?Q;9D7y+DnO?_b#;^C=D_B5mM;10y$LITFCkIOa**nLk(H> z@g*@5W6!n679NVl-Fb{sGkh>_rE>FpEhb=B`e2Oa#P}x?hGpnlD+VG-|T>mEVy=R9HF)va0D($Au1WO z4x@xoow?Lbec=q?jU22(df>Y8c(r4*Bg|H9C-SO*q2!yA-N5Gs%Xh7#Y_voOyw8{7 zehlpom1DkE-gOE-y)JDL^jVAPecu)(!ThR&gAf0WEipFiBO&L2$A`$J>-c^6eNt`O zQE+J@+X7TlICq7cMXhc_^JaAkNo|3T(BwdA$^H&Lq(aKejyS`Lz%4)wLv;nu&Crul zSp)peH9F1!-|5jEAt6-To9W5}%{m4fyu)SPF*dYLlHy*W-rcCt_4lCc;i5F8{h)l4 z+AZn)8k&KG&~FD}O_$uP>-XU9f6@}&(D?wR;a41yA76eL9#G$_Vfp7B9(ZJi<}J6g zzN+-)IN^jRoq={sn}>TkNi>f>VJ~;dbPc1vk-0ltXcz?;U5)x+8{E0`4vTDN>G_DZ zr8!5T(3~bb@y!oai*~3N6fHsDFu^y%i4mAlDK#!w)9q%S_6GgvCRjde z>wcAEt#UGVF(@ND@idk!*Y%&J*7Un!4L_lx)mcRTT`$df92|n~7AIY&75yyLf1A1= zH%H=w5a53{>ns9%S-7FNe%1K*AT zx5notEIQibOpMRZbj3=XPvO#Ct@s|(L}1RSI{S+qe0YX~_a!h^nT1?zOl(z1**ICF z>+>vC_?g=+3lvW54&L=w{g($RwM2aPf`cznhQk=FgKz!d3j)XSC5R*5m?W|!9R0#~ zVwUJ>Kw94*EHIX*)Wu^aox=?wV;Oeh)P6TU=zx`m@%sDFoWaN}#23zHmpE=!!ozT; zQbwowVM|?%eM11hc>p{McPAHB9D#kQUxS>g-gE~i?X+ar=eol3Lg(KMFZyd-%q;At zSvTAH@vt%Y2*d1B{onNC2J1d*WyhU2%ufZOtYLHz)<;2DMZba-kr)1d0_%7`{o)Gs z{9*R>!6rtbj=*GXy8JWs`i7mb0_#uM5=cG1=0oUL?b_<~3&% z)+XGYu-4X1YzcRVE?{j&$C-L7Znzumx_k=31PJgyUqR}vinurk0e)sAmt98T=o%OU z^9uEZIIZFaS@7Fz^zNDJ@5H?cjeF=Vvj=)4mHG-ZHoDri`Bk{ZL}T?a(QPIcQVZw83>qWxc&v+s`2U@H^FF5$#pmcYPQemI_q`03&JEr|bpI9`VMvEld*#OsIS zhY){lIDQ)OmxkkQi0>bc_ak1TvOPQ2(e_mT9(>i2?~Q^d@=n9h{afZzvcSgK>66EE$Rp1D_uw}GW7%9v$H<^oM_`AvIw*a2SYG_v=GD~Gw7K{n z1|h$u2qT|+;dkEZk}li=bbEMg$}36xmv!LT?VUyMvzoWC6UJeFO)>O6F7EPMWL-f&@U zemwa0xI%pY%2HEk&95ohjkg$Ic(2FVE%|Y4M|Yby@%YMt zGd=EZl)RgcJ%h2IhuN@L*ME-Ijw=~0XR-kglQbUEvNP*;`|`VI=bbN_oriZ6R(hO$ zCd%*PhGB!($2n+A)AOd!ufa@MUOc{->3N7bkALsFeZ|XHrsTyToG+s79YXm;)Mw?C zCH20PJ9|C3m^%gCRYm6u&4#$5#Juw>6Z7I$CFU(hs9BY6Ow5b6N8@H@6vw9adGvYF zC02MoL>ESvaB?OWi#*8Ki&g)(kU^Y~8ot7ln1|+b%ioEU+#Hc2q>Zt(YN8j=&3ALARn;^4QG@p69;|hDLjpJJaook zb&Fv!qAd;jr@uR-JO6cA_UE$IDC_>Y?706>mjAhIG_+QWOGe-_|Dmk#bJ=Q?b^lzp z1K(z#`uktwp#QmSbSdDLj=(+lOIfSF0dw8VcbCH|Q6(PG^5;h9Rim^UrR_*X=0&eY zU3eQNAr+Qajg%XyZ#DcmU0(DWyj!z3=KxZCUNur~q^JZp=zrn(Fg`!G@etN-l~{zb zWAmc#LCt&i<`|Jei%7YVYUBBHI3M1NclYkic^)aWh?EugrP z_qcJ>AK%9S)KvQ24Kl44)}rFI_sl51zi3ri$(ptI&2X$*ziRef#lUUpEekW!bLZZ4 z(@i7MjPjXt)5}LvvomJSokN3(uC(QZ)89@QaT(#n+lcvv?|dsAyR;8*Sztm*l2vi5&IRIoY1>#yDP6gtX zK=Do>Z3?{WU@Ax)$Y+=aGYON9^#yeP;#eks!Bm)M(i6=&| zS923H^B6Kya#A7U8X#&F5CAEa|G;2?g9V{nAoi+NvsN(#0LK+Sfn~}W7-qtiK=m;o z>x+WQ&Vrc906hB@t^;f!*vwU{Sb;Q1UkBVY2m_m$FeQUQ&SSy Date: Sun, 7 Jan 2024 14:50:25 +1100 Subject: [PATCH 0426/1335] AP_HAL_ChibiOS: Add readme file to Here4 FC --- .../AP_HAL_ChibiOS/hwdef/Here4FC/README.md | 24 +++++++++++++++++++ 1 file changed, 24 insertions(+) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/Here4FC/README.md diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Here4FC/README.md b/libraries/AP_HAL_ChibiOS/hwdef/Here4FC/README.md new file mode 100644 index 00000000000000..42cdc2cc3eb7de --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Here4FC/README.md @@ -0,0 +1,24 @@ +# Here4 GPS Module as Flight Controller + +Here4 Module is sold as a GPS module, but it can be used as a flight controller. + +## Features +- STM32H757 MCU +- ICM45686 IMU +- MS5611 Barometer +- RM3100 Compass +- 1x UART +- 2x CAN +- 8x PWM +- 1x RCIN +- 1x UBLOX NEO-F9P L1L5 GNSS + +## How to use +- To load the FC firmware on production Here4. User needs to first update Here4 through DroneCAN tool or Mission Planners DroneCAN config using FC firmware, which is .bin format. +- After first update, users can connect through the serial port. Check https://docs.cubepilot.org/user-guides/here-4/here-4-manual#pinout for breakout board pinouts. +- For enabling future updates to FC firmware, use flash bootloader through mission planner, and then user should be able to update firmware through Serial port. +- Please note that once the firmware is updated to FC, to rollback to GPS firmware user will need to update using APJ file available here https://github.com/CubePilot/GNSSPeriph-release/releases. + +## Pinout and Connectors + +https://docs.cubepilot.org/user-guides/here-4/here-4-manual#pinout From ca32c8a8730eedacf8f7fd65134c67ee582be8a5 Mon Sep 17 00:00:00 2001 From: David Buzz Date: Sun, 7 Jan 2024 16:19:48 +1000 Subject: [PATCH 0427/1335] AP_HAL_ESP32 : this was an attempt at resolving watchdog issues , now just needs to go superceeded by https://github.com/ArduPilot/ardupilot/commit/b9ac504d0daa4e370e5b8660b618005b31a16796 --- libraries/AP_HAL_ESP32/Scheduler.cpp | 2 +- libraries/AP_HAL_ESP32/SdCard.cpp | 4 ---- libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp | 2 -- 3 files changed, 1 insertion(+), 7 deletions(-) diff --git a/libraries/AP_HAL_ESP32/Scheduler.cpp b/libraries/AP_HAL_ESP32/Scheduler.cpp index 8a30f612eb81e9..976b7245fdd484 100644 --- a/libraries/AP_HAL_ESP32/Scheduler.cpp +++ b/libraries/AP_HAL_ESP32/Scheduler.cpp @@ -235,7 +235,7 @@ void Scheduler::delay_microseconds(uint16_t us) ets_delay_us(us); } else { // Minimum delay for FreeRTOS is 1ms uint32_t tick = portTICK_PERIOD_MS * 1000; - rtc_wdt_feed(); + vTaskDelay((us+tick-1)/tick); } } diff --git a/libraries/AP_HAL_ESP32/SdCard.cpp b/libraries/AP_HAL_ESP32/SdCard.cpp index 725235fba9e098..0f91711e1a9a90 100644 --- a/libraries/AP_HAL_ESP32/SdCard.cpp +++ b/libraries/AP_HAL_ESP32/SdCard.cpp @@ -165,9 +165,7 @@ void mount_sdcard_mmc() // Please check its source code and implement error recovery when developing // production applications. sdmmc_card_t* card; - rtc_wdt_feed(); esp_err_t ret = esp_vfs_fat_sdmmc_mount("/SDCARD", &host, &slot_config, &mount_config, &card); - rtc_wdt_feed(); if (ret == ESP_OK) { mkdir("/SDCARD/APM", 0777); @@ -237,9 +235,7 @@ void mount_sdcard_spi() //host.flags = SDMMC_HOST_FLAG_1BIT | SDMMC_HOST_FLAG_DDR; host.max_freq_khz = SDMMC_FREQ_PROBING; - rtc_wdt_feed(); ret = esp_vfs_fat_sdspi_mount("/SDCARD", &host, &slot_config, &mount_config, &card); - rtc_wdt_feed(); if (ret == ESP_OK) { // Card has been initialized, print its properties diff --git a/libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp b/libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp index b7a48f4f949cd2..7352254d85fe81 100644 --- a/libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp +++ b/libraries/AP_HAL_ESP32/WiFiUdpDriver.cpp @@ -351,10 +351,8 @@ void WiFiUdpDriver::_wifi_thread2(void *arg) .tv_usec = 100*1000, // 10 times a sec, we try to write-all even if we read nothing , at just 1000, it floggs the APM_WIFI2 task cpu usage unecessarily, slowing APM_WIFI1 response }; fd_set rfds; - rtc_wdt_feed(); FD_ZERO(&rfds); FD_SET(self->accept_socket, &rfds); - rtc_wdt_feed(); int s = select(self->accept_socket + 1, &rfds, NULL, NULL, &tv); if (s > 0 && FD_ISSET(self->accept_socket, &rfds)) { self->read_all(); From 77afdf1539029ec52e58bbaec616be3ac28e25e2 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 7 Jan 2024 12:29:47 +1100 Subject: [PATCH 0428/1335] Tracker: stream BATTERY_STATUS by default ... if a user has set up a monitor they almost certainly want this --- AntennaTracker/GCS_Mavlink.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/AntennaTracker/GCS_Mavlink.cpp b/AntennaTracker/GCS_Mavlink.cpp index 0fbe19edaa8ca8..919a7c7305cd95 100644 --- a/AntennaTracker/GCS_Mavlink.cpp +++ b/AntennaTracker/GCS_Mavlink.cpp @@ -313,6 +313,7 @@ static const ap_message STREAM_EXTRA3_msgs[] = { MSG_MAG_CAL_PROGRESS, #endif MSG_EKF_STATUS_REPORT, + MSG_BATTERY_STATUS, }; static const ap_message STREAM_PARAMS_msgs[] = { MSG_NEXT_PARAM From 5acf58c310aeb578259fc4c6d57a80edfba66d0b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 7 Jan 2024 12:30:38 +1100 Subject: [PATCH 0429/1335] autotest: add test for receiving base messages --- Tools/autotest/antennatracker.py | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/Tools/autotest/antennatracker.py b/Tools/autotest/antennatracker.py index b06df26492126c..438e6d7ce66587 100644 --- a/Tools/autotest/antennatracker.py +++ b/Tools/autotest/antennatracker.py @@ -162,6 +162,13 @@ def SCAN(self): timeout=90, comparator=operator.le) + def BaseMessageSet(self): + '''ensure we're getting messages we expect''' + self.set_parameter('BATT_MONITOR', 4) + self.reboot_sitl() + for msg in 'BATTERY_STATUS', : + self.assert_receive_message(msg) + def disabled_tests(self): return { "ArmFeatures": "See https://github.com/ArduPilot/ardupilot/issues/10652", @@ -178,5 +185,6 @@ def tests(self): self.MAV_CMD_MISSION_START, self.NMEAOutput, self.SCAN, + self.BaseMessageSet, ]) return ret From 7292c89766b294e1280662392ab5f1cf6a442f8f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 4 Jan 2024 13:30:41 +1100 Subject: [PATCH 0430/1335] AP_Networking: auto-restart PPP on error this makes it easier to handle startup timing with PPP --- libraries/AP_Networking/AP_Networking_PPP.cpp | 101 ++++++------------ libraries/AP_Networking/AP_Networking_PPP.h | 1 + 2 files changed, 34 insertions(+), 68 deletions(-) diff --git a/libraries/AP_Networking/AP_Networking_PPP.cpp b/libraries/AP_Networking/AP_Networking_PPP.cpp index b5437de9e4a71f..13929634e79239 100644 --- a/libraries/AP_Networking/AP_Networking_PPP.cpp +++ b/libraries/AP_Networking/AP_Networking_PPP.cpp @@ -53,70 +53,28 @@ void AP_Networking_PPP::ppp_status_callback(struct ppp_pcb_s *pcb, int code, voi { auto &driver = *(AP_Networking_PPP *)ctx; struct netif *pppif = ppp_netif(pcb); - const char *msg = nullptr; switch (code) { - case PPPERR_NONE: { - // got addresses + case PPPERR_NONE: + // got new addresses for the link driver.activeSettings.ip = ntohl(netif_ip4_addr(pppif)->addr); driver.activeSettings.gw = ntohl(netif_ip4_gw(pppif)->addr); driver.activeSettings.nm = ntohl(netif_ip4_netmask(pppif)->addr); driver.activeSettings.last_change_ms = AP_HAL::millis(); - - break; - } - case PPPERR_PARAM: { /* Invalid parameter. */ - msg = "PPPERR_PARAM"; - break; - } - case PPPERR_OPEN: { /* Unable to open PPP session. */ - msg = "PPPERR_OPEN"; - break; - } - case PPPERR_DEVICE: { /* Invalid I/O device for PPP. */ - msg = "PPPERR_DEVICE"; - break; - } - case PPPERR_ALLOC: { /* Unable to allocate resources. */ - msg = "PPPERR_ALLOC"; - break; - } - case PPPERR_USER: { /* User interrupt. */ - msg = "PPPERR_USER"; - break; - } - case PPPERR_CONNECT: { /* Connection lost. */ - msg = "PPPERR_CONNECT"; - break; - } - case PPPERR_AUTHFAIL: { /* Failed authentication challenge. */ - msg = "PPPERR_AUTHFAIL"; - break; - } - case PPPERR_PROTOCOL: { /* Failed to meet protocol. */ - msg = "PPPERR_PROTOCOL"; - break; - } - case PPPERR_PEERDEAD: { /* Connection timeout */ - msg = "PPPERR_PEERDEAD"; break; - } - case PPPERR_IDLETIMEOUT: { /* Idle Timeout */ - msg = "PPPERR_IDLETIMEOUT"; - break; - } - case PPPERR_CONNECTTIME: { /* Max connect time reached */ - msg = "PPPERR_CONNECTTIME"; + + case PPPERR_OPEN: + case PPPERR_CONNECT: + case PPPERR_PEERDEAD: + case PPPERR_IDLETIMEOUT: + case PPPERR_CONNECTTIME: + driver.need_restart = true; break; - } - case PPPERR_LOOPBACK: { /* Loopback detected */ - msg = "PPPERR_LOOPBACK"; + + default: + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "PPP: error %d", code); break; } - } - if (msg != nullptr) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "PPP: %s", msg); - } } @@ -169,13 +127,6 @@ void AP_Networking_PPP::ppp_loop(void) while (!hal.scheduler->is_system_initialized()) { hal.scheduler->delay_microseconds(1000); } - - // connect and set as default route - LWIP_TCPIP_LOCK(); - ppp_connect(ppp, 0); - - netif_set_default(pppif); - LWIP_TCPIP_UNLOCK(); // ensure this thread owns the uart uart->begin(0); @@ -183,13 +134,27 @@ void AP_Networking_PPP::ppp_loop(void) while (true) { uint8_t buf[1024]; - auto n = uart->read(buf, sizeof(buf)); - if (n > 0) { - LWIP_TCPIP_LOCK(); - pppos_input(ppp, buf, n); - LWIP_TCPIP_UNLOCK(); - } else { - hal.scheduler->delay_microseconds(200); + + // connect and set as default route + LWIP_TCPIP_LOCK(); + ppp_connect(ppp, 0); + + netif_set_default(pppif); + LWIP_TCPIP_UNLOCK(); + + need_restart = false; + + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "PPP: connected"); + + while (!need_restart) { + auto n = uart->read(buf, sizeof(buf)); + if (n > 0) { + LWIP_TCPIP_LOCK(); + pppos_input(ppp, buf, n); + LWIP_TCPIP_UNLOCK(); + } else { + hal.scheduler->delay_microseconds(200); + } } } } diff --git a/libraries/AP_Networking/AP_Networking_PPP.h b/libraries/AP_Networking/AP_Networking_PPP.h index e04b9ec2345a36..7e4a16d60a5a27 100644 --- a/libraries/AP_Networking/AP_Networking_PPP.h +++ b/libraries/AP_Networking/AP_Networking_PPP.h @@ -21,6 +21,7 @@ class AP_Networking_PPP : public AP_Networking_Backend AP_HAL::UARTDriver *uart; struct netif *pppif; struct ppp_pcb_s *ppp; + bool need_restart; static void ppp_status_callback(struct ppp_pcb_s *pcb, int code, void *ctx); static uint32_t ppp_output_cb(struct ppp_pcb_s *pcb, const void *data, uint32_t len, void *ctx); From efac52136b9b9defa6e181bcbc17b9b4255feca9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 4 Jan 2024 10:23:57 +1100 Subject: [PATCH 0431/1335] AP_Scripting: fixed memory leak in sendfile() this leaked the SocketAPM on each sendfile() call, we now rely on the script calling close(). The net_webserver.lua is already using close() correctly, this change just makes close able to find the socket --- libraries/AP_Scripting/AP_Scripting.cpp | 1 - libraries/AP_Scripting/AP_Scripting.h | 1 - libraries/AP_Scripting/lua_bindings.cpp | 77 +++++++++---------------- 3 files changed, 28 insertions(+), 51 deletions(-) diff --git a/libraries/AP_Scripting/AP_Scripting.cpp b/libraries/AP_Scripting/AP_Scripting.cpp index 1240c6e070b2cc..86dab106f3fe09 100644 --- a/libraries/AP_Scripting/AP_Scripting.cpp +++ b/libraries/AP_Scripting/AP_Scripting.cpp @@ -328,7 +328,6 @@ void AP_Scripting::thread(void) { _net_sockets[i] = nullptr; } } - num_net_sockets = 0; #endif // AP_NETWORKING_ENABLED // Clear blocked commands diff --git a/libraries/AP_Scripting/AP_Scripting.h b/libraries/AP_Scripting/AP_Scripting.h index 158ad429ac3ebc..f7139775c02f6b 100644 --- a/libraries/AP_Scripting/AP_Scripting.h +++ b/libraries/AP_Scripting/AP_Scripting.h @@ -121,7 +121,6 @@ class AP_Scripting #if AP_NETWORKING_ENABLED // SocketAPM storage - uint8_t num_net_sockets; SocketAPM *_net_sockets[SCRIPTING_MAX_NUM_NET_SOCKET]; #endif diff --git a/libraries/AP_Scripting/lua_bindings.cpp b/libraries/AP_Scripting/lua_bindings.cpp index f1ae9a99875678..ffa3e349fe00b9 100644 --- a/libraries/AP_Scripting/lua_bindings.cpp +++ b/libraries/AP_Scripting/lua_bindings.cpp @@ -794,22 +794,20 @@ int lua_get_SocketAPM(lua_State *L) { const uint8_t datagram = get_uint8_t(L, 1); auto *scripting = AP::scripting(); - if (scripting->num_net_sockets >= SCRIPTING_MAX_NUM_NET_SOCKET) { - return luaL_argerror(L, 1, "no sockets available"); - } - auto *sock = new SocketAPM(datagram); if (sock == nullptr) { return luaL_argerror(L, 1, "SocketAPM device nullptr"); } - scripting->_net_sockets[scripting->num_net_sockets] = sock; - - new_SocketAPM(L); - *((SocketAPM**)luaL_checkudata(L, -1, "SocketAPM")) = scripting->_net_sockets[scripting->num_net_sockets]; - - scripting->num_net_sockets++; + for (uint8_t i=0; i_net_sockets[i] == nullptr) { + scripting->_net_sockets[i] = sock; + new_SocketAPM(L); + *((SocketAPM**)luaL_checkudata(L, -1, "SocketAPM")) = scripting->_net_sockets[i]; + return 1; + } + } - return 1; + return luaL_argerror(L, 1, "no sockets available"); } /* @@ -822,17 +820,12 @@ int SocketAPM_close(lua_State *L) { auto *scripting = AP::scripting(); - if (scripting->num_net_sockets == 0) { - return luaL_argerror(L, 1, "socket close error"); - } - // clear allocated socket for (uint8_t i=0; i_net_sockets[i] == ud) { ud->close(); delete ud; scripting->_net_sockets[i] = nullptr; - scripting->num_net_sockets--; break; } } @@ -848,28 +841,15 @@ int SocketAPM_sendfile(lua_State *L) { SocketAPM *ud = *check_SocketAPM(L, 1); - auto *scripting = AP::scripting(); - - if (scripting->num_net_sockets == 0) { - return luaL_argerror(L, 1, "sendfile error"); - } - auto *p = (luaL_Stream *)luaL_checkudata(L, 2, LUA_FILEHANDLE); int fd = p->f->fd; - bool ret = false; - // find the socket - for (uint8_t i=0; i_net_sockets[i] == ud) { - ret = AP::network().sendfile(ud, fd); - if (ret) { - // remove from scripting, leave socket and fd open - p->f->fd = -1; - scripting->_net_sockets[i] = nullptr; - scripting->num_net_sockets--; - } - break; - } + bool ret = fd != -1 && AP::network().sendfile(ud, fd); + if (ret) { + // the fd is no longer valid. The lua script must + // still call close() to release the memory from the + // socket + p->f->fd = -1; } lua_pushboolean(L, ret); @@ -912,23 +892,22 @@ int SocketAPM_accept(lua_State *L) { SocketAPM * ud = *check_SocketAPM(L, 1); auto *scripting = AP::scripting(); - if (scripting->num_net_sockets >= SCRIPTING_MAX_NUM_NET_SOCKET) { - return 0; - } - auto *sock = ud->accept(0); - if (sock == nullptr) { - return 0; + // find an empty slot + for (uint8_t i=0; i_net_sockets[i] == nullptr) { + scripting->_net_sockets[i] = ud->accept(0); + if (scripting->_net_sockets[i] == nullptr) { + return 0; + } + new_SocketAPM(L); + *((SocketAPM**)luaL_checkudata(L, -1, "SocketAPM")) = scripting->_net_sockets[i]; + return 1; + } } - scripting->_net_sockets[scripting->num_net_sockets] = sock; - - new_SocketAPM(L); - *((SocketAPM**)luaL_checkudata(L, -1, "SocketAPM")) = scripting->_net_sockets[scripting->num_net_sockets]; - - scripting->num_net_sockets++; - - return 1; + // out of socket slots, return nil, caller can retry + return 0; } #endif // AP_NETWORKING_ENABLED From af898220e7eaf32f0ee82c01ba6cbd424274c098 Mon Sep 17 00:00:00 2001 From: coleschon Date: Tue, 31 Oct 2023 20:41:32 -0700 Subject: [PATCH 0432/1335] AP_TECS: improve velRateMin scaling wrt airspeed --- libraries/AP_TECS/AP_TECS.cpp | 16 +++++++++++++--- libraries/AP_TECS/AP_TECS.h | 7 ++++--- 2 files changed, 17 insertions(+), 6 deletions(-) diff --git a/libraries/AP_TECS/AP_TECS.cpp b/libraries/AP_TECS/AP_TECS.cpp index f5892d68585728..48f848c8320781 100644 --- a/libraries/AP_TECS/AP_TECS.cpp +++ b/libraries/AP_TECS/AP_TECS.cpp @@ -470,11 +470,19 @@ void AP_TECS::_update_speed_demand(void) // Constrain speed demand, taking into account the load factor _TAS_dem = constrain_float(_TAS_dem, _TASmin, _TASmax); + // Determine the true cruising airspeed (m/s) + const float TAScruise = 0.01f * (float)aparm.airspeed_cruise_cm * _ahrs.get_EAS2TAS(); + // calculate velocity rate limits based on physical performance limits // provision to use a different rate limit if bad descent or underspeed condition exists - // Use 50% of maximum energy rate to allow margin for total energy contgroller + // Use 50% of maximum energy rate on gain, 90% on dissipation to allow margin for total energy controller const float velRateMax = 0.5f * _STEdot_max / _TAS_state; - const float velRateMin = 0.5f * _STEdot_min / _TAS_state; + // Maximum permissible rate of deceleration value at max airspeed + const float velRateNegMax = 0.9f * _STEdot_neg_max / _TASmax; + // Maximum permissible rate of deceleration value at cruise speed + const float velRateNegCruise = 0.9f * _STEdot_min / TAScruise; + // Linear interpolation between velocity rate at cruise and max speeds, capped at those speeds + const float velRateMin = linear_interpolate(velRateNegMax, velRateNegCruise, _TAS_state, _TASmax, TAScruise); const float TAS_dem_previous = _TAS_dem_adj; // Apply rate limit @@ -1163,10 +1171,12 @@ void AP_TECS::_initialise_states(int32_t ptchMinCO_cd, float hgt_afe) void AP_TECS::_update_STE_rate_lim(void) { - // Calculate Specific Total Energy Rate Limits + // Calculate Specific Total Energy Rate Limits & deceleration rate bounds + // Keep the 50% energy margin from the original velRate calculation for now // This is a trivial calculation at the moment but will get bigger once we start adding altitude effects _STEdot_max = _climb_rate_limit * GRAVITY_MSS; _STEdot_min = - _minSinkRate * GRAVITY_MSS; + _STEdot_neg_max = - _maxSinkRate * GRAVITY_MSS; } diff --git a/libraries/AP_TECS/AP_TECS.h b/libraries/AP_TECS/AP_TECS.h index 4b83d133fa2df0..b392a0bfc555be 100644 --- a/libraries/AP_TECS/AP_TECS.h +++ b/libraries/AP_TECS/AP_TECS.h @@ -349,9 +349,10 @@ class AP_TECS { // pitch demand before limiting float _pitch_dem_unc; - // Maximum and minimum specific total energy rate limits - float _STEdot_max; - float _STEdot_min; + // Specific total energy rate limits + float _STEdot_max; // Specific total energy rate gain at cruise airspeed & THR_MAX (m/s/s) + float _STEdot_min; // Specific total energy rate loss at cruise airspeed & THR_MIN (m/s/s) + float _STEdot_neg_max; // Specific total energy rate loss at max airspeed & THR_MIN (m/s/s) // Maximum and minimum floating point throttle limits float _THRmaxf; From 147c5ad78dc2ecdc4018a1f7dacf0eb5b40d397b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 8 Jan 2024 13:07:46 +1100 Subject: [PATCH 0433/1335] AP_HAL: move simulated height_agl into fdm structure allows value to be shipped via multicast to simulated peripherals --- libraries/AP_HAL/SIMState.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL/SIMState.cpp b/libraries/AP_HAL/SIMState.cpp index b7c562f3b47d80..47cd3d4e79bbf8 100644 --- a/libraries/AP_HAL/SIMState.cpp +++ b/libraries/AP_HAL/SIMState.cpp @@ -384,7 +384,7 @@ void SIMState::set_height_agl(void) AP_Terrain *_terrain = AP_Terrain::get_singleton(); if (_terrain != nullptr && _terrain->height_amsl(location, terrain_height_amsl)) { - _sitl->height_agl = _sitl->state.altitude - terrain_height_amsl; + _sitl->state.height_agl = _sitl->state.altitude - terrain_height_amsl; return; } } @@ -392,7 +392,7 @@ void SIMState::set_height_agl(void) if (_sitl != nullptr) { // fall back to flat earth model - _sitl->height_agl = _sitl->state.altitude - home_alt; + _sitl->state.height_agl = _sitl->state.altitude - home_alt; } } From 7201eae4edf537cc23f2bab859ce7eb1b835bf89 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 8 Jan 2024 13:07:46 +1100 Subject: [PATCH 0434/1335] AP_HAL_SITL: move simulated height_agl into fdm structure allows value to be shipped via multicast to simulated peripherals --- libraries/AP_HAL_SITL/SITL_State.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_SITL/SITL_State.cpp b/libraries/AP_HAL_SITL/SITL_State.cpp index e2e27e1fa0df2b..02810a9ac3b433 100644 --- a/libraries/AP_HAL_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_State.cpp @@ -598,7 +598,7 @@ void SITL_State::set_height_agl(void) AP_Terrain *_terrain = AP_Terrain::get_singleton(); if (_terrain != nullptr && _terrain->height_amsl(location, terrain_height_amsl, false)) { - _sitl->height_agl = _sitl->state.altitude - terrain_height_amsl; + _sitl->state.height_agl = _sitl->state.altitude - terrain_height_amsl; return; } } @@ -606,7 +606,7 @@ void SITL_State::set_height_agl(void) if (_sitl != nullptr) { // fall back to flat earth model - _sitl->height_agl = _sitl->state.altitude - home_alt; + _sitl->state.height_agl = _sitl->state.altitude - home_alt; } } From b1311d6d256b89d85f10f9d2afc4e6459cd15100 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 8 Jan 2024 13:07:46 +1100 Subject: [PATCH 0435/1335] AP_OpticalFlow: move simulated height_agl into fdm structure allows value to be shipped via multicast to simulated peripherals --- libraries/AP_OpticalFlow/AP_OpticalFlow_SITL.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_SITL.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_SITL.cpp index 5ac842daba2f2a..d2382543134db1 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_SITL.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_SITL.cpp @@ -64,9 +64,9 @@ void AP_OpticalFlow_SITL::update(void) // estimate range to centre of image float range; - if (rotmat.c.z > 0.05f && _sitl->height_agl > 0) { + if (rotmat.c.z > 0.05f && _sitl->state.height_agl > 0) { Vector3f relPosSensorEF = rotmat * posRelSensorBF; - range = (_sitl->height_agl - relPosSensorEF.z) / rotmat.c.z; + range = (_sitl->state.height_agl - relPosSensorEF.z) / rotmat.c.z; } else { range = 1e38f; } From c583edc34b6609861c1d46dcbadbc9fa83a1e568 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 8 Jan 2024 13:07:46 +1100 Subject: [PATCH 0436/1335] AP_Proximity: move simulated height_agl into fdm structure allows value to be shipped via multicast to simulated peripherals --- libraries/AP_Proximity/AP_Proximity_SITL.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Proximity/AP_Proximity_SITL.cpp b/libraries/AP_Proximity/AP_Proximity_SITL.cpp index 1d72a8ebed41db..6c1e6dcdb72e62 100644 --- a/libraries/AP_Proximity/AP_Proximity_SITL.cpp +++ b/libraries/AP_Proximity/AP_Proximity_SITL.cpp @@ -131,7 +131,7 @@ float AP_Proximity_SITL::distance_min() const bool AP_Proximity_SITL::get_upward_distance(float &distance) const { // return distance to fence altitude - distance = MAX(0.0f, fence_alt_max->get() - sitl->height_agl); + distance = MAX(0.0f, fence_alt_max->get() - sitl->state.height_agl); return true; } From 3a37796eb268d35a84a548c1b09bf25c48abc5be Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 8 Jan 2024 13:07:46 +1100 Subject: [PATCH 0437/1335] SITL: move simulated height_agl into fdm structure allows value to be shipped via multicast to simulated peripherals --- libraries/SITL/SIM_Aircraft.cpp | 2 +- libraries/SITL/SITL.h | 7 ++++--- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/libraries/SITL/SIM_Aircraft.cpp b/libraries/SITL/SIM_Aircraft.cpp index c718d76bd0db5f..58b22308a0e80c 100644 --- a/libraries/SITL/SIM_Aircraft.cpp +++ b/libraries/SITL/SIM_Aircraft.cpp @@ -490,7 +490,7 @@ float Aircraft::perpendicular_distance_to_rangefinder_surface() const { switch ((Rotation)sitl->sonar_rot.get()) { case Rotation::ROTATION_PITCH_270: - return sitl->height_agl; + return sitl->state.height_agl; case ROTATION_NONE ... ROTATION_YAW_315: return sitl->measure_distance_at_angle_bf(location, sitl->sonar_rot.get()*45); default: diff --git a/libraries/SITL/SITL.h b/libraries/SITL/SITL.h index 24dbdac91a6aec..68b30ddeb97a5a 100644 --- a/libraries/SITL/SITL.h +++ b/libraries/SITL/SITL.h @@ -92,6 +92,10 @@ struct sitl_fdm { // earthframe wind, from backends that know it Vector3f wind_ef; + + // AGL altitude, usually derived from the terrain database in simulation: + float height_agl; + }; // number of rc output channels @@ -152,9 +156,6 @@ class SIM { // throttle when motors are active float throttle; - // height above ground - float height_agl; - static const struct AP_Param::GroupInfo var_info[]; static const struct AP_Param::GroupInfo var_info2[]; static const struct AP_Param::GroupInfo var_info3[]; From 0cf616044caa7a79de481e0743749413461b807c Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 8 Jan 2024 15:19:34 +0900 Subject: [PATCH 0438/1335] AC_WPNav: ACCEL_C defaults to 2x ACCEL --- libraries/AC_WPNav/AC_WPNav.cpp | 2 +- libraries/AC_WPNav/AC_WPNav.h | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AC_WPNav/AC_WPNav.cpp b/libraries/AC_WPNav/AC_WPNav.cpp index e2163264e01abf..be5c7ac97873d5 100644 --- a/libraries/AC_WPNav/AC_WPNav.cpp +++ b/libraries/AC_WPNav/AC_WPNav.cpp @@ -94,7 +94,7 @@ const AP_Param::GroupInfo AC_WPNav::var_info[] = { // @Param: ACCEL_C // @DisplayName: Waypoint Cornering Acceleration - // @Description: Defines the maximum cornering acceleration in cm/s/s used during missions, zero uses max lean angle. + // @Description: Defines the maximum cornering acceleration in cm/s/s used during missions. If zero uses 2x accel value. // @Units: cm/s/s // @Range: 0 500 // @Increment: 10 diff --git a/libraries/AC_WPNav/AC_WPNav.h b/libraries/AC_WPNav/AC_WPNav.h index 74bd95075c92af..5e2249597698d6 100644 --- a/libraries/AC_WPNav/AC_WPNav.h +++ b/libraries/AC_WPNav/AC_WPNav.h @@ -87,8 +87,8 @@ class AC_WPNav /// get_wp_acceleration - returns acceleration in cm/s/s during missions float get_wp_acceleration() const { return (is_positive(_wp_accel_cmss)) ? _wp_accel_cmss : WPNAV_ACCELERATION; } - /// get_wp_acceleration - returns acceleration in cm/s/s during missions - float get_corner_acceleration() const { return (is_positive(_wp_accel_c_cmss)) ? _wp_accel_c_cmss : get_wp_acceleration(); } + /// get_corner_acceleration - returns maximum acceleration in cm/s/s used during cornering in missions + float get_corner_acceleration() const { return (is_positive(_wp_accel_c_cmss)) ? _wp_accel_c_cmss : 2.0 * get_wp_acceleration(); } /// get_wp_destination waypoint using position vector /// x,y are distance from ekf origin in cm From fd855781d83d2526713d33f387ffe936b9e22656 Mon Sep 17 00:00:00 2001 From: Bob Long Date: Sat, 6 Jan 2024 14:42:52 +1100 Subject: [PATCH 0439/1335] AP_BattMonitor: add scripting backend AP_BattMonitor_Scripting: whitespace consistency --- libraries/AP_BattMonitor/AP_BattMonitor.cpp | 19 +++++ libraries/AP_BattMonitor/AP_BattMonitor.h | 7 ++ .../AP_BattMonitor/AP_BattMonitor_Backend.h | 26 +++++- .../AP_BattMonitor/AP_BattMonitor_Params.cpp | 2 +- .../AP_BattMonitor_Scripting.cpp | 84 +++++++++++++++++++ .../AP_BattMonitor/AP_BattMonitor_Scripting.h | 32 +++++++ .../AP_BattMonitor/AP_BattMonitor_config.h | 3 + 7 files changed, 171 insertions(+), 2 deletions(-) create mode 100644 libraries/AP_BattMonitor/AP_BattMonitor_Scripting.cpp create mode 100644 libraries/AP_BattMonitor/AP_BattMonitor_Scripting.h diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.cpp b/libraries/AP_BattMonitor/AP_BattMonitor.cpp index 45f630ce3bb6f1..35819b8d2efc0f 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor.cpp @@ -21,6 +21,7 @@ #include "AP_BattMonitor_FuelLevel_Analog.h" #include "AP_BattMonitor_Synthetic_Current.h" #include "AP_BattMonitor_AD7091R5.h" +#include "AP_BattMonitor_Scripting.h" #include @@ -560,6 +561,11 @@ AP_BattMonitor::init() drivers[instance] = new AP_BattMonitor_AD7091R5(*this, state[instance], _params[instance]); break; #endif// AP_BATTERY_AD7091R5_ENABLED +#if AP_BATTERY_SCRIPTING_ENABLED + case Type::Scripting: + drivers[instance] = new AP_BattMonitor_Scripting(*this, state[instance], _params[instance]); + break; +#endif // AP_BATTERY_SCRIPTING_ENABLED case Type::NONE: default: break; @@ -1081,6 +1087,19 @@ bool AP_BattMonitor::healthy() const return true; } +#if AP_BATTERY_SCRIPTING_ENABLED +/* + handle state update from a lua script + */ +bool AP_BattMonitor::handle_scripting(uint8_t idx, const BattMonitorScript_State &_state) +{ + if (idx >= _num_instances) { + return false; + } + return drivers[idx]->handle_scripting(_state); +} +#endif + namespace AP { AP_BattMonitor &battery() diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.h b/libraries/AP_BattMonitor/AP_BattMonitor.h index dbeed2e470ff18..2df3fd5210830d 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor.h @@ -45,6 +45,7 @@ class AP_BattMonitor_LTC2946; class AP_BattMonitor_Torqeedo; class AP_BattMonitor_FuelLevel_Analog; class AP_BattMonitor_EFI; +class AP_BattMonitor_Scripting; class AP_BattMonitor @@ -70,6 +71,7 @@ class AP_BattMonitor friend class AP_BattMonitor_Torqeedo; friend class AP_BattMonitor_FuelLevel_Analog; friend class AP_BattMonitor_Synthetic_Current; + friend class AP_BattMonitor_Scripting; public: @@ -109,6 +111,7 @@ class AP_BattMonitor INA239_SPI = 26, EFI = 27, AD7091R5 = 28, + Scripting = 29, }; FUNCTOR_TYPEDEF(battery_failsafe_handler_fn_t, void, const char *, const int8_t); @@ -273,6 +276,10 @@ class AP_BattMonitor static const struct AP_Param::GroupInfo var_info[]; +#if AP_BATTERY_SCRIPTING_ENABLED + bool handle_scripting(uint8_t idx, const struct BattMonitorScript_State &state); +#endif + protected: /// parameters diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Backend.h b/libraries/AP_BattMonitor/AP_BattMonitor_Backend.h index 85d62127708c82..8cc972e7e8a5e9 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Backend.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Backend.h @@ -63,7 +63,7 @@ class AP_BattMonitor_Backend float voltage_resting_estimate() const; // update battery resistance estimate and voltage_resting_estimate - void update_resistance_estimate(); + virtual void update_resistance_estimate(); // updates failsafe timers, and returns what failsafes are active virtual AP_BattMonitor::Failsafe update_failsafes(void); @@ -95,6 +95,10 @@ class AP_BattMonitor_Backend bool option_is_set(const AP_BattMonitor_Params::Options option) const { return (uint16_t(_params._options.get()) & uint16_t(option)) != 0; } + +#if AP_BATTERY_SCRIPTING_ENABLED + virtual bool handle_scripting(const BattMonitorScript_State &battmon_state) { return false; } +#endif protected: AP_BattMonitor &_mon; // reference to front-end @@ -114,3 +118,23 @@ class AP_BattMonitor_Backend float _resistance_voltage_ref; // voltage used for maximum resistance calculation float _resistance_current_ref; // current used for maximum resistance calculation }; + +#if AP_BATTERY_SCRIPTING_ENABLED +struct BattMonitorScript_State { + float voltage; // Battery voltage in volts + bool healthy; // True if communicating properly + uint8_t cell_count; // Number of valid cells in state + uint8_t capacity_remaining_pct=UINT8_MAX; // Remaining battery capacity in percent, 255 for invalid + uint16_t cell_voltages[32]; // allow script to have up to 32 cells, will be limited internally + uint16_t cycle_count=UINT16_MAX; // Battery cycle count, 65535 for unavailable + /* + all of the following float variables should be set to NaN by the + script if they are not known. + consumed_mah will auto-integrate if set to NaN + */ + float current_amps=nanf(""); // Battery current in amperes + float consumed_mah=nanf(""); // Total current drawn since start-up in milliampere hours + float consumed_wh=nanf(""); // Total energy drawn since start-up in watt hours + float temperature=nanf(""); // Battery temperature in degrees Celsius +}; +#endif // AP_BATTERY_SCRIPTING_ENABLED diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp index 5302bf77306a66..0eb859d2a4f833 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Params.cpp @@ -17,7 +17,7 @@ const AP_Param::GroupInfo AP_BattMonitor_Params::var_info[] = { // @Param: MONITOR // @DisplayName: Battery monitoring // @Description: Controls enabling monitoring of the battery's voltage and current - // @Values: 0:Disabled,3:Analog Voltage Only,4:Analog Voltage and Current,5:Solo,6:Bebop,7:SMBus-Generic,8:DroneCAN-BatteryInfo,9:ESC,10:Sum Of Selected Monitors,11:FuelFlow,12:FuelLevelPWM,13:SMBUS-SUI3,14:SMBUS-SUI6,15:NeoDesign,16:SMBus-Maxell,17:Generator-Elec,18:Generator-Fuel,19:Rotoye,20:MPPT,21:INA2XX,22:LTC2946,23:Torqeedo,24:FuelLevelAnalog,25:Synthetic Current and Analog Voltage,26:INA239_SPI,27:EFI,28:AD7091R5 + // @Values: 0:Disabled,3:Analog Voltage Only,4:Analog Voltage and Current,5:Solo,6:Bebop,7:SMBus-Generic,8:DroneCAN-BatteryInfo,9:ESC,10:Sum Of Selected Monitors,11:FuelFlow,12:FuelLevelPWM,13:SMBUS-SUI3,14:SMBUS-SUI6,15:NeoDesign,16:SMBus-Maxell,17:Generator-Elec,18:Generator-Fuel,19:Rotoye,20:MPPT,21:INA2XX,22:LTC2946,23:Torqeedo,24:FuelLevelAnalog,25:Synthetic Current and Analog Voltage,26:INA239_SPI,27:EFI,28:AD7091R5,29:Scripting // @User: Standard // @RebootRequired: True AP_GROUPINFO_FLAGS("MONITOR", 1, AP_BattMonitor_Params, _type, int8_t(AP_BattMonitor::Type::NONE), AP_PARAM_FLAG_ENABLE), diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Scripting.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Scripting.cpp new file mode 100644 index 00000000000000..337c9d9b7ac2c1 --- /dev/null +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Scripting.cpp @@ -0,0 +1,84 @@ +#include "AP_BattMonitor_Scripting.h" + +#if AP_BATTERY_SCRIPTING_ENABLED + +#define AP_BATT_MONITOR_SCRIPTING_TIMEOUT_US 5000000 + +bool AP_BattMonitor_Scripting::capacity_remaining_pct(uint8_t &percentage) const +{ + if (internal_state.capacity_remaining_pct != UINT8_MAX) { + percentage = internal_state.capacity_remaining_pct; + return true; + } + // Fall back to default implementation + return AP_BattMonitor_Backend::capacity_remaining_pct(percentage); +} + +bool AP_BattMonitor_Scripting::get_cycle_count(uint16_t &cycles) const +{ + if (internal_state.cycle_count == UINT16_MAX) { + return false; + } + cycles = internal_state.cycle_count; + return true; +} + +// Called by frontend to update the state. Called at 10Hz +void AP_BattMonitor_Scripting::read() +{ + WITH_SEMAPHORE(sem); + + // Check for timeout, to prevent a faulty script from appearing healthy + if (last_update_us == 0 || AP_HAL::micros() - last_update_us > AP_BATT_MONITOR_SCRIPTING_TIMEOUT_US) { + _state.healthy = false; + return; + } + + if (_state.last_time_micros == last_update_us) { + // No new data + return; + } + + /* + the script can fill in voltages up to 32 cells, for mavlink reporting + the extra cell voltages get distributed over the max of 14 for mavlink + */ + for (uint8_t i = 0; i < MIN(AP_BATT_MONITOR_CELLS_MAX,internal_state.cell_count); i++) { + _state.cell_voltages.cells[i] = internal_state.cell_voltages[i]; + } + _state.voltage = internal_state.voltage; + if (!isnan(internal_state.current_amps)) { + _state.current_amps = internal_state.current_amps; + } + if (!isnan(internal_state.consumed_mah)) { + _state.consumed_mah = internal_state.consumed_mah; + } + // Overide integrated consumed energy with script value if it has been set + if (!isnan(internal_state.consumed_wh)) { + _state.consumed_wh = internal_state.consumed_wh; + } + if (!isnan(internal_state.temperature)) { + _state.temperature = internal_state.temperature; + } + + _state.healthy = internal_state.healthy; + + // Update the timestamp (has to be done after the consumed_mah calculation) + _state.last_time_micros = last_update_us; +} + +bool AP_BattMonitor_Scripting::handle_scripting(const BattMonitorScript_State &battmon_state) +{ + WITH_SEMAPHORE(sem); + internal_state = battmon_state; + const uint32_t now_us = AP_HAL::micros(); + uint32_t dt_us = now_us - last_update_us; + if (last_update_us != 0 && !isnan(internal_state.current_amps) && isnan(internal_state.consumed_mah)) { + AP_BattMonitor_Backend::update_consumed(_state, dt_us); + } + last_update_us = now_us; + return true; +} + +#endif // AP_BATTERY_SCRIPTING_ENABLED + diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Scripting.h b/libraries/AP_BattMonitor/AP_BattMonitor_Scripting.h new file mode 100644 index 00000000000000..f68f11b9dceb5b --- /dev/null +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Scripting.h @@ -0,0 +1,32 @@ +#pragma once + +#include "AP_BattMonitor_Backend.h" + +#if AP_BATTERY_SCRIPTING_ENABLED + +class AP_BattMonitor_Scripting : public AP_BattMonitor_Backend +{ +public: + // Inherit constructor + using AP_BattMonitor_Backend::AP_BattMonitor_Backend; + + bool has_current() const override { return last_update_us != 0 && !isnan(internal_state.current_amps); } + bool has_consumed_energy() const override { return has_current(); } + bool has_cell_voltages() const override { return internal_state.cell_count > 0; } + bool has_temperature() const override { return last_update_us != 0 && !isnan(internal_state.temperature); } + bool capacity_remaining_pct(uint8_t &percentage) const override; + bool get_cycle_count(uint16_t &cycles) const override; + + void read() override; + + bool handle_scripting(const BattMonitorScript_State &battmon_state) override; + +protected: + BattMonitorScript_State internal_state; + uint32_t last_update_us; + + HAL_Semaphore sem; +}; + +#endif // AP_BATTMONITOR_SCRIPTING_ENABLED + diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_config.h b/libraries/AP_BattMonitor/AP_BattMonitor_config.h index 92d5ad074e937f..e15909c1435794 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_config.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_config.h @@ -116,3 +116,6 @@ #define AP_BATTERY_SMBUS_ROTOYE_ENABLED AP_BATTERY_SMBUS_GENERIC_ENABLED #endif +#ifndef AP_BATTERY_SCRIPTING_ENABLED +#define AP_BATTERY_SCRIPTING_ENABLED (AP_SCRIPTING_ENABLED && AP_BATTERY_BACKEND_DEFAULT_ENABLED) +#endif From 1ffda7ef3c829a0f00702a3836ca904f5cb3127a Mon Sep 17 00:00:00 2001 From: Bob Long Date: Sat, 6 Jan 2024 14:42:52 +1100 Subject: [PATCH 0440/1335] AP_Scripting: add scripting backend AP_BattMonitor_Scripting: whitespace consistency --- libraries/AP_Scripting/docs/docs.lua | 158 ++++++++++++++++++ .../generator/description/bindings.desc | 14 ++ 2 files changed, 172 insertions(+) diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index 34ea6336d44169..053d98d9d829a8 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -817,6 +817,150 @@ function Vector3f_ud:normalize() end ---@return number function Vector3f_ud:length() end + +-- desc +---@class BattMonitorScript_State_ud +local BattMonitorScript_State_ud = {} + +---@return BattMonitorScript_State_ud +function BattMonitorScript_State() end + +-- get field +---@return number +function BattMonitorScript_State_ud:resting_voltage() end + +-- set field +---@param value number +function BattMonitorScript_State_ud:resting_voltage(value) end + +-- get field +---@return number +function BattMonitorScript_State_ud:resistance() end + +-- set field +---@param value number +function BattMonitorScript_State_ud:resistance(value) end + +-- get field +---@return uint32_t_ud +function BattMonitorScript_State_ud:mavlink_faults() end + +-- set field +---@param value uint32_t_ud +function BattMonitorScript_State_ud:mavlink_faults(value) end + +-- get field +---@return integer +---| '0' # None +---| '1' # Low +---| '2' # Critical +function BattMonitorScript_State_ud:failsafe() end + +-- set field +---@param value integer +---| '0' # None +---| '1' # Low +---| '2' # Critical +function BattMonitorScript_State_ud:failsafe(value) end + +-- get field +---@return uint32_t_ud +function BattMonitorScript_State_ud:time_remaining() end + +-- set field +---@param value uint32_t_ud +function BattMonitorScript_State_ud:time_remaining(value) end + +-- get field +---@return integer +function BattMonitorScript_State_ud:cycle_count() end + +-- set field +---@param value integer +function BattMonitorScript_State_ud:cycle_count(value) end + +-- get field +---@return integer +function BattMonitorScript_State_ud:capacity_remaining_pct() end + +-- set field +---@param value integer +function BattMonitorScript_State_ud:capacity_remaining_pct(value) end + +-- get field +---@return number +function BattMonitorScript_State_ud:temperature() end + +-- set field +---@param value number +function BattMonitorScript_State_ud:temperature(value) end + +-- get field +---@return number +function BattMonitorScript_State_ud:consumed_wh() end + +-- set field +---@param value number +function BattMonitorScript_State_ud:consumed_wh(value) end + +-- get field +---@return number +function BattMonitorScript_State_ud:consumed_mah() end + +-- set field +---@param value number +function BattMonitorScript_State_ud:consumed_mah(value) end + +-- get field +---@return number +function BattMonitorScript_State_ud:current_amps() end + +-- set field +---@param value number +function BattMonitorScript_State_ud:current_amps(value) end + +-- get array field +---@param index integer +---@return integer +function BattMonitorScript_State_ud:cell_voltages(index) end + +-- set array field +---@param index integer +---@param value integer +function BattMonitorScript_State_ud:cell_voltages(index, value) end + +-- get field +---@return integer +function BattMonitorScript_State_ud:cell_count() end + +-- set field +---@param value integer +function BattMonitorScript_State_ud:cell_count(value) end + +-- get field +---@return number +function BattMonitorScript_State_ud:voltage() end + +-- set field +---@param value number +function BattMonitorScript_State_ud:voltage(value) end + +-- get field +---@return boolean +function BattMonitorScript_State_ud:healthy() end + +-- set field +---@param value boolean +function BattMonitorScript_State_ud:healthy(value) end + +-- get field +---@return uint32_t_ud +function BattMonitorScript_State_ud:last_update_us() end + +-- set field +---@param value uint32_t_ud +function BattMonitorScript_State_ud:last_update_us(value) end + -- Computes angle between this vector and vector v2 ---@param v2 Vector3f_ud ---@return number @@ -1181,6 +1325,15 @@ function RC_Channel_ud:norm_input() end ---@return number function RC_Channel_ud:norm_input_dz() end +-- desc +---@class AP_BattMonitor_Backend_ud +local AP_BattMonitor_Backend_ud = {} + +-- desc +---@param battmon_state BattMonitorScript_State_ud +---@return boolean +function AP_BattMonitor_Backend_ud:handle_scripting(battmon_state) end + -- desc ---@class winch winch = {} @@ -2867,6 +3020,11 @@ function gps:num_sensors() end ---@class battery battery = {} +-- desc +---@param index integer +---@return AP_BattMonitor_Backend_ud +function battery:get_backend(index) end + -- desc ---@param instance integer ---@param percentage number diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index f0608bfcb39265..7cbc293a90d8cb 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -76,6 +76,19 @@ singleton AP_Arming method set_aux_auth_failed void uint8_t'skip_check string include AP_BattMonitor/AP_BattMonitor.h +include AP_BattMonitor/AP_BattMonitor_Scripting.h +userdata BattMonitorScript_State depends AP_BATTERY_SCRIPTING_ENABLED == 1 +userdata BattMonitorScript_State field healthy boolean write +userdata BattMonitorScript_State field voltage float'skip_check write +userdata BattMonitorScript_State field cell_count uint8_t'skip_check write +userdata BattMonitorScript_State field capacity_remaining_pct uint8_t'skip_check write +userdata BattMonitorScript_State field cell_voltages'array int(ARRAY_SIZE(ud->cell_voltages)) uint16_t'skip_check write +userdata BattMonitorScript_State field cycle_count uint16_t'skip_check write +userdata BattMonitorScript_State field current_amps float'skip_check write +userdata BattMonitorScript_State field consumed_mah float'skip_check write +userdata BattMonitorScript_State field consumed_wh float'skip_check write +userdata BattMonitorScript_State field temperature float'skip_check write + singleton AP_BattMonitor rename battery singleton AP_BattMonitor depends (!defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_BATTERY)) singleton AP_BattMonitor method num_instances uint8_t @@ -93,6 +106,7 @@ singleton AP_BattMonitor method get_temperature boolean float'Null uint8_t 0 ud- singleton AP_BattMonitor method get_cycle_count boolean uint8_t 0 ud->num_instances() uint16_t'Null singleton AP_BattMonitor method reset_remaining boolean uint8_t 0 ud->num_instances() float 0 100 singleton AP_BattMonitor method get_cell_voltage boolean uint8_t'skip_check uint8_t'skip_check float'Null +singleton AP_BattMonitor method handle_scripting boolean uint8_t'skip_check BattMonitorScript_State include AP_GPS/AP_GPS.h From 70d6788855be7b10434f5961ace7c39554595c5e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 6 Jan 2024 16:03:45 +1100 Subject: [PATCH 0441/1335] AP_Scripting: update docs --- libraries/AP_Scripting/docs/docs.lua | 207 +++++++-------------------- 1 file changed, 51 insertions(+), 156 deletions(-) diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index 053d98d9d829a8..b3b2deba2ff787 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -817,150 +817,6 @@ function Vector3f_ud:normalize() end ---@return number function Vector3f_ud:length() end - --- desc ----@class BattMonitorScript_State_ud -local BattMonitorScript_State_ud = {} - ----@return BattMonitorScript_State_ud -function BattMonitorScript_State() end - --- get field ----@return number -function BattMonitorScript_State_ud:resting_voltage() end - --- set field ----@param value number -function BattMonitorScript_State_ud:resting_voltage(value) end - --- get field ----@return number -function BattMonitorScript_State_ud:resistance() end - --- set field ----@param value number -function BattMonitorScript_State_ud:resistance(value) end - --- get field ----@return uint32_t_ud -function BattMonitorScript_State_ud:mavlink_faults() end - --- set field ----@param value uint32_t_ud -function BattMonitorScript_State_ud:mavlink_faults(value) end - --- get field ----@return integer ----| '0' # None ----| '1' # Low ----| '2' # Critical -function BattMonitorScript_State_ud:failsafe() end - --- set field ----@param value integer ----| '0' # None ----| '1' # Low ----| '2' # Critical -function BattMonitorScript_State_ud:failsafe(value) end - --- get field ----@return uint32_t_ud -function BattMonitorScript_State_ud:time_remaining() end - --- set field ----@param value uint32_t_ud -function BattMonitorScript_State_ud:time_remaining(value) end - --- get field ----@return integer -function BattMonitorScript_State_ud:cycle_count() end - --- set field ----@param value integer -function BattMonitorScript_State_ud:cycle_count(value) end - --- get field ----@return integer -function BattMonitorScript_State_ud:capacity_remaining_pct() end - --- set field ----@param value integer -function BattMonitorScript_State_ud:capacity_remaining_pct(value) end - --- get field ----@return number -function BattMonitorScript_State_ud:temperature() end - --- set field ----@param value number -function BattMonitorScript_State_ud:temperature(value) end - --- get field ----@return number -function BattMonitorScript_State_ud:consumed_wh() end - --- set field ----@param value number -function BattMonitorScript_State_ud:consumed_wh(value) end - --- get field ----@return number -function BattMonitorScript_State_ud:consumed_mah() end - --- set field ----@param value number -function BattMonitorScript_State_ud:consumed_mah(value) end - --- get field ----@return number -function BattMonitorScript_State_ud:current_amps() end - --- set field ----@param value number -function BattMonitorScript_State_ud:current_amps(value) end - --- get array field ----@param index integer ----@return integer -function BattMonitorScript_State_ud:cell_voltages(index) end - --- set array field ----@param index integer ----@param value integer -function BattMonitorScript_State_ud:cell_voltages(index, value) end - --- get field ----@return integer -function BattMonitorScript_State_ud:cell_count() end - --- set field ----@param value integer -function BattMonitorScript_State_ud:cell_count(value) end - --- get field ----@return number -function BattMonitorScript_State_ud:voltage() end - --- set field ----@param value number -function BattMonitorScript_State_ud:voltage(value) end - --- get field ----@return boolean -function BattMonitorScript_State_ud:healthy() end - --- set field ----@param value boolean -function BattMonitorScript_State_ud:healthy(value) end - --- get field ----@return uint32_t_ud -function BattMonitorScript_State_ud:last_update_us() end - --- set field ----@param value uint32_t_ud -function BattMonitorScript_State_ud:last_update_us(value) end - -- Computes angle between this vector and vector v2 ---@param v2 Vector3f_ud ---@return number @@ -1325,15 +1181,6 @@ function RC_Channel_ud:norm_input() end ---@return number function RC_Channel_ud:norm_input_dz() end --- desc ----@class AP_BattMonitor_Backend_ud -local AP_BattMonitor_Backend_ud = {} - --- desc ----@param battmon_state BattMonitorScript_State_ud ----@return boolean -function AP_BattMonitor_Backend_ud:handle_scripting(battmon_state) end - -- desc ---@class winch winch = {} @@ -3015,15 +2862,63 @@ function gps:primary_sensor() end ---@return integer function gps:num_sensors() end +-- desc +---@class BattMonitorScript_State_ud +local BattMonitorScript_State_ud = {} + +---@return BattMonitorScript_State_ud +function BattMonitorScript_State() end + +-- set field +---@param value number +function BattMonitorScript_State_ud:temperature(value) end + +-- set field +---@param value number +function BattMonitorScript_State_ud:consumed_wh(value) end + +-- set field +---@param value number +function BattMonitorScript_State_ud:consumed_mah(value) end + +-- set field +---@param value number +function BattMonitorScript_State_ud:current_amps(value) end + +-- set field +---@param value integer +function BattMonitorScript_State_ud:cycle_count(value) end + +-- set array field +---@param index integer +---@param value integer +function BattMonitorScript_State_ud:cell_voltages(index, value) end + +-- set field +---@param value integer +function BattMonitorScript_State_ud:capacity_remaining_pct(value) end + +-- set field +---@param value integer +function BattMonitorScript_State_ud:cell_count(value) end + +-- set field +---@param value number +function BattMonitorScript_State_ud:voltage(value) end + +-- set field +---@param value boolean +function BattMonitorScript_State_ud:healthy(value) end -- desc ---@class battery battery = {} -- desc ----@param index integer ----@return AP_BattMonitor_Backend_ud -function battery:get_backend(index) end +---@param idx integer +---@param state BattMonitorScript_State_ud +---@return boolean +function battery:handle_scripting(idx, state) end -- desc ---@param instance integer From 098277ce6a3789797fe13ffb4e9d3f27991006be Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 6 Jan 2024 16:23:24 +1100 Subject: [PATCH 0442/1335] AP_Scripting: added ANX CAN battery driver --- .../AP_Scripting/drivers/BattMon_ANX.lua | 253 ++++++++++++++++++ libraries/AP_Scripting/drivers/BattMon_ANX.md | 20 ++ 2 files changed, 273 insertions(+) create mode 100644 libraries/AP_Scripting/drivers/BattMon_ANX.lua create mode 100644 libraries/AP_Scripting/drivers/BattMon_ANX.md diff --git a/libraries/AP_Scripting/drivers/BattMon_ANX.lua b/libraries/AP_Scripting/drivers/BattMon_ANX.lua new file mode 100644 index 00000000000000..80b32b924dc8e8 --- /dev/null +++ b/libraries/AP_Scripting/drivers/BattMon_ANX.lua @@ -0,0 +1,253 @@ +--[[ + device driver for ANX CAN battery monitor +--]] + +local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7} + +local PARAM_TABLE_KEY = 45 +local PARAM_TABLE_PREFIX = "BATT_ANX_" + +-- add a parameter and bind it to a variable +function bind_add_param(name, idx, default_value) + assert(param:add_param(PARAM_TABLE_KEY, idx, name, default_value), string.format('could not add param %s', name)) + return Parameter(PARAM_TABLE_PREFIX .. name) +end + +-- Type conversion functions, little endian +function get_uint16(frame, ofs) + return frame:data(ofs) + (frame:data(ofs + 1) << 8) +end + +-- Setup EFI Parameters +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 15), 'could not add param table') + +--[[ + // @Param: BATT_ANX_ENABLE + // @DisplayName: Enable ANX battery support + // @Description: Enable ANX battery support + // @Values: 0:Disabled,1:Enabled + // @User: Standard +--]] +local BATT_ANX_ENABLE = bind_add_param('ENABLE', 1, 0) + +--[[ + // @Param: BATT_ANX_CANDRV + // @DisplayName: Set ANX CAN driver + // @Description: Set ANX CAN driver + // @Values: 0:None,1:1stCANDriver,2:2ndCanDriver + // @User: Standard +--]] +local BATT_ANX_CANDRV = bind_add_param('CANDRV', 2, 1) + +--[[ + // @Param: BATT_ANX_INDEX + // @DisplayName: ANX CAN battery index + // @Description: ANX CAN battery index + // @Range: 1 10 + // @User: Standard +--]] +local BATT_ANX_INDEX = bind_add_param('INDEX', 3, 1) + +--[[ + // @Param: BATT_ANX_OPTIONS + // @DisplayName: ANX CAN battery options + // @Description: ANX CAN battery options + // @Bitmask: 0:LogAllFrames + // @User: Advanced +--]] +local BATT_ANX_OPTIONS = bind_add_param('OPTIONS', 4, 0) + +local OPTION_LOGALLFRAMES = 0x01 + +if BATT_ANX_ENABLE:get() == 0 then + gcs:send_text(0, string.format("BATT_ANX: disabled")) + return +end + +-- Register for the CAN drivers +local driver + +local CAN_BUF_LEN = 25 +if BATT_ANX_CANDRV:get() == 1 then + driver = CAN.get_device(CAN_BUF_LEN) +elseif BATT_ANX_CANDRV:get() == 2 then + driver = CAN.get_device2(CAN_BUF_LEN) +end + +if not driver then + gcs:send_text(0, string.format("BATT_ANX: Failed to load driver")) + return +end + +local assembly = {} +assembly.num_frames = 0 +assembly.frames = {} + +--[[ + xmodem CRC implementation thanks to https://github.com/cloudwu/skynet + under MIT license +--]] +local XMODEMCRC16Lookup = { + 0x0000, 0x1021, 0x2042, 0x3063, 0x4084, 0x50A5, 0x60C6, 0x70E7, + 0x8108, 0x9129, 0xA14A, 0xB16B, 0xC18C, 0xD1AD, 0xE1CE, 0xF1EF, + 0x1231, 0x0210, 0x3273, 0x2252, 0x52B5, 0x4294, 0x72F7, 0x62D6, + 0x9339, 0x8318, 0xB37B, 0xA35A, 0xD3BD, 0xC39C, 0xF3FF, 0xE3DE, + 0x2462, 0x3443, 0x0420, 0x1401, 0x64E6, 0x74C7, 0x44A4, 0x5485, + 0xA56A, 0xB54B, 0x8528, 0x9509, 0xE5EE, 0xF5CF, 0xC5AC, 0xD58D, + 0x3653, 0x2672, 0x1611, 0x0630, 0x76D7, 0x66F6, 0x5695, 0x46B4, + 0xB75B, 0xA77A, 0x9719, 0x8738, 0xF7DF, 0xE7FE, 0xD79D, 0xC7BC, + 0x48C4, 0x58E5, 0x6886, 0x78A7, 0x0840, 0x1861, 0x2802, 0x3823, + 0xC9CC, 0xD9ED, 0xE98E, 0xF9AF, 0x8948, 0x9969, 0xA90A, 0xB92B, + 0x5AF5, 0x4AD4, 0x7AB7, 0x6A96, 0x1A71, 0x0A50, 0x3A33, 0x2A12, + 0xDBFD, 0xCBDC, 0xFBBF, 0xEB9E, 0x9B79, 0x8B58, 0xBB3B, 0xAB1A, + 0x6CA6, 0x7C87, 0x4CE4, 0x5CC5, 0x2C22, 0x3C03, 0x0C60, 0x1C41, + 0xEDAE, 0xFD8F, 0xCDEC, 0xDDCD, 0xAD2A, 0xBD0B, 0x8D68, 0x9D49, + 0x7E97, 0x6EB6, 0x5ED5, 0x4EF4, 0x3E13, 0x2E32, 0x1E51, 0x0E70, + 0xFF9F, 0xEFBE, 0xDFDD, 0xCFFC, 0xBF1B, 0xAF3A, 0x9F59, 0x8F78, + 0x9188, 0x81A9, 0xB1CA, 0xA1EB, 0xD10C, 0xC12D, 0xF14E, 0xE16F, + 0x1080, 0x00A1, 0x30C2, 0x20E3, 0x5004, 0x4025, 0x7046, 0x6067, + 0x83B9, 0x9398, 0xA3FB, 0xB3DA, 0xC33D, 0xD31C, 0xE37F, 0xF35E, + 0x02B1, 0x1290, 0x22F3, 0x32D2, 0x4235, 0x5214, 0x6277, 0x7256, + 0xB5EA, 0xA5CB, 0x95A8, 0x8589, 0xF56E, 0xE54F, 0xD52C, 0xC50D, + 0x34E2, 0x24C3, 0x14A0, 0x0481, 0x7466, 0x6447, 0x5424, 0x4405, + 0xA7DB, 0xB7FA, 0x8799, 0x97B8, 0xE75F, 0xF77E, 0xC71D, 0xD73C, + 0x26D3, 0x36F2, 0x0691, 0x16B0, 0x6657, 0x7676, 0x4615, 0x5634, + 0xD94C, 0xC96D, 0xF90E, 0xE92F, 0x99C8, 0x89E9, 0xB98A, 0xA9AB, + 0x5844, 0x4865, 0x7806, 0x6827, 0x18C0, 0x08E1, 0x3882, 0x28A3, + 0xCB7D, 0xDB5C, 0xEB3F, 0xFB1E, 0x8BF9, 0x9BD8, 0xABBB, 0xBB9A, + 0x4A75, 0x5A54, 0x6A37, 0x7A16, 0x0AF1, 0x1AD0, 0x2AB3, 0x3A92, + 0xFD2E, 0xED0F, 0xDD6C, 0xCD4D, 0xBDAA, 0xAD8B, 0x9DE8, 0x8DC9, + 0x7C26, 0x6C07, 0x5C64, 0x4C45, 0x3CA2, 0x2C83, 0x1CE0, 0x0CC1, + 0xEF1F, 0xFF3E, 0xCF5D, 0xDF7C, 0xAF9B, 0xBFBA, 0x8FD9, 0x9FF8, + 0x6E17, 0x7E36, 0x4E55, 0x5E74, 0x2E93, 0x3EB2, 0x0ED1, 0x1EF0 +} + +local function crc_ANX(bytes) + -- ANX CRC uses xmodem with a seed of 0xa635 + local crc = 0xa635 + for i=1,#bytes do + local b = string.byte(bytes,i,i) + crc = ((crc<<8) & 0xffff) ~ XMODEMCRC16Lookup[(((crc>>8)~b) & 0xff) + 1] + end + return crc +end + +local frame_count = 0 + +local function log_can_frame(frame) + logger.write("CANF",'Id,DLC,FC,B0,B1,B2,B3,B4,B5,B6,B7','IBIBBBBBBBB', + frame:id(), + frame:dlc(), + frame_count, + frame:data(0), frame:data(1), frame:data(2), frame:data(3), + frame:data(4), frame:data(5), frame:data(6), frame:data(7)) + frame_count = frame_count + 1 +end + + +local function parse_volt_frame(payload) + if #payload < 12 then + -- invalid length + return + end + local total_volt, current, rem_cap, temperature, _ = string.unpack(" 32 then + num_cells = 32 + end + + local state = BattMonitorScript_State() + state:healthy(true) + state:voltage(total_volt) + state:cell_count(num_cells) + state:capacity_remaining_pct(math.floor(rem_cap)) + for i = 1, num_cells do + state:cell_voltages(i-1, cells[i]) + end + state:current_amps(current) + state:temperature(temperature) + + battery:handle_scripting(BATT_ANX_INDEX:get()-1, state) +end + + +--[[ + process a set of frames for a whole packet +--]] +local function process_frames(msg_type_id) + local bytes = "" + for i = 1, assembly.num_frames do + local dlc = assembly.frames[i]:dlc() + for ofs = 1, dlc do + bytes = bytes .. string.char(assembly.frames[i]:data(ofs-1)) + end + end + local crc = string.unpack("= 721 and msg_type_id <= 727 then + parse_volt_frame(payload) + end +end + +--[[ + read from CAN bus, updating battery backend +--]] +local function read_can() + while true do + local frame = driver:read_frame() + if not frame then + return + end + if BATT_ANX_OPTIONS:get() & OPTION_LOGALLFRAMES ~= 0 then + log_can_frame(frame) + end + if not frame:isExtended() then + -- only want extended frames + break + end + local id = frame:id_signed() + -- local sender_id = id&0x7 + local last_pkt_id = (id>>3) & 1 + local pkt_count = (id>>4) & 0x3F + -- local pkt_id = (id>>10) & 0x7f + -- local trans_type = (id>>17) & 0x03 + local msg_type_id = (id>>19) & 0x3FF + + if pkt_count ~= assembly.num_frames then + -- reset, non-contiguous packets + assembly.num_frames = 0 + end + + assembly.num_frames = assembly.num_frames + 1 + assembly.frames[assembly.num_frames] = frame + if last_pkt_id == 1 then + process_frames(msg_type_id) + -- reset for next frame + assembly.num_frames = 0 + end + end +end + +function update() + read_can() + return update,10 +end + +gcs:send_text(MAV_SEVERITY.INFO, "BATT_ANX: Started") + +return update() diff --git a/libraries/AP_Scripting/drivers/BattMon_ANX.md b/libraries/AP_Scripting/drivers/BattMon_ANX.md new file mode 100644 index 00000000000000..1deb4d9d665891 --- /dev/null +++ b/libraries/AP_Scripting/drivers/BattMon_ANX.md @@ -0,0 +1,20 @@ +# ANX Battery Driver + +This driver implements support for the ANX CAN battery protocol + +# Parameters + +The script used the following parameters: + +## BATT_ANX_ENABLE + +this must be set to 1 to enable the driver + +## BATT_ANX_CANDRV + +This sets the scripting CAN driver to use, this should be 1 or 2. + +## BATT_ANX_INDEX + +This sets the battery monitor index to use. Set to 1 for BATT1, 2 for +BATT2 etc From 35f1fdf0d899139ec1fb3993b1c929ee0b611869 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 4 Jan 2024 17:02:47 +1100 Subject: [PATCH 0443/1335] AP_Arming: be more consistent withb our defines around optional features --- libraries/AP_Arming/AP_Arming.cpp | 80 ++++++++++++++++++++++--------- libraries/AP_Arming/AP_Arming.h | 3 ++ 2 files changed, 61 insertions(+), 22 deletions(-) diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index 209dbdefe13118..1153490b7a9996 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -602,6 +602,7 @@ bool AP_Arming::compass_checks(bool report) return true; } +#if AP_GPS_ENABLED bool AP_Arming::gps_checks(bool report) { const AP_GPS &gps = AP::gps(); @@ -692,7 +693,9 @@ bool AP_Arming::gps_checks(bool report) return true; } +#endif // AP_GPS_ENABLED +#if AP_BATTERY_ENABLED bool AP_Arming::battery_checks(bool report) { if (check_enabled(ARMING_CHECK_BATTERY)) { @@ -705,6 +708,7 @@ bool AP_Arming::battery_checks(bool report) } return true; } +#endif // AP_BATTERY_ENABLED bool AP_Arming::hardware_safety_check(bool report) { @@ -840,6 +844,7 @@ bool AP_Arming::manual_transmitter_checks(bool report) } #endif // AP_RC_CHANNEL_ENABLED +#if AP_MISSION_ENABLED bool AP_Arming::mission_checks(bool report) { AP_Mission *mission = AP::mission(); @@ -914,6 +919,7 @@ bool AP_Arming::mission_checks(bool report) return true; } +#endif // AP_MISSION_ENABLED bool AP_Arming::rangefinder_checks(bool report) { @@ -1178,10 +1184,10 @@ bool AP_Arming::terrain_checks(bool report) const } +#if HAL_PROXIMITY_ENABLED // check nothing is too close to vehicle bool AP_Arming::proximity_checks(bool report) const { -#if HAL_PROXIMITY_ENABLED const AP_Proximity *proximity = AP::proximity(); // return true immediately if no sensor present if (proximity == nullptr) { @@ -1193,14 +1199,14 @@ bool AP_Arming::proximity_checks(bool report) const return false; } return true; -#endif return true; } +#endif // HAL_PROXIMITY_ENABLED +#if HAL_MAX_CAN_PROTOCOL_DRIVERS && HAL_CANMANAGER_ENABLED bool AP_Arming::can_checks(bool report) { -#if HAL_MAX_CAN_PROTOCOL_DRIVERS && HAL_CANMANAGER_ENABLED if (check_enabled(ARMING_CHECK_SYSTEM)) { char fail_msg[50] = {}; (void)fail_msg; // might be left unused @@ -1257,14 +1263,14 @@ bool AP_Arming::can_checks(bool report) } } } -#endif return true; } +#endif // HAL_MAX_CAN_PROTOCOL_DRIVERS && HAL_CANMANAGER_ENABLED +#if AP_FENCE_ENABLED bool AP_Arming::fence_checks(bool display_failure) { -#if AP_FENCE_ENABLED const AC_Fence *fence = AP::fence(); if (fence == nullptr) { return true; @@ -1283,15 +1289,13 @@ bool AP_Arming::fence_checks(bool display_failure) } return false; -#else - return true; -#endif } +#endif // AP_FENCE_ENABLED +#if HAL_RUNCAM_ENABLED bool AP_Arming::camera_checks(bool display_failure) { if (check_enabled(ARMING_CHECK_CAMERA)) { -#if HAL_RUNCAM_ENABLED AP_RunCam *runcam = AP::runcam(); if (runcam == nullptr) { return true; @@ -1303,14 +1307,14 @@ bool AP_Arming::camera_checks(bool display_failure) check_failed(ARMING_CHECK_CAMERA, display_failure, "%s", fail_msg); return false; } -#endif } return true; } +#endif // HAL_RUNCAM_ENABLED +#if OSD_ENABLED bool AP_Arming::osd_checks(bool display_failure) const { -#if OSD_ENABLED if (check_enabled(ARMING_CHECK_OSD)) { // if no OSD then pass const AP_OSD *osd = AP::osd(); @@ -1324,13 +1328,13 @@ bool AP_Arming::osd_checks(bool display_failure) const return false; } } -#endif return true; } +#endif // OSD_ENABLED +#if HAL_MOUNT_ENABLED bool AP_Arming::mount_checks(bool display_failure) const { -#if HAL_MOUNT_ENABLED if (check_enabled(ARMING_CHECK_CAMERA)) { AP_Mount *mount = AP::mount(); if (mount == nullptr) { @@ -1342,13 +1346,13 @@ bool AP_Arming::mount_checks(bool display_failure) const return false; } } -#endif return true; } +#endif // HAL_MOUNT_ENABLED +#if AP_FETTEC_ONEWIRE_ENABLED bool AP_Arming::fettec_checks(bool display_failure) const { -#if AP_FETTEC_ONEWIRE_ENABLED const AP_FETtecOneWire *f = AP_FETtecOneWire::get_singleton(); if (f == nullptr) { return true; @@ -1360,9 +1364,9 @@ bool AP_Arming::fettec_checks(bool display_failure) const check_failed(ARMING_CHECK_ALL, display_failure, "FETtec: %s", fail_msg); return false; } -#endif return true; } +#endif // AP_FETTEC_ONEWIRE_ENABLED #if AP_ARMING_AUX_AUTH_ENABLED // request an auxiliary authorisation id. This id should be used in subsequent calls to set_aux_auth_passed/failed @@ -1483,9 +1487,9 @@ bool AP_Arming::aux_auth_checks(bool display_failure) } #endif // AP_ARMING_AUX_AUTH_ENABLED +#if HAL_GENERATOR_ENABLED bool AP_Arming::generator_checks(bool display_failure) const { -#if HAL_GENERATOR_ENABLED const AP_Generator *generator = AP::generator(); if (generator == nullptr) { return true; @@ -1495,14 +1499,14 @@ bool AP_Arming::generator_checks(bool display_failure) const check_failed(display_failure, "Generator: %s", failure_msg); return false; } -#endif return true; } +#endif // HAL_GENERATOR_ENABLED +#if AP_OPENDRONEID_ENABLED // OpenDroneID Checks bool AP_Arming::opendroneid_checks(bool display_failure) { -#if AP_OPENDRONEID_ENABLED auto &opendroneid = AP::opendroneid(); char failure_msg[50] {}; @@ -1510,9 +1514,9 @@ bool AP_Arming::opendroneid_checks(bool display_failure) check_failed(display_failure, "OpenDroneID: %s", failure_msg); return false; } -#endif return true; } +#endif // AP_OPENDRONEID_ENABLED //Check for multiple RC in serial protocols bool AP_Arming::serial_protocol_checks(bool display_failure) @@ -1560,41 +1564,73 @@ bool AP_Arming::pre_arm_checks(bool report) #if HAL_HAVE_IMU_HEATER & heater_min_temperature_checks(report) #endif +#if AP_BARO_ENABLED & barometer_checks(report) +#endif #if AP_INERTIALSENSOR_ENABLED & ins_checks(report) #endif +#if AP_COMPASS_ENABLED & compass_checks(report) +#endif +#if AP_GPS_ENABLED & gps_checks(report) +#endif +#if AP_BATTERY_ENABLED & battery_checks(report) +#endif #if HAL_LOGGING_ENABLED & logging_checks(report) #endif #if AP_RC_CHANNEL_ENABLED & manual_transmitter_checks(report) #endif +#if AP_MISSION_ENABLED & mission_checks(report) +#endif +#if AP_RANGEFINDER_ENABLED & rangefinder_checks(report) +#endif & servo_checks(report) & board_voltage_checks(report) & system_checks(report) & terrain_checks(report) +#if HAL_MAX_CAN_PROTOCOL_DRIVERS && HAL_CANMANAGER_ENABLED & can_checks(report) +#endif +#if HAL_GENERATOR_ENABLED & generator_checks(report) +#endif +#if HAL_PROXIMITY_ENABLED & proximity_checks(report) +#endif +#if HAL_RUNCAM_ENABLED & camera_checks(report) +#endif +#if OSD_ENABLED & osd_checks(report) +#endif +#if HAL_MOUNT_ENABLED & mount_checks(report) +#endif +#if AP_FETTEC_ONEWIRE_ENABLED & fettec_checks(report) +#endif +#if HAL_VISUALODOM_ENABLED & visodom_checks(report) +#endif #if AP_ARMING_AUX_AUTH_ENABLED & aux_auth_checks(report) #endif #if AP_RC_CHANNEL_ENABLED & disarm_switch_checks(report) #endif +#if AP_FENCE_ENABLED & fence_checks(report) +#endif +#if AP_OPENDRONEID_ENABLED & opendroneid_checks(report) +#endif & serial_protocol_checks(report) & estop_checks(report); @@ -1827,6 +1863,7 @@ bool AP_Arming::rc_checks_copter_sub(const bool display_failure, const RC_Channe } #endif // AP_RC_CHANNEL_ENABLED +#if HAL_VISUALODOM_ENABLED // check visual odometry is working bool AP_Arming::visodom_checks(bool display_failure) const { @@ -1834,7 +1871,6 @@ bool AP_Arming::visodom_checks(bool display_failure) const return true; } -#if HAL_VISUALODOM_ENABLED AP_VisualOdom *visual_odom = AP::visualodom(); if (visual_odom != nullptr) { char fail_msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1]; @@ -1843,10 +1879,10 @@ bool AP_Arming::visodom_checks(bool display_failure) const return false; } } -#endif return true; } +#endif #if AP_RC_CHANNEL_ENABLED // check disarm switch is asserted diff --git a/libraries/AP_Arming/AP_Arming.h b/libraries/AP_Arming/AP_Arming.h index 603e1b6b85a7a5..7569227da85110 100644 --- a/libraries/AP_Arming/AP_Arming.h +++ b/libraries/AP_Arming/AP_Arming.h @@ -6,6 +6,7 @@ #include "AP_Arming_config.h" #include "AP_InertialSensor/AP_InertialSensor_config.h" +#include "AP_Proximity/AP_Proximity_config.h" class AP_Arming { public: @@ -237,7 +238,9 @@ class AP_Arming { bool kdecan_checks(bool display_failure) const; +#if HAL_PROXIMITY_ENABLED virtual bool proximity_checks(bool report) const; +#endif bool servo_checks(bool report) const; bool rc_checks_copter_sub(bool display_failure, const class RC_Channel *channels[4]) const; From 3691fdadc8425ee43b53ebbb834d75f8c740faee Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 4 Jan 2024 17:02:47 +1100 Subject: [PATCH 0444/1335] ArduCopter: be more consistent withb our defines around optional features --- ArduCopter/AP_Arming.cpp | 4 ++-- ArduCopter/AP_Arming.h | 2 ++ 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index d2e4838f8ce30e..72bc9addf073bf 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -398,10 +398,10 @@ bool AP_Arming_Copter::pre_arm_ekf_attitude_check() return filt_status.flags.attitude; } +#if HAL_PROXIMITY_ENABLED // check nothing is too close to vehicle bool AP_Arming_Copter::proximity_checks(bool display_failure) const { -#if HAL_PROXIMITY_ENABLED if (!AP_Arming::proximity_checks(display_failure)) { return false; @@ -425,9 +425,9 @@ bool AP_Arming_Copter::proximity_checks(bool display_failure) const } #endif -#endif return true; } +#endif // HAL_PROXIMITY_ENABLED // performs mandatory gps checks. returns true if passed bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure) diff --git a/ArduCopter/AP_Arming.h b/ArduCopter/AP_Arming.h index 15495469b48840..180525594cdb6f 100644 --- a/ArduCopter/AP_Arming.h +++ b/ArduCopter/AP_Arming.h @@ -27,7 +27,9 @@ class AP_Arming_Copter : public AP_Arming bool pre_arm_checks(bool display_failure) override; bool pre_arm_ekf_attitude_check(); +#if HAL_PROXIMITY_ENABLED bool proximity_checks(bool display_failure) const override; +#endif bool arm_checks(AP_Arming::Method method) override; // mandatory checks that cannot be bypassed. This function will only be called if ARMING_CHECK is zero or arming forced From 689a5c7b52a9e64d5ddfed7e51a4b0ed0e514111 Mon Sep 17 00:00:00 2001 From: Jacob Olson Date: Thu, 4 Jan 2024 12:15:23 -0700 Subject: [PATCH 0445/1335] SITL: SIM_Frame: fixed per_motor_vars config loading --- libraries/SITL/SIM_Frame.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/SITL/SIM_Frame.cpp b/libraries/SITL/SIM_Frame.cpp index e16ceabb8f9f80..a9b49040427371 100644 --- a/libraries/SITL/SIM_Frame.cpp +++ b/libraries/SITL/SIM_Frame.cpp @@ -413,7 +413,7 @@ void Frame::load_frame_params(const char *model_json) // use default value continue; } - if (vars[i].t == VarType::FLOAT) { + if (per_motor_vars[i].t == VarType::FLOAT) { parse_float(v, label_name, *(((float *)per_motor_vars[i].ptr) + j)); } else if (per_motor_vars[i].t == VarType::VECTOR3F) { From ae256b168ed22b688399a54fd7b6346d4af1663e Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Fri, 5 Jan 2024 15:40:13 -0700 Subject: [PATCH 0446/1335] AP_Scripting: Add bindings for jump to landing and abort in the mission --- libraries/AP_Scripting/docs/docs.lua | 8 ++++++++ .../AP_Scripting/generator/description/bindings.desc | 2 ++ 2 files changed, 10 insertions(+) diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index b3b2deba2ff787..00e2ee4ca174b7 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -1799,6 +1799,14 @@ function mission:get_index_of_jump_tag(tag) end function mission:get_last_jump_tag() end +-- Jump the mission to the start of the closest landing sequence. Returns true if one was found +---@return boolean +function mission:jump_to_landing_sequence() end + +-- Jump to the landing abort sequence +-- @return boolean +function mission:jump_to_abort_landing_sequence() end + -- desc ---@class param param = {} diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index 7cbc293a90d8cb..5788f9c64c1cf8 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -485,6 +485,8 @@ singleton AP_Mission method cmd_has_location boolean uint16_t'skip_check singleton AP_Mission method jump_to_tag boolean uint16_t 0 UINT16_MAX singleton AP_Mission method get_index_of_jump_tag uint16_t uint16_t 0 UINT16_MAX singleton AP_Mission method get_last_jump_tag boolean uint16_t'Null uint16_t'Null +singleton AP_Mission method jump_to_landing_sequence boolean +singleton AP_Mission method jump_to_abort_landing_sequence boolean userdata mavlink_mission_item_int_t depends AP_MISSION_ENABLED From 809e15acf40bbe9e7985ad7bf41f33c4ff53975e Mon Sep 17 00:00:00 2001 From: Maxim Buzdalov Date: Mon, 8 Jan 2024 20:57:29 +0000 Subject: [PATCH 0447/1335] hwdef: Add pinout for Flywoo GOKU F745 AIO v1.2 --- ...inout.png => GOKUGN745AIO_v1.0_Pinout.png} | Bin .../FlywooF745/GOKUGN745AIO_v1.2_Pinout.jpg | Bin 0 -> 1165090 bytes .../AP_HAL_ChibiOS/hwdef/FlywooF745/README.md | 8 +++++++- 3 files changed, 7 insertions(+), 1 deletion(-) rename libraries/AP_HAL_ChibiOS/hwdef/FlywooF745/{GOKUGN745AIO_Pinout.png => GOKUGN745AIO_v1.0_Pinout.png} (100%) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/FlywooF745/GOKUGN745AIO_v1.2_Pinout.jpg diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlywooF745/GOKUGN745AIO_Pinout.png b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF745/GOKUGN745AIO_v1.0_Pinout.png similarity index 100% rename from libraries/AP_HAL_ChibiOS/hwdef/FlywooF745/GOKUGN745AIO_Pinout.png rename to libraries/AP_HAL_ChibiOS/hwdef/FlywooF745/GOKUGN745AIO_v1.0_Pinout.png diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlywooF745/GOKUGN745AIO_v1.2_Pinout.jpg b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF745/GOKUGN745AIO_v1.2_Pinout.jpg new file mode 100644 index 0000000000000000000000000000000000000000..fc34078cc795323456640d784ff41071cc01fe01 GIT binary patch literal 1165090 zcmeEu2UJwa((oOaAxRQY$;`qKl?($jz$_yO43a?v1CoXyIjDexJA#5J$sy+`K`{_S zQACs|IVm6pBn==c2&kaD{ynJZy1sqy`@TKzy>tGp1NYYLP*q*sU0q$b?|dBkI0|tZ z>JjuH7=UfCZ4mVF8PvBU$lV2k2m~3334$O-hzmv!!2m}4=Z7KI?v4N#_>3O}xYXw| zbO2X`(LrqB?hpQz0L}yMWbp4E316$52yhx~0|aR_zuff+#%4$*IYk9IWi+U%prnFT zP{b;rk&5bA6*ce&!67J~k#>a?l#~=j%j3=_txX{|f_R1|V&=)H& z?;RlL;Oyf_lyma&k`Hq5l~A(=MjQ)pTC%(- za;-?9hnA=fXqt|XKM|=Sry{2y3sihqNfglVcXq*A=<0o@0G_l&KZ|QVilXk6iK;VwUpz@z-EWj$*mnd&R4DdPR??l{jnCKlS_NBVB(|TRs zL;jv?4RCgnCwdaSK(PRzam963v>snCO>3~LyO-};4WQZeQoe3Jfj$9lKECTkf7gWd z?6uDPA_gGvomLR21*_}hbciMyL03z3hdNqCWxKkXvXU+uqqJRJQ9%W-s)$k1 z!ziH9>T2p=>JYpG0v)`ah_pI@ik!QY(RR5eIe^Y__i}J0${+M4x{4xcO2p#L2wI{_ zatfax%{(0fX=SxUjoiHt1$|Dna`z%y20G9*qo}5!qDpI%f})bL5=QBB32UN%02o9x zQft#t6uGWltd5VTkH4{xGf_)ad95K>9e<)jAW;|mg9-{tin5AIvP!B}iWsaa2CIzO zs-TWl01^QWeJbkXZ{_3TsU^BT(Ld!GgSq1D5a_T@=<~d{`ZDjgDk!WI0s^?Z1pl+5 zwAs1Vy9Vw7fj<7hpJ$pS(eE?n>5g0*=U4|P+N{wM4RAP2bQb-b=;Y?$?MejmAB@3I z#oT|;<9cd(cr{(LiW(lRxYtS={};ByQQ6T! zji{m^i&1h?msL?!can8bcX9+>spP1xsHBK?CV~$CVO#XUd|flyNU61f_DA_uWEB); z70{piQdQw|U()24r{BhW7fVD2ey)iuA5#Q@^AQC1AlAaZw>sdfxk8I zw+8?Bf{S6@re=0W%9zJ%Z5=u)BpIx?E2uuK>6<1bKM}`djF4 zN7~r#K{8H*9Vi3D1<64y4o(5Scr!DjwLRkxFK-^K?N_0GSsJY$7Wv1CY|dbl1~$A% zP(<6w*FO;8_5ep83G}7msQ~8zj;Axg%K*O39|#EWAzHfQCwz{EyRPB1jW)#NZ)Kqa z+D6-9BVE729lyby-2A;j85K|l^XJfT2H7Tmo-N&sX5^0)tk`uuD4%|I10yT6YAIJ-G zSgQ}w`T&#x@Kv_~F3L)4Nif#!5QKR0@#CU62ty=5(68|yKfcfV`0>|#u*rV}LG|8W z>-*$Fkoq!6kN=v6%7Gw`6A)D0_%+Qj1%j?cLJ;q;uYuxkJrTz#AXXY z+&vJ)viFnTKprh0Dj0+yE1)Z*P6$d%had@8KzrXmXg4ixvaYv3E%RA_A74P*zU~N= zdA5QOc4=mo^}1wp6N`u*bwqyxd}>1ls(dN=|OM=-E3G5}y>W?^FC zVB_TEVB=ul$j!^Mk!uSVJI5x$O?x=cs#g3$S`dbxN;JZV3vsM(yh^ga}wYb2;zj` zWF|NrfmV)=3HpT49{vJAh#zl{C3z6j{9TNPW}5q~tRQ4H#=VQpvs^2BxHfCwP!x)e zee*%$y%Dx6bP1_~9l1|pTk(qv;qvUWuJusim_+tIp{j@V5M<%I2n5`P;DXarg`mMNT-s=oORM)5&=1VE=%OGdb%)X|k_XYFFoZ;v ze}I8P@!7Lzr$Qn1>p&?8$?gcwvgcFptROi5*~U0AUkyJqghZmBQcstN!6q6h3w*v{ zZC{6NpqJ}D>_&4WE$uG>7DE%1uV`Z-878iO0GGZMDx~UnGQh#JWcf&UZnp&#?Gza!Hc|30%#gf*3>o`M%T z?hvPYOAF&E27~t{Wjr|&nFC}9q2K39i=IQg;m^kFxxDlrirYgLBss^^aRptEV2IMi z(&jj@7?urn7sreOuRsbXr@GxFEHuy>LNIm|3p1MG%4DQvP3U|VJHll`d#nI0m_4Z| zppOZn6jbHtXOn5<{}SL3o8qQ$5+w7^%C?Kb%-=>GW-+lNRRo3QSE6i^Cy@!2IfhAe z3D3lY2}?D@t+J-EF}i$9MBwpOq5A^oA>=#XyIi4ihke0|gy98gI7J(JgPWF* zi|9~9LQL=+F99T!yCO&>b2@X}G(66Dk5L^=8PuxVoHl3zr=Qc*-FTMniq86Y7~|b$ zDG`IL>-6<2npANViCk5W ztfg`z@vr9Y-YVPm+C9 z;A_Ax=5PTmnt0XI4-LWcQtct+SaTR_&0D@%7^4Et0{MtdGaMQE(25CXfVpG4yzwx^ zs4ZU)+9ZYBu0ogpp@r*+&U9Gry5e{;c~_PSOQwr^i~3kGcT8mP5_6%aLcr)PB<;hS zFRcu+kdZyz@hlrEUs`-9e5YM0qdav3pM;wM^Aw`b%t2)#=NMW&in}D>WW?J3}d`95hx-V>uL%ovhA!=`KX_mO+ z!ch>H42#FTkb#S!1V>BWSG9g>2LH;!Pg5>kU8E2ADA3<6@G=xvD=yxDH9Y0q(fS=JZlY6Wm2$J61ZLHD+nAmX+ncQ+RBe*QvWw2qtKs z0U(VyUMkRwO3X}M2`m(Xug;fzV)uW)(y_CW-r#ND*j@)~4#dK7%7__Ab4doG3!hX@ z348axYDpT$r8tqZGi%?wp$AdesAYl;;vbGS!W+y@GL4W459zhV(HzgTc@`5<(gb0t zJQHWgp#8q8gp(8>5LWQA9|?*9Gsn(Pnr0t5Tsf8>R`7iM80w40{1~_4tfggeHCR3* z^lEEcw03(EN?9ON-;6~6&pT<^cQKqi|=FLwO6y2kD zsIY?B@nSNJu_1ypVJ4uG3_%aNqYO~*1s~S~GKlg8%yHCg@j#P3Z^Br(pts~OqbAPa z8$~@&7`U!nw67!{lxE?GiBTw7efOk0CPqc5aMh@6U0e9YvyBGw-8bUw!GhT6Qp=th zY6mPkf7*f{!F<_afEi3td$avH0V%lbl~6Hpj^8QCkYD_AzD4bLF-wZ)Q1C-9Pk#lWj!cP3@xC5IxGEJ!G)dsx3t z4yC#GOpjQ|e=@S37?U9{mw787uo%ukYAf!JT0Wkz=-0#&cPTb3Abf)SbphbQOFTGI zaDle?(_7=VN-GzSM3&y^&OW6?eI$7uF0z3)H&pcSSi;0&8oe*BQwDX%cX!HPXZx8zbtp;n^)u^vgTq650&o$~%W3 z2=naqPw*VOEO_BNgO(&dZb1t>5n_g-8FUQ?{K?hpGouiG{@DrC>b|*A2vV&avtWjx zK&RUz-bwI$n;v!WcI_9moQyNib5b(KR_4pBvLY5e} zce%MGs~t0_u+PTKkFixB$FLeo1_La7qCYL%7uN+0JaSYLLf*^q--2Llk)RNk3HJeG zzwoKBFUu!bWAAonvk-7(jc0(vXHanMqNaYr(FM1X$Y0X`^p25!J^Z=APuFq zLz}60P@6<{3(LU#C@Tii9RrAE}8C3cW!DBAJn_4^HY2Hh&=C7fOr5FXfmft*emm zTDlu{Q^Xlq-S7#gEczf^6BvcC3nH5mlSK9lG2Id2Ox#lZsA=>&6*6IlUptHvdN?k2 ze;s=4cBFi5XbqGZADy)Sg#ME&u#l+SPh}F0;i>`mPXHq<@Li_AAY!>GevdG6s-^uL zD(C1HhFFq6Uh=*x2=U;XrDBXeAL05bYOWaa>cQwUF*-*Y>L#C3~lO zAT&Ku2I9#<2~O}8ytq37rsg(jZ0QqbhG^0N{#Yo9X!H!2Q+z{Q)+rg>1#CRvRV>2K zlLFRV`|vcucU!2BPL3kq*)-A5a9`ue*(zAZH~!*vE(90Z#D4{>Ob%dFv6x1)=_Xvw z(a&^Vsmh&g8JN_DV9gxqOiIO%QDo3W7z2eA?{w#?h#j9}E_nU~Y};1guRo!vN8MLg z>OZId`Hd%@<~;+@Mrg0y!3DWuG}*`}_G0W^JgkEw(U5?9BgaaZzeA7=!kqx?YQp3= zg_9Up({|eQM07Cl)SQ6#^$fA_#0u6Dp#9Vo=SpsHy_*fV-SdoAr_{Gu&CO8=a<{)?WL_BGmWYkcZ~4G%b2N?UMusvS$)}aR!;xd4OdZj`7l}cwUYSLaAx2)D8?r4YkOBdaQVp0; z=43muIydym`q2`huT2N;_WufCjN-Wc(lQ!ROXgZJYt)TU5eEes5KSqDz32 zY;3s>jn9mI_1Zk&byT3H83!dxq;aCE^M?XvEv_)BB#cuirdN!YKF?Xnp{bWZBr{T- z|Mm?DFB()JOzCTPZIFbvd=Uo53%~6`4MB3C7zFM(l*g1I17PpKzUZRNm%+sukT8)S zW}4SEYXy4ZnEFo$*Wrj!K!9!EyRzJ})qxfDdHJ}SGgrW-zHtQB1Evy%#-ANaAH$d<16AkYBI8|iKZ&Jpy0|}VM1As(H8q~2GV(VqGahC zObsx7U`+*1EQWB`H2bt+Twzy_l?AEMpN_+F)~ST-6i4Yqg>MVJyAKHUjW2=^!-;D$ zV~3YvHqaIIyfI+@{I&N9J$l$xCysxhhg;PY7gvIrBaMx+tKrlAzlB5ft`zpKVuSIkOm~ z6tS)6%ywolGhvP-7Z2x6d;!OlBzURk(%@MGtAZswIn2DTP0w|8anO&4n<8)Hy3lmS z+V4iMp~{{ZSG8nLH}gov^#|f6K zI6q|j(9S!anGQysHLg$#OrIRIpq0?J)y6UiUmzj`wrT2zq0bZbIHLq^zZ9zMFze)~8E_C?Aq9TgFQCXlQ3U?nz2vP8!CLp*xix_WKed!&+vN9 z76UVwPu{Tj(qaxQ1t&IeLeM4=AHGFil8glyb)^P4XZ2|yhh$%|JB{sM19(Tj@Wk|} zDcG!+Bp$nPEeXQg`-vr_*MNAJj)vcDE(72bO{MS4F%wdtO9&HGnOBY+J~u6`QW>5( zaTOIl@TBWu;8?yk*lFSy?wnF$9GvQ)ZJ0&mHlG__TIh?SiOElRZSLu%KQw9IlA|fu z0m2$FWpj}(S|F2^dEu<5i)ndBE?8f}1qE}va}IKm$nL~DOTzb5Ulr|+7J#S@z^#L>y+Oz_H!`~YCTLXV<;BO85t%1Ka@V5s3hZ-OQPvXB8 zn7}(T=Koshz{^=P0@(lm_kx8P%-kIL-z%S)88`(1-pl{D0t^8@vl8E-{hyEz2^{`^ z3Um~(5#jnzXb?sKUB`@yXM*DYnUrBHz{W7k{Dm>4f5!1kJ~E69gOi!zU=PLlPwWUN z3N~1VQM9+c|6V{K;AGm~4&ox9D6l_OCkziX`5zgO$Xp;JfHg72wb$?;U+6o?Amcw_ z7cDHb*F}OS{Ymg`ZPq}Lj0~K-Ug6(^Fd=ilGQuOd2;ZtwJ8UEJYc2#cbmSEO2@Ko+ z#Qe@J{6-R5ccS9IOdvWYQBkvRbCFS&C_^S=P=hW%_uuYLEPksq@J0YhA;^5Oofdn8 z-%OG;#-IPbHI^v7o%&WwHMdqvz;r^Efa|{(EPkgyz#E35SkX?&fvC=IllhxCzc)3- zzt<$fhp(ki*wtik&YxCHW-Ss%!~R{s!$ba_6^cTDgG9PbeYLpTS+_2EJ#hE7OJ4}Y z`#Nw~Ok7o-O7&#$d|*uOXS-gh*&%&BHNSOHNj&PT(&Sl^)0zCC!u#+&(!Uhc-g@)O z6};G?&B!$!(9nMq(1nF*f6t1JfGPoQF$|`N^=1HwNsZgwf^*iRy@EhT-p{V1vRgLyR@8uOTjRBZJ zYj+y{?*UF)0Q7rcMuF29(z^}kkKzu$#T?nIk`SyK;3sS9&#cKIrXCRPtFbj>Cdkw!Ya)uu_V(+N_ksqu-&x#4Z`*Hd+)DCW#bMC2a{{0k`{Hv5B8oCI-Q3d^Rx55iBg ze(f^20)bPl5Em1elyHg#7zPHYQ%cu*pV*D~T#mV z>tRPoL8Flwyc7LiCYOEmcg1S%PP*h&q-OH?*PWtO4v$uBXKp2HXqGK@Gpkmlzhn@R z^RQ{2U43LXJJGHAGV3P$s8drI_q>2oSe zsJEt$2dM=lq(o%87#&a9wv&74!Op(=7cOSMr~CUSypg_4*Y(&?LO%^y2RwKKi?@YyaVTBEqc(+6@Q59{{Y4Xdj8_^tV>fLA;Z4xB>$Vf ztAjp<9+Oos(bsq)EL&eyr`7e#y&YV8`N`8D6vfy->qCw%h^!3~V# z!RI7U2p!lI&^NB=KIAB1mkQ>xI@~a2c~D8uv#^zyTV-#?Pt6@?>r%xapQ3%EEj_Nn z+d4n=vrqYt3wkjWc|p@C^0!34!||st2GwcS7{2oGB2~wvmv>1hz9|xRc_p*&F_HTy zPn(#RWzOz|C%l;1VUOYNcV>pP;Komrx-hmu1$|USN#wH$x|sq=_X7M@U_li;X=X2+dJ{)`Z34&Zw75 zT(>vw2%p}5${YpQo?{{^-!_q~p4lp?`s+jVJ$cW%LO?7@p#g^~0_ z7HyKXmMQd_X*IN{Af@#=Nl*&JdnN;oQP`#_O{8F}`gA8@=6JRvn`KD){f+;6Iye*LPgWM`ByTb`2Q8H#lkYM4Fg^Nww z&Rikj)%bS+=O-NA7Y=u2i!Q(vmD`n;KuHRx(w9!D6eu`!%#dtSbplMzCJP>Iotux1 ze!BZ-$t6tfQo87q!bIW7REf#~F%hQbOsrq1x;eki_}~ryzT1c)aQoLeDkbK(h%QLob~MRxGpws+0?DSKm>m!i7aY;rd@-*7QdqK2sZ-4v{9 zO{SWvHJnJyY8-Xx@DH!xD~O5rj8JdLntr6c-n7pMkD&H~@+9I}vf3$+pP6T!NZxbZ z{VV-$i7*C@rn&j%_r=q{A`mArC|Nq*iJm>oJw7s!HHbR3t5`hJTzf1Vq-R-Sfe#VK3hYB0H)?Dn3nAqtXoY6+J!QDICB zfpeoY?!c52;NW8^aGMGUu$MEo8R{rMsnup&NN*^|I($;K!38armd5R=RLFlXLyiD8 z%=y~Lu&@mQJxi*ht+lHCdHnZk`DfAk6I@!Q6H6WM?$SIq60{T$O3IAun{-=@ET1~clX%>AW+AIdn!0}h8(`Zx zL!Dk8pL?Pa6nJZ)YA?Jr`F{5aSL#dtH!dC{zZ?nAkhcr{2vrVULVYLCzwpTGWP?`T zFV|^Pt-)N(&xtO`PYtK`-^@JGl$H1vvvG;}96#m}tf}+LQ&zu4#bvxWV;-D0oZ1ko zOx=!Jx&F$P7mEpJJWdMC#WUWc-fu#YVY5ugFl}&Do8Ji^xHl!jV9I4Kgg@$rupa9w zG%nHQR>U)6tkS+&{LU4DyxuMw_lWDB5|_NF&bR=z{DHxpVe@x$c5XpJ1Y0CzX6B}6 zFao|Alkb@Eg~8*4Q|X-{3Z>Fcp}5B1Q{uFbetBWa6z`+x;8-;}0~zGnVfWv)8X=D2 zw6X|+n=2V!zrRHnN;_j@e6Z+(1viqDKpnYmK zu;^f#vy-Rn^Tf>gUF}kJhKH#YGg1@7!FDQ>=})zaeJ*8Z-y09nkW)VWa*}#1l2Lc0 z*frTIY`R4FWN#qB>~}KI9$@h8W^23bKjc8E=N+xZk!yv6iqqN@kc!+lNYLAF$#!pMbccN=9r9`N7q%U0IAFfEzQ?HWm z;LB1jdP%rza@rv_mb4leR{vH$hV`XBPH{(RoYE9@U86VS`}Xprjw1t{3NuSO1Yi+r z?$KUq72O3|#X0B`HZ0~b#l}}vyF8j}ZFNWZ@!4{0@o%N|k<>|Qtx(5Jtx$Ghul}q( z#)=;Krb-nRLpzQ{&z$P+ew+Hxm2~o2TT_k7Q;j<_M>||@U`ldws-r7XmJem@g)iNB z8a^zk{=9w9@`sr-c28v6PHjb%40V!UQFFhS4uTo=Z9N!JW&Ps-CY^_}^JDbqFts$2 zF4qFYV8A-d1q=^`fB=ph0VRA=7f_AYhQbIafN;VHa8AcF`E%u3-Ig6C!jWgq@nicq zgR&WPugUH7AFY-nXvT@M?92}vjVC}9CRCUq@KZy`5JDotIVN>tif5=JI3$F>^a|b3 zRe2-n6uC40;d!Y##!BQ`Rc>cZ4zBq@xD@^?+5XZ39$sc=t+C#D79 zv3}PJP6Ue-%zXISwD#?XqlD8#@UDxUFW*^wgpA+cj$7#3a0s9&DH-(%mNV6@+rg^)w?SC;~8 z_fFNy7Tqf@?yh`x_dw6{pMRcx6mVeA^1GV2(uQ5j?eRg0JUl!Z(!C}F-#Fx-rPdX7 zY!45m58rR{e5WqK{=2rUJ;Jk>V-lpNkM?h!UF?t`BEOWOy)IezBM0^YF^dLi6y2CLzJqOPMu{=KGrmD=!OW zdL(4Md#jdm#iy478xn)9G;A(a~g;`qj_{%@4nZ;32*zOTl<<5J-g-yET zZ$)3n>G*`@Vn^D&G9FBwcXVD)UVBwTd*b+=ku&oX1Gb}q!&1W02w#!WTgXShSHX2Z z2A`=ieo!$YsGe_}&Z}tDgCS!77MB4#UhYaRK!ZsN32|)K247L!Ywif;_069vSw{Qk z_f)DhV2P}G;pj?!`_plvM!oo{{Q@(0jAkwi%pCS$c;eq5DA!K6M0M>WY6CLA0~SMY z5U{W;(R{P6aXul6PMq_^E|jPXj9_anF7sN(p(&U&oBrbc%$dITXLh>R$!%4=7=R=6 z@6rvt=OXdw?oIE^TWY)dB}1G7CkC+!^MgC*s;HG}W>tFwi;i7i*zFzNC6vLTx*+tM zx5v*K7Z1O`PyQYIPY-k(IRxb!G%p?!`9=Do85>e`Qw_`J#5-^aYZqOopsj z3}oP3Od#OCRu@JvK;@G01RE#}Pq3W|5w@q~TCv#=vqVWNNCds5l?kJOFIn@(7*{x8xnVNSnDC61vSWSB-SyOJb<4#HeyVqn* zG>-CzcZhUss0SM=QSQ{5Isx~#PL&shWF}0_ag7;5OH5CXap8lGdjkgPuT75a-`ceF z>x;){mujmcc^rrF3>}^d6vlFz>=|2P9;&EluNXT2v`L(SPj6hbmC8Niuxoy?)FV#10xVDHx!L`EZw!y-AssWBb_L-Eeyay*e){Sq5zxo_4pVeX}0t!w%aiml)5->?hXh z6y`$sX|O{MqvUU}99WcXujr^jz1AXVnpg$upjkNRMk$ZNhu&!7$E>YkpLY2v_F)9t z_ZOddercH?`Cj@@6vg5_s@!EcDwz{=6J%It2jNXrET+`FNVw=>kWjQ(obSSD?Ni66 zMFB^tU9!|y!uprV%O7fg(a(B$`zoKXh+fOq*;|x-yR?OpYx6it4`He^LNh=C@%6bd zt=@@{<#$)rE$zSbI3yuf9F!Hhdt~yGHZ4svF1o8ZaGZd3SnyktuFjDZG0Y5{*5}40 zW9~7Ast2FJonUOA8VVej@Ng;d4S(SjD@cB9@{&{$D(c*^V2)qJ7iI;%lx(B!QW=Lr zS$xAASKZ3im}zn(#nirP>7F|8C81feEXS&7K58Sd@uh=Nc|Y6q%D&EIM0uus%;-R; z)jhs~##e|nd4eIBxeZvQ7_kbHXRoIzCugNjG^>nsFb~ISdl6S=4AiDpa|TAWE|pT54KM=B(F*_;OLCYN3@iJtA1AC-2~=LXyZ# z(wg070RtS6cmCEfZjD;L{&?U!u1tiSRRDx3uV#$u4{hub^5sFx4#^qxCm z`csQ{<;3cd4=MMx;(kt8&7nYP&2b% zV3u?zUkoqW*@O(*MYfCt|9sTAn%KMBG)nME=8JT{{H*Nc@uIA4ze@VF?|Vaf)WWs; zg*OC~nyHib+5INyvo$Ca5fkyqdSZVqMQNZp|0 zt5Gi5>C$?belnnpKk5lbbZ5t$zNL(8-0AM3xNOsM(`1tp-^FSA{B-F>^Ed9GZvo(^ z2J$}glQp`}Q+?4o4*lSovGn%e zJWI?sYDX1ST}xkiu&lIj;o<#=#O7=UOJnqgLrw{+|n)^<#U}nvjcr$ zU!q0&~ry4$WZ%}J^!cAW^+VJ967&G!#a+rofa zZEQ_vUgUeTV%`y#9(%$+VQ!o{eqPY#MX?E{w1MMt+ge-b5-5EA#}rz$uzrE=F4ID!HX^ZZE^jc}k3}TX&hQfPjqrI@V!%xEP zs=`T^c{hee$Bu;vWpUKzrruf4NHkhGS%@dMLW!Z#ol#q%sr&>MUy{fx=CoCorCapf zLpIiqL;*Y!5cx4ML1Ejae?oCdZ-sM(Ar#W!o5WFuF88_cQ21uTu{|l1+TYjviQ(kv z(!wvfccpg}uI0t!kz^VIkN@V-44rvD$?nPJxrJRyv^=`-DS8$kNoL$UZl_Xn;AG^G zYgeR^NBN zvgr}o@hO$2LtUo4^R+X-5R#V{_e|e5PG2V52|;&KTw?L44CYH*+GwSn^gLF0aRiaU zppAbxgMnue^_hhs*5}N~{a>?XinM7d78Y(1JP%{8%wwL7267`0GPvDP3CQEmD;03B zqTox?ELHFY0(>dZ-PA=~!0XEV?D`(#p&Eq<-UKX>P4fX;)x%H27P9alt|Y1S=Lqzk zQJhkF$chnn>2Qzm9f{R-?ZBri7F%wMIWZV59VurN9F4ZL#wwPjrwy^zsckoPQYb~lJjk~@(lXT}Z7iN9qg`*+2E1RrZ*ZHpP329HX;M7+@ z-c2E{xLFZAtv6IQhH)rSCYBTfg5ryohYg;%(yL+dfdE%Izg<*zWkQ zDFtyhQt4bPvXg%yOEH4fAgrf5MJ0dck{I}O%e4#dHFp_(NdXz3PM|?+jl7jJfNXJpj?z8Hu`sE-EvO zg35@r@{FHu@|%0wrO!+_#Ra%aV{4EQi&3!eQDNsWLk_V=xs-|uL%d|v90B!>5bKP8 zfbhg?gQGJ)$oQP}MPYYE&lvS?GVYa5+=bTV+$c?k4B+v2@WmJm1rfj|%zQ1pvsOu5 zNUiC`>~GzhERo;P1r9n5Xx+RHEbKC#k^1Vr7c$b?J60la85jrK3u%k{uy>NxnX8kV zT?K*iTA*nLklYioZ&Q(mXU@M2I9d-!^~*< z3z;9NdN*7RyXh!BU8&(;THtsJ9rB&W{iF&`X@J@RLcV>3SJypQgqp1mvlvb zJ^`T{4_-1*cI`52Z=1UJ!-+~X(2*Y;|#yKb_6@yN3Tp+TOHtC6m(%zdDs@6R+2H? zWpdhYy#BdMqEC@#wQ2*}xy#K{&rLW|ktX~fXJUAyAZKpjCXww~g$Y?X3dx`+`s2=> z2|tmETxESB+0`P1EnT`3j=2-2RD3p0x!6P*PNq?!0UeuLLpEYznrO&w=W28>9ULSo zmzL*HVs$7M;%pI6>@+%l9C=N%YvABivNywB552%DrK$6t&9xq`I+&TNM1J?%sg;L- z>lg+zCyZHy2or1CVxx)234vy2R(q2rvDli!pE&*56**v<=AuYhimYuS?z(ou)T`ap zc&o*OT{2T@mmZ(<^X>0_uI$cMo#5?3xnAX^h<&szdUb0=jl9(>RfmM7T^B0%RQzZR z!;S%CNCpNM|(U!|K-Y?6hvVz*hw=fh$=G*>yH?CPUqpTE7faAK@%7w22*9 zeWd2*P8ngF=#Q?slKOg}Y0KoZSsVU^(`YAxMpSd>(6U0ab6;%Y!AK2k-jwH*X0<|b zT6yM&HombBwdxMEHvXZ15Rw?&E_wD3-Y!M{{WFy^9xW{=OCNW|JH$dBj4rs7>fjUn z+>V+>OjXWaKKeBNjRVGy!gDf5A9odgeJReu&gsPJZfl+0sC2X_<_98c|rE-$=207d(-Qzs$M4itY_Ym?{}>@_?C>pH@w!- z^&LQ4TKCqSvB8y3uE!Y$9P_GGi#ynKso$%AZ|L)Dq~-^q%Y&h1RIa%@CzZ9ig3^@P zgZOk>7nGXS8`H*_KopTI&!os;-zcDXT6s#nLMZ}1%w|)obw*jrUK{ZGgYAY9UZ-_) z6tdTW02}y7oJ#|ZNy0t_N_LUW$oc!Ud_e z5zY&rL)HnzfLC5GBVL5bEap09bIxM*{xZzNt- z;+^3ZT)-9AFh~s<*Pe%E(=*EZsN}VTyc6;d_KTIA^;JaX1x992)t=)FE4R>b7 zK0^2tyH!t>AF6N_=gudbNNbzev~5jpaJc5v(Y;Tt_<_b3qAull@D-fkPerX7tem1o zK48?Af{XmbAGN&FX~IQdw8kZEl>sU*Un&PGN0L?#HOx3_f1(GxCl6;P*5-3Tvd~I)d@O)YB58^JWHW4j3buK^F8lm3o~O4emSZ(Nkk)a->S{?laidcQ0%j%a^$)a z3&&1MRJnFtCsl>2_=lr|GOK2aq7OHuWx?O7)kAPP3OHqz^r<&!4m6BWU8#BWV3FW7 zoIj7jrY$|~D#hwxGpUd5!~K}5`t-D_w2IM1Oj=d?LN7~KAanK6En2gN+8g#-vYk6DyuYZoYbrF(v4DWZRPi+W@7Wt> zxO(qm{=uuE3D0e>oH;7d=P|u+vr>^$*XEw28_Tj69uIbI9=LnRcP!-k?8K{)D>F}( zE;D4QweQYof9!ct^2qMGhkw4j@KEg%=0|!5`KiPkyYIQT9ebLS_aSlz`i%T`#jLA+ zxZ<2#lFOnj#|wq_hD~yr);0p>c^QhMA=&3d z++~0Aj)fEq-?i+i^MPci4az9Tj^IdD`ybh`MfX;d`cVF0Vb_jGG;RcAyLhLE<9yuq z@N5xTzVNy62tm|yhFQ|Ir~VM)S-lDGk;NKL(i=aW>Ky#n?HV1sy%QVHO!KIJ!Ug`` z(u|GAJc>LYvKh1pJi7vPPCJzT=_vf`wX@^0-SM4?tDd6~=e;L~rw;0wJv1Ve3aNC9 zsAs9v$(zW8S_g<_Wxz&^dKtT?<^slR1snTf8vA29nuP3EhGrwt$}Og7Wzp}u75IBh zsPl#JC}XmAzD$Ow)iA-FAWqz&nr+Ozxa!k3bzz6z>_NmcTf!XJfrV^g$TOI&eVi`; zOV;t}cCDl--iwO?OP*Q#l%L*vHW8B5Ae@s%Jlkz|GV7&E%Wb^r7_*_c6w=dSBF!l(UT7MvJ7TVH>$p>(;;Mk=Uju}^lhc)Q$L!L z^&&{#hETP;1CtDb?>%qg@Tvg;SjBLR`B_9xzww-tJ;MX!VPie92bTn1su$V6?1m+M$h9Kb` zv{z};D*d9Kk}|5}QnqQYA5~+|cD5OnR%DJ2cQOq}NBIV)|CFH+u|z23Yp~QPKdw?K z7qmq`?PjLYh_U?>wr$T{NYFaqnJ5yiQ74R$hCNY9gv8_bSf#TSrXC)QJh-Dcp*LdT zXyucSP|nOPF1if|)I4{`4PFV|ov~ZjU)mFK93QS>Yiop&vz}ZzFwMpfZxQQDI5=f_ zIWdW@pr>pZm3#l9K;mBROF?ae&MCGH1=$adyx*O1$p4*t^3NGXZ_*DI=~X}W@CqAv zRb5uNF3~s0djEzc6;&EL*61Z*_|rO`Bo>{&rPSYU;GxS^0$%hANMA~%5T>jwtoCh* zkSa;&ChW6r@P%DTOl)8$TS^8;+h5SWA+Z=HLho!THf{CwOyY%;~ zax1V01y&3!E4Yy6HBIV#>xu0FdlX$>2BkAU>^hAHN0|(19j+O-T^odgoZ|eaa~HJ? zAPNi1DO6eY)~z6Ip?s+8++VV$O_X^K#j{hbXY{~&JeO^xg z;BP~m79K_U&M~dGP!uKwy?ml^)iNra#lB-D6*+iDS;Dndu{qYtXUB}$7n(3aGux@@ zVzhFz{dffHgUpBWVXDGg(h(#5=#0~3Ls{mdRrR_r!hpcOdvMSVEls`g%&pYtSQG!^@wUgkT~F~D?QT9{|#>9OFfLy5L& z+hJEIy6SV?e0xL6o~Jd77`}g4V>M>D^DYbz=iE?8R4pp4J68Lv)`O&RKTjDc-7GeA zb65~xCC-cSpSUYLmjc=zWOBUI3KITHz!D@A$EY61UTLeVl`p;VYzsyq%bVMA|C|VQS?2u zz9Kr4At?9R6ls=G0`n|h^E4A;NS3|CKBnv$1L>`lQgf9HtNDE++uNHNyPDgA`NSmb zJ3U9*6Y5`1rY)YWN>^Oo82FW`D8Jn?T`|AGVdbQm9Xol>opU=e5T(m$yQNubQLb(0 zYo6STsBA8v^9jP zaBcVA)Z)z?JzWYE34lp=M^X6}O(Xi@Tn^lor-FbVjGAB=?Q1sbhE#2*zH_ z;FCN)8zD2>)H052}N5Fhi&GlR;S3SX!2WBnF; zmu8xb;~SE)4muf5yj}S@?XA|%+hZ>;M>oPYSKscOaU*?%c0T>}mkuR5p{BqU5`|#0lc?Q~QOWyFTq6vnzvk2MT_Pw64z1*xa|P zQ|yjlzV(&ImgOnbfIs#4?K^Lijy*|j%D&nXvd3<|rB>>yUtNsfW6uMnMjxT$m+p<5 zYQDD%s*0YO-ow{7aZ9nK)Zg93`M&W$2meaEikP2rQ5ms4!BqL&%H`}G&k|KEiD)M~ z@T#y-;HToXPWXQJwQ(cCr|IJ5oN}qPY`Rnn(1Xlc5Lgr20Dt2G}X~?0x>qxq@ylU9}XOpZNA)|9_-?1z1$g*Z6|8beFgyAsq`S2)L_= z#1c|UBPlH{ONgLIcb7;?ONW4TE+t3{DzT&}rC_}OS?u?Hzu)tHzyEojoqO)=+?jLd zPM&k-9QrHg&bRIqG@g)K>e}#1ox}=TP}C5JAK2gHEPHR*%S?oDKvCxMviYKwy3BxZ?5(r9rO~~+29f=rB63%~jhn1tP_8;bV>P+%RayW2 z3qn2CkwWsXTw?9ct?s_oRXX=l%8kT+K0j2+y49`3eei4L13nmmbe^`ZF5U|*{!q;+ zdLPDX5g%Y8+Ep^jmFC5h9qX}dz?60Q%itds^859tNcu7lOay-v7=6`dhNdK*Ny#?7 zi!Vow0L}4;bqwc&`r~j=6XC_h(_(i+|5(4%76ly)zE#1v+8Sl3W4{FGU0^2*@y`Sp z)oOgL@kygcdj{81VV)82S&dueU`&MM9we`Ae+FCjuGk7>PQ_y*Jf&3;mtGi~Wt4QicKF;pajD^g65#Fr6MhbWR0etD z!GW4Q;iivMOo9;jyS&etsKLqrD2Id7guBwMc>cs#%#Vm;U-~YX8gzA+;s0b$pUH6^ z^56ehHvh5U&%&;5_LdDl<5_uo$7%7KoD(bX;(+CSw(dH!;s<;gUk!uy(Z&!FWZ8Gt zgVw7ELWGGHgN1VePFX40km8yS^bDEaF8hr2Yd>onB8YZ z`JJ+QD2QgWIwt`e&KV{9I6%Lg;{YZ`J?7TB7+ZpKJ#5Qj0WQP~{Z7oKuaPfqeh>^j zhK?al%+1IQDZF}6hK#*1-VnIf6f$WJA|vAT{3 z_!j(Z`|@Hhn~m?tq+lK;A`Tpy-S!Q>P`v)|$;bcxo^oS_Ta zlh7?Ibz{StYurY@`5#?}?Y0`-$1USTpYCX)-^c?fZ^_f{w!@b+Thc(e_6YbRV^oR{ zk&9i>;#T_Z`Zwmv7nK*FHwj;G_b>O^1bRQ^5eRSD6_33rg_9w9sxHIgJrLE5jZx&2 zOWQ4nY28o>8cg84JEx|R39=&+2@G<*G)t*injAYDKx7%NzAsHy*Tp8!KizMpE4uWk zf;qUxf2>9{kZ3F-1eFq86PK_o)=s}{-pb!ii$s~`aa(e9ig~sVeK2OZ?VZjBE}Rhq<1sHUBN@#1`N#qgda<6l3NiE z-<^;(q~A_;VB_B@%kFkL7!aPzxE^UaIk&O*7sQcl>y4MQ_rcDyCd?dXp0b&gZf0_& z?Dd2|$N-Zl(z<{)l{hmUy+rU_#|&AXneI9Ugyz|Lq67xD;+JlTbTv9yton&^!z3yV z&hD@|5I`5?{QfQ`l75#V@P6(Y|EGtXbinrw6bxNaN7Dc`98ivjaoBk;TYLG_LuO0t zJ%F6?{+%-}n)K@G)?IV9gh;Uk3yF3)k$kIjy-yf-BuGWp?BGq3<+Vxe)OK9v?TqdG z<|;%R++u>rQ^_J+gSPT*CXtuQ>9AR8+%of$v^KG`Y&2IhBXW@E?_{YTAYXF{XkNn2V^JuHx@g{60d6fr>F;03`6knEiZmSnQD3`e3fxXop#x~+XYWKeNpdTM8< z6VjRN^2#;XEH2}7wr*(h+I4ByULrRS=~KQ$?IWXa;q<(nJSgX*QLWcfnSDgP&A#(d z(b(dDgI|MWy31GjTGsK()zXv0mY=%=cedgM&W0LQ*IxE8PMx5cVg3tJmNr`?YrEX0 zp}3)&9BV8cR{lnp$p!3YGRMPS#|d+eEP{hycO@=<91qWFVIjUJM0zS#r1RjGAp=*O z{jyjG6YQTe8|a?&pnE3x48?>5pS?t2N*)KauhBhcH9aIBl`+Ar#V+}ZJxBXNIOf76 zODVyT4nG{pna0m*B_qC=uH+vBKW$Qs+Qr?>m@K5VHwprBSVTnu8=yNPTm~`3&{%TP zI-s;>N^;l4Fe8VSt-}vg0U|qXcQ*8NOF1u(Xl6$u!K4j$@@+D7xrltDF$4EqM3{ts zPb~~DKP?XZ1pQ``73G2z{pYW4yanB-}Z!$1YxG6>_sNCZ9 z_oJ=fXyouyfcnFMAQp7)zq2I>GiW-S&rd8pbXm;GbmW@8`QW1D$P`6duoRD_;{y^w zifpyiq3l6QHx~o((>W;vJwDXpfiG+yUg--4k%KtjtT{Q6{n02eChSY6u9 zzLbIu3*^-E5I<~A{$t?T>(`*ePffo|o#wO(;@en;2M? zXIZGX{xGlK!COn>b3Sz{S=Qmm^GX}%wz;QSJVGj-=bfiLqt4?CWemDSUU+)yeiO=8 z?HU(hQR;D#so)>E{(k*A@m;oF)eQ>aTvfhWQtD}IpX3;KE=Tj-oX^m(wT~5dHaOcn2KG_%m7}qh$ZQKNFS0XN;+cp zmgq{o@bZ{RM3wy!wTPCXWA+@&+{WTG!vn0hRs)Iplguhucy@H%9lBU2$TMsS@Bpu* zJ_#mlO8)K^Z0se{x-cF7B1|%gPi)jo#L}cAJ#!Kc#Z^*(`eAcSNKAZSU|qky@uyxg zgo=!W8?&y;ZmPZiAj^ld(#mIoJj`g)<&)+!GjDm6^NH1p^^CtD@?5N4?^EJOYBLI2 zQ<&nVidA1wIrWc5cB>h#Uz2B6*^Vvx#nC=`gKxo4T?QVE>z(lFRPiB;QD3Rgp_}hk zFPwT74+JhqM@tmL_`>7`$@TH3!j*Z8q3B$@W%o;VB9`NxbjC z7otyaR0)K}APa)T*nbxDA7?YS05@4D8MVwoJ@R2QRbLmlRb;MOBH6o1G{R4`E6??k ziP(;z)T4Vcq*VS=S6lnli3eX|-uO6#evlOdLnIb(fIc@kd_-xRhenv|G5Nuv5JfK5 zXM%miz-}=DXf4$6BcDKW#?Y%#-%Nl}-n!J%lVrNvNyo6<;Sz95MBcT9C3u`7l{82| zd3!cswpsj`qj1-)_7ix^ORHtS1G4-<7NPQUnqp6RdLyjf_-C1W3pjh$VP82 zn-_Jo2Ldni2mI8W3roMYGncZdEaSMKe|y)W{Pv;g(}m-2%|bRzeC!ScBU25E(_DJTdLH*O#?J1@glfRK&wD%!-fIw={WvQ6EmOkaol`X@ zIu`P18)TGSL|v)TkK0&yvY1ReMoFg>lf>I^36QOHBvo3AS57j*ZV4RECepFb!`l^J zdY{H4Ze}5Dnd7F3Z9E7(YBa9~Mghamm_b%Oa>>mk=B z1k9vkWqri=+Dt9zLv>P-Mv1Hqo^#TNuhTV!4cIs@b3~DZDD?sR`%xMW1Q{sY7?Ma) zI5u}I{Ktm>Ey?%rU#pS0_C(JsF1gm!tJw+po|5$?i3A*dCrH~E+Xbz=_-B+|#H`3} zV!Ce656augU!RDCi5f8%%thFNV_oB__pHbrv`~rMw}t$$ZW=H&mgf;@vPS>0UfQH% zW5va-ObgdIWJBaZ9#!;wjuscjwkRC-%U1+^Bx(e+ANsF5W`>A8HXWLU11E5d&!-7|IGrEN9M3-KH zF8;>5*q(dXia;P(xU&~B9}(o;=zw1z4wF|H4Q&g+b=53RI-QZMsmdo5R^FK6839}? zqBMNSb-tC44e@YEE{Yl5p?;h`pFabPuKeB7moz!Gy9;JV)=ah3KELn5MJel@`d!5x zkrC49>J+BgZ>xe|+5NzN)}MvJM0#2Jde~~I$KWX8s#VR$#ExBkz9C~t8`(MiJCW7J zUG-a5l*&?eTxq&Yr-eO}Owm(h=24D>$(C9`b3U7ihS4+m4Z4dO0cENrB8DE7@OSc^6&ZQKOLybjgji$b&NcDPJeIK~Q7NEIC4EFdNeH;~{V*5=R}lFiZ)pwBq@Jh1%nzZ~fzc zoU-Khj8rOfFBZgInNS)FVYvX|n|Wgve=GY(a>!4WQc>3n!87xWm8&KB4$ZUWP72%4 z>xPu--X@%!>A&-_sp>*uiPUq4AV&g)O4u@OY)`FNY-U`H%VHZ_ znh%+x{Sa?;<5N~&s9rRKV+;B_J04%FEjhTDy6zhhB&OON6-SMe@)S%9?e{Gf_{8hk z7LV!aV;nta*$?B_&)}fHZ|OZ3{Qd9m7yXCqEZ76!5ji)xNO#WwA+EKhNngVK`e?xc z{;hmYsYe5$0oMg7G--_!F9*LM^E(Kd539FxIrfa@HT1Wvpu^h-hwC*v&#J&7hkrKP z-%|b)#UW9l0ZK;mh2Wx45egi*z@QH$5hMl&ocIS9 z%%m12jYlZar7Qn?x(7bF?In zwp56Z+6s3e%LP<(OvxzGN$sW_PlYYzVhQZ!$6Q7wTz0I5LN#;$IKLR6RTgbvUu8TJ zrJ(@_%Pih_c$6F+|MwL`97JZeoCPKC$c-s*4RMb4a$G6t7smxBFsgOShxMN0*Kt*E~x!rpQ< zskOXaGurx7w;BAwW{$O=0g#`-KNLe&btw1dUIu=$gM~_5JDWvo=1J9uqAWNi^p?YR z@+RXzW!r*a?bfI%%w%dPePD7hsojE~OubH&;JNMc^}ci>EVa0#lFr8TOZA*9P-+Ae zf>_i*(Pfxq=IqIks9kE=mgxbWOZ=7mewGUuHQ}gcj~vI0X9j-P87p@8`PELJ(>@c| z3hdtE3;P!!Oi@YMf*PI)%j%DFx)=!SvFw>mQiFOAj#;x>mMzR$117x5`%PVH!BdC8 z(f)ks@_fP0?oN2cb1&hQIge{9HQp&!O6yA-86KAJt%%l!2uFrqdN-pthVa(AE!Mid zN_JdpWNjbqT1~yHL0JDr*)NpfbngttsOSA^tHiI!Kd}_!hK~*QU$7Mx8wTk9IGRGzdo3wFG1dXTfA~*ba_<5Amhs2W&PCE{1oe9QpBvP`it>-EjOcMWU7x@_ zadorXYUx=uL`%`yvS~_XVrXVA;gyxzx!_tB-7;p+U8WdGV%?GxaTs~Lx0tFcqDhfw zv-3NzD51QA*-fY9VzepG=Ka*)YS}6TNHTH%=8WVN9DQ#=z z-0=dUe{1|8%_+-?*ITnqN(QbsG+tpJ`USLcQ94*2{x5)10^3u5if~>?3pqbo0J4 zEPM`)*J__D+oWLR>jzHIgc>O~6~4vHd^{97u!`N2Uz!?9TAG%ejV%%^6G`niw3n#K zW!2yP3)1Uj+vL>qDaqyG6U_9NVu_E{aPX42 zDeKwT_`+!3#Lt@oM8AIkr8;8mj|kv@D4eBr#fT@Gf?0v4wlI%-AeABpAU$)&gC4?^8~2&1`^b@Ax%3yKv*l5p|M zB(!ytLt(%G$8lg`tV*=mCkWZ? zD&8JdX&bB8)U2e_cYx`;Vff7L4P@gQswQi`dZhH4+6Q4N1VatEF_s@$4aZhzh+ z=+ig;?=2BQxidJu71>ic^1>H3BO!4qrwX%vfOA&V38@-vwx z6nhZ_H|0vAK&jLli#&#%0A&zZ7hs#=jlV0(sl2!L0+^pl4)_OV}>uL z`n>jO#dN3H0mtiwvEJzsdlOvlRmKN0%$UfvH&vrIUWcmXzCWDL4t!z#?^OjM@~0C1 zwJZMpjqc@H{INJb`fulN2IoOXO~q{@ma6fsImuQMnct7Tazc|w=@g81+jbR_G7!)A z*u^VBYUX?*sh)!stF~0>ZfJeq44*CC?%8y2`%6Ol0>1oi=VjOvTxvWVj@umyiuJYC zzI5NVLHhkp%)jDS`3=wcoHj^5gwv)C2ekAtmrwQkk_j90tyszC2TY(^Ahk=)G#Hr^ z57rw~4o^R1^nW*$u>9Df|MV^Kojhs?KJWHB3kvrxG zCA@8dG;gY1l$M_g7^T!SE8mndHd(5nuvwOZb>%bB&3@io7+f8#NgLOx+xz%5aHRT3 zvh=TX{_i4jNtA;BNQsL+fX>hzDmtiOz681$bDuPtB|BgGriONtl^S>g_ijjP-a7!AIV%@nmSdEYUtndusrY-+Tqnsnbm3H}9tpk=?fLVKdAY)n=EE}V;Pt8 zZ>K+L5S;;5lCrY!5IhJa$UTI%rGT)aI?$tx!MO^BXhdA`py|$=;cqOHQO-_OOuZqe zawSf!N;+4oqXW%ldKIabQ9k9A<`C^MkRMUi>BwxzZ9VuDIo^Llu*6X@HPx!=`KSBK zng2$^{~-=oQGtF-9tDShT?JreFdv}OLS>9kYMM<9jPL9gme7c34U~V})2?x!vfc9D zNmzJcH9BOygsEybYR|UJIB`62Wqame4{as3IC1dhykfKaoNuhLvDaw#sMFpKi_@V_ zs%o=QL1O+Bd(3*;*Rs-jGpF@=sYd2EFR%py02&`Scz(bhGT^qtu@Qd)PtdT-I|qGG zr_{$?qFEl5Fu7<*jQR?wy1T}X(Po$@Jdl-AT)AlxY-feEHgN-LQV>X9gle_1_^Qe7 z;6hg2$vgcRnmcE33^hrXBs^bWC@#kA3uv#G&&At^{{@lVyQCJ}+p)Q0q%Se!y}p+! zP9Au7a_ijL=kP!2_&?u4qYy{W;BbK21-xtQ4bfHlxGeS;@j*dx{z^HaI;K4pHW#_L zD&#skM|gr_azoGqnj+L%r|3fxlY+n34{dwE)Byi>yfB=Em=}6)ktQ@qjw33`J-gy> z>(issG)g5Jo8#wCAaK-gAy#Lzp7Zw#wO%rW+VuHRq(OJTj&;tfRK0tj0R-b*^@- z4OR!5`nFy*WkQAz2gm<{uBaop3lK{rk6y0575Ht~$@( zJ9{O^K37nL{*C_s<1N(h+XFbn^vh>D7#GYXXpb654E$d*qM}H3byo+L4Jvu)B_Y~c2JyU!=wuS$k*%T3HjCg#U?B~*_~(`{D zxBH)>zE=_WmYPBOY+C01IVk2Bk6fQ&>;wN(J&C#KSKc~&TNvtg8{Oq#by1(duDcj! zDRCXfYf5fR^uVR4u?>#R;19q-cF9VvmuziTG3(Z`BG={b87F0_7TQi8N_(L{&85G5 zKatP@5z*ej7|kYF z)e*CMpE8pg#bA}JV&xiYxv9V2)ynjS-P2d!-T17n<5}-WviVJ^PW5$i((`~IX)(}?bF8cKT@&Qxb>fY8Bv%fo;TO0^aw+eE1JbNoX2phQPtP};e&K; zlNt|(2!rtKoB8M&nMJoxnC6ke-UT*&5iz3=n3R3b8uG9W&b$0KhI{`>>i;DM=V-8} zIL4T!H*9p8HzfKIJr~duaXk=-zE+&Ar0=M+q>J6Z;o!^RW*%jngZsPZ0#Knk5%!=$ zHRY^f#ymH5JPMyUcfTmRq*Hk-;a0im@W6`)YWs^P?a)qe4=b#skYibK2gQNMwgNi}dpmg3l7iX2W@J#A$ zt$DSW%^>cmqeq;~qg4vim>8wPz58!9Yc4msp_F0by?WxjmAA!JPFEawIhPLDnWobW zHh&qoBam#Y#{bMnyAS?@j{owCM+ruJ4gI81R;{q;Xtf4T+{`={O(@wH zeYVdU%WS5kMEc?2KB)@xRKNoV5T6Ms2!$S-tdFIG}bJoL4YePPwRoT9u5nu;3+_vEj+A2it} z#rypz_rJX25`ohosT>QM4u(v$hFLkfNwKCJF{C)fNwj@a9s1k~*B+mCQO&67E7``* z1Mknhj|B2V)jBP@>efNuOAk&>+0MOG$F-Gp%RAZEZh3fOKT0b{GR(bul zz}KWms=A3flNhgc(SrV}1~uRg1&ELuNaM`#ZoLDpK%kW0yod2Xf$@T$tfZiu$savp zn_uVu*wF&3D6ETfAw!zQC(obg!7MZOFc2^{N@QO-KVX$SADG!0#6RC;e;qhFPr*X>KKiJx+FUHw_^ ze_5YEbq9xljhpcJl(|KejM_0a+n`?BxV$A6CXP7Px;+`1(tH!~I9Cok!kAmD)6qxA z@^7;~nI#iO(_3BTq|!MXdw#A6HP;KdCuinqeP{HJzMdK^m1QIgoZoi!&-_Ui(St!L z$-VK;f>rXs@Q@o63U>HaRoNXY!+n<=gAY)nkJ?n9T^o541rhG1JnLd~UeeVBCDJ^k ze5e3H++FGBj7S`NCN6Ag(w2M-1$*^9TN2a8PeQm~Q64Hje&3@gonb8_swsNu$i)Z2 zuk65quO}k;Zj$BWHy&x!ZNa?xvNdYXbC@qU;3u zl-ZJp@~G~+P|@_W=M_<2hSe{v#peW0z>9yr#(#@I{mBJvK6dOHR81`lPm~lO@C&?k zJQH|6@X2$;0?}~-Dn6ez-HnA>XdtITAClgr)aM7m9eyqU+-zWRv3vMR{o>8QTRjjQ zL?H_znUL`8PFiv-hvL|8Q)S-C^EWXbW+t*hfhaQ^5o@w-_M~))0h3CRiWcST#UDE! zaVr+Bol}5NnkdL1@4D#79=sIT)Q!TC)9bb|9NDCwP&1=84;JP8`28hu&K^WR;cw67eW7%#1}KziDlhfrwZ86=y2uIJ^bkbD%amNFIZ9sML3o_^V`t=?P_ zn0Y-G&FGTHe6`@jnN`B*!LX@l(4Mp<+D&-GPRmQ9%R|nbe~q2{zX52J_N?RUj9w=Z zmm;oLt}4ms77ia!1FCyvw4ac4cmUe9sTZT#tdUU~IhWaAp&jDDeX>DJJ^gym}%N79GyfL(e7G5u<)R z`T1CH{Ex@~f38q}&IOU3n#m2y)wGxT_(f$!H`AhRbOWSJl(Vh)k6$uA8&k=w%T~~z zr9^h~iA=1>dDl)CIyf-j7icF>G#M5h3Ny(;zMuj;Q(`Wy1dGd$qNRHTgMX0}Q!^!Wpr-2>rxm; zb3pP0{0~$=mp$uEJ#-+uwE!%+2zRG1K8Bp4gb;(34-l&5RT@hz)%d<_`B@xd8SHSf zo{#{|Jq6i2(qU7Pyg~!QIkO=V%}$qkRxzi}Pwn9BNxJ`h;Qs^hk4e62B~>k%F}e3u z_2nbIxYoQyaNtYyRkaW)PLvR`cTG2Cb;U}>WJiXyH;te`dGRe;)rAJg3rm}iT^)}6IRS~+&f6Cwt zUVOT9S@t6+#QBnr6w{#USCr}Ko%4q*Z{I3!S>YF!K&-qe&?w!=teu^C?N-XgS_4Ms zkLw-&yl^589G)lOrAf5MR+r`)+*$VhepbO59xH$ZCeQqr=83+_+;4Y(Y}_Sw6UL*T3P&Xm4ukf?Aea%lC@*Xq2yaG(S$Ho zX~lbVG(3Tu8L9D=hq%-b!n>UH8z{PH#Bn7}$SEx&E?yo1P6hn;oZ?~J{fDv!Gv+eB z%D&dMZ`K-jC3Qko$-_Rp@SIB-14WTo40(Qa;XW}FdF99A2*lFTf}J;3p&*9L;2p5z z=3*sonr$hbZ7F6twn9)tmh>Y08^Z*f>i+|vnR!O;`uQog8DaS*m>J8Gf@;?{@A{Kt zD#lvr?@xvC@rrWFnk6MR%d zVgr1^x7(-bm)mYwtnxKh9a4mr&KJcN&r97Us4yiBb~fvG@#Lr$1iCP^3AwGh%P!g0 zLTE&3I&P(tSog=KtGabtLqo*dOB3^zJW1oeCnsiP|AKUWSjW!Nv;%G=o($!q6~@Cq zDS!}3w_tA`1OEzm5CzbT@o*JELk1Sm6rm6x>BRo|Ujpdn>bKDgjwdfzCwxh75R#Z` z;=zl73+LhO%N&1ov$t7Zo5cVrH^aCRt~21UQ-IcIV!7rtDr0)`((AGkd#w&X3ekY! zoSc2$LK?+0$9t$0Q^q+Zv_*I_bAZ{1$HhO%!lg*Ba`uvbgh$)a#>;b`OX>QG@ufk5 z36W9t@rKgm5z;`Eqr}i^lERsDQ}JTXlP^OT+(fxM0>>OpAR11wPaY!D>UvV%he(I7 zv|TDiBiU(SG`vCg-A)dEePI2mjDDdK3d-WSrk{^LYPWRQ@~hx)j_-g3AAtvfV-ryl zg8+&P2m1M-208rT*nP%-13+1xJ8dYuq+dWq$j*zKTmE@jJt9El9z*w|TekOuE4ZZ} z@)o}iR;{tFG_)KEu0AteiCWC!i=T@#N{@`q_rXjTg!u8R+E}8e!bAuaWzJ-|RBRu< z_1fN>5q)*>l(L#o-g>2w%DQ&GoOrf0!q;rj|CfRv4&gvbmDiafO3xTOOrzLG4WfiE z{L=ch@9l?b%cLfl_y;4ejR`-dWsNI` zfhvF;nIrWB$TvVhzauz`>fbSN@mKtXf5(7*);RRXq}aP|VECHx$g3N-sLV}{OL}gR zP$aH%)mCg;AXHx~=()}KvV?W`_=rlDW!geEtI@|fy;||+Q2|?|v!tsJaq9~w8ZAgb z%n5~qv{i!7HiXIp_5*pb2aeAT4h=qJMDphl#WM}^VPs?iHa^>ju77SwSmbJS(|nNX zEz8xj3rleSB>#X0eXBNo!o{e|R$*#gW{sLe z37nJ3c^plY(yMhn2u{UoY7>_ka})ZQ5`_zg?3$FfUP4F zNeRKj1&2;RgyM=P2!DJdnDt8VV{rcmfbk)zBrZbMRlNQ4IuS>TaaxuHE-g~7q5Xt%{ z%uKg5Txn#qDcij^HkaWGUP)O)l4Ov^_OeI3o}VHzUvdZTd$J_1Dx~ zHA01Y>h@Y$#CNhP6{?AD@4ZbZB~MrsuYMFIg*V|+?G~cHDy5edOKuW=bM*?VM1ZNN zrG~-IgH?BMC^Phq)J1q+sY~~+{*^1qPaKz&K6bo9GCfO+n+jWv7d3%s(vAKFkv=3V zd)uhyi=DD?6a&i0I_wjk!GEiffA#nn5XG}x)-cEY$XPFrabfs9M^8L$Vs5>I4vOo3 z$XKMtVwE(h=PmtYjhKqKj{*tT=tF5{Yaw*W*&UgC(n>>6g9PhFy|G=9kTwVdA&{Cd zELoUmSa6qfCv)Cigg`z>0|F>CMfJcDskpdAf-~FTUNm^4==X+kL?bQ{=o@T0X=K>} zjt>;t4L?2f>dp5zsZni67qrba5-yh!t!z~B;1puNSSHzA&hWx!-d1cgap+~Eu66@C z%L0Z^r6Ai;%^S1gV3az$TR=@h%meH|$!Sw7nOefNsgvY#sbGqrfBrT}6FuO~OW9C8 zsjzf5lJA;V-xn6Xk(be0o;xK5sm3(kNm_b|w>WPp4%r_>GUh!B~rFmZZU_ zRJ7hMfv-hX^x3$){EK7!)(CdE;0f75H{aowIiJwnb5s@If+KSizujX|eC|`%Mu0J# zWi1pN0p-40kZ4ey!ecb!o5^}L{}+7AC05DKCXqC=HLBNp=`G=Hz^-LmMrR!YYIieW zvWuHvFP`zu5(9C)-b>1G*Lx74lo16HB)eB3NGx)H>h^86yav##WQHKrI1mamej~Qa zmm3@?PLD9gbbwieNp4^3cLI-S!zBX!I?JkUd?7{i*txy84o_z%S>$tXkLNYyW}g7_ zfK=eM&Ewiy?S0(Fp|+lb$r70Hj9}e$yLU~DJA;D;T+ua}hBHi+DeEi?kLS`U63Ys9 zHqSiHSzI2s;qsm!?R`$7%I~Ua1v%F9rW+}7x?_RhqYI6zxaK*x-%s4~6>>Keb_eZw_eF0mD7MG@n%6>RHiLu1-1(NV=vVqiUI z2q+oEGI1A)X2Z{u)=L_xq& zPrsPX8`N+h70}yVGxz&e%C8U#OzNLW-mWxIBc6G9v)hhKqSHuVH$NhIX1ZE; z%lfP8Chp|RP3#}ys%M3k8&s=S>nqOY(`{gO*1FpErkt944FxutQxeqYg=b1Ip1dOY zB0{RSjahV;-H(xbD>*FB0?iRgocX~GGjcr*(Ci!pRQrA#`6xTBN{K$W1$^bFg;atg3AM_J{uQeV7r;R0K(~Rldz zDdXC-?`y88wETK&tZnGO1Mt9l%O40d z1!A3GFrrgbqDbkSIH(^71V!K3W&u?qx)+N;ybYn^;Ru39#lTBw*@>aJ2u`cJZ#C3` zLLCAcLj=Kv^KsM)QixI`Gw1Mv&YF?wUyJiooj5VfT7FFJO=DIwu8{B6l?QCD8TcaJ+YEGac+uT_QAlngVBajDRC0eFackG? z?TmQ4^90k+46q1oyXHqBeXCE#u=zYcaIX>JlQ^`PpY1d{h5h>n(9-(-K!0B8a|xt@ z(V0a9CiXeDiuXJ26$>wEHb>Kka_?&@>zWk%?{+2tZh(FjL=oSvtl_t5md9UX^Qr1QtOtV;w)$jGa-`zf!(WWoAn%XrI@8%*BUcKrX zwt$$c)wDO$pEPnw`(#hU^yOe{xmH9!sH}j)AINNicsccK#mcmc)FDA~<0;bxV5{&R znpq{ND0rk0`>m?ji@8uXuA>yz3won{dn>xeHeI`D7kk@MYvfo>sgHC0{19^2AUW+eO{Ux{ULJ!-ddcO0ALeb0U43o&kQnGaumE8$z{i3`R1`@oH3cjGwj zD?$K|EI4Fac9*8-q zkiSKjddgq)$|F~O2F~C|QHti~{nW2kfzE0%({{jhe$)Cm-MrwMMO0i$>l22{<^ST7 z6^wm3Iq#Ees_RN;5BEPGknVSFZv{3r(XCwTpJv!AgOwc0`Y?Pn9xV4NaktA>u5J>L zk{g)wTB1k4*s|_fMK;&X&GW@hSMLSwLdwN((VeM}a!v?OT@4>HPH&8S;UUm?BH#`* z>XfXLgW2+zZk=7<<5`Cn&QeJmyhP(faO_I`WE@hOQJD4gQp@oa4dB`#$3v7fO={o; zl)-W_Q6i6fa9btW;lJ1ZnIiSiALgf<7dq=UuwQ{lUhvk3P-BVT)8P8Y(h0EZezcGJ z`}lR-W!4|g;isRmdwYA`wzsfcM)H&E(pKTjW%Vc`4u}`q$KB_@ep1hq+ACX0Y*2)&!%qS!r^Jv54+& zm7#t7*Q(yi#t;MUakikxrR;E?b2uX^w`a-hRxTe{>%V(=dN+O4F=OhybiE%H?DaLi zSD%bhr?y#Y9q(Gxw3B5{lB4YJKN?s3UOBk2cj+x%=lUYeO|E9Wyv{-Mx|`8G;&9cy3XjK>*}1-$9ec3bTm`|ME#REW_Z#-fH%>Nb-!Q z<0X|ZE=Yfn5USiR{erarylMI3>D#XUftNXR9yhEzt0z3p){KhgvTg}w^hry7GT15q-oC2%JvfPWuAZKXcB@D7E5%oaQ3ihB%Y+{6`ma304|XRFZeW$(ymB7+agVJ? zy9v%koZ$fm{?sm!TSoNg{GgDwDF3V1+gW4&$YJM$9RcaDPluFan#S3=B5`_UMlKO900qJaE?2wbrLJ=##<;ehBT;^yY+>QP-!eh+=@2f<^* z1i!_>^CyOGgTwqWaA*v+#Q{@2Q4pD4&`Wx9z{dbf zUbY9xP+&cY?Y`CB+rQQ^N2P%Pj6k@->iQk46XD0emOT06^Qj1X!|UtfhBro%Fq;Dw zc^d5N3Jnv|*?eP$%2UR=B^K7jF{ap04j5Wcx$DK~9z1;ORHV)ib4u8pq08KNpTyWK zzp-6LJ`)SbVVzy+O0vSKO}UFlPgst40PBKGDe#AXe*A-sGa(Dovc-{=_iq}+(DoH3 zB$XT=C=6DlOvzdau_*rhAV2+(oaNaisSw((Ycb1BXB)5^@?Q{etupH6@Z*(u1t>23 zTQnF3c%YzG{o&9`0cA7vdm-c#!r-kmQ}2_P@VDpuV`C4EF9>bDtG>TrR58FL_j=Sh ztPe)~B5Z2oxPL%Txv+V%izo#(smM)3wq@x(p`l~aHhFddtQV{K!u4`%7A8l?&~?&k zW-Tv{$FiIDh+3YTCOb15c^aa9oYA;%O?TnCDE@nAU{A0hpNai*d!q2ON(P-NUO(u_ zKqDjd8}^_uXee}zOKhKEP`wQcqTSF^AQ-hy23bV)Yf;u(W@ zqy51TcH0c0dxF~aMbGJqG>&Y@LU4Z!FuyYSS4{Kz*o6!G`}0ljo5cO_@nRIf@LiZv z?ES@|fp2{xT~q9`=dv%o5vt~kjQZ~x;B(blaXj_T&e8^?{RBK*VEYgOsSsYOSB&Ko zg|pE>yTJ#b2XR|e?0nht3;7~F1(W= zxA&D%%ulL+AlUX#qVOO-C1Q3dX`+kmn8teBKzL} zj*{5?z?aQuyC*3oZsVQ`bGhCnd;jz9OqVZJ`o>1``!Jt;;Hf^Y@9E&l*Rm0RLDr;g zBh@kvXRcpMmG5sK9CGixqaxPWJnovsw`Ds$AR6&QXA?rA$RizX(7`owuGdD#qHy-c zIx&w7%{S9?KPZE9_;>6n6D8y9-P7XL;JX?3LvuB10ZHyKXz6B%*$*#!*4VWx`2j)~_ zJfh1Xd2nJpI$AoUT!$Q50ixx_hW}3`G3;Q50|Y5bp{K+I=&lj#RH5jwtqcob*!bT7 zK8?YZ!99znxjQNlO>)Pfo$I{LM)QX4YWg^==QiF=x$bT*CVJ-;HZFs+WAIgthykjJW142sWRMA0KtrEDy!S-Xi-@|= z=kVXiLD&I%OC0`_`%pjNA(dK=okrsZb+AHCowTx_x&|>HFORg^r4Iiru({8Q((;VY zq9Tq9hCcov5E{?}tPUwDLSib>L?NcU$;rvkfZ4~uldmZ;$6cZd8ztaTTq#5$NRG?W zT;b@6n9Sb_K0@(8m@^U98vwJ2-ca{Sl&`T1Y_<%AL9a88N}%X-R|8=3lt&rKae-TqBD@_!wtD79cd{k}s!s42kw=(3SIwyZVlT5w{$ddL6tHx-t+M!WQyc zU8%uCDxcqrKMxrnJk1Gnv9$}#v_MBYgRM$*7DJcogmOv+vj|gdstkljvbFh`t{~s_ zpf>cp-c0m{XWGhqXvJh5@2`6Lg}I21O-EcbCzYIt@HUDA#<)Ehk7=B}7(iq}mei6g z8qiZG)w=O3`G3TS*x4r{y?h0HJ~@qlJv}igTh^aG*I=_R{tv? z(WEOST$VZMQ?a-EW}58Zai5fmd#~gXQIJzxv!0xPEp>)2BUMzuS{K}bWr5?Z}r(>y*@K@3-%ui%~oPzY1NdpL=d5?W4aDG3Fj~hb0YfZ6I;*>OJ7Wp{tB{}AahF7v zXo5Z$7cox5 z!)o#AB8yp{hiD1M^S#4g?u28SjduxXBB$cs0?CZP)5C{ht|w%Qg;e#_Jfy9~txgc4 z*PH(zY2O_XMUym=~D=bbK?e~2)!d)jt8}?q(Csoj2 zJieA*+nwp_?}KX66qQtKph}r|lAoUKiTq~S|2#Bzmzk9*-q-N~4v!t-qa?eDaMWXX z@GB+RhJ%|gyolBnI?~=vgIw-c2&3+#Ui8rtz2bL0*Ls-iuYKN*3I;LLHSU2b6k#D` zFevdy7Wm^2=7icekf;oB7Y_t;_p z)8j>T8|AEz*!%RY%iZ(-9}w|@qQKCvC1j5Nml@4c0!Yw%rcxq1b=MBeDT}WUHborC z->l+&E41##?KvhjSIKnXc=2SI3BI@;8>)v#3eBiJpV6?C7ya6M#y^8TIC*qDZkcSE zt-SPN`RhdY9!CCe-rlQ!VIj$`q3tZiYc zz<(NuRCDt|kPC<^Zd4G$&tI#6l(HCp83#Q7mJzP$bv0TN||#s1ZrvktV%Dnrwgs-cD1 z28iy$2P)zvG=FJLIp0&dj7DzZ5Scl@`1bPG44A@7n)@~qU5TvY6KXH}&(zg(B3{?d zPpKY_tz2Ck8hRV)ea!s6ruw=V%e5`o*lBy>PMbScl&!Xc+74Vo0{snq_dbVJCZ^Ht zNl->l4{8X&%_+0{u_8mMX+$-G73<&mp9}y)wN!q#PG@5Vn_%OlTZCrxP=%j51f+su z7f4=OjTD}T&y+Ml+en4QF1Y?LhD;_*(pM;(M#k0g>D_LI#eqPZmk(q4bGKY|0GB2G zmq!12Nq9y1##_G6rGC&_25gYZ)M4Q5J6{iG%0BNe?WOm6q~BVoe;aAc}lD;Y3?E^Djs?k+>78K|Gxxt_EE{It}*ue7QX4P|Z5V6d|p6D?yM z7|Ak*xEzOir;+Ok%3FtTJhA(GW@%qneQ!#5b(p3xb`SAAsTfz=DI%Lu zcQCNgC^}`LLp|7B8?F6@)$sNcmr+&~@;)AQS?~FfbUB7qte_o7{R7@vTc50qKidPi z=L){I0g(EI{Z0XtwBAndJ|=0^G1ofjzNN|_C6?umk~9Jv$+cD(=(jPsKh;n^@m6~4 zb&UaZwat|O(Rm{jX_A4fmgxnp=&a$4wglkBCd^+E60-1}S4Du(m?0OQKpI*R8yhc| z_=xw8p0y$z%L^3t6+(l!s;j)65@%AQ3D}5<7(Q_thmg0Ilt;^e(CPn5%=|mTf4w45 z!hY>UTgZ^sgUFw@<#whaxN5$|SAkYNg(z|JlRo-uas2f;U54d0 z{B26wb}uv?g*T%24_ylO`{=(0VyBveda92QB^-SRC1X=ZrwUzgVzb^%V_AvDI~`_c zJ276?NRBh_--;Ykai?#4O_@pV#agv+jH3f?r}qT}BG@ltBtIKv^TsXgPS`$8`n`k^3_T z*W;6Y43jU4U6k~djOOVx48NCwO>n7f(!BHccG1P>*MV=rV;V}D36DeF3xNQ2f`PNK z9K3Hplh0cFjK$ThgnD2-8AU*vxkLaKXH940SP&!{POXUFJdCbT2I?+%3TeoR7;7L+ z4g;x@;uk0W@{Yg1?O$Ax-1vdpMo`ICWP<=_IG{?2Rsz)XQyl8q7ze=YpFxgOp?Yg3 zf@1{%)m%F6eYxg@UiNx>3%haf2ZXb?;iq;Al6jzhqY0s%u;Q)ORQh)PCu^0%@>)RL zLcj&AH|xOUlI-=Hb2o4Jwh{n{^4$#X~dO z>-brOL>~PC>EGIkKs%(mdG4BSBIbLn_jh|%M)Bw|#Jh7>SDcNaqR`+eX{ORP(Fk!l z&H08^RiWER&UDcJ>-}-=3f4O!mQVu*V$zq5;c0z;6-FOH@nM~T1{VU6frH2#ijbIh zdqC0xAvaGtl~56=KS&<}=RF{y(tzcGKocIn_zwI6noFW!;8gjp<3Ba|B|Ll6ReK!t zGkh08r9HieKwFOQflxDr`P6>Q=D%44Q14%W;GAI5i|^t>=^Eqxb%8}fBiOn?jjRbM z$=4+xVKWVElX&~_P`+2H<#vXOPkXUsLZ6au)f<(zF+(! zO8xer>`yS?Vpq{69u6M+==#dzv4p;W2&ndB%s27Wq1=7Mt|-hR2HL9tt?aO9WDgb9V+dfI@oufNEVg( z@kbrSRh+y;QE#3#HNS&rWW@Spw+ZEa2Pr$(YZ2WZ7tNs061g}L5Q#3u=atWQllGE! ziJ!)V!x z%KiczBJyOIJjQnrN?bzOBvh8`0^=wD|G$kFpC{{%N^%Uh1!$OE+S>Ow*H679TF`9dK0t5Rn~Q_UhX-WeC3&e=Ieyw2pEy)lLsE z!-xr{5BLXAMmkKj-^0}SEs1ZN&Pv_f_3^pRJF|u8&X9fmwf zo|dd4x(PcnsuTL-y?@0bK4}|-j7OF8xkT9fyU!Z3Dwe}Fh+c^rF5#>OA?{+wF5M@H zGcU)(A=8vm#!y&|ke1541E+-Ijl5_^Q zH)Nv7f#-r2o7K(FTYElFP9<$3Q{Szy4LBPA#aZeX%KzqgirU{@M@LW3mp%@KDFo?% z7vHb@Lfhmna?br_EJJ|n{$DE~=FH;`+Y=HcxQ))SlyJ)V~St@NP z03ExCx{VXD$GsK7G^MLVv`?iihCd{U!&Za&%9EN1q3KJ?MlVl(gJhHzf%oY8f(|M6ikK_%`c@3-`znYN^;KO(kp&RNDQG*U5;j7>U_$R$U|K&oh4Xv7nv7 z%UIXiYoXxD#}c%~kLc-;HfX`Fx{&Cg446P5r}M+>VOkWOoC1$y$(1O!Af z=z*T!^X_@A?^_aK(b1126p28@odrt^-Z=!j8&>o~R+Nm-e?0vNh-f@4m!d1)D6Jbq z7jI{}`k~tEH~r}266ZA_JCbdP;FH!NSfw)~fvmjgXQebW0Ge4G-e`kIG$X2*X9u3idYubt}7Ke(VaWW4u{xskhV;2~CU z@aI&AA@%qVUypRQ<;8#*XO}hPZorKvql_!2w*$pe5A@B_E!XcC=kc5JUWoA9Xz=|4 zFd|UOG%4${_SI8Xxub=AM0$q*B28VDnV!h`A@h{QjZ5x`SHx@-bD9OoNlw7mY?l0_ z6(aU8eDR~vQn~{Rp%NG;1gj8`GNpmocxoDykD^e569QVi z_>K#XXYI)#QNS=*$9Is-iT*8tp<%91;a6NgCbiRhuW<*Pa-7id53AkZG;U^$Xi zv-?0prM+(Xi^h>AEmOh%F;o>;{u!6VcfLIs{EA{+^Bf&fHwhX(LI;%fc!0_BYH5Z8 z7Z)j2C}5IMiD_i6{Sna_q+z(eFf5KW<$6BbY0xSHMG5Q3givR@ z!cmnZ7n+gytjZfucoLk}lFO$4`MoR&%J~e`bC96ohsj@MIcm!n?_ePii7Rebs{|_g z6WIvBUI9E9YyyO2NWA&c9UlD;W z*Kj@gdrn4i!8WA0;4gI%$;LYT0pVV@4va}h&Es_R4U(PfL2{vI;bjRU{y#<1*UB$E zXfvX^9ab{+RqW{>5RI>SK9`sEs%v;nUbm{8z0CJ>j5KY%*m`T|!q!ZD&{~~aign~< zlo=+^?94UG)5eRpO>>lY10N)<3Dj(?1)scHhV;};(bR--{{6nuc8q_(`LNfjCGrl| z=P-g{`emv23hKoRKU4fF`wLeB;v~%_9~7JXSJ?N278fXwTZ@^heSTikUSNVy-++@> z`IkE~2JWVW(G^tgRD{D@Byx?gEiS(Hhtb?T9lRQZ3*cM-81u1$3-~QDg0$>LiKp02 zP;f?I>7@nS>T=m0dKxpf!3uUHsN6f=U(i~vg*WnaM-gx&5*M22eXoh`87GD{@N^GK z|3c{hc_h2>tmD)95JldeP#I13o51m7xSlss;Hodfv+_+pRIY7OelV2>m<8?UX{~s| zv|(CSVBkYQ{FxBQuieJq)f1?($9Y{3-t{n3d+#<9S9^93m4JAbG9=ut;N!PDv(v7i zH;rI4jksu=g4u*dW_wIUFL@R`afu zK`hp%-CO?-=)vDX=H9&?KFt`3@Qf%Q*2!d`?K!t*DQPrf=pEFue^guD7Wv{3_o+zW zo>@FG$tOpf5NG1|Z12DLG2|5}`8vU&@bk0`7G#_V4NF0%rC_Hvg#trX!7!^y4o_Zn z3r~wL+lX#Uy&G(u&#o)KP*3!T$vWSv3+slyn^c4MU0_+L<)su*O{1@HO-%S(C)k3%MjG1F$LY)WUz=C!vm7TKeBGE%XPKi{0T{)=vY456orRFG=y1hx5^PTh9*3ef)^rcC$k6PVV4> zPu@-Z5ZmPzc2~`tTcO-Ym$97{5~=_pwM>*pkp@vD^T+Xkhmb%E3EY27pXM zwt0gkED&=)%2GGqAHB_FtlsP2H;{UOTFd9MiJkmO8p;8_+-L&g_evIq3}3n!7ohNX zd17KY=o5}iPZ^FRr7t?Z@og)xoCXOE_whEywl~}`#+)dhXu||+*dCn5FMjd8m1TEK z&!gdtXdFcGDjds$w#XW8ffGhAf4`2Ge*Qkd|*#oieDlkMvbGnK$)we-aMewyzAgsp8#ohCRy{<>2-W8uXdS8CSo!tZ({Atd z#zsf-YA8l1wck5bWnF!7&|9`NA!x2yn;gwz#4msue6#yE48b~}qzG%r2Nl>ttevxy zkE?oJ)gw2<&Mpljlm^OSGNLFY5O`e?5=;Pt$STFk0xc%~HXJzd5Rwx?6!9`A3<7}= zN`vJF5=BJ||A%o0PyQ7Uo>lN4Hl{(wQd7yEsiUX1=(U@sv^dK6&Z8X4#T!X8PED{G z5bGNoLJo^o4u(+Qkw#DeV^`qd`=afwKcb6(;+Fh!I&C#G+-yQb~8GZWN_8$y8{sD2Dn-eL0vi?2G!q#oO z!Fk_fXah5O*vvS5zo0m=YdUU!1sWh z9}vI^5rv%mU})SZqr*U^YWFlD%tCghC{}8L=6%}SSg%f5VET<=o6qWfd9n@ z0r*olh;%Nu9W(YGy&qWnR(;1~Y7xgsiuU9+E6bi-Sdy$IsgB=o=IpN*nrvz* z4vMUa*=^Cy8+o2PqyITjWE=!#s7u2x{;XxMMCZM)7SkZvH|2Ij{NQ1{OsTv~wI940si%u-J8|FBQMxy%yBpGCQW9*w&hq5z1fRT{ z+K|Ik9Rang-m0?qYl2`IASIOTlOcr1-@R+Y=TEOz#UKUgO6@2%E_&^{sjt+}S zBzM|VUaeDF4p;MrD^`;X`*9d6Tv0Ure1BwoWI}JSH)EHy{)>*`#X`2PwR9+X_BspI zE5PRJ-9&g3$SjK$YNakkLY3Ni8WZv*McnZ!mRst4d9IZrK<3N3l=(tX_TY79V*ISN zLY{T^+?N_&71nep8@pf+!{fBO#Zg*zHtWcX4{Z%GEPO+PlT-D0`}I}h_`h$}K1OEW zRfv7*?k(s^H&gl#D?PO|ABFpl>ySwFs+;&}Q>EYI0HM%G?GsF$8*P91ij!xgMh;5S zqoXBL#_;qGmY32(O zD%lWFp^hHjS^sY}b2FIQs*86oS08Ak?z;qOWRE1@rf&gTjA57tX3{auO}A|-qXg}_ z)jrSp(Rz$M*4I&@C5>ZU0)^=I%^mY~p9GesHO#NEZkOp7py`q&?Je&|5{%|r%$`mz z{y>&h4wP)0i4T~x$Mj6p`Fb}a48W_2f+4Vxmks>);AC>F2I^{}IuIE9nQK#FkJ8e) zna$F9((Wxk{p6n!5D1V3Ko<)z2i6q}1=Jw7TMa@*Yy49j^poS3Dl9~aMN{h@G?%oV z{YDKZiDDC{#EVE43UYWb@FyT9daO*&uKYpXCriKMfKHfXOm5@!%lGeeFzzD<;3!* zBtNKH<6L}w%v7`4EdBct0V(B8LXR~=6p38z6(c#SQ#X90w9F|zU`YD-_Dq9~({X9( zpH}CO2S%HYMI-ak&z9da#8^sJ!*g=zg7L{*axzX0Z-dH+t)lA2KqYlx%o-J$6-&iU2lW`7X*nBkHX zmAb9^8wl`Aj0VnGG$L46KrY>~-9+v|h)MhM{rNd0L_>SemYQ5%SXv4RID7JK0mU&G zF(r68J_I+V$9Oc@tHk#UFb(d6K?q1+ZEF4QB{-C{4hF7i$N*IXrhDK7{&`YK^z`2} z$!FZ{yT49m?a|ON@uA+KU)L7m|MMphQcxu`9nu`v=k}=Tc8|=9E$)T|v^8aITN{>~{fMcq;h@|>y;x^XIN4v;WA)$P zE9(5{zd6&k;_gW$;+W4?jaRgk@PfB0LTG{z>!ad9Q%GTj_zh_vty9>t6t(CN`iL=4aBPBbPV(nP3x)WFM^ z0*zOn5J7Jj;`<3!ob$NLoJf%fEP)GjQREPa5;+UCYLp_e9PoBfA_@j&$hcs@0#Hd2 z5}p075m1y9cqCKflZ@8NU8~b_U+}msHRv3c)A9Qm{zS$p<(m$w$ z*-+cR|91&G!itU`u^}6hly~%$Tdw9{c|j_i(?~YykZ5vlUeyr(A5Jf3X{=5KN~Vxr z;+9a8=(+4a+V>JdL`VH=Jb;tziNXg$MidO{q_E(*=~eS}N`B|(ZOmq5)~ZkyYs^f# z9P%f0{_Am2?Z|#=?d0OnzVLWWckcE|)xJrh8EL-mVHvH=ph4eZk=H(z5!;%(g;zfB zP8}}LwB&7BdftA@jQiM~+LYj3aiMF%y=$n6wzkUexQ&ax(%_YVI;E;ElYqX=nO9hF z&VW!*rKulSow@ezvf{9s#8A%_?*KvkmI}2Dm&^wgc$+3adPWkvV6FR0U3Y5E8IF`20)HWP>W1rJ1A6aT_}!j_yc@XdFWu51 zr*wo_Do-2hweX$CtC;P$t_nS};tg}hfw_tYf?Rc9E3qT{Z=AQIZ^{bl8ClIX@w^Hf z{`C}pBqB_-XUIp7qM7Lr^cpwgs=C-hiv1J(CF>$y{!)?QsaA18#{SDi1p`S+EiJ8L z7!ssfA|`!kpeaKXO-B5YyJELYiGV{^G7&zeCO8@CL1WPu4LV37n6z*K{}OIEp)@#w zEejfOB2d0|)HsQC$pq33$2(uiXWAt>uz3`bXhL@In;}3L8obTIt2!)qZf9* zNLu!fzLndbl6WtR zo_+cG5WEUPNPUjwEPF(7S``Ein^%|%AB96`@|eXY#W&c0-nqik0fL?fgRe|k5eU%0 z0|jV#f+eUV|UNo3xA&o^mE!ePlZ2dq1r2FdkoTa{5hQTI-} zJ>fzqzc0VUSC*7D{5~<(<`sE+zANt;yFQ@g*)(GM(G|bcVciLTbXWKkT`JeLSE*{& z3LW>l=lkn-261K6-lVFZKeI);ENMqg>-blaFYhu3=_rCP=s=EU5}Keh(HA}oG{(QY@l0C zs1ArAa`OL2J;l+|M1(Ss$9I1mGcZlf9ix-?9|aj{6?X}%j4ktOq%2D?o87K$&+z@} zJ1JA+>V%(?-#DDO*N?&wtMW@C(=7tyU5EaOX)BqBOnfv|8$UJF&EhAU>s%!_28i^R z+#HV(;?AhLV1TZY5`C=9IodWJrvppp5@~6&o6}QnNuODAAi=pVY2OgQlvh_v*De-c z78VlyJChP2rNA(a4Bq&LCroR+c$c3elqgz@9PgFtN=Y+az?lCAc!9G3Dyaw~jLy(f zf=BtGZkNx=D8YbGB@c-vCkg?(2Y^wu$chGc)0%FFM|9$r#HWItAzM&bc z76RfvmsRAAay*~np|BrhIeyB6WGKMX;1hU$C&EMUYmBN|cIB8l8imqi7B;L4Q$U(1 zU3j#-J5lj_*}Te0gbJoh7f$sOk&Dujy$ajrgcTHnP#sx-%aJZ<0HWa9?S8pndA;d` zyxPW%PgYSN-nBHG8nl87Le3q_#zxD>58eos18yS(WJDR#vSZ0JcUO8Eeu^kht%}Zz z<*Q9xZcj-WTKE|wu=`UXYLmm_egP_01$%L`jBA-DLz&C_K5qx@J zeFB#s3jl9KeDBv6O&C%k4Fl1;-r*ksAPjl)>jFZAvcC8G5+CyS?Vn2*HKmu}6Xg9w zua;B?pX96a3HjHCIG?IHw=yp4R@+DY{tK);*;Pe9rRbFcv~uUMedXxZS$Y2-*4Qa- zd_nRZL+O)(WUvgviVQN43OQV`pqLJr>2mWwy+%z=6b(35Xzmv5^5buhgS9Lq9V*)s z9QQ_%g=)b-Rwk?f*fadFeZJVMGY+FA522{Iyw~w92dvrQ{}S0ah03kzPYLDXmrG){cRRP71k;V=S|j&7zMWsIG7sXq<|Js~q1)5! z#1zwbrZRrYg?EPS@#~7YqJkH%zqE`=Ibpq;N>QFZ6MiERDx;X!Ad~zFJOA5ihnno9 z^Zv5~80`}vBcOKZ`aV%Qz_7aID0uTsVQ{s;)y|pm#Fv@VYXKECg%;$5(vNirKRyP2 z)~vUZzZ;Eim>E`kewO#mu^+eCI)|+qVzfJm7pyk~Q~0FHkZ3Z<4#<~du)UHQr6WUH z*xxtq#DRXs$@3oUL2<$98S^vYmzy>gg0<;C`dt1gacJ9;(4*`K0fD>_8ZZcCpI_qCm!`<+^2=+ z)6UO}aXa6ohknV}1q!e@j+g3-*T!Oo)_}Oyp1bKGCdyINS-<7!c$5(8aXfm_w$8)p z4VMNNZeMuQXVRxpqC^6#{Iv}A2LxTydQN~zVCL)kPbrfbv673DRb5_R`vaV%)GVxk z3{K1@7a|S$uYpe0-OsjrIMYwID`F%*W!T>QT!)zZ2!>lljLE3LwmRG?;C{c1kELoz z-D5r9SbE079V58U1zHmKm3*FR@49NF8S?d~K5M}@)!s^_VgpZ$k2NnkIdqVQf~Z`0 z01UB`0SpYB`>n)80Y@L-2$Mz>V6G-}U?sLvG! zN?9UcSa}aZP~_8;JR8=P^!{6*46YfO%8JDD4I+3N9-z0awsQ(8tr{Dy`|cEjy|E;s zcybo@*^A~))3vij>thmsK=e%(m**sB<6Me8uQS)$VOG*ST4#iUG|<~a;wZ_qZ(&8F z4)Z2Rs{FRa7LmG@5r423=%C$qkcORR_Eb`3zU4FClR*@&F6J6HTD%@O+&rQq0#c~v~JQ+d$BSjV$y#7wh{Kg zrO45ydI^OgXTD8b z*YQnFWq1H-+OWUr`mE4#2~&IJX~qXq@;gW|Q{ashOaS>co&L+wCzDSd!>rks8P-6yp1-6YXNaI=Daei0kT)|_-%if- zy^m@7RL_^tckCj*>A~xnFlOb4_? zQbF|Ek`t4T-3<2SsZDtS+>%@OS+16>jiPAjP@+yIuPzMOHB@PpJ@xI$s(qfHuZFl$ z_C(Nh^`mmyo5W;&T;CAc6T_haqlvUHL)}SQI?|kog}79;4Q`FdiMYk(^_d|3Cd0kP zu&_g8zX;*3AIJ4SO;JiC5zRFSZS=e?}!bfG6qR1 zRlftKCd$uW)_$7lC!|ch@o?xqMD95Mbi7{HHdTUkBPN;))Ai{X0#A5 z>Lgz+I(J6$;>$i--qNB4?}_C((`UjU<;jMBQ|6oxHOP!gVtdA$NhohP+&*v3NJW3J z=Ck|Mka*9h#uA}p*W^!MBh@yp)1Dvk3T(1_u~<|(6rc6HG{w=ey3~Qk`-O>ZtU{V& ziBO)q?d#MxZ{xi0$S7&D5m(zf<$6UjS8{icOiTPsDSY{$a_KvjEwgWX;CJydA8}FW zkF^xb(WcFf7yAZ>63mjmMPrf%(nQ=EJ;;;@TH+Oi?Zd6A^;+U9%23w`jf$!%Y zST$|-*^Z%~;zR{CET7pmHxeoI*!+J-F(r^2duD`?yl~%PX3cLR%yB-s%?sMmp*6-3 zHofui`Bce8N5kQj(R}#RRfEy{>Skvnltwzkn#JK}%;>jIf7l5aCn5x} z(9qB||H}dGed}@q*^BAg&x}_VyUfc*0`&tvF(#o@KBL>3B`GRv2Lm5u)_d4JAF3(q zov9^#Qn8#G5G3ciqf5aqX^KO7Nut!#+a_jzG`zkY+uki1$zDIwo1~#98X6rtp|qff zMCHG7I`g9H{g2Q4rfP?gq$Wp0V{gO44{l=2YxgfF1*(?{j78M8ARhE?PFlqI8vBQh zEOcuBZH3E^O5 zbb-wEpysa2_s`Zbv7jsdKLEC$JI>4r_L6g&J(l2YVx@6jJZTGSgx(_ z_6`E&p){Clcs3r$Ys-IPNEdtRmzII^DKo}TqJ9_H9w*0+!!m-&xvt_1Q4_$Z^?)*% zFxJxTExK+h-HC2Zr#;g`&+oiD5C(XZivkPZPke4_=_--r-?tpYzPT*1FX45N-;Ud? zs4z|`I?J<$9E$rHv)z2T{Sw1aZGIoLHfi1$cNY3KOX6q43$FcVBMZY~KMtNz+4eJC z_OMN3T}(F$GhSUlb7ZC-wIo!dou*o@v@$fJPWTQ@`xc^KF_FDsJsC6?b9mO8475 zF)V6btSqxFeD|i1iA#2Vo-S6Ey=Xb$9B-smFuvXYHNX~W)x{l~HrRIQ&IK{_>3)k( z_Kure3`?vPup3^grEW{m7U^uw+O)XhnO6M1XMa#od~B5GZAolyWt~y*j>nRDt=9hQ zwa(oSy~;L{Ptne4YV7Y$u+h?zhCu#q1O>JF+t4v${0cBbh#lyC?Rz;H5IuZBJb)Nw z5LnHVj~}yG4mNC;$iq!Pu+!h_(;JK#M)z1~Iwz{Z4CAzpjh>Y?AWb~{d^i@%jC$XB zna8wiy!H=L$B2JGa_CE)-|_D%${#e<$gabhG7fo1rXtdL!z*Xe(q4FhyqftEY< zLeLh;^0ukZKg9CNF;wvgXM{&t#PR{z+~QHwdNCHZ17nDDaWlEpzTUZw^PUy2wh$iE_)T)7+S92n{0l? zH17sF6>Qk` z-7~b;={P~=Bw8-e5dVTx9e<8iuM@h6ZOmIq?NQI4lMEEW+lA1jj$N7^Y2HZFOTIsR z<=twxZc;^A#)s?{v_ zs7z~~Q?uI-xzAj_q#Hjgvo9Gx68_4`EL#fI9K;`*hix00_3?XMyq~><)_!I%6;rVF zzY7y;_ET$-F;c;d2F8j8?D19LPMIRMd4FaHxs!_S_<6W`#JFqV^H&apr-ZH#G$rBQyI;69I76v?spBXCHg8Zp(F}POK~r@ ztM4*ld=mf87F=1YXQbS7T4;e=c;)Q&kN5fj687K zKwGbOSun`lGmE2kc-FI%Hp48Vs(hZz~m@8BGKF}99t#RJ@a{K%CCOx`oy&xHjJ$}8f|9_K_4 zHTne{Wn2xDV)_BSqP~Nl3BTk;fEX|uAuTvTQ0~U8$OHym^I)}UI1kMaG>930BF@c4 z%y<66+uoxTJ0oqI?(5lA&IhmKh+zqW*D5wAK8L<&E5q4ZHvQV?^n7b-n>POcyhl9*ywZHG-+*JKObl0K#x(Q~QZC?i^3DVs(;;Z8O=}u4ZKH zsB2v>mz&Q^s(*P-Gc;c3!}&RD)h7ccdj0hY581m<$F^zZ3dv#AtiH?8ah&2T{?F*6Q9Kx`FEK_QKgIS-H`czknWGTdk4jNNEo ztiz|C`=36UCY#6eL|XI|_ax5u=e!Xi1m)-w%NT1S^lX=XqO&?6^s#?y4m1P%{ENX# zyNZdu5^j_?zalH92e?i{udBay^T5nimR{EBiYEznqlMaPDuS z(l$|(lnt|>IDI9Dp-tffl0I6`M|m5~GF?Fb$n^CGM%#xVmR47%wH%F>mePvuN5Oep z;ZXZsW4e%N4c2Kaz15XIjf{v@FgFR$YWYv=+E$x%i#Wt-rTh)M|Kfs#-c*CzKAqSh zaX4lZdA_xBbUfB@vf;IT^88YDYfnySC=46A8+LCkaHw~nyW!277C*xl`yRPfdQ?uj z;(ehS+4!>ipD|9rYQj&Yoq4%^g@;x4#^aPLMHjY*SBa%VDDWS82EdGfluqbW&iSk} zirq=9aQjcYrt$1|+nIXCDQ``O4CBNIIwP|{UqUF%pYEf+N&49aR-%=|AR%w=;3qJP zIk7bei;?$HPL)l-iks_(o0O1sUU(idOu_L$D?H*WX(9w--@iz6z+lGHiej|Y4)aW& zvb)`6^k|~nv->)qZCs;1hn|7oxFxqlts~B~RI>fdl1*03c+PiuYe*YI=XXJ@oNzWR zmxjIe6*j=c?G`bg@w^;6_yVLhL_Hz4mQJqqai15owJw|3^r4TEQSwAG=$f=DOTHBe z1_(OjfBHCyun=iL50^_ue{qv@tnr>+wfhq-JnS} z&#TJswRrP_GJ1xCm7!N}xNR#wFW+~G#e+}$jO`@P(`5VIGMRR@?gVwCS(K#h{kg$* zQNJ{L|&+An=^_b5rSOidCv>uB|; zf18W9S7L2R8tgXE<))`KUzokJ`c*C-!hIFry7MmL>36r0d3gy~(}K`qtrsJ5>>eh^ zmpCd1;Bm?Nyho2xijoePpbv_f?Jr1E!61+i16bl&<%#VlcP+j&smnVqS~`be$-}~I zr&j`*Q7M>|RcreaZ+%;l*%&=s6ROq7mR%$|TI1G$WRc9ea*N$qINe;^dnET1=|fE) zBNRuJ1Xp`2jp=2g!Iuj~l^wehk+M(sVrs`$N8*K(3ByQrsNQE^ zY^lC_!jk=bc8cfM*)j?LsWYh`5^2jogiB&T^0`kiAmfAwlfk1YZyAaZQh?Y*5Je#7 zLkJUJK8PH^JgwL8iwIQ>E;z|x0JOA6lVi_%MTeAj8wAlRASN#b&xZJHTzq$1banT^ zW%1fUuaCL(*{X}HmD>nO#^vvJEzg*G0upG;gMpa`2}xwM^QMUZmi|K>@(Xp2=Web< z8oM-Zk6-Zl#4jw(a~>^x=pu|E?D};hg%O2(Lrr9SCJ@P>&)KB((vzK zEhIA<=!_}J&T6%J)+3ajx#T@)tv3>@EPXO4EEMr9+ccw3yd&J4B!7}`r;vJCIPfV45 zAqA{W_)jE1{Lkm+EgqHKXDWmAm);S@(cy0q6zwxjj)nI03BA<=?yLhd7;&r0Qn9Th z3_1g8Q2z35`B39AsT#TN#+e|=aH$WtAA2Qj`FpP8hHq8$K08K%VS+8i`uBQkC|raJ zUD-55<=(#iRDj19Ww>2fgK1x}sjSWAF|AtqEaCeHBy(}6Ysxrrvin0t|28jh$(P;1v`bt_rL^;rAU zd-kZ6IGJ4*_|$s;hNjTG-=PAdBX-=V*IzHDdeF<@^~C%)HN>SVGrLxQAxjRS5wGqc zHDOZ(PgVE>$H2(2FKTvg`JbkGZhs*R0cvphdw;{=6v)E#OJbxeirj9Hcr(Vf=?>xM zgyBn2o|SmhWKa+qT5j;-b(LHfwbh|#7f5+w?qC{FK|f3Tv?(Q<=l0u2#+->$EP*YE zPN0;N?PI=?deC)kz2Z}=%u~76%Y96a?>{bRj?5h$BEK&gowmzH2YinC*Koko+G1-J{ujC};k1AM!*4=pji8VvbQ2H8U8YHx)Ks43K$MIa^ zWzs8H%{8i9j}n$l^@a8B7}Lc*>Z#zTw=gede5Nf(1K1k9J9@rxP}^|R{^8ztZCwZ5 z88S;sN~_58uZuGyge@&4;l zFMAppB5G;S1Y(+{WFb-S)QO8UC++&@11yRh9-VQbUHs>V5VB|N)k1Uu#74_lCKlWz zdrN4?$F50<(cOgQM2D|-m=sL)yd%m8`3(iNuXM+`&y)snV^+f(YEuQVp=g}-qRN*d z7evKKUdZ4;Kw5E`ijhdq#tWz94>-M=Lk#ZXkNNXD&Tx9#yR}P$PD0-l;$oSi#3wl;)V5q{E@zr_&6*qzk4pENOny%mz zGLn7Qcj?vZByu%W@Q%boHX+A1n7ld1Xu$TZU8hlwWXbN?D&jfoZgRN5sf^FtQ=fc%5DK;)=b^>vs~!D# zqWEtB9F)FqNLS_BPt4E znuvwjMEF}o)Z9~hiMwH=8q!h6-&VL_K<##l-zrxv8W|g{v}vnm*E3>%=ISF4zC0Th zI6dm#&ebB$vw?axRF;#v6Ect}8B1Lp-zT~)5p4@D0qd1A28ANs+3;nvEr)6UzDe)y z>nmHUY2&tTLuOdt-JT8Gfo{|anqz&dub+re8emVFTK^>ZN!q8E;ebW__W8& zg77x_-sp3H6yRN%n);l-X%HA(HLQ<|A42st!c;u zt(JoD6#tqr*=U`AN5kz}_wyQwoy1Q)9yk{PW0pPt$$gs++#*iZK7=lwbed6;MHUOW5`9v%=8e~bIoEUrZiLeE1Iz*E@QYp&hP-IYCmCMM-7D$g z;$*$~>Bncq=JfQONt@7Un>d?Mxhu2`KW3$H)6ipN4)`Mxce~pdRp*Fhx;`haX|gQt zA%u<)7!Y&v+ZKAJ#cs5tNd!Bx-h~`Bv)q03S-e>6)%KQ6c*Y(Hb%R*_Q-Rxs#D$K? z3$nOc9!huhJBAnbDR}5qRk_%1Bt5=$*0A+s?N#2M$AuE_WBKld#C%}LPg*shQ<>fp zU>D4Z@=byB4^~UOe3g9TcDao~;tz*6Q%BB6&lsB9d%o3A#Sm0gNKBP~-F{5}NSps?h!SV~2kNXlNDz41e_x09$NV49yp<&H1{M zkM^_1Sof#{ubA_mcM8u5SPP@&a0RL7)Gt{-=oV!d$g8I?OfAbr0u9xj%olPG& zVw~?=o}L&YfBuk6j)yZT^BjXRw^F#pPF$8iikjBzYhXq#fLWP=NA!*sSL@L?+jw!? zz@pv)I=P-P!+k0ZW~^ykdfJG9y3=l;joG83%R>>}OAe7M`7avN`+Pm_b{^k;Rdt*n zvofU90V<(;o%_akY8k3g{thwAAk;<45)FcxEl#*2&tq%y9~eb(mu8sJ#oI_1R3tn> z#aU;jXebzAyj(kSiVLRC#+tv}Qd;(ljprydST{VseOCG|u##h3f|>NxzKdT{ymj{vG_w@g_X$W6dq<&%?*i2<-7xE(v#)>!efaD|r$kZ1wI(hM15>9Gb4z~9P@3A*NyKW{szxjU0&7oIJe9_ABhGzc(}9J)m}|YLXOt8}iurCA7!;Yd{%uFS9)lEB{{wPM z2qfpGO4tYtZy(*M3SxYpR0AU9`Zay)`@X!Ccew65#T-pLl5eex=VnC1_QaXl^j-h)f*(gXO-GdTCgT&CGQo_(30+K^Y%#ecTe(2uk?DLO% z&wZbVFW2WR*SqSi-}@NQm-Gc+39gj5RGok@VV3PRaQWc2Jf4jp;z{?;R2%O^&7r?# zZkFvHD0{JcG4AqBHjrJ~@`u|rNWBetVEUPNcLVmLaHEa4-P;OiDqP~{(Ls{;SJ16- z@Sv#PJY&W5WgXbtn|XzDo8(jLt!->G;=Ls_gvT7*N&;bg`^g9HhO(^L!!2UxVyEm+ zuH{qT2*~eFJKWg^aw^K$0WvxrNTudud)nq0gEbig%42moPSh{cK9yZ4&q^{X;p;~R z_XJ`>&d`w;s>K}aH<*Yjlv$VAZt^5^Rh9HL8UP8~3Ems(nv%AM*B<=X6RrDh>hu0> z^ybuqpe%be-)(tr+liqnpQVJOGfp7>M4Fw?rU}B9Lfy4lp8;;9(fXWngYQ%4EwOa< zbI;Ll<@eYbf&b+HPQYRu{9oR(i#0Y)8qBV9M$C#zjaMO^mb~<9%ZRCf@xLTe!3K?} zs7Z->aeG5=Qm--@Gp_wDnuA~41atdbk6t_|{Y=ICQ?EqTcj`(}g=BcPPv%QUOW9pi z&8*m2$vw^5%n$6MhS4If?qi$JhCgL}T~PZty@iQXF4?43EqTpJ;gD<5*fn8lQP+hz znDDpu+AMJdSWXNmCvtP8aR4O&Gaf7VsW74@aKjpm%Wt%u!@dnUld!x9YCs-Hy#cux z=VUwj7_W-%x)kujj?%O0M`8XXlV?AhR>g_WK)(WGcgZ_CcSX|fg|;^zYk@2^f9Cy!T0^@eu`)3j6lHN!PzyBZ2moZ;$W8WV1X4HZPteXpgVgWT*hSUuOh(ss z=TTH#gMn0FK7%_7}OG8 zWNRMFaN*l3(Na}&6XYmYe}$lz$W7-pi!Eow;kJ$xD>o&djZ39q@8$N3)=W}#SJaVm z6-#i?Fwozi^pM;4LLMf?6AVW#kxdRH=zjb+CjR#uKz79s{@Y``WSAcpMUqiNtS~|^ zwJ=NlNR4;iCmB)6wTz&tY`^V;V@;&4olyN0!EK=4AP~ z3zn9Hmr*%(pR+J^?eeoJBr7(DAPo?e$+ucVy9v$~U_=AF_xa`nu1CxNcM_bXRJat zW$Gr@>}Ab5da9~-@!h^dsHe|DZ}IHh<7{)+4|*WM6CW}vlF?m5R;+jFkh1*4x@NZV zE4C?ZJUYT5D#=%c-nvA9uvTFX;>Sj1*IoLKec5bEZ9QW`d9Vu0F zasv^Z8Rw>Tm&S8XoncQcBg+}_xws}Bziy=wt6I2FSXkbUUp`uO(QSTKtbqAVSlGj^OJ#Dvnkui`(sA&IBP7cnA_OHo)X(D%s^`_; z$e1gTUj>4qfS4DJXT)HRUq3`BJg82$?r~{?1a1$3KThB|z;~R4++Z9zJs_BC(9136 zsq!T3=WAXK|D`$?jGl9}THu3Qe&zO)>Dv-PPPOL?A`w$!4_wwuS}YH;H6$^Dsnz`D z?it#`6&z+_pDNz3UA_dj4?;n$e(1Ov05*9TCI!)E8>k;?V=MPczGSr+KO39H992|s zmWm7WmY8fi9up6ILL{d%4e#@6$bM;L>`Ce?1r5m-=nlLuVYg3$wknsishlamCy!TZ?1RJ5b?PG#@-z&uL% zCSadW>m-T$h!~H!)>dpArv?M{g+iCWEqAL~JZy`nLq z5`CeVuM30W)+lWg;YVu1vf7}vjGC>cI=g?d`G37i_%r(AssPXz>e4aW=s1mhZW~D^ zI}Q2u&FYlQk)b7Gb12!i{ZVqiMt)b)RA5D>q>!wkWM6UtHF+AtrM)(Mz|MmLLlT)Q%!ke6gbZG&wR|UC z({z}8Z~BKYS_^IS(OaofDgtT091{tRP6ct3So%s1$knFIs{|6M>^s@-3iZfc-YFk& z={%f;!dfLNrnkpTohS-3M&_*txO#Mr0W^}t;i3b{z9?GxWLd|syJ**Tk>!itjIs*H zx45gu49RhKvsxg=2j{#EO+OSf=iMr3ALzfyKEFSQexUvY@JtiiwVofSKJr+-gd4U> zheM~_=?yGtGQoM`p0c0B*{#eq@K;ql&q(7OW?!Eg!NYqQtgU-fg=%_fs(THOOd!U; z=H&mOUohfHUp@WP7y;H~1Q_&-@a5bj1<~F^_p@VJIUTsB)~4M@N5s2I=Q*A9kR5V{ zs^9C7q{~wXBtlod`L=Lt**PWk)+y7M10HP~B!xk(-Q!-SO$j_N!Ft)OF8=_C03e-Q zEdzh~@)8PvSEoaG%>Q$m0QP!U9SDHGk;cK-hJ0&-)I8x+2ZW+MRD=8s(KO!CPHbWYf^=Fo9s$i;3CNu?n4jygCK6+$ff^D7;XOU&JU@e)=KC6)UfTgxIp zkRA$lDe!#>S=OhP+0l|&HI6JZM^kvLV84S*0u=|od%AA|7)u0vSl8x3m#X?omf{T) zGw~)tgB!~9k>Azw$Zo08U6;+J=NFHhLQwXw@xgs#KHZ<5XD{!B44xSd2(Rv<$fe{%R=C%__wLxdlUdzCy5Ai&6oBaIJSB*^@=z)*I&?h2yo5Dpp6 zhGrIdMBFsF4MYX(JG9U-404q9p&%GaF@P+*HFsCsM5wWRAL*|uH^pbE+R}J2H~^s< z=cS#7jl`Fo8ZCI-g^c!U6cz_Y3ISdMhd6l3y;r{p(5ve`pL8}ewy%hle;mX)F{?hq7$LqyAXPXH_Zfapn%$B<`n0ZQ*TEhW$(N>##lmY(2GbRBM&>K7s}xh<|2F_w%I|C_$Y!Cy5>m-o$Xp zgn-thIR#no=93zC%vQv&dKKjO3p&lb}MRg#LO4#ne znTi?QzZf1#LSFy3!4GCk00VZ2zo}~puL5`g1pim#znOs}V^4+|OrM`^yr|z4gFG$| zRDbqF+#A_zr)?>7j@VZ51V9{M1gfBS zgwNW^%TL#9?4f@`Jaf&M$} zsqqg}BeGSzL=imT1a^vJl zqJMd0^OH)rsR}`^-m@#Ke&(TD5rH3%)QMDsmXyiblcpGpQb!RkeSV7X&|VIQh<`S1idyV_~mZ4O)Q%F^YSCDFCUzWR-B<@2H9t-1F=qx?mH*#%(jI~>OUKE?rw z`mcxA3DFelG=5GtnAlcj-aWf+w9}nrv`NePXi&zG=GzweEn%h-a%7cg9Bd?jG3)<306gs)us_>EOqo4Xy5IVU|TJ?abm z4~o3bv(B%o#zw4E0G`u(YHhL8x_Tl7BgFQx|AcMWbt&o94WOb-)z)Cn*6^FLMI!--hyEZ~pB}D2x=9 zulc;dkAyeJW)s)9)r?8F4{#QEdTjR?Bc_t;9w-|_%^Vb}Vor9jUG_QbV-keX=QC70 zno)ugSU$VKyvKDzq5J+*y?0yCNVHSfNJ#lvfw6XgfRUv&&ACOh3zV zu;pY}CoSgY2LtJ?|E!Cimh>-vKR}=RK5a)03ccpR#W~?p;*@%Qa4t#t=|^k23k02e z5Z$Bph}*-#WR~xA&Snc?I$q&X+K(QUvivTdQ?s&tK|if7)kd^?`qOAFt;6}p@_Ad@ z;w1NqE#7g<4zGR=bs96}TQE4|$)h_~(X?_YUXe&&hl0jG1PK0^ybVBhr1?BTyMOC} zTia^#syX&&RE@=1#?i@C(R7b{jCD>$b%;O<&bHEwX3T_qsn_M2`4yzkgN!-)?KM+M z`tWess+NtE9eZ`>&3o?H5Q>v6!}=TnD04|-sv~)-EMv$63fRi=*TaGDfn*SUhj9`m zf8F-&IPexiWoo%p3HP?8B5O0nt=^_oN+&Oi#Bhi{H;LyNVuUgeUPzkVo$|S~dLfnl z-BiC(tJr<3FL%$(W{#{OLVq^lTWLU-a|NCE|005f7Hbn82v_5!p0F3P#(s)vnjSM@ zu)6I$K<88yAU8(jV3^tE@)9y8e2`WkpanyO!}^ja2x>vv12$Q$Cb204Xs15g+lFh2 z$%vV*+}TH5V_S9g2f|kq^lxh@P=#0O7?9ttgiGEwuyFjvX8 z+WU=`v}N;k?>nrGg(uSzC4qtGXp@i@1L{QKfELH(MM?H?ft9DDu*N12259Y31^|u(PYvv=du9UU@gA ziq~R4Rc8*y!`3EP|G z7qxsn8X}1~eU7z^SPo9bYL2ooiuCZwmY}(42JA)&bkoR>iVUhcS0K14-mNhWa2@Yq z<;FUVF3B|qN%O>#*Qe#nFP0Dt#m5RfocV>Mw)O#z+(H%Jkj-U>$mMtotD8htYrwYs zm%kLC2K~=C4m7zCt8wuIY2j9NyebTRO?|5f%Vjj~1XMDFb<4OYqj@5p?2Qy?3IOJ{U#i!uK8Aav5DgO^IF6GYF9vR} z=I$#h%MS)7@h)iOfrOOiiI^wqbHxrUrRywJEMf>O6@1_)Vt}IB^P}a3tm`$^cBl`l zaYy9uWLWwGGO#hMaU)0UsFh>}18RY{5D=IREy}OL>{B50&8aclx=B;K5bf9>ra=WG zy)cS6PR47~@7^US6BDvO!Ry>Q+bvhasw{mdeXU^yN#U%^qk|Ge_!(1DhdrLA_`qGP z*Jw~T*#dk8UQ9nyR7(m<-a_D)nbs#pUxDpFgi4q9dwIOEj0tEfoVA4F^8~ z0JHvU9lm<-zY-xkmraw^SW=gFc)N=|OSYMm8MnwO)10bVqe7;Tsmw!CC18gHum}I{ zOeHx|EP*H8uk%vUH0#1>^btC0Dc>}Eu*tJz+bvxy8X#IXTUBuXC*09|NogajwN~yD-whtm^ z)=>AG*u!;A%#qG6s*XL4K^C~)F4pe*sgWWRZU>?Ua9^#AsJwTRUJo6+D=*SZ zY-gDYY$!hyk7#PfipV;@c?axhnEx~MaiHO!SA@iB#U#@`he+3T_3hfDYVWD+? zrrFvr{>9!aoDm$HQj$+*JigrrgW6-!W=VbLWr}b6&v%|=picOuyxbRJ8{noU+PrKM zTY*%b`!>Zti}YD!aX&q3%ZBe6F#QRoCx@#9UvPhf)dBz4Zv0-@@+Z z?$_~XkY7whl2~$BgF!Klb&?S`_6<@6u+=wT$QXKZbUzzJ_QB}uTbhqG9*i7K-9ndl z4NBf|%8{%9N$q@9tF&e48H1}#tY&`%;|CK;N$?5m98PP$Q>zk&$o2{&zTK@gdc+O5 zN8kThYUhF;RZzNeH3mPwYQX=5@NkQZQM$Ws{->Gtv5&a!&#?}fhEKE3H`#JuVeYVB zmnOYJ|0jh}y;Wk&KVrta$zDmJEg!a?MWr_qv~SA_+Y;Rwt5fw%sl_3V{P^cjzS6*e zBKHt88-8BElRxL*-|8r}NhT-oYP| zs%{%rpH^QC?1~9ya*mHp<#I1!uph?6JPZW1sz6b`R_lBKRQXWa=tr7}Y3hU+Aj*6Iz~xCE+_xA0rbiVi@LB+oWv2Wge3Zmt|J9PUkD zyi|NN(i?eBA`$7AwQx|OKeSm)Hj+H)rf({&`bWIfD-Ime00VQDiM3W0mGaH}t>;|~ zBLa|=F{9+(8JOMZ!!6sm+&d|RV&>zYP%+qbv>E4r!rEVDWC)mTYYIJ0b8op}Kxli% zA2FUAWCd2ixCElYWA8JTkaWEj^o$?VS9G3W66tTPD7o&eClZxEj0J+A2<#v zn{ycYq1lW2SakiHry6l28aIzF_9XfHJfPU8p*xF~g-P5__X!p-uGwt?g^Zpnx&k+{ z6@HkwKoJi(&71gU1xIv|8Q*6XAri6-FJj6j)q+2!$lGf2cP$lO<4nWYu7#y&d&Nu1f-I_qbTM+T{s>;68N|z%?_hZ<``7zr4>x@p7GD0 zy;6^B6ztadoF~X3iZc2v9K)3(lBh~F9Xbpnl_C(0y5eQwCES8UOb*F>jL(!4#S5bMB9}Oh>Lg$RQyYoC96V8#? zUT?%c)mRn;G)pNc*w9(G+hw!(n^;_Ph?EmK1OPPbgq)E#EOl%9AbwR~@wfDK`*)SHZr<7f*x zQsUkSxhZ}@%7kau!XXI>xa*PeK*B;cODWT`^<_63oq>!qAI>Ot&>u=X;4pE@$+n+Q zofcW=qk6G**X=gDV>~J)&fWHmxi3w*y^C7m=Ql(9{_vL^k9S)Fbx;Z!Qv*SVk~jD2P!e2chxGJ8VG=nh>p$kPP7!M>STo*< znK$c8k@j$`_&x|k0YNwWf5>WKuYfj>bR6t|7RaXe&bs*NReoY-7Rq1OSD&%12~`c$ zYn=1H-?&|uiV+dB7}L048hL@<;ReO#*OHWBj`m!lSb+4|QnvbJKXPc=f}Hlu&MwKQ zdIRfG%RgTwngk;1QAesfc5pw$LSkyNm+BZ@Zf4KRUM!IBbro60TXul8xcK=G95{d+ z{HXiP%)C(R@RBpqNZCnUd+SiM{z+E1Z+-{7U};`8nJr5{Po?dFyiwrR#KTTRW2r(5 zJhq-uzacL(&(|!i5Wm1yiEsVbL%SafKz_a+NUJ_wD-35&6xT7nTYb^-Kzabiop(3Q z0L&t%6RKr^|5k=Y4v2gSA>`2CkaMFOET!&Gt8w86(q(bwGrYzlD(#~+s4R?|+wKJ_ z)p~D-cbg_jD}!}Ho=4J|`_=Fo;Ac){&j<*ys)|hZl^IQNw#G1l>oYbwnGdHUkANB}MP3-|(nDXGlTztaHprNUE8=L1j!?V*@2! z;sz0H=39H84_#;1hBEfB<@`Ml1_qM1w^f&6qAnsEz0fv-sKMhYN3@T3<@%Xj`lx#j z_wgjd0}BkgfZM0s6Rf+1Qi&E0^;mTIHuK}Y&pmH67G3h;L%5-^{2B!Xc|>KzC()+B zQ;9OBS%R9iuVzA%(8BDz5e8%&ZC$0|z#^!`F>wQ0u+!|Ost^I$(krw}CY`(!cx%~} z{Yyq;Q=W;wgL+ctvwalZ1`i=`p~cb&Z$Hr{!K0pNnBM{ zG7c-|A|UQyI0P5KYs70^dLTaOLFV}I15q@-0RFTjQ=l@AWIssctTHEcs{RnVlByV{ zhm1f_DL3ow5p5Wa1?{c2AB(Y$0@72I2CkW@LUmz;C#>-CEiik7`a+hUOB99f^YY%A z*i|t2@Y4}HTc6@YVIO+D@WXGGFp?5-Fp~n;xcF}$GDd)Lp2^^U!3D>qJno|I0lt8 z5-#>-$2npLCXU}k2%H#!NM}HJ2O@{AjHn4zua&K>I^~fI8WQG<)p~$WEO~g>T2GOA z9i(((&gUEO#kKB7>$fV09w~dFc>U((eoVR>I*FNDa6;5Jde}#XMhC0210CZr#bvr5 zI_~?X)fC>O~eQw4`+d*n5NJ1ps3xuwd1u3 zet5y)>ws=TiGv-7To1g8*E;h6r029er|IcvKWY#4E286v?M;tw?TVNC@T^Q($?J3(TbwDV=?l$MI78n zMfzNiL?AcuPu(JbCnbChWI-q%VF>QINvd>RI@pg!p0&tkZJRUP>Fq>8wF(ull7&^6 z-u+`z5_W@`y3B_`hIF@$Iz_;qD!dOnHI)22MvX37NIdQln{RjnQ23iDB^+|x8+PZX zWxrb-Xm8RGB3AHUcfZd07#3z_MhvGUky1!7iS`!&;`CqdNnydj4K9l{K5$Zc8==M? zWd}D)Y&j1qo8^f5_&nju>t2eC!G`U0XrZUK2jpN>M+c0Lm!O{Fl@^z2Jx~gTyeD)7 z+%GVl*vpzxZD_u$nah{YJ_mtdV74Ue3Q5A*C^chlNIn-bMr*CEN(T13nCsj z3fR>7Gq5`D^8?tPG>_}luu4UT9Lz{iq)N!@0e3jT%Z$Tq1uCL&zM$x=t5GyC}CTBzADzv^CSXp?rHFj?my*P|D*b_FC0=ekQp@ z1C+HSk4XqJQ~4tx={_#XXI3Ig!oej4<1)!G;`~LEgF;@{)E@rtg|HJ1%q zJOV2?&>EHRd{MCxtLiEh9`!56Mrg_$&J2FRSJIId{P08QpX~bU*Z(@d%g6B}zY>>@ zKoJ}O+S@pgP_&Nnr4%KZZ^>foVQ-aC5VCaRBocyege zI%eii&SKrVcA;&R5hzbgkClk!^atK(vColr;DO5UC$SBKJkien?z|d9g{sGQoPJCV z`b`-9jPjioWounom4Jz?dV9{5hn1qIEm_9PHa+VHrz*!d0)D7`SNtPPd=t})E$+Cp z?4F>Ozfw4?IHWj&zAN%9kw$nsB`$6IsZv)1?WCG(Cq3g?(E))DKSF6O|J4S2<>Ok* z1jzWiq7Xt(NfJIkTBfg9uAxW6`R_uM!yj|%w?2y0^SX;18ByP*UNPL&6PL&A_^)&d zRq~a7CI!y`VccPi?}{*h?yISe&@&H6jtoe;|3d%=KB;}zr!Cv4;45B!WDZsmKfs!6 zf>A?RHm&fH*BT`=2`a)$legm4Y?I`x-3JVhn2@TfT@=(JkwRrADXUZKD6?5w>i{xO z5)U)M8)4Aej8f-)A0}mu9Ca>S@=Qj`iHRj_)nA6@f3oS%3tRvPh6>0n0}AGRjGs*P zuh+QOuf`b;kS{a%>dc;(Ww|}O?`xF&Qg^(eErnB1*o^yC-j~{ny5yZ)UZ<4Nu@8PP zlUBVBeB*5O`P%Wb%Qg_PPAu^eqO>w&aV7DpwWiK78r|4ag4Q({@M&hy-Z#G^`Aa6d zmVnFMGvC;s3~iOxYK^vrXHBeqmLE3hD>*NazUM*qAFJkiRF6yM;_@~q(1bwPt{81Y zn$Akh87S0rKlVO+7_R4Z1AJFP5vtg$oAXZl^WaDO*Z07kH^Gt1{>e_mETyvOabF`O zTl)Y^E$@E91Qn?cu^dOJR<171b-v>_e|$IY`)ta>B25|U|5?hZY+k-PY|x8tF$djV zz~Xpv>AsR$k)TNo7Qg?2+L)Ahh)|B5gSjE>XCOW5t821G=bX%p`o2|3 zDGR>O*#|(d#(O;2LKmc!Bv31T$gA34W97(-Bp4l;ELQ2h=T-( zP@(EgkVI7XT2@Z&cFV$6d3*EfvGWjt)z$%j+L8ZY*2}(2JXFqv-lfX;MXLGK+P>t% z8{u{?axe>X$Xn0EvOFr4jj!1T8oa~b7=Vm@@`uesYW1($3Id_RMnbV|E_dK&`P}!j zriOB%AaCx10l%<=aWU-jNi5pI6&{qSc6OqAwCZpoaw}o|HC~? zKBymVRrj$%o_fmb8X7cTZS1+l`cB8@j;f{uXHa9x9Mg1BtZ=}_nD}x~NXB8Q0y|$V zF#H%1`J71x98}ss#*RjqAx?r4KIg(n_qKQzgwI@Mc24--GvO3{46THM>O}N&31%dU zzkvCzrhXQ4QQ6$U&US&k9Nw?CxoV%k(K_NjRmM!JV2>KUY~p;$0{_>!nY}l;uu$F4 zA$PjHR&=FYx!+GZ_w|nrII2&S-_(8tIa@ZfY5o3L%_H71Ox&U}8-ZNat+n~eg3K^44Zf2oJXcPMF39f&G!UK~ z3(|k9&)+YB5f11%zyNwY6=g84;XfUa088+5pd79tpyLDxkF^DzGh2sgp{L=U76za| zo;71kwtJer0~S)du+6;sZwg?GCPeA6<(okoAFvmbW~IY}o1Lr)wJc=p#TJ@`u-Pm~ zVlyZD7%JqZ0qxJlM)+y#R%I-3MQJJ@)6=IN@E_%5GEHyB7L@rImw!}W6kZqGwnhYU z)SYcU(0srucd5pYnHldF_mZtHT(=HtQS4+vv(}}dOQJ!Sg(q&hA-B}2TSJ3VSXqY34 z9+Z&gff8okG_-Gm!prT}lQl`6<$^gSmESkcyj4T+yeTzI>sQsJKxmCPtT^3;Wxfuy zw8MZ3mi&xnQwb-JQ7?u9!svA1_w+Kec9XLc47d3yXbrQaQl=0MbMo`HHm_0RSV{9Y zsf+^8zt_;tDcndwb=am2u}%MN9lm1fKMC&&N9GDU9`uJM&>jAsqze=bl#*1|5Rkqq z{o29!XBcl{=k)nyi@YRp?x?i99BGERY1(?;$FUEKs+H58>U;39v&%q~2Cqh8A#!eL z(tbX>{sxC%wX(0AoYA(av*P{x$G7?GCTkIg^_y@P7o=%&eP~{mA81ni@VL20ha)s! zqkqIvr`p?-xHio(jIT~`J;U>w%#$$%5%T^IA|0~g_WiMu_6jdf_z0effv42fJ!N%y zRL}Z{ZmJ=nZJ6VAc9F2qncmov;>uz7wMhtr9I0;-Id}uckZdaZv8b7`ma*tv9~&z& zvhHzj#**q()2x(h*$DOijq#X~!uUbTc9CntlhOPH2K)*G2y-pft?fvoB3Qn#LJyi@m&LrpaYij4s(`}Easmm~`8#^?uk?$xxhx_`a6JKx;m zg3w4DsB5>bSD(7L(4;UQoA(+TfZeq?_iuIYVC(4#{f?crg@41in!wAt4F`F+*j%gy z>pT)spO4S^Rjhqmw(qnJ(TnsR9%$P2A0FP~kC%*+{n(cv<6xMQpGtm`%J>HV%_v$P zgc2NY;VOi%a)@)wa0xY$$JK7_?n%!1SQL?bkza=2f`%)W(ct6 zbH;Ze)xkJ`UlDNlMc0Y9(oasijwQu}BYhMEt3CIjz9+i;AD|r}sQQ6`-3B+Wxo!~@ z6y-44BUw%7F=;8V*;FS+gd#F+2UoZ_a}hjsud3erRBpX7MivWQ=~}|(XdU(AsZen} zXB`ph!C01BIs}@wD864;TS0NVO+>AkyF8A{R4m`7aWoCecp874Ap)q^25aNQXQP-b z*}_`4KOOA}PR%lS+WxA zfn;xG3B)Rda`E&QnVxrJwAj!C9(5s>8-}r(b``9nY^*Po3&=xq&G{Mxo&(wHyV5n? z!B$$??;XV(R&58YqV$`Lq+n%pdJD{%C4LEqv6P50;YC(Ae(?ZdSC`Sr=&a&og7@os zGHgkbC7aLp+^>eHR`dh2JmYTd)Yygskrt{>O(tl00HR~Wi1mv;<$K>`<&=nw+H2A)vNJ2vt^!3|Cz|!gA-N1Nu*S^8_@G6m;T);{@d{?mK0AzTILF)0C-774rcsa=34iC!NDJpU6{C; z*$_sGw?K1DBFHks{gV6f#-*9qP@~kVzBv~^U!yWV--~k}`W98$8iLfIp33y^F^~ru zoP`XZmq*!mP3GtqUsB|F1TuG<@D`%Qa-NKJqHA5&j1GJyAB@g6e+FcCLM~VI1gy5l z-+%Vp)Lcy?$62Feq7kdW`*_BWQ$_04R8k&qSJ^3`XA_4jEpK$pqa^Rp*)%!_O6)~! z|FACWd)RR~Bw_R&)3np0q;@`|+@=y5?`;CMqD=5hA_X&s;A+Ykf(@@*k!tDbz>>+O zOGdAKT)6#Z@{X2_Ar>_Cc9uUm$DmHGj(bfF{yJViUw|#%!5<#_fd@$b_c$wLvSei> zUU-z-bj+S~Nm+7}+JawZ}9KY;WcXlf-TTeLZ2q5k214n|%Uo zcpMz9g8x~yf4}(U)>2kP3V``u4Gv}?OW1GHyaVaQ2Fli~7x=w+c38mF#Ve@QTkb(Y zXv)NnXTwUEmc%qEuW65bktPq#TiZ5r^S$^n+Ah&#;ebOb1K#p!bB3*t#`(M?(HLY8 z=}~jJ*MCDQ!zr6~Cy-VxPw>-3@hRY)(F(xY*?E{6k-&`-9HrG7uVO3;mSJI4liGe>PS{8HNu<)M#g#)N z+3A~(=PI;ET5Q%OcV3~s%Sa4_c7GAGZXnAvS!Rq5Ff2qTmzDf`nUgwX(PrJ`}Y^0wOUsl^GAQ2Ps0>nSpwF7qSc~!#A(n z%4)PCrYvTT+{3@1QnTn7o;M_anzfL)f&4HlAQVY;5IW&hsjra?6>)8PGa&+5;Hwe~ z&zy-G%gmyV%NiZ&di_;DASVZKSyn_z z1-~lt&pik(+VHFpb$M;m1%la=y^=N=-d(}E0rcA5_$PuUv2#f(cGh~mCVC@Y6x%;$cbmX+dB;r`=Z%7SxzPg~-uKZs;;|6)&d zDP?su)8yvew&pg|Sq!@DoXLi1+Ni;kU!b*m=iR%ITrhJP+foWqyK z9_V8mQIWdF>N^~lzIE_Ao#{KoBuDxYONFn>ntUpmXqm_vgtOP5x47&J-N9QU8-*nR+S6+3U)xH6gIPZdDxbt*dV-p4s)Pgaa)bj?TIE+2#nac_ z1nthRWoANG=57{FOjP*OH+ngE?;fmgj%R&tOCFz@)AW_9;%5^0QnZmt>N}=@bwh^7n?~6XK>ytMzzY9@frtyNw4yv&8 zD08%irn?%E8^Z}|TOzG>iU6Lz=C^Jf)lBo66%+FdKqa;fz)bQU0J4Dzxi7ViRZ$HP zb!>5SG_n5>h+LDE%E7C-6Wv>u=x}ngXGka0Z|>uCOsFJz{cE>UZBR^snQ)aoqWqa< z-TAocM_Q?Z$*xD`u*xDwop>@ZFkQYl2MHB&LqrC;`d7JS@>28@`@~MwFDv zpJ&bZ3=?{>6Y(4*0txH){$$}_zx}r}JE#}9yKeQH>j0i#5uoq;1y^#+P%pFCgN*`m zv|M?aLL-AWwzQ8*U&&yh+OalU90aa2^DLahsHk&L@>5~&Q^hwJmE&vP|xoSrbArXRN@lvO-&`NEO#Ft8(YTcw!*WYj4#)W)w8_GiC%0% zGbp3f>U$5}md}5<2L$NRx5Cr4yMT;pPqMek{%*Yx@oj82L&w7_C)iz!;BjTL+Y~{Eh6fKlF;2mNf=G{Z`JZWtnJXLf0YBR__+rh6bBiMmYdB-G zw>yq5_eV>WD{k(dP4mhQB6O2-q}dV*?-9TEdHfc`$y{{A@mlt?PM?Nlccm{(d7t5V zJD0|@=?Gmb9HNr$yVc_hnj52aet0e_9Y{5pZr)@~Y82G{fHBP~?periD?8Va<(Ic4 zTH}eseQ;K}$v!93UEgm)S!zxnCSAg38v)-$$y~v1Dv5}EIBXlM|7v?D;N+-Q+gf17 zG>3#A+wyY+v#_YXI$Ip46wy;yAQGj_lwKn~kZVC{1)t8t6@{q#2y-L-Buv>ESiTg;IZ zYvUgPf64Wfe&KZjD5z}uL+#Ic#=m-DYRe=8$4a}#8ZNWPYI;T+E@P%@dd5XBo!V=< zM$ZBVhF)^2ppQgu2khijetRKtHXK@ADOf{;=#zAEWNIY-J21*FY@t}QLj3S%IbMk zj4GDwIm$9xm%!^f#8%ZfjFDCQUF24%XFD}KLytCyDj91blOAqPL8f~0y3aQ9Pq@0h#oM2U6t~ZuQfBLHft6pd;0gPA?5N;vJDXvMgS$Uqd0DK6$U<28$a*StoTR zQ>iCwI^WX0MhuakX&Ut3V)*2?(hQ)N_r+lw-ri^WIXsIOuN zf$*3&wvI;ok%t{V2SMJG-eawmx!D}$?x0gO_mj2NidmTHY3x66RBNxY6J@WgH=LG~ zQ`qANgPDT~@q>Ty18}L1_|2IAkKKr%Mw zHm?2%8(m^T$td>-wFD(b-MBY@1UQqAt9==Lzr;zgK^v>cA6K?!5omq=59qCt>u(?P zL_OPRwa?=;438?AEod`J6$kYx-x}}QWbleZmo|LijM&FXhH8e7VJV@Cz`6(*h>|42DJiq!5Az*R z(XSpXwR0kGtEtSg`cTSA@`%|lV=3)1KVX3Z7Q+vcL_8$2orgUA#dcP=pJOvlZYmB= z0H#X^OWPsUEJ)3!iIaF81!7N4#&pHn|hC-q1)5QlZDueu3rOyAP1$>=qljTLZYt+kG3 zZ_M&NC;Y}XdL6)Q`xpJ`JaAZcF|~fVH@cAeN#70+@GW3?_gApRud*EBMZmZtO=6dF zNM(P_o|Kf#FpQ{K})A@A$H#P*plam0ex3F0+hm{BXHvwXVV2pH#K zsXgg-s=;NAT*~XMla^@lp?t`!rTO5TF{Er`Duz0-V4^lnZ_vYVPDyIyxAl;~R_mBe83@HpDBlw<$+kMXa`@XaHd;hT(vt}{tequdw$91XFd*+Q@lrLdb zrK!)~mp7!iZ78aMNSCh3Xxy{n7BfMYOuetb`}=m_{1>Pg0b6}djN@o!_I50NK~5~e zi)$Ov-$Ebv8_*k1E&0B)Z#rY%fKuFE9X*}x)cdGZXhfqQV_(ulO|{a*2@uR^PJD+R zpcPaH!X%^^^rtj?i7^|3pNOx zUWl?3Zk~V2Iy=i!@#iLiO;sSaomZ{`0>USET#S>ixJT09?1g*~I)_59@K5gy6{;VD zCpY{l_kL+d)?UUUa+!|4y?`Z>2g|ymol4J918Y$|zwLp46&;5da42fs!3q4kCjR}5 zeb0I8mh+N|$aLhInLuY=8cKR1k|dk5vv2Z#txZu=QyT6B-YEV5_alE&P9)UQ{64i} ztR{bmt%KeU0i(}vN6?@9{t(QvNm_`a8Xi!>^fsl~*%%Xu8oIXCCATtod!!l@yFc80 zsU=NZ`a(+@n+UHUHb{y-PBEN~J}xgzuk(RkrwMp)4f_Q_uH(jYaUoNkLY7o}L-L|3 zX;&yIg$&(It0rPJvyp2-T+PslZu{dmI*zMzdis`wU3*l#M}jiD@rG2dq_sWwm!Iq% zWKe@8cZO!tF&P<=ljxu4A$$9c#uFSwYD$7nG$VRvH)e~rMGgl83KTi~UvsqhE~nUh z&1&s#GET*awJ^Cjau>Hp9zl$dKL#xC{n&rU*-vrn&dNJ%2A!WzYR2Z8T6a*mz`E+c zBu;@HSZw{*g@67N$m1qf0AWjm;s7&2EMClijp2XD7H&s_(Q2vZ%gUJ7Scc#JVjsDN z>i8qL>^Q$|=>W<4eLsiI8n)`{H~_|B+Z2EC%(y?!>So24D--g54G5YMWiu!?1EOlMA-wLx50Gj_~K zr~xZm97p?GPJok>kZH%1`{ZQljrGZbQx0UL@rL3~Bbc9`ZY|BEhQUv_B(sGXPW=Ew z=r>>S7|3p`Y@YVy)qMhP{dC*PhAv6FQ}4*`UEd-Kg_B>m71uH46t*f zLa}7zk%J}wkAdm8mg3Tpyv*+L@5otGKF!lYe7R^mWbgi6^1mwpz?J%-b7I9G};PzKEVMGbo=nA9mDV8U4^! zB&RwOB`U*rJfpHVrt*Cff6h^lnzA_k4V>DflA<@aJgK*w?{@erpTrxV=0y#9#Nydb z09%mK@$3n!M88Dgfp=n@LAZ}1KxNDr;yWNhYlTZbJjkDJ77CAH&9+@gRPl4bz8jvo z8`{D#T==4t6v{(OX-i9UMLm4NFM+{8Yhd_t##~5L@AK{5=}TkPwC!LcOG_vD!lbZt zZN+uL^(Ar1*8_=bZg%d8rKE}_wG5^V4#We<2{G95WrjAi_~YN@|NDGRi}Fu6zSsBQ zP#tZTGsNZLMW{&;uxWD3>*7Z^k`v;Buqa)P?Pg07DkHSwP%?CaMRy+a{ zI(5Nx*%v{vFzi?+X%rs5yXr9c^*ZOT;M*HL+-SAr^M^{X?7Iftudwg10zuk;1sDML zU@=MM1OZW|alqdie#fqw1!<%}aA`THz=Qc0~APt_eCViYK18gVwDVy_!w(Y+hb!iG zBqAx@LbQq3AL7-t;^e?k*AlfSyug$#DXyCSwW>a{yVAqJ-W}DCc3Ex4)T?rfnF2-s zKZHIONOJ;e{hx$1gU?PQOCD~NL?Ei8rSrmvPUAcfPpEP@d9_q{R8UrS`4xZw6#<`^rxwEOsK)htQKKs7)g9 zP=Jl%`qAE9m*bmP=M%q@KP#7VfNl&GoUj8duR&74cQ_<>aQc38CjI7X2eC=M7AZ+0 zF8u-m@^sZ6_&hTec%Y#HrhPu%V&!NoxIall+%TFtsUc=EOf*5#qdD;bPD#RGV`VLp zJFoiE5zbgIv=*N^^i5-bi%0l|nWS&%n;k7 z<+xa1Yyg(Og;NoESbULIqowbZxKDx~GM16)P{2_H1tt2EXnQRF5a(-Ln92jo=n1Aq z6z+0+M=g0Rwfs2GYBwKX4}V#z9UPt-G3{U-_S9UNJxEhXMn+~h&qSlcl8FZ>_ZpA@S6i~S~D@qdO zi8ExMj?0mQ`v|qW%B2d+2Y|dg5xZ|{)Fvz?u4d{xBq9PA!lV*c{y1~12tey?1)lMT zP&vA3(w77?}FLzhG zs_T7{t?Vs~D}QUoeZ%?@Z>M+5xgU) zOH1_)krBZ1Dmrm+`p2T3F}KywS4`7?tp~45hjU%;SpQx7jIsate(-A2h#`kLEVc9% z9h||aSItV9iw<*F$xNM-gIy1!h++83(itfqe&oQSzg<(0FC}~V&D-lwfmq0 z2De|Ut+9t)Pc%7XKs2uuaKla6TMP#fPu2H>vabq&&(|W2CK^#G{xY!o<(rO9dp!3>_i+BrDiSZ_mOY87S!|&Nia_2H>?lu)-2Q>Q>q7PT?=1 zVLZG|oNQ4eBdnQ&Ja*?+kWkYIBDnDx!+->ck82l#2kc}!Am2iq!(>`F2*Z?1J~9SB zn=MzG*Y31<*K+R`c}aKI0pI+itanr|YcXlzZ)A&a=NbwEw8)UX1Br%n-5%|3#L2(` z*g4ICE~(r`u4Ze0(O}}Q5&%bF7Qtc!=HfUhpj|-N!0~^It)`Klb(1s^x2W{Cv>sEg zw@*;~*JDUTjI7^>9WAXCJ(9|>1KU0{gr*?{ar656{phq^n1HLx)~Dj2X%^b zIcenWDhk0+z;Uk>ho>g%Hx9LdRulNBTT+PI&n*}IR^r-$sG%VxF`9N+*^V(r{-C^e zNYLk;07FZiG3N~*f+m1R9;N%LwmnMnt+hG1)MKt zv-uy8-WbDzg1wgcFy|6rdS$NnrMShjs4Uu;Hl84H*NoN9a?DnvVlZfIwsh-zJ6~w7 zo~^V(IJad3`I{929E?guVyj%0o;nVpmV$DgybK!$J3Cm-Z0fCUIlyjLr4Ys0$I8KP z$=QHImX$bDe>qdtvQqx+vF)q#QSi>i53c*eZzC%wPD@Y9l(R2i*eBuA5hLcB&*PiT z-DQW|@{z$w@CU3JZDqbNjK(ZCaWGGV7YD3?D@_y4UCX%~7#%_{fwN1Z%gKO;7fb^6!F z@8)x=5wIup{iIglpIhlKhH2ndg+9LtPp` z3bU%Hh`S{bilanBpAhzTtU`aS5^~5NcX5@R2PV(2ICic&>hC0M}&%Tcz8^=BY>a`AH}!blFsOqps)xMvh?)&Kxcn|DQc zfzdoixp$oRfCZ?96&&+)yWX`xm8N*p_2xN8TIPvCoRT6n$!NZRp8o**NlF)TQzM;=9Zr}6EkWo+DYFh5 z?JE5}RDpcJoqmTU2TL&n^4GgZU;zH@*TW$;FNInp)LwQgT3@u+F5(z;hMk1^*IN&*lr zAgX&DqUi%)7$kM$WWAF*7VB`~Ff1D&+BA6knG8Fh(@gO*Kx8K`0bn^p2>6uZ`})a4 z-&9kJzL!wD!EAd=ATHlsjHcF3fGYM(&F&&5XQ>IX&%4X1R=9N%<2LwXPOPpX_z@up z0A(VU2AxU{3VjFB2N7-Qo7C(eKc0F77#kfrI+QhRA>7x$u)R}x^Ua5j<;|*hmQ}D^ zqLD%#cr&atOxCox8f>U3hcNnhQt(p)**RVLtXI)?sopEeU&N6y@UN=)$Ky>FrigD~ z3ZaNd83n#PZDOBTSO=bRYrT9rW~gX@N~0DfU%gsonJruV?mlI@&e>6H!ERz*VOd72 zd5IltLATD8-ykeB$eJU3TC;x0a}-1@IKCzXhclOf>c1GM~&7D$MTqjZ-`)>4D^eMvC3)NkdnS-0B7 z2WPUspDi4F%+a}#(x-+W3lM0As+@^bz})JSUY$Y)A|f`lN?3W22Au{%{8sv;ChF1P z`-$&U{i(WZ&>=1YO7o__%$$2wmB?q#dS{E#H~SsEiKX@Sys4=i2H%3Bzt?a@Jql33 zp(NfLNqPqw%z_hs;3k1X=` z@6%w{$f$Jb*ZD2Cw7J-5uiAe+@oqM5+PJj2r}_#f=yxd?G1hy5L_}oS9Qrq6JPU{S zY%iB8_#Zx>u#2o0GR$I$@p@z9Xm`t$j^KB6qP)p){L zupzT7zST%$$)mkapijjWha$WOY#?aukc7BeEgcPpHkz(vsA`MoMKH647O*Cl!^xzw z%`ud2cv)6T{%lXb{m}iQxco)rC!u3E@ISd!!*-vFtSIeY0Q zY0}2rA832BhK;4czUAzr)Ahy{KTRiI60)ut5*z-$He+FfQ}6owmtc#PS8;E<8tDs) zx5*5iMP~+|2-XN>G=C+cWuaaXGEG&qgQ`gjEF8_Km+vgBHDqQ?4wIhVWJ#UIZ>q>x zUsBH9w7&ICKRtXnS|(P@{dj%(y}jGBN(xJQ%GIGw=5_$U3cv>bNhY{H)0;Qr?>dJf zhp*{jq-r2)nnM@n-Q*iq_L6~VM@n*7<&)%Rh@ZxzzP_I_>y{FuA7npEhWob5^^8*i z;fvRDQ*L&1Pl}D#V|$g(YW@cr7Oz*|#+%e@yfD&n;-f46LoeFra&tCstV_lrb=eXv zc;4e|So`^OA~nK+?qXQs)5fRP1yi*4YX6!LY&bMm4&vt!uz&Fhp~F8Q`E$5UXX`=t zzHfz{fuS+@%7(`511 zIL*?*a+9=gseMLUH$vUX+U~{Zd;>*fvnoSq3=E&%knM)!?qhG9!KT-ce|3?|@kj5>7i8G_aWQ1Vg z?`s7G1>FN*8^foSZZL7g(`i{ni%bq-O)JTp4ilnojo63fG(x`617nAsQ*T?*hxWwo zIaKGeMTK7b67@l={e|b}qci=jPt2#S!*W^=}tEWFgi}` zUfCPf5jVG6cetWMD4tK-pt`!Qs7XHXhI~kuAnJiPlXi3H;A?fT)N5Qu8>LO^wt1k6 z3dBiOx*gUvjOJVM#^14p=FY#zRFY4Kkh>`^C4REKICSzspW7H@u4$k6G-o%hT_Q&j zMa(FbGQ+G)gY$+QpiUlWW+b!tisz~;Rw)qwDj$oM?O11&09F34f~R_` z;(PR>@LdJKSB!;|L}JJ_9-4wqISz-j5ReWVwZkB}yLv~FKApJu$TAP__JWmNI|amL z&r{|JaD}Yfd5k`DCFuf!u;ZC&o#P>CVwOkxY#oxtzI=UBqa%p1n*Ax3^2}Z9FFM`{ z`nwuZf0V&aY_~aXKSX8ge!BuDS3vI29}6_O>GNr4sgQT2<`Z#6TYl0`5Tk4*d;CSB zc(d^0l{CzXY>#!AoJEr{_MUwY2y1N=@rkZ^nL;T(uRY7&tFV9gr`_D;!musX5LMT{0zgUW1G&45z!Xc#1g&*_YE460XI z!I4>sNpj&ZpDx>ZiVvHs~m`cQzQy)0c-U9y^3`X+s_hW7)T zD6LjFE5LiKE+P^gadJFS*EI})%BEsN*+?>i()iR0w za-K1%o^SAq$h9MonIZoaim*fp1LzUj^UN#*%*Bsl!36B1qeM?$&Fx8Db7KNNKOoi2 zIP&`yxBbBd?DMsLgffUB4+A_M*M61{WF56%i>U1RhVos)c5zq3x86H4Az)L{Wjhd_X%Pl)LtfKSy2bsTm2C-?6)VUBL+5$*gS!vx+lY)1)CC z%gcp(@R8yBS|+&%(&`FdhjROvMpnkECfTyebf3*gPQqcAY9I1b`eAfTT^y<>^Kicq zWw^ML$ex6f#-5CAn#JyT5)!uSLMc+4)O|D}B^KP=6p_+37sJ8l+{;3(`v@4NVschn z)vPbhDd7$V#x;J+b*(P$a6W5vtsa0;?1oHgudl2~IBj!mt7I|T-73DWCy)&D63ct< z*RO-oS6^?dk+*GoH{Ku3__#2t!m3u#Bh$n^6dnpzCKW#9`YD&{XmhB!Z5*<_`p_(? zv(4$Of?v?GN@1ICsIrzV z`o~X~m@&UL7Sx5W;QriozRbT0`Bs1LYj)j5s)EvLh1;pnN7!F;>L3zx1(DFWgC)mDBZ&QRX~I+;;mo6t^9{lwTA#CJ zOBs(KqZ;wTBuV9kVZ1CQ4bv{;_RNkqxU0C@K!JeO`VNpu4#JiX-)NQG(mMFgam`5r zz!4BxyvZAP0na@FBg!a>hgrrtC|LY-OY;rY`jzw(GES}t%#Efy5>gl3V~kno$o8Ye8bMDvWu(6%VyChh>hL$A|}aq!mgzN z6$u0{>?Wi3$7h*EHigyN2+s(jXDSRMq52MW?S&>95WL9#=%6&$`5BjG+KvN9I}g*` zZ7nV78cNfiVI2ej+0DN%u_}r{FP@BYlho4;ApzX;OnI#en;9iqCS^Fx-Qc8!H}p*g zIJekF$^UV_ig$H7)G^BEW5!hc>_XvG`Anqg*SNiQ&YiWf6LFIh9NqAJnj4fVg#mMD zy6KJn$(;xwb@xoKmp7K(ju1g7DO_Q2JE8Cq*VGZUyT)kfA%`K_ zAqg#XRN&*FMAsD2O=Jw&_vp3zMQ!zCxAQ+Bsr4<%U*g#x;G_L24^cczdCN-I2Izkk z-mTumPh)~Gn=D=fhusF91q%la)+C-u%li5^-(U%YeQ=|3UXqGVfEg9$JH3P(R{h{k z#zvX1;CXnb&J?t1E+Ws*biPZM-}*eUl`H<~QtT9ir;-llG_L?0f3yFlMx3c9%rGkj zI-1vFFhc@<{Su9+aLd$9H_~r^VrV1U^jo{@?uEw?V0rZGC#up6joFj}E@Khg6|fVU zuO?$cu&hs-sal8>?BmX8?<*dL#l_32(Q@5ijZS#n?WoZJeoiYAf*_kqoMjfhm>JnN zrw4%$pSaG9bTGFc8XjiPZKTh@3>?T)RieQwJ{v~Kw?6GUZ~iQpjd-h~M7GojNT%;IbM_-zuY1Q6uQd zhrHhmsRdDnyEm(RxG8-IwSleKC!&wW;y{v5eIZ{%xoQ*1$N8-D$~G1gWB_!wsdGHI z=kn+H+D|HntUvn`fOu#HfCD0!y~0{N3W#^URvdt$_Zc+H%fYu{dd?(NGDidz{bFi$ zFL)>sqyVbnRY;hMarcYoyqUU&dhA#F3Ut%q!mIkYSu{&*=MwXSPL@dsHaIYJf9_SA zr1I+kI@i%zdcZHt624=?K5J5($+OMYs6St>EP_ANGrp;#1wbaKZ^M#t$YNhUSOqbj z;83HI=(o1a1Sbt76bo0(k-K-Ft}o-;6wzu`3D)pg;k%3snoZ3_p*&57j*1D5(hZss z8Rd6#D!TEz3hZs&vE+2=))diMO zQ6udG{9eda$!l1G{)wtv#7xE>x1Ic{^Q3=kT^2^&R{P$<$a3AKaBk{%uV}n(pZTS; zy7BZ4c>GCg#xMQPr~euI@-ZS{Y0@ZR&X!7*#6bBM=C%0b=!6jRW}%a`^GrV-B^r zr7E#KRnMu4)27leZ+ML=q6Ma+@pNu}Z5e8j)dXlmoCe#nKTHlV_)HB`Xae^4LQ=(@z1xly?eEBxI=--^ z0$>)h%+JeG+*-ujG9ws@)%7OJo`?<7@;0V+Y?q&NDXo5MRI9d=CRf@jB(3gp?_`t`WgYsE&lwGlMA`TF(40OHxabP!iX{Ga!l~5hl(cDm z+&8eU^bmh8vn=%)kk!ikh%j3|8@Es*Gm+EClG!vuW}3^=-$7u$;k3bG;eIq+`?}27 zkAz$T4A-yVmFrhRpSFMa{apA#JNR}FR`H8M0d>sxobkdNGkYTWQt&a4eoCj!vCytD z0dft|o2He9A|Vf6xne!mSb(njmX%{f7T2hsfOogrm9l14O15eWF0)nC3pee`P54nE zt8>u3rj2?Ml&DD2;?YVAYG&o@2K}`P|033M{p0{OA2P97D8+awW01Dhrh?B%oibv^ zbh@Q}Dp)J#>DwON>O7Vn7M-xU!|cqmeSH{n$hFz8MQ7(on}t#z3T;a7Mp})4i_5C= zr;a&PI5bIu!iVRx8Y&U;Bs;ZqvbJLpa1TGP4p)Z?nHiE@TPv^5+(Tuf_S*EWN`@7bnC>6%-fboJqty&A*{N#e0mJc4sdQX)4J0+)vAidOoJ0z!JXdO~+K_Xcs<3 zzF|9;gBLkbeb+Uv`fWLtbVCaEY)%~h2WKm$kQ((e_jjOXfqs8O%Yn+raunsWvenNy zTfn2l>$TkXJ}yV&=}!9&gquC8ezsJhfHyD@p{T%aGv^1ehpf)G4BwQ?;0P@*P251A zOmnrxaND6ae!nep5kI_lHnJ#|R=uwrdXYbNv(+};)t)SWM4??WC3W9ed)4F+`klC< zxn7v6)O0O0UJ5&fss`{DR@C*I7;xu01^6_e5bagj$KdGGvaM|$u)*fVTBB3+*7p1_ z;k;Il(*bq8I_LI!=wVxuev*s6g;8=_huad_58Z8=dE>ETVcuQoM{>_ zJQ-^3L)BB-TWwQqDv$Rg2Nm5%O_$Q)Q|)bc3h4@O5}(Ea<{`a^z4HRVH4v|{#M9Na zg@8IiQ6jK~5oG@oH;1HleG}OzlzCJH#xepX5=qJEE>YR_(jd&%&N+TW7j~wI=nYM9p9%3NUo~0j`V+!)kN~Qnm0zk=-26IpX4!5hztV(ow07c%}+Dp zH05>A#EV~r(H2*!-a+$PKG?>cQSnARC_Jay4VTTVIR+>_GJ5hoR26Ks*ZU}#x>^J? zcS^tgnWwzQy?=7I{u-s3PKpo;@7GS!lqj3|Hsh~~PY|Fds+T|-Yd&Ox6BM^f7q=^? z9Qa+}Ml?mJE@u>K)rat@IhswX;8^9TKN81$sLFz)1`fPW@yfpWo}9z>NZgSA1BFcu z0Jr79=$**Yqfow3;p9mjcSgSz@&OA6;+hlL3>_;QT?5(jo;B+go)%#ncmAh|d^t6t z2@PgFRKbGS#lECj=46_xgWrCN_ul$7c9sH<-?AImH&C%lGj|_B7g4p13R`S%UH2<2 z1>1I^Oo@i>pBZWtRV}^`A2nlMgWb}&4T1u-6mC@(8;mh z_^Z*I@6HaMWO*KaYFi(2(TA+>Hu`OxI(cPp9ZvpmYbZkAQvTi3|Dj_6gC|ymC{eF= zu;b>CJLwN_nas;)kHPhp7(2u~kNgS1=%&feq@}_u_EpoQO$UZ#3&~?1Vd1y+UTROs z5OmnEU3a2L$Yx)-NjAJBaiWP=#!G$@{zYaJtjMiD-}Y!T1^O0n>#D{pS+M!qn1yqV zTKJ@iuGbCn-%hQX_GQ#JyY@X?3xQzmuYjxG{9yz=@Cobo6XXbIRawt_8|^0blVb~q zJLfmY&9eeB^0kx)NqVaES>G#%w+~B35P`aH7?k363?oK<0{m^*^_MMk z7u4H+{$7`~NwBTBz0LkJtLV*1+%J=MhCaGwn|4b@%miaSc=9+D-LU{ZroH8~DgO9- zfv4-c?|23hW2JEuOLf#0Sl&3>ylZ_)jb*`om&+DT9v8{?T%Z=56GGT1Ax{r54b3Wl zIWWT;vM=Wx=yV@6dZQv?$>#>$yd_b?+xsX@Z@xvVAziQ&UtPDA&$WNf+c9*=!)Xjd zy2XMmF@XML_uU_{5Lz^CHo>s)vImpp@rlK#w;Ks*&2{$WYmI zgXHVy=;MVsjE~ zRwiH3R$!MLG0sy?su-3nHiBiCtccOu(qbkt;B^s=lo_^Uq1N}APp;8#Y)Evd)M=sJ zRShz&*(DFlkWjfQAyMiYQn4wNyj^m;{P3;G7RnyP~uMiZw4jvh$;Cput zi5EE-H2%`?c831uYvF@msVD7tzc*+&G(Y7es^{qvt!%qlq=aQoW;5?}JRtQ9X@WZ6 z>WjkWQ`jM!l!9)~*_YZVEGJ%+(4xeN=T}=Hlux@V4BwBO>a^j%0zK}%hq%1*Xg7*c zRV@|s*@w{4*(|8ebRtIMx7Q?=+SPY2(#}izgHL!*`FmT78Joe1QoNSzWSP#j%{Y$!e$RFM>PnDzepC&y?W#6O?l&`=!HzpMpqk?%u@~$o794w;+*O-<9DC+ zQ;yX@_($_2aTdeQYkccBU!eRjo7|3xaBoIUvhOMbuHjog4nrP;6!sX?#rsF0b-dq? z%Qqhpe^2f0B)jkGA>z;HI_Edy^R#)n@(11Y(U-~Bg3a#;TIfPgo=?)j-MdV){Q7eg^Zxb9RmHQ)k-ep@Ed*a*O)&_o z@*!igrF<9N1O08a5eOu`Yd(D%EKoEu9&`4w>*rS_dbEgrFzGCvEje*>0=)sl%xfVk znijT;0=-e{aU<{to1U7NJ>N1 zj?FZD5_aI8`MxGy6>RUILs%cN>K?ghHb*LbhaF-k^g*Q79@Y)mu3955r`UDwgTQc%|$x3L>o!rC^C*0JkBkb6c) zG`qL%7Y}>%SJYY0*<(~AOQDv3v^)lAPdBbcCnbwIW_Yd@C%W&OFV)gR)|t~0`~y5t zI-C2Br!Y>4?6eM%IQyZDVcaq4lb8^bAW|Z}wrq5~oq5Gc)}7JfF1E!S=OLN($LY^F zPoo5nH#3Zdrq;%Hk)y%8TS!<@sn5*(rRpUCg%dmAO7WUn|9HZ?gij=sWI(7O1yQoC zAskm-_kay`=S-=kF}FP(kLP{v+(i*`GgZM)1Dc8*_oIWRJlx%vCol-a!G=SrSVcIk zcrW2gQs7%FarN=Yn)`k`)=v#}lZ_!+=Yv}O@Ktja6a8|ri|0R9N%u?U;$8IZTqLdg z9&^K14ypDHcE~bmFg%;}ey4Xr5{%1$Sl@;gpG6~>#^!~ZB`x*hQDbQ8IUP+vs?X-+ z^u*;qtS(*X!VdYisY9*J$%4Bwi+j*^IdHF>1~FI5{!Fhye*7ILI@#WGGb7W=k&2`hKqR#o6HLdJ9)%+zD{V zJ82fu6#Ms4>c-~_Q#;vwkMQMP`)(TeKKV)ie4A=~^|WjMw4H-cRRl-Mu`YM>=BQX% zAet;K52k>!-qei|Mc^U?COk0>@!5l*bZ<|_d7A2Rl=WPR_>gL3p+}2`Eu4h>7}1Pz zsoqLLc!o=a%d$3xm$EpNZQR;&$Z-8W<}t4}5-!Tjkf){%T_rf*+zY9c>Q zrw>o3%$4nBpppd{&7F7F(^n#N60FMnE9qj`^|=bk;e%}=o3(Q$rvl7$h5gbFJaUhX z^#J^AC+D^0nHh9LR)u}Kc-zrM<>#wN+|hl8b>cffW!+RzuGEY0s&qTXPc}~MZ2eT< za@_uYEq`>MZf5J^eHMEz12Gd3sY<(Igo*CZ^xPeop$BPGt)XnGjEuq1qT+>QNh_Cn zfI-&AP{kvZ#yD}9Iv&%Z#fwrhAlD@!ks?GU@UJHMhhu}JQrd97Tk5vxysK?<(`N07 zZi$8``$!>w#K_FcWdP$0Iy%w|1##5W?=`YG=RxTRz49FW`qyNQNU3|%l`y6i_Qh+qj~G2gm;BX3@2 zx=b!(W;<#>t8nuheIQ`SR=^1)U~e}+4md=O>VInkzq(dA%x#fodRN{k{eoxCMAmWu zY-{~USm6PQuiWkD9wIV(Q}uYK^ZQE8!z)A4M~1xAZw7_{xGt`JE1ObaO#f}r&dPk4 z3_l#+Yd~BzvmL_pt$Za8-?xc6Rc@|8xa=H%`A2mTaqHjCWl5Dj@J5d14(y-^7f2MR z(k^;7+is25q@ej;CX#RTM{~s6Jci@rccS zW*hlTUF8S~waY0fdx&$B#Gp;NvMb{^$=8dEO~UN}+2^ERr9-A?OxiEEGi7GF@!u5# zK$;=<>9#ifDQY$Y9D1v_`hM<+`r8dlL@!KTL?`DDjH3DvVLEv1wHwP@_cH|hCQ%Y~ z{W|vW^E9191G}`Tas~y7K2V?nJxHEDRtiYIb%(`W*Z4n+hAZWJ^9Z;jha{=vxiPdE zyUmD2EqsE>QBymC0X+MonXB0aMQ!EFUPvDnC(GEOsD3A5Xc#9BPnxHIh%M|9KZ&_i z0dcStahyGzr-nR;p|*cBMOET6UGY58=;T3WvuW_lA*a)fDX95x{{}9Q+ehc}g!dxb z>*TQLyGP%(Y7A7&(YFp?>QR^Q^wEt=x;XI-byC%;6+o1N-8}3y!}a-Y2 z2EbU8`{3@4tnExf)@}HGHA=vcpTXZ23a3BcG>iIR3Z>Mf(z3)?*GmMG1em_ph|#kr z*QWp#1S$62PTkj$r269RVZP0XtTJi8pSHJX&}>*@>kTl8rDWwN&AA_lS-scNdJ35y zJN_gzL#=dY=dQmf$*aizD4`F<4Mh!=jGi6PMP^kJ+?~CNr5aW;TbF4T#Y92?NFt4bi0}y!?bjn;HOR zqD(QH#ENoGd5Xph1twXmTu(#df9@C8-`wG`thVoIHoJF%)Se^?$l|Lq!0;h`Iu_bg0K#tDI2!WJJOPfrLAqX%~wzyWe|KK zX79n@z41ELh*dBvU@j3Jnf-U4g778xF(`P%kGH5DJ3vTUh zWAvA`GG8e^ zg%1xmL{3*SG40qUCOywOQkQ(s=ypx3vwN?WsKC+oz}DQc$9q*o(a2$Iy_Z1SQtOP- zVS0`GH7EiW39&T$kdXy$o>}aWa|ARBgBFFQ8X0Tsat&tulxS*du^I-JxF*bc{96g9w%kZzv*6V8i{}*h0LudxSYisp(@kddc zz9?Q7ozwfB_~s&YK$!ITd!wi=x>VZTeO?VE<=(hjLOfY5lM219UgMyY)Ef73ug>5_nl8$l--gkS3nP0BnIPrxs$u7|C?-pWr4Nn`Kn7z&Hqyg2>66A`5jURE z^4(>}VzuHOq7XG&#H)J`3-|EuovK#uR_-OZ;ZtzqDvd}i3U1r2; z_p&8BXH%!-%_{D7dUP={keo#ZQega_nd#UA@8#k-z(KofT@w~VLmCnv*!px_>%2RO ztl>xM$)n1jAS;qKZ>Q}%1bVXySdjeOlsevtU6`kF7V0>POfMjX7K}2}CA$1Fgo>+1 z@^K|Glo1w2iSf(SM(V=QMJLm7!MbUR5i3e+4aYEO`upex^S>hPPZ&XXj|z@4;tjf~ z27tXE2(%}Zr+;dTu6aMWB`TY({@{-72YawX6t5M+GNny6FN>du7iD{z-b-3GO`KVd zDWn7@On`mv6Ww%xCFTi*;d%CA-ep00UDrXt%vG7Aj6vX`J(DG;#~PT*hv^RLG+x4pDXQl%*X zvQ;IvoS|7&joNq<{t{7URqGQ(!hwYs%f`glkiv$o-~-fqER2j0CTkm(%U37M7^Kbc zQA-O3KTc{ZvB*GhrZSQGB0UxM@k16yDt&%G6&Oee1pKx(ud>J6lY6cSSMKshWwy>l z)9=dA2<&f_tU8l~4cPB)^jqj#^Mw|kVmN(y zb=f0)(T4QYaTQCNWr$7TmB(NODqB4KOU7OfZTV`ir-=F#U}+V_P2uYvZx469%kQC% zuReX>-aAuf>b<3gG^qS6W!CTDvYmgQn<*U4B`;Un-apGWKHV&FmEVwM@n_o%!XflQ zmb>hmeK#7`bJ(grxESizsUBF%W;+S+)ZG>>4gS3Z{@2#~`^&dC@IAvmV@b=DYrb|lWa$uxNeXX3McY@{0`vu}2vBWht zW;xd<3iLA^=q)U`l^+m}S=2n3b)9qSnX-zE^-ijuXL|YjSpX%w#A<-WvE(_b()e2& zGjNetuCr*`ik4LpE-H-%|T+Dgl$HqzrOmz+|K$eSQaJQQ6K-{f~Y~+ z?z!b-W=}MnSRV8?mP!gFqnR{i=Btd@HGFJuFUIq6`+ef3UAuQc7D-G)3?|Fy_SE_p z%!5TG?z=WV3F(gzbmno;c>J!`LCql`^7755cWNKro9!3Sq-r#)#G?&vx7ieX=5pV` zDbny5>pGr1Qw5-?hUt&KLCIrl5qX?-TnJ;F3u1G8o9eW=OrGB7NyqM;8*fnpHpK;t z_{vQ*Eng*8KF8$7q{J^yR^;d8Z>+DHn#bX?rXe%86p;)je7G_UE8@b!#-4@3ix-=k zul_Ux77=N8m65Qe_#mp+`Ou43gRO8*f3hXg0&^%nnO6-IH{-!tX(H8^G*0C)Am9GQ zpa1)p6QL=-x}Puc3%lEV+=Kay1}QZ+^u9+zRbV0c4qOVrRt{KG)8oMjUnnqW&9XBT zFsr|Mqy3^Tsp@^JWzu9b58RADD?M>{p^}m$GZSZOgv;H{mH%5#4LG{|_fu~dgRq0$ z{QTd?e2PI41FMJ#Njo0PZIjWw`-Cqasw7*AO5AjCo*puvSpwdN9Kx)wJ~6x3=X$fl?q@KkxI8=w^2(@iL~~8HkTBj7Ch@(*N%048fL{S@m)(W=ZF| zAz=@GW0+7~O^!b${z_zYMATvGZe9P?eNs%1igIMo^bTX3;;8AS*`v&#(N-1E zc(#v!Hw59++AUtCNt=`yI)AW;=h-C3e?Z2#2|yy`XQdmJG+`}5ZiE_EBhF5txzqnM zBp&$DpuW!(-Cxw#ZLFACg)});tf=o<*3an794e*j=5<<^mgo=mg==WY$Z$NJQl5|| zA|-vAFyRxdNrp~Ww<*YhlYU`~EyyE#I#RQtzglSLx1C_++f+G`_I$!^vVaP=h?=rK z^}7$bY)O6K?;@N6jFDNlx2}x+P9#-edoJevn%ebijDB|S?l6@-KjS5@u^tg*8sB$?VjJkd$-}qlw;r4csIB( zwQL1NEj$S(_xQARkD{!*(QEBQFNvK#&_-^!rxu!eql#w9C`m!@dJ@gxT&c;}q0W8B zr%{}zpiUsK4A;E3MCDW3$@#)uiFn6!3Cz>2tYNN zfke*yuZ?Nz{8=k{yGhFM&%dh#INTxBN+GgQE+Mf_2m}>;3#Makb-J}_vl-`JLvDr7 zHW&W)jsJ4iPx}&JNS0-pk(Fg)OReoT z0ZH@0u@%4(F|Ii;04!bU+a))v^iCgr;JjChRI#QGPiF@Y5`X@x`1$&Q*KF9VYC~DN zi~iy}myCfxw0`HiY^kK8(a`bF7hf@;W(oDKc{`=;9kbL6_<94^WVXHmVB!3}5Fe=4 zlq{g7pFh@@d1{ma{O9itu*JH&^}dJXJp_57=>(#qzIjFq)$4Y0A-)wrMhw6sR2_c^ z0oI#KxewqF zr17ob?NoWeF#wb@K)`>?YRD$OVD->3)fS!BeRIx4aCZN}W5fe~V_wqqmIYDUL*#pH z0FBZkyi&5(=`^dKJWlE+GvkHGG!Wy!0T~Q8ukoU4Zu_sd573_w7sxHP27v4u>5qY3 z)xA6OQQv{f|4a0!GOEW~AXp_CNgNTzB(`?nTSNA`J<_RFgnV@T;3W2=_fwUbM|GNz z84e1OmOoAhH+&%+fjfh}&@##Z$*A|bM-z>7QGV{Zl#Y^7Jzh<%wuXB1cG-#gH>s7& z_d2M?6&gF8gP@Ebs@^6Poz=?dE0U zk!j#X!jlFPiwG51;zT> z--T_PXvDA($;a@1$N(MzgM6r6D2G6pF*(y18yjOio64#qfL(>XT_UMYm@S$b5tpVo zl@C{GkI>!FYnW1hDEPQud)V{}+sKV-WfFNotkV|`>)^0Z=cNewe~9}ExTwBu;Q>Jq zgHGv?5|Hi^5NT;?$)S;!RzQ&Mj-iq65&@O&jv*Ck29O#WzXR$&yuSCnd*AiG^_$;0 zyJqjT_F22u-g~X=$9e47>?AkI)WiXL5N|#@x={sOPp-{hyZvcyF_j@w*dWPeB{2{rw6dkho^NY|z37gQJH|{%Q6n*JkccOdw@&@G{vkST! zz!S~Gu0R3{|F$PnJu1a__XUCNh5O}E#KvpG`fJ8L(Rt;iDlXBa{weCE9|)*MHc-qt zKKsN(M~cq$!akxoi5>en>p*9MqmuhXlkATiiyn+3Q){X(-yKFJ49X(@Gk%bL2yww?{eBcONpL&3zb%q-KI|2GqdbtcbA7R$sW)~iK)h7?S6#N z2Zxc?vm_1bY{(@xd2#XQ-bmH7oORZgJrcV)+8?mqnq<6NpC4EDa&7qo+ zSOsUY$%qKbo_f`hH)OKM zLB2Ed=};7q_PXIbd&gXexh@>t5IBOE_Q;0QcEwRlicKjAxYKToY}}xuM5Nz~uAED9 zZ}gU_cIwOY`+RmaLAwhpfkO!o-uE|2Ev`=F@tXG+k7njZsjarhsGWtym87vP(yv7> znyso82Zw~-nKh|3&fsy(?9RP4_iX3$dd2<9Ai`QP^QKB?#Z;*orQIAy)d-w>Ey z1h@ZKUuP24bR^_oWfW|(o#pCIDg|Za7uV{th^w^2x*1p$OS&@&n-?dQEZb6RM~z8| zNd?Ey=Il$=pe{+NMA9#Cz3QnGY_u<0m7y?tKvm;Q zKw$6FaU0_H;rX|*?ESDe*+mq({Ms8~9Gmk&)UPKLDy5$TQ>6Z|Xf)}bHv9dSKBsLZ z0H=QmP+vCWCg~S*hwcvv7Uoo!#gEpP;&oY!2V0kMzoKI(JW^d`FZ<$PL+Yi9m!x8v z8pq67aHIORjgY#IEmy~=$1QgF+Qp4UO%p3%@g=~-fs zTiJM+xGUq6ko%A6HSm%1q*SUyg+dEDt7ljT#{F)omGXk?W?sC4epFfn7vlIU)OO0ey|N zqO}o@bUf2^t@x@_xn8EaA!`;Qnst2{x5>sMEmpiG(wg|9eCjAzvoRps2ikJ(ZH5?) z`bz%d|H(w*Ct|*P1$s${l51WiM+@pNnl!N2sD{V44W@yuJZrubkf6adP&4_rMpK6D z2N`n$DqSmr%xV_}@z{qMb9pP}W0LyXqa6u?k*zv6*v*e7?Vpt^YOhVNOJz!9+B{pY z4q{N?$~sAXAU`-(iPcpXHy2#xTrXJ^fZ?r@%1L8O|M0tpHU*(C_b6Q3Kj=aIfb{iC(==@c5Z@!i~4A%K^ZVcB7sLu0|ErhLD_bOFQV) z2U;4_(IsYBHx-&oubEuS)CYrEO3KCvi&xe6X~{I+%JcH_RJ|Ri3Mubg(#=f_Qn|*j zvB&!en3~FSxx-z==M?wv))cgg{6O-beIt>Y6h6lHjrD6Y?j+Btcok61l)a&HA0aY6 z-ylg2n@&!ZYLxU^j>&5kRaTv}WLI~F`<0kc3i-xJvc;CF;?&R8&_w7NslD^=hF=s7 zn05mIQMwb9VVL@9eUIcc?BQhuF!7DQi24%{P!M_2r}}m-sxnAOlk@(-b0vf|qw81R z?a`6<;I$%0&>$NREE{j5MOg{N*xKI)I zMPu^m_(Y4BwajP(+>pqg7x@#rf6j$~goj+q5|kl=iispEO`UhI+&nNV()xKchOBG` zPR^tIB9TVXh$4uX*l4}1*UAly=@PrBuSH&#hx~2B4A4O;E@Zglxx3mAbOoi~%Kw{M z-isj7z7U5EkdGd34_}Oi44#IXOG+{ozQ0h=<5w8z^nsXLW{Hv81x%_hXnhma=xs~` zOU&1?9=SFXnzrp5b35@pNN4}daQ8K7WU(Sz`m&ld(ThOp!ZdFhHCH1uD}PAl}& z@iiLpa3#YqgF~N=`KlDVk}M|NiElLgD^CmrV5Ni@cFW>uoR3PuV$2~rlRk%Pt~%cL z7#9~0To%j9_vsTyQ@^;}B8%_pQm1|cHYU4=4y$+!mS$?3s`jNQuvl!@E$NQx>cQ;oD-)!%V3Kp%Kxq@7J%%;!%76+HdvA!XTgz@MntWi0Y z7c;LqXh}N74`7GO`SP4JT^iO&*QDcR>rf@&+ zOK=pk?KgV5nT5mJNftK}Ptf`Om=qIvSL<<78~|;h@)P=dt(tqJ!ZK0Eo@!bo0!z%} zvxgqcSPcwI@~$@GBu16Xo6FiwlBJF=>UcrKRgLzWI;3*FtC}L;Q4%4~dVZlX87Ff| zm~jt1=S;7E{o9xbn5m{C|DNi{E9>aXQX9`~PLqr#gZvA;g=$A@eseFu)lE;E%+J-g z@zZ;~in;2x3XXK1@%OXsyPsy$=D7%kxPGp3+HqTzk%f;7^u1MGjyX=XmQHlEVHqsY z=8`|R@k|DU)Z?e;Z#i=#+!}SGHeAkVtR5KBvM?fdBE@D?k0$t~8or{&Fj?XYb+t>J z(_dQOspeR=YGORm$goM}mtAE>lkUI&u7_0eg{$szw#KR|_-UJMzz83GauGanxz|IU zL?0JX3IwMUR6sPZeQDNLG=jU?u^0Wn=)W%N1OY>)KXnj|a&%QXVyQtOil}G~w0tmmAj@$ajFVQC-!8C2y75_*iUujbjgv?bX>Y$I^?ekPy*; zZ9D{xM|A!@jq0;!oNK4Jb{7#KdU8ZjsY}!De*g@?bQbaAGICt5;2Z82YmQ{J)mx+U-SC~$VVL1oid%or@o^K2 zB-6h8bPUVrTZjVx%9q`cBgb_G4S`eOh!xio+XlT-b(h2#Rgjbh zjq%lX^`WQJGTz2q|E>x}r9jHQcQLB|9iEE&tzP`uz=_7NHi)=U&6(Ceyj2yXDa}T04S_jfE`rb-aDh zy;Q61RA;s8{C0YVynmY}*Lxb6cAhgK)JoQZ>qkpW0pDF#H z`H?82U6jsWr{IeGDt!*wJs04><#OH^-GYnw3l;XiN{5r|A3Le{a@A3frLl6_f(XBC zS$lWRWV?QU<8!QQs^^2K@wX*XrnM_egM7TlwD``k+~ZrilIt#Ynr36CO_ETV*}`Z3 z14k(ZOK1GrTpwmSfkrO}uxDQlLwsF~nwpXnZ3MOIwEiyC(lt_4%IoHdpaYQ>Q}5_9 zrkjj`W%-+PsDV@WP*03%48ibpW57;86DwfYEvDJZ>5a}D-yOR63HIu>R9k>MQ_&FY9J%rD0UQo{)$=Pase&%r{_vZlok4yZGM!%9e#=UaofYDf!?CAtlpm}w zHfA4_(W+P8-(=r(IdglzcN$X}Kjfh+Xfe5an)9?mGn+P@hK3qgL5kr#!&iN#D&@$? zW6U=7-U9;3#N?bf;$z9wn?7Eo4vN@@4D;Wn5H?i5C{ zGs@M@ADRG7K^fa+G6%FFvr7&>n3f{{1*!j9kTRO_t~%tvOY*>7u5~B>SD7GV3bVU- z+3z*weL1gqbddrF=lQP^%5quZc}Ns8}8V9Uxg|WO}H7~@dCB2JPg@@kr?^5Z@J_G9?=ma5j1qTdD2fhHc5#K!~ zCVc{Euom5W_uZ5WAP~L4?4D$I%ayd0z3^**V<0MTA}E9S0>Ta_`7@pJ)e>05hb2C*&dt!V4i?auTGiY>^A! zzY~z}1(bkxJ*P_dPaEIY5dV^p4954*Je%JhoW^}`f(yUK0ELkaECJ{!_67(USV+D2 zB2s&0q@!og9k3h!zxtGZUBrJAit`~Mmwn;jpg4??(c0yg>uGxbo>cA? zGT9U1E32HBS)u%j2Z5y(pvQ&=nf&!OYqjc)w{#arRRP7zf9bZbAiBR5;k!0>v1jz} z1yl*NU1l$5$EluPt<cLRBKPy*;bj#@df67W);r^Y1Ju$q6s(x0@!_(R z`qv_n-ecnh_(C!1q)@Sq6tS_QWwD>UlEy-1WHn8?li#Jxid%)7dwcO%w->tGc(J1k zz%Kda>!-)XKK~;n1R9eH@SS>aX8!0!{Dr{z5BRNLY}=EiaHOuma_QVl26i;7(7dml z;znlEZJTOS^guAFX^CepWxsOLbqn0NQ;eRoJ>=@|+_&PMI?E{3=QI3KpEg$$Fk3it zY7uWnd_L=}Cv3j99V))%T~e~!`io-xM8=!AWo^;Z{ZVOuaa@?x#1MT5DvVOEh}5YZ9KD?K zA$%W9E)%|kuwdNsb{{D8eO$Jc z;xkiZSEE~t36Gc-*|%_Be=*Y@o*k(uuDZWzR}u7qWtpE~g%UmieK2?(`eBIMcjkfa zb(h{v4W*jM^PVLGsF!AYrP|n}Z0pD$*=G=EvSe2Us3?*BnDmH`}`X{mv%0) zo+HqvUo8QX)mvp2j9kQDxqN<0`TN?~-!S>pqZEkN75U9ePmb{r>2e(WGa4jHV=QuE zhX8~dgJHpC$6xKr*C28cFL?R9Z~^DluoveM2IP;wPc^;;{>CS8u}J*+W&Rk~$g_a? z-QNLOLL?lpTtObL1lVY>xqG*gpH0=_nJfeOh3((})7t)yCm^jxy!LmTFO8i5wza}V zkt3uwALHkyFSF2V#olSUi!hR3>sR?C)K3lF0PP*H5B~@JzCP-YB7W((;O?IQ7Z*{4 z+}j&fo`MLojJS?ZYQfU4%XFwG>4ni_yqt_D8G=17D=8mW{KYxN93DKnIP&-h+@t+A z>-r02f5iPp$9Idre=XtCK(LaM3*PGIZi}@~gXy`Q7Q^qV_^$bJMU_(NakT9Dx>7x- zx@st`>{L}&MkZE}M^zs81TZM{2mD`s6Vc0++8<~D4xqOIAtTd7zoh_7Ca|sL_AX%x zS(tR+A0^DprFuh^l)JPyrs5$|yc0@fyZ0G;rRIf3jO1|OZbdZ}xhpP^K_zS2xBRZ$ za$kAKZCG^?cnQcyt`C2>f9v}ns6qlREnTz{7owXQ_8B=`r0c{Dp_a(uS zW@?ohv`dba1`EfII-ihMx}S=FiV9^4!*Oyj4;%?yuxU>RruMy|H@>5d1p1>LUgM`2 z7x}H!{K)(tr~<4YfzYHMQWEW_4)qRr_ZYaCB`PF@u-%!qG;NE^Hp^$q zxuFB`KjVC>$8q52u;1eU>D1X}mjHYl(3QlMr8u1g_t{G8t1Bwz^vk*24_+tPp+zW} zA=@4JjX7jmJ-9p8tHYOP@|fy_I`TqeNStbh2eGI6KN41aFVG2eK@(nmpU%6++T zSteD~n7{81@U#Ah*bkljuN5as1B{kHM?nrk<;^L!&!8w-8mhQaR+aOz6m5bEFLH_^ zj8(dek|m+I7MdMWpj4T$cfgj{#dQA-C3yq$;+{l`c>oA>%k-%-#iidfz(xJyh>5PT-;W=tl4%lg=PGVN?Ic3saqFd{EWhPJZ713vR$t0ooyA zl^5D3#h)H&clLH*{spFVX zs9Qf~p6-C2nPv|+#qS$SDB?EFk8>_NT9A&DDkQmYMU6VYZ-B_VIrqDACvTvypL!@y zf7)4>Bm4?NsYpNdDqGAU0(A0(Dtn*DZ`cfnG7j|H9u>pDmaAVul8ZJF#x?WC<&?l< zK%4yA(P9}y>)gHvvyN0!-0aM@RMpAUo07tOQh~f0**+C1&;G`5zsc8Uyy@D z=;?tVWLnnIEGVau{+m=q9=^IR=h~#<6oQKUqRwIK&_p{`C)3a{qFvtVL0+>ilkVm) zs`}iX=HyO7Y$9!$6-K^&V4_Mq@G%`}!F@A${MK%=YRs8k)v`<#C}&Gi@71JUz( z7EyNQpU!j{SW`}VJbrAkgwsxCtcO(-S-apu`Gqr^2TmIJC=r3?PRo<-W@4bug7|vB z)ma)g?yJIaX{VH+;x1{ulMDw7c|IO)m_PzJV(J7G_0=*&YdcCrsUo_BSqSAy`f1j`M5dzLJD2nZAo^xTgSr3H{d+4P*+oW-Xq*ZU&yIoS0*@L#))){r|*70%}2R|$)X|mw+t{N5# zjX+$rXy*EhWXCMCO$6R>R+tI|QSQAbtU%QZH@NnnVVR8k&qWv9@LrZVptDu9)G~El77S4C{s&6G)v-(dJ^Raf8Hk?# zyI)4R;!(8BKqGY|_Iwq?2YOkiLNOV?TtX)9`?13sk@l%F3I^{|=-DSa| zlegY|$KW@=lpcLA;5$PDbCyd$dV9mYNP+#`=naSd#Wd_z6(?MJIj=`b}O0DXGhxf8xVdf@bhNW8@bB%r{R9 zamd({V`YTuUoBztbmPwYHl^t7uX3~cW1`~ynpywdLYXZ+f#3LWm zKo7|g0aNUvAPfZRaM5p_7?SrjYM)Ay=f8=PpR&dHb`%UTBkdtD2~-mK7LCFsH8M?BIDQN;DZb04vYtf_ERdb!0|Y(S*=8lO|~8ndkI(Bx<>`<+_j-tc3jX(i~R+QXoV%kPXZ4K7vrrZOGuBcovV8Z*3e?a>h zztn$-0fF;;z$xSldB}w;^4fP)t|Z1&sq$&$le`=2PYNqW3%qGYY?~c9Nm;vSF7bf; zfCZI~L2hSCH0QRWlezg6<;M=Phqr4%J_E0JKp^v6o*&%|AU^_K)EEHdb8;h>9mO~A z?|o)HzeWw*Q3lQ`{wN2bSC(QTI9Yhe(?`L*^5Rf9j~$uW?70<20CQAk2mjio1=XWQ-U=Jq6KRp8$-)-d}lJTLd4S!*xHAr zH%!0t8?f_hxA&Galg|Q0m%}iVSY^83(1NpBS1>prh0|V%PYS}zTATEQfqc=g&njC4 z@gb+OImo+Q~=SZZ!(HE72o^suX5-gu(o0&@{NG1jmCaE2eFSKK))=LcM=C6e?ty z<7?TLWxYhO!v(U)*|S$VoD1RUPE6mUfBa{;zuyJSJiJBzQjChMP*KSF>FJ>b}->+?rS0Fl?J zMtt5i3Ixjdyo>zU1{kNq#UV}GWkxX2iOv4BAVSYUZnG#MVVv&p$OT`V^xcmg1hD?{=LLWZ*(4pkpa{xO+x-YgF)@Gt+wb*ZppyT*X{83JAo`=_r~y(K442e2 z#K`AAA)=!4qoe;R;x~Aa5Tya#jX!0qq6W0+?_r1;r2w9fTtNtbS$|!|{YNVl&^7P_ zqwk1a+&B1Bj(Z_pM?j`|0{Xk)6G#gjhX3Oq|Fq+43rGm)x2__Bt{@|$AR%4>#*{0- zg`+D-$X7A3uyHVO@hDiyDetk1pir@KaEd;{r{;P>^YqUB=VILA57OR!odlsGAOM&l zeg&PqafX&P1(h}Sp30qQ!R7{RKEW(6!KTLW2Y5-AeS@a7x#6t}Lqji|Fps41AxoPT zE^cU9SG0ue<_Ndz9|>19J<_WIyJ;f{V#iT*UP{L3YqIHQQqjVBZ2tRq9tFUI z=ND+iGw>6jWBun@U1a}7Iv@)3e2AD^!;ys>maw9`1XGpLo81&kr$q@(+o@jY|u?!l84z{p~bljWbPQk~4O@Fb01EzsBp?C^a{bKTp%^F(1-ClJZnZ7~zVp z(ZK4Xub|1Bi7}r~UT8rST+Q6&LMe>nRmT}@COKZB*z@N~1~63zmoJv#Z=ki7DaVg% z(1o3Mun%xX;EASE@^+_Cy4Ay9?eSDTYtz3Y;Cph_kh1IZP)tfsH`sZ@_3EsaOuKzm z+CaI6Q#|Bow!Z>0%zvXz(kW5%AXRJA>50l(%oEX_lT6sdcV6vh1tp^=LVaGchxis; z`RE@p3fNWkgCuWulX;8XR?H8Ac5F(gmbE61PU(8h;hP1onz-Pdm6L(5vzHvkMqwjf zDW+e9W3CuhlT1B@SaTd`=I!Z%V@hG;!6V%yrT_Gj++syg+SI z*VEp>nrZjcTQ>+!L?L~Zu=nKq_!7|4)7XqEF9`iW4bFT$qt_#r05+MYnYzZqOfgLs zhS=TH`XfhiXTcTJxp%wqjT&c=Ds$1_W`e{Wui!n3F-^ILz z;TQdJGp|i1bX~G|Nbm*=4NnQaS-@9ND(r;kjJ@nYOTW->QC$rbWROv`ZdNr48*4## zPyIlEe)ttsWq;fRhPJOlu8^Oh*XVXXVNXOyXd6UpLTn6b%l%uo~`et8uZw%Og~2}A;9 zF9k)YM~rwjqZ>4i83HNOIQDPpi#2Um=&z8Rkbq%)VCrkDIB#Vi=(i(9+{n*Lc)Blt zQxB6#(wy&s@0(}X((N!f_M%nrW0eG212$gU6Q)8;bwr1DT4~tJYezfu_a577nE)#H z(>~L=aP!DsTP-h$Ql%~Rqk8HzD(FXh?p6W&y!Q^Ao@yj8ny^)t6T2JVifBe2VNtdf zH6exooYsaHd#PVm??)rDbhzh4D~&@w%Pp0#A3wj>1&^QB-`z%A*AO0_j5rg_Bm2us zD32mmT{I5@RlljmJ`j1|Be-w3-Xa*&@ z@xS>R^PI>}Uw?eon<*eX#k;Y;qJSACXtLr=tODRk4?kDJvn@2)g9(YU(0My+`FfI~ zLMDuX1Z6Z=w!4HKEyl$k2pZZQCaF8Rr#dZ8y5dhzJs=8e3^LFju!9N%EVyey5RK13 z;wp`lN*!rhRN0+SBRZWJ$ZL1mPgmbM`x`*6Lrfl(^5rN!uHuvMyRJ@yH>$*7;&cY- zRALS~Z>>p9>{?~1qdD(!3h1sYC1=$k2%6-Gh%7_PmL0d5BuUQ~O+CSQklDJur}Tkx zywtcXe6YsxS_^%Z(-Zq+i%1x&@a_x*OqN5?RT7wpIAZaL!soNQUq{vCK_`sjIbcQi zL|wQ5?vd=7@P!S1;KUYvyC1kLO)j29Z*T16kuqv!3=>)-Fo#2(;JO*rS7O=iIzryH zxRHB4YY1LH4aazKM3!EktXgFu_*(h>79&fg^!x%`NrA6h9D?b_<@MUhBk5eBT*X%+ zj87|S5pGbabMT~F%DBl;jJJId`TPSx$cu>~HxsspBs2C^wq?NV;>BXoH zzCoDim|Prv883W33Gaox&|r|NKlFlu6EN!r^S6m6b2%rC%OL9MYxWx-oadFkg33Gx zVLXZxk%K1>=o5v%@a)b9~ootvCfBBx_xy~lpisC)-| z{l$<&8GGayC-lm0D-5i+@Z1-@;|zV0$^Qxo1nhX)Su^0)m9CrSN1{KAaa{CIpvO(HZ&A1jsNwpetyYlqq>E?C~?A;TGk+ba3 zF`PaUj1$Q-_VS8-^o*VnskZ(aM2m!Q{Igev95Evcg7HR(5LZ2{O-U)m2{G6b>z$gZ z6Uir`2yl!vXNdF-h0_BtbbK|TO?2!bEF;%x$(_zhGz2ENYo zOLj!=bE(U>C=d<$F76dz7NyGyo+=Z{`9GWSCUC#y=i8=wrGATFsQ<2uayRsQdwbG8 zDUeE^5}vST!sTs6I-91jgW)JG%=m$(kD_sB(rFL*dr%={Kj6=LKcw)|ADLqX*8jIfV1% z(ASjjL%3dAkcW9BlpnG-PScb>;NDn%HQ!#3s-OS4?fqrXpWnFY?xCB(eoM-WG{ZU) z6R#nzQ9=I(%Bk06-I?A+_tyU++|wU=qGU420NAsBJs`PHgnFJSN;YCj8O0FrY^x@9 z%AqPBMiDUTY|L#Ie7psrrX9!3-b{R-;uQk_V=!pPgxjJ`hjx`dS{f`AC2Q`;J+R`1 zE8pk8&D9YZ0T0t_nKL%35=k8zTK8=I!8}*l$9Z;0dsG{(#lEnc9J0yxh-&i^x?dr@ zduyW(b|MVvs8O()6!eRLzIeB0Ed#K?H;zfSHJW5&)IF$#1%Fs*P(3tlKSrTgDXrBGoI5 zOy6~0=VOlEx+0w_UFj&8^%#OP#l8=I@Z&*zu%hO^!F9aiJ3;`#XD^+{JtJ$uP^8(l}`82TWnskD_GC&(U2}7)LNZ+~w;MHt65K)nDP&=|foe z6|^uDuXjZ6eq;AEr~>yZh~iM#bpNbsDD=jdHmxQaq0wgJ9>%+m4kL|olftVhK&S43 zkm~0Wfo+wrRT^Z7*uIBaweJK+&41oh$tcgVhFf}`u7&A>?P!)w8vHyT_H{p7h2s|!6yLR&>Wga*C9@_@y98`L!PK6!~1_3NfS3YU0A{b+Tr-4GyinbXX~^FpOc{5XM1>WL zjl?jGsKLQ{pFP5b1$0~cSZ{4SJmD)M4@OG>eQ_0|{el*UHVivfF)FI!DDEgH4m`8W zNJ06?I7|tdRR{TzT}e-evBrpOp7ixsoZL#CXb2J>;TP)t3c7Oxd~Hky`l`f-@{sVu zVYyI`pnwaZJ8>Yoi!z!14F+ee`^-5p9-3h$l=teCC`(_Joi$Z@4f8V!KRUjVOKly? z->qEiWN^4WBWrfeN?0AjsDiTRDA{bH2RnLcAM21GyrU5Qae;^T)-5rg|JJcO!}@AO z_|8gWR_m@nP;r07k#B$5q&6u+g9UUBejMX;$-y(7QB z^d%JvQQEhG1v1Q@NLo%=kNPC;OibJjPIjc@d+*Au@P_tz2^4O7toN=%SZt%+mZ2Wa z25|`e#}BOw6=!X{+>ot$i!rn-9<8EOKT8r^LzS3+tm>riF^45(jPtpbV`=Ubn~>wy<{Q`vAEY~3 zS8M~TISxT59@k6RPVdSF*%~SU9^Bo>5Is2a* zCN$>xu);9ESZJ;y;MgI|b1V8-lC= z!zX9K#a)3e_-y$MR3l8L#Eg=zB zco|l0t&9JzYw->fFr7FN0LMvg6dp=%+CnGYuP`}%tT@(+-1sqxPN<|xxL-V1F;&df zaR4mGJTIIf)Jin1uZkP!pjQ|B6r=9Nx{~+DT=@!9 z@Uc%w1(OrTdzRz)1veNg+(*}P(uu2z;&Gd1Z<4l{p@9ROF}{;!+=acooCrqCHmPB8 zxpVPUytL>`l^aO)1$PQjJ1rIp}8-v$w!{*FV{iKpQtd(~7jbA}^ z-Z~l*BIvflN)tyNWa@J_O$fKj^NS@a-)NfdmC1AfqA8p6Hr6P^)weGx*&`spB0Gdn zmWDM&yIcYuU_!mDj&S1-6_5m6jxZQ zO743O-NAf#a=+4%-O~7REx7Rm!A*qnFdtx=HucIY)Sax7(VF`J2yIYzQa+VkKeZ`G zSq`e%K+xvk$6(Xqn-7CWu!0(gx|M_m=M*&-)bLusjnkCD%M-N2lfta<0R0{a)K_G! zL}s!(ZGR68%&(7|A?i@@u|F8vv~Xgt?V+ZKJ1N7)qv2SIl(|9bf&xf&aPG1d$WU)P zHT&(Ya;WqUjmNc|JSd_PjcxEIxO*!$3d-u7+-K0dnZ;hWO!VQ9{5WbXdamrfe7_1v4)s5WC~ax-3HG+%&rwA;3sLMg{vJDxbl@CE6% z&~+s+@JogEmm7eW8WGUsQtp+C)*+pE_CNACzTuJSS@fl`PgovU7KZgm`}K?!dG_Ca zoDev5UnxlmT}cgiu#;EHmx753gbr|0VLhW$<2Z~eCTf06s7(U#0$iW>JpnrXrrjHp~Mg$=OCRv7( z%!%&U<0dbtdp;R*RfJ~3j{M}RBZq{LyX7Aics8myI`q9#v0tj!!MvyM=CXKYM^{@t zi7j+BFtM|o7K7C-?C}H0FrR2VmaZDQDrGSWAVIJX0?;PF4K|EGRFN<>wJ66EHh$tL z3^p+!ad(A3tlADXihtV?ix#+p9{y2WGMPZ0mp*TG4=!s&aJn*v{z#NV^%Vz)U$;2tmuF%Fh8<|_3~JX2UX#zzSdfQD$2MN| zM;#ciN>4Ab5S7a|TD+;1`^nrRlO*4glcf5(9!|HRm~TC5)t5>R4%DjcJr14+Rj{Wa zC>9h#*@iKU*V@g)34Ms}eL7605)%p1yCM=K2E26=iK%%!uf9kNPRS{LHX5u#M|(R@ z#H5kheqgN8UrZ;F2;Ni8`Ne^=cm}yezgY&=64PR0{QUss_*c;GIN4W_BE-yVpTcYJ z=!E|(Xm!I)3wSmk-u?>utPJPk;yxd4I_DT~o|u?B?rX$r`wBYj){`h}+81*MXf_J3dCd&9Qt7&}8+y*%=npDgjef|zVpc4!jGy)eUG zkLzt;{|X9nJoP&lk~w|~#!Ed>+O8`d{B#>rU+v7WXi(PfrWJL8xLkXVNZ3{EG4%ct z*E%@;qLdHX8#(W}*1~w30rg?&3bYnWCB=d)S(j<0-pbdts`x|@W`Se+n2zF{7!&!* zYHb^wQro({C`RS0btm{a_nnZuGvl9WlXnw|vrYRuuJo!!q$(n^4MR~Fs)+>=$g?{gcom7oUDy3J{ za0bZ=T0imP)l>M@jjDRhGZCfDPgEXB8b@0`Q^_YP#`kdV+*B?qlSISe^QZa>ik)aF(rzQ> zS~Ou)B5dnqNP`g7)kYXHo7|hkm5>IvPKBPQY#)3D_3*=cjGA%@DjH;u=Vq;rbqfs~ z;+!;$IAM>l-n9usu~wa?mckD+JP^ostP1C&g-m;Q;<=eb<>o9?uSb@H~hpOgEJ2orHe3p=+{ z${VC#m&;(^4Wgx9u_v#JP~sV~$!u_oNOD0simv7r$oeU_`vYwQ5aSa(JCd9;FG6_JKqyH$gK#wA+B^!U9$ z78~UlAu(SgVO1$60_kp_RO)^TEH&pYQG0F;nS=G1j0b!zyCa!W-cyQSaM#YFX-B%k z`E6Fe3p$i<=MxUUf8Ym+7-?vwt+WZv@QTw=-|cp10o3-kiL2eAiZgJeSnr z!6Knyi>2YNrhdHq*qtkEWngLPweW4Cw<3D*$apKUY*UA#TQTWFm3(Uc(gUlSB#i&A zAQ@B5#|iB|<);e$&IM33Mr zrcaOXMam5*QZ60zP{K#Nnyta* zqUEnQADSL&&|&h~6^TZL-wr$u4m@mHwel)kUnNlov=7ffXz^1QWE5Ca1d5$FZ_z&< zmGUg0tBpQOm6zHn_B|Ih4A$rfda~r8-N|czQ%z&BNQ9S=(MnUc_ZpjkGVyBOPBA>e z-as{GAdhxIZb(BWuePv5+0Z}(tcs1*7@3=AM|u$PG{IV=vLH@m#=aop>a1+i)L0xN zPHlJ5Eo3J$-U)kOSZ}Rzkbr2FToktjaYestJDoK)IJ$H(?$|20+~?+L9y&YTJdKBV z5H-{IoNr)ff`m4A`Sn^ZJ7wld%{P%>!m=8I~3PY+@-iX2@Zt_?(VxS?gR)9#a)6sEfNyk30|~#3oTyQ z|Lpxc=RD83Jy&NvlkZ!1x%g&g&Ac=3EKJwiuij;3@jCmdQ$t>erPSDKzA|;pTD$;l zX9H46Gt=`H0Z|n>oz2F>l{UkPjWwdJv-V4@c_F^cU3HRY|2!y}xV}qZL=K2W3{kkg z#;!%a#wCuMv+9*&dmJjo^TnjS)*pIMX!y84o6e{gqy41YN8{h3uc9$Ut+frCIo2vZOY1na0Txy?431#TrqQ@#M zoLF)x=Ofm~!dM=MVyDrluzz9C_IjAw=(*2hqx71mMNMc2ZcUO&W{e>8X_yFN8e0GR zd4nMW9@b72NvpwOw;V~=`nr#Xuqje+)h&+JXO<57iZSC@01j;u+v4!1eUl|87V$c* zRN}RLT}+a@si2|HeD7|H=x-AVf`gQS;kZ3EXeMgtz+D6lXCu9oj> zt>zeAM~TKeWBupBUN7wX4@+}ltylDw$#4^>)mE?Vvo@Q59{kp61TWpnOp*0l>4otw zwe^gxGMc^m{0Xs>py)$RAT!qb(~Np^uw*RVoCjL^m?ODb&}8B+mzpG2r9S%EF&Qi- zK$E$rDzr3&03wPyu)2m6DiGLovyOlF3Oo)B?qvOZ^ z=g%c4VkXinBa)Ed9Oo>afO+^z*M0b`rx~)&r}+=4;(PT|%a5UqQVyOj1_JHI^USVz z(q6H4h@WoD#`POuiS$tAF*5~ri_mvBKvnvr3cvB^rqzv~)=X^n*_a4e!vcm4ukWzHWb(R$f3u7$y#*F5=|z)UkTKN*D-nG&R#&dT$;V@_QHo zjNblL<5-=mtUNl;$v#w}EbHcytE|7w(fe_kK>6a;-mB>eo{V2tC#t_I9@|{>P1B?< zN~gug%tE65l~zasnHym7RUq>+6fcW;W6G+e4#VIDvX7@IN6cr6J;HV<7=7UmW$fgr z9g23x^H^&Qr$RwQ8LR#z3#*?(n@E(pfC?dfLa>vwFrbE{otkZ2_`P-;u|q?5^uanjlo6b0qfzlxiCTQ;gVbsyf&%Kl#k2SVcK$Ks?Oz8wn=Yx6!ik3>{j8de7-Q zHb@)-MZL*JL{EzN!GZ$SpSVg-0Ml|AiwrHW=jdAzx{*rCWVQoRRcGk$32~8mfCr13 z3-^oWs5X9q;pjRiXyiW+UJ>SI;-@};>}DfMJZNxSJA znB~wg)WJr=Q=6Jver&N;EoLWxrG!ibhb?Xq7Q@w5gyP!Bv?C?6|DKOonlA+^RM!UJ z2WdY-(o|G`l1^Du!qF>(KVvI}VK4QgnnV8ngHy}W3jX@N7m-T+1zZxWL;ZP%v{|>m zr5-BiE~=@Io!AUI&^k5#@x`@I$m3L5w$Unc5r-v)(AN`#5*bb?pF5h(J{$yDUuQTb!c+C z0s^$8)NE_^?6y4ha86V0zvseSzJ;$&xpiRcu$w=fSrqyY3)JFO$XO%8Bsh{_ zd#XjzTzv}+k#638vs{q`j|)Tbs{I#Ev2PdrsGF2xR>UsS_>UKVS{NC~M9?LhZk_Vt zJtnWRxnnNh6_p{Gn|6=6gqj>#N%dFjp#u{3N>LQ2Gj=;>u^9fIpZ;X2Ns=wC$B)J( zl6`#%cR7Xa1Ic0nX@q${9+$0G!Nw)N8KjEar&<3cViIH=FP|u_7M=+u=S$bV)o>+7 zvoxKHsQ252coWDMw1l-R0jGA`!4;Wa`k4j^lYF)bR&7~cvZy$wiEI*n*(=e5Oh>Bv zN(TU7v;`IyTxPv}DOGuh50f%JmmOj#-bcQNozcg;!*})k2{xu~`bMF$SE|1U-L)-ciWJ@d5oAN{$$_%&T}v8OMi!G!l0u`eB(syqH7 zCiLfTYqL0PH(PkpJrCpON zJs({-R2?Z@G4&qec2wG#`_6v2I)e3!|8_m*dy-#DhN6YH)9*!j>?TFJU2#0!Z;b8I zTStr9`k4(t$z#CjUh6Z1Sf$DUHc?`p1vfEXalA*s)3jJcAd)8md1~|oD5@NTAcyf^C@wUX|RKzTK-x5GK1T+iR>7qS=VomC0CPPe(b{8+6xU|O&01d?ea`6-l@xf)Ihdef7}>e8d$CDSz$ z7t%z`KHA*Rq7zgoweuPy%q*A@Vv)nz;9(#voOTZV%!hA`jnrbp#?b1)PAefcr;<{c z`*Xc3TTSW2U7Dx(QxdVnt5Kts-mbJ%aieYUz@+XAhKxImBo2&z&B~b*_(oWSB1zs| zx45690fuzapDh37H`DRE*;<3G^dWplBju46r{a-!l)hRPLdUUmcee3)^=zw+i3~`; z>}#xs%h7_yeKfK%+G+h``2e1uxAPTOobn(SBYNVHjH~WpyF$HRi@?O`k4BIChsGK)Q5QT>{*lWX3* z)3MD}d&o6(yZQu=kyi5LD4MF{V`9vLM5()~t%z`N*KXM+k_R@cG?-}~6!UoB4X~8@ zXCtHLkzri$Lch>tCb?1PS=UmLoXKErF;{Ox4aUQ7)&w zd>Ffq5WJb$Hs5gsn^N=dK92{7o8AqGI0XqyJUSat-s!p1Kybg`VQFJc1IFT-nM8WjV}n)f@Rf41%fzo{R7mQq zkvAOdZ))_&6^vmtuzmiD7A-O z@}#Q-BUG#E94aYnm+*ZdMw?nSIf0Fw1B4!1>)WK|lB0+tWPq=|BTCPLZ5T<#tDvv% zQrDok*|wptGQrr*Ra$#6; zq$VpWr3P~rYcu_)5vu&lFA%zZ9_H4AuuJ`?(y^myHu;ft;i*lnXUeCsoWBA;Y+@Sl zgGVU9V36Rh8Q7zWOt2Q8=3NaQpFA?R}EjWAXLA}6p2;1~9ulhMw zory4{cq?#E?{BRRH-h|2&}JG!x#+vGo$vXYRo4y+>8&Lm5X+&(;F9+j-9j za)p*TM9&(iKn6?@fwiG=;7l{3HDy655tIEjaitS4_jym+Lzog5NSxPsMfpr4Gsjzc zi?=d9Gx_kuSRv{3JF~ERx`17Lm?Zw-A+K6RLTeROXEMOM8G)c8>v=!KO6gG``I6OX zxxUzk>CjWvqgYzSX2lVx*_!Wf!Fz@Vu8jjJfNneHnG5QXdK|k8p_DKZ8Ht^vx18z? zZ`W{8SGLQqMkQ(CkIs%9C+Tjd(FVq08NRQ-bBBx%w4ZLU(RHbzL_crOQw5BFsdC)f zp7(fhdy;o?b1bAwWtxM#$%i|9^v>WSUp?=-&PdK?~m5M+ZHghQ}U+l2M zc*RRI?OMa46vch-*HAMxI!_E-ryaw@`b5k{`NIo`P-fhXxi2#71RuivmFxeO6=1&vsz9-lxxa~f)9H6---2;o}Y*pMF{NLn?|1a-QRVcFHKOBsJ z;1S@$&h5g^aZ%vn)uLxw_+46_w6Fuh1VK#F~;Aq}chZmZcnwe0VBg`!O;ieFxJz>9 zO_h{~c_zZkqj)<~jpwYLa^Q*tJURCBR9BNn&ujk3a2o8X$Cgi-lr>#}-a_TZO07wI z%kcuGOSF0_?2ZnrYkTl58s9*p8&ZG?dKt;R=k`Za9J9 z6S@~2+bSsijx7QB3@^1UmbpVi`49!GgT$fTsV-heZNU$?9X7hnCczQh2_L&PFJJQX zj6RAB%QBOX`pTiuYB2qFB>ZNOn)%CZhlwj^EUTsrmlB+D$XZn@i<^fTJYiRxbxo%f zqvA70NBY?v!s4;QSb|pxHRl!iYuNLeE^@ozV`d8D(_J}MaL-P{Ekg3d_(%Kyf49~Y zXK-dHwOC^o-0WVl_Y=Gk8ckTK(bklPYQc_znk;s;#pZTUhMtv79DnFy8SbT{)!kDk zjnR$a`5f1L9*yw|;bOHv%WC3nygeDTd|unGQvOM?`Bj-HqZCwH$saK4yxb;4^=Q=4 zaO(s@blN#o^tHUmlhqYJ?^N2|dNu88^w~~Che-;atWq@2TeFqb1piTr3Aq^Lf0@q1 zbf*@%gQOHWqgR!+V%!eSqJ1+mVG-l~xL2;AcF>1BF5nrh0wlR6-p8?V)^RkVb*Z_e z7!haZSih=nXobpj5(QFKy+})DryW(7MAQz}|A^K-W7`GKu8s~~aO{*UJ|b_5TTJr- z&@*>17E=E!1@_8=8MP?pK3~(LWCMD`Wl%{c9?;@$Un3&g4TSzTLxN7mYOn#`d4dYDZU`=JULTBU(^DXDv9SsJAepbvlQkq+0vw41b z-f?eYi7N!tY6QaVDMJ`CFWMM&2c)Vd-18@?J zRteGO8;R~5Lhc?<^iLJe0oT-qXiyF;T~W2AaeH>#swJO-c_V}gB{ugDU3S26Td8lw zt*l(RDR@L`f$gOhDv+ z*WUc=2h2MHMogFVVdbtf5E27N=hRLM0dm9H;W^u$twkxHO5QV-nm3|;9a(reZKdPs z*`)R$6MOlWO~6uBtD%gwyZDQISa;Ed2tMj-qV^2cbkDxB`AZ`rn`#`GbyzHQV^%MC zQbpw%BrP357QY0@6g!@cBuX$JO4yFfNu&l(LG{%Gcqq>bO`}Wt<%gbmBS)CaR9=n? zi{n`#Sbf&zUUGp`UPbHB`U^al*@}^{R~3x4SXiVj2F-tgwfOtedZ+afzBHa+;OWhB zH|Olm^ML&Gpa3)~2Dj-PgY-m#Lr_B$E`RR2|2SV95&gh%_kuf*aSaGF{*+Tb#9rbM zq32EbEkeTIYsViS(byYV7f9zw$};wuF+bZSQg~6t`%st9QqGhgszJUYG;N|XAZyp% zOg@NU1Q7GDSfk-W0vBT=%^S!3ToEKQcHg#n`bs3)0h=kuVWyqU3R!jr)FZc2~p=ASr-cwDJQDczD<1Eg+Sz82)x<(y{{#q{amFeKFjFZ(($8o=AF`#bkc2;CtZVSlR)2H@Tmy;v@JIO2<}{@_#c z8~Rfi3#~6rDthir5UybDD6mK>@`7zzOWhvN0GSzVUYvEUwq@v5^XwxPost6SDPmD9 z@8L9+0>mxDAl9CjWtmxnpDKZZAf3QTWYbR}PUy_cx>R+ezKnvb%v^)uvxmMa8$6Yb z)~f_PCJ~0RXXGj1@{x39FLg@9@o8PJoF;Dl7imp&RJwyPlrjobe!s8ot!#x|g=rYR z>N?n=f(>tY9JwH->i5|~;2XQi`z#^Z()d^VMepv%OqtN9k#;#nl>zf#nJ~@LR#6=5 zs0xU2BOIiE+3n4mjmU&Py9Oy2rX_!(3QE~UxfQ=N4PFX&Ijd=s`D6SzbpqKG&fUv{ zW`5K7T`&nNFyQZF=PtLz`c8Nbx2^;=Bus4nCn@Yi?m9rm^CZ!$)aL3VPy#Rf^VLyF)>Q430Sa{Dh zig?sLEIfpHih?1XQkW3%k^eSi+cGF52s}9&@DY@P0>`;$Y@IPL2D@;)?~#~Qlk3W2$aq$@aKz;Q(oPVQdj|WG^$>YtaW0eMQyU z5c;MG#X+L+@|Z6;%O|)v#OP@GJFYo7r1cZ9FW+F};PaoSECWB|IneeM4qO$7XRJ1v~6!0;~D*nJ2$Eb;nZ z#0CfAEDOCU z$?D>*eX(n0X5+y)bU4`xyeZq2_j8?%Q-CSHbzJ+;EY&QBkwNK#t^VJ@M79Nz11j3VJk!O zlF1(DxJdfK>(7#{4H6W~bomiRfD4n-1iKS2qIaLDlT^I6I((AG+CA_*qt(R~Q`G8g z@;oTH#rJFoSc(;cJ-5C(H=Vwc8BQ-O$gq7%!;K6}Rs--Ad+SZ^R2PpSg#s}EJOr6Q zM-L!Xnc~HQ`BW_)b4O#MB{HdL&N|cW<0OCgLz9ng?qTgkLqC94T)b*VEVxqjTdQq> zP;`E|Q4tu2lK=C72oW#iz<;GV5jBB!@_#}B*I8YB_}i%NX+{QQH zV=`J1D_GTSeiOrj_Tc^At;{E~?{JwJmBljKC6%3!v7S)dC5pq06SIvg){B%z`L=1W zbko66$b`d{Nj{*Bh*2e!t7l?a!BEy#w%qJK?Wt4D;`6bS$!bSFrT(zMqu_yt>G_sq;mJXZdjd|W{+K=_=58b?RUts@HAM~|0 z2?sY`dhe5o#f=skDT#p(HXwyQA7v?S8)d(-GKz4gIC@c7@`^~{&z;Xo!bP}@s-5tp z#Y8dT7eV@q;te^z9YZoQ7fC9F4ppUo&LEdLyPNtijVlriG5<>u;&TXkrvQ((0-2{U zwK71jw;sxva<6z7_!4c`TKLrb9b9R#<|ES^h&nBckVO__U)~te#m{t?*hWPm1x4Y4 zLOzJH5N;>tL(u$?X<gikh*v)M$ll>&tr;jXL+4YW^17 zhjRTmI^b_Ly9mEImVO&-Lk4=KzbKEG-CMU;6Q)?~EKYBcnWp76T5Qn4l}5vF*60!z zR)AOZ8ALdeR$)W;i-2+OAjNm#7qN`?(Q+wdkBqJz>Ndca!=FQXtd0BRiIWkAs1!ZJ zvy2Ab(cS){lIjMJQtP_{6CSE#<3IOj<+#c|n(x)=A503E>B|mDlazu40%7NNRmS}0 z?PtMB`4dQI*s@{N?lL z@MyVDfKj$baFans!KVbCx{Q*a-ns83Eq$Wjjgel~+R~jeqj+9xy{YrU46Fy3Gl`S0 zk*_y?di2MG?jw);Rg3E~n8-OlGfqC6u!=m^@Xq_O!y-(6f+!qv4kT6gIj{p8ID`UI;?c$8!q>md0WCwUlf0lT)YmeT}Jg+m?InB6y!~agRm~rL%m~`E!Cx^ENQ-ctbob6b|DnY&BENvEuMTR$0_`{c-BW~d_nktfKB0YvZmB$j7&J!Yw_oe+IzSIEqg7Q@AH7}M&RaV_2VYgXLD&2 zBkDr2bCOf)Wh&uwUA{-XKxF#4xHx6Z!|QWGnW=tg@L?LF#J(Y-YsVcsjiV zQ$2tSY_3v0Sakp~wV9j$u>cyXjDsSrV}XlxH~zqmBbSy6D|skVBH~HR#yqM{IsE*Q zD8Ns7ZZkch#Vc{kr9HveMqB-(U(mIH3lg5E>#oMDnHHz*FyBfV!oM|pSpN43vxro6 zAhk!H^T4CVT33>GYZ0;0#kqZytG;i>XcdKVKSb4iuNOO`n1V;yS^Go%DBx4ahVEu% zb$u5qH=nnaG}Yky#)WZyI?67S+8%L zP-kcj>(Ph37Je4+Db1&>?Z%UI3aWf>^xNM-`Dg40ys~nGgFy<(Uf~kk#e;h%wNJCayXd#|Fx(&Bmxz4r*C4R5SY9A1R8Gh&<=)r!y!9231krPSXS27|lS#=C0X8-3-vvf8_r-PW0v z?{qBrQO-vl?l3^Ty{4^(HBnBMSzCNHj63^eIuK^MFk_4+rY~zTgCB*8h?4iqNRvPz zFg`}efESne((2hAm*31R2a{hcOB@BhDe8_4`R5jp(lfvN)O`P*+g*HpYTnq6nb-LYzB6!ay@nFwGm!yn)w zTr#1O01}<40`TYYYFZs{;U=%-skKSC4RKTKm@LgRZ zyz4~d!g$Lt)z`-WGCIsli6cp9p@eBzkdZF|IjdaEz|s)i{$nTRwhy8l zcezFHAbQmuasQ6jP30d9Xx0m#{4)2J|;tm4PzCvumeK|ugzjtNO}L#dE(@y>mRtp0B9e;zDe-WUCQz6Iy{1o#{-FZ$eEICUo) z9II<7|Ke5AJ?EWR9$8v&P5*MX-p?2lkUmSbXS_{zZoS?FBMzN~KfhJ68*gQ=Yoxhg z!=maG>zX*?-`*t1$=YF7UCbgn>|ZuZzo9e|s9o0OwNXASY%YjHf< z))DHOG^J#u5APYwKBsheu{rrX;CR081A&iS2=V!21qFr3Q7Xc}3i`yP#vYkcQy(Su z>u1$eCmIgHB2RFTwV2BDjb9s2b3XzI2#NX>6vC+Gia%UXsfgUYzYaPsEX995kZXVry;$(PqF?`E5bO0X6^iifvf1EEt zr|GEPNKR5hCz!X3Oj;(=!_9L*(CYJP>)R8C^BEF=jog!T&?^dHA_eFb`TT!^+sq}B z&%Gj>e>mcx=~r3pSBjH5OO9%K_9}X||Ae)Qo~4?e`9JyJhN&8dMbI+091@pBCw+y3VPj(`LGD}syv%4t-1XsbR`c}Ruq@lh4aJSgV?T~+tDcgkv`PlH6) z?-`(Op&3X;k+I=Oo?wuS)Fn2p?_TYx6vVi&qas}XgQL;p&`*>&RRxH@YRfN$v4l-2 z?)lyj^h?~DIOxthc7BF?Q!;iyeWlVvx@)G!#LPlDVs>N+WguX~ZI8JY#@G6obzOh- zT`@IE$bIUm!82-k5>)Hv*OFML%E2@^_W@Y#(^F@GH!45pCF$Bhbh9JZq-72^=nN-s zu@z9sMC?O}2J?udEX^oYDNe~^7F0IUvko#%>jDkE|@A>^C4FTl*SZi<# zo#`7AdEgK~zFdd%_g4D-kgMCfZWa+|5SWhX3i z_;9;4RO82c&*>d9olW&QGpcD2lyutxiY2t_m)~WvWNp-M)^II1N5s95a^Gqt%RgT} z3^|Aw@Pu3LCcJTYtWJMQQ|mGO(y5aOdzzX@tZ)2@T%4Dg+x)pheU@=iXLGTV4Yf%P zt+GOVzoF^N7iwt+T#VGS@R*V5`L2*a=dMWRPi~jQrH}zkdD`oEn7p9ts2?&izBs4S zwt^>Sn&OwqzbCbhy~o~ZDPo!vT(WpNI}IC&p0->}rJzHTm)9ffCM>Sa0%C?O-C9~W z!|Cko@9*kX7Lu8?`CsM=gj}fphZh6B7E^6&) zU4)&J>;Teg_D5{O!D?T5X-)d%*uKfZO=G@)3gZy0G&l#kJ&BFuklI7;SwQxA2P`6h zuiKKs0RyA0wc1KV2@$(yNn6#On_15;vGamfteLgm0v?o}EF&TJ-0nQ?va^N$JGm!X ztClUAx;H@rxMVJvKd$dbN7X+M{E{uR?kpdX5nO2(fsFA*v%{k&QovT`gHEAx-mt97 zeSISlIYtc$bJFn%`7kFH)jjfYnXPz^>>D$FI&<&t>T+n?C<$;bG4}UoLn2hp$q{y-qA6C&X2-) z{9RcFa(1fvB11RDKtS@Bm`*AY;krR{rR0U)o=5uamF@$Dnmx(Fa7)c~atu3KCXDiW-`1PCZD=ar(qmUq`=XKz5lvR?{ByST0Wj-+$E63_ zPVQR*cjepNhJVq~XlFKJ$l6#^MD;q1B-E!uWSUi40;TjZwIa6HbmMxW0H|ZD3P-+;~&kd$uL@JVZ?il9(KQX*eemmD$-ll^xnCA9kEBzL zh->#n3S-|IX*q*h4Cbtb{(M~-6^k!lGVc^Opi@?Pzr?B$;)twaRgA?ORtnHr6RlyD zC9%%=_%&=SpXsX_=7?DT&^$+^4J(x=#k zF9E@dl0sil+*Nt`aSMyGuPACh{>+Ux!m55!dfKBns^8*xTD8@m&?Qqdv^)7VZw`tt zk&^zR0y(Ea036aI(zV`9tIuyNj&+IRqpD4`*C5__iE>PT5(jFKST2p4y_$6^RJEir zY|XOgDY^^zc0@ugJ+8qOJl32h6c~6(!Zc@O?@Qa!+*FTe!jdc=UKKKpP*t}TXv7NJ znQdz~N>mOndUEnwG{LJPV_CD^J+`ZT_UhhW!1DdZ@IljCc*5+A)?C)J`^R>tVc8yM z7%mqjfAPsSkLz;w))C`+=up+^L+7&N)S*yFLVab2Xoi;jXvYAA4?ld!Uy!=hgzca7r6d_@r0*> z3vNPCfs7x=5~;s@@Chyqu?x-*NyQH?yf+Wd3u!*jQHXLUWTK%}6bq}4kkZfyL{w}w z@)HhJ4l^x{w0FR=1O%}#AAe2L-JnoXdJ_TxHS_WF{pof0GsIpIBCDaBOO8dZeX7bg5&7^k?%cVk<^ z;YhVVxxIt3R7&Bc0!?#qahdCDyGp;w6((dCON=KB`SV3(xAn!N@;7NmZr3-20OHuF z_xZW^j_iM;Z^8vOb(eW1tld|gsiiN28rdn`Q}$RX4LLcOCpiQRwUzzh$2Q#4a`)uDmIX)8jUSDc+uml5CatgZ2)@>uh9d{05ajq(_IO1@?HW z1Ej1oH5YobdRDR))15VHiYnP0_^`*a;Pig`19N%x?dd;{Zf<${q}VIYI4-^;U6Te& z49%xo47wDel+ng1jwZ<}jU429M@vL?S!s?v%Th692Gh`Hf(Sv=p*2=`G!+Xw5BdU7 z%RIw3?`gbw#Jf3K zY$pVLI$~3>D|hB*fotHh6$QB~bP{5JSsiZ90!6wfNc>*v7%|i=Di3Ipo9Xg@8}XK= zvBYLD;zQil+1iIzb2aKQiyRi_5f|=Dk=%1O8>hoLDE&AISEM-b=Taj_lJ?T%FzMh# zK!>4PV^zsJ7RGBvwVi?(6n%A}3ENCQ6*EWb(qeT5%-P(S-_qx%J8L6e0cL2q^S4@) zb*jnuAbb=QcSYq`kp@;h_HYwi>HDAl#wJek{~eWUG13(sPSh+64U{lc(vk5708%sI zwa%vAlK_%Osme195tvttPY5-{)|2&8wy%hz#g^&e*?T-z}zLi1lkF(QN4I&ns z{={b34XEBo)Lwj_msrjezDyfD4c!{vZ8!4e4ah=mq)ZoTO5$gM{+K}5R((tl)N)#f zdtYDsZM2qcn=2^7D0r1M7LaT_eLUyW{Tm!8;nQldBm41Z;tn!m#iH#|Kk$UMc1;;u)^ zzi9f`?_q(=p4+=kbmpF@~fas`hJ2D=&t!P%Y(wxaZU@G+hPZ4%#eRHm#69IRu4 zsT+jxI}$!_Z#5JfNh(=hAS-?}=xjuoMYLc9@mmj!IHh@!XbjfKcejp{OC$PY3I6TV zHq8#2MTM}2$R>8`yyZ;e^8DRAXk_(MXL)__?Z<15CCjVR29wpe_0_f})8cmL_lHIz zzjj0s^IE|x9q}dIz(}R!w#*_An2~l;S1t9iQ%2trefG0A9ZEcE`2m9Vxf=dtiX6ZB zoYP*t(s}8AuuB%k(DZ6#B6#83+F6jK-i--;UxWqOtZJD}%Ua|cMGD$Fd%Xgv(XPV~ z=>Si3rmNp3Nz28_rU!*536WDax=vQLGI*Bn_p=)J(tJ(wv-YTvm&V7gDtOF%xH>X5 zOg8xAFPf{sqqT^y7a>DOw)F1v*5&%MDbA{VDZI{GQ=6IxAs48xBdl1Hb|_8P>PZ{o zheE6g?CyOyr)~)^I6)JccbpPuB2HAHuMR=G(@GpTG$3<%xu|{SGhf@t`FwqC(tudL zaMAV#lI`A^i~X6?3a9Q^8dO@X_9qqm=RqpESgd38)i3Cud7W#L^XD4AWMro?$uSA0 zR1P=9>kSDA7l3nM`{Cx{o2>|o;Pr!^50xq%fvqnp2P8`Ae%!wPb)xD^Lj zV-xtzM+0rEOnlmO)uH=)Xo%v|i&JB(pR?Yc5-$*G&Z~53QUO;!e{Apv)VWjc3-JcGF@ z7t`TZ`wc~fW)w~1Gn!=LQU`FAB`!Z(+ZlR=I$nhewep{TLOZq+anavh$oS~E09>7? zGVXvqj_Ee(NBKw<;c%HL5mfTURj-{+iJ;6RL@b(^7QRXBXen#5nigunyGi;eRzhn2 zf+3fhzZFU-e`V&hIRY~c^kLCV#E%_y#bOuoKf5TnROnMH)Jh2#_tlcvPkuc(n1?kfQ2N=N&)I|EsX8oU(cMWd0tvESMf$Hrb z%II=rJ73XO)5V;DIDUcK9*atE;m~$pV$4jh{$RYOhJJg$>YQyHQlPPaAtl8(L6%9f z&D*3gW?r*07GbE`5?ASzU>JxGJlWQy&EnRAp4&T*HdJhLr87Zg=(34Fl0CVz@6#Bh z2ML=2t}^@uJyuCmp~ffDObyxq4X)36Q)+b`$oIQ)u^PB5)eOxh%6w9o5Yfh+`kaCJ z%o>J2bLu|)AxGW%9>XFI@|!b)4D3y86m=c;JRdKT=+BGjC~N^xTuS z7*PswkyOu$ONt8zuHdyy{1RTbot2fHVkAg^S4>t#-PIIVV{|%8GZrlNrv_gpC}KZ@ ztXzE5rQa_{ zG?XENdmLeNRrlt1Lhdu8;UHOLCYFh9a%n*L{y+ES+M_MZfu5c5Ly&kFwe$f!m&nkx zUMK3LuB<87luYu~?U3Xt;gfI6Tl#bJ+Cv;YwHSVWry@iorsW(9Ewh+&Xhg772qP2D zw~Y^d&?nhmHFl2Bg*@Sm%0mITV~&%z$@;Hd?O47SDo|*9l~egJ7rLa8o)!(#OuQsS z^{s2fQ!vlq666huBshka7Jf0SdtV!j?n1wDoHQJ7|IPHPWQYBO2FESzW=ggWPfPkV zyc5<5cFK-_t~BOp_jH{jn>6%R)p6AG9Zu=o076Pc40Z_pN$_$3{;^iLj7&r3!L+K? zCNcCcK2Xkw(N`Q~(IPLFwD1ra2hN&CFfOH(nK2F5xFAGG1v1!D^7}VkUcE*xDx#c8 zRj1M~=9&Kd{;tt}mAH*RzdVt9Dwk7F038K!hM)elxW4g3`T9^@XU8c(@wA|q)~!^{ zHEuKw!j#Q6xY@aVsGGxcfH-`*uKs~EJ6B^sm)Jaooi>T_p%B|aOS>w@*DK4KUD_?L zleewkJ0!6u`fny=%&5E-{8kr^6~2Q6Cz^g~Osa6O%IsP+n2XnfnPL7E$dB^tW%8cSKFJ;;12D0?O&m{9IkeV`V^dytSG@q+mQkhxCg@)4} zp`SRxY*n9yR#xvLNWk@II|XC@fjqOCIw>vvoLzbxdmF#bg%wZ3mjFI=WS({+H-0of7qFRT8B8SJK7gVpIPF&*IER|SG zD9=m|08%b$mJFl<^GDVhE@^s0wbJ&yhIu@jGb*Q)qgWW<`ES)c>oqQ$_z`{Ar!zY9 zt#xpQ%?7g#Y6)ZKVZ%3LgRHX2 z95ZlAG7d{5N}U`(3Nh;2Du`$#W$E@d1&)}EsL7Rr;4^igdR2?1#Pil)AK`OQePYqw zIe+%!B{<#-;eBDCmSV`Dw2@j6KaY5$RqB#A2K4J=)T-NF+pM73^gy%Sf;5a7S(WHI zlO$v73N(IQ1$)+_<${M(?!Yy?A+n%@7WA4mrHRnPqM^>mTsbE5cKM{Q=)G4@7XT(s1HHZ9#P$e{c!phAJNCYU*C^A%nGWd5;P5e3NmV< zRpX*tMSE(ewh0&L5&?Hjr`3z#N0LX%(6@Db%#pefN*n4P#ALZBN@C-skOt}Ii;m?Rt?V65fqj>eRh_e3$d85A!-WHU))!IqE%51N8$^U31_k4I_l zV@bOT-)1*GrAKribIft#;?lu#(Zn}^Mv%SEEK6asyoUHV7vIhO=I z$6NO|YL}~{ICe&=qV2->&)-ELPieK=0Yjk{Yz(sCp$h(_L9GwEiPV>KjyRRY9ljSn zq_qL76|D1~OfI_Ex#BLfAA55WzZ`U8`kXukE0<8&DGD*Z8g`ZtvXy)ca(cv{)zR9V zNyfRzTcSfVf=7_Gk<`bb90DX zRF;o6V57xDBq*1oKO3C#D%HisU6+?VT_^bfJij`TCI4KnpUbXgJWLW+cGgRx>u!SXL^CE|%jeT5Ihu$3I;=!fd@PU*Gm>7{K?-oi8hG=~5TbJiAH zBkVtK1>Sm5wF@LM3mW1@y^MN}PwF+5$iARFvsr}k+&_6gxQ+vwDO|GITm-4yUY-{ox< zTilzC{-UxCrRR_+gLDZh3c|PE{p9nz1B3hK{`9S#9QHJKfxzhtXXeagM#BP6dIhT? zG}}WgXF(aYq}ZGC4)v(B(C>m|62E8!{yv=T&v^c--&?|^9L*5792uWjJFEfX&4I7W zJGzKuGWlG;<}L|<-eSYiIRU618c=TNd=Kdd|>{`JN`{O?aRjNiZf#D8q__5bxmK&(NC zQbMNg=5?pjmLZfzfu<&>I?o^`Z3e%*w{qYO(jf=ISlJ~o@Chu}{P+oM$qXebEimU> zyNZ=@e=3H>tFFoXbv-7 zqBg}OVo8TNYK*WP|2*(U`@et!O~l^weto{_@7WT_mb8&_aAF>@N?NgqBcKgIq9#ZO z7&LkeAe43D*^-iHKSUeZ5smdFp-abCRM`|SV>5&($IP?Snqf$3#z(XXaaDf&Vnz~| zwEZk6w>%F5^d9`m`)f`5@1B$==Ieu;<`vl-I|jcs7ibm4moO0U+N_i!dvTh6qKbvc zLfbb?i(oHpV?^=5Z$F1V_(;>{grP%yuC>*9Z9=8TE8l(^m)?y9%|x5v3mr3{b{(s> zPLrzo$_J{bwrGM!;z{f+VFU}R!Gv1-K#s-=R=G-#y8cr~pyBI0@*n>^koXr&adG`l z-)1!I(e7gR>imt=;td{R+*Qot15OY4_kW9pq_MDeHPAcwlI(T(=j~(?U8WZ~a!TR> zVQ-J|Ce{f``p7k6IRCfZ??*&dryjo_Vf^QTu>bAX)zkmW{-6H;=L^Z+zg1V^PpaM} z%VeAkWX8o+Ly~o%saL5?tzXaOpu6k3c0^<(GZgs1rycUaB(AKpReLeXqlN^Iy!j+x zzGJh&%3mQ$1md26&W}l^<}%9yCZ-^Y{i0y#h86TE%l+bfEh>DzND1pC&;!Ce?PJJ5w9OHgATL4cF&{Eh}Q07PiHGk%t~GdA=P{ zY;~#x<5od%n2G?VwAS7cBq*0)FmK$SsL#ZOajy)oFAS zVb1G6cToRM09Q5cf*kI!9;`}46f6u<+M#N3u*SfqVl#k~q-H%3ogY7%kGg!Gs_rg$ zK{FQ7eOz`u{xmZPqnX_XY6t{l6o1$puq1w%+;jin(FVsVmX% z?TGY3jv~vRyn0tx;EiH~rJ&TjTK968K$79L#UJ%s9N?_@_2;Z|oE9<3V$@W#{%L6X zH)XUK=jQ9p+C@J5pKOWRyp2z0$)uxc)>-N@Kn!15O;1g$vVFM!n%Yk@#e(FOy8LO zr^5lmWt}YACUbpFj9Id$ug?r0l?=bdP6ifX4kKKvLYaGAzcn9MX{Kx|eTqJSm`NG} zXyS>gt;9WM(Ybaly*a~eSlWjB1N z-vYNPw2GU@?+0(yDpN8W-||3m=O)m1q2iA-hTL7Xs>x%Wcv>{cbf2}fv}s+% zLRDVp8l4Geg&r>{lRF2KcI=jya11v^RVw1hF){z6Dp)*(=jZzNjhOfh&6vXi=Tio! z*j=$=95eXgD zH!nAV19E;*d`8X^rZgw~VJRg9zNx9npUr8d51oBJQ=m|H{#uA?*JPzYZ0Rb1~eWwW^YAdfpbOE8d!Z zC&1PUVOh{NkswQ5eCmgy)!op4jfvI|etWx6l`g1^=H_E|D*l`f9iIG_y)x$~*k2hg zy}ylZr>`e^S{Lqmsn1K*Sym@+b_P8EEB^Yj=x?2sy-$9#I|Sn zaD6uuaYCb4zliX_3sluD9GS_*L)<_I-3jlRWuuNn_8i+2ODGLZgD>9yroiLGcT<>H z@g;rNXL*n>@<|E)oWwD_kM_+mzL}g7oN(W=D$(tA$Nuy-wY&NM>8)gj)>;F;eY})(0%p!Ms=?$5#e7z;4s05G9lj(OSet!K z`^t6w2aUSNZ((#M-3wNBDIvcg65fEW;($vQjZalt#~3uFSATd)t*m^YHe^+8b*Z9E zpmz!WRHgdE%ui41NtvFQ(!7IkJC%&-R&9_1y!T$Tm`u+^EI}=hd|g^^D`Y3FsrzkK zQQB54NaLRee6Y~E>q~)W1dPvmqo%W=<-V8g<~;hBr7h|j)^xIFMgKgoGkRXzke<$K z0(>5mBdUUBaMZ6KDDJ2sNW%F2mb>q|dcE)=)mFn#ZFHanbm$6?r@J%y=fMe4Ak5m~=dAJPd^VrdU3E6!vib05mNg^rTbqnFeH-pRa^Lmm(Dmkb6x2}TKc7-Ic&OBQ? z<6>R%Yo&kH9jwiqid+zfTn9e;e8#&->r;u&fhwpZ zkA~dB%6(!r<09K*K&hJ|`j&R`(z7p5lgz}3jSs>ZJ5nhty$`C9eBt<6QPyVo(m}IyM3?#(4!Lo0LDHHL` z;AtWw6AQoO9`}@-!Go$L+SlYG4SWrTV-KR2o1O}ivtRGf(irNyr)EDFRbCI^sID5iR{&M*SKdTegCryO{CobiHW5Z?U$sDwy#@VLOG8HKHl5cGU`Yh&TN^<2S z&}@uo72rzmDw!#{uJeO#aJxthQ957usPp__7Tal2VO+5U?A-f+#6K~nzzmklEx9E3 z`J7~b5;P;bM9 z#34!1HM5=*Q)4U>V3rib6N}t>{yKuA&;`rF4pV$_m##UiJihBk6Z9_No0~UIg7V0^ z;MIpn7xr8;K5x*QPst6p5sPNNUux~WyYO#E9m3qVH>HZP7sFX2_=ZhwsrBOG@Ow$6 z|n?_g>eniSZzn)HpTB+*ETB=vth*?h-JQ=6810SE*HpW^YZN zoLo>(BxFD)>OZGx^c$;-y)r$Q?oBPDlJ~b^S-%rt)D6k!w-ULA@|{%s*REedF906n zvUJ5vB2I_-))XXzs{u>g`W}Zee+zDujROQT)w(LLsc`FTdT^ymjcLA5 z?Eh-O+RK(pr^Dp8o;Q)+KRE3qS%O>;vbbb6pCa&{#E1ZQbvn@J2lv^e-HleW3hi5 zdZXxB_&@(P7a}e{sD{PD2WDjnYnw*7=t}l1 zdga!k%KCp#2l$mKpE3f?2KHzhQxeqKpl%}4H3`9Nhb$^53V8#sPTe;z`x(vU&BYNP z5a#VE|a51hL7NDW!k6P{kv1L0u>Ix20 z`^gw@Bj!@a?1%JT-O#eN17pXW1sh>wA_1LQi?n%{87yWDp#>}0Te}E{Q#O-;f^8lf zN8Y3*xv;O54N%K$!A(Y;gjn?JSq&k+20lK99FX3OO*M95!m{$ha zE!bjg1sm=XImIwnkqfP=zp`b-={^EtylBpzVO*8`a$-4VHRxYt6G_*Gg_Ko>4LhuA z5%CxZA<-m5^bnyJK}5;RqGlEe7|9!ta03#R!w!$8#ltepvC#kkCtEt~E*(9A?Rq4@ z&5lS{V`=7dpbu#UZZhmTmEma#juH`tFwDD;s?zB8cwQy!obkD3*`bD}7Z}@A#^lys zUL;%0M_bis@eVkojuxdp6@Oa;zqK;-uIozHf5XdyHhx-?=l;DGihyLGO+@EJ_jxpU z+D5(KC@LS6W5b-~T?7lii>(=O;DSxz9)wBjl$O>M)8_zRXrZncf$?wL$d zbe1n}I~CvlVh1RtrY1#c01mU?-k1K#v8fipLQUtj6A4{3JIng^^(ZXcmp2?%M}~0U zES?nWF+1Il-dM5bT`_fHRLo|i$QklBU!(zR@h(1dX`f;(t9&gY;6H0;e`W$M^D!YS z`GR3v+JL=4hTrq2$^|mLx=G=AeVWK)@lh-MUheBmex2}MK}F`4SX1P4%x`bnXQs=8 zb>nANsRm`s`b|7OSP6Qg&TRkyGIzuU95Jtna!lyUdwER?*;@>Jy$9M5%}i>h)TSi@ z#3L({#h5=uv>OMqa|^-2aE&yo6%oCUu#E|J37CEJ39XI%%=FBJ8SiYXU`deIv2Jh7 z;M%wJSxde11Rg&)HAx*yT?Yr7pMa`+^io4EzH%dd^D{fh^UZ{g=}I`> z?iRz>bpc+`D4WXT^yBm;hJ`p#TA%?hyT|e1R$X1oFjHt8c?V=9xiRT*9CFcLuK1TCM-swWscsqX?9?< z3*LJzkK3)qDft8jT6qVa6um|MOePyf$sc@HrWFgCC^Q%v2+Wv5MX{QQWa-%5R*xB2 z;=q$G`pM0lCPLmCOKz)6Lr06Qk0Cpk*uU$I%s1*MdP?$Yct3xrPfl%XQb#jbA_=b& zqB2Z+aP~!lFdZ)%oPZLDmc11;BU;iOSoZ^c4XF*jXm`3hU~`?=97GN{NHB?P3bU&L z`&>2{(k66=*iVznx1x%H%W4jQAo?OnNREzk!lB2(0=!M~7jq)9o2kmNmJ?)^sDF)| zB5J*O;cvHfueq`RfqDy}q!Ls^B~|%-lk6)mdNHAJH2C{`Q~{L($6o(jvc!0(pRqM; zJ{@*G2of?_p86Zn)`PrylK--2!Cb!sCo9M>=&4jJB|8LbNEG*Lkz`~(w8~(GFZ2ZV z#42Nz8%wxT4HAUmJcR;l*7)>?Bk08);5{p-*I}VTDbnJ) zc44f$!%wkJHht}^;KAdz1jO3!d}QrqinKM4zNCGLSaEPwR7d!TA+N2DblvNF_}fUmG7^V~|fqtHNvc z*?`ER9$eK;twn}vZ6_t?1H%WVdr1f`U#cX3)liDm$S3RhR7Mp`(%fnADLS1bT;zb2Hkn@RWD3Up$fdr#9l&ZcP!eZ@Fvg9}OgDFcq^e)&-L z_Rf^b$y$JVo6F^7%;Y4@aClD-V=}}Fu^n`Qj-zqeLyA;KY*I0gzLuqcZr|k^3 zpHtAC|EBBaj8})j?VktT9e1WqO6Q*yiZ*t6NJ_M>V10m`+aKJ{<#@a2&lLsNj$m=X zXeEHcZ>x)2KV!Fj~89Zvs=5p}`gGy{wPzd(M@3|bs&D;?+>{xRokd8?M-}_#yMuyC7LpA=fVBJSn zG;e)vP|sj?6VQLeblS{X4dH}l4>x=5$uh427OoBS7TudSEC#rOan%dn$k|PjL%@Kq z{V-R!*(M?Ph1)z<%#`NzB`V1MllIQ}H83P?w%xU88K)X@wMqzzpI^hnvd7Xf;K{hG zuQA}I|6&U*%+bb=7GSTT<2>Z}BPmVP&GJS12`yd`0Rvv~xH3K4IKbf*#*6gPgydlr z$+$Ra=Ht}Dgf>lbO-;!`mGI&JcwPSrbK$|crfBQL+bY$6aJ0$A-+#l|^%3;`+Yb2p z_D^bqY<(PeD?YT9;K-`W#L}%M9{h{S)7X#MQL8vmT9V>H*`?)EF^fd?V%!}6mpWMf zx=ejuOrlCqprM&Q%2k4t8v}FtkE;RvTXd*VeNfxupLo(ubnuGju~rIEu7=%}|8tFS z6-J@Rw#%R;9ZzQt{ANF$ocA>cmKiiA;HaS6E6OljBNAI-zw8{mqK8vKsb{z&=gez$ z-yzU-m>-6-{iVxs>NB;AtIgdJ3hTnp_ussTrlWMgsc8ezJi< zZq>&>SJXHLBSbB+65fv1U;lGUzeA-b#98B}(i;6{$ui5^ykW3}wSpN#*Xqoj&)eP7 zy+y_Yslke6gScx_F03Jf$bBnBp{0DtL%FxqNTkw&M$eZ(g8zV_o;kyxOy&g;r zg0Z13+U&I;3pR5OjQtEdczZ^cpFzDKv|c*sL9ZZLLU~OTQd1yNLQ-3VWgWVB^r{}i zcL;14UE=yNhD^3(%$#DWGHoc*T_^Qe)5)}Rp{q^r006KVvc&yaBeU}*>DJ@0?=-4T2<}2`wZx-$G9-H} zb1}Z8FC@)s4Xwieiks!4$@D^8_tcf$pq$QYlLLd{Ggvf!vN5nEF#q*x)+zSkhv zE@R!7FK~xnGx<4PZP?iXw7Y-WsMmwROsB`5i2vmr*Q9bI$*$ci4eI$~K{o2^I&dNuWgCG}9k z2yNXA@Qmkrvj?VuwtH;sxKw+DHeor`MRnwH?LL9P%Ii@l0UgOngcPAGi&7@7=z3n2 zFlduxxdwd%nrbx&ssNh8P(4t${HrQ%ZYZZ3!Rz_163JVQCj|k=^9V{JdsbGWqgVYe zMJ^0L&YbluRtI4sGU=vOKpDye?OfWcjJ$rmq4%%)j$VAN8C~_za!{Shro8dmz{+6W z3uv$;G=2Us=k(u+$o9eK7~fKbgn@2$t%-fRUK`dsvDc6bT7NzyB<^;gqr1qHP<)6# z^F_1A262VFv7X&xZ$+MoZ&F^{9QNG>;@E8wihTz<`OgET|FVXP)hs89 zzt#nPnGIK7ElXn(dn-k~R;BEy6T`9Au5=ItAc_E?tW>MDNZCH7UYG!7-+q4D&Cw4f z@1gL~gvG&^o6>YP{GjV~glm)&b2!dVJ&0!brx+K5pBM>uslKZ(UZubsP!lC#U;pdV zLY5WX90J}%ulF?P=rm11NKHKS?qgddko8OQaO33_E_G)3n~iEbc3LxG(^Mf-Ma5Rh z@~^>qQ;}k!O2a|67|1n**pBr0`jqh9t4!noj@0+TZh*j&gC9nRY0umYzURV;Uq(i< z1EdN{WA4JLSQ*PgncB&DE7y$+afFLhx-bSaiGZb-(M`-~7EM$dQFa0{%0&1sksY9B zu`zyxm#5cZtl3uPBSSRj|5A2bOcCY@BG=+d)aI!##w}{Y+Tf*Gq*Am(iIn0>TjYdi&w@ znn!sSI_|DAtzgrjz^83P*+Q(j&BAl9FC(Wp2Bcw-=lyheeuoY$hS2C@vGwRRk@bj% zMOs5^ZBe(#GfX}kJtV5Q=gqN?1Q`cWL_nj9qKn8v8o==(L%_^w(O3|YGVz9r{6Tsq&cgN_XUI!>kHaU>l5dQRWwO&q z&n-n!_cHH!M2*JBu5S0%`lOjgstpb}-N9(gZKmi3zUwCPrnR zCi1at(7Z)Hc9!3yA>rs@p3C+o&aIw!kNui|lVQJr<&QB8&NlUi%S;1dN4p$YTLJt1 zr=m*Fpz>y>$kLl?+Re>!d7#2WZo41?vE4aZg9i9EYFXKSUDks>3o@_MOa3){ z1*Urouk%X&dy1yE_=6!oBxqP|W}|`Un^K$^62b3kzkuXojucgV!fO@@BF0_KZcma$0dXJ?zxo=*s#iDQQbtnCIFpUhy6&hs#y;!ovfQ7iO;SxTS1WJ<}fo9{-EI+#xPX$ei#|8?dP~H>b+@f zU)Lzw%4Efdh-U~I(>buij=NU6S>%IbF;;t@%;%}5#Zfhk_lzeJ;wVF_fklg>D64lj z{o}J;%xpO~qGhdiae(F^H$-vFR$nI?oR{H^4?5b;7@fCleL8D#Tv3kEqZd80G&cG^ z57PYTbc3b1Mp=#^HZ_6$EPS2N`XeYcH<-bhEoGB1w>`Op59WPvLf=2;w6d+UAe{lP zscZE5F~1q`yR7Yq@vlL{eO@P36bk8qV!!4^@idZs66~m>Z!4!3-kAAx!u3pVxDIho z$bDNNa;?yN<#>Pi2e0zp{W>#c;`!p`-CYvdh5td&JNX-%@ZnIKxx)pG9?zxGl(}(S zA?Uu;xk&Qj5p)f!R*-@-DeMd&mbu9$>+5_nu7gPcj|36zXdx3xd&%7F`;4F#f#n<$ zJj4LUXq+IY&N@AQ5CMcw@Ag8H$l}?`93~TI?AuDvbh#Wz55u~|pmMTi2YQwOZ=+>m z4*?B{589$`q>g`Vc=4Os8c;Pfi9QRVCJOL4QFezoYT4yE4ZJJc_{ql!Vh%)PAUr0C zMqD3f4MJ`qzfpDlOs-8xLZC)k97FYcoK~w$3P=dx$HXV!>C(1590qIcs5xN>loBYA z3FNMaI6F4eQ#Jggp?I#2apPvrOmPUfUgAW-mL*A$mn9Cq;?KXfSE6fO5w0}{AoJmf z{&=c+Hw{)*bV;-Bnq|}!AH8qKldKGHNagW0rKIC6?eepOtV+)w!m71St(se#EE8I!wHLM9-jEAFR&&vk zymzpkZudGP1%a|8Ed^cy2mPR7D^`EK_z|~!UN`8{?zZBat^Cp6qk$2-O}L2Lo~V>9 z5_q22?8hN#6|grfU~7zM^+}h!IN7qQ-2~c4lsg2(9R;>#RI3p^IxK5Klnh15%%s!A z_%w95h}zqaIFWAvIx!An@>Eo)7ly0l1tmOwfRt}6?f)^A(a?!PfqAipD051Gv*o5m zU+Vr07cx?G&PdaN^r<`E@SABPTA9Bu4(@Kh`UTw(zg)Cy7m#*^@F*&cXd#wZCAt^w zL}`6h*NN+Y%W$T?sstq!Dc?y` zPM-j0R)7Ir&@6@1#?su7Pjcu)uzJw*(PWD3l%=SllculTSjiE1X-jOv%Z(NYtuI&K ztC=2M^S+dJviTTn2TW_B2OxiEMh_7z)XiDK8P_yHeg}Z<-}$?485fc56+}PV!lmpu z%#0f}TWT$0E0;wNvv_kl`W9rE>gY-~B@&gzJDhx)HusGFYAU{O7a<}v$mg&Cp~{Vh zKgAeu3`kTBEx_%HRd9}S$O$v=_s72hntNe~d8&`=Sy0n5#AC?V7a!k#&P6(ZWZb0J zdtWr(FMUjSRdOh_raxk~_71&+EH$oI;VZ=n0#MJHkggO45%cjr3-1-E;q-Tph?hO~ z1_*Wl$`ttvMrfHN2Me|1J>U3A8KHGK;RA8iF6zbTG?0P6W{ZGe$rzZM^M}KnOc=fE z&?D^ibjC}Hjbu7q2=>|`Yu4QR7L6*@d=`L7P9v^uV6HvTKp(;BDWr19iWijeJ96t3ZV$Jb79pYb(121SZ~ zINkAQrTF~d4bixEYSQDJwz0B|tDi(MEr)b=J!4f^pGF2J(z?AzeD%u)#&YL}pQ%F) z(BARH@gwDaPr;7H{JW5as<@ATOKZmsS;6^-xsq;()W-C5V$Q2_Gp&JA_?NuX?~-8K zpFfrAT65|XascU6?G)4876L#D%&=9sEl@4+^4i0YwwMt^W(B_Z`XO~boIHXpfknDoQVU&UV6B$w05 zut*G(WIuLaCJMo8UAY?h{p7r@*V_UD7CeZu*l=j zMs7C@(&l?N%_F$@c8^Fgm{G3S>5VGLmbV|n~O$ZC@ z3ml-7qDHfi)e62jLsG0!+IO<#OW(#DK8Sc`oJ<$fRR@^$?ZXA@ISxoRW^WcZyhjwRR`J#zP zadDf8NXoZVX0|3wkx{;l67iDW@P47zhtwVv?83!tBtv$y;E9~%m9gXE1m`2J!{Wb%ANYW?86&EcR|w9gmx|bB-X8pNFt7={YJH4;!kMZlN2(Gz*2@h%;D($qY zJSXP48G4_4yEhKtF-B+++gGhdYD7l=|L_Wf7%pk!)8LBs!z#9W1ERJk1r7mNt59P^ zOSz7=RyrQ^fCs^1BBgEx96arFE7I_!>TuU3+@}#+PEyx>-?7D_i> z>AN)kFM7dNsLYhUcIa8<3gUPSfr1T5{nQ($@QHL<)pdog~F_|+T`-I7kLj%R^GU(ShkyHt{jTUZR0xP_*BLpjcMc6HJHTskn7 z|I;n(zvk#ToudD?e;&LUw6xgRNUUlL{R$so{9SHM5Nq6Kep#9q2c9hGUvGZ=f(<(_ zUA~}bY{o928!D)sElS(szDQ3G z2V3Vmj650q49a)$ShirtRX?5wHvqTbjcq3j@R7WtsDj$gWCuT5HZMoh%||a)+NA`B zavc`L4^N5aEi8*`Njy6SAKiD@I}F$rQ?!&z9c)lezWMe!Ty(p~T_>230?Az>3wu|F^ut{xv}1#D@n>qWQd~7k^Yb!}oT97TBcFZ? zY?AWyYFftmTH$gX4k?k)bnVL(Q(+FZFKL`#-$pu|r6VTX^V6PA1^y*amAXB$!=V|f zdXQKuh&}6#d$$$WF9~;2PSLU?r#Ccs>$btW)>3KO_0I#BL8Us`QGp7Pm?L?pXsE(* z*!fqCqenn>9ouXglO6V&;tBC!rt#vp9>3rzaH@=7o#okyGjKT2_zYsbo6=YiqodhU zZr2Tv+CK5zUv9RlRNRvE-9^QlQ{I@HtJ)qiuc+9~$q06`xMf4!(b8wzyTEmfb0_Do z60V#o?m;kPqa~Jq%DpQ2@{t8K8GlWs9yVQOmXtq+`uAEw?#UH;vn%|H?qFQ>!gq07 z5z^g5M>jt{*8-BcZSOaK7_pX{vh-?qLbMDkKPTb*qY>Z6Nu!%RiPFszlh7$q*i_Y< zO>|X=&0zg|TJ*-dqrQ5S_MW7%;g$kle_ z=>6wGGpFI#24jn>@z?x3Q!kyLs420|qDpJ>TuXCXq74n4O{Oos8z2|!`ZYzmKKDg1_X)4@Wew8eomQdUu1We2IVE&r?3?b)(6PI& z#2egDaQ}Kh_e3NabMa~2!o732vk{T`rsLL#8~C-aCFS0LYWu!NS5Ubfr5a1r=O}Zi zj8i@CDCj**26x=dC~f?Wk^OhD~- zWT_c%))(Y6Sh40SVK7AsOv`VGYN_Z0myyi2@({FILvyk(iQ;xrXFRp7#88W$dg_0`We{U_2Xe{o(g{Y*?(*Yv(h(+%Gnayl9uw|KH|%OwtV@7 zYrgs#@80>5vjxXC|81wcZ9mvVNa1O4?g%iT0*8VfjlOqNJT>^|K~D1RxOG5$Db0JS z-iqDFw@0%_+jZ8PoCn_YTAnIZgNndmnNa3|www6xStC<@%cX1~Nrnrd*k&msvg@p7 z9iPq5OI^AOdt?ksEpiEOF>gn>)87o+Df7;IsP<(v)+=SuGg(zWlM!96;o@Y;x#lb{ z>)s%pjz-W*vh=YR!7;Q%q_M)3)inEY-|kWy%1Way?-Ox9WzlsQK^+Wr)UML86>Vnu zRQuUi_N(+r_HQE`oX=xH5om%4;f)XO0u44ApA{QVCEoL;-P_XKX1b08IP77CvPQ|5 z_S`&UIUO~$YP#+ACeO6W(B_o}Bx#K8ZWRx!xN==^7{r>bI34H`qd4&3%haoXU1Bz1rT3MZzRS5 zvb|3a>Y~l7NVGri@!v!nZZ*{$qnCB;zyE0S8m?hZHDB%N*+mG`@!Tp zqUHx!`9Jvj3b?46uVEh*1O=4tX6afw1f*l>ZX{(XX#@eKSz>`@>5`W2E@@amx=UKR zK|=f%pZGs-eD6KGbI(0KNF5QA1Lwxjk!UqCy z%!e=>648hP5}u|+?BxpU(BP%u2#lRP1c5gzgtQ_jtZ{VQjF=idcRjH_N6;}GMW53Z zNyZ1DFmv~8DSS&o35ddNrgTecpncfJky_CG>w&Rd0Bqh)&>Hh{2|ak%ukl-s43sQ* zyg(g`E;yAz?GBQBSG2?2rmFJE>0*vGc#7MD!!phwug|=zO6JwA-q6NN*L}-vFZ3w53bIIe7mk-Jr>3LX4^s~y(G_W!dALCp9`-2>cl!HyB?x&^CJ=~zG+u$g}#WRvmO%4GDv;iYXB0A5+ul(7%TX3)5CH~9y(Z5r`2DnG~^tOTv#CK zT(2F1E>HSg4!H}*R`QsGjPESBMQ+^+vTs6n_21r3-izj-+KY~e} z0dNu#ZNR4)db4ucJJj>5mKfBrz^HAmSe+* zBRWF+d@=|xrEl|8PMk9OPzYc29c!-@HO7e>u#^NrNA;4_=X(k&(V|G|I1zojc8;~$ z*F0Rzle!&>#LR|v;<>*lkB-SyS0ZlM&sgBJ?5!f2EF6jcP7G_hK((mWjtF$u2Ya^dgNL&k)N(nX(woECI zZ6=GV6tLmVq6w7^&1Foq3y6y`dTv%z8tjPpej>JODHIqqLrtxb<_JhwLMuiKoqKcu zx6*G;dX4CJQDY{aVG3mcOw+wTW=R1%QP_y|!XOi8V?-{=%iYUX?LL2`2lpV4%k$Z? zo$hU|tE&?)U7meS7Xn0*18HtcVr^*sXi$}hkLG??8RTZV5YQg!Q zo=gb#XP{psL0?NY8C7uLjQw!9f#Hx8ugNSxwe(GYEEbfN(d~$&7=juPaLouxA;kA_ z8w~6Gz@5H|SHrrp7nnC|6wpk^r!Vr54JPm|O0usL!Uj|H*C>y}(IM|qkV=;X*Th2* zHBJq-hgcR(G8QuiqVv*boASEz2MP)c5w#Z5{f3eBT5JK)bUN$u(TA$B3S^SO<8+^- zvwl4&sU@UF!_v+1Ydvk}OxJa2d5nX=-Xn6RRn66|!^)FF`x-)BgPE)clHyNG6UDHZ zHVtdwvZ#7J46J|aShmu*!V_A@f3aUUv8u`a2BvIva&7NMP0*xxMrbpKnS|yee4(WO ztOkra(C;Y%E%L)R+KuI>e}Co*EaI@IU9V)db*laK;K>xxP@DGXi-@b9Sj$9i(N-Dl zxXBsIAp{F)UXIFp0a$erOJY4@2!Pz#lZ!@?MOLAGFWz7Zmm9r`_ziDzr{V^8qOZ2B zkRqf(DR9bNbXY_z7AW*gL+vT8W6HH}LHc{=8Bg2z0romzNc?S{8A0a-kfwkI0Ebj$ z;=M~od_d}q589X!yFT-%rPAT)m~grdXYTK%?i!#nPZu~8 zg&5N_=XQ7jz*_GO7y08*#(YpBYS?S2?sK|~)=R$qLe*(6bcSB9yuSG9r6$4pHzc*Q zJ6-+hMY1cU0JmbDH3j(m=AhR!E>nkc+pdP%3(eXwLS6+D*pcFc#K;_MocH)lIRfVu zJS}@o_NFu%oUE(miTJrwRjyUYIdG@+xt0%k@XF7i*-aED>c)06UM$U1ceoHhY;|qo zw|>@}E!;5sQjWRjX?!;p*eS;T!YakC<4=@0|4JUN4bUYyhGl6t;dwD7uIr(Q8m25T z=ecm(R^_L}LUZ-se$X}Nm@E0=j$wCE67|m7^EoxrALiZDd`4W5K$QlzE2`SN+85bJ z?s#kG64DeII#>^VHz7sS){-IK$5)6wx&VqY)4a3RT@K< zI}}c0lT+RWE@cUFGSPSydR1KTvcF`qQ^47vI7X{sq@pDA!+FXSy8XtmXQu;q8IJ8d zRs0yVyD>OmN|C4a(#wptWFAdvx} zc$U2lK-ff16-tv~;F7%NKzm#FZ2Vi}v|x=nL8t>ShVD6Iw_P^sy8s#P@dOY!{HS)bs0avt7$NC2a ztpq*lrz*2|-J7DwuuG~JCDf(fTqPARgQp5z^_lc=>tf97`mIH5<`tsYa6rGk1EC^z z$SWosIjhqgok#+YsqwX-XgzMeMPv%OyrGR*gAl*T#f zv@8XyrNy*@GhHx^rTH%W`-!^lwtKms7*v%)f_0?c)7oDb?Jks(&FJx9?RT*s*D^iU zNr|O=bP~Z8kNI6KX34FR1)XMl2uOe-%)FD^;UJaf646eW-ZJ61ub@1<`1FL1I8o$n zUmQ05T7sP*yN0Gc8!}iOd1?aol9GlF&tB#Jo9)G6HR3k#3C1|?M){A3554J5&-R=u(04wP$x|qresxMe>RGtNB>7z>}D#;rK ze9e0t;P%vs5zUP~Ui?`a$ye5JafSnCdg)llRi{mTcrdLLZF-G-VT}@mGD+Sx`b^d{ z@)lRb{cV*`(D7pQg8N+beE*?(S94SeV)zheB~!WeEf%)?gFS{A8WvpE ztvNjwQd8`eNlAYVHhi3~I&il&{9(e-qHq0P2pswF0Ya1J0lH!~tI`Eb8ExayYX)SP zxMv3RJKr>1z89+#ZpLB5vdd5NN0pYPd0aJQ|4jI0*WJ){1VZL0zbE({%ty5l1ZRC* z$f+7=K5l$IDw^0G>1?NFgu+RD?W=%pfj~x&n}b*5Lcnm&k9$PJ1&W#WsqTYq_7DAt z(wqWc#?>a^1dq)bSYliV1(x9KY-)?~UG$BdtoOO2WPKC2lKOm@yzFFa+0C?ZY9{NX zmOYKLCiZ0~SMQWT&Leq``NSvqQ{|cbbLlu5Dc+fOpLq{@{;8v)=Gr%c?4NV#BDJ6N z_B*M#LIF!jay%|0xwGt=E|$vl*_5mA!cET8rS@`${8-1VyjcKFxaILRl?&Dd&c2;6 z@@PbnN%U#lu{m|!TBSqtO5gWfdC6!Zz-d+$lXj&x40=12CFv7KBG*r}h6&eUUTYG1 zpDTE|(e3Bad*0@w zy=*XWn3oFrjK$)|q1Rj^RVAL?Yz93J6YgO=BtoJ=dNNNdeQe5-ChBHmPoB}`ywZ^2|nj8w6y$4_8+Jd=utZ5(h?XHEm5X-1oxZ_B~Tlv)61}{d{En+tz5a}Z26@`(u1l%aZ0a%@u z-{u*?qWvM%mD{y*2GlN!L+b_#d2B0)o|!a)v2>AUL3}nuQ3yU~)=yxBzriSR7Hs`< zhE|!s@sxj}y?N6r^e{qp@i@ezn|v9s{Z)iyW`q#qTGnen1z!1bN7olp>KQ}c)+aFsKK zppV9`04!zMMzq5Dac3M4VOO9cTkI2{iRDSdtwg!951&he4nSoChu%j?tw9&!Uap7k z>+~f$X1UtA%h^WX^1q8YB3D;Ud74~Mtf%5T{8(#HXfD-aT0U%=+hvhRv0F@4e8Pp) zP}V?Gp_Ru&lD3hUe5CInSk{#bUv>FejIl)F8Yv^H+1N=*fxxnIL<&h`fcm~oLiGB8 zO~)x6xZ%g0oQVNE0e85rPZyeliyV7fldZ4Q%1Kr@*H?1C-@-+ru75UT# z!1S%L4|lktVj_Jdcg~NVtt5RH_R$}RDb7-Qj<8~J++R`AY+@{zC5+LN)+{}NOeXh* zkq3g;eI+b&6jpG)0{krvB>da3CxUaRFQ7flmT&JGogVM7nw7E^7U=5`KJ6UMaO*7E z%D&Of*~mh#GfDn&fV?%d(2XRXytHWN&RBiRiFs)!xpMgRNGS~#?yg~2ZEow3g%w7) zCR|?&mttj5YB8$Ub4iKBD#SQJt3!#5RHqQjcwlV9B zoB8lyz$cF~v@3@jKe6wiUIuIjQ<4RL+_TEK-Yc%&ne2J<@@b9cyj{iuEAk2- z!SJvRU0w~eZ?bo|NY7SbV_&?d)=yia#dzc*Wm@=#+cEGsJwZD;H6tst`^B|$aU9o6 zJr~&dS=$>X9@)ez>2RnluUii5a<=RiL(l0=%x&D#KOHShsAbA3 zx3*`C$w1pl<`H&Soe$K&0*xg_fcj|s^Z{(O@qTXW%)pl z*L!#x1BNqgdSxMPek3(Fipl<@_7>9J$tTmi&jv|NmRXkO2i7;-mvPD2xGo_8>t z1JU6RC`C``>-O%Py)ZWQEx9q%li8ndm?zJ;!u!pB^3=1Q`sPG^IB&QhiXIi6sKqC~ zE=ac)HRw>-Ao6-#(>N)KJ<<>%>(!ZRUxn(@-q<1Mz@nIu7{^wxRJZ}>rT1Q9_gA0p zHqkFVa~d7h2cduZIC4k?)UtnlYn7I|-g^VHhpljaE@raukIt2Iy1do|7=k&#A40H8 z3*yv*j?TF$<3jsv(s+K9@CurgvhC-My+WwHa$7UTdlzqGUgbj1fq|xn8I{CdPbEG;hyq;?ViFL(j9e z+C_&cSGY%Du;;?p0{4(O0X>txhJgg;bd;w>Fg)j!^Acp2sv^^8An%4I&KHweW-BR) zjGKbdX~xND2e{0Xg}s$96OXYi9~3nI(t3)W>-NX?ZNBiJY|5})7<<5?dCXf}jZpDIudy(Zreu^??S}M_z=iMKytsHD2h4_X z{jB!cDRGibp2un7;y>3_?X61cpc(<1nErZTkYO4?OeZG5aWaj*l*i-dR0rskAaOPb zi!@;!o77;-iIy^H8p9^WGQ`e?b{H^*=Jdw!HGRy}S3ps`jSjp1K_k+|pI~lF^Kye* zbW%xGUR8=fflGbD!cCs4ffE0NcNGeGH_Cis|%i%iD=HkZHayxikEq_sPl>*BkP?18%QKo#H$V%*Tp`j?Z~ zpLPUURFJG4_+D+J&tA} zh+l_4QcW5W9NG8XbsfMaH2v*|6$e!lFJ6UV2=0%{Yop(8dD8uvndP7Qulqo+bAU`W zoaZlF@oQTR8c8nR2xH7k7rR19^~8Bt_f^D89Yl(_(!G{E6|5TNXSy=^;AX+ zMYPXBJm`eciO<&u^n@)=+p{!-rhx;gP@@-e4#Rj`3~cCkuj;IR0x z0k&fc^U6LJ9osmAMUNJgs}CD`)qH8W1wQIU#wKh{q=b7L=CcN8lGkyWKNTq_+V7Ju zAHeT%^V>`r_O3_I!FCUF8ZuNk_n*C7> zqciM+3U|21EV@_(Z)bAizrhSP?|0U)EC2PtQz9QOfhjKS5$~_Qp81D*{HMKY0N2}9 z89_negP<9<6W*)ihqF*o9Kh%4LC1C~bM8qRP7X7RbSPI<-?mAZ+M>#0ca#nbodda~ zU^A^c83?jx*ptG;#!gt#+6@Au#^HolF*f+db2s2Gnz5Hrl!ds&xW*i?H^K1TBIh;< zr#2`;OW~D9F8j%`+0zzJiEEXVdKua+24rWXyBvYN`9S8D>no;;Fvaz;B=?slgD>ac z*Q&V`G_z@$?unJf89J_qUh4$tfxjL^oGh4b<*n~29YP|EEH($gmbuSNsxH533x{xP zrhoq^oY(B3^zI<}c#(HSi_^{W!iTo7`xut>s(<_IPIV=zRF8X}p&f}Ehu2#53ji=o z(_l`#sD~-NRGjcjEWShYELaSe=}LEc8|gs)@clh<Yu7faqw#PyVcocBNqgfVAW*HD*i(-eaff6r?Ev#4# z7J5h2Vb;}2O5m2Z$P@F)4$Ru+HZmkpTU}5`HE76WFOZ;WJk)!YQk*#zXN>fxA|psas!RfXrUx*8|)IL`$0c+Zw8yXDi>WJ>3t#5&6Dl>hjEAN$fKh z1~j6QMLqec{&jS7{j#`Xsp^TBBKbCtM^5{n=q@Mym|lX{Ao(_@NAX`YB$`vP6noFP z`#1G(hRR+f?=B}Vn05Lu1+0I`-IG0vzoh8BcmArcbD#MqrG4p78E&6{O#Ii3|CsoX zHT0^4fkXL#7AvgtMB%B|hkAdby8l6uRPz=~=znAQn>U`kI$rs|6z%uj{mV4+IdJ>z zvfe)m#@kazO?0sYPMuUoiB@#D*wWlv;hOrq(reSX^@Aw;hbohsqt@J@&jP+!7_fPobh&&cei z^vEb0pJ9HQs_qP}U%$;!3fx5j>nDC6{bY85x@);NtJD91q0O*sx~~hJhw!-A!Knai z-91u6yH4W)u^oE@vxXu7cA;4BzZ;zmhF40@!Zey3r=(?<_6)U@8^S%J&MWq}jjE$4 z!g}oed`u$>)($b4z=}<{Yp|}|N?RQg7&H4^S?^Md)l!oFoJNk zpkx~7G56i7|4QRk%s25I_b{{EcFe9&cv%l!d<)Tjm-gZm2#h5@coA*G;pvco}#$kZ1j;Aww?Kq`;=uB*66y1-Cl0V zx@=mk(KO!f)^6^yew>K?`>%3Adx^*@yA@ewi+1C0mn9|*{(A67*#?`KXkzo!*A|Ou ziR}X30ktZlE;7iWD~H{HOq6oZtT?9{<~LPi&g7Ggxc7ykF-zQms~U?3PG`2Nj2t8g zoU5@xe&~~|Z zGYo`_!^Cm#7p(nH#y&e_#;>I8$ZEVv4v{W6#@Bs%-8)$gm+a$;V`DX3mcUOgBj$zr0bxLz zB|J3_mKon2P-pTQ;&XT7M0@vYd(vpd(6miF9QSgRSPZ8DaKbHRA)pVpnrJ)))J&&& zyPsguoj>(`I%2JXqlNu_I1fb8e}i%yaUCbrl;@Oan16; z1}$2Vsd^eLz`FF@@^eBbR$EqQR9w#pxs+8^3FV;#)x5=GKX&sVNvG14dh$+3;oxr` zm|uigoB>p0#nSosoI!})|LiEwzoAu zMCsLj0NeUL6eL#vl;D}*o9EVzFf!w(FbCV^R>NyVs;Rdj2Bs8gkuPU^7_yIqdD)XU z`EseQAd11n9);G6np1ob#ad}#-WUWTrF*J6ZVM0T*G8k-9qFk9eBJ`vm=#E{(! zs$5Ilti0A@i$jrzmVw0>f95ICwVv3C0ol2d>|KQV5Sk(Vo2!G8@+Cf`Qh7x5Rx%c; zE2|gjSIa0>bS2u%g5+L;ab*lX8rYKrW<>HsvRq_&MB+pCp!nUlB1g7uVz)^Fs2CQU z{RLXXM*@&RxMhkxgs{RKqDQ+UIkp&0P9}lkog!=N*gNMYDm_!DIx6PcDeruBslnt- zmqn7c)qts%BWb)Q2!u1AV~`H9BKr~oC#I@0;WH3QX_PLjtzSEP+A68u2@wLYjOfSUzrcY$IMIVRcc^J0D8CEQ+_qr)Q z(PH(`Y`HY76y1r(HK6m;8X%u$_4qS$fP9h_-*rsI4MaZ8_?vclFN3`L&Eb5x=-lfz zfK~zz^3X(Tt6Ow#pBR|_E5BST_75!tmbQZaO`+~Vfq7#tbSGZ8^z}gl67?^D3;#{s zOX^%iszNFrK+)q2aZ|Wgf3NS}(j*cs*Q$iH?#BNkfK>Ch?7hanlYQ?EE(>3na&2;foW-aWG9Xk9cEh%cV7z8lK^`oj-CY?_NKcYW!L4R)qjOXM{mN!k z=eY1)vYT5A2U5BQoXXt5Wuibv~k@V5OKOdg8*axVf-3Wy37!a_Lg$fiRtb`@h z%`AC&wi^pRrO~)+NZx69Z|hkEombwD9do$wDV{%-kB}B~-Mk9B)!8WUn^|84hx^w& z<$hd3*14)$$Tpz&on>RhJL8R{u@}h&?-390-gnz7lLuYHOc;01A$+!+<5(K%^S>Tw z+TA_Nt-82^Q1`?PzS^X6c_A1|)&(__1=1#__ulDwqY%c5ahONa{soWz!Du5zQo&^Z z6{LK^u09Qhy1Wn=`wb(1oyXAndP(G*a(-w0Lwq)94LtEHphH@;{%?x@QHz>I-4)Yw z53v8RJht$O^5ii=P}&5Y(U{3xg&1Mx&{7xbf1}|Slq*y>5Wt2nMTMnxODF3)LAd%M z1TkTnpvFoqUs1$0J@pZZ89^jlr5;(R22N4}R~XC5)1enh_S`GUs#dQ$4Z((9p6Y>y zPQjhnNv{b_-EGaZSx>o{ftS>Z**QW%`GoeVVanVB`-K(ob{G%c+Ibb3nGh}izI<0w?Fmm#08##`2%55d3uq=h7sfEhaL~3XCBv5os zA4FuM+9kuD4obKs~#7F>J$z4j9=s!nWYg@1#`{?{0k|4X2>-;maGgboalrg9PYeU`m*`bq-RWr}m5-seJk2M9!K-wkI_sKH7HKh^?qAm5K( zmRO;?{&|mXJthf3bs=oG)68T?ZSFq0yc(Yny^xKsG#IgUlt%`e2dU(D_21pQ+|H#? z3i=LT&Sv5enP}F+>zSa3%GYs1tnU`md&RJy{CYrWj%wI)MTn63@w&45VVKcaP}@Ud z;OEqkFcBNVGBqdF$xh5%HtMMOUk?VJd)H2OL7+IqG^1#cRhLW7UPR0ZTfYTfh#eg> z_x>|JKnuO0hmtytJgoyupH*5-PAxmLUVZ2|*s}VL_{DO9AaDanLP?f%Y*wGA*&y-= z^CVe}bBG0FUT~%@`S}(v^$e8UAQX(A=p@9XT)y`vhh#-zmrlmjj{(sdmxznMzE=wV z!iZzq|Ms&DUf)*|%i1;EOzPgeXEr@0nbM}%y00%{DAxl$W3j|WM2xE+F}2`2B7Iri zp0+_xB`jnjcC?M}r=3ses#ln@Ez`ICr1*HdtwaL?pgeOo;3V^{R9H?SM(HqkvdOYd zTozx(AQc5OL1dT)5p+*bNTn->=yl@QC-ukYGKnXk*G#Djii8yy4V#1A7q+ab_*4VD zRbQW$6fYz|bAc5e$zCF9 zQfMuZh;yK0f2jy+uw*>Jh(TIH>0>=SHQNFJg-=dsK!yv2-SYn&Ma1+v&DdZd>O=yW-Zg zd7@&bqzHK&J6cH{a1;$0Iufd(IH*!0k{YyPw1E+hFTUMR?GA3T7>dNU5P4L!Rzdqi z5?73Kc;E*t6*?QlRpK%=do+4m)#^o606I{q?{Gr8|_ft;a z)Muy(sHr5bj`aeDB(C7mj&CcDboKJT9wf{--F|(lErc5KYD7}r&M#P0eY_`~@X51) zp!Rzv$9hR+EJD;Y5+o)lT}t@m(cc-3Jm1Cx{A5f`c$iRa?imHh$exk0V-Y@i*o%}N zkrO$YlKt|HuKpFQk__u!$9?8Q+%Mu$Fw7bx+n*-BxyS@1t{@A>^L;#9IZ}w{8{brx zhVSKl?w8*MxG(X2xgQ6t-d7ZyW(SlScn}$zIZ{-g=t^|Q6cfC-vV+A4wJi{%J&w7< zv%{e%qNes2_T-Hjocy{sVGbq1{_;%hD2()colc>Ew8x)t{-CqAodtR@=`Jpk>&Qb_ za8qpXF7;~5I$3p{lUe&th3UA|iDRH&?GdS_)x0ZnD=Uc6zdmy#2mFTBBG6&*f>)+i zadfh{4im5-N_)+vtSGFtLy^>AaEc~DCm7(8aCXX)J@>{VPVGA@cNr6RnL_K_ z#g77%$z8lioedwUy+W7VSlI^l-Q!WzJ=!L8y-}hR=Y=o~lF`kzt}5o{;!hR-uIxrj7?xc0ON`uoz?}!YNXo-c=KYp^qEm}&7no}#lA3N6O4uF`ywp1)U;27 zCtWZCZ*tE1qPpw=Yvy-7e$z&U&A^Vk!D&9MJmpD66Z zR)MOqpgeL!m4NFQ{~(;Jc;$H09C0{cPb)Gw*tBzbJ7%_-FC-M+kRX2@fP<6nr1QDU zy70AJ;9HI+ZCXh_!&tm!9S=tC$Men_WG4q3k9A12Z)A3T7Ah7IbMtGqO>p4`aklM* zq;+~iwY-teBt3eu*=AT#M)V1nPt*0H>v2tG>n z8-BIM<^n?>BRh-c9~0~+TZcM75&45XSLXTV-HskrL;o^T49T@c*NbEixR-lqsNmNK zyXTY@d6XK1%tJa|1p7#5QGHc43gl0Jt3j$4d6e$=RqpS?{7Lv|OY>XscUk2A6eK%) zTn{3B?wxgK@~V%hIb;}`WU)%;Ea+rLYG2x+uoU}c!Gw!`#_7u}Up1hOWE?O7Zac3_x z$WfFhH?;CKSZ3{r>wwpF0e~Ga^_s3s67i%9-jnnzZLH>gH)pfP#UdHX>PYelL%xOD z;vY{ud+Avi$U0`4S{))ebKOQkN3#R&g6y6Jwy@JG>NakhI6)wZW2#J-cV+`0)GOes zt>N}eSX5%J27s%rC@@$Qe=U2U?gSkT6cb&+AkKJd%Vo81l`&*56~CL`coV7O3wWgaIN)y{UPp~FPDfr!y6ug zv^cnLyiBLM4!J=r>u3S-7bDX*nGjnwd6oRCw$ME| zR}M==czF-fJvQ9;0nJR$2@MS(62AK*67xOUxl;jVqnr0gVe31-G(CCK?v}Z>E{0l* zL(BI$dGVz<)=~Ki?x9W#7QDopwv!}Y=4Wru(lDUOEg>XwX~sivXLg)78!ab;LWXkS zuRKFOjP@ci2E42{Bv;B;H5TJvA3^91!iy6cCS!9%f4bH^np7^PFS(d4wcKn+KO(Mx z!sr4+Y`q#FrSSvU#6Ie4lIp6TPobn>`VrDH(}scbC#N!ZKhe_2yEWO+q|g_sH9_kw zCd>xmdGB&s9_kTA>38W2Z^?n*wjZP?OPCHxc{&lS0ys}BJ0mXD={syXgp~kr?jMq3 zbOFYZJ>`lF%+pl?FIQ?bfH{}maiwhBLvm)1t664a4F~hnPVHLFb{hNH+T%N@W#8oh zjcxsF8RRViS$mO&U9xedj_)@<@K~_zdR5m%BzIWPSi90oW}yd5;gb35Kc4cVa*V{p z{Lqw`umzw2^B)X)jPA&$H3qUzcNkXGrM8f|0n3kf5<%z?u#rh&RL zZtkR8yh7Ycac~WON=c?e#$YZcOgUxI6`H0}sL=Nnb^v%c8`>(M7|6z^+v_=;zij#$ zChz%-%sf%N-&z80c=>7KrJn*Kv+->vZA1h~wO|419W~0Kt#MB{vbFc*MZy!0O5v8w z5o%_}c@pIYbGV>+yx?DHLOC2Jf0!^+|6Ny+PtJ7+E9sNG0;nPb4yJuPjYf}rLm|j2 z+P9F&7l9|N&f}%J8&KVEC&*+2`aq5?n)_xX=a`bUm$jE=7>?9wCHSUQKZLbIEqep1 z2UXoj+#o`J?}3Q!=z{x1yk=|Q1bLNyC0nYxfu*(^Z~h;ME6?leWkl*?{GHxwMM67& z_H*yDP1onh`XyIzU7539NvmvH{X^lOiewfwg>L|pUPG=P9_tB&oQnyLIq%daY zw2vD#+^4zktaOWVeDR73>+;JwT^=(t0drNZ4%8HUdYrDT-KV%VI*%6GS7tvJUGd&g zB)$~kRwFV{RiQ|Hv$E~~SeAN9E&oogHL0JC2b;7kkur`-QH63YYHx{9GQZgR3PiyA5zDMhr#K; zTiM7atqP_P8G}IeUya+N@y`1;?q65`oHAEE67przDZNF1fLHQm(vZR*X*5v&fY2=S@*wnN<-<%|&vDUa`GzZ7pEzlR{n5+9`_tm28}Bd|IHFr}zHL zd4C2NN+G++d%Sc}$usxvwP(ZSKZ&lGb;EQFulc!w;5Y~RFCILrexSqT$%LtownZ&NCiAr%=>LRBlYWnL&+7i+E z@4}3^j8pQAwLq(=7n86=*hJovCkF3R7Xpm>9eoggO(j7cY)-eO6t?2|>p@*&!d2k4 zdm;km$@ZsK{E*?u6JOjVd$p@M!cn1ZKIKNm8W-OpHEHyDzy>?-QyZ0K+MAx?8*`D+ z!?UjgW2wCr02{^i3FfhD%jBzF`*%zF4y6bfekFT_M*Y4kIGZh zVKp%bxlO2=w#u{#;4uO1d;&>6X0Xpex|YU4+ic82Uyj+c(!S6rkWRX)VU0iy z$x?;Cf+f8QoWO9ChsI>c_xM97$7aCQKG#`pjeXv1dW~$7L#}wNO%11eSAw0rR_65*^i16e%Ts!SP?`0c}d=M}}3F|oZGsu7&Rodn!D{}*fV&L!!_MMzhLV{Qnm(zwkmyFinrJS^jN_t0(Q0PQkewTgk9cYJ|@;p$qfDDxy1Uhr}dan-7v z@elCZjoDd>hAi2Bj*U}WSzBAG6*s3O!L3hk`{ntAjRXr1>1AabGfE8xd0WvaRw-!I4Xm_XMfguv(%+##Sl#7M%)|il>3K zQxJ4Vr$?&&-B02iXO?Tqo%PW@pWzN4X17B1>gCXVo{HQUkcq#k9!L(#;YWuQD$fglc98#6Zu8o1JEeGH7S9WdKKBweZ_pDgR7@u zS`My9W~JPwo7jN1SHJ&UxLv`^^6-9nzP(AvgSgX-NGDRdsBGvvjuhp8De|GqI7z(wt%tjIuc zCIA9|Ic1C<#imQTr4j4L4AdH;CsfUPB2gMy$e?S_i$#)cz8wWfMz-#Z2P#HR7OyNm zcon`Iqm&jdrXiEnHQ?<^>@@;Rdv#0#B)N|%;EHVMFO#&DcDXwGd0cR zOPbn6eYuUy1=P*Kg)ia%)g-{u1Y`i^oP83iXXN!ECk)x;cfD-!4 zS0is>V_xstYuBplRx{g8er!$-Y^GV}6%z^aZkMKxe)4c^;D}K?XXE!1$0l}fR_UqU$K&a}Q8jU#G*Y%bJKZsfnx{8n zfwm=|g0!EN_vwvDS3Y0E)zzqn=VKf{(?IKFyL7&7oXY~rzRoi&j{W*(caD^lx?=rh za8FNX{viroyb&pFu7&GhVD%h^bF?5ERMI?pX1x}PfXrdP5&uzKQ4X_h*$UO{K4p?R8==) zTu;SWoejwHdYLK^cE1rMhn;f@x`evb7>2Vd(y;myCZyiqWl;D73@GpIpWz!r7G{G_ zPzkDG{@dhzN&hj4q~qg*lYwRg9pA+t#&tHIO~-jP zq$!eQBz&J6@Ln6*;1i_wmSCHOhl|AOI4PGO1@zJin`xunG*`4$0RJwvZ%H1r>S7S*gCl<|Y zHGg0v$lcQ0x~Jn)eN{_s{CYtXDbYl)er1^-b&)f{Tc%p~H!})cFAVw3S;klj=?ZN0 zBEu5kpXP^{meoYg*;OnUCKmh&HZ31M4iRoDkLcS3%ueD(2$DSSR{Nf#Brry01Z1N_ zdZ3X#-4PN9jn=*$SAV6IWn+()^%vWhRq`@761wI>MUJxdevEHtrcFPGD%1sFRPKhl zcV0kSQOwl^26o33mg0FTawA#6<{%Q?v5p^?|KL6U$`}tge6sYsnerXQ+6LJCFI@D< z=i5zt{v)X^7NqP=`{mzEe`fqv^e@)2o_NtCN=j~JOr)`Y(Jy;jMUMZ6Rnsh!d#y;J ze--clx*!MOJiBXg!zfrNJ1boPA;|Cx6oN3%j1+H|EuZfk6)$>?G>0v3Tuk}O8%N}f z4cp5O*`8*ZY&OyQzSgVFHs=>K61W(;JvL?uW7y=?Oa_9Np+os*o9AVr zr)vsKILTp)&^F)yCwldkWFD9!LlE249k$uqTef3l3kfCD%fdw*UEQTkf z0g(GA^n!Mkp;hmK?P6ZEBxZ{1sfG=@8cR(XJR8~PN}LaHzyd_p^L;}iMDqcV_O6P- zlT{Bxq&%AaXjerY>LRHlPF(j54CCYeCm15M)w zKwigJA*mf?AaosURA0GGmheb(NP8XXlt3z}qm#gIBbfDkEyt`R6VbLJ$4JVW9%jA3 z)V)@|Z>x?tQK2FyZS%E~rq23y9$gePDdexx6p$6ouLq+MpxY^(YXkd&$sc+~Q@aYL zgP^bYUMfx{X+_in>Zo><=diOtHmGmeW;~>Mi z&XS%!eBVpKVOVf1{KnT0dY5)=a$?gt=m^PR_ZXfDEkHd>9?+yQWJtixinc4{?#U;1 zs-Q?rv(d73>QJlVAyJC&@6|yIWoyMhnTXjW0e4D(mY6*onG56zk=rTot`D!i>QXsq zZK3$=^gi~r+FTlA!(sVq*V_8~XSc6f&Y9qh>9TAiK_r+go4{PAjWngICCz*8`k8^)GUri0mKNk=nr$ME7N9rV;Pg7x)sCx@Z~= zbWjIkOTUs;rqIxKzZpS2h`az#>x$DH~SQ zVF;4&rw~cxe>sw}o75EHEzB^5u))8gpO*``|Qh0X<8rYltam8*(07ozjS2^UIUFz1UXNkvjdcr#PhALfBU%VxPXcZEc4Hb zB*xB#+3WW~%JptTC_0&n9netlnjE*ibWgODg*-S%w6I4B+bmCL20HLy_l1RmI2KQ2 ztxO5it2>W_Y#P^HpL3mF@`>@#gJ8|{ZA;0f@nQFZeDYQKs3t0#RX4lL?}z2%J3{fD zdwf?2DCB7faea0q)zDKiFvi`3;ePZHB?FQkO%-ouV;%)qhoTO4oc7D|XhhsXY zoIin*!&c2X%CLvnK18@AOG>UUj0idJKF&<>&usfjWVJ(aWwIa4ox<)~NkT?v{?U@Zj47gsPv(@idzjWRi)i%g8rwup*?j) zt1<1>=a#pF37Sd7I@`LHDNNgiVRKx|Oal4qwzmOq#WiP5QVPnPF@2@g5y`#39_SSR zd}rw0P>~731%4Od6GbEz7vIJNIX7_4XePFjBm?u}ySr6}z(Md#mQ$Zu9k$u({falp z3QIpl^0_c^-v$2B79?>(v-^{&(=NlGm6yeB(#P;6yE;MF7wfq7ImQHx=?+_DPhY{`eOs}BaXdc= zh^B(7gZeyLSLPK2h|gw0De|xIe=KVM9+N4ADTFTMFT8&_{@c#M0+^}m8{eaZEgEDH zAe@=`^f^*BAZJN4;3(_7DIiWvjvDCvEQft%BbSI?eAJR`sd&U1*bU>P`_wx02~=h$ z7+>(Qp?M?1*_brZh^gT9y^q%Rp{nu%9`M-IV-+7G6l1)x^|jMX{>^C|H};8M2u|Ip z+&N@R-gXXB7c2W-J%mRhiS}w#R<#fzJGI5OtmS+_D&u-J1?Sh3;<*Ru%cs=R$CgfU zPZ{3!(FO4oHIj=*od74@Poz|Z#zSd^t$|Oh(M-CoE{^`HU}d3&xSYNwcM_CfK(WwI zJ#aPJv&lh`Csqkg;*72+7vx@`PY1E%Wty^dHcQ{h?5r%z_wP}~wYjm+2->pGvFP&x z^ou#qnNQte$;-*bbJVperx^SQM1j%bGUSx8aRaiORD45jk3Ss$-5wt|D7#qzoE3Va zM8J^xk0F|SV1n0wI{xtp)&?~UkpFg2{o8^3S?r$(KuBVNe+DXWeC+=nfNVjD^UvTR z)RezR`}gqF&;DlvWxU_x1lfiZvczS`{@WulTJE3tk0Bl>EcefZ3;yF*ij6&xgbm-< z31xR;wIMB#z4m+h93Hqq7P~l2<6I0dWUorT8?NOe25Jt2`zUkwMmI989N&%h#fAHb z*K;ZjWRo>-50u5s>CTDm(urzUxpcRY+h4P8^g#>f)#S_?IibeD&B?uhouqs4o^(`H zrJO}t67izr?W`ytwU3<~*_6`v5~r-Fn>hC9B93ovUix7$B20$23@6oRoR$1K`U#$noL_Pl+)xzpRS&& z8d6msq+v=W->sb<(XKT|O*-=~;~!5@iBIKmJ~_yr(V(z2;IS2`iv9H@Rwf<_K!{CxOqm%>3XUp$S9lr(0C4y6;mSgb zfb_;Ycqgr}5N@tf;L@KM9Ei+*s;~8w$VGuVxixX`%T@ldL>)S@LUS=#@%UKgYm{KE z!$@KwkG>ow^g-FmNr|ysiT4onuIr~{s)&(jeLGP|Pg7V5SNt@w zfF$ELRRbwNF^Ug)8ALC~O>bpGkSM(wZ^6yqG@WXx7c|Na5I_JRI*Be3fDL{xvpw}6OLlO{v69q` zy_JC4bq*@;zkxcLMLHy=r6O1S6yVY9c@;sq zIr@Czgiw0ATAG~k)=hPP)MRZm6-Tcu3Cs*?rOvB_(;(?po>@mZQYPT3qP?xfgR)G6 zVy81aU`}WtH;p#If!Zi=%vTsJO392kgEGLEvMlXW0u_~U;r*w%Mzkt^4D6w_TJN2l z>Tj7Wf?&BYsrlpe`-oNNfye?{*fr=!@LWG(KuWI{RfcOm-vuJ6ebQ7arBt`NJ|eyv z4^qsFWW3Pd5R;NZqpo~?T-_&fY<-qz$X>+{3i(9mME#T$lI1U>yB4;4!Y~Sn?2JvQ zHpT5LVfm%BYOM5ToyrFbjzU~N^;?s(>Ahve-yN+r!WP_NsQ&z=^6>1om~k!JM!sB( zJ5ol4p_3#uc=b?p!*ud%&TQY1c9RPyk~rp<(ghPewNklvbEJD~v%&+3lL^Zli#7{T z1cQ3X1kDXPE31RDRPPj~2Xuh4<-su}BOT_bDrM3Uq`E1ODzd&3W=lVa;3!#~uy<%E zU9XWh929>uhkAiQ7_V9=EvMgL{@seE->3|BX^EtSVL`EwH}dc{?i74qIi@7@7nm2z zAP}j(4IbC%=^>dxa3zL|zV)H?Huvd6PE;AcipxsXwJCKu{ef)kNr1J`(AXur-LF@WE!M*qNsx%ro8tUcm8Q)N zi#tx&39`Cy7C~997Bj#Nmt4C}Y5B&2Tub(DtGh6a7!ExEV{ctf{?JZR1#&j4XD2J$ zhuJkgS5H!9dO;q@gN^_j$!nBs3^S2h1Qte8R zihPFJb{j0bjOb`mFh2V__aA}-{;9;TCrtE0l1Zg;J~FDl+_f`@TIckzxph*EdNXsM?E;w(&eiS|X(S@sCW`iv?~kBcXPuJW?I{) zRg?ZWMbqaYCM5JX1e~6z)A`b`EW9>}y7k z>kMCCrF*Ac#*A>DdOAa-x&HnFcFa(uuCn1IfR;duzDSF{m?iTqFK-kSFH({I2NmDi zLl!mWkW;yVwY&ZHT3=C}T?7@pwF$BiF1~jWx@;0}{ho@9 z-psc&xHg>;-1v^P<15MzMLaOpO&gmJ`;o{9<@kJJYhbMnxNs%$FU{K+tWxa4{*++2 z7MZ~1vjTwo>;WRx^2~CFzy%ii)5SN_%}R5aTVsrE(>@|Mr${-cY+x8p{j)$~#9&FD ziYePP<*IZN^?VH5q-|b>@DZ9@562686fxBUbqm*eUJ8z=g)cgst?%PjtDkOjECYod zLc$qC#Xklak(I%6GzbxjEwI(!hF0+2A@Br|lIIRsI1&)SLIHTQsGquK(1ICu^@v~o zgJ`A`!5*6*p-osndG1s_KgvJYs6vRYee!^fqwa5$-%fxDV9PPdum9);^brsXN)%f> z?s4Z%aS6DFC{Ap0{U_A4^sONc8h|V`H%PBA`mckVw2~0kUywu zu(r+OCeJ@UU$pSNTzIu&$%2R7GKj-Y`waF1}4YzLOtVhQJ#cIP)t}VMrU!Ha6VAxi^$I z>>Tj6h`&XMANsM4@&?5QhhS_9yV>C&V%bz#(fQ6wXzq?+{)e@3V^Dan#zQNKC2M}m zgkUZ?H%ff0zby^E1eJA}rOXOE@!0zw6KOCLpK4DE%Al50j+?-9kL~;t@D?V!ZU}kw zuD$ozdkvJhRoY}705&@JwFud!U*1}nXG(a<>4k0mw!3rY{ z-b>4e?0~n%z8wH}CVth|W>N7WTdXRu`+#or<2oe&{YVy+{Y#g}1ao26Qs78%whG8* z2o#V)(5S=4ar+IW@t&ewV}0QFtrOHZLuHALr_?5PdKrbee-to^M@8>n~vR zmwd>MBNp^DiSB8eBFnFfF+vPrQ?vwQT)lZ?jL{Bw-`GDxLLgtoy8*x_dUCX^#8uN? zcaZSN_WKjl9$f;0SDf>yECLBtstARRpH=ykLX0_EF$llJQa*>gjkFP{#PYaBzU%8y zPUa6~mKfYWB#EPL{vcKpW6~3m0xcSXP1BH#8TauvdIufh{!k^N2FcGR+6{o8eIy_{ zC&1Eg(O(^bKx1xkUk~79=-7f4Xwsh#%F2 z%t=>-O!WPv#J{~;B6-HPa7vsG0}_FIn=M1lanuMvH;k9mu#vmvg{KZS+F;HC;ism? z;RWAcvPM)QXRl%IE9RmKj<^HL69&43T#6tW%`1S6Wb8Py!YcM=0h0klmnK~ES&`Ea zJBe#bXkYrUg_%$~@K{RQq%d~KGNU2tCA(z!`0%@qL&42JYk#v=$1~D;wcGAP>n-6^ zTW3Xi9pV_(GZ|CS%R~>I{co@C`o3lvGTM zfrT&s)lUnymWjgJpO{i?QA}+`c6pX=&uGguD!kQ6jvp_Rcd;>4wP%*Oye6^yMavXW zCEBz~6aM%l@pGeS`pN%&4Y zYF9bK2o0&? zmNbXXLIN*ksEJ-lSfXfA)u-(UWCYMk$@e=Aj=v%R<6Rofi6U5ej8QqgW%ep4Tj|#F z6hd4$>W)`USFy>H=21VN&Cm9%6b*)AX?%_KW37{a#se!KAH>o|NoBG^fLAEMR$ zJ*BMCEuuY>_;9yAX{@Y&+N$a&eRh&_>{{!Lhd8eGRHG}`B%(q@1zoMBtVC0l0M-q? ztnYXUu~O>zqI!itCprG?++S4wYDf@e?bvlj9%b+~<)KV@+>-Mkl{75&y+T2lN~-Ry z)^%XY$1jsY0y2RMKqf*2>HrE!?AxQ%|c(#^wW%An31Ty zei4CvL873W>X;2+xBPu{MNS8Kma|f-Ay+i22BZ1YbU|uE_(lNo3UIiW8Ud@P7s{Da z0X19y^#ncj*%8Zt;-SOtITubeSL-UX3RQ+%2Dpll*>QT$vx_t1uRR3ri)W=A#Jc_3 z)v1ap@h2bJc<1Lv&A0GAhA}kmv#6INaFiPiaxfBToh;NY>DHwtF-iCZ7s~c~*ImB4 z_I3q8r2suBo*MN_iJ^~!zIv;s2)~|;bcUZYe-kLo4B0|zOko_z`PhWZbj4Up^Rs|C z-zzA4^Vaggpe%~};(NuS&rEHT)vm6dvPihw=Am-P3E!-jBmbva<9|%?Kc)aUnr`3d|DJ*kFopl;o27qdxAfmOPiY$auV}PvtndgZ$76V4zUvx6lYsMqK#tD zv})%7urJES0>dk^kx%AT98Skyw{S9t`IsJonW08s6 zjrE~Ye(y0?G%ay-V4);NW-5lPjJT%j*8NBOe!5>z8l9#tK^8g535Ki(N{bc|K4Zbb z0a>jCM3jNnYZlfG$25KI70-~9SAd20_Y3dzXkyMTxJ}~>zRmd$-<*3XH@9*W1t2s7 zNspe++=qWmtpQzsyT=kfZKM=i$+rkG^-}jg+qnx;IEZKm7rC|GVy+{lGc%{Zc)zjOEB5&Q0_rhtcA;dCBmZ{%9=eCX>m=kQp9%i`AD=R z!JC@Oc>fhG2Os=f&j;k5m;_yEh5lyVLr10AeRe)jWou8Kn>W7ih-NDGp*zu8^<74) zLbrL(kLQduOqg=WG701ShNCZ|PEdZWv?$IM2D5?{V$@@k^m_{%W*W`^=Xm}Ayixuj^cj==2!+#hR z6Y{Etq)TcJfSGF>rzKz>G~*gk^m6t;yv^<#`?(4E706$WnQ^StM-N3ifsQ5|+Sies z0_pof!rufx^YX#0L>(pr8>g?8YUX6rNqkZmarlXyh?!`0VXM?nC4Q{G988`VJbHCk z{Wi)PgV;O%AcNS+U#QaFDA-4>xNCVX4uNS{B6xwPakRj;SlfNzdmXv-l2K3{)eSrb zNeCAAfcJ~-)Jg64Q_&nt(H{c^aopt`4pYfsv2Pc|o)5j>$auc!-(jJH0XyGbav#P) zK&UoJkD_N49DEH>C(y8_ENKcq$FEVv9z^Gs9F3VQNzUHbj2rdk4%q1=&=Cb9u=Io~ zIG>^o9s$%EBC6_iNrzn9<~1Ha@>y-Y@0`SvOP=1d+779&H_05)_~D5H;kI5!uH_0f z;IcbWu|J1xFb_D2Bg`ix(9v|ZKL&ikwFoLzrecbhb&$QGz5vv29#|p1nvkOxX0F+- zq1JWN4kS?m1TP5;pU!%+SNp_2ce?H6?1De{yjp$pl^UQ+?eq_Y05@hftgH+93OJIQ z`-2-;)^_uxnJnG-krCXl`!^SbLN6Au1)-}<<%GvU&AZ{_Z`-|r=mSQiPR-s!0fa`I( zkeI-s&(4iU+yvuzTh!epeMmVmmWU%xolh`RDHAdHwAbL9ugkzdA*uc>JG6KuvSc^p zP4j-txxKWVm|%35^EmqZ+;2Zm5qb^=DEyy3wWc6*hW1P0Iji_dzV+)h>746RHekYi zT2prM3Slk=@ihr<6*)mAlNvs8L=rb%pUF{SaGzFuCLv$66wP%lGE5lL>Q<~y_2gq` zTe9rcxy%neBzN{qH4YNFpCQX@Eb8OX%eyH6eM7nHq}{pX-XRQxt$12a>R77p*6rpc zQ{^AFV3WR+pvY5Lwy61n9V`Nrdtws3#;n9Qlk7J!f@p7^t*>=fDcQiwi zL%#mZU4Y7Vhk``>N7Tsf4oO`&uPK$u=SgF{++A$EuQSoj=&Z4#{ z(x*+s@4ueX-(4@-Nb?mV)2*HtDLW(z~}4`dy^&M9$G$CBnWmNhjt5 zu)d`h?pM6q&L)|!Xh7WG;opZz*MdVSwht81Sl$8>aVvz*wqKf_nRWq*lU((wn1Lea zkBp(K*4vf6&ZfV+rB@KQ=@OGLLRUyVM9xEi3BMR2f9!Oyl+LBxOrA{LeWUGyI;)aV zP-B1}*!EPg*HU7t2qkQGDDo#&-5o^+SBtGhcyk@KTw{`9I0J|lv65=u2+3A3&VZ4y zU13E0XLh|b&rnF2JZUV&W92iS`?&G%*FgQ=SJ@x4HAJfw@zY|eBhdr1(`I_uw$SJ1 zyBxXhJw(hk8(hjJ3v{BQ0Oc2PbI5AUJ`-mk$DzX41PYy{M_awNUNlg(m^!_ zF8A8T#YLHV+ikCgwB^9#s?kI#BqkS9wKn} zE_?UQm&mq@643-;h0IcFM}(tRnmP#&uDp|3DE@~3MlSr_yr$4b)t&bpGs<&5kcbD6 zl9m-WF1u6UG|9h5bRI&gc=J2I>~|vC?{?)s31@#Y(`0{Vrj-JQSxT(`a{S{VOtva( zx_R2N_n*mQkBMym4hUqL{jY`s`pq+7=*LX8zZ1^>m&yNVARi+eE>QUY4g5d6{ynsZ z#5j7rA=rtrDCj9UxW-a|r59(I?0x9z3BFm5VHZgs*rb%>#3Nr<#}tM3^?<3mMLI#A z#{rY7Cu_;*x(io!9bC^~%u2%zU8v{hVVMP@yG93M@AbU%=vz zmNq?!Hy|(aj)Yu{jrgDJvNVy>MSq95aU=~BRx+9GZ#(N7gKwA_xu^7MLykx%aDM<> z^{jfQ`Reo$OfeVzjO;@tj1~PhWfs4l=)6BGZwc*66?`?gtf=7ymr-k}j-xoLK&Mr} zw{NQY>j_skHe2DaN6S*^rxeIp*Z8R-A8g7H%7DFjbyG~^C$Mv6Hbi8@dG`@O3 z^JBmXEpZdu^HmF;u7a@Q&LV3;iB^pDCqhC*6)OebtwO-tIrDmxK*T#a4^-Pk> zhtOXOhYQ$A&i>9RjZgHC3OJ-6ez}BQcjenlKDvm0NOs5N=zgRKxt$dxW z7N@Q=uQ8$e<)QA)a7jzx{<1z$PIWXm>`N|0Kb1R4wn9L;N|u$r7koE7KTVq%6D1yf zs5HV;6t#}y8(-}|6M%lg@vXAltOlEu<%^ZwbKGU0EH5f;nXri3p?xb%bz zs-H|dI~%0Ax6+(d{b3J5M|i`ZbOUbKlf-@c65vZxRq#x{kYs`a)f9^q!BNW#`jmu2 z1d<*^g{=8gYc}>vbDx!B!4*25%=@6z^O_{0BaWlN1;~-E&b&8IWSpwn4tKpYkR3P5x@hhWe7Jccjc0;1dBeNq!DLo_j3Zp~_I6MT`U#Sfx*?HIgqm*A23lJC^qHWq4=BerEa=R(t>SR^h)>~TgC`fnQYe7n-KM_U*g~W zl^u_nvy#|QA2y1gm{K$nK|=_xOCt+IUv|00+fC|<`{&>#`%o3{#bACSXv)v_w2-Q> zQhbJnIbg_UM`TeI#IYu8_!JZIp|(#f4%6>A>AZzfNQJ>9Q4eRC`m#cw+VgGcFz>SK zC(=&>LEUL1+p<@8FMB&=a0;}wWozDL@}~74rloX}+}dsxQG3kvFrXD3h$Q%QM(#JS zFFas!uEQP0?KX#?aUQagL43ZrKW{eSFN5ct?d!W`>*8!<8Mcybl7GjTLGz`FL!p-w zm+g=pRy<9KY-ufyP=7D-5E!!oQpqh*ES>$vvG>O0Q>A@v#6>W3wEX_&kIL>--zHN! z!$K%N3qY2ocreNyix3@j1+G`>X$J>Odg}KTU_NE5t&I6kQW;)%kaJOsK9}ng(Fve9 zpWA`5FAZ{|u;AmfEYk2AX+u?Tj26zOTPyBYID|pU_p>1r#RaZaCulYgS3Zu&(J~N8 zQ~c*%Xxh*xdAQD8#oxMVeCugQ_6{&QNXhM$M|;ecXky2QJ-0$SbaCV)dwz%xR&f(5z4I6C=Qh-Nm2}7JykMwVdS2iIg?mr z+%vRfZQ`MoKQir4;B4-$i}i0FR4ZF-i5c-FisHU`H@V)pxH${T8`8_*y_outuhrlN zYvY0vB$Hy*#)c)r}0$xM^P z)&A_#ZQlG49c7mw^1dAf<++C^9`Andx#t5@&!;%OQ^+#mB|o|E*i$US4;tBbhwfCT zA4F;QmgJGoDM7R|tY^e=zHFh(uO64g)J+rnLmIobTa>v?%w)~#l#d8N9fh9NB>Z|3 z@b}eY>=O>1?+-oT5tEScC4~8`)!%o)#(tNF_b|Cvsnc-%9F@BVYdI)R%fk6Dv_aY` zmKVE|Ytgv8#gC#JUmg<-9UMMT3sGGSAFBIu`X@yPSmsfH zqxdC26F~tqIo2E;@4w>meg-5z6j9;0AC*BYKg(*NiKZD@EbRSO3bFhh*BNmA3y7<# z1b9D=22n)e1C&DisJq0n&?6r%z4kN5H4rt$%!-`S2|ip6rRDDB7ph>j5G z1Jsj81`8k8uACBpV4lw=ewYudA@#SZ=!x*8#W+JtPrSFaqGZoG@MMZc=O`pgbjByF z>2a4Ivgs%f)!!P?5*D$p%hqjVNAw5ND~4^y?{nyyd`>3lR3X;XF&;>_WpF6YO?D_7 znzg3%CbIm7lISuS*fU9|-@m=g)`g4sO~o z$e+Xd@1`uS;=kYi9pwM;d+hPN)BE26|CbAti86}rKW6m*2nNjcpPrzTQtI>XwIKWz6oBB5-SCl_WZ zcVm5OQSxa{pW!exv0SdCf9p+I6?(w)SbuS!7~hxbW?MDBuP>PVdU$vj^AD-g#tdvy z;C_JTLH?I)q@%Yyq!dj*?u5PI-hkHZ(Kk(YEpX(E5tioE3EP~kTMeIn z&t4C4ILMRguBhr*nG4nW+_v`;Z{W?MHUS4R-LP^9x_*e*?Ok?IRojFn5@O|O?q0%Edk3rZax-UNY&woiv8ifd+YT zAe(i5SYv0q3;v+)ya%FagdVKA?j0C zCcTu!6$=GT$)FOUe=DekD_wedP1^;YW-&J2;j3I=P%zO{;FKlSc8dg&pc`sx znqg?B+|q^(VJHGrkpB6?1%mQU>~@ZmDv{d|KCWC4rJUz`X^t%@DtU6bJ!GGwcpZ^l zL{5da!lqX*-8yCz{Ka&C{S8;uHAH#7E^gSHQ=K7`o4b#%PwD4JiHE63f{(?rYd*E3 zKp70l=zKg68>!ds4Fqqh zhKs5j3`%2XwXk=PC?d@sKp331n_q}+d26O|VYBt?j__6>GZz{mQ)MI;;0ZEFdMbIE zj*=qyTTJYnoYuQ)E5T5Zp)ev&GW&jNZEJH)be(XQQQ5AtrRmpKsNFW;zHhDeuRUr3 zOUTm$pFTVGNmnVK;0<$e(JP7T4xov@FYkGqzqpD@?HPZCRpVLB9)~8z_2@eTA|W z&Kd1{Jn=*vMH6g+r;tAQhRFdaC15XHgs&dW$sHcyENxpJ%uCk$iNO`)%%_mQt#2p-l%na#q;3Qv=`?De}^$1rO^ZLOMyULAdTp5Jm>evjB6N z(ZzU>j$EQQagsAhrP^Tl{V>%sqBGAqLbZF#voE)EG~u1{P&%qG_V_bb2XqczphA1t zZ3in8NAf^Ng3lK(W>@QP))294_ARUohSC$-!@YdoAA&f6k!F*8`Z7zGyg6V5VSh@M zx%Eq&XQV|8+F6|uq;Y!JKGB0od|BA2m`Em>a?o8my%Th5^gRkm{WLzu%rN~Cj5Rip zasa-Zt||zqEwi;@e*hy-h^$c)53+_FEYX8ZG?P<&R1h z9=PcBT+Q>vozXViA_%Jmn@<><8GK(C7IOD62YB|l%@EzwsO~D~LFc$@7{Lf1JDo?h zrj2e~!kZX#(~~ja;YYirFUxwf8gXDDK6N>cDtm4J71J+ z*5Y2P+t(^%)I*@uMEtC8z}`us#JnuL+EdP)h8}_r_}MtN>arRM8EPkB?n&k;7!SazXxfB-Gjpi$!F(X%?LE=}WQHVE9rwml;hWUYxG)Ze?a9PcH zEg5U7NyL`R&<%Pssg+5(wQ?~4D=PKZEMS>h4Z+=9@v(_ixeElyAy#zh3tyVonJb+M z?|24z&9${!P?|TJk||mZRLf{aPY*x+kE>U3K-ecOdGP%J(gq$M4QQ{pe zGF+cKYR2zoMjt|)&)cN4^^2&%iN$dwC@z70+hfNiVyR3?U=~f0B^9Hw7FccRfbrvk95;eOrvF>XD7xHF0`4NvT$p95L|xim-DI9{^kqZki2igLaGPj%%}e7>^mqP zCwrVvTD2s*(lk>$tsMcKq z%M4;cxUa+NdevQCgh@dYdzg0p^+9pp>~Lktw(u^?CxL8T(czLtq-5r>l=^Lhl0JQK z9WlRRLA_RXIwh7Nxlck~1CS4GHrQmb+g87-G7>A*MdiM1(6{rs*E(7wYJVccuGXwv z?JwKqxlhK22yvYJ%bhFGSZrN~ z)O7TllbktTidj(v3@sXNrl9ccp&acoqk#}&TMc3I8(s_oy^{<_x@3`Fjvii5qUfIL&x|fC<{6|IxAr&$540MVr4S%bp@!VU%u9A2bYpD zT#R~FE}L7EWBF78^u1|6;yNEkl&0>77xO*M18U%WSmMfoDtT*ZjD6KR8m9um&NCzz zIpje-#3cSf8sF#b4#%Ue{MXE%1jrwZMF$T@+OhXzdI7HCLhM6U&YR}qo#3vRq1&^K zS9hz%0N&WYBc-R%PBTR)4(VlWqq-@VM3A`RB$)ql@WzqLwyc49M(T#{qVg_>XHddl z3|Db~d{8*qF!O%5LoBFPPFPON@r}deqRN8zO&*pZ8GRj_IXh(n`G$n034WMpx#Q%9 z3peP4(DF#0igLSITj_|JR&xjUAxFN-hB|})>b*+RkHkTJ*fymXyjL8t76<98Wu;h# zEpD8O7G@VrDvEa=FC3>ViA$B(He73&O>jeODyEm|F*6b{+cmz94ndn$KP<;ivJy+> z(J;5V=r%WL*ZXi@smfU$(zal97OUFndVl5VZzo6MYC>g1Ro41!Nxscrd0-i2&GOe= z%c`8d&Pg15??7x-@9i1~kw@FE(lzE!O5h(Hcv>O$hQ#FNA2pUsMc^bwi#q{D+5P20 z5Q5xM{Lcu8$LSWKN%c8z{rpKg@br@AkB1xXz6IUDM3l@-ck|DbD*1Qx7UJCJ%I7AG zKV=_k6<+NG6GYPsN8I7U-GA@Vgx!9Zm%vhqS(z73p|WX~w+_Xb1gd)OUWOJcnZ7%R z+y)}%o)THv#`q-d`p$; z_VH$O_^L^vR%_o%O@+Wt$Ws8vMgxMEH^RyuzClbN+W?4VI7mDjgaCPU!p;S0Q zTECD}Z#q~LBw;s~l~!k+#X|Zycd7d0IKbEm<&d6Kbt&U!IT-iOHkP!+L_^(bEX#Lx zewOMZr*SQ%CaNTAUDd6)Fa7F8u`mk*GXXoM>1LS7UU9Lnb{>}4_Ov{+p5dWSig22) za|cj1C()&#RlYI!KH<{s!i;s(cF5CFo247qdAHgWsPHjxjzL1vQ&f^1rT~)9_l`Y$ z(TMW${TuUeS^2UBF1D>OZ8b#%K9k1LpQ$R-0NX<1s>g(<`+kSeU<;3>kG*Kd#Ob*d zh6yKxDE%0(`(r+GqniD*7n|?SXZ5OphN@`eOEre~z7bb_24JV3*Bh15xB{XmON06= zk;+reXP+O?4&1d zst}i@G3()7i0?91b7!;Ja0{K!)r`Q^5aExPXTy8?23`ggHCm}3e zZsgoJT4bEsma?HGSDTTibMk6+VhJkWB4wpnEh6%O+L7-oZTxwZX*M;@HxTLt-bwAW9WbwT{)--=K|RZjZ2Hb@CyqZV`}&F$SF9pP&14X6m3U@9v>RKs;yKB zB7iHhxP?z|X32q4VFAay4o7{82;0@17Ji1qV%4W+uPJj!B{5YO0?|GEaySwY)T8B9 z+fP{`c|ae70{3o#)R)Tb6wa5-?Evyg?}f+w$x~HQm=YtPj`>HZa+j#*smoI$%EZ#4 z=n(#>XlqD{--y^#_h)H-V`7Nmyhme=FlrB%rJO?=63sT-inNLtfziRS_1b2W#=RhG_aqF5b zCBdu1b6g2>ua2-#9H2j>FSaA=*VP2G27KE3;3H+fb|m@@Sx^ja*fY8aTg| zzJ#UwvOvmCj~`X2?5d{!r!`kLh9_@Mi+m1fkerQpEJbYD#JW!L?rL!u(QBd4OyCt- z8hXeOhZA~A981e}W*ZT(;fyEBUIj5qkWEKK#H$Q?(Wfh~=%V0kscN%m8fGgVc@I9h z4#DvodAAh4M_u0$YoF68;x|p@q*iH(>W;<>-~HXP$z;HXLVk&tRIR=BGBF3VPV^EI z4}rb?lB19sZevr#ZVnk{(T#M(LP(+4meOJ*9tIzz+7(;N8P7GS;plL`mHJLCvJVt^sw^xn-KfwI{;2`Y0K;$& z`KDaYa3;4I$l}IdYsp{ZnOa_vjPMle4 zJpwyJ<}?1utq#nnI7B}qAR_ZiIpf$sT?Bct&E#8r2SupMUZP>MV5PFs710Q}G%prRRYb)P-PYX$ptaCO-kg-%1ctK{&Y*<#XxPRY*R*Ur=r3@ zBa^0oMO{`OHf;GSw}8GQlQK2|!Css?F!V#3LN6u)`w#`EMc}amQxpTYLwE_Q?syP- zvq}f*n~*7^`JrZwsKK4jz?q`SM$$fP{y|>$vwEVRzi&D4?(}Q_L%DG2?)L$2_H1v) zO5ZS*&3g9fc^9Y5_>E0HPNk1kat}nVQ|X^>@fOXA(9?YNFosdf$7O z0caEf#I2e*h>)Q)<%Hw`A#8|?`%MEqamXEFjFcy1GQn0})68S<2Lzc1xt3MuRneQ1TP)lQ#?clkym&LrfHEUK*pBl*$BlR)nI5wMQ90mT!-pUsz%OOcy#A_EC_t^ISz~rk-AeD(i;h|L z@+7cAZ-dR6y$5~-no?Hi_+^l(j3}I&aC}qau-7*KN?6R@)qWguwRVc$zSklz9!0A! zbLpyw24`{zf}J$pu}s(&BB#mt`8=8ggE?MnlPW8T z1vgu_DD7Bw3n%5kJwfHK7An5bn9FmxZ64`@T^kX3H!pR9ZB;2X1yFRO0U$S$fLQgR z+OB@N=*O=oSbOLSn(#Rh66RCG3SQystpi!TIwr9x>}gbe)#5RdMaz0AAz89NXO~=D zc`$p`scKvI6m?k6Z>DSrzW0ub@LKP!<=wSM0ZYTa9ti`?+r-^Z%kF}~ZaUe?#8TGB zBu{f9YnZ8bdJ%T<+YR7|!{f6RBX0k->FxTEmfQ7@9mXJU(qPP!G{1Z4JE@g`7t{ z*(@8a=kOqy@2AMLqUBQ@A*&)wm_I*a>Gd$al$T(XQN6o!`@U_sSi?4dW`lEST2sY& zLG~t`Y}r4ClDu9aqV%FidlT~O3F1wq3;&J(a|lt=Kvu${@4k>fRGPmo9~9Udh@)GR zKC9S|$N!2EgJvmBq3cD&#{xYy;WypOdDZEf5&U0C)F??3hJ2>d96vc7vFEJ5f;V;f zUbww)JvrT9L?YJZ*P9oiVai>CZ71ERZf-*mqI_rO7!qw92EXsnpKgiaq3r@1{3?%S zAV;Q?5Nv01*Izv@ct!-fCZFv0Kew9yVygJQH^5;pUqW8Uhl(Gi+qT8`l_6f2MOJdc zg0e*FU+OR=Knu}byK{Y#q-T3}(>2MBi<1_jHBEeivi~u9tK8#fkE&t>0kbA4G4$ki zsOY=(d`MF5%nGyrq1oh$_WVFm;DDm ztn08v3?!(V5M8V`%mI}I8GbUjc@<=%S84hnRZxmV*Qn&Q6-=t{auu;zREzK-&XhBj za(+A&#~@%o0o+N^JCG#3T%TKdBJ?G<>(%6)_?bI!%We<0$`|=z@4Y#}h%@4Hsj7^s>Sk&opRm78Zl*A#9z22;9ZlWgfkK*|RWfDU+(1W~YJ+b>qeZS} zO8wAxH{M1y5H$!*9`L*IXCdigeRmgWL7I<71ZzUGi(VMee_j{>YG$Udah2kpzahSI@S7dQZ1LXdKv?_{c1!FOF z-+W;gd06+90J~<@XK-7a51W}bPN0=4NY<*A9jH>hhi%fsyP7^FUYT+c$P@vCztlaw za^wE!L+yz=HB_(Rr9cEP4Qz%Vm}`(!YAU= zyn=P9lTB1ZheJenC-T1XVRWPRMWhQ#G zQTMUlfZ`_w+gOmJZ4mNU>!;eLvp2m<((&IUVfOn!dBuIPkv{JG203;h?lG(-G4w~^ z>D(?6zQiz*-jB7dbM+>K&an3xvrx_8W&mld?yr8tlHZyX* z>ZUs`=xe^%_ij66j!V5MmB7%&xbKMWCf(RSA;yP#gUhx81wNDHL~y1b0Z$Qrw}qyA&@@@!}pJ!J$yxEw~pC?rz21-P$L= z=Xu}F&NtcpXJ;~*%H z2g;$8y?FRmpk2@R0;`0Qj;(bK3TX$pWXIfjoOA2%G;rsWJ#f`u zbc`+fab(D(H|i`rCatIGv<#zxyDS9Eqivwf3jY`Hrggf7zJ+<}8QquY^X`-LZG*=T zs|H0r8FsA>hvWTqA&z8KZqu6#)-e7 zoQ8OPIn@t(4(l4&)lvRC`?8fG^m3eBMM;obbVqwK4T++mNat;V7N~FfF0j8-Ih5xf z4L9Vbi%v*8+zsu$p_cRylzJ{~go7&p9G+v~cv zWm(`SN}i@|9r9mFqsO2U7p8xG{m(n|wA4vC_QnhHY2sACh<>9R(HT+rdwHk+>_SIJ z?=7B=v375;e_vZrC3IYo$o(tq6&t~Wyj}t?pV2{;TE^@j{o~>g5Sz4-n6zs-5Il|K zc(gxFb)nZ$qjmp;C@CxAPwR`U`DZ8Y-%)^a4JSXRW3Cju)#kJf%*2csmbXuKe-3Xr zS7dXD=m|XPOm(^XCFdsTRYDM@o+mhuQ6^MFXiigcDDl*8SHhb}8=Y@FGHle&RiUwS zYfRzCZtRe%;Uc~(E4@U66JZ6=fz7JEk$iA!^x_$7^y2g@`u1)63payT5zO(u;UL1y ztT&H~?^*g@C9C9mdlz`>D`WSqDPX+|!p#o#Z;oY#-0@%T$}lsXC1W3aIdh|&%w5Bv z9RKBk!HsyIu3bZ+>t@>HFww(U^1BPT8TYI2ks7xOfl!F!#alD6kC*iqt6vAcl?s)y z{@b?;7o&labiDh<2q;igFazUQ^%0U9x+f_UN@rxF zx=4tvBB-q7iGU8vGfc*N6ecnkeY)j|kEkp9ILARcz`-kz>xRN{RfJjeWh{zBj!Smw z_j`b`0!a*$dgaVW&gUkd)go5`GBG#Allc$Q_>BM=bLyWfvWJltv6NiPmLMlhp8v{+ctaw#zXv{Cb!+WmEhm z_4=9o-y8X%m;IFal84c2#{<<~@A>(NV^XW-=TI5IaCNlGV7wa5l!4|+WNG-$QtbR7 z9=lbMZBr0QSMPQdDm0vci>;j(`77c5(}EukrA zS+*aFC@Flp-!`iH%&N6vO#3lX!BS(o=n_LS4E}l=?De`ZFkjt$yiLb^p=(@nF%~Y0 z<~#lf5I8B$X4G0XZU(EUeTZ4{=&O$np*>ol9p^t-6$vDhn$K5u4VE731rA~3PZJgb zZxuqcRLTo2363h=CLfDSfc8-1>)2W<{cKsj-icD!i1l@J{X^j=A9M8AL+=pmMmwa4 z$fOAV5xsDO-FUSTb}~6;hEyxRh!5xV%yb>=kF${09y63brc>nxvi1L^;?R3+qnBXq!(}Q?z9?4Cu{;Wfm0XTeW3X z28LPb3lZ1>T_IGk5HH(xEA0wW0D9wGM^(;1Z!2LdsT(qQebrx!8_QXor6q z)z8&DCl)Ttd)k<5lzKLLf!13~OXp^oEV_e7=Zf?wL-!czde}1W%|Fswo5Duu`c8PWXja=nSM%qQ0rEBWk+3VG$;1F6P*ofgIxdlv zGBReZZ&D+}{nD}A6JkZy-DTdh1@PhIiD1Lx$Vl!fHjImInbK166mG%F)R_GhOjAWn zuIEfQww1#+ZM3#Xisrt&u7W(!X5i!bhD2fGSONVKc?`=J6FGgIbdBEv^k zPt+WU6LiuPWPeSXQ4FO!xLV62u}zZs<1Gidu|zAYd^ItZ*JEoVfXUU5vi`xJ-dT#$ zP?59gc<4g32e*%0{3*J}e7LN(JcO{k#cu3gKISBCt&)f#Vpj?q*N^&|JM)+2x*U>2 zEqRi7-$)w3H?{}MN-Z*jU_~Srjx!oLa{WQF*?iAK;Uw zvCvD}J^yqp$NKnngkGb9FA>b}ltOBSlKQoUs^bvvr_!Sf(?(m6Y2Tr;N^@3Os`a86 zhV+0WZ8`+21K0LHBo)rK+FbxKdQF?7lWUgxcdnfIS*g6i;~c362eNMoQSuG)o@v?B z^Nr?0c?Ul!$#Y$@05xEg3Ob-4o8@|q&#y-w=IN5V-P^A>*JK8j;AP5uyTS7Iu) z_J#=!du!YFrefw)(yZdF09#n&2|ct22sjPS2Vj${LAHO%gGmVXRlr9WdM{#_IsCX?oj93(s*ZSVqye zc_*vrH5B$z*~jt&?Xf$YY}-EmXuYMZ&_37Apw(v z5{ALg^`)!ng+;%JJCj31BM9#+>-s2cYc}!lan}&VUFyVAGsbgW>bqz)ygwJsn3F+w zI9DfD`i7|n8lQZs>3BPQ*G)qUt~6Kflv_*)XPFpK2x-oYD3%>S!U!eS*K6h#XtdN`=Uv z-Fv5IHRk9ce76FTvN9vr%%iB& zr0CgGqJm_|RZFMO4%9_3o>6Zt zIx)8@s3ehb*w{3S7u)KTQR$<6d|$z61Z0*<>xNeF_tg(XN*0F;$;mKE+oCEymJZ%K zi{a2?%hEOpxNm|9)9aTQI^Onlkl)t4x7=;@9IbqukVm^ILNtpJIE1d%v zUQ-}mSb{xUXUZJTx3o$&!z{`&#oy@-@WMpnmIqh zhA^F)W+hTiPEH`bt{ z+~z@BS5=m(cK5_9RK~VyPQb>6kNP*Z4;=M zOczbP3$fWV+V!WO{YVR~asjgFc<$e!m9ok^Z`Dm|^}<-qn6|Mxi^gUzOPROT(_HdQ zk+nW&Ls1z(}-9VK=Oy1gW#(O>+1u{P^qTPPq) zA~Wue=RhSeWT*Za-BmADOv>vb)7j#4oWe>tKUy=mYU!nU#^equ5Z;tZ)F=H7U10MV z`5-u^T~F6FY#6z7Ph(IFYA zW?@DAsKae;)$+Z%lO;b^KZwAO;`68rHEueXOA#fXyU(XufmoR1$EqN^Ut|16)YW@k zDdhq|LSFM0`OkjqXVKRYMrgcm>9Sei!YmoDUee#sqA%A7HwhCmO&U6o<;33_gnt9< z7C>tADOfSVTjD%P{f5n`?_qX}@aQ^7ygyw}{}woGFAQDSZrnE}I$0%V{$B2Gb5~itHh_pEtgp9ith*5Jtfd(_jsEC^WIx z1KrNB9_U(N@#Vlu(E>*msjBx;Ip9M~E%O-NWE0lcbLuquNi~~+j&Q|u0RTUdRpu31 z62I>Wt@bOyiR*ei z`M51L8!}dadPZ)DhzZlIo@Kt^G_mMCnTD;C(7IlYjey6L3HH2HbpWN^hE(&vH-2-% zew4$@5pKD(!|o-*$c+nAzuX0LCyWdcFvP z8_yx3B@3+*_bczyPO>RJtDS5Pew^v>dQ90xDe~{>$&h8b?txANlW4}>fyPf4&JN$; zvM=3lZ|?3ujH-uVirGc@&*b0L%<0LY5as$gr8p=%YwA}3W*|eIf-T4Xu!JkBW13Lr zV7_qtViMu%q6TbF&B0vxGx2nqV5w+(i}JPTEor@$FW{5;pj2~+k9RQ%;dDN)@Q>vf z%7+whbHj9^JpcFgx}*6?J43Gf*E9x-kk$<5icx!t8f)Q-4lUGneW%*1Ewt#A4VFTh zYCR^!fjogmA1#thEX0`8mm6W}Jb;H8McaPTXm?*~fd!SfRoghX7HQff!S;kszcrHH zJxN=Pk(XKQ@?QsZ&GhyH*-QB4@62?4VV-RB3RYJ^@b8i+Dt4^`duFyT{7A(s7S|Lx z>Q=SCB|{@gv2lA4vaJYoENnaq20lJuk5r#Tc$y7oaNwKHpnb>?*OLjmFRvIsdor{g zlL7J>|4~4$5HvVyCU46yV!O~SPH9-nU@B0`$K?I?th0;FUR z;T7nfb2M>AJTF}i=|d5#dT-p4COo=G(b2|+g#GkugHI@!b|x$8qZYPyWp&Eb^Ck7S z;{9J9X#bCO_(LV%(OVw*v{Wi#duPV;(J*41%%om$dMF_W2)|S9=&>{}60gM5IQyb5 z=Sc_9R-1*77YdwudTxrcAp5^4#)6c++mrDF!k4@=VnbNfDF$4#`6jBg_?n57N58#l z1oo3OeM|S$KJoCon-wgTH@3o1T;_WVAWJ$@_nS@pY^5p=TH8y!1bx_0_o4p4YD_uBlK9#o^Srx??X1VJxg9n2t9>PiGF?FcuW$LDL|RGD z#dL8=PZE!=OiSYqQV3X}&?jkv%ue9zl3Xfnk=V67q9>B_g0%-B9xm7-u>qY1v7lAY zJJ9?7N(x~}WqFJS1xad@)>z7nye(dulOorFUi8!DgMAegESn4n$0e;=^ZXx{rPlLm z$vkNFQySlwP3sp$=StTvZ!g8^J z<8+d#hQF_(6i=+h*;F(c=9?^)>jpY`O>kZx?YQ^CK>IlQ?*|$o_gK4^B)0mW=mDf9 zcFOw7mXJ8FLHZprR;9u<6V`>5}M(5rX&DRBxIXs6M>ncq* z&&qGmxpOI0oI#aN&}LgdRoGlc2??ERw4MCkSOWrl)B2>+qPkGlF?KNKOGfo$!ot{) zRy^UZQGbdm7}|#st=?NNGvcAS*FuWL+!GsM9^7%r!&5w6l>X=+n%jZ=bl~&u8kZ7S zv^ztVRP^r+$_<7ByfqnIXj;hTp@LocTZ3Yae%RxW@yrB1L+_9ak+cPbT)?4tN-R+} zo@&%)R!P!0JGd}{t`hbm45*CFlSI|A+R7GrhNsNRyGg>gTYpI0mS7&YNKlq)!PGIs zvy@JXl+zKhav!QUanJr!xla2%UgW!V67i?P}};|Z(UsWo4B ztHl;aA)c!u+L4Y?Li_~2;j@E*G7^9)((0(Ym4t42rN=|213Ip~>56aTJL_th{e1(t z`|i(%d*z0Q))W3w7Zf=n`90oU@yD%QlU`o%t<<{W&mE#i zxbNnWhCDjY{A*=g+}*d@z~Jj~iMEd?fBQbqRKXd$>3Ss3bESXvRu*)Kd!uAs`*+gJ zu&6OB*tkK6Hp^?-NkgV^Nz)Xdefg83p?`sj65kRk{r3t+9im0*==~%DlTP&H^Z@;# ztp|)I8(*GejsFh&_EvrOs1B*~^53}-mi4>|=GRwIRbA&%*M!i+eE~u{yt<)f%CSPz zA(UXh&?&eh58wt_UL?`T#X-YbXONLzf8cLl5+WhYtPn=6#-70^TLNQFI49*(u41_5 zaws>W8@B^0UL%E|bHSD%?gGIQ@Yu{H^8NkYU&-Xwv60KfI?S156t}RQXF^4~+uS(8 z0d@;zv-$W{s$VxCf&i=IszFGx4i9f_*0)_70*?~+a!Q^-S_?=nTrIRuEg2tWCa1;6 zmzPpAHD6rO!TFJ76zADxG1^IRO3La(&0;)$v~ZHTm2%zyNf~ul0<6M(D(XS$j%a|< z?mF!bw8rhJH#1nToFWEnA8$(w<2w@1l^0?bB`h*AT|KOEFbX{t9sH7a&3TKc!J{WK zMGsO(N6i=Lle&pCYfN>2G(gSQ!my-CIDANvtP)PxiB>CSf)p++w{fb5{dfY!tKVD?M-z>NeC4p?PPISHC9jl7>pQ<2j=ku8(a7jPD{a4-=^EI zu*0AwA?P@?*`Jm|XSminD#<|+MzUn@j0l{a^P@ObG#Fj^bA~(Hz;sByANAbg^V5Y2lSZ`N6+6-!d|&#^ba-HGAEDKR>$MnCtB- z9}Lt1|E;EcH5Ptq_d5Acu&=TO4~jyNpZVS8*HYu_7C_mX|E^SP%Th_!%YZ>YDdNw) zM{`>0YRTD(OEEZ+V8NcgE;+tGhh%5uqAnWGrO5(T4M5TVn3AO}k)WFtw8;o(C4@kd zhSQv-mO40cm2_J68gR@u=%`y&quy7K%`(bJiPK^w@VgFf^GLWiP7`&+f04|}!_-Tw zYEdF)=g~Pa;LEXI3*l2xirfs<6-m17qsxj|5E_Gny64z8M{a#QVr4}0*Md!$C}fG#6_Pqu)vZu`Fuh$N(9;o z^wjrAm@|th`|KG@?+eH7DjBvEV02n=ap+tk!`nf-X)@bJwGMRe-UKV&9C7E&k;7Gi zJFbFwwH@QZ1lJ<`vNO4N&Bqcfn*~OL2*KlRZt{pv$GTZ#0?l=-PZ24x z$qf`onyH>OhDgish_=nfW-Z^|b}NM?-SRU#(p|#7{0fmrNt5%v&(BjeOb@Xu*ga#nTtA zj@8~)QFML6=b}PaD_{(=RiFL1mxPO367>2<9#7q>M<)N%2KSNj_6fYAzWkuuJJE$i z$}-I*-(fV?22aUh+JEa2Qn4dI+L1|;)sk{}I}K{6{JQ5KwkQ$oC2=S1o-S?B6H!sU z;woz2x4qGE`Fiq^p!p;vr{pDR`|s?(H#m`bQb_@rSO4C`7k_<@4TYbWHjVkfl0Oh; zd2Wqx8Gk)@egun#@FH1@t59XqfAO_idahsUJaUQL89Q}zCRd21Wp$@bcFOK2w5e%w z)lYx4L<7AoOd>u`YGx zM4?K5>4O37%)OC<>?xtK*;QPLIo+QFMYAr4;l+xWZgKiJhJ0d5`5>`{rrRPOey2^? zez0E@%4Tym_S;Q$@x;qXJq6GedW@3-g`%9mH(C~3DbclJnS%PJIB+AAa%H5;zKIvH zo1O2E9h%5-N{2kb+OGsl2~qsEHfeT4eq8k9POYztB3jX@Ay-{e##4xyCv@DTrfMwb0mY>zAqG`gbS%@ygvsH}+z9+Yv-lB>b z-Q&b>GIMX~td$tcQpQy^kSm4{EV6#L#`3WFnLb6=&!Y*L-e`Q*7+ki(Q#FwA#KB}x zjooO&HI>MoU&W9(@1z(9J@Qa_?=Y>6aw74K(L2?8T0*ILq6Y-jAx0w2N#bLgfYhYS zCJ!2Kuak0gQAgUj0e6#=2mw3>BecD7KokALH2KHNbh5cR*|J!MJ4Je$A=FGR-2ROfIY6E)uv39B`e(yuojg7rR}QN9mwEWG_rF zTDCkfG%Z2*+Zs~ZR`g)lRAvh0xBL{@ox#0^d`^`aqT+jvE<7|vv5svuv;}BxmdKTY zf{Y}ndnn-fECm9)mQemWDTit1nBB-nZaJ@LB}b0tp`7ER^o76lcR0L<)Pc4Dx9wUK zT`ZXS&^_Yb6n>>eu717ELFn zadU0}sF_LF89?@Ph%fp$Ma`oM2D^IuKmsEb&b_Eyd8&nsj1`@MGw>Roz8>)f?b62 z4DxWQgp|F3Kef(TkR-A=ei(%$vxdzAj%s39=(}492vJA)ET!&7I#F*X=*deNIDCs< z5-pyYfP;h54YYyx= z;jqi^RgR{iTo>0dGI?8+*Vx19R)_awo@uI^J-bFAEk*M3u12dJsV|W(DjM!pFS_V4 zsrAWN(TJ*4w--@@F+s;}BSf&UiE_AdQU)Ohhp)lDvR@xe~jQND^;seZ4W?;fbI@8NQ_gh<)NRj0zJ>)D`@bk+; zpnEzJ(SlSq>4Y2*Z!2yP6YdboOue+nDgim~;Arq8;aSwdvekg~GVK<0$U{q6 z9kfJ#?!ddx)S)=D*!03HGKP*ND;OsnJ4*A)20tv~AB-ItYAFkcLX-9sXBCEizR4KG zmD3UB@mtKWqRJz{hv?p8#_^YWb12_Kcv8lekF0TtCiu3FFHXG*O_EBaiwYRQdILN> zSB}-`vJYZlM7;P)pX@0L8_F(Fm%t*oXiWQGV`gO7uzbyO}ClS{_CZ9>U{HfQ{LMq z@nV-Nb%chFMM-R}WQ)d*jza1^JOY8qaYOQ(i3P`2UIspphLhaE$To?2u-9EM|R9;qd?^Z!jxJk576< z^pgX2iiZE}lApWH^4Ci1_w8AlJ4o8OF-t+@!Mc1Gcl2vUWW!2}lX|AU?b%_j#sf=ukCnk$ZF( z6((z9^|&U9y!`oPFhLaUBrAdefD<|2as8i=V1AYq{Stf7#>C;^0uA>y{Y%0≤VB zvN_SLX$W-&r~1tuI|6=|cTIOyNQP<4QPdroe5>0JGn1&SjiFkhuZc3}SPd?+KO^(0 z#8b+N4PQ5ENFx1Wp(_X0n&&njOtjhdbag=FRP6nBhUyn=6=1%=3V;P~MvxiR6NPk7 zlSNd3hUz}&R8FRXu}RN?{p*(riM!*V0cz-6)&RJwcK7}r5c)X-(eRi1UcyE+8(r|N zv^;*M{{|qCgzfrql(z5vfV$r^wn9RXRGt$0x7>Z}N`?m3A0`*_!A%r~&z&6i6-v!+;sdkHC4S9BGzPmzFJDxG|*bbQnX<5(^k4wzMDvK7{GEa&) z^5dq9LQsSJdM9pnSkysO(N6oEhP*ke4fv%mPjM8MlASY>a_ll4Hld**E~B90x|Fh@ z@DuKmn%AUXtYI^!@qUq~*yJn5#FHES1d6A1Nbz6@ zwaK?t6uo;wVQ|5#uyViQvphOSPhoV4=dSAau}HLN!KC>U>&Do|ZPqwzX0^8}YsfGU z=lzPSo+tV)$hO*fdKQ!-1VojjAOQU*ZOX6jnvV%pDUZKz)Hqt088*PbJfJu>@Ssv4x zc~NOHX&9JGzxJ>Z^|lx5HKo$d$<~2lllv=!MUhSf@cg4hLqzfAm*BFkm84+|V=O-o zu_ZIqY;O3_B0J^bmD&F_-wXk*J;PFOnsn zkMJzAg2v>7^(7IP68G^XMm(9lG;~wnQ zhfPlKo-wcTvRZzobHTvi%a|-UPYVUxOQtPh`^a&PMoFk@kQ}c-`>K6R5ChGjfgf#S z)}BtW0xMVb>0o@RN%l#BUX&s!7fWMMw$|3E^;+2pW37*s0jCb!>dmYAqx+J7GC{5MuWggew3CO?n}fp?(&vZs zBq(u@x7weX14KR^(-;rP5 zABN#_StSj`9D7{E$|V$Sj9kgX>&{1bkiBip$_*lBcN^MRv^rY+1HbYWmuxpP>O;xR6nz>x@Q`Hva-vyfQBmisXaf0dfsrU>hQpsJSNsi2M6rUm+?0@EUGpra?Ko9R%^d=IlW6&`^T|)@@uPGIaDD+p!CS!1yWP!DdhZ}83v#G}n zfat^WJvkcbb4OtE2Y2rep93Q0ky9r0#ncel`a!xP(e9dH)%Fi?pJ)u3O5`zIt;#wb zRI*@0o=@J1Ng)_%b;t~(V6{Wl?DW`lSf#y|@pT|ua*xp9dk;lqfJLcugytV+dt`3& z9NX&C2Mx%>HJ%r#L6q!NSjD2Wj0Hs{gV? z$SR3Vp6EWf7R#EoERnOU ztE(caANG??5?gIhx3Ro2Se;?mRWWNN+;oGRf#)(~*FZX&%@Uq{3}#E55joH&nk`l7!veo%6g<*n8$@5e8d`S^V4K&4ZHll5Bg z7uv9r8TA!W`;PVK#g3YGm|yO^kDrV3;7<%hR-^kQ zU57YyT1VoiKdouRD6H7=meUpaLecN1h;+zuiW4GFI209rZhcqk^H}#SxIA9tnMVH< zLe*y7qDT4S{kv+(NEsrJSAYpzKHSf;Wr^-48jehImBnaOWsH+ zvjH^|!Jg(<+RuTUv-mPrLtl1FTt{7%Tw?*rq?7q!8+NmuyLS&`X<2lPEjH--l)f2) zBdEM==?#~wykmO+3_XJzCF@!Y5ktUV5d={7s5(E0iZqr~48W*F9J=h`06F0hCJ zy|AoTFfqs|2jYI3nE3bR)@@IRXitlH?Ug9JYY9fqp-wMzZlFzHh{lH-!?L4nt!Zwy z^?i2R)qdH^6G9mp9-pZZQEFC1Zq-%5cT#!j35@c9vE&HLAuzUaGAVhm-f|8U{Xys4sGv36p@VO9a8ex2`1b6Bi{Xm|UbC^28%14>X^?JhRYP)-n=KR|2TGnjEqE4r z_hS(44{bihC!bAz0XuY^xB2qXwu1Y!{OV2%Lmh^mB(ivGt$fgVY`8$m6umZ3gEeW* zO_k0{Lv8v*haC8lAb&3x#gI==^Y~b&aIZ>Loz;|BT#gw=E4ypIw{6d#gB>|95Nk7Q z$NpAkha-q`i6M&9g=CAn&ms~*R~)zzc=-d1SkF=}JiX)HSs&;o*~o_DB4B$CxFJ_3 zd=a1Yp5jh?(i6(eebUlK2WI1YEYa%|cGi!9w8fM_I-zgH>^X;(ylbm1a7QK3mcm-H;TSRd*}szyX52lJ5x)ipsO^R zjMSnr>B`OL`Zd)u_?~kNm07B2EX3t)5!kAvEI&#+&R+`7HfDEC=t;{}*?zTRb>t2h z@p1q6#*(2pDmE#q$MJ(xCL1&EQqpYbv(?SjZWAH5WuAuBZRUeDFz0>di8*D@%Lkl5 z)$OYnOdR5+7mtsBzMHlG7lHrBCaC?baPRNhce+Sll_N*BdXt){o$5MqvB3Y{d^}UL zUKtXJh&~0OvG2%u#;GXrUg9LJ1=}?xf-$jo>EYVK5!F$2uA9T!G7pKK+ow6{k#;t5 zDmldbl4-wGDW8%yI z;@AAX!}2eKK_UO7(@OM9)8oXvZ=bl;uH!Y?`m|&17X-kWAT^2mfMU>TC@(F!Ja!*$ z;1s~IhScLNy><=``{SHVNuSFmBs*Q=K1|6BHYgCp6ZGp31zk3c=>pe*kmDGQGLJ&H zdGvjPz*UBpV^rGTrK~(BvekbFkE2K33#`g@xa;ouYjU{!M5Ob0r%GaEtd`JWo&iRb zC0F{7j!y`ClM0!*$o4Rk>nuTWe)!xd9qvr2X$O=&f|bObBQ4TP@{sq(ldQ^-YR1n? zoGp5){7KRf1?_YK7fXOH)T}}|7{p8~%l8Yqn0UN$B&b5dR81mOyhioG(Jm^kH`+!V zl=Dr}T;*hmOl|w@Rh|+;j73RxaubI{Nu8 z3ILsJ=EJtj$vYJ|ZbyW?V9b(3_ zsU2_^$s%VU-6)thR1Cc&@TfQ1QL)DVw*mJ7)1+O7q8ia`!A@Md^gy$kX%x_GiIvv$ zF-vnmGoqkh<4qfujMV`Mvw=E>%5+;u%IF}%z=>cEcL?_m>J>S0A9z_7r&LE4r4Ck7 z(J!SHx)RR*;##IgIAZ5`B=on@s2uBtSn0~xmO`=Ap*+{hhKQTfI%i#sGvDlie4#^ z;>5(W&+P9rW(6dR`H93{GX1V1QvvHKXN!}!q(%wl>vD_0@(XHbKmFLJ;)j?^pI{6~ z^MszNkK5S)gdl`w|K2#VI>mA85x#WX3aj~y)ocnt(0awvkuSP@7l<-llMX-B-Qtgo zMs7=|ZC6t3F$tQn1+!ZRH)jhU*<4c0Le3d0DEohu)uo++t=JDzUL8`=c15^fAX;|0 zO4e@gCheCOo|AVYPUw=hg4V2NLFp^~#NS?hLLNd0yy&{3SIP{ePf}+Pwf~5#!du^m#=z2!|Du3exM&-}qlv2*y_4w);Qerl z@R3R{5iaL+kZ(4L5=ecx>{nyDjTyn*0(#}(i}Ayy?{@!rJc)>i;l-tI-~ZN-K9T>O zek$se&ICX5+6DSKvRY5KnLc**X$$((zbiJ4QmQNGOH|Ow4M6*%#gM9g)=G?H2d-yn z>19Ssc{paklwC6*jJSVQtV|#OE~lRo%#Sy_)vONX?y)c)LL!Akzs?PMj|JCzE9Z~V z3jJY>2~)uf>EH8$`!FabajBc|w?z%@CMwf20y7i=ftkSkG^gQYKpux<%*1a^&9ZU% zFqMP?2tnek7;PA=fGPsJ7dNV)^PXFu3^zrowVcDYCEvJFxKWmE(iXI6P}E!nqUpX$ zX4W9;_r)FWF%gwh`!&~h^<3K{G1X(WW2cQ^%VRYc&1REEdKdB)b!a^_<;J$p#9Mwb z@7MTxc3wA$r$i0uawWsnSFD3IEB8S*Mr5}tUs{L?tttH1eQBn%7>Q1!5XL&Z-Be=G zAN;0}%uqj2SGnLFRfR<#jGT9~)!XC})t zdv=ESNhUmz_H4EH2iiZ*GR=Iktgn=sCYhj>PZyd7*fIF$=`_~o;088Zs!)GdlLl@Q zI}G4Fe?%l-D+hg)qGPp1=opUwSl5jMK-kYUS&bcWO2&evM<-_%ngc-@+Dmf7s)$L` zx|S%VF=I0Wd%F2Oc0Tv7T8iephpE(pj*G!sP>0!VzGB<>WsB3Ej-XiC>Uc$`?<;Ac zI{TlbtDQC|d+W>r%q-i0=hn5Ls`;BEH1%zfUwu9vr`ei>BnAj^i)|E zjOU;7gY?17-_9+PlJ zzP?#}%?pUi$Z%9+PBr~r0mB_5 z^%W?r=@qRNDN^6c#U3B#4uM|{Eqqi28tDsBHY^Y$*o9Su7tUHb6ptYHvglJbg66hS zPgYzTx-xNcSOOu)tn`-sUM}eeL@(V1mghZoM>f|TJyrBOr+1s(7%i^eObv%Py#CJx zo68?<)F53dq}b0Fa@)UagPm=LcoC}P3ZPJ*gLLG8ZW|C_9xG4RLkl7f@74GFfJ22# z944S?PT!}?bD`w%;hhW>a;yj@1p+s7!Qk>Wf`F+{J_W3h;R4T;<+Pv@s3mQ!ck-DG zkY3E6R2UNPL1T~e1pRxX%1TprPKxE%i1_RCg1Z3obb!OW4@vbc8Zyz)`+~ME(1+)r zCnGa|*2WE)&NLv&s}s1I+vQMNcvVlzT#}R9Jr^auWzB^`y+8yt)LuMuNM_6j#NaIG z(0#pZI!lO_#Ka~)qae><6wVP7eU8+6OtYVA#Ks~qw=Nz}_e#ocp?Meg_rv}B_*=3< z{|S49c4<@UHicl2yujqmfULtZEP@9`mHAoXetCkPZw)zY>38+;Y8^L%>kU(f%ofW2;V-50y_ z?^Y#i;T)PWTKlC|x9O)CqIW|+QgS(mm#>+Nwx&Jsx{|R zjZV5H_YCFp2RP?tq}V4hXn^F1;(TQn;^(-mY%Y8zsnLinkoIDaZ#w)v*O8O)A|I~z zSZ5d*AZ{$a&4Gpo7D<16cSTy1l48BF{E>xDbv?@L{jYHyidF*|k|2jmF)qdheC>_x zxjLk;D7OFJcsyS`XH`2lv~$HILl58&7@M9y2+e^GS7W?89YH&%+J&>q{ zLzt42VMLY$(y+zuKFP+po2L`G_YS^Ca!Ikd#oXJcA#SOG8fpCjXM~C_Lqt~Kd$i3Z z!K63Rq#jcD7J30DZJLNU*Y|MS5I8UdUWARvK!`|keGk^XM5^6F59z}fx5W2c86U~j ztBg<#b|rUFGdzGYs~zbjmCj-Jx*(q&kRmfi0w`$5(j?xuq2W_%X8JVf2yOh4t^Asa z;)AkG;8z?$Ll%UKBF1N2czEGTfM2jVyzRG3GY3>uVCGEF!RrZf{Jg@QzqxrOiBdD> z-RWxXekNOO7?MmnFcG?<{y`dJx(I^>CUdfr>R^eV-Zwzm$HQ_*F#`LDmt@^5{O=9z zH$XxiM(pFNV~=xCcJ$U1E?oe0Bk zQfIzse%E-qG9_qX?;C$#w!L*-G&16wtE}6g=~BKVFsUSs=w2m+CFAX_D@%^c4B99_ z0LGtArAz%V1^Pj61s07glZGP}8zA_JV}Bx)sdF4m^b-7{shO(Q>PNC^EG25BrdZZW z#_ylsQkJ`}rCP7@-#`Bs<7wFe@^x11TEtp|9Yd`0ScLBc&KEZy(ZLG=gOtw{1fk@j zj|5&jUq%l7^IM~#=kPqff!*8@o3ZN7JhU186zaNo((&g=`bBQ`ZxiM$ZF?kk?I+cw4wU_E>3XA(EAFt^+c&OhYmVK0)(eoUYOvm2ozBmD25*~@FX?Mgbf(jgRczZ(Ji5_bgNmr~gXxS#bttrWn-XgUXnTEV7?~VBaSx*!{rjWM#ZuZtkp0ia-Ur}5 z1J#*n53b6z!`)!{v>%h03*ICHI$Wx_LZ!x?D6-VmBmPVMlPAvlv*-JpFFBIDuJY0rv>C5Fa;9K9EVj40d)Ra+ zd1yMBOgw%uqaB~H9=^@@2`*Oiyl&Mvl@16<1moAN1UTnASB=Q>?M!Ujw(ZRAd7gFgez~X5 zs+IV2|MurH&NV_6A4Lo|4@v*e;*|;yv6>73v>c_NN&|LKa-F3R>c^7z z4v*}2A@tCMz(c1>%t8{UA_V>QAI-7%O8Sl|)JY&o#^Ic4dkr9Ek&�o9AXUnEp+WCfT zLK4?f;0v0z9|nU~QAzLNUA=0+wyX|&(2%Pa0H~YDRSZ4ZdyM?!&bmu%!lSpRvndD7 z{H27D2$`yty=dMk($!0lmT@4)@Y5kh?+JoJNs$#v`hdr8!)8pHF8RcfmiC57&7LK8 zG~5n`sW(7;P!4+Fi(IP#k?ba|VSM$P5=RkA@Vs(Jq{<5JIXItJll?fV{NZcA50X!D z9IaXLW*Uuz-tlFJwm^x*CT>N(Wz-goE|f{QC%!)R$B<&IQ&y9p2d-ksqB*S9gql-h z`=_~`mz0(SAW9fPn->_3Q=Zc|uLMyp#~Iq}6>fn*&Pu0_Vb_J*4|!>!S`m}`qS1$p z`XTrMoIm8UyQ#${b)caGbNEaJqyG+sUO&LaP{IUKmkM$bM+^A z9IwHeSMxpt6K{(RIaNk&j_f%#o$LP3DVN?I{?uKAnS59?@sdWv_KBI=a~Zf}>6S$v z6#xP^#P%R{QCP9IdA~%M>#-fV3AfU??+3U6j^H=^x&tP!ZJMDoJ%XJlYN$b1KI~d2 zI<;|5dgA7&ZFLlU;mjoc1AMxk<;Vy@Qj_7)$Ax_V=P&#mmN!X|vR$x%ywWl1agk2o zWf-d1TaV^ z91Ny0g@9>H|M*A|{~;v(vyx-R#1DY>`TsuuegNU4M9%Dx8W;Ln+HYDsikxn$5h?P^ zr?+*4$fg(Fn`<6r0KG^@K`gvTO)1PR##>riQ;V| z)E`*|WmfK&@Qa2nfMuBrhnDo>PdU3XVGcHeaIDmB&17O%wWgo*Ji#u-hZF0GIu_+ zt<&vJURq+JH~rrJJIfrliwed>^wkE>!i1}Q`ddPO2i5NdJgz|*i!zt6HbMl$Is$=3 zzSZ&DRdXw@8Mi_%zeP@WL(dHi%2r!C8GS_BOF5%J-~$X^dop86JIkgiG7Ps8J<^p~fw0 zX_0k<89bp}#|U;AT*A9Il%U+C|7$AoDV8f8-*e&Oeqg_6eqkIkLo*j&yxG6Qo2p~J z1Tc1vNBn0zNZ4kMtm^1Ux0kG(piSC9McF__UO+{j4@OoDMppjEt`v)+`)s-h!N}9F z>azZ2^h0C{rA}E20xGDCC7`XPSjFstA`R$j;SnHlj!}8Gh-#T@zsPz&0N-5p*b93& zuIiHJa}YS)*kL!9vM|0Z4mc;N>9QTOtP|4lXI<@M?d&kZL~)c##e&L z94#yOKH$%Ss=sIB_+T??x5g=p1My5?NvlES$=A8NM9gx_3WloU1SP}mwA zs)KN`oSnvcN+ZY{-?+`Q7q?Bl+1Q_9GmP@TpEj*N>>j%bbBq&l_ z@j>#RNWAeMQG8_X78?~3tlpdyYTo}mr$b|^oSFZ5ZgsA}g;3B_sJ*P-1PartbH5n* zY2(sxadB4AsB`H}mzfz_nY(Yt zB3U^G_4a#`MZ82qf+{!+twh7xj~2W5ZQBiVpf})R#B(J%40|PaXd2<;%705I9Red# zi6D72Yp(s2%FF&VLNUAgg;i$!LY{&;g%Wg4VF5K>9A$b-kS$2%|M=5vw_q5*48ToFdK=_8}9#qbD z%+y(%tHKB=;n`B;0w-84K54^sFWHM+TOm=stY+Ey-sv56a${*JfDMnepYelzf6$vV zX##kNh*o?XkFd61f1l6bxX#uhe8$hGVtjiH&qH=H3)F~MM%S+g+b_iYo4YWB$m zS|wPJe9#M=kPtnj2>GW$@$M%BU~YIUI{a&*aWP-KK4UY!rntR0yTh6v{U*=-`SaYz z)>3c8Ov{krf}nUXM=>mw<1uF0n1*$!N-Ap}u1R+=`<2faQJQY;*q<)5Q!rPqz1^7I z4fw=#^JUP|?Sfy$+RcfOb#}TyRYO@iLq|+}ZRrEC_qCGLxnatrrFzB{MNYLXWW09G znfLQEN(qSICwB}dO>vQpSX+5*SZjgdGaQEeV!~pd384zYQt0T9q3X04#U)&ak4n37muZdnR(w1E&Z5zRnRO# zWO6Wiq*RS~*#%Bg$N6olzu&R4aFIa>q4u=z=0G%JjgBib3Da({YV0Xuht}XpXCc|Q9cew8D!jvn=D%U@VEHe_&G8NHB?nyk)NL` zEX_*rY7)oXg&efaIt*)$(4EmSOhv-xgfqJ_IqKYb4640Sp>t1iJJ2^f*)5#VmfesV z$s{dE*&j}tGFF4Xhp}E^nGzZBiSsU{^>UyYM4m%(y4nGpJ35w`;2R}-9FnW zG#(!5Bd-g~JVa)$)g)u|J#G@JzIC^w6xiW1_T;IaJzDyT5_$mL$g+f!X?z_CQ!#)S zpsS+!f~()qd^hs=nm=Q74-bN^NbFfj3LSJCWD=ibq$&v_Oo|tZmSGXK8496qRhE>z zelX_z_ESzYDWZ<#Cp}m4Nx!zHZgmWaf=Z_ct;B^T0`9dVpF;V#3@H{nchB91^dfx3 z#E1u4srba~bw`ATc z5b&?yfQXf06iLbbK$7iHSL)cAZV=>{5|JMsB{^CM7>!MQ%>UF&F3~kOPavlYSh6l{*_SvBmatF*t!MzjvQ~ z7e1`JPn)Lny=@y9GgF^+i;1y2o?MqRP1E&u3Ovf&X&Q1F!gRkc^Gxi%uwl z13%$HP3v%%wiy2y{u=!3ClI~VXETewW&jaK$y!KDOR6kb?WBYc&a{3Sz&B4KuAo3& zH@`e7fpM&BnqrtILE1-R3vDH%D0f?UAv0gamHkpRLMT{a*UvsQv0)V#R6@p0VV|$6 z23Gaf^1_GP`zgQbzczMGS-!~ap7V1@v&9WR7{uV)@kCiaBSyETiH{PIX%2Vs} zg?!j8SBq+%aPmjL%Mj{^#0UR-*F*2$PqNjIdsmb=9uzCOJuvtX@ighSznhQAz5-K6 zwPi8m73Ok}!_n>P%_g|qyn|jB%SQ>kOl<0VWMWRJ5@+dFbm{=$aw?Sz`Uv$l>z_Aj zGw+d%l(}@%JI)gB6l2?6oXwVA^C@l*$oIIoOZ))2WPZ_MZS{~Wt!p;+<(mIH{_E2| zT-F(atJuKfp;StM+-f+fsBOUYcloBj4YQLT!bJ=jqu_%pokO+q_@2D!56K z8!sdR5GJzd{K)^P2x#3YWlMQWsklhR(H7=(c$uPFxym*Mv%IR*b|Gs%p%w-E0% zK4doR?QLhw*}o0$`v|QW zaz>)h!kxd|AV$`o%eE&az#2Akyt#eP`8p(fcRTjf z#(ysbC(cn>($}jgQ;0l`Vp+pyF_L+xDZTAfckiLfv}Do_R`Ez%hindzYawjkjP?qPm5Op(%bQEztz!pz5ynY5)G4 zJK|nLdCN{~_FLj^-A-xFPHA>X1RbZbiYSkgGGN@q5_b4xstQ8|nvL;H{y{>E;1W|g zSoNBwuk8p~_gY3i$OX20xryO)aVNC~kGLxF?UZA_0Q@H#GMcAxG}yluLra4~OZ{$E z!Y4y5f5`i$0j)A5Y%!{qv567OlxCZ$V?S2+ zZk*khLkAa%w9LKf+iqfd41;v4r7l-!i94ie9@4PGwEd>P<+o0|gja00+tSn5#NagG zG@lMjqV@)LPskrqg6Z0``18mI*oVmnk#5nTZ=46516;o+mJWP9@$!n92*i*N&CvXR ztP{&dn%jm4vHXPM_$fXJ4sK;gDo`dTO*g(babowe0mZnM1P}04cRG4(Qag6<`*==` ztqQJzp!16TYcf$2??GfiS6>`G!i0gppLQkVDiu}nEq}3Pl3W0>KBtvT*Nd7An-yH0 z!%mlf9P31b^RW1icU_8SxwA@S8uhkR%l?02D-B8z5ZYp-ECh>9NkZ5irU3>@eaKoI zi$So!kO`@uUa9!pP_?+rxYA({_wYl`R5cW80GGb%8)@=knVVPyZv6a6Nhs)jphGl= zXA3mG{}%xi2YF6P7y%$2CG%c3n$hJpgA zQW^PjL-m@K+{b*b?9);bGHuH6n|SN82+q7?%0MkqYSt1J*{VdjlJNmGG&9G$(NOW& zZDw5i)WwLU+{)oPQlS&A-!dSoggq=>vV8D;X>*o- zdQ5Xby0&`_6WM)<58BR^Xu1 z3g_z1NqyRuDI^_BX^EQaO~vMwV802a9fj^J!Kn8)^@zY0LXmO(RUsa-UZx&=OymhG zBnZwb2oAx8l*5uZ-B;4t?NP^-@Jg==dXk}rjufI}Q9E}S))9x$rqCO&4lCuB(8d$& zv+}nUn_;!8-jkvXa{rf1=mT8?qys#;mI_2-pTH3*|7UpBP+mVmlq%$6z#sP!W;DYI zW12BfG5(+R-9+YJZ=dkaNEh{qs=;sOMEp+4qtPjhi`WWlg}9#5!wChavbCmQu+aJ6 zPmM(TTAX_85SL*Al5he^`jLbS!&*CbVKxD_=39#_(ddWRf={1Is9?4bUk3?rC1VS| zMq*9_*A~BY2&1h-M5X-wlx-Hgh>9i`l*`t8eS$?+nE>r34=5;5YL92t8Amm|f*=jB zDh0Br2pY_z8ZZnyQ@VeJxq(&i<)>c>{X#KZ7@Vxek2-ku=h*2}W0Nk5+L7bdenasNI;>><&AY*5f^NW-t7fbA%fFu%`9WBi4!9W-2Cvsk z?CC6Te?Q%gzr%P@bx_|l$W+ra_FjS6=B($ZD~mQtpreH8@;x*hT{SM=kbTVEeyp#3 zk6-&1|2uK7dH?X_Zn+k2ky1627Bo5Egv>beajnF+c8OKyCVOw>i74P;r%-p z;V^4b^jftJlu3MhHnG?ydbK-S7Y!#diJp1#tE7zb)am^7>Wt@k=MXPcqS^E0=dWEy zo9tVmFm$W;@vD6j|6@a?HDY;bZBF>NHAxARWf}`ce;nfX;u`D10^X+i5wA+pb!XAi zrx_Zqx_93W)GFp%hzcZyJvhN!x9%7LnuC=$F)b)(0lei`J9F1!D{~ zrlO(2g5~MnoRY*c!o?wRTJg?e2cwfz5m71m6a^tM%Gw7tD!lPjjF3?q5fxv^0Hs9Q z#i`Da^h6jPdRoax_4X)N5uL!&4=9TS$G-|%U`#hQ0TRE!~xER zIGpBv*CfbkLg_$#3n`-%1j;-5{5I5_`Pemh@nfB0K4Uq_Jf}5qK2*qBwTZxUpJAHJ ztuxK&Q--8*KV)8r#^p#PaAadV`UfvLs zk^Ja5XqV}i5TxUBfwPvw32_4^SYeKZyC7#B0sA5_$dQe^pyN?UsAZL4V(G%!4+SqA z%@RjVY)=h!>RK~D6m@iRO2jHd`~dTBm-@y#>X2MUk{>Uq?lE56ZV0u}bgz>6+i^fy1Z~;(e6#Ue z1`maT*o8D$%b~bF7!c#1I5=DXC1V~~V{jxQu`dYK((dDE3s+s>1S9fv9MOP)N1f|NA zNit3n=xw^4T>Xa3r*|E+e7q!b*76kZ``vrIM|+n!3Psc=zx_si23X&4T?JX?Ol>KL z?5>zXDTkN0q0rQq&$Y?KCZOD!upp?DzJM|uS*s|qj0g@5U>9pD`%dpASS^)^9YEjV zY-_Y2^o3eg%E(t%M_Ceik|c8FMh0d?AoP+MeYn1oN7vEz7$c38NB}ylON5&*$Q-l| zz8PMDMOiRqFiKd5d5Z{sjd9K1Qf#O8iN+5JD=`asl1#=W5~nuxo+iiN`p^!vgdByZ zFMlOf$Q%0mX=-veYhZJlekQfh5({+3Up8#YtM`SrtZ+f)Lm*q2baj4D-T|)l;kcG2 zqkeLTi380*lOC@*Cc%hSvls=QrfUnmH*zeJJ2v5Zdm{4iOV3>T$ z7Bg8exIH#f(E4)28A)aXTGWOAAnYad^Ee~c&+h8uc}30x^HL=4e$G=|RC$P{l!sHy zEo?DEc(4Bb6d-Z|G*nCrV-hLFBBiJmuCKcOcq;&LxE#lY1uDu(YFLfE?-gwT08j_p zDJ*j4(m9YL=0N?zVen3KbQl{)9Kv%4$zN-&$+Yk^C1A1qB4#wkRZu+MKsJc-XnK;R zDaI;8^YHi6hi|LGAPTwD?P0eGbH+yCX%UBQ20;F*#Xoegv@FKR2EgT;xF%Z2C5vwH zNJi#(nN9mGz`5qfjUiWlDlX7(8Y0@N{c3VNHrNV0>=7bKYWl#+V8729kS>~ot-z@2 zJ}~77d1(hA*dBSCib_>@B1~|+k0F5C zG>9h%^wyI`_9apr#u(@hcOz;J3Yv}LTJvx;H=hn*NI(=6AQhT)sZI8`U}Ak3Og}Rw z7v{`E11sFF$*zR2Yzi^P%nbtZ$2xAJ1ha&0F)kViR_62a*q2G>#0Z2H3A7Ceguc?X zSa1vf4$;C-4q~Ic41F)%sdqWIlbM4Iagj&C9O-txDL!8>OH8?zps21&

#1|VZI14_!pEN+NbVq!5_ zeS15$zt_ywwuzPMuIfIsY!ZN8=GcUm{r!NoO|N>F=QC{NEp~uQo8oZ@PN^mIuwN0~ z*>xThHXx&!yv~^$JJ%om>KSTofn{NM{Jf)iu{_vMA;2wAApCtnpg$Unh}WkENM_Js zs{JuK20n+tK1M|g#~Jyi(P1j}S=dhg8qCSLyNQ@H%e3O@D49(3&Ih5ia`J8zxx06+#z-8?Qgm$1R+jBWy^$E_E6*Hr&0TWM zU2{#{!<4YAael9u^FGO>Q!>>p@*q<*&2mSu zyq5KAR%~P&Ipe(10IaCEU{B}HoU4I-6r2oX=mcEPIrJ!E10h@;^0kzS>WmIsmVcd^ z5J`U>UTk<`q|?kORJs5MPtKOwpucGpd zRxoa@bZ?E+Y_-<>JFZl_TC48qPbGT88@V#ZY%ToO54Y{M^M`lGhXjM*v1YIa^tQ9< zpL@>vt^TcKgt!K~oK#xNtkBtU7j1^(v69SFe^_Ro$df?4&|c|BW#Tc>6oI*3cp(!G zu3`&r=o-8-d)m6MwN`xsQ9DDseJF0Rv`b-hCL)-m*JKT>nIm~ju~og%SdZkI4jv^>})pG_FB)vgs_x z4R$FYXi50ST*;uKKQTu;?{lH%6^nfDwYu&TeMMqwWlRX)PVq&8V;+qr#~2Z8*-4-{ zEd}Z;CpUk?$k75Nt-_;o$vnznBZaQg%2wQp{zyLJ-hAuwNy~1qk2njVVhGNevjc&b zZ0>Kpt3+U=gPh2>-h8u5?M*MR8xA_z6%1#pl$>V+#1YWaNuF-w0t=wsvQos|f9DrF z%odQY)1k^L#~%8ehf!R_^&r&32tecjnS?$TksU{*6eY|!Pnb^=xx2d;o4M{IuhdW1 z2;2vCYZl8{xh;qr?0{#UFZYNYLhb0>-Tw~#T9;o5+=E;x0dA=UIZ~RQVW&6lAy_Cz zih4_cU3_O{4HkB=hPE-v(qc_-O%GW0^D|iV6M_TUE_!MkAIKqY7rjmL?=;LmEl>_I z=>MEFGqXzqCj^A_q;e|PeM*w9=)7UYCjn=jjW;!_H7KESlGewY)gfEYg-RtGacW!7 z?bOAN$2=q~!bMK0QQx{sPgHt+)rCUP9Yc%7ey?F9ml|M%QATbW#7a_D(t35Zk8@<|SJlNJE9pJp--rm99HM|{OibYZ_^L^ueLNUlpYuVk* zEZ4P_sXOq4@ZO|0S7Z?vz`-Mq^wc^jTai zj?m9gzi@R=+`QIYhUGUXQ}cc$s!vdE_&j!)MFE#WW zNsMb6Ndy&@GGN&m30Cp<+Jx&-zTUIYTA}fE5#ZyUBEdU$_lC&aq2gUE_Vk1e;N}^= zWjEyW*^E?h^z)GYeij^&Uz6^L7Hf|AHsIO1-2MzD3%7l4H857K3>RFdJVwD1rJQ}o z|Dd*m_aH7#Plf}kt;Oy=q9{+_NdW5xXWO{%rqyL>G;g<-%QRppXJy7dX3B;%K1JKh zNg4~Ycv#n0kdKJ3Ns5znGWc6dniJ2Mvv5h^&oErvi5h+nCThjez*XJo4d@w0Dd>M| zaF5PcJv#9G`{|v8t8vx8U@$_uxPysYa9eo^5$q$%HHQ|528&E`)XE^e4S0i}Or$J> zggw)m_~(|_o&87t8fV~us7FZf(WX5@f!}#}-tpdB9BXpyHpyV-L6!kOio3)!Z&kyj zw8?ltyBr9($i{fWOyE!U0etba{>S*4@|fDe`&NMv5dn5*YHIp(z&;IF$Oa+8kFk%V z%a=a9OVV~x={o8(K32go95LeeGy_;+<^PDQI9ee_{0f{|;+M|4HC^(G*<)IEvKLc9 zcT#{-L6-F9ni8vt@Qwim@EaORzFUYTyG&>ODTqPoM19O02H)d5u%egLV{}%cFGKuu zEbo0{{AOtvnqI)&a{)K&QD6^G&%4|T3B|M?9lmR+nB*{eu%+bPLx&7TyG%~;{ZPL# z+Wc)oi?Fu?|5rIXh^}hyYtFsm17X>s@P%n){T{2QsW`Hj=7#g{zsrn#cfKu03-W9- zEpr&j3@bpiOCg;`OvW37qcU+Lv3lU%)tMGJdy@u^el6kR>0Fcsn;CVfs6yr@Hl3f* z3+CP?BE|G2vRvXyrf`7cFNaQT1 zg@%x_*Wh4wyrXpjyxu%lbhROTv2e$zXpShvi0$ciE_Oc!{9Qzf2-x6lBJrbRT>_p6 z$H~j0XjmR!0_xrZN5@KkVY~5prU0y>Su5N3Te=R1LMprAGK-QB#_avs{h`LP#5CN; zZBF}SDUn9}@(EK+jtw&Q{Qis08aj{WP6?bt2hXT6j@tyzO7kDZEG=K@7q*)cW2tML z86~8`EWe-EyT6DX=&Gn?Si!w&*sP0qF(rR+dP@{ZJRbYt>cJ2EkT{u~8weky73P4V z6+lVXbj6JMQ->em4}K`R^V)KD5$jBS6rIbt10@8F80^>o-QMHZl{3pludX^v2{N1O zZ}Zs=(WKM2U)sl^a!&H(S*yuSHNndms8_b)Jo@*7mW>ieGdU6|1~F{UoKsvF~B5#v>lM;|$riBE zq9kZgVrVh?5BI$os_~QX4%4^*Yt~|e93)Z8HbSxM9Jnc+J^k&}5w&k2=C))ekosJs zQ0YMS>TFU*{|MnbBz<6P1_~lr8HP>BtFt3hXmt7JJl)4VORjur^R*;=@YQ2H#6by> zmQLUcDZgnVMDe}P;d1YIQ`9C?qn+m8PeX>OaY?2~@iD$5)(k_YcJZZ$1x1uY%$L^> z*@HE?Nh+oxNwK9GS70xuKuaRf&b&F}}3^ z6yMw6yAk|uA0C&hP0!suxKa6$IAt158+z+FWYUJTVy$J4#7@AFISFnJ5D$IB)8@0n z`yAJfxP5`pX!7<|UV8M-uyE{hk&!J2zr(G>2c#RDKo+Sc1~^F_;cWMiuaxu#;maJ; zy}v$#fXtJpQss+USix9MMlNU#_sW{nhsccIi{Hzj7e;s!Hlg|)3MNXh78{eB3}pi@ zcBcMq?7#GgLlMd2D2$hQaa$brXmy10iXG7|ac*dw`l%BWB<-B&B6GIqc&N|vMdP!W z>XN3^hKFg5xHlVrRnfu&danBbE9>(Zq#~n4cb7p0c1z-0x_0P zyxGOIcS+k=iUH{**G#5+yc8LwMT|uBDw$#*!l81MFL+MZmS%fGL$&T9YWAt-H0-dE z!uT=#gPc#`CJ|lw19;=Hn*ve8V)vJ?cF_Unq~LDuvA}@`cw}>$7V?u?8Z-0Yn;@4? z#FnWSnQxO@n_w=~=f)XmTitGFaE2J1B7V4E5m_?Szj;)${rf2a z`24ZIoZy+Y;WyD9%eorx;Cd%?s@ltpEU97mEmRJ zoOZdfI>A(dVBnTazF|kQa7IIhO;iJYwOK^Re3?Wn_wIwp=e!jcpHxUE5FA-u@oFap zSI}$X;-2$Y&_^C_7cF`htt>YBsDB^$pz2^o`?w+Xp9}XjRD_|pIKwhWh=?SjNZ+Ru zsVxvTTUTr~H}L{i-(d8`;}-XPa5JMKvAHW^U2MUYU8`lV?P4)NeGvaYqXi z{FaIO5@XJIC0cDsXxdDm$oh?xBEN&@oqu+(_*7a)QnCV0;&829_-eR-?Ab$v_o+rf zCrkMn@T!{k!XWOFDCVPAD5wFD-fRZU+(gdfdKrclwumpW&j>7(&vKO3d$`%yF>8}r zBzkMQ(8R;TQ5$~0{`-mQ{S^o2TBIMNho0yJ)Mn7Us)*ZE9898tZ%O^?uU^&2pYH#G zA2kssBpABv*a&GE!AZxa1>?s1O+6TsfyrXwa@r+AF(g(yjrw~qPXJ}u?9(_{$2t^2 zO|9|S2d6985JY+s-0U|^XcV&-IlE~RbYX!Hal0Vhq&vJ~2dUnfcbfGrmm$F(PyJ-^ zv-i$PNs`gr(~1APmB@tmLdD9gsV!a4?5pV_tW<{ybwvbcs!`Bcuu%vm0E=45qq02jNCV+ zPT$)!1k;s4%p{~8hnJlch_A_rC;DMf2kNM^qbk-fBm*=hU;E7nslH!xNy{~#;`Jw7 z2wNl7xAW0s`Q;%&i4h`&^AO>?@-Y(m?P6bfIuIg<^AO+*4&(}Xa`|%wbx!P5^uBVK z1>Nn(ymNm4NU!HFqAm83O(mL59K74kdFM1z+hQ~r_Liv6z5Ng~^f?}F4PMQ-Mj!3i ziF^)*-2nNu1b?sCDRvqAo~AxR+7Kz!VQATDfcP5H`4q~%z+fYYPY2#){^y<}(qzK& zN2T7#e`Qeql4I*UH<~)Qkb8#Xl4G}BebGY%x-PO#Dn$N&Z&KjkRIn9MG&>Bi4HLQY zHk^BcJumW~$@!)FNB0uL_p`j1$GETU>IBF5E@8Nr9NTY!@J=K~JKi~yy_z1K zq<9Yv_j^c3(k8)l9)xm6rGmRLZeMTCn9mujYxzKXEh;0o@_Zvp)X6*4(W%1>V`uiQ zm8orX5wkMgxwpn9XJD*tl<TGH!MybM(_HwI)c9cH%7S+eDe_HOV#m-99$`mTGb_R?*;(`y-~sP3 z{uCl}#fQdo56=PLDua}nQ9i4sg8zJIXrSYG<4#C4-q0(8t1w~X=J$#OoCDC z&?P;)0o3mn#n*S{7JQBuIsgVB1&0dN8iM-oWFf2TEOQ-2^<^N1eugwh7T6AIj%~Mc z!tUMKLSHZZ+G9r$58S4bcH;6v%Zu(*6F!O{kip&IC;;FNE0R`pPq(7>gk%Pc$Cz~` zY`#bYA@H7c;AR5$(+vGriNfbRL82iP)t9Xtp2K`bny_ymjRKWT|N9PSH)l5_l06|K zIITv#j&X$o7-C%!djHknx;+xz7pdUH%1^z81!8I&gG_7@Mr>fE${-v>CVV4~A^YfE zT5$~rqpIY~&tGovc?@-BicFT>3b=`0{(d?U)nWqhLB#(3rz zSOTP*cTOzh$P8}RLI4NbipF9IQ!83~k&ZN6z4j?x(QBX!yqTI;id{x~)}Qn>R*fsL$m5`9q`k@;@3?k}_SpGiOubqfT z3ns-V9S{8t#2rji$hPAmK2TDM-y4V@5MDqg6RibjTSJQe4iKAMG`}ira%On>V*^#Uw?B`7nJxG=n~zKEXH_S?*+5N}!K?3Z+)neIx=;Iqu#* zi7BxivNMzz>PgAFM_1S8?mYj;S`D+I2VD!E_>MK>4Qu{h`q1nNcE}Ww)h?@!3Qyy< zp4}9I)aGXlI)!W;PxxRcm2%xm8??Upj!Lhm zlOs^fqN2IX$Zo9fNpg^4QBNy3E*=y_Jn%f8lT<Mj2GA_dF zFs}XO-B~JzIH@fy$)>DYL0mAQ-HJso0zf0D);zNPA6?ij~d#~Yi;IHC6Su&?4M zg}&|Yr|YyQ0M;7g)9NjF3kcpOv#zq-m>-*B7qF*{Z7`e5-f4t?i_Tl*i6F0IHfo}b zmWg79W+s)(ZDcLLVgT#G!%5w!VMg#>ZEr(F@kBrl^`?_4d&;~q!@aT28qpnfM7(mn z@H+E8hY)3$>KuveAsyF(8_zo=j`o*tw^+Q7AH3fS`CX9wM~>sw%C4QUD&aFqdwBc> z2cg?G6tz$2!d~B0<4SBvBbzUFRK%-207Y)WPAexHC2q}VVM>gxgSx+?2bEo}&BEd@ z1R#$pRBB7mXpZ;kP>KR&oTLNPw0k)eYbfQ)jjA)u)n72r#zOHEm}b~X6pYhh&K<~h zBe_!7e#Z%H4X@DS0+q9prP<+=FuG@2#bzl7#dBuLX}>KKzg;yc?%_P;M(po62<)OF z^Ke{U&2H7WeM1WsXWWJ%?VbsDWmCVhs@XagMnaC~AqBchieJUYY;%(KD2BUAs$Yf2 zY=ekvum=6I7+in$i3GOuU_K|8p+-MX4@mkCdFD18`-|@7v4}2dU5S>$$lf%J>rB}&95tdyOppLorh5j^xz5gR_x)3LJ=gmU)VEh8tVc}c>e zY1ejj)8g+Z1k=-xZcm}7w6mDK*Uq~EeznaxW0A)a+VtXx$1iZzzH!Ty<8I)JlUfQ> z+8`=|H?Ia4#04rF6>>v`LMoal97#nWPm8U}o?@Bg!uV+tRmDaLH-4`2(>d;n!v0Up z-pbU>s-eAZ6URgHmT&V%P;3X%dwuc6QJ7NtB)p3xQWi5a+z$GqnP(ysRl<#j>hTuO z@~UrTIJCJHchns;DO5wrliAdWvun@`YA<8WlD$F;T;IpTT}P*T3qp^)*r9X5U_I>yH8 zt@hGkj~9>ky|jA*7`<*VYSl`cog3_YH6SS?r~$}JWYCPM)>QyPp>;-!MELj-W%M|J z1P&0~<0;SoNE-v*{rw~C%7$=`aQtJi>n%gszWn`!&R@*WNQ7=4QgCK@0v2bC+o$zg zuW|R{Q@K^De)sblm_BQSrhI@N`knIS_H4sH05eUG754sNXwsb#1K+|SDgZi%LUBiN zxS~@bRe=mfqOlMI#kg0m?&1cK9M0cnVT`2SDgn&RPFLUce7yl7Td25%C z&V2~C(P%rGj9gOoYl-Y+%9s2@)G|!T48^lg4L9>0>2BuVIpqb!eL3%UQ?!39>I&?M zdQyZ^XIvb~%*F^+vN@e= z6UwObNU6e6lo67ZBG+mb=0CN@yLSH1`9II-nMO7jodHLbrBbF;!oi?a^~G**rS~r0 z`DQ~6xC}g!WZ+-JZnhHwVnxgX1L6Rcn7a_cCG_w0Kg2Hce{QJy{Dw=1Tyu+E3yZ;J znn7VyL$0mm%yA2y+u+Wxh1x?`gF$}Uh!jNql+;ExVd%Fx6X>^&4KnveBNJcN5OIJq z8LlK=;I7s;{`-12(H3Z}^9IVMG4UM|qfYj?{@#XYet>K`RK4#lFoLqj2R3+4 zSZH1}i}$F=GaPb;%uDc{czx1+_cY(z_`TH1cD^%xK>`QeSi%Vz^OqfZ-Z6Ao0m&@# z@enIqW*cQ>kDk0?stNi@I8N$swww|9Jr2`#`Z(=?$c*mUW-ga6X^LNvBsur82h$Rj zR*%c96i0vJA8_=3NUG6}xWd%AwcE7$HJ1rYt0L}{Ly2isAuU91S7O#PytsusUgCK0 z<@pJF74xATvx6>afApppkt3|#aLJ5a-@;B%AmOPa;Vge0qZuRAGC=~> zF}RV%1_fIwBi^`0KBelb#(iEIfnpLrAz~c!^t#$|9h7}K1|nX@{wM<`Q-uVgNpK9> zErEqSLwpC$1Pn3BfrhiYdE?~Mnb$2vbWQI+1~e}>Su%)&?as;a)N*cuE@GFq6bQ#g z0|dlp+K1xmgq738!|46dyZFkvIcAawcHF2|lun;Q`Y1zyadO+BZ%Hx`aYA@(hHe>7Ja&Y+hn~$~V80@b2L$<-EC~s509zkWQwb z1q_5aMBV|)QFD~AQMM+@QxFWyc&t|UY_H)x>|MpXN0T0w9!~GawM=R`s@NtN{4wpG zwsK1ND+psf!mr%QMN6o4gVKm0VE6D(I^bO9Wb{rkPzm zd>Za|a1G%sHJ8IezlTu*S*1Qzu0~oyER5`+meAwi|6=PcquP9;w%@k6LvXj??(P%_ z?i9D+ZpERv2MF%&1&T`xZPDQF?pmCpZBPEsd!Do24<|FZb0=B(kgUnvGkfprcWFcs z3E{MgP0Ggj^*V}N;$8|32f#4bB~!_!51QP1TP#wWMl}!Ef+`|;!9+1aV{q!GJLx-V z?J3Zz9u3e|rw~nLtgZ(6;jqHR z@EcI!>txHb&xqMKn>HqWK;vnQ9az6nL5CC2qS>!Dn zx@(XMooy+|o$rsI1}8-cr^gZV5Xa2l;c6^wDXMwkGSi$`a7cW(Za&Tlg&o#A7Sr*%UDAb^Wt zX~zx$_PvnO%Z~))nNdkeq{%Yr{i^=45>%A*VK@KYeBepX5wjsr8iHmpgn-3k7mm}o zOK*2qu8ESBwO+~+?+;7JnpALj#!w${vgMV$6BnBetN*?xk0;36Q;5p?X{vWxE)Z+3 z1Wx!@P#xz~Fao}J*iH0vkdM+~k*QnZ+LmcmD4tCy15|d9OSMf`R9zh4&ejT+3Sf`` za|N#>?uSG2`BP0juV3NeH!+Iz38kscpRTdPwl&S@b(zK)5&Db$`kbh_C)}7--R%1d z_)Y)F#CEncoqrX$tJ+7~C;iTzgLpB_P5upd7X!t8HY?P9KR;5dZN?($5Uhe&#xp@j zX&uz(!6=+?O!+Dqw!8k9cEDm$Iv`|6M!iF(=Est zWjPdH=`bJD%x8nPgnnElodi(O{8`?pTb2;CYGBFP?oIet+=XJOGWGTkj)J8Fw+mYg zw3z~3X5KyFyGS?`UZ1ND7^%FaaBUC;iLNTlT7!_~tvYaRP0SI8i8@>D@w)BFD(XBI zF|dWu#$^suV%dj6*e-h*FWA(ShUr|s#fw_6F}K?7%ZHq*SYtx6Hk#{`sU{viRH^G& z#PV5Xf@IX%CYDTS+qZw#@LqYW&kVf2+eaL%L?C4Dp@(hx@6urlQX zBW9XORW&@Aop+)rs#K}5*?gKtnjlcZ%4F!rWPkX8{r5(}%$lHH&y=f4P?0uD9ojo3?S_ZK5L1y8CG3cb6{C1b ze~?w@z6LQJu~5+cNCyTameqJ?P4mMOB;DCFFi*M@o-+{&ySdxT?IpEe;fw>FL#ty2su%Pq-@96<7+c0Bk|MsvY?w_P{Pi*AK&j ztx@=|IU^ET&x6Cnv2{>o?K2W@Uvjz59Lj-_h!X4IpA>|MR+RlDzL+|ayYXU~+>QvC zC^(=@p&^O+8f5u0i5kb3S-PFu9S%}F7w~M{)W#-N=nfpnI$OdwQf=3+wO?j{*K<6T z-!Flng`hwC{^Hs{C#L5FB>8r*wL)=l@Qcx`ghe@Qwv0+aJSOFaN)9aeU$?fLlTdyo zu=@#x57ZU*B^QO>NH_&c%%WeWOI-!Sr84EOmH{bfyrkyPlVmEbgU1kKqz<>;GoTB3 zJXXbYu!HgaqQ=18$#1Q7JBH6LQ3rQ@W*X|}0d<+Ij6#J!w3?v$D*QEU^eHZg;xUqJ z-yO=`|Zq`~tGsz4H047=S%9I(~-+RvZr{r4dFoJC!*mA&gXc(jNz0R|G(3k@ zmrgD7tH12^rCK;<5qyh$@8C1#we#=IXVHhha%do|I-3@9o+kLcg+f6%(fMbMT&xr= znrh7B2rC_j$45XXRv%~8*r)MF%_KZ(ROM;uSp`pFk*{c6?wue&?|n7wptVSQaZ|k? z#G464c@&n(DHpbsl{q!Qo;HH>#7=uWJo0SS?G;0#RFzl#2duMG9O3*MFM#kY)&RDZ zq5yra^nQ87+}r9!pUFG}xUz~iG=+GEL?=#0^?Uq|dYb`Krn72`ny!__EMzH7^joYl>(A=l|+R2R@Em1o}~CvWE}nv{W}e*qi(BX@QQQJ;A!%jc^g| z%~wE(_svaRy%-DNY_i+zVdcBzL}nNQ$pE5CDEq;%i!1v=T!?XqtwoRPv~B-5t*bSn ziJ-Xroq}l0x&zGdqFLwH0(nC2?Pt&lS=ze{akZ@~ohYj(Z8xGUitjCn_YQ%`tmn&W z;yT{vE|`-lTJx=PuU%v@fHvAzib^NYZjt7=LQ=Xz^TWJ!+P*y5gKnkT38sN$e+wb;?|Jl=O@4ihfJ5J0s}@8O)O%60!; z>Fn=9HnGI)SgNezlS&^h2hI?V%xfWaP8Ahh?A2aNdxx0iNd{~CjQEsD@b68RVEgAY zla_N0Xj7ktd=Vcn2*D^SPsJlX0d5VGMbXs3Kot8Mp42e-D-~1R`MDdn-v!I5bzD6= zJ4qQ@!|5h#Qcp~pYmzBX)Fy0gOU4z{V|f3;p!VA=uGwFk^11lGnPpU;{-9_ih`?v2mAA8)Dr$47-(zduyk7~2$oK$^j3?vH8G5_1pNN0Hy%0#DY zG2aiO3mN_ZFII=Nj34^v|6D}K#kLT!1)uHZ4B;0C(o3ArH2r(?TXif(vDogShWX%f zU0b^YOH?J~%)GV2q0{NGc@-zI)%G;)$4ZfQ@{b-kdi#la5sJt*mG_}|8cvcrXxjCs;O0)KHpBq!Vd8`V#yLw(qGe9ggT@peA-JNrBH zX0Elf)%*reXJj{!PV*9}+LT}F=;*#aX8If%a|KEF2wh&=?}?0M*tpM4O|?3VDjGDQ z+14P;OPc$V^qw^@|2Z9D1Fi5L;Sl;o&ik%sVPSU9+t02y4;REP{q47vqiPl&bM-1! zYt3A&6Je!PIn%c3juLU+O`We%fhB40{XHR}b=91bdi$GciF!*uDf@O6OVj{W6xM*q zKkpq7nHht6NBHkeVsF#}6yJ{fK$Ky0n{g}`C^gj3f9_Jzj>;S2cxPVCJG-huaK5;} zMhIAo5p{7ke&pICQu}K1t5zve`Of?SiC~FU~5Z@p_?GB#1OP0>~62R?1$BUsl0l{ckI9OtRKuW=1fFXfPb)HR7U4`S`I^5wGt&m3*^bk`{`Jm`Kt z`!q}i9qNc%1Z>yF?=XT~gOo`6#{8`7T|V&qG1$&yI5%^QUN( zr!>;bF)2;6&XX+J2w-l$Y`760Clx@h{QUr+2eB^pu~m@mJ8AISqKy4bz&(J9aoUw4 z%eF3a-4S%F`X%9=BF%d6xhw^%xD~+8_`sdaRO(`>@%*UTccf2y-Q!pX*t4OH#Qzn& z*q?t!a#b%}cwTP8;wcO{Mi=g%t~w1$DZ*@*5k40HH2I0+9`C-l97P=}t<79^{~Tvh z1#k+X#?Um@bc9RssRn1U*^3;HNd3b(1t-5U!S{TebZbAQOH)U3%|cIaHMB@2$x)&H ziQNyVU$ReE>?d4g>V@FxN)q}sJcOF)_c87F~XpcxQecAc5w#6G-$wP~G?p7qX$aH9$ zyS#!24SPO!vVo{MVxA|>s|G$aJUJrr+Y+ShnAh#Mz+g+!>aqgGMkB&BcC`Bxm%DnITe57gaM9 zp={4LjydWJ$zA4sX)k1?EO3wGl(3zx`S&J(AT2H1xvaQQ8}hR~eUOe+p0jSmGo^Vn zQ_HkQ(QgGT(6l?iqh_$_YG@t2IT$3H#jxY%*%oasVQ0DM>htF4*gWK z^BDzI_l7-)xTpjcUKhsC{Co4UN6H^EKcuS$z~CJLlv@g4UkXCCP9&#F0vGGOoOF$J z%)Yl&99qdZ40M)5Jcr3*NRxhFO0R3j;6WH5UggRur*T}JpA!7-G50<51Y3~smdxJg z|7^}cNCy*~utO@@YM2!%1Q_qW5$Z zw-7?M#9TffRYBua&y7Id3$O}*-B@hDV6pZ#HcEKZbfHerJ4I3&1knSM8Pn(Ds4 zsdN@Y#w=k;%wgMZL-7)rpgC^>)ud@^ynub{L1XG8D&uMN{r$yyI zH)-(Q;#H)>JLd%!`wxdvpIf!DN~jjx0L0^*0MJ;A3=7zW*XgiF73}j}y-_KHPs_U~ z+5Qs4$5mkTH)R;%oV=hRXTg^Pe&TSC)d6xBhSq1oAzkm;)hP>hp{)5%lC~(I3+wN# z`0=py6hZHdL$Tbq@9JaIx)WwUq=f%_!*R-DGWF?lo5%Tx6|~lgz4CLj0infxgosUA zOfRDCgCs*in7`m!J}Teg69jGocqksuPkBX@^G{)Rg?VsqTCP4T%=4mmrj*Tl zVOuq$HO>3Ww5RgN#~#b;WXcsuq)+=|7v<$%f_GRVTk{deg5Oi!Ygr=%}#D-0$!DzX1azAZr>41GR5Jq9jGYQB2*k&E@qytR_0!*bAgNV1^uJH#Du$- zUkk*_Dv2w!GU0!oZ3^fm(9|2|m#g1l7N}MIY}Bg^wz$Mo9X{-%S5C2HWZlZE{e2Ll zA6dOY&*?#m@6xFfZxOqy#g?6y=#apdqr!=v5~!kh6gP5Y5LyRzy>ZlgER|f3gBZpV_rSdXM>ixV20`EKuPIeMp9DnZeZUup-k%QW*-6BC-^*5FooC-I*f0?&m z+8aeL;sE})ve>%%;z9IRUGxtX{oVT4K-<)dw&rx}2{}nGs zwB46$Xq;R~U%C>$r_nM?#_#Z1b$t&TASm~>4gU9j=RQl)kwdY2*zO#=Wsk~(&sLY| z;K9bpGk|4;y(|x|u+{SzNN&ZV_|_ft<)zj~re$Ui$D`xd*GEh<;;kCVAevcWMI1*n zZ6s*tkobz2CbwtAuB$A%NDfWDv%VLau08=_7(zVekC`Cexc_lMgdanbFo)x^T#`Bes9Wx1$| zKn3#rJ^M2Zl@v>+HUr@YA%?&>zntJj!{?HKq8cRPud&BR`xFek+R%OH@0qFsv>sWT zH|=#O8`#2k8AD$}$ec*BY}@t(!F6O^xI~0ajX?HkC+~c!=q!YI&JT9iKVBzFa{3|W zA6GFM$k2J|wBjqs-miEJvffgzmux_=&)t2Ee(Ev%YDLs*z5DDv>?0{wsdSMw?5#w( zc*Qy#?zoRomx5k#H7HhR#z*LZu~+?iv2iFaJHuHYiFZMaf+VMV>JSOn2@WPD2+Wkw zu1Eht+g2LM*LJDOGQS@PoeDdt z%`)jio%sdLljEB}ljwZ~&Bf=`9Ro~11r!cHE#~E)OXJCia1IPXY4Sj1J@O8}GL0j! z{0<8k>~$8n&JBw?3;|Z7v`(r7?I?cvRBp&!N7N`(k7akX_L2^GEd?oi;8y%i9;ekMH*qcxE?tEGM6kXjF!C`t_&UBc9!#b4fWK{VeW z*?kDc{28v4bx0=F?RJ%V98h#wpGjpCm{tzJU?8rjQ}VEu3y!jGa~4!d+nT~EqgY1ZU}O`_a%AFhP5Wj`r3 zC0c09;3&7Svm1WYz$1 zk3H8$2r41r^Jo|L^eDM~#6K2(80WYR)1Ix*zooK(w~S#N8YU!-2;r z)_Say@$=}1odXocfDTN%jEQ0?UpU;9<-pfziKHU5tUIi2{lTR!kr2UHAIy|9GW0KC z-*Qj%_C&EmZoR#?1{0|tjBclo%8Qu3DuwYYh`P}yl#Iz>Yb!F)B2{FZ>+1Dz7pMum zXp&{|pEEooF-@5%G=40F)!8VusIK7s%2w*logdn1kK$D0b2jLUnE!64dElRw+f-rp>vY>_zamQ)c-V4LQ zEj9D;L=SI02Y zaC$Ven3~3`R%2+{?F|_n9X(a8dw9Z2gxdy)s#8_@l}GPFFyy*!%gZ9+azfI)gV-|Z zT->JI2|5$bkt{1cEk#=&^-cm{ERZwku3B~2>Ej9}ddx}qe`xwUqpsS!W3DM#+WR=q{hDBR($XD&+9j{icn;kk-nubUA zN$FtyCBQV^ubNx+y&{1sE)~^8@REZfl=yaVsPSF@is5LiAV;>lR{zKH^~lyhVV<{6 z943WWMfa=c*`AGhTLab{s#v$XMTN;z4bb{pUBy(nuH{~T26bL`j>QPvBcvQ3vHz^M z#jp-IpWZ>1PEZz%UCUhUj-r{SQ}DR*X+Y8!Wt)y1&s}Gvgw6}-QJ9rDzo!fNP2iVg z{aS;wR-7B;OuHw2IxpIWU1MEXJf9|;CLT-Jm2w&703oIbVk>?=NFjZ$POd@MKqKX~hm+P$Z_o^vL*X|1UG_S5T*7np1&qluy)Oq;Qwg3X* zyLR;L8m;7Zsx7r@t?G=qd=J=2{&g^|lt4TU*CAmco5FdFAzkj$=BZt_vDs$gVla*1rY{c9(X$h+ei`@HPc8R}=Gs;IIQY=SI^=_IR#{JLWQ zZRSv!i^JYOLQ|vUJPAr~!nnp5zSq7jT8T-hgNTQe*|)d`YHtR`0sL$B%M~gDWGO%G zy(_)#jtU;|Ke!u3g%xvZQT>%@9M5_SOxw*|&S1>^#8h$?>f6y++U6 z-o~T!2i+>nr>F$r^S1)CJNrrHP|C#YFHe*QQtWet4?K8`@f1j7L}>CRz9Gh&)O?N= zT%vNXW+mT$ge3%(|D|@=`g!V^Zo|V!!N+ISnJ#L-b4-B{B(s%yx%cI6Tf&`W2kt#3 zC)26k9RW(2Ua}4QDCej>5UcO8%IP1yv%*|SHv+y@DLubc2+ClU?^v~xyH3B!_b_QA z;U`o2HlcczO7x=i6;&a5O14I?FVSaMW)38+CsLk;=Zt*7QSmU|Mo+-cqH{PbxO2}A z3HsypSy2>59YD68XGx-xK2dJJAxi0^3igF*B`JZzFfWHW$6ybp}ydsB{)^_(WsN`0&F~UUD z<1IlbXYN~=sR~CJzi`b{l=TLG*{a^MBrl{iW8A~(=4<*hKKidmM}vhmMYn8frb3FQ zfaW0Nt-27Ev{fsW%Dv}W`Hy5f5G+`^ieMiwwbS#@V?#@uA%7HnrO%O}x+9~`m-s6! zR`{0a1zP#Qzov9=&7(+>UPdTWZ zjJCK3({M{NWM*RRC_wLJvcGW_wKe(Q8+m^uQXpPx1bQ&g-aXT9pWq>v z>Q*3JDtHPMx9oEet+L6NPwwNWK?)JT7Qkj8xjo;e?Mrc>WlqTY0oF1~7=>1*gJ%<2 z%0M4Orq{ia4x#J%CW)W4R(TxE=3uZ~dHHYx^aI(F(3cTIdNr~e-!K~-+-vy^QX36C zp^)`~VMWZYq?)QIOt}=dMGq8Onj{zuiIAMxtpMU^aFFqS}@5LSk?l+V1h} z5RP<~lzLYWyfdMXq8sdKdkeK>P;YiEj@KUyVMoinK zM>ZyXhsIQos^JMNk+-MY)e7`g^E&;5pg?%2PFz$nyDY>@^;NhX%VFi)3K|>a87p_& zRS)-)b%5GmFGWl=9K}bQFxX%q@ASslpIssBKgefzN1UWND z12hH5c^0H=gG}v921?q12W!EB*xN-JB%(9`*@2RtT&_BwUc;ar(?KruF$M9xVhCyda0Et7+5y zJD;Pnde64PwuUWFunJ4gPUq$5Ud0fFR)#F5tj*pZuPLQ*ULg9_EDvmR@0l*3`pVO8 za1XuLqb_l8Jx9=5qGfbR{d0|m?Ytu8v2dI+!XDe@D%$7~2^=vxvUgG_5xVNSB{xUk zZOkK?`(d*x-Q#mE+vxgp?8C436e#6Pwi~)xc(mC3y{r8|;oGK7Nc8Smodcau1mebi zU&?p0(U12A`a!ID5B63YM-+U!c$sq!Nt8Kw)4eFx{;Eyp6pdR{c>pn$974Dgo|O%4 zCPBleMY2zpnya$f`$|&>I11UOYc#&zVX<<-b$Hp$9oxR(G$cJZ_htDgkv)}SgPuZ$ zm7EEP=ODD0zY+^mdvhajIpBnp#vUP}y=tDgPQ~Z$H}P{%2<89h)YAS>LP2`Rg^UmD zuDZ5K`RCS422N&K8pyY1@SPztu~+=#&{Gt^Z83idnL&WNJ}Jy=;h&Ek830(~OYGAdu}`!+Q_ zmBT4^IVJLxB&l%ajLFXFZzY7?Y1{kp*Fa5;d`k`~#ULyUg|R}HV_K$3r-KRgyTUcV4SP<)r~(_JG_-*TIAYkJS6YALlwoEoSRf{#sAUblekAl01`x#tsW zRG@-tHcutxa|s{mNI_XQXdAMrk8cr^!a0)sFUON*mOwRtLmzwI+aU~1&65cCpPjax zM7t&5LWAEfc*6|f-{HB0(S`*v4Pv&pQ#u=pKUJj^Zvrxsd`!E@K~PFJvAiP{PX`Ks zV^3tCBEwfckI*EB_mHD=+X4i!l}qCQ8NfJ4%<5c^&jna50)H#5an*SR(@U#cI6xe8xkleD*TYc>R2wXu$gTZwN-HK z2PGxZCq=xJ_tgeCwCK-S@)(1TO+u>f0!aqaQjPtI>*^!_y^)B(l&qfo@x|2(9I}$o z{v-&yw_)@1MM@}ca$-Qf#vsfJKYwd+8xvL$-p3HRJ&Cw&Nx}~%bB7_?#OmX!v+2tS z|FXYOLPM*ImEpE7C$NQi#=^a}hMCFHcxKyiM*$)r#8oBtBzt@Nq3AH8pTt?u39v%} zp0os!Dm4_e3*H2wD4b`@g1O{1f}#s!N8_|z8bIK`D4~9Mek0w5(@Q^6g}F$ zT0_Kz#yF(%5x49ao$L!QTw3n}=yra_gUq`c+6_dpB8yryR%LIEwh6ax71P<&4HnAz z)D0!n&(1OGYc|aN%F|4W++HaB96z4hbx8L3>}Oph+aXBZDY_SDDt_ zM4iK7?f-LgThsiX>AxoUZfaY>sj~ zIAAMFU_>+5K?ju1L2gvK2k9QDB8@x%XNa(#YL!q1^i@DlZP+fwhsN=8u=&m*CqV7O zx|(E#8?}AU@$|m3N^)pyGIS=hfQK@4Q^SCu<-FVpV&K)$cWWOXt*MQs*EG$@Ur5gT z_XXcb%T_ywQb&fX#Fn77*hdWkIz6%F;&Gkf-dujGgT7vhT*ZCNgl3vWT^me_DI)sG zrpcF3kEq7TOgf3fy}*rmN06)J8}2g&`7gfdQ*yqswS)CV8NJ9(?wr_>=lUR4=W(bJ zT)XJhG1oG+eQXb}{UbkL-u(|9PgR1p^jvAIGmg11;_X=!-;%$5SU+f>B_+VeqJ`JO ztCOKlpzrGZ)Yv7VPD&KM*n+G;uF+$Tg;7)QJxv;FGn6{;Uz1COOGPcQ9k8ubJ%Apm z@YDaEIQ+kl?uQWj!;~XDZ1*Es?@xGUKbQRU<5 zBRPGLC<)Q18r9mIAvFO`VOndKl;%d8cR+$>wqAo-X2qq@tl;6=ZQ>|92robGe@ zZ^)p&i;@<7X zuyx6|ZuF0i+E4Xo>F+#z@e8+6gPKrp9 zag%YT9Hb^_#3X5LrIl^tNbey&a8>`dJ+p!Z(O%b!WIs4SD(xwHHbMYo3027l zN1g``p;5?ycq!1g&^vwv>^#WfW7B8yjcQS6TOvD&xjjD6_MRnP_l3X#)pe3L%j~h; zl1WDqsV2^z`f{e_%o2~nFQ}e6^R6CT)WI?Yo=~xcT{eoSe+qFtm%jd6IdN%3tolUpp%R^icJ#uvxV=u3ef^X{=LDyN7Y`#YdBEQ5dkV9 zd`vaLQBsMWPDK{)kJF$+sIUH6RD{MdN$ouD2KVI{f+C-y!lf)VrIb31BEKL3Z(+_c z+F|qMK5q))_z!YE)LX856@KVSbmXwlu}39-=Pf#LMsPOQh|FBFOja`&_-_`>KhVrTZNjKeRVPU4s63tK(-tW@D+?dE_#O&rxRM65Bx*hZK&HJlrY*XeOKWIa z;Id>twxD{Yt?2wGpT?gde2#Kc0H~ASVtEldnZY~Q>te)*2oRl7?a6952<0>+dB|2e zEjh4Y{Z$bFb`^U}J7mT$e{uc$Ho!#Vcqlr$C+DvWx%L6WuM)eTUrh7J&*`RjZ#~d` zPTFp)<#})p%1Q2Us=FNT>$Oscw-ElS3p}bJHZ#UXC*uC;`v!9sIW&J>fiW5xbHDjlS|nNb7TKBXO!&^B<7ek-_f?jaZ!1~m$w;}#q9tQOdhr=mm2n~wHUy3or$ z5rW<%bkhK3hfDB<7PR2mtDzz-9*T~s_ClSc@4Ve6(i`0qp&Mxc&h**R2E7Q+Dlv-p zK3)q}>#=z0f!xs5I{zz`90yuXp9!SVW*6*L6@ey8v1lukBWGv4M7U~fAKBxHkh<`N zr_H@($Pp-3GQOOC-3~VyZMrNQW>Y_iX(@?m*onrVj<%8%L0bx9dE=-3=BoVdjuJv& z3Q80W4!SfI!6)(meVGr}LCK4vNoIJ6okCBIo-mHHpElFF(h~bCrTck6n>)#7IF9XQ z3b!L2!FitM!r96(>Ue|`N5#PJbGIf({;KS!q+V-{>}_w)MG<9+usNV7K(5Rwn2o-| z-uqX$Wz(3_LAfW)9UJa`R%~YbzVY4|Cmpm5szJ!#7O0ob)sEwasinkD7>?~35PzGw zW;wVLz@YZHTb>r~0~YS;7~UWxY=6W|uV*oIijBeDqoe5iPfhQI3fI&BkE|Z@-#q!> zObJ)ni$sc)i_}o;NB9G=?yyVftCdc1MI+%SHPWZJ*g9a*_F?U?1wqkrBo$fN&#N+w z3sI0;FkzY_k`*pL$CnW*bdhm4v4B9wwN16foal7ogZD|c~~4s_?cPFUrR z;DurA!4h*2e~E=@nmfDKGxg4*oY#l}*b22qYg@D)Ft-;4IQkOeTT>>yZ81`&W$+Ma z6qkeRIOzgv*-HFIGdmxxYYFdzNdsN~BH(MPPkNTLXw4P-%2~s?!sE*qwhv=|@; zeX5jyZ+KDxAO|jbG>HggR5Fd0hxmY^^iD@)TWjia)#Z~RQX0QGguY+dt;HwS?5*uZ zI?4?m8azzbUmAfqmlpHVeL+J*!_`tWwoOF}b*5#MH-yR?HY|zoZpv?2XE&3KcIW6%x=##~ zIQp2Df#)IgG!?mDF?}+mF?v9}uO|!9Mt&^ulU0!@R{`g1YRR&NZL{V5olvMWPs+1( z9T2g_Q?$U4oU81q916RKIf;hUJxYX1bo8Gx?yTg|>H{}frJTel2qiJ55DyOHoh--A zBA*pbmJ9?NE4uageKh-EERjCIQ5HAL^j#lKn$D!aesZGOY`D-a;F%ME-0z4UK`F-? z*iD~l^r-*guqInCAEU-}@})z(Wa}6urCn|yb=)tWPyID}P23jq@*N|TJX@jl1?kh`b3lHCvOE3&R=d-xGQ zw8*&vW%^~voswsx@!jX3ejl#$ViokyDVBO}=d}fBpS_dXsll`-@&xB)6eDtZ>?|vy zr_={tjEG&#VInl+i%-z`r>qD1m#{z6f476-6SCmr%k{(FWei5~$cDqOt8N0gR$Fd+ zB?ZvGy&B|cN|BXF;ExdY$CHW&<`<*>1PL32{Gwb{5UWmP%(LWoKv78XF2}BpB{al7 z0YzJQVzsfyNLUwsajPDSiPe9B9ifvU_RF~;h9HbcfM)A;_!u^4&by><>~JL#^~gFjC> zWJuq)7*O<2Lkfkc8sg`uOy%0fO8_9X&-V5&sPL&wL3}tHUXB+ZxT9lc7;-2VN$Rvl zn@}Ckb4;d0FFiJuJVK>Vo||j}Oygc13_T3Vl9eZ7Ab6!?`*Fq8<<+z@jh(R3;dL1G zOuWOnwMsXP_KtHSwBy5j2AD^MAXs7>Y%yjr3opS(N5y+i^p_}hg~Im zlj7dcHvgwXN*$11rvO{S;Jb%%`2OL)y@SVp$9F#T`Dutd*gQjWad4aB|3jp4pm3m= zhd9b~LlI9^y|hJY5Kpiz5xY~ebSlK54BekxaS!1ikYN~rU(_>5RQ0muU2#_&sFjOz zngd^Z39178?u+ahI6n?9w0Pe?{V!!!NC{bT8tkfwcD%-)$&fl&XXX9) zTd*={gtxQ^vHj1+QAY~E$Q8R&1+KW9(*i|@#_AwA(4%wJYabxGnPh*!5-FL$=m zLOh9R+Qw4@KkC`DXTtKU+uyhPyWA9|-Q>UO4ET!Rn5V%U{IFPZ7oPjMBWMYR){z+o@C2(;8O63SsNv@W?&Q;dreMoA6w>3dc$tN_IPZ0iQ;kOy#M|?T?W0di z+m}?_9ptTK72nA@C{w67izeJM8f#~2f}eVum6gfk995nW73rX3HEbV1F+%FfHT}kpZsZOU0u~Yb4M?>Ox1Wufa$kyQu^7lwYh^L_Ofb zPEAq1Xtd?0cwydkvxo$6&wU9Mz zW(Y}<#FyQ2y(z|1fpUz%mtAJPNw$_g#&Ma}yL>?4gZQ#*K)x)M(Lm@oW^U*<>u(TW z&i2RNtn7si!~SHfBg#zG;w3VC1$?|#xT6mTA`UDdHxy^Kn*KFTG8BF6?)P*B5xvjm zf`3MHeZ4!*&D&hC#0HT!O5Oa_2tXrR9LiFwr)$liH$>kM^FdSBgSK~Lq`ATd{X@WI zKEX8$$UAZVJD+!ir}nb{;=HXzVqX$pT}n8gB{SZ%$2vTtaTn;Xrn>T*imdJb?kJE| zAeEF&!*QO+PJz93a1-(eS;BmeuL zDH=A9L`?#QCn2=KopDR5BFKvP>2s!{CX_V7&qza~U$1`=?nR0{Z5!O6zWg={+n7Xe z&$ra6`0V2uUJla~q9Xs`-~_tC`Y~5)6YQjrbw3oxrfk4)I9?%YaVRW02r1dXzsT{a z6y4)JT_k2u;k1g-$RPvE07ueDL6>$ToFBx$c$!eEMAW$ZCWbRHh+Z*e%CA*MiHNAD z1sX$Sf>P3p_)9@roeD8d&G6cIE$Bo`n(Z@5^Z?)ZUWkE(jNi z!82H`lE=Z*FC`DsUGx_*8^3}2ZhB}WgKZKn%jE*DV}@-N;0`3j-0dVBWODs z9ljY4?;{My+U|g5flvHBjdD$j6^S zYA`Pce~SXml+*U}jB?8T#dpndTed$*c98{z;L$s3$9Z`M zWnf0jAfw#hdbUX3-;f4tEG5VoNajrE&W&e44Ll}!(ctznK-@##+7}*5J;%&MU|+?w zV;E8tuHXvZ4X|agi<-S9{SkD75vbruv**(Y&iwbrp1R>nV>iAOo5c)E6`O`5WEFFb zqh#2K0z*?PS!9%8tAxqLnf>vy(QKX5=EcA57a?=HqD?#oh95Z@9jo z&20_7$eo_{8ezS&GubZkK9aUtN#ChEd>=n(Vn;a8#q_`iUzbVQT7PALWi#YM-OhKK zspnwbq3750al!?O?sq<4dZ`v?9d&Dmt(wPj?F(*&l!m!!H{e$cckSQAWdK}xg1%`i zQC!v~0j#np`4k7lu#zzfq=t87Hv+-y0S@?x*@`3~z$L}Qu8*tubW!OXUaKG_TR^5x zu0v-=tj&A&-sdLOk{1*!VHj=0+@sd|f#|m+$E5L>!y6oc8gpbrB)pK` z+g-BuH7$ouP2JFgQ+~Ys`_ci?inP-74muH)L%Kp%?!7a-CL&SE=j{m=ZYsT_R&GDe zS5nPeQdM9JfA)2$5}T0H^$+n4xuG#C;Sbk+!w@2I_ha#$oxPahq ztMohBr$k!E?69Z0$n$NJf~s`R<$__{mk4b#za_y@*?X2JZHkOTn%@l))iH+C_2v!s z@zRY_%`DBz*#Xkj6vYRaRNF-}KCj>HqczABoZ#1*pED~msjuNNtcd}$Zrfy#mo0zw zvfWeej8wxRNO0G{kFxSn*qY5s|J-=yYxP``yH=?UF&HFKDA40$c2wArvV?~*J90O* z$nxbe1HcVqs{5=in!;Kc#{|OWA?A{BlLkTtS++bwclNEe+boV86g~xCjy3Y*(A&rQ z0IC`$bJVF#8-Q{IUUD7Jh>Wg0+Lz+4nPd8PP7xa}#(Fp!Y(O1S_jEo79r>XgzzyUg zwUYszZb4hu!SKl!OTo&%m^T;01J1&IX*cVt_^g-tKm}?x0`g@&|-$3?C7P>1bKTmL`pvSROxCFA-c<^4SO zYs!!dK2`nt*>exXUm!MJqPEfn(X5I0ffAF1cct{u!6@bgR*(1vRxFEF-2ng*rNHxr2dGd9Vfk{s+ulf4>Y)ZdDmIe#OveC+Ok&c35=SuA+(!^xd>>BAx+N;Fj z+YlKAk4g7A=E$ekBME22U8DVYw3I2MHX0W@6(v*mw&I>JxqC_Ru7MaOxcUDoZ75bN z|9g|V&K4^91+W|H*&m7DGSE^r+a~P=6Uml|jO;-?kZ0YUif+RtNF0yD)K$pZH4t}8 z0K`mBnDlhT-uSL2f+adqMb>BLz-Bz-ie@|F8~qaZac{0jNl`hNydJhJjJVAzV7M!# zZpjSK`?7fwT;)(@XN7=nS^J5xU!%gzlf&8WY`CS`DuTFdweoIUQ#uR8ZC`q$+XO@G=unmfg?+Q*nm9cz{zrqw@ zG>@>Mw8q}Q0kfYk+hjd5ev!2mp0m3qv=C4V=xDXCjvv<|Z(kHUlP|NI_-Gq`wbz|j z)Zs%Du>-@CgJJuxn+ZGdLY z&RCEz;hfSDz5-x&AZ24as*%NL3|9?T{nk_4Uhna>8J|;p`G6%T^2}BJAEOq;15N=5 zvq#RC#3F863pG3;3o!Tf4EHY^Mr;OBsvG{aRJwJs(fTn-ISJg|f<5OF&YscBiHH~p zrGkC~i@Ah_Pzwd6uS+*>tY1NEJV?~q*BWGnH`4_e_$8jwb*jcP8U{;m9NG&ut7VyI z(s5)?l25thL7UM=yR_Q<=&l|rB??Hv-22}3`f?tuOarpJp0K-vUqq~0yAY0u+D%{2 zlsW|uDZg+)JvomchdtlaFFuay^^wEsCi%WtUMs2kR)QH;Xtr?;8fB|hDd%z7J>dj2sfU~G5H%tGtmJPbwrxnKbP+^ z4E&?MKs%hrX87S;8L!FS{NvI`5YE&DVX&mzZ7O6DWN&e5e8YY_!cgN3VZ^QQvgU0g zF0yZZgJPUBsw$;>cAs@hmoXbp9!J^G9gGCTDm_=gd+EiM{u4MHMDRu@fwo!N@+R=K$v>Q>N{}h$6un z4`g5FEEvqtP1hPj?XoL-zNBn>9Fvh`OMxEkx?q&sIr6g(LJ9 z>8}(6>~tHmm$->m8n)ZQRae}AC}+YY_WCoX@mzI{eiNk2_`-(%9RvAom!;8?0*WB= zXwHyR8YI(Oj1nm1C-5!3e%PJL0?r%Sx9Ab&OCfpTd^z7yN>6f7hqb=HhqAc6K5k0S~{Aog(2*7nEDB13^ByaqPM^*Ni@=IP< zK34Z>7hBUh^_+P?2Kyie&st6*OaDFyv6(qfXlzH~p{15kC`Wn#p*8GuIpGKTHD4TzD}L$Q&*^a%ad$f7GREon&HYNt@S`yFjsE5 zcaW;i4lKhO@#@X&J8e1qpM0YauVJx)FVZGZVml}7gW|rXToBP81l7>rjPyCmX6qHz zdC2;}#xn8P0YNQFl$%QkXES}MbGNtV0xuOzf?4zwSM)ayUEet*bwSi)-QBrcOMCu9 zF>s*Ay1B`c>#g}y>-dQoF6)~su1^}Y12$(; zA?&Xo5sTl|Y@8WzUwMVRmO76Qz@AA%7NnV1YS+BnrP>K;tzb^&7yUlXWiNc}&M zfe232RgPyZZ5DWIq<1Gq`I~Tw14CyMyTT82+a91W%hhgj%U(A7JkpR5v%o1Fv?!P= zMqK$iZww`0g_v4WD+cM?cwC+BdRiLJJbJKSyMjIn385^VwA_(5N%m($hA(aQE=x%c zb6sMEJCvPb4|;WOjAtdr>G(Vww31fvsC#YtHn6vin-g6GW`CBdW5(QxgBuQCE?#)h zxK#*DR!;C?3qS5zI3j}4vm-Efe8 zNnG6N9dW8uJIeCqyd+GxD^1B6U=_X85^{t?zqB4}d|qY|l!Spj>u79)N!gBio=o8T z^dsU|h8~=R^ex4`S zhog0>e2RriR0#moh^^w7$(n3alKJQ*jX%WzC*`B`21~OP*i;fui-#gt05dbSE5*(iWRpOnuW~? zR70ff8ZuWLUm{6fz2Q91)Y+@lcQCMy;72w~OR7?{1P}Q0Hv+r*C8}ND;biEP@_Ay? zJFjYG!?BFT9y-yb)u@;8SyiZ_DOwA0|>9W3}zpt=t zs+pqIkKE7;$1`lzYzn6rd6XfyWhB*CT{pyNsYR4ktKl`t9(~UG5iN3a|0J?=Q&_cJ zAI?Xa$A&T&c$`e&;OXA_M!96X8@^IL;x>w<-2*;4cwLwAu|*#cd6g_*L{_$@qPUy7 zdG;oJ``D12wlE8K?!Zo|qlJ`r+BQg=@2pft`mA!BrJ^ck%57D;2Ivxh^4j|ut(0o1 z#)W!FV@`EVj=z4W8ozDJQx*e|NEGiVxF(0(6bH2!3-{n+q{Tdf&2iEg z!`|CjVL#hP@wr}?&zz;pc(6uzB44V`jW+*A690oh!|}tSESk$g2HWeD!t-p8_*J{- zg`$7{>Tw3NWoKkZva8@qQ#!?vD%KVX9kuHVMxw0?SJn>uhz=v|@o(drh$8QRlL|dz zL52O8%?{cY=W~B_k*d)fZO=t$V8=^_b_i9H9l)cRL;*P#ih3^U+Qp{Y*4*lCsVjL} zWs!Vm_43!CiF8!`y|&mmLv9y$6wHc)q-y7K(vzL&uV0+*lv{4G8j#TBr7@wB@xhebV!-6z#rpQoSYGm7>xL{y{!uT~&IYS^ecypJXomygO zT(wv3;&c?oH|X{KZupbToDasS_gO+rweo09Of*ev&DXXTCjupT*3@M(!+`*05C7Hjk?#bUDbBDf6k?vp{stpD2Vbr8v-1>zHM!JB*hQXkgeKxKWINU;u zg3PGXAZj|El|5T}LqY$iRk_f{lsvfS1F*y5cE_I>j?Y?rNgzjB2HCP;j;%)_HnykV`50(8vMUrUByrwwAzq0#@ugH-@`k**s?d(=_ZB;`$N>0KZ zh3qE2g1UtHqPe8`I-C6SJJDCSDE7RDfMU^`FS|s?c$mFP%n&MTu6|xBz{%3JVJjNM zLZCj*Sp+P<##ZIWAT2#dvWsFbC*efLJy*i6lHD*Pk0hBAKtC!$x9+YKo?gJa>=;hE0u%S$vMU_9p4B#@xv8>LD;n$N{?}t%X|L$M12qtH!)! zYk(SPUgfW^1L6wFU{Hz;!6cMoSe6HQRqSOh9e{!&^kXzJ=59E!%`|=|oFsU`EeqYP z+$+A3IsP>IV|L8h2~ND}UqZ!Oc=Xi+EdZJ%|~L1sv7I?9?=JiN%qaH2CNQ(mVz z(%=aI+*zPHJ~c68lJ15V&Nhd=P5sTNi}o-5oW2A>C$Gt;KkE>BxR#-grJ%J06~(W|5jsYR9rr zs~hxK&c~XFwuPEZxZ*^QFDS~5>?;Y#Q59Q7-IOyAT7R$%v#T$dYs4g_Edceg?sY+K zyNfAeBclfBu2yMy1y8`qI@qy$HQ+g=wuwRPlMR|0uMgZeMez7GIPYaPPSSpw8<`A> zcR39+f5h^ja~y-q?^b-MwD^5>`ZC17TtBfING%056MZ7Ym6ukDy|28e@Wn=>5CxB_htEHLgsj1L0l>mCt&>;`r&2_wFa-ocEUaoU*G zDQ7_QL#yM>%0KNu#0>kA&q~HeOv4g|7FmQ6zkRgalWRd1y3LzO;_uAQ&kF4veD?QM zfB*xGgTe24%%|-!6izuz#iM>B`Rz%v>mTsis>#Ts+{z*I2w+4W%Ej);2oWGzQf~_G zwxtzvP0(@-8-9onPV^O+?JrYu;G(*jCq-H`1Oz_Kw9A3%J7(==Jl049d^JJG;TllG1IA?LY3CNrU446G8FhV)(l2Q! zy8>E=LY;IO)@SeNgv+AD06`xVwNXA~7UFabhOwrtMat^5CuF*}I%_dM644_Xby?O< zMsJk%H*i9Ze$rX+#h^}5+x*~7TUE%T@r9GY+|>1b9SRK?P{H9bT=0Zr!zI5L`D%{N z1Y1_0Mj5xgh6Li}F{8g{a1a(3lh)q?NC?%V z*sWT^@xQj&QNCTB;OYm7gkG_K?*8(06Y!o5<^l~5VhL3dW1tIodyj4;@5AyWYQ^&w z2zyR|cA^h+tAJUd4^vZ=?Bka0>Sxs^ij3%UYSYoolxS9b%npOMWa{g5B%6Ga2d$6E zh@(4fSul*E9XY4SYH+UGL`D02+12AnYu3Z{In4gSLFhpWJoUZ5#!}0)!9;g5 z=I*kT79IvQtv4sDDUc?)Yh6t;Eaj6g2dz+z;I8`6%Iw(4tk^eE$BooT^!w6>NdQN< z~IU6kFYCTTvQn%)OsK699ZvNd>>Nn%1BF9r`?+g}@s$Xb=gEmP zM8lpwbpHb1%!6oud~tUSoWXIwP8YmjQA$Rdi* z{nnmUYy=!L71&8^T#xn`N|?UKUx9HS|Mu@3@>+OJq;uXcj_>SkUf zDxji!jxHF=Yd5KVx2M}rWy;Ee($g}ntUsx}j+zWRgUYtB?SUGMw# zyd^aY39bkc?~?5+q!%^Lzlth}b>9R~J~YVEzimkgF+~Ec(vk4v&Qg(r^3%p>L&b5T zm@RnJ;9hbqt-zN1UL@WUKH^eb2`hRqv4XXv8-K|NAbJPc6eCZ0nS{2W-g#Xk3kzT& z$Ah0SDru2z(2(UPio~02!=pA4@oAKYxCJf3l#{l^4&)R?|=lBx#lqO(G?*-VD~`dOzx2;Z|{3Qc|E zHH;I_c%!l6S_HCP18e(&VccyIx4-j5=~&Xg{f-4@B3fxE%fz=Uw{0;KSih`(CWOkN zUhgPDwWP97xbDWyXe$rpAy1Xvwl6;ZEYts79oaCy!3l13(Qj`ogUdUiQY$)UlV`p_ zXw!|{737m)Qu#(LXMl&t-E=dvBIZEyGa;AHs`LHuO#c{5Upc?}sEIRx-Tp zj4IJQP(x&$;#58n)?6c5&S2X1^lA`Si>Ph0;b}wru8$f$N}m__2O$@dItOjzIeesF zJrb4D(tvE$j?j+Sqw{Y)$MnD{%b4LVb^UN+#N^A?r?LCkA`-^2w3LmG=^Uy3Chulu z7S?X$1G6WlT9eGx7tLqWd%={v*8=VG_ID}P@@3srOOi{`Gri3^)o0N!wC=TKaHG`T`RF^sN?XxUEhPl!F_K3%|mmw zoQtuGe=JvW_O?~jz*_D~;-X@|NSSrP`WoYcGlIZ@L0GkgoLiQb52wY)G6<1+@oLpy znoOdGt9wWc;(oF#M|$46*mjPbFDB$+z0tY1-f=oJLl;jmtx;L&;@i|Txy!+%to97Qd zg7YfF{jX*BF(u+ZMGqGnaDOF6+0j(zp;HrA|I49`SIIu&07pjB-$((d+-q-YxmoXW zZOu-;6C02Ye7z7z#0B;?Y`sIf55xRbcY^jzKet9+;g~&N?V<@t12QXTjI?e>twv2& z40_rIlTjGtfWG9|Mct~~Eiff>R9MAS*-g1tctaw7U~;?}b8n>aZzO{aFi6=swg`t0 zob#2f@F1eh+<4Bda(y$Tf(a`2okny4!vN55sGw#4;Qdi-DX7{_B}2*f5FcefbiiLi zt1b!8a;BE}1LKQzmary8RP%>P_F2K%PoeWRDXX$Hj-k#4Y;Xq69rG~OxZqE`M1Z0| zALTqQnL*n%dA!2tJuQW1!z{oTh5h~*`YU&$+rxA9ortP3G5<-X2se51c_w_xq)ps+ zZsXYH-wm1;e)R!gM#P{w%^tJA8ehH)9QwZ`sKnJBrr-I;PF$^|AN!ColcA6m$14C6 zS5gN2*-%lm$w~E(^xhfw#h-rhGXuEl1I2mLC7&fl?gAvLhqv>3Kn5Q@Y066RwKmvyf@$AdNm`-smX<$9zUROFk;$b zG=R-P99p73py)n+Uz4_`k_05f*~})+WL+bc@oz_3!>gs$hcBeqjdK3z6grGcc7x*j z-6;*2v^8??=v7#Q#?0k^%3!{9*P@V(L~tkqqu0+EqZM$n89FQ?6ladJ$l*TLAh+t^ z_*Kehu$co7fm?Bz)Kgy+5 zc>nI#N@(x{4>7kF1=vsp7b_72B1$`T-bL|iC38_?HhO{-ANfM#eB^wbB zq{2NjGA7=`?pKBKlG=78yrqWF_9o{G*Jmm{t+ zee4qG0-a%q^+pU{mnRm%)T9yk`e^7)s)lI7@gy!Y|zb0QR%( zHhkto^Md>HCSe_d`E2mA#tCF-%S9b-SR4&{>Wko#P8Sjf^!{*77~jb&_SF_I+oi1W zL+;%-={E{Udh{@b0~EkfZoiu!*vkD-gBPg%QFM1f|C#zX|8MqR{~mbA6&V0NH~s>Z8!K(L$y3P}KUCNu z1l384^GF9?Qx5+Rayx8&9~@)+oPhPAKEN38<+mFa;VKrPp2L(z5(^qf>=xHv`H?!)#C-P=Cw@!5ArJgr zzAAYSjamsjm2C-LldZNKTB4&d=f|2Dt){H4`;X_v$T>*Wz>^|96G{rsS`_S!6da9s zuH?DeFg>&N|Ewg5wb2`1Nyp$Ymovkp&MMg`fiWB+_u#2hXqA4Wa!ic95pR|5IL({B z>bJdD&mdsDnle3cMbzlc5DYN1WB^Iom+zlAZSr=HZ!dk0_7|W1{magAJ@bw>4?RnK zNj$dWnHF|B(5w9nXOyaW2jrvbY@|9nDs~vLzqz%O*i3r8rVw?u64Gh*+L~_5V~Bhe zo4=n}#bfB59`*oNc6_SNuzqI?l?@B)JE{?Hqg8AHlyJ>cX%n$ukvOk;Y(02XlC&kM zv}V;EWbF6<+XExdM&S>9+n7?+X%Nm+|6QvtD&k&0D8Y%Iuq1l-6prZ9aZU468Pdmp-c8iai90|){&w8@ zgOE0{E^Y;d(@O7A4+ARfHg^P+@fdMCV9I>c#F)Hsi7Ve9MgAa!|CeUFD~5M@4qKpq zsSj$}DpSh!KZzjBkC<%+T>bf_f&)q3g}hSI25A*G{^8OK)(uy~-%}=#LWu>XES^S_ z8Xl!|NwmYTyj{x4k+F5)oZH?ff|2KB8h4mQvR@`A_Qyo}`HdxC31 zF&}@$lrqxjLd+r8n6%>PAyRJZh6BA0sKs6@xaNpXbWehH#%nRFbg^yCNEr}Cf}u+B zxy_C2nufzOW~!s_6*~2jK!v@r7R()X+16 z|1AoWT|FK7V8o0^Et}v<3w!af4bR1*fENNrVdtY>QP^>3uYvmF>b%BIo1-6+9Cm0J zb1yC8q9C1Hj@PJdBs8BAjymA4P&3xDx$V(w&zCs}S#kS0t|a=XmMB|m$N~nRU|HW0 z!=V(19jD=ASSkn&)|C_)9h_?Bb7DPtY)loOC| zD#`heY|-xE@uZ})P#khy@Nmor2JUkP!hdZ?5HD0#o1N|x&nL@>G8RG~=~pa1OF@x? zjXm{e^`;e%BfmaMbj1%9kP1OSGLI4xk?pCVBnm%kss#VeU+Ph>9xLy5jcqYd5*yw7 zaHb4Wu$*!H(5G)^pju)I*7kXqE8^pS5cXW|-u+tjhU4#mixk`wV=E2aA$fGs?528j zeAH!QBj9oR11B03y@d!&cj&!E2@wzCq3A2`5cVmmg|J5I18voKf`C-wLoGVxABos1 zmS>sbnFb={>B6Sj3JQML)Wf234YBup7d+zgk^*rNr8Qxsi}|B-fx}<^Ai%ME;uN;? zzSUnF{6UDyhxKKwM6qi)$R>YzbRgW|HFosQ3Sql8Jd+<7hkwbJ+Wg+wav$x2pDX0CE-3RQ`|+DMn<%JMa{zZU9{0(+P|9bO!ap>g zsyHh!vhPI)jvJ8Px3cw(>*J+}vGo-*TNbI_%d=tSgAmP&Pk$Fr&4)WnrOsq2r-c!(?+r=>B3?dwi^d^dA~&&9X*h9GfEpr@NX- zJHAA4W>{jQT(Gh9mmUKkv3UC(ao%xnJ7w3_?Im9kz*^TqGV-5U5@&IY(E%T9_4e0B z!ig9njB8SZ{;)$EhG+gD z%u)bIt}M4L0!v|%N%Nxol)P4>TzvL#n+dEK_J?sHS7Hpb5_+LNlD5(8=k(^a2iSZi%JcRsMH$1Z)+SK@W3><3g2 zSPpW&xk_>d+MH1L>Bm{d4W3w2_M(`lXN-K-)|lC3+zQ;%#O}9wk1aKCcC^N{^R-2?=!>}Pea6G)noj=PIX(gvT{wT5b@A!r-XJZC zIdWyh6`(WSsYbEN1Df`g^#;`qPKy&JEHq|Q?0Dx464y2xRM3=|+blc|`*8;hNBoMU zz5SMLOmBXTq?8?+JatJ^BvI`NX7g${5aLFi9W*|Lv%F6xI52Y02}>d3q`4jZgMh_9 z;5I89mehUrHyF(N8rXnduK1IAVFU8f213-g1Lxc}ng#@9jNTIc!cD88C%#AHo^p}**oHR2epkKM^KxA|9jE4UW6V23huaYLlB zD8sKcXY+(!r3da6c~|$C-iO9Ii@W|Sx92Gr-eChqQT$M98Mb^%GIK(r<`2V9=42zp zwrTSV$KKx=cDQt9Xe7ghetB|xnvD|$fW=8$Ij;5=Bm~lKmWXh2&38OPoOF0qx7Q{O zqbd$XDn~bYnKK?Wj2nwAs9RF{!;oyWJRX_T1{Iw-O}fEqR6rbWHSWxuG2Jd>Ly=k& zz9$PtF%K!0(xB5XTkt_C6ziwL4&_MpHC+I=xJSr^V?!Q4{WW&>+fj9foMOHYn`#Bp zIjuibzV5vz@gHNUfh2L2P^HMr`~2j`L9%xPd?l)OP;9SmC6SwHaiRsP6I=q-vT+j1 zQayI0LuAn7JfbC|N59(0OsZL1{T`Vw{yQp9+wi=jKDtaC2#}`N7N9C#>LeN|*RYY} zJ#MP~4aQtki!gEChTiTKbsrF&TT3i!U#(=EngwVyDs>WLP%o!FWTc#a=_E!|KmWn@ z?$Ew^O%KE~+9mUayfx)|YHP}$bgpQh2UzlRweEvaPG*G-%of@E_o#FBYBm4$MB@HO z#_f~|=J(w>qz8c)LC<=Aw4@JcuOFAQ*4EyW$)b3ZON3`>w0@3ynDbtRx4Ev=)a$wD7zi0^oEqi5rjpq;*>k*9OY6>sFRa3ciAPmAi#Di|o->}sTrCavE;Fa@w%w{J zE{OE!>Cy;F;%pqzEX?XT_nH5%ZkCy#0RyGJuDn#OC7D zsR&w(O{YyZ#zYX|STaQtY0Gy{k&F9*lt}j`Pc(tb@E!#2r-3d>CmP57j9H)IO-hND zJ!4y`9>T>a67{~)F2Do>55IHl=a}XW)R@t@*Uq0hrwB*!;^d$eCXTVce{!JTk)sSNoIxU9sRbT^t6}Lrs8TCu8&Ij z6=%^}kJ#VF%IKkZ$yDO6?^yZCQwk!N6>de=RkWy?YY)!%xEP(AkCFdwUy_p+B(@rF zBMsg*GStE9puv{3nBhft##SiD6b=uXiv9GffR4|cL?L&JZn_iny27nb16zsL3^{Tl z5bf`~Jz!*F(qrVmkHt+K)jLqlB4dAI6a* z+&Jo&xuL&EI67t3t%}o2{M4q}&>EvYWWJyf+%Q&ES?sl&$d$1$=GUoc=>V<~2|_oz za!Hy$G%RRz9^)EAOW8uEy%rn7R>NNTK8Wu$4yDJd$d8pax7B2F0V$Y@pg$Q-+-z;Z zEkplKQqo^5TdfTZz5k}+6YKwW{Mu>=@vD2G=7{Jmp6VT`s9x3pO^o{Ibo}VH510~X zbB-G5NDYkDm<0@2k>&DsTFM;*H>8Y;_sS9_#&2&)qK6`#y_3>WCEY3&+mv$_8?CqU zuy;{)<#8L`$xsiixc?xawX)_3v0aindt|-S(4t95;;OUiL9%>s9D&;}Tl43TzbYnP z7apjT`v)O@S^c(D;N1rg3UQM3^yufD0KI`7rMSv7)`mx)vC9~U*{!7kn}dXYHHbJj zc3vg&6s48%edKK{No)jetnUsINc5NQK+ph66!kZIrZ{vq>8niu#iR6m0+ae@rI6IC zZH}D2{KgR)sP?z|=iHZMU?l66VS9?q;0wF~PUuvZ<*l2@ zF}00a^U4&THWJe6O~tB~f{|g?syC-IbXCExDA9WPi@P6bXc$#M#*(R-G+fT;IyZTs z9>iZJK2jGh5g`jA6b0MAvEG$?i30jgD6mv7eEx4{0{h0fwigqSs=c^?eK8d1x))|6 zAp{~s4ckKrNUZOSGc(Hr;+60(xo0X+afi6*xjPQdycM0PXsQ*DuM^rI%U9 zFl;c_d6x`B6GA50?B=Gs=R)fX1%MreM;mY)e>HOC=o6(>r+9!x=}by)utzG@$g5z` zooW8)<6-WIYK=iyE@U00-62+eP;Ufx!8xss$3v^%Z1`9`

sc)iLuDblb5lEP2o?P&GJ%AVc8P&?XxL4bf^C$%O3WyZPUwBHu!kCahoH+TH1S%n; zX@c7T5)&rH(Ci3IXBGc>QyqmDiVvI9TIp@?1UD2t4rek_5Pa(+9{OaOGAA4)rGAB& zNY@g5ZRbr}hg$oo2HNl8=;CHfQ(D>I4k>wuLa3owXljp(^+a3A{!Yl+-J#RK|4Ks4!1)mCXp zUNH8$fLnGBOj*1b(VvO`+`v--J0)-j%Vo=h>!vocnU(u)r;F z>Vdo#P`(e^qs%&U&IabBB~9ASDgfU42XP(deuAI{&qgoctV=rg^x9bRr_|C~D#w8Z zVGbP8$NH64fFS6o{CIj)P5+%;3^Ydg&o9EIY0O9-ahEK`rj{O8tK&rdo^aWrmgaQ0 zf|}}`Kq<5=yQHW9TvFsvlJ@`o1OFVdGx_!y(rFa1iVNIP~Df(n4MuXJFvKoj_!D%9OixmeoMokNsJW))L)Lwl{vMoqmto5chF=~o z(yE~RcfbrHF@Kt}RfO%P6V9wzZuvLXITt#4jIp+lYAjj??4#ehE@REw){kG3#AJDB zn!lCH%{Gn9RdzdXQx6pJ=DsU{sz>9_aqg$%oz}N0()7#OLSMF8wDq?Irf?{7(%S~I zhENA+At6kRGSGVTrd_0#Xu%hS5jWXb#RokvOEUGJDrunXZ(DfU86f9Y09$7xuPMw4 zdE0jIa33}R@-mFvmcWZS9vy5A0I6{9iWz-=*3}9=pH{-H2+iUy`Z>PJMCPQYk?T|4 zU9I9K?uym2t=xBT*1Cj?x(toLkTTp6dpcR8-0{_EcaxCcA$4KSJ;D0Y5sqabOk8e2hnr*Zu7P*TG;ykf+V(&eVMLXUq$ zQE}WjFEpWVQN^iq#W{UGp-(Tz683((J-TVm+VAX6`zKI_G}`g%{HsaB`+`d! zDyZ-YydZ#wKmz&UQSaURcIK?J3k*zv!7`{AP$_2ls;ykHI~JF6L>{(j{U%n-xTZa# z!GyH(&gFh54iO1wV%(JyS~#NBh|-ww?Lt+yP6nJpDUQU=Q-V!IQY_9=@}rdbwHcm5 zc}?ygjdPdPoa--rC_G&p3mZHNid`t5jKcjEZkW@67_F9p_=!bP z=U=#&mfWcc7K~-Jqs9rT;;}ZO^f!=``7B zfz++LDNxeZo<$Mjp&F680DZrJiI)}%0;p;srW4Q%Od;3z#8GX?t0b;9+;xO)`@;pJ zQHvwI)3w^tk~^63Bq>I$v+s{f@x~_SuiVc}TwR#DfDfsi_20j7)^V2Np5V*Pku03H zp~_yy7%%L5ppd+ zz;wX3fF)D(hGd(5rdd}qAkIPwe6h-_eVnkk)(wg^>?{Uqi`#1VH9>&c=%?qQSZa4V zrg=1wbdL^X5c%k{OZk-OAi|(sQO@8b?^1?>`>CFMMTdlZp_W`5I}ThI2vb0&sm6Md zD}AFD?QUnu?D2PXkbpYF0^X&m*9B`A1P++hfV2Rgij(10Y0lH-?{cWeU&)#=`@nUm zmJ9MsEQQ0NrD{?<=h~XQzLdLAOjdG_sZe>>!jD#li!pUTeV|-QCtPe5xV-{#U8pPr#-NB;EEFh79Otf@XE-6l}?>44cWc z4)q&^IrkGXpk%VQC7Dm`gMr0C`&gdf&BooA6H5C*uqVJ!guy}g*RuBF#Uyv}uT5|K zoV+!Fe~@zzNxp*3peBK$LV892ncA3j8*LnqHh-vyQgsX|*Zz!Cmx70H(*k$D$@ejI zuJl1!qhuTI?W*QwmU|j__fTi#xvp-D0v3*H7!Q8#Y+py6-FY9 zawBs`G|}`6?RQXryI%Bwi{v`;) zMhNnEZ+~oM<1qD#@s&aUwfYb923p13j$8FR8K`UU;P0})wvjG0QYIOVO^;?j86ANs zpFkUAxDUwNNZg=y(|_ixWj%#a9FaL_z5E4dC(FIil5u+3D*uY@fm7b0e=(%wsb`J> zGx+M0(ZOjZlJ3~l5!T@o`ns>lJ{aY`a?<%mir+aep5|^luo7qGy*{-2Xfr0{2)1OL z5wz++R=LJo4nqCpv9+(6r%J%ZBAsu*dthuzGTAujpM@0}#e!(pY2boi%+F3@oZGo) z%&@me!J+{(uDHOG+i(m! z3ZMh7fMlU}UXUz{J+BKQ>6GTXAmijblKy8GObH%+3s}tR8P;?e#)kYh`340uvn^Zk zxb0FT3onjMv^g(ED7WTZq+saBrK9hz_voX7ABi^KMNQ`WmF{MoWHlH-!BT&U0gUNw zmG}Z8Yik|40$jH)ty(e;@f|{g2I1eVIn5ou<2awk97#$w`@n_~u*$tKPAo>;6eLio zz!ME>m1Z3kQYwctxLk=&-w)K4S%*}F_TWq`zi$nd)ugtuj*+5ljwJhtsb@yZ|KQbE z9ss=hu;$H&7TiZjDTc~3*&9S`{>%~g+;f!6!9(e)(_Acpq^s^%oTng7JJ{XNWExY6 zvd=Xz{t1ngW#uFO9L>uZ0BxT*PZDy^4II}|%cr5^(YQl?9s}lL)B+(P-k+{bC(~v6D z6ZDm#z07`;7{vRWV5|_lgud>GzV59#b9OuM_ zViqmW91Xib9oh8TeQegzUZ#a~Ge>B=xSSt&78P8yS+$n^y^kC0bcdRhp*GhM1a%hwK6|L?(pr0!sK)PBr~H{xI?E z4&#qYUTEc9hfJ~0Lv@L7ZlTEks_p$C=0&$#E!^XqX=U))`t%4I*}c_fIUwJz%pAe! zWc}mPVUIe+bG6~2s08wXEtL-l4GQ7epdn9o!>a6ny4Qe5dJ>ER5Otb&0+H%v*}I+W zG&A845G6q~GXulLe;3pNhx%$rEKlwaFZ~2EM5!f3b$v{LnFz&2=ou3hn1sgp?4X3^ zu>sOCOnK)MKSjyc>x}1rRns06T}W)W=>>p=!$rwV^}D4{@O7Ivq1O!6q+P0FVFJg) z>pmuj^dF@^e^Dldbb9oUBT}eSq-?`+g4BVS2Ir;^U0q-9ONs6buEIg~8#{H_lM_lL zBAHG8P4tTlb5|~ch23{^`nog5Qzm#Pi5ITrtDKwA_R@<3vdUb1v%A10cDUneRZZ2dl_n_OoLZVT zanV#@?KV>kURW|=Ky94(eNy0b8e9C^shUr~`?SFc~wyXe7$ri|Gcqh!CQ!wZD zN;X{MEkknc31WvcjCtS6$a2xJvaTiPtYHPvjK~aY3QR^eP~Tj_uB4V{X(kj@cL@;$ z)2{vT_$#7)H`f!1Y0*lJ)R9zyw3!Yq^x3eq9|<3qr*KI{56^WH^-7zm;F9yh3J;qL zTbh$;e917JMeCNyO6ecyrN2=xZLj02AlI|7>lVfoF>6sW`cBoh_R1c}dyQ58hIyze z>L9cxQSXfH{#nHEu~8<4r)A^;f>x{{aGL1ldt;9DR9e(iS{b;Ejjxlh`n7B&5`8Z# z9@~Bk{FW3TssaY=f86BF(}=ZvLt`2^Gx zB1@f<`$0cZ<+OvZSXSbdZ&$uen3-A6YqqutnX4lI41!32Fh*x59;Yeq=tO5_NDk{) zHFvaWs{P=<*AG;I3`8sNqFEgBfEt~5x3g$xEq5O8w7eJ2A}%bCY3YJIa#iiU3uUpu zG9~_9z_6-S!_D|Dk~5PSSDT{Qf14iRdA{H{Z-{Acg%LunKC7&&G=Qqr^Xu0S#gJ4f zFGJ%16*-Pa>S1BZ>SOE4GTMy!UXQjxS0rO>_2K_+AGMUEFZ4NZ#Ry%*`Zz z5Wen&s8MyZ)6B9{4WP-E3>eSy6=Yl(bRN0h1xn!Eo?eajO2P;Xy0^40xGZn0jN}WU4`xuMZUBZbq$aqeK@E8PTIVLTj70L}YTd~XGmZ(<8=)}zp}IDbuI{?@ z?U6UsJNMiU*(+X1<6^aoiJT82-)x%fsHsDyOn25DvN6HN;Swe=4^tNwH8+u$jfR?Y z2HB$mlRP^8(_`QGj_9@B7yGp1`I#Zi@w{51rv$J0zOeHNvv~#aadyghW5!b}KdbG8 zYukQtp3)D~+UfOuIHA0+>dR$sUmqPB?>WiG8&c|jwyFDcj7QqH5^TfoQD$~3EZFl6 z_yRq!ZEyimx2?NWEJmkW;ODW3=PI$Yd?=FY66Lwa+HWqI?E+0RL;jTNGu%rAZIzGD7taO37&&&qA2J*%)IZcq*tQ2ZtHBQh%T0Gtit)KAyq;lDMWKh9=l8^ zgk07<+AkTBjNooSKyuir`sCV0oNCqELNedQ7z1vVMTSq6y=x3)%iREE&DF(fnRPJH z<>t#0x8FCIjqz75Y~(YonX~XVlKhfi@YqmyuHs$Eu4R$b)}+)Wfv#n^q&|r9KCJue zP~?a@PjvNv-u+c0&We1c)1 zxK*iXc+uNqkCBL~omYmpzIeNZJB4dfM1Reb;F^DNB_Sbkdqan*A?bFcJEQ|ZVLlZM zcFJ^j<4mEKf>PG~+Z5!~@?NI(r}y*)bet96o-a6Q%9xK=1o}R!GY=nCTGxjeHEjVV zU#x^Zld@xEsVUnh>P?e%;5)JXsS083sAoSX)%(RAmAJMkeqdI^?m1OUF!;Rgad2rBz}%^tyR92benMV`-Vcq!hX zT0-c%7Sn?CAPO|IkqN$Zu9{I_}v@V^UP6&s`IP)?^ft^Ey zR1>^lC@FNa6*XC*=wgjyQE&LSlW;dX`6+Gt1tgiDBw$Dyov1&88;ok8tAbR$DYzpz z4F_clf~;|$`_EKXy_!TK=p=I&?3LJ}O1*JHW^MUJ(CEs-1uYcYS>kL}xSCaau=TTg zMq=U{-`~Wpt#?b&9(;N2{yGh|F6j}(jBy27IobT>d z0K}Hl$Gf^|r-#TaGX`e9EQiY<0>cX~IOosawLI!vTf|c?N`HuqBPE(Xqm0dtKP@RvF{hkngzG5(YVL;|Y-6 zp%_q$j_}zEgA_G4pAPH^Uh~ntES=*USu!O!RlSGL2UbK;%7l-s+}WchBffD;vus7d z&7}hcFQz00fI>Aux+qUl(7nB{GK7*LV)jU939?DG1fa^gz^p0{f8}bAw$P(o!H^*{ zVY5lI2~2swN^|}qmeJ?cPH+q4zpaAoWZT5Yvgcm*Y~|-z$Xj*)O7&XE3@3GNLY8W&zHl5vhLw;4-^xZEe{*pqHPKJ^Gp&Db87WH>#)l!%$2-%wQD0@LV zc=M1-0PvcJ>gCAHoT0;94NsWNQ^EyGnujt~-ughU0z^}{eMoxKvF??63S$+g(<{q< zStk3VWXm0ob)rO5q07V*<`T`U z0#_c{f!7%YhN@2GCiRxw9Hv>-BKVY*K`3GHKvu`*m0ael_OfO!(rq6JmOxRDc~H^3 z`r<*FiaBobL0G@7`>|kP#%@w*dRFwbA%(L3hsoH+}*kX^?h z*U*Q79+sV8>N2HR@u_xe$V?Hq=6h2rC_>t)pF?>Z%ociz!g5W4xI33$K~jLDaK1DL zkmPop2gjJ7yKL_fNRf<_|MkOwFF?tl&3%=e(S1Ev1&2K%aY-fH6W{;`fm}6q!nB>M zZJFMzd!=TcpAU#HW;3^2R$iH{cLi|pAD3#^adCoyDM4Fr#ZxHrZG!Ju0PH&Rb83c_ zZ!F<;;(ASWm_zB2iyqVu(7gGIrDz2^fNip8oRI<|UOLW209+>qK`$Wc9I_8A7csy% zZN6Q1UAG^md6GD9(E)`$iUzY5fp7IvdmNP0EW4UxxVoU60|p&g@xeKP=Hy;nnh)Xi z$fx^*u|ka|vpVKsR_%Y~`t_H$b!R0jKIx}apZ69!Is6o)IzTWTe$3^zUjI>R^HD*R zs64zpVNEv%Uu}ykX$6?>WDD3U2dI0bUk{9v!)W%TbtOzUh2a1e|se7?-{=8)t zOx1su{;#0gjwRDxVINegrC`3YV5*_XiU2XhL19NFFeP$IVWq6&Zny+_@u1sM|KY(P zu)L4O?P2YN%*fmU5U1-jPgt{9_igV9HJ8l04~z?NG?_)hR>O)qiJ|%LFAK`WwYBhu+IZ)$#{P2I`2mnt^ToO~D$3ZxxMnn+{|vO4B1 zK079DJ+CE;mP!+U*7Jdqz9?G|1CHEfU2wqEfe0~JRm-q8d2uuF=Pl!+jL^x2o z5+loV7h2CGpq5E1L9aKKL`{NS%&!IN$UDvB#ep%Phb7yWta0p63Dn2MsIe(|2p@tz zN`cNiF90LI30C~m`E|r_{dzw|nfjZ+e-xy=ewpW>*ptUR=6k?jOZNot^q!QtL7L|% zflH)xF9BZ%L2ta0z@u-LneBY@QJW+g7pQCo_1Bsm7f1;4!J(keIqI<_-$K?!DYVie zG(PG%yQp(Nj)fY>T4t-z1Qt7mA;GuNOOh!?1pe_#EeJ@9Hl%EsuVM_(8z^`7vm4>v zSEJ*;$o&8S`Hm>r#6oz9YS6BF_nV8*=ZI2owU$zB)<^7zUn4S zqPe?j(-IIyvwPv~<jcsmpBaa#gE%cV0Mf6LS&sWEIHh4-S-ziEQe`#e z&V}^t+`TwZ-uu}?u~@t@&>khE8{(k=v;=JZPn1U1f&4;j)zJpcvx++!Yl~HB#x_Ec z<>uQhH6k-5e;iw5sYDT4atV(`D?MC=WD}UrFZnR^OT$5SN!zhL&!Z5GtAg&aAqEeO zijf6Z^=z|=$Q=blG)J=Vx{rpe_#0j+D1g)%Ad$>hekud96^`&#aE1(%nYxdCac0gl z2uI$Wh=_F7hzEWz7>@Q_?ODSau6Dvkfs6a??r3r_i=;{5b*lVXGt-Lg+Sab(Lj0$0 z8nGjhM>KD3H8UOnqR=D@F|!B2IxPCiyr&ye3()9Ij8(^~)4~PtVpMtY$M}njeJYyJ zG(!IgA{v6h6g};}1Rvvza2jgjvsRrU~)8D!3+@s$qsmK*{hbBwq=pZ5c zEPMcE(1vcSEf=P`aPfn4;e(AI-DNV54Dq35$r3b8mKA2&v)q+(3>(OXp1DxSz@?xddBx4vJht&fL$!zFf{v2_2=V z;>9?CtnkP*78Az8Q1q2|!N~uVORZlZSS)pb7UyUVT(f$KZQJId+h&t8Z7w&huTKvG zI0X}{fWs0vzkJxB_Ab1QFVeq3C#vQ=jk!MU1R_$ZN?P}qUCNtmb zQa((f;hBtm;TIhyu_d6pVO7k4`woNgU02@ytwZb@!^T;u0l-&K0OC%`8m* zoh7TPOy&612f6qW{=O3ZuQ#pQF?B5n=af~M8+RixssJ+PT9@FpRuEO+G^X$YH@g^b z!fC#)d>~ND;IdJ_ZKPQ5l_aBRvK0`X3piZ3MZDZ$c|=xha&N_Q0!Z1rct_Hi85x;M zVHt_U@QUk4bAb8rK{NpQ7?&7w2-3hs7%Ow2D0$3+=ALBe54kH`=E^#hU}?TfJs3U{ z(J)(`6lzRS{QjbKr1(0=e2)zoy+fJaFiCA!3w?sU1#JXsYFSEF2+Cupk)m!hnScpQ zv-jk1ba@n9zW<^?y`Q6`rGr^GrB(O?^S%^4kH8S39E8iE5|4%9A6C{$&8V9{$(%kv z5s$Nzx}mV=1&rIu_Mr*QiUM>dYv_S2S}QUaV2Ai>@*VI^n65bRY|t7$7Ee5737;DW zft(9D0hVKsSIepv)DJ5J9Cv=cKhwtm+QF$r<5vB4xnd*`EP%~i4l{(l3Y845B>J*I z&!kLOft$)mQ2c(s?1~$$0PX{T<5&#spZ0HYZjB1;GxS8bI|oMvIWLYsNg(}&lD`N~C9M1mBAxJM2G`&Ij)XWxC}jw;g~Pgz zrJ*wL17QzP_G(D42#`KBm4NqUj}CwKM0uuQ72;nrcO)6ch1<4r;i@* zjxwy&L7WX3K;#^{XD;l4oR$})KIb#1LlIfBHX6FWk#lafb?ge_Wjg58azMKE8H?|Y z6Y#bVp#p}FAu@p4?11k$z()qjaS?e6-JwQu@;-#zLWjr>W&3C$`5|1-m*4gUC~I(eCqKoOPFncB(9zwzelWUns^K;n!AFb-j0bFF zAL^NGZJ$Tza|7(ZX{B`e>zc98f*Cf2ms_zFSrpFgW1et1&xLoTuO}^yKjYLxTQoQM zzLwuFEAF2js=lZJ)vVOm-okah0Z2hKVF0_p?2TrM(4G{#g-bR9guUr?+Qg3^53uXf zrnjc0F1aN2m^tH=`xa%p2H7)G4_(H4EgvTCNeP+bkg2-wN%R~?^AJ!v#8ru;P%x!( zIy~jAN6~eNdj@Ewn!|8eQCO~uM=_pA_+yKkPxsCu231aXOPiJj^i36t=_(48T}4x| z`=|GL`8qT5+r{pPP7l@E4x^Nv`%=mxqCma%Gtbjx*OJCp`Mwz&D{w=mcb`I%oz@j0 zgm%MV_5jq)DCckG!K9GdkRf+C8h>Rdj?b68lrAwME%az66J#H>-C9@0Iv0&Ow=z?s ztNt|j=ay+o)T8XE(?EgZS&2YgWOGP|$)>T!d-Jr8^EBxX#_+=?tUP3EdlhF9~lB%e>C~){SH+xg{n?Rgbd=(=@ zMHPpzWDFe5nZLprYp@QQz|*d~WA<4ART*`yo}g@v>v@w54PzYb2o9qqt+u^tjU;Fy zK$1)h^zAKDct3IcZY-{Rn9U|YxynNTCE+}s8TP4}Ml+)Id8@}D!BD^ zR0U6={NYuG52YYlz=F};Tkb@S9qJ_|?TbiB51IH<*y%?W zim1smSJ_(#F1%rSLqh^kLk5BoT`i~4>t^fH1ncp@Z1MbV(QZ}HS{Jn;GhfM8>ZmG- z)SH5h(AByHO}Qoup(BWc@(IJ2GIiJDjfp5NrMh^I1T7}MAQP>V>x(?6iPPE|4aWfe;oi1y`vXo6j0y98 zN@fxI5z~{17WVm#@BQ*9&i1~vbMr&-v*k%5uY@TFa?X{%RF=1LRH6&EWPt>aAw{#v zE5{>Q%^Ez^R1gjNq!Z)f9?g$S*HX_-6p%})=-VsO@*%$M^!zDBGLY<+l_hcxetYV~ zMuIOsuB5Zz%1Lsm?c?J0RKRISMVT5KXJz`O^cm#|ng5cRlN~Mh9@X`B3&aaW8a>+u z>IT7pQ#562vheJiqS*5^+P{yeC^5}tgV7rc|CoOj0FADaAW7{GC^(eULfXPhI_oI= zEAb*ckvX??xXdqFZ;@fFofzVN*12vUzqdh(j`)VIQp(l>NZ3iJCn`(k9GPMKbWbo! zU_}XK))CE5*3sf;OweNc>JEgfs617b;nnKM>(sj{Z}&7sxiqgBz!Tq~PvoOmlGw3H zzLC??uiVeuQ$3h=oO?1=C%R#s7Dgo{nroIuumV-X`v(j%Jxe3Dwk>H<(){;pm`&7@ zecT1HO09Qh>w+7aMZ9XK>`OW&= z)_m30?4_+Zt-p9%!F2#XkjvF!8WFzsMc$ z&flJ}8|AFJ)Ye2G#>R%^@jNOO1wynH^OBS^%*WG9|wtCkNAIAnboNabRtmY?wmYWrBB zEsR={&DK!*;!1~a5n!%uxng)9j$dEhlO{?5ivjiHQmkkYFL=^h&EUrYh&uTysLn-Z zr%#`*2Zcd~VK2n9FmmulevcoQ47KhC)O{iu+Cl|<)eshWHVO~jd`jeanKE9?js{Y_ z$CB&}EZ5*oB>C0XxGK{!t1P}nLf3@VLRj?n^50wQCZn4tN_H`&?z7eO@<$SxTj%8& z0I<;L1D{dm0kc-PymQF`RM5=tsadDsfZTkTaaly^yl*w*muPIq{qdqsR$~{HInB6& z=ys-0Z+-Yup6K*OfMgSUSSd%mB-9CR5rqWwib#puN8AN1b;~U#NA#ssRTQ|kb8Vj7 z`-@+qhZO7+NQSbz(wf`gig!0b)%?3G!M4Y#pb5#AwBwsS68ZvWYICjG_bk*Zw zob_jmw}gl!ZvLlTG(iu!W1Tx==1kKw@1Uvl**3)_#Z4gxF3EP4pC`p8KDn05#ivuZ z4yWH7AYd2&_0+*E7%>hN&Zj&0x+!&UI5D#xHG|WdQV3zMpUEW{0(kS&uO0( zZr0YEm4M6I{`k%8CSa5!%-h611$u<20$qJ9SC zMZkYFT{6CP>6hPr{q5K5WLIxoyL|cbujId6`t`TV)HEEzw2!Xb;)IK6zH-9Q{SKA+ zD<(roRLdDxf1B%%Cnhej{j=L*vM(K7-)5F*`#0=dHT^S-`)OSEz#P4tS%BO7&!vrh zyFVr_UHj#iOIM|T1(Yh(S0A_QlV3fe0~KA*F!j`q`^#|h%=e^GfN9(-D{usFP&bcdZYvbw6J{=Sy*fdiXC{Bd#f z{M%Gt19?k>orCAUo=4{&jXc|f6gl~R0I@X^hzB`WT&XtG02nf|E{NBwR?Yg-S7&ea_h$>nlqEAwE2Prhb`5@ zKk2`W)2Fre#wUlpD_IYHoqpu7sjuBnjQVkD=kAc!pd>!S=_t;Iv5_`;9cI2|x~m@b zHc@>fMm);5m{4aL~0a0=Z)>96WV*Nr>3&(*p46j(o(l0{Ed-;j2iKIi_Jy1@Q45Prc?$8v=MHi)JJjOvn<-X-5E-bDzL}v8?S#{nvM82 z^Ra&4W7YK&F@eWj=0Or8am0s18h2dj1=?iQ2~s-#q*@A*{Aya57omB z_W2-jqtQFt0|Q^as$VAkySL_m&R|P-vDiAV(UxR`;`KWcayR{k+$r)xYl6r>z9c2T zeUSL_4VS0&XI$@Mr=j?S=Bk`9C!e)G;~Hix>|_a2`1fsKrapbMcIQOH&&uoRlOc(k z>uM4B_FQB(7EkQpTDY2D|M!@AtWWEsZzB<3oa?M_9zmk3gJJ`?CbjR+HtnVO*12~` zsp;;+^1LT>It+*UV--smew%Yi+{yZ@TRbJGN8D=sC~BXz0mS`(Klvj4(POez_Z+&( z{wjXnc0JQUUn54BL21u}wsz;lr8OgO@JlBE1uyhz@%u96i#iUKCU~y?xYXp^xbQmL z{^MT@o<8qb(h35DXPb5A>nwfoy!8t|F8%G0deU6p8hh)ZRaMI-&jJ>na`2JpGv4@B zM~I3FQ)Dsw@EmeiQ;Wp;3i++Q*QY1^oAH9&3u@OV#>Q zOf2%9p>4dfe=js&@3iu2ttntYB+wS{_O9vWFaGX;9`?ZL`&(-DccK>xXTPMBHBHT9 zSsBq;*nX+Wyw(NIoU3!`2x9N<{lg~1vUS+urv6U#^MrD~$q%WvX=K0s#v(eIrr{_* zK(oxIjBv$%vYgy48B(`nwQJH&V(Frrew1glw@cmcn4QzdnuVDvHmU6UamjO`a*Xn^ z@4er`t?F@(2WOKCzyZ)9)Y}+&O8tx+Nx;1d?H5ZdZ11%OBo<8qE zglvcvU z$*Wo&)e{MFQ>tpK4lMjHhxVeDqQ2Y~6Do5G_c+{Dd-KE%VwqGpV(dho}3q7p_Kg*DxLVOj_ zPWOIX@|bQJE#(!OV_UruZ+-W-+PP(xtKsi7wYJub4A;N4tR{%}7Jy=m4pHLqHbhOk zS{(buqzJ`39O0svqI|mKi@z)O)$%h0g5hfv!D*$Q$>Eb zG@o2(2ep?i+SGcg?jR6VQ#pBs%R)cx{q^Emp*w{V=%;=MZ?8?VAj4n0Y7Wx*GGEZJ zQjLks#(wmNt}CRMBdER&&5qpP9Tw_X*KTf$Jvw>!??5}pv>wCX5rXy?*fexmOha>e zol5_hdY1l6L9C?VkrV!Z^B$8F@2RoE+m=!i;Kb2=H;MJP=TW(&Xyg8&=@RnO2Pub- z#FebxM{e|m9CynrVM@}SB1fv1pZWFqE%p|Y-jh19&xntR3CItJ{zrnox*KGh2CKyr zRD=|j`W8j{^4)~GlLM#0f!3np3f$E)J&KP@>o463?+A_@N_fo|%}PFM7#NYCa7dcZ zCB62W7SCHPC1r(+kx#WdN&bmds*3gNci|yrE~ydayHXCrlVBUPzvtLrOL~8z8n>9c z)3}ndevYuUoon7HS2&_>eJ0DX9GNB6g73A&>Ygr>YTc$kK`ayR3#RT>X_FeeXxcsb zk?DJc;8?BJ2$bI8oCliyMu+Dj*~hBmyrFF!eiNo@k^IfIJ?NXr_t7(P?sw7Ag+Zf! z6so6eMNk`kmFlvq(&H zcv#LPO7WGIyJA%AK^M_aCv)mUvLD|I(Q)oGt>4xVmNUU|*Y99Qmi0XE`cVbf`w29v z@GOf?&!nk66=5B$YV2}F7WLoqO#)(J__o9O$0YZ(dZcw)lrmdr)4|Sq;3TcLZe%?? zJ@W1S2?>X-y>*xCUt}n#t{%UL^+B{*F?tCswx^S(sVX9_hQ~O|TK!TOZKU`@y;ri! zL%mN`eM7#4LeLt=R%`NGoZGzym+6|W0@CZcsh{IK3R(i~$m!rX%3P)~P&eC&qWS2M z zuEHEoC~GR5Hn{D1v_-7X?WQ@tM3$SY2!ps5idCdEjkYluMzUvhb`!S3n%uOV6re?&gn#6=}e0j`<*=}A@P4uyQl%AVgRZUPXfl_u=J+%Jt{H< zm)HcD`_^)4B(6pH;ZiqS;SC*>&Xn%!ij$8sV{DzVk~J*DEw7jCaRC;6n6UmWy|M2(mVVbK%G18RT%`e&cEQ-EUzG_l|J3_OkleHbI z+BpIKTf{nrm@5BIl2qeIJIx4vBrh4-B+RoartJP3pNZ=5Z=a%rNSe{}A{fgdO6gwyV{U5D-!e)0g3t441h5Wd5gI8*k2y#lE6qZ(o^`l>s zj^=|In^~bYTNYRrpO3bUIx=e>lU;@R6?c?B6EB@hb0~{dsl}3^NwpnhX{wa?;Q!@4 zz<$qln+cqX_V4jv;h$@-ZrjQnW_u_iYx45*9L=g0C2QJ*$7Og)@VR3<$O6kvPydlm&)9)-!H0vnr~{9JCm zw7)y3>)sp^= zgx5Q5(eY!)(%PNY%ldVSS1Z2CUp8o)U`Cv300SfafySuF##uP`mEREskccBH;u)f& zqt$yP6p#8wn%7a@U-mlQ*$$|g7!etBAl9}Hl&1|-St91Xgq@>3Ht=u%htDX~2I{Sy zRN|_&VfW1k=?^-+#}rS4lav%chG0F<0-{c7M9=JwPU3iRjU>gWyn|0f&(+L4k9lo% z$3t?85wCO}dG#)5#O&)QAp*v9j0dB>Dqx$+w&dk z?8Wx!r6{Vv(I{Fkk%Q{5sfN}y3KN<3PqB`31*gD2;P~H_Wbd!ZIW5Agh&dZuv60+- zNvcdgtxxY+5b&Jwj&;ukK*mh z&UEq| zMVq%6>~Mw12OQpZM@S`kH-b-5NUFQc~ zIiw`gT9OJ;gg6RMIJ7+aWDZ;J{Xg8j?BeW-$_*5uHR`Vu?_n41A6lHbwR*XLVjvOF zRZl{tzb%uMrVctyC40BheJuvM=*f!}2$&Il*s>(HCdr?pj%xntBw@QL-mIRm$(Hu_ z?$@FBlV!|R?xB@g_6?W+x0ZANCngyJ<(72g#(ZJkubVECkQW|FEbI_@1wvk1H<){>2E4Y?JQ{mE)AO7_tA%<*ZdUOL;3DkgO_LN=;k<{Ksr2nqIY z4ZQ{KFpI5dU<-lSgz|hg$ptyxhQF#M6~CG4|NazdIr|`Y?E57s$v9q3_xHN)s+%QI z*S`OG8vK9t^8WvIjm+FxdN~&UhJkw9AD6z|imHyEuAh!^bigA-KCY zkc42t-6b^c?h-UXx^Z`h#@$^Tcc*a(?k<`Bz3-jxd+*fDRNec>)Kqny>OQBd`qb0= z>}Tz@wq$zKviTPJoNxqw$ll!8>{q^@^KS8?kmcKIvqk=q93O9Q+T-QcH~!4bqU3W) zI%Vf1Z24StL3}^weuaqjsSr@;|BSir$PsIWg(ymU1ak&Q)gB8Uwf#jBItpL3fQWk5 z-vyU$Osb^(MM`i@d#E*!9*@@KkhWo&Kl9)^aavmY;VHk`F3^$i!= z-v2sRykPi?q=VR=AkA0ZhnvMm7$Sd2olq|kZ8D_pNTM#aIuUV*=oMlnnbaLa15$Gs zJ8z2#--QAypbc9bv4dhUKx3YCOjaJ^Mvcx8KL3uCWQLU82;utS|5r=06B{gzbU;LqFv?L0ZM`0n&Y+)0uTO?Z1-7mKB2i^iIvpZ{zU!>Bscg;gz#1oWZSN|QsPDiq}M#!m7zZ(mvh4BCF0^Q15re_W_1QldYd7fFkFe7-h z+4qB%euMe?;Nfv-2te+s?R??Z+R=ftb+khdCFQM0s#wlbjA>_^ z&DLEOUbWM-Z}$92-{zc87y5(qQDMi$|{1m zf=5Is(#`BrF>8LVCwD70AgtHNz_J}0H%zwpgcuyFOve+|jVxTbX&$SaF#K^slsQ;5 zmT=hQ#{VuHeyY!&0)LyXVc>)f&MWJ22DCl%Sy1lwoUY|0Q@U-LIm(+R{ddSl_8iL$ zbmH(Pp7#-<)c-hTB@wLiWA!xKvF)UNYd`DdaBoP4%GtCMZtO^(VE@Ib-i*BDRO)EY z@%rN<-}RPm>{07qBx%=yN#B0}@!6zLV}|V(5jaiZI3!_4IJ;>3e85JYD3~;dc;IOS zEq1!J8-N;NyIqUZ!Ac`%Td6rdFts@Izi2)GwzoekYelVqKzpF%xrF)+%N{BZf`M#@ zkR&!v0Qtp$G-m_LvKJZmvv=Y5Iib)OB~ko2-NU6h!WHl9MSeWAeTiLLsX08gf0iKQ z=6kOCEG%sNpU~bO7u{N#$Nu@4Z`W_08a$t@%mCUoyT1Cs25E_dv^cZt^T>zwV6W_s zeZ1OoYy&#--Or#t<@}csDLg4ZZ=O5KOquHrL>w@tx$Ul_{d(5X_f4U-3jgpSHp|i5 zJh^*WwoM|CGqinG0IwgpG=jtBkTjsmeuY13K zZ9lH!{7YOOfyOs%zA<uH&&v|S{WZ**N^{l|K{UsKy=*+IjRp|xs zl?0g)Pqjw4eDK#P*0}V~Gj+ zPJ0dhCttP^oh;{4nO;EKEodi2+_m1vQ*fr~kZ@BR-Z?c~`s>f|2^Oc^g^5Z%_FX;Y z&a}uq4B!vE$>4|-RQE>+I}eEU{ErBWhMtla6080AaQiR%U|tIkZ(8oYbkjqTSyFq`0U$PT&K5kj#0wDz|z&IxHcY*o1>B-&%HT)i@b`i6^4ux(B_ z{u`O|%OKL+LQq$Cq&lm~mEG-KZOJ{|IMU`Sdxau?UeIUR)dYfk-R}hc@z5-*C7kHO zJZj&4tlwEaEM`z%I4tx7!p(p{(3KEr>r%@YOub+fDUcj`~Y&+Fz94DzKrD$lj6w*QWth}H#6&QoHaa>|Dv$&?O8a9X~l zY0n&9P!^kQsc=4thV%bI_iLb!R1-1P;uxDdz917a0*A8CwSu-eUOQO#8>T)L-)#mk?Iinb*y{x&j@!u+@2@$VEY$|<9}Qq{65CAwD!?petr7pte@-% z+*z+bnekNr7b)p&5rbFW5ov@(@G3by1C+Ho+|<~w{M@~LeJCM$S8{E(oQ|8o{ve*A0c`kG`z?l5-t3;|qf79}hU=&8=nmxE}6&3M;!cD?2F1*EU%r>osC~Y>2 z1h|}IKNb)Qw82T2PQ^2=M@DFL zBXN;FrN7(qHEHbOH~Pb-Go%h*1nng#r6uJGQe-twa)Cn=D#GM_sV#*0#=xgC(_>9V zW#l6b5Zlys-|#aXOqDX<9lq(yW|szXXZ}MXUQj;rA1oR#hhhkXz)rBs>C*$ML$<3a zspC}Y`@X}^h5LpATkDtdq>;RNq=gStNgtU#Wq%8Kd5(i)jzHukIfT6qg?q3Qy5E|w z$g=7g$*jf_uQS+A=V`Y^lyqzbkW-4<405ec+DC%g5-!L%40Euff|$5Q!O z(}!PVya(FXcmD92Bh-zWFEv;49YPWg{*NZn#6HDgz8<`5W6zriKD?bU6T*4#0D2n2 zG}`L-JY0(L>Qv{nm6x-H9}T#A1>#xre_gh@@4xkKv2WctEC7hEHjfn=5PE^kR!vXa zlc*`dt8$NRMbGkN`Ue@;XLCLc-suL=d>etp*9I8Nt89RjKw>h*X!iX)958c0@v-BQtt^ zCFM8Tb7{}?MN)dv3hEXh3vGx8xy4HtUx73P=|M5HHVCrpD!7&HPr6DO@cFYdx_dD3 zx!a%B);z0Xz?BY{D~zK!XkHVmG;sg;%H$`~GVp&=U@pi2Naw+(?;fHo{jgs5kn@OA zmdY#GwYS?}V49-7*#7L0gdhh)ncV&{3`+UP841-c8K%5xHiS~P_VZqpiP~SoKNc-PSi@3w#xh;fg@s)3#X2c$R~8I9i@Q5$cRdg^f(^=vO9ul{^ z^APyM9bSCA8eCTwU3Kf;d@%IH!lrbSNdgqpHjUGwhj>9 z!PosYL&Fl6>5QG&BfjtuVqUaNf9R+0ye-~zeIH9szw9FfFqHm6ls|>J$fcWaKA#3j zeauc=PjJy719G7riRs)~Jq+~@T`%E`|qZSmnS~gLRNFpm>@{HJfY(WzuD;huY zleVtd`DZ9GWk#F(6_$my+~~DKMGaByHB9o8d7b$KS-{Wx1S#)y)E1L^zoosIuAPk!B+Cy(%e32RXWMDfWrYnY^)kn0#QzqD12xU+72V7ZX2@$|FCN@|P<0dgU^ zy;tdiif^w;8@$FV2Ga=iXUmI#B-!0iB)1DVu{G@w>21o3?xo<1K8lb6u~^}OT!_uB zZ|C_7S8VL0w9E}5S7m+GzkeBl*9U?n$oq8P?*Ab}r?mYD)Y>-PownM`jprxVn*yK* zh2DYX4|Uo=$`6FBiPO)$Lp$6el@9;6Cyl;FyCeW~CnE6_vG?ZzYkdB3r=o~al2ofdX5MF$W)5%`_oJ+`&S!acsbV{2!ln08*m2Rd}pvGcF{-ahKR$-a;BJ8$*U z)u%5X(g+K3H#5&z#nC+VB0q}P`5=E}JhPS`%vwzJA;$7fXe*ePd=_QE%gV=l8W*`#R@z51-rk$SJN%*@kBHzGWSwC{m4h2CmqAqFnX z(8LvowHp7(35P8;f);9@zz)OOr6MpX>GPI2GZ6{L$j%NX)w?|R7!(od z;godneA8F0%C{bUC{RQiDHa=Jq)zW&RpM@D?6dOzG-iBKgh3Gxs@U1uBde+w8)N2i z3qU5zTMn-hpJT%q()HyKfvzHW19=W_dwh(o2x`|gE-=HT5^0^T!+uROQ`w+N)4CrQ zJ6T5q5G-jHFQ3yxpMhnKN?~8xW z9qJkj{^}w4C%8+U;K;cR`U^SCcIHqiM8Dd2C8QJB*>(Q?!O<29A_ThUj_8EHu!mi};@W6rfD3$L$;zMFpA`<}z?^TPS)IqH>&aoAP#_6t(#{G%n zZ}-2bOxox<>q&K9w#m!4|AV(O0+R39$#Vr&xtwqJ7oY3t&91R}&JRp88GkVOD9T^T zZJl&3lT$=3HtkK09y*99K|eXs$mR#)Nf9)cXFHOvv|!By@m~T-`i5N_g-&+)R;fm@ zt!Qz@D&J?Pn+=0aj9!MvP7cZ9S6S*BZ^f}UY1RwxrxS?($qnskes83zvZR?TL5Gj$ z1o*D8NnTvd;9;@TR{nvjaWD2IEh^`1Pfk&ax$uj8YHEAGdA(ttwvb8bPC3tI8=bnE z(2(tX~QiA}f4&!OMmn$h?jxZ7Qv!JL_8r$r--%5RYj_dT?5^Co%ARWcqCFqQOn80;fjCJ;Jtm(AYw*H zlaKosiH!;R<0(^@5!*4Y?hJCn@~y;XrqDgV*!NLgE=_>5g=#$};Ts@0iCgEPSk$jRS!%4kW&4fx7+5EKORJJ6^gEndZADJ;|cIL6pX^3gP zv0rrPGL277#95IVK7W6ho~qH3wsbVc|5p2IQgnd#Do*9}VsSaP7JvBs*AY6ugzR4= zkAg>XD{>8KR&VFG*=gr#VE8hb+Js#xT@epvq{KasK!HHKJvyZwC+{ALI<-;fr9=+l zsd##+zvSq)*6g28Ze*#M&?KZ5h$$5&A`{@Zov2Y5fo)QtF+9kc(#48>k;a)k55-Cq zll!Zov@4_>A5%tWLF;Wco+FWsj;{4}{fT0eM+!_~Sk{Iy`~eT|>Y~ZId69hbAdLU} z>}fUq`~(cdZa!^=Wl@*RU#ijvj%^-ao834cc4J?STh6wYu0&MJHP=6o-h5@3B(Z~3 zZNG(v?Za7mreEB|J46Fa=d*c~RbK zZ2mM272?n#RJh%=s^-2ut%nW_Op(eg@7k)el=;(>{y9O01cF!bXo~Z4&(+y>2{Iuy zFw^V+7w{K@VsfD{+EL$aUB}$(j_RaRA#v_0-fQ!tU`c-DSiPAG z=zHJvX|H@q^!D@RMk>B*{E9Kco7`*XKrIT-zC&hxo|I+Aohi>CuSHwC@)X%){0sBe zt~P7l2KABro40p0@b&*6d?k4beV#R)CcnB68-_9BnHjabvGS+w{qCSxWpgNJrzzfN zhs_G!GsPLZApkCAZ88$!H70HfuDy!HU_`4dH^^@ESz5e~RJGa;ET}JeBXrbmE?)p4 zkRUB#b~CG;uC#N_3zgSq-C~Gf-Ii5aX0bjofO<8SzFTvo6f!zdQki2fedj-aaf{%$ zEz~EJ`&E%IUW~lLHY^R!=F?Ob3KP|M9efS5f-VKC0~;W@xA}yi-q5HPoI|^IAALho zite!%@JMOf6}9av^dnN;&`rkug2MIJM%U@8eMZG%09noza~-+T164hpFWJw<^2QCt zyHS2%N1b_?z%qQlPM~p#?2B+vM>%EDwwQeqW#2&n9bJj}hHzZRuG3T4&XUGD^_{LX zil^vn!9G@Ji7i>I4&BgQS^QTu!$GA3O{Hr;LOM@ni|oi}+}_{e`W|6JKkuJ?fGbsI|00D?oaxYMYb~0JKg2Je2PM4RVfp0h0wv0^ z>m`>nmkBArO`@}}FT`_ZS0grH>ChNcxh`ClP!L_*si(|`0IMkE-&Gz6!_;ZObdiWxU)>t4VSUR&Im=gPJZr9 zvQ8xn9U_C@Xal8EXwou)xg85z;8I72rUdlPEnbg&GvJ;Um|4iu;74TD661QsjLOih zI5Eb@R2quG+rna_V*j*S93;e?s7AiY({Rq;ojf*{ff!Cla!;80d5~`Z>P*-~Py4zm;Rl zWUs#`Jb2asbgo$q-Hi}t-Dv6`xMFGwEG<~)YJ8%{Qsyy&fc71wJ<_*nNQIeyLjX#$hTg*&4Rhb%*n?T1l(EB1k1TtB& z_S@B!qPNXmG}?w~FG|Tf8&k>m=9DLQEYhHp!e%&V`fj*X(Q%f4s*YQK0OUr^Iy$}8 zG%5j!+AO_JSCjUmzqX34!;y4JD$P}~p8|?8>Q;|$LA8)R)_gpp96kXAe{o24;D@5o zZ?i(oKi382@5S4=S^GYrA_((u?{ni_bz%w>6nf@7=pm@Qp%9>rrPYSKzt!|I!(M7< zs>Yk9!kpr`6Qko#Cjx0&szUfw5K9U>RJ5B2d}&>^+hvx=F^j_N;=-jbIIc{oK`|}y zAs3%91I`e06H)M;a0Co))*NlE7!pj;66J|v(kyxJn)0(Clq`$O6-TVu(Zbld&f1_> zIGJtpw`ZK7pj#}$Z?eB#m8>vwJ+-tE!y!;RrBrRS9n6lz>&nXC*b5@=`dZ)r_N#0T zdIiSizABd?DFCoAUmn^w6!-y?GkM=dH&EcFv34$6h3C5;WqA#4BJ|U_sc02k-uGCE zH$c+*%fuJ8`#F+=)J3fH8Cj;5o1RIe~ILg{}j6{x0~@ z-Xoc2jSYK<->&GR&oM)?Esf)~2cMwwTH0;Q^?V5+jL{iB=z5q6%d(*)JJu1zVa;*` zwV9ef;$s~8O)1ZyZ@!*a6(YkBFO)8xcW)azbgF%&k8G25K1fzb*!3;s%IQqyb(7U= z3YzCyOfqA9n^~`=53yQn(0dm}6(xB$_?fWlHYNHdiyeF*4v-Ua6ilcmCmTY{5Mpcv z&UO^Sv8h)gBo=uC+Cq1*gHodJA~e?fQHn%WL3QaZmrJZwXF5kXpEMzrO;;fg2dt{% zJiQqjuQVy9i#)PGm3%{2xVtv51$!~3twAe=_rA5^j!z5xXPs*J33!@-{Bfri_jQSB@+BKXJ5X@+7j86r& zda=NL1b9$K?H6PlU^w)2l07v3i`4dbu33V}T^^I&JI*vn|Kw0vWv%K%5bp?@!o_Ww@K@h(uz8I!4W8L=X5SHFd7fV!7v!(Dy=Vsf78SOg>SXS?P^O5p&+wp>! zUqMY6wtsqhl}D)Ph#few((7wUIwxaYRedURq)4xF3pzg{Rey)UjAGB(crH?X5*8}B zUi+(}yi5Lfzg!nthRIKcx#_Np2wYL|#z>#-t|K#Et}U#`>DcHETp1hYrn%M`89U`B zT;gen12+*5WT(ca-Qv8Bj6+46r#2ojgy4-au*_QFm9Z5C$y|@VJY!hZYM840)abH&+A>m95KM6yCD*xIl0N^i?l@}7%x1HuDQYA(ADnq>^R8ffbbS0t^0{Bt<)<)x zj{Sr{bXEC4+BQIXy(tv&r)-cq_QvS_u{FB!dGGpWh`G|i+Td+}pr7@hA2Y_$tD8GM zSMiz*#QV7zzmHJ6J=R>5r=`U3N_c%Wn~E}RF+^T5_fXrt;#Y9jnNMdRoqTxln~seD zXI48kb&eD5aD=OwkQT;|HsDkqp4x`IR+-_s=X9bKlsyi}_Ca?gSq!5wtvbmXcSixSE~F3`Er zI8N!;xzZmx=BVYVQ|5qNs+&u`+3OhjX3fskesg%iDf~>A(o0Rt-a}Jk^akZmu2qI= z$6aDBpZ2U8k;SK|rEWcJLb{)V>XNJYlf1n;2qAFrqvt=L;=R=Ekz9&v`~?Z==2<+w z)FsF8VPnl<==)h%`y41P^N0$jfv~h3NBTbEv{!nCKV))BT-cs1BkO=)F zNud@d&bB-}mVDFk;LgbQE6gp9Fe=hCg$G~;uf-R813DnJ@{BRpxo*=@W5W30ke{1X z&?+NekqICol698!}f2IInXvhn63oX))C-F*=Mn9n`eM3*VdF<7`08K&}1xZJIgJy&-u^qEP)BLJcu!k0K?@lXzGC0u4Zba zO>SA~FH6=!W=lvj9dv);wx(s)pei`4Npk#v4jA>oPyV3$c`!8oPBeL0)7bf|Ipe1S zs|dczG$)0r{^}@j-OAE&k`QN4lt{8K&2rU7w;+I0Aa$u&S(H??2wcS!iORK4S|L6@ z3-12iM3+2yBuT2VT@Z4zER9p;7R*z@w=!#!_ag`lPH0VL3V<4fs$-%jzFml~ss6J> z9rTks=QCfWigGt&6TCyg@-+b%Nj6%N=tG4*YaHH*=6dcI zriq-QTpX7R;2Ktqy*A|;eAbq0d_Q%Y zOy?A7l~z`;8d!4rkw-%(3}NKXsr8V1&wKcbwe~Gk%l}8a6uBOSpc&hYSSIRkBIj*0KHmTSN-b_S1g-RlwoKI`-+w1L2#$NC;`B z7!v6`azn?^s}W}D7})Q9eQ>BhiTRXprgGW)APTVCI1mr;AIq=LjkK7WCXBTM%f}>~ zH;MvU8%xVyt6AsTfUt8!EL_*c8*AT5g7|tvHqxOoOStGIc}~@9L6G5NGr^zVCe`6z z8YdQ?mx?~EJ8V)K^P#7O#lSP`?xTF23N3-nAjo4Hgc-9f`Z?xbn*4y$QQc#<{aRPy zl2_fg!hG8|NJa+E;X=MUvdIkohAee7q^(&T(Anr)BeE>tQH#GwsoP}Wa)oiPx5oMj zR_yQD4(-i6=PnU_01!(4j-G7&(n|0A=?{H>H~t;IGphmA)GeN?TjRsf%_Bu*mc_u; zcc|6H=d|KZZdFdoH9z?a?B5C$R1OC-9gDZ9*r!(Z%-%K*LIuLV#>bUMl?ezkm98}y z@;Ula%pS=5XRCer7}*?a9byL-LcWf!L(XwNR_<2iH1wGw3psp7541pPK{eCyL{t6X zHzd2VXLYa>=*4i}C$t>B^5sCbaIFmA=uo&A4Rvvb>YNvS^}BTQA@p^8%JEwd?e#^{ z2pjaL!Ls7OSKxCirf}Rc7nPIZ$iDu@qt^Nj28Ob?>olr_(e9M&a6Fst&@zqg9&dHP z_&WLf;-DFM*H3H*DGTboVtoGACHc3%hu%lcT=iv@Stk#xKd1olzikGUjn%IB^vZVD z*fl8B0f$~}lh24zsX)TJH2*-#DHmE5lNZN2uf*Bx8tW^ByuUM8ye(%6{fhj1JaD&V z-E26H*_#)wvOJ_wl-5)!-UiS26Y9EUX-d^??CkV3M`$o>{>jd^668hUyU8jxB+Dxm z#naSm&Fiw!n~JLZXygxZ=j@vOgw|ba%8Fh;B2JeJyDMtTAwpRP!#jzCA7?vIX|Xb* zck?gTMQOU;>W?AG|YMi&%lt9h|4+GC<%><_^kn}-;&gFeY znn>-mxFRWq#rpC@j`>|ufTrxJy=aDFH+FSPSd;(sd9aQc@iU$ z71PjGx5j~jOe&um_E~W`e!4lu& zSCSODDxIe2OgfyrIR7Wt88{p%F;+QYO>gv`<9g`Aub{-q|1)b0OBmfQRwVj5KRzw0 z?nseAYbvw-eD>N!$cz$taE&=UH$QQt7Cie=JlC0kQKF1yDU3TIBYEJ=Ed0Id&r>Ve z5ah)aO|GMJb#qFalgc-nr8bn8$=cV2X__=6Rn6#_P(Et0k`bLyxs}ylDQa1XS+Ph6x$goIwH~VC`mW zt=a`sfj2kkNB)cXoO;GyI~SS@b9+P2R-GC-#~fifZP?H(f((p1?Hk`^&su>dwU8-t zMIXrl<%D|A(q#1-wKp#D#1)v|U0BW#co_{ZG zDJvpGxu(#NAF;*CXm>e7bMy4BfWS*7wsdD;t;?iebd(LTNkPeS2D{$x!;uWeg&`Q(P20g>3d-lvnHsJi#+^Pp|(9P9%} z6_FTx$4D5VC2Uqh4Bxnu&VAg$Svz_&6`JxWiD+&TN8`DQsDzTZ&uCTh$!j-c1Kyjb zvtb>{U(DuumJu`cR6S|2-i_#Aq-GcC)FjgmuO5UklRQKEGU!d(+|C72*KqlGw?TtBgKY@FJ z-R~ZTH+7BXM)w{miL0eCW*^7}TvEbPPv)E!yr~)-Uw&n(yEp<+5NrtyGW@Jc(G&@yEykS-rGUHCQO?L3e&5TkWHl&+@$hAEP255fHDd z|7wiBZ;tch4glaxqpa*?HTf4Qy7iaDOWgG$oA+1}_HT(rz40W7U2z*khLWU|>6-2F z2AOm5-wkWcC01Xr$gDJ@XA{Q6jmWPHu)On^OctPR>d`Kw&n`x4=L={Ws6>(KL@8^7 z@7~aTtW8H*y{d;YT80cJC%~?qN-?`6>n{*<3(`TR%Q}lZ&W(%3x9)}xLIFhGIeG3~==kKbk%aaQh1N^^t?I6zt*>P%8>S@308Fw0B z!HneS({iyEky7sF48-YssO*x~NmB;kS8yTWrfD29bG#>Y7zmF8(4{U=b zm%z(+YgOzYeQ2nnEV>>6b`+UR)Owmr<4 zsLodQL#L}T2;Jc;@pdnh6`#&E4z{A)TKl8amkQ5RZ_dr0xxye8vY$~w4V(nBc?G$T z#+{``5#iz_wn;q=Sntnh&_G0f1Lx`ps1_V^sKS(OGBfPL(ODd{oE7?=@6Y~*>nGl- zS)pH{=@bV;zSs}YUt->wW>eaRBYGU%TMKq9EH3nDr^>5)aW3_5_U{Nu?h|^Ikbi^Z ziv7JZ&jH`r>N|y}SvqYjwGZ5~`NUDz?Cg4qRyzGA+KCqpPhfJ6udSAmA+=YLKcF-J>?ED;mBV^v7YwaLI%S+~1`eOJlWIQ!Ld{ zbL7)9w$`3)K#UOZtNP$?LV5QmImEM;cm1t+eeGqUTX%Sb=EaibEO)V=!rC38wdm0o zh^xyc2}k7*(;i}-F0Wp}D5}4JJMFwLtN$YH>5%dhJ?M-Xy$cHSClvGrO z4nx^p0sS`&IlAnLeP@PWbNA<;4g!W8$Ynn~xIH0K7zEA*%l=u$U%n6OXzq;Qb@tYY zC-yEe?+gDTsovxh8Ata1Bv^~poBb;CD8VhNr)#4) zMyT8r0}9CsH>bhbDT zC2SJs6v`zQ?Bs|DvaWGa9LgJ0RF?fkFcLI-pg(c+RDSx;vHoAjf8HPd>&!n#g~_Hc z6DsFQG*;VRTf7&ZZkL-AgfN(;BUN@^ovGhJ@K#o#<8XLJP6xMK;co$+it~V*PkmLI zBrAH%Mx!{}0)!WziB~wX6VJ)!3WcOD*+3k1cT1GULR2pvByAnUzad-2dVQb~sy<4q zBD~Zs!hBHmO@!;mAk+v&?&}G&yC+Vtl6tTY(+DlX;|>d%<7R5D1=$ zAfP{o#So#nI@ERf`Xgik2aoq88pkVms_gaXMue4{R+HcM>_y&~G0=l1#ZiBHw12#u z;E*p_Di$B_oSv|uY4ehaYXliC{Sr2>C-i6?gys^q&b;Uxu^&Y6O7fh*&n{Om4h}2OAK9U;GVZc3L^1z$Ad(&!0ujdT`67!mqCUSMPaKA{;`cmaiL=NCo?q z3cTt~dK=sYm!?~i^IH5y>b6OblQqLlagposZ)Nx&Y>KxFaICc*ZMlyIf*_hyDZ=JM zy(Ch-*;jVkL7G$FZ}e5sNq5C6iL|t*i}sA74L?%-(l1w;AqnoiCs0S?}cOa;jjop(p>h zAk)J0MnD!7cLkRx!cq$JfZ@B`yEUyCm7Pf9>Yk;m73EG&Jrk=D7bKR?^4WQ7$uQ%1 zp$rzli+Cs`E{DvR^V+Y~WBW`lGc3Sjv$POE366jH1dSH35Y_ne^L?;j57g|IH^AaY zu~lZ1J7ssEy|VCK2-mY`tPJ)1A}36@GX6=e3={9>Qd@f2h2FYsJS&WascK{YLifX3 zI|CN#lrsy43pSlu?hocVQEm#?SM%>Ompv|3C>2TP1C=gvzG6*Os4sz2IRjNqiL^o7(tROQLV3 zGJ!y7v(jLpNgepZQhT;RPHJ-jhQ~~ah-~(Wm1XHYwLXNKKdy*-L4P+w`eqLg6Zh-H zYMoM(D92rxIN3`nnj((rE9ZJ^LAt-uqcSSJ5FtLI6IH9Q0FjG~dvg%1J@hW&836=5 zARZPn@B3_~YV04T5ot?l-w&Gi(|opXg-sXDx6~J3ocoD zhtmC$mi+@4?#)t~ma!t@I1-Y&f)H9UQ>9Nf{Hye7u|c{?o8 z#Foay8DAg3-$xl;oafo76x^CVv>IAYTp8EQ1F2H=>QCO~4p{JAMPSd9MunxK)nlM4 z&ObHDXL6xsXLX-{INu07nxeIWTLypcCz6p5A2b5d*Vvl&{|9ho_56#p?Dpp`lJX5y zf4crq;WS*7mn^m2USWu$Wq3;pE)o>=pX7aGVP~mIOuSB_?SHAcw%)QBHLQjiL60cGd%9<)uP# z6O~iluOe*!7&qD_f#;>%2;Yq0V{lCTa)94fGMIl1st8sICR)n;h))gFcwQn_EyP0JtdC_4?86(w`N8}ZWUxTXi@<)>$L1a}8_ zI76SyX=0x8q$}437*l*4H~Nh>snN}J>yeSQf500=&Nd~F)p^w&LIaGInJR=j_(a@< zLQT}CM`Us3a~8tRRmmAvnP}9tWX^}gI%iA@7d84uN?m?xvsQk)C{Dy4O4R6Ak%YV8 zW;2Bg@c(Q>wP&x5pcor};am+->L+6lr>~mkKE~o9`U+9|^?G3W>*mN*$e10ES))=@ zS~RDLm3`fi95Y|dM))irIPY{`mxDm)7Jm5Y2qu6Ae=6qh;Mto{YS}bvO=Zep8pQ-B zHI#W}Iq(5*YCH>I>uW!QZE-5@%TjdQwCXtpFpUV>Wuz=2@n=P5C4)Dd|~ zGRm;tQ)prKx%m&!D27#&(KOyP*it|Jv!M>f?bo*+>XOKsmB8~1baN0i+FYEpMzL|3 zXpwF~meS_UHeVLmH#Z}*k+Km~Y?WnNp~Z&fLP1eKp|681SZj@G!koWwSIRsG=LgRh zWVR!!>;}~;XSZp76d7rd{q8&3M(s7Uwoy<^k6tNpxXe4fGJN~2HfAwc#f?boD$^GX zxc2ip#$H76W$<4uLB|J%$F*nMK6Mkc7+MDX7BBc&wu9_akDm(Pt}f1d544Sc`Ic*9 za*=m`KD+h-rtEH6|J)G`a-T6l5wEQj|D9cGZX(0A-I64XXj(4<7B&dT4-hN|>iS^Q3Cq5HQ% zV{OEV;^gG13EhI%s@%iDeDzws@8zV=Royxf4=#wgJFuRmWrjGIaDYc`tL|Zj&5rpK zO@Pm~;`fsSK*EpZg4|>@O;Yga(Ev`EAt?Q*ST>m@zyy@zGSfFoAY;uX7dMj17aW$N zkv}gexPW|*8RafkK)Yu_fJsMYWy0- zvF<6<+FvQ2D?abm%tfgMYEn#Rp$py45Z_pi&Y!Dj2jaG!^kg+ivJPjU{D&*oG3)2(b{N|qTO-+d)KZD>n!yXNjVIs4}Yx%fa4TCxU(gTU9s|zNAJSB~rWv98< zkLF*_rCtm8C4S6DmEHu&?N{w0dRdf4`KS8Pd|db5kM`%~ z8bNE^hZpt?gLd-6xrA3jp-qT!G8FbU?&q<;0(L+oCmK?gS-M>@Ax6Yu0yjd?>{Ng? z$k7&#H!(x7>3IT^_ea%|{)G;GlNFV&EQ8s5&daMZgMTjS!l#d=hCH8-qtdVZDtOb< zvi`;sPbEqy-(GlPVLN+mo*v${ueRoVv&DH!!*SCwz8dd?<$`N;==CVR2G#u~@K|2l z`<2WP{k6mao`re#{9xD858(D^L@2a}Zcip@6Xu^HEtt4R4|2!k>Dgtabk_9#cK!0W z*>PX*i>|``PX`2ev}yaU#P@mp>(XII59?a-*??DeD$nHA@&ZTu5EV|}Aura9ozn#W zgu6I%@lu)iAXLBWQyIb6-5>6Jo%I&${BRctc!as(DmA0)u#Ce07z2A6s|S{oV63?P zlDCP|a@$!#Ur4!PB!z@5p;obuK11r&c{*c7S$ z4*CyUR;BSga2`H=uBk4&#^{857O?=`<;tmXG~>wgop&2d%Hkwq&ebe%c&|DcUoYiC zq%3y}*21UWlx=XwjjqCJ#7oH?Wj5UjUJ7Hp3Q6-l`a>f#e)1Y%v|n379JMH@HFko7 zwGZiX{cf2_B;YYQD!8Mzu20}N3rNB?wM1d{1O-o@3b^pxV7}Uo4oz?NU(ZYGc?}f* zg1T5-M7N(ls@*TpnN{Gbgt%C_)`Pw*eRzCO_P$pzjq61N`KBv+3h8+H`NAu9sQ}vf z40z_c#H>(7lMJ(^yy_Ksue`#sQ#i^BqU%s@u2m`byKp&^Q<0cnLKI~-$*I_AebJd- zbSf8B5+_RfXCF0fc3GN)cFEN|`tXyUv#!{WdZzSjv+(nN~5; zQHBF81xRop)6(s$oIui}^G5c_STb#7L)-iV(NM2E!s7%_7{0kI3mWw*kq=$ArRYDG-hSjU&BY3>FsXrW+LcdqpHHxo@rG| z-cdv>Z>1f8%CL{?x$EE^s`;kPAriG}Ku2Ix`^@F+_=59P^hY(t+*W+yLUjSJ9qH7= ztjEdoZuQu?w<@CUzE)NAlTaQgKPtNZQXbDXR-*2T6^iNDt#icUthrO?cf|h0xK;MX zbwa{q&3d|4BiGK-sZsOQAwp)JLz~c?`X(}p-`Q}>B;!Ic?;vkN)3&_hU+3zd6yV&g zMico3j$;*F!M8=Cn?XQK4KCYvEbTQn1_%B@FR7}p4tq^eQ+wn!{(gwmMnr0jRc?L@ z8@sH;-EeN>@d#;;N^(~eT3m;RW%k@jR(jrM7Oq``n5;`( zz&ES#W^K(LR#w-EV9aw=Yu ztpZC@(vor<2jf+EP2H>X_t17Qdv*Eyibub;(o*I`Rya?uHk6F8f(AdfWtz>op-#i; zOl6`M4+$JMH)#KMi=>U|>hZ&gXw^eb4~(8OEA+0P-8pQAcd=6G11r_DX z8eQv=y~_`AW)9T4gDCE22Utxi&JOR$q)d8uc{de?2RLcE@j-G?7Hsb`;>gRt5$h{Ky?D)&qd`nx(6_K#Ul8+wQe$c2 zYNC57*Ruapd-MH=kgCl<1X!PGfCEvu`AMZLx9@?G3*JPt&vt)^!4)wG z=eqb0EY24OTbphDy`b=*11zLTGPG8 zRi@WJl9aeL_#H7e3m`Lf6J=iL6P!MjdPip(bdsrhI5N6%ueqF;?S4=9sqMhOwHhxY z#$6(PTt_59%C6Oe6^nUhQG>ay4%Bi_Z<@Sa5uHE^AC%EA|JinQ=Ou#FFjiiv6XLT7 z?e*QnX3U6HJL)D*Bf?{Fott=>Cg_AQ`s|*}mu$0ij(mB#l8u|}`F0kg0Qw`$-{nv87(qR7? z@{~7rE*C#*U9-sE(_`Bn{9ltyDU))i*LsWmt!ux#D<}r~@!}_irl~ zewn((Vc4w8wT^qmn1UqMe$$FhTx-|m#f-vOgfo8a_UkI+?q$P(?S+}B-ZuZXyH^-N z^PGqK=6pPSCl8)UnK>|WLxq3Ty!Mt0qCr_sEbAp+?4uX?6{hAU6a~L=ChOjO@eRbF z9wS`N-*t_wKyE#`B+vEYg+ag?uZ+`~9dKqnP~Y2U^J{5KuoVzbq#_&Ft&_#}@Q_&C zD_pzWHfI`2WLBQqJ*2H0Th~M7mD~@9G8|nBvJ^QF4T&C>j^4@BFZJMKyDdn4qQy&y zhFT7>rs9q&W<+`J18C$RKQB_%@?DXSm~zG51GWpTM8`lGt8QYBFLN%y(Ip+{t9_^kyjXzM#LadZ7Pb%%wgz ziIpCaI5Kb_0mdMgZl90gUM-M@GVoZqq=-2#>n@FUOn9d@(dZD?l?jPFg|6Tk>0-{5 z@VilU}FHTGX$R5vFQ;o++6K%(Gct(?}lcKk(EdJWy za^ei?9Bc((W$ZIUt^|~q(G+{k@omx0KUh`xRsuJ)#@M^Grtay>?C41hW7^tQHoCON zbkLnD;t*Ll&!6!msTC=xrv_lBr>C&eE!4Vz@l`HTkN_l13~iUBxzVXkDm4!cQXX7e zo9n54rW_a6O3|(9=;K6Wz_dM#Qf#lFC>+kc#~o$^vlv}AU=IDD1?DH-CKh4HwCiX= zGqgIV#fECk3+cu+=%)6h@WX}dh9b6WkpmBOh4x(}!)RH9G7B>LVM2;^f7jRsq1DOw zf;SH31{73RIU$nO;~V;=0;tGP1fdhX7o4BpbF#z^c`VcV&B_@)J}P#BNep1^^90+I zKg&WCK>I-%%Bphzc)})l+kHFuvsrX^2giavrpKv4x-O0TNhNY68OdO;$R+W?@(cAx z389>e+L7a|E6?P6^}n*zoEX{1XBV1e;g6^Lr4=i3`jpR!eSsH9#&&4GO#6vQ1w)x!pQf&D9NgJ$ZGoz1CnU!Yv zNk)>Iantmtv-{(ksk42S!c#f5WlgJ(N)e>=%8PVjN>f#d4t6iKJ#BsLWEMnNzQ(K( zW1l^h?>81);-*}ZWDAgIeKO8=-9CNH>G`m zA@a0*eL^+dLQsh4MgQCR6rTs|A@n!fnycoSSjkpQYct zpU*WJ12y>&WP+ywH0J?f$$SV{lT^B2iw6PbLglG`EqM=flsK4gmxi&Z2r{+}oYD1) z?Z`Zue#IYjC@2KE#=}+J$MvPF#wa%Yv;smuW#+&CYjo>a#CXG*cvJj0^>16#f`n?G zivc4V(IYbtsW+YYWC=v`xZCW))#!&)wLln+Fq=F_PV-r|DU+$}Ti<^OjNGvu!@S69 zh5E5JkIRGojcA_6 zXTBP%jcS-47E(=pI}g61d6HK}^1C~x`PTfaaV2a(3`^7VXA2YV*pYV~SCu#G z*+(BE%{D_dXThXN z>zGJWBa{1tSQ4^2PFTv@t zdTu~Y`L6F8ZAibm0xi?kw^Wfu8(m#`gf&Qt=Q*~oJfDm3vTgbH*KHqiQ{FAjt_;q5 zAg@jhV`lcFR__^6)`lR%Lf@hp4zhlAFB!VKU}xbcM=!M76wKw~61lDtfDMc>2(p3+ zZJaRg`4RX0f`@ldS^m=<3i_yZm!ir@q%N*T<~k?X(y(1nw#8?tNm>Nv=9D7wph9PHEb)F(jaJVj+U0I#)^lVES;f(z^v8 z>GbmK}8gqaD>=UB7w8K`>SWrURWo*$AIvc!t zUQ@6Vx@~ovtQl0z%QRP|j1hM|8C}}1R?5bHQ?+8RSxT#;vzn7~d9*GJSU>jWDyBib>~$ygeOPl= zs8FFTj^(l}xlUK=Qj0aC(kG(1pIOTC0ID+P0hfPsBM+JhCoqRb6S$H(_J0L#Cc#vB z4{-ka$Z3_^_bKac!dRr_wLyEzw#V*saPSAsFDrX{i}o6BFLWb+5|(~cjjp}uW?>vz zJ2OrHotD~O7} zS-uqi-ukFMEa!?9S@Ivkhjnx~7#kzb{_BmpbYTbIKN#1*cWzF!t4dfCWAa};Ft*8& z+8yLsXS*b^cTgCdpPPSW%Jef_vKKS|cOnTUjdfcp3_`9g%ak0Z-x~G>MN?lucQbWh zXi;i2??FkRMLxlbL=qBkVQz)pPS4X?hk%K9SFKbLvc^kSJM`|febXw+^ZNpi!g&p~ zngDF21$Ilr4x^9}gXS;3LT}D&;&n(=W1_&O!mPABEl%d{>R*4xdtq95mfP&+(pg-^ zmKO8C@?&2pz7Gxh_Ma6ddarno(62K$@HdIb1^{1!Mr^JAgx)av@qfuvwafEoe!qVji^6TGahm7-w6V z9Le9SgDSngWQCB+Q(D*_iRK#lV7rXxGHdnF=4I84Sw4b?J$D857PrVMq%7A5&MAWU zbUVl_eYf)JKUHqY5bDB3V@%zsJCI{M_3G>K$j$>=FGjOc$E|Q|vGxLf9;e~8iVoEZzAI9^k8^we{&ejtgux*j({$p_vT|N_ z*CFP#ZiBEp_4TM>3_!TF+5FDI>AAH$M`j6T>4i+#Ug2PF24JFYMQZ9Hal46$U5o={ zU;6!r&};iYQ0>D1p-Oo}cIX30N`ZWonS0Cn`S zfBsqZ7kJFF32>Wqwtr_(_zCbz98{^}02oDdS?B9aO{h)3Gley;d1kxu`vvIS<+$ZX|<#Kj-p{rsCyz=A;tu5N~i0|Bbmsk?H{;UT$0e1{EhjONNY z*C22)eka^~fui+)Z;sFm4&$Vq>0^nuus0Hj(2*hZuI&1tI_T%j_5nSCeb&D4i@ z|MqhSKG6=a>d3jhAKf9gOA%jRdJs_jqyvKcE((2C^O@T|E$K{0=U5%per)7~do%*8 z-t|Z=(>BEqAwK@$vZ|FE>dN~O9Wt}Dgyz-k7}3gwOsd$VV;P&sTRzclif+<7v3vN~ zAINA)9^I?rl3VR`rsf=qj4G1J2RHThCfy&q_g+m=7A0JxwXNj3dVZR2xzwvQFN^K6 z_AWab{tw~teSWGn58tvp5sSx}i~*%)?r1^5$yiVHnBK4e5i!fwQSu1=lH$m~vBmU4 zPZ9YuIh?#@{LK3Q`bZAHpA|Zpo6}#^Z;7kI`*ri6qs&E9nn3uXt?InqkDICkwG4Kl z*jDl?R~Y>8y>Wqu0qFS$kkhxNN~Y<&z<<%vQm!JBU)&(6@UOUM2BDh#94(;y@KL>= zX8I1sBI-%<`4uNp8pokI%0LWf63_>2ae-xzZCFZLGC7Xg!pA>rN~*Dym!lj*%b0R9 zLd}I}Zq)Y!;X8?+c@01L7TRpC@|>ddw)8DDZZ^2lNeints{(`?O<9!73TY9M=|lcC zyO2!24KnhHSf@|K)O9Shs1=r%Rg~ghG)L3|h-ANTsOtxiv{y zP=5|7I@Fx1W&T14lNwHnCWCci!;K0t|GdK97tlKW>8uvudoU1aBGtz31mtO zm!g>;c$B?VB{of1hUtDODRY0sw!N)amj;|uO^gXzMEHCNAXzbXit@m=N^%*X3X}eE zdCaw658(ipBQ5UWPD5`o@eVh0Dc9UnEP%pluG-tz!>sdgy@-I|hqyMA*i2Ld@84KiQFmdo5CPqC3{mbN z^N%*za$%XHDzuNSzM#AxduVm*M9CsKzIjKBjq3$>4%}w%RdkLjT-O<&lOb%|v$cAc zA_P}FgZXo1?~t16JSf8mhqX2X{9-jSM$g-vjbApNv{C&>;hMat;9D@MV z^f|5UaWy5^DP5{auCG2-={o!Iota(97Gjq60fO6n2XimgCs$}3_$&8FHMu#Fg_rN0 zw5)=E@ChJ$%QmFdN9cMtuySpHZ2u zCrB{UpWl~|nS}B(w^Yy3#lbE&^%D)I&K&pkHE<6b(=|ij$gZ|_9I0ZQ&Tp&YW zgz7w$$b#K9Q1GE#BB$Zw$F((sQaa1h8gN(dW5XvN4ON~*M3sL_29F#EXsepI7WFS3 z5jl~aGbP*(UwE*cv1WQMGz-H{_!kC%@497AHnY4~8Sx27c=}qE`)A%bRI8ETca=vL4sMI9p()JH}~_V~~O zj*kpzajj=sY$?5CvpXw7*m%bsu#ZKY42(YS>)0#n%GL;FLBgo zmhd!9T2_*7SS*VFSk_UJth2vVa67dp4Lc|Q0Xf4Rq%5P?a~|5z^-`x#9~IJrml&9z zi((w8ogH#o51x~$RLsHhI-9kW)h}w(7j8^xm|~`F44xN*d?n@xUlYQ+J}Daf{8X#( zWuA>7I`%MePGLxzmVNPnIRFx8yK!HrtgJFT%IgBOgqT|#8L2W=0ePVJ^T^HBf=26e zqqa0AIgd>(^IkN|-KzGR`T|iU+)w(PX0ck!xk}uASBhb%=^Kn$5nOn+egPl(&ycD`)-^mRf zcD`0+8BpnHo;bb4{I^X;qk;_ z99|rILk%tIK0MsX^tC>wghU*wh7MgzULlt$G^d6`fzyTH?X91gq&cTfU545G7|-G7 znwlKW$?ixO3Dy2~VDSvwu9UlsR{(Q036czoph7KK5$3Hs6)2lm!)QBm49upJ96V9X(V@<(8q6|fT2wEC z_*~ z&=~Fa(NdP`VGX)SnNX|xoe4u@xYIWso}m4;CZUZ_?3jVhg24R1TsaEV9y&ja+`Lis zhGPC3|0L^y<+G3frr?PN&>1?*2KQoUpS$6UFox*13WuM<5k{CBjU}oG`bvj}6t9%2 za^7jJA_XGmGW&7GgT4OO{)Yzi@Rr3}H3Qay;E4gntuCCk`$hzZ!IWHy(hbumJ{t%I z9Gw_X=e@#&&E>(Z8Jgv7Zg;}|nH%C0uQOJN+z9X$g#5D&(CD~Yr?Jh_j zBkGD)GKv($zft{95nxOeoYg4slh!#{_hGE13<4pF(rIhk8+bGt4i|!LxpK@5dGyHc z->J`w_0eRhyVq4Z(wGgV=>>h->2!AU`WLJp|GwAZDBUBqPhPPa7c>ZHPRMFZqvWb` zbInokGBhc)0$gW*M50U4G^9g6ssY0o6z9B8%9ykGbldhr-+WTk zm;36(p08G32Q_BKcxE#3(~ylREJbFjVgeTcQdw8k1(5tLExGM8pe~*qrlw{U;(ggN zJJ5r0-(`$@7xyEdEo*in$=5rG9$BQI8`N;(GCP~~x?xfMb zTSWYja*8b-6Te4?Us}S)VRYHAmFzPzy6Yd$$%D3thuvzIIO{aD+n+s@L#$Kk$F^Gm z90ojH9rK8Xb%vxnV!nm=#Rg1B^v1ygp?_G(U0d8fyQ+oR#ghJEIPakllNtORwL`-jI0VxHE8~Gd9 z%;1EUmL!D>hWC|on`D{QWue?yROa7`L2+D|VHi&$@u%7o1FAQqJlr$KPahW^h?VS4 zi@?3G^61l(d1tl?-ejqh^A1J^{OK?25{41k=k9e0RTgl5#%m!rE{3^pCJop3u{}#b zL11#z67MK_{LUQPZdG&Mz^}a&g$*QVMb=8UA8l**uXA|30bUBI$NEK^rjhIc z?k(C|2=LeR?{c*#I*og%gqYl|S*s%lGA42J-{Jak^WCM)%svm_Gv&Se4}tx4Oh@>( z$O!tm6G&PA!vRs*@h@u@oBuc(gX&2?*%tV`Edp<~K6!Mfk_Yyv8M3H&eLH%e- zmXYi*wC7*mB@dP9=tvJjyM{JQn0usp3A<#R)==80~bJ8SVv5$Y&RsebsqmHurf z+M4_pJB;iZk}-8#zvQv{cKE-lIQeb}IeAd!;D=u@6?EC7Eo{nKXC2oa_YBT{-EuZv z^Fn^sMv*)gu5`XLdwnq=C$EY;I5GHox*p@-0T#WOc$Q1F`xm{wJjTE4NZw_sbiRUT zT96BYt2_-$T`?wZ@xJ)V1!Xd2;V_kLI&o+xo?G^K$8$s|QiUg9Q+Mx!^*5Qgr+r0Z$WQ=U)Ygs+2U^Nf`ED_~ol8evHeMYmO)d94 zo+>~B6S}299+@nf!uV#e;a|7TY_Kzp6oP^6G0|fT)mI6)F57Rk;pSxP6qPSn|6}`l+4tfJ4&={-$d%mQL6zu^SXI9pIDgFpm4z6+s}2FdGO~TTM1*_ zP*L%-dx;}K>ybt>kI#0(Qniw&_<5o((T$v?q=Ex3*CsG1G1pasYGJG-Ycu2fYhil7 zM`uSe>X)_|#Sj?x3f;qZ37YxT-Qa}g$k}ix;=1FB0DXD>hsdljX;Qh|$k2WIwt?)~ z2R?$6Tt~xSn)BR%m@Gbw-frtE^~gFdF(w$TYiUJ#t32lSVU7JBo{n#LJBcpQ!CIc}tYFzK+xb{maBfEHw;0`g_9jda$=DW1_4hA+GZxkk zut`2um~6jS)vpN5;>P4|`d>+?$!Oz;`hjOjKHe#J4H0hvuEk&lMN1w948atk*=@{l z1;M|$(jxrKA*tu6sJ1RoA5AO*u2R?Hd>iz7Ct(l<6IRx|%H8!dS_S#71lWn-Y?d5} z!5chWKrVfj0EeYD?yh8Z_Q!t+SEW2)3KW;NzAj2)I5HQfh$Z|7{vC(|LPw z=PzM;qf%x?$=f`)s7sAJ-u4@aEv%Bgcb>pS#Lb5JHF3;6%FG#CY8MbGF#KQ1?40zT zDsPsjPMjT6e$kTr4eUkhP8YZ}NLAy$e%;YnW^1}XuxeZh?_0i3Tq?#})*Ze0>|0{&{gYfWFVCnG^g! z{G#`bpQm1r=*#GvmEFZ`_geSN7hw>}EtKXe3r|FBGy-Jqs--RacjE{F75N=4?Yze) zN+qS?&@F$Vw#D|S{L>~bWNi0(;cT;v(&?G{^;rlW-c8;3W3BHe7jQIR=dD4g7vE}t|Rbu`& z1C9sUb-kuL&OBibc6ZwG*d}CUC!(1aZQ~}hLUinHGfeBI+JN|Di(hzq`FZc(^fOTi zBFk;>4xBs{ELyqOWB~*NO?WYXlogq*OfG@P$@Ny4d}&dFe5DhS>bHxw__({kMzyn# z@KRcr&|?&T8?G4{yRZKAdwv?7ss(O;X&=q}h4$yZm(X#Hamh(Vx?hMKz<^fEp_ocw zP;O@t2(C;ANjZ9+X~GdA6w~5dn2zMr40Vlc0(RfLoY)NlaL4WS*==2Z`ndTu8PJjx z;*bUib|m+FaHeMS9qdnMHJ@M6z~xlfmnUZmJB+w3FHO~@p+al%U>Q`^))n1xbjBXw z+$}SUz4zr8a<}rQEiFi?;ZP7ZT(@{rSZpx^4T$E}oI*F>@R*kruRX(74e>;goOwtj z1i}-1DO8)2;X+30&6aYG4$|MfF)2c+twoee879STlx&oL=3kgOxXD6x^VD{s(2pVBg% zMJsBe+Eh69jX_$VEj^vT)jtlKLusL-yxc<`OZEv%WPg6OLH1%y(G$r;f1K{p1q&HPo^P<;Ylz-bmg%gtR zdJB9b0Q+!VFJXZ5u+LE*lDx~nr5O&jg{ztA2iJ$X`PtagS!=3_Q-;$UkKlVIH@82s zH!v4+_WFgo!A-rb1t^d%D@;hIfp;qQ77sni?#%^j9!O6VB)GA<4`kFc7}p5}-`uM- z{ptB;;FyD<{-LfzE55o{h%}++{`UcoUbJJ%qwi-6G4^0Fq}JW?oJ1ljUiaL>Fl?J0 zM||)kbEv(1hR-gr`3Cqi2@}wEukYO~Xd8~Pa?DCw=!kOe_cQv4{!jeV_%8e-cGShe zf)D9esGl77$VV>cB|L9qQi)~YSvk7fRirpFqKIxDPAiFjwS>q=iBef7SK_ zfG0Ggw5+#p>d zKYk7?w+br}Zd8eY8K;b_r~fo+0S;xa^eMk4C(nVGa&ie_9Q}#Qi%LfsE@ZmySKEFf zUl$GVlNO4>WzDiQ&eV1#ZuuJtg_O1>Q+64GOA&nuOg^>_Hq+x1>+k0+(cY{~Bxd-F`J3 zNAD8^wXAejTx6^wyYasrGZ5vo1Unim8?Dzy3el{TA%bEDw%=AcWJ$yF6EVW|D$7_o zv<2kl<5URVNzx4rcXIbvnxPuMaAVwYj>Upskqi|TP{0hnl&`4WL_dXtg6>wG`lAgs zKhOlRON6}RdH(Q!Pvnzf zT4aUhZM-J;Ypaq-mt`*q=;|~2|G4Ci^U=GvL2J?}b~XV(CC|R{Rv-UWf->Kbp#r=L zqy9rs{A1|-sW9oN`{jq!U2BU9W@MGm%A%l{Qdzrn7_XNLl$<6d(NEgYH1%hpr+S{{ zPuOBhB_6CcDm}WrIiq6DA8&VC%b`2;`r6g70$167bz$}w#k-U&^CPnf5tKdqVr%}E zY1ev0?_r$a6*mg}x>FX%-?->A9A6cycPtZ`Q%ms43crd^xAKQCAmO)HBS^p5C|!9K zX0B}h6!LcY*PMa{1RlGHkMFTX2jLj1e~sWVA_O<}&}{0x9?8Ao`|l`!?7JV2X8BTD-M28O!xrvNsv5*cUmW#Hncjc5UvB<8 zl@^#`OVNjD)k-fan3Dp>L~J21FA4!_)KBqUoe_r% zjmh7jI`N1NEW`MLRn1^1sqAES{48nvNogkIrVDNXLgir`hBI9YrPE(6*I`ehqEth-{uIVQ$ zN}g7a1AP3x`nPaPL5t{po^mh6lut{}$lr^24}cwR?B=*~!V`U#zQ5ebkARrQr4S`# z>{I2cJ)n|yeWHz1&>tk$WEl6vyq1Q%$1qO@10=F~X}_yplhc&u(}vqos|ykMn4V#M zw&7>L<({Jb_`oZkvbqw9?&tAkX|?^X*_cMvxvOSHE5Ncq_1B$GCZC_Zygvqtq= z2WAf*lT)6hBIyXC^T$!*D7i)M825GNj1x_EZ3Xkl8NpPgR3e%g73DoPzU4`nWC|#} z0&(PCE>o7q*R=_52;YoK%P?=V={`N2o>7ygjBXQ3DxheLT`{FJ*2nk{A*d2>+(N1J zqmuG8Iea%;&=Nz4?X7!vZ0s6k^tr&E-tuqQDm9vIA=t(uMAmQriMa+vqBe;%;20GX zqsRkCb*i~73!$p_FLB#g^@aCj2{dNQTS@|O+aRy(9d}&opYI%a?ABvf#mpnfwW*ZE zhxUx;x8|&O?R1SqEzHUypha>%55e&2ti4jat*>~YR;?u|MaHT2rd6Gub2y~JG>=$k zD!=1s+crCiAky3DlF-N5%`M4qw&JvEVS1kZR$2I-Hu|&>-|13)E-ajI)fr2#Y>R-s z!zM3iwdL2Xymq~HveNb+R_K^Fw)Qke)@pZJn z)`DLugJ->#d(+}}zwczwu^>_&!JwekerK$6*0Ns(&Lo@}#Unl)zfX!HVtLQhusv~l zsq1ggdF}o-DEfFL9p{e+?>waK5*_RxWNuvPKQsyH|A#>D?|-KRJ>R?^BHZ!C937d{ z=t@+y=i;5;hKo|Q96m@SBg_m+NXyG-DX#U1wyE}FP`PWU_I+rv`YNLWMu9`Gsd?-A zjssVhLax4o$E_U@OpD)?mCjq1xk1nV8krHYXV4%_=OrBkJYutF=s$lX;|7- z^16zc3n}+&sbs}yHir`Qb>511q(=~S}`6F3f{zuk-$B z6KElE5hts_N$=O_(GC6*H!wf`zK^?+l#47$)xo>ODsWw*6lGV7YfWNiSV`u?u-wPo zc`>utsfKKR%IeX`Bo*THV5#XpOT($VLg99Fr(>883}xnf!sDa;-jL0bnbyS9iix)7 zmNSj-C4sYlj1KsMt=arV&C)KkR-t!}LWL=(@V!7|SR2D)epue=9ABHgecdoRs{^CD zaMN6pl6p5ry8B7j87Rd|zO z{q?8||C&!SlWhkLpTT@$Q5DuNWPQfH6s<V+_`^6Uoy^hGGR)Ss9<0INE7MQ)HSXf#`eFcNs-0ZRYL7ZO*45Sbo;S4rb;c~6 zSCiLfe^qn-QWn+r$Nw);%0Ie1O7F3Y*RdzAw+(pQT^BWCz)31Rg&ZTy;ENv-$FikZTC&pO-UY?r~NOK*kr`qd1{<*Fs+O<8d6ILR!XPXz$Z!WD4rxpwqm1NT+ zCX>SvT~&irm@B;JnzKr1VPh73TU`?JjF>1?9la+~bq}i_n)e!1Q&Q)1RXNRUoqa+Z zP7Rn9&1TG)kQLz3(D_#!n^)Tw0%%9AMiW$Kah`{CBXKEBgC*Wat#n(SU%MaO6GKi) z6V*QwMl+W;Ll^>yq5)2!qeS**ZgcM!>=iraFgFRQO9S}KraYb@M;@wBZ>!dpo6|N0 zXe&kCTo02X&(tF<0)ygBwb@?jZW)y!N;pO}EH)osstg&s=4U$A z{_i6A|GU7Si9Ts7`OVK_ulLoLJ+Nl`5=@Gq9Z>fA?y}}^`yN&tC>jgcJO^g-*TS7AH-_P*+e z+vJP*XdbwiXu_QOF1f{GP^A7M8-=T=@2|zD0q#CN+9}g)wY)25Y>K@Ja&g$ws zDbF6~He-?}s@LsFr7fpqlLIGx`j2sSNUA4h_AJK$ zCshGEnz4v2X!-SwM6L6OUHlCzo^%&OlQOI60?vdxhE{Y5i=k~q_&K_UuFx{0F!N&$ zgg*=5k*?$7Su%$rCB#H^AK#3zc^CfCtc^euH|94$g^2`NM+uTu7}$enV3$sE@8&s` z*a_ZP@Go}uV^ZbfYc)S>{~eYS8=;^?xmgI-<770fs9lq$7GlX2Bynh}EGl=vb+Bix z@J?1NELal6FJvr{6msAcZc8i3ZiVpzaGvt;Y#tu9kbCsV!H&-4`i=| zAva1X`E6mD~^d@ci;$cI+v@oX>37BWuV%WMe(Rna86=Uw)SUm|%6~H=ni=!i}T5 zqmQ<%*)&Tqo7y(r;!!>=&%M6xf$hWGB~<0+GjVgSkE1%;RRfIAg{V+^@+@ylCMSBU z<|3m3Xs6UpusPK-4xz(O0-iN=sZtR#t?swq=??m?OW5tp$`5P#c=^xoC{*Q6RNEw# zN5#xFnzzBpB?Ly(@o(6R;ft( zJ#tVUh1j_(om4(end>cfXn(Ab`MZCM?H-2D!*k2ttTwP^HOh3tkL!F9J>V~G-O+sv zEgvqtt?4r9WAg(rVcN@c^#fDKrN&8hTy+^`{%*~EzfnXdFJOv9c<)}Tvw;ie`^(e` zWLopb3a*5$hEVxx?}zE1D}-T(#^5793rFyrdnhWog`EjUpi3QVLK(RnIkcaX)#fCS zx%@TVocjTSx};G|puIjR2k7UeI%BoX05DHD`LtSZF{5G9&FBZL#N=4h|U4>W?lJ9&il~M;UWwJP9OzJcvqS9DXPVniY zq{QxyjefwAQ?0s)RBF>*oyfedj#rTMrpP>3K|BA4cFFmd{rtXli9Pf1sKAu%bC++z zKCJg}3gvJZWkt<|nup|lsCo(f>}g|cf}*hyo5Dx1Fc7lh{Z(ISZP(&#cNj`G9m~sX zJRPf?Na(>Nz%AgZZ;b-~$;f)CR$KFaL@O(`<}hP*Dk}5WDgO`Qlaz&d(e7TC>1GK= zRud&i>9#gJuc6=ZZywVn;U7~X$o+7ZhsQ-9o+h5|jgm9Qg;H!gCjuFLhCPX~jq?AR zClGu7Ns!q6_oy&RTT22@k6ZMrzW}nm2MGwHaUGA}kTbF954_&0l2Jz^z%vd-P2p8o zb{)3_69#s-{2Ju~;!H@u;#X5RWTA$3pxnbnt>ktT>QBn`d8Z9_c z)#TynXJ;N=P!&NzlBlzFc%L>#Xe-klUg7Pl3L2C5E1yxuj^Po6^GEhJ``9`D!0!B! zcC%@}v$+4-{kOSq`f*K8c`mP!0oG;Q1}Ono@EL|<+`DRw$5{ORDh`uoLSg37_&17RNcN${`t)zDE1qvZg{OiH|73;OmPT6;&4?`P@(@dH**sjz ztG!AooU17dMi+UtiPr^fD+VZLg=RbYL!8z%Lvf`$DeK~(8?8;i{XHqKxaNwgUsz?H zg&r;k`A6INcdszbjY@KFuDQtsNmQg(JSLhxT&3Ok z%3inUB$#>tbS+EOrnu2|O2CHY^>1;J0_n5OpGWF;eZ=4gVCI$Cd5JwHlVRMDcb8D- z1|%lu$+cWwPU))@vOIq8&G24A`;us!>$xj`@68>Vi3H!Td6msg$mk}GNpE5~Tta2* zhiti>Y3OW?f`2UpH5HP=yyQXPms5Vv*ho+6>&s` z?pC`ZGCMl9U6G;6X@Z&4O0u8G>Tr}u+-eJ1jX~KU`T&M?-|9g*?bp~qKBHSom`>CU z78v)AB1Clh{SFwwxFM&T7Az#J#8vYUljc;7d61j7c_+6Zl8XUd3B{m<@Dp8)>`@69r+>hRI@Md3;p z=%3uKk=Y4FtYlN3Owp~hAjsOpe+bSBRsDx+yn-vO0DMYiYvT=#o}d^jzXwjJvpNJR z_sC|vC|23dIvzL+E1a;%mr z1iv*YMS>~OoC@G@xeQX1)vqw>;$~AMSBxqPerbijlaHlJpx(^XdL9Qf#VakYDgtQ- zc`NoJ<1Y5`u+#sCv$qUt>y5fcY0+XW#R*c1yStTAq`14g1$Ql8+}(;3T!XuNv0%Zi z1gE(5=J&q$|MA|rb7!6p$vHEbGxI#zXYak%UW<>foo_T&&Dp*D!kt-KSuO5Ip*|P- z+RxeV;e){uKGE10`7uT`pU{AB_o|Ft!xri{6B}7ungVMq9Fe6;+@F-Z29->w5|po6FpD?JV=TYdYij+VQSNG0hs)88BYZzvEhK>7|&H5ln&Z6BW&cyxG@ZoA%?+BqRpC~`aLyn;mNoH?>xb|?z z(q4`CEob6Rp>yPh96?=HJT%`9@!|zi$wc@&HZqa)&-HKe1lbl-E3$8(Zh=)|ri)6i z#G7Z1`yH|wr+o7!^{T3p_ys90e-M8&=gIQ@z$6_yVvI(fA(aF_Q23ok4!vhR{N zD%5lqW|4k0>E{|{cur#mIJjJun|aJPL8+L2b-n28r#!M`E{ohx`_9wv#sB8Y5=>?& z3l*dv%7no8#KbK`T6kl9!bXjvB=s|G0|RjSB$S`|?ja5bVE!7L^tUB}E9OTpimlup|0sBj^b(-{wkt zebrt*BIjNu)%>E_Pp((g5(W&i24J_ zr1y^ReLZn;O#R^cGFFfty4ULRbm8h}uQazGz;t zY3yUz9*WpdMCEBa5VsH|w{VI~MuF5~+K~^ZD_Ku_&gqYoBrm$=b_^}JKAq*D)fSh5 zSK4xN)p4AB5o6^&E1fA)n<$w7RQW|V%jTR*N%i4Vf`ha zB4`b_f+J9;BvlemW%l74aSsbVmilDuMK&*}+L8N~kwg@^k3~`=|L0YR4kYuQtf?mc zJ)0e*G^)DkAd58bK0A$-spC^!MD)X*N7Ph+pIJ!j=ky7?YR|XcEQSjG&!o%Zz%^#+ zq*g@+T?o1k*mUi$SQ|D*|5Rc$*OoDkpf?7llW`@ZF}vS# z8nwXJ%N4Bfm-~_Ux#XOq0$-i>nXp~i4NS?Lx3zrRY`>dUL2F!^ok1WO~JCY$?| z725-VOs2)lHxe(>zoe@6ZHZ%w5cpyYzr{9ujPPM~UcPS!w2$d7VMXYG#oTR2*NF%3 za#Pw*4wGNnG555RlRg%mX*kppZS|RMmMrIzxsr~z71)6$UL%y%)aI4;&XSou))(Rt zAkqXXr&LK|dOeXptlf1f!*cQ~+VYR|XRd3k9<{h$m@;2ekopJu^d02c7Lf;@^nhS! z^xtaFK;$$XR=_jLJ;^4che)k=gX6ZR6fB;OZ{<&>lKgrL+JcKojDMvW#(a%>gbz33qX9mOV+_%s1m`mT#6Py zYd2-6XVqAXDzd_3@@@S8B+WY?1^IX)ywPVlW_Y25tKhiUzKE}1>n5u}dt&>VX?%6J z&2W>=m6Y#gDQ_SX&Tq%PbFf1>46V&$JX$72l>o(5ApN(4)#R1jzk#W1lk;ywswsoF+3t zB{Y7GBkGLuX{CNh^ zJ}vKo*XZm|eJ>?7sCrlR66(bfH-yr6aRfy#LUx1pOAM_I`&RJ_OuSFfuljFWYDP0C z{eC#Uv65p8cFU&QvZ?2NK!qQDL+po~b6oeNB44rX@Ox*4T5boUfw<@!_}Hwix1cC* z;^44j*ihM2Wophmt-iXvP!asVcf?~>_Z}M#@l5i1!GR_UC2}Q-Kr%wu4BlqVZqegm zRN%$P%hYonBT9ob%1%7xfq!s)tjml$m=OA%Gx1h)oRcefcXjZh{7Z2~55|{ko@JDp`rb`vv6PyHM zPCA=rYt>dn%F8UeFa>Ih9ZEk&{3}ryOr?7Jw@uqV251vy%=Y7wqxq|}z#|IM@(VM~ zaPR1>W3zR*q|%qqiE*L0F)^{JDs~3AHjU1ns+_Z8*1zptTJWIc%jR~wJERWA~} z`L?J$cPUO{Y#?`@IzHukVOe3a(=M`$;`)3yx^!>vr)}{$8GG4hZR8M{_=DrF2XEWbyM&11Q=3y)e(_;TqWW2n}$k-Nve+RA&i! z&$kNtHosjIxt#yOQEU}tS(-jpVPoVWhIIu~UQ~7pIbtN5qycx3ov1E3#i~?QC$>84 zE=v=j{;4NSUa>GaH1X-k{fPz9Byq;Z*@~*As%g%V+3V@ztqkXvwwG`M(}!iWD(V;k zI^p#K_Q}k-MCfIsIpxasMrmzXZ5eL+mcZ%I*lpOSZJ!L7p%QhS?j|h7)Q&RKh2SQ-B+t7yDxFkQ4rBTC1R_+CVw zL3FY|b4>H(hY4eU(CmV+K%r2aViseTrVNq*hRMlJKV8#@mkD-ZZBI5p}WDMY6I&~Izi z-on);VhUeir2CEBfRvsvUA_aUefAQTs~Cr+tzrvx=G>Z_lx)@jI=!xszQ0RBLNbTW zOVzrfX2X<+@De{uLaJ_5ZuO+j zlNf!{#&)*z+0-x3K6hD7e;~5hTpF+)xwR<6-h@~v0m4TVd)m;3j4;-&IX z;TnIQI+g+1&V(T5Q((QWf~ug7`LdoPUA56Cp*{8w0f4LDD8fh4ETOz<&=yx%-gGE*rp$ez?pAGWvj!IRY7c_Q0S)yuI6|zX+^7)vIrIQq;dT5(?K7T z;S;7dN+7;87uRYhZr%lGm0cvBbp*n#kVo7XYCGNZJnReyI__Ft3fw7akR2RJFq2I) zPu=z~pVW+q`)?1roi7yAJPEtTD*++i?N91WHx7=%C!>J0vA+=wiW*~G5vsvSDcr-; zNoy(kREh@&m$5C2YK!9IcJF)Rw{m@QV->EZ$Bp`VVl%TFH9`qmNC$(WU2xTxnlBxR zn)RdvI;hA|6CttcaPE9SH##~RMbtFWgeO8a9g2O*^#b9EMI@Qp(=8MoE^Ozj59 zwNadE3qiKC`b(F*jP<=d2B4e^f(n#!E{1(|30 z>2V1?{W0Sf+B1CyDh%Bvkx)OlO6ps=(Gym>Z!bjyc{<}$-!->w4i5a`z1cj!T3et3 z-sDL5@G)L9mK%Jt7`<(vP!Ho{X$$tS*Sf9*4vmb8pvUk35JD?5*;I3vSLaBtxTJ14 zExD$|L$U$&AF~1Ok!hZRdH;1Ys7uqm_VNnzktOVJpS?moafcQzUE16PZbdg;o^@lm zU$bjsC3T2K!4gsNH<(X&36mUBaKdYm*R^!US^Xd};5Oj}^`K3iP$Vf3NlzNXrnX1j zJa_0^FsbSd^`Fi{I6RtQb1jVz?|tl4Kb}6#Vo%~^d>dv_V6_+N(w7K<8CY-5esmMj zSHi)VpkQXAos!)pjhzkPky#;w%-dC}%<~db=nNmtP3}C9x{BAwIM7Kdy*pxGUq8I6 z)RM`oHorq2JQnYF5@2S$?V_?9 zI*VsZQF&z{f89(WL%@FsL%gCN6ALLHzpSYAgkTHU?BZ;*HlKE>EG~)E^lu$zAF#A( zXvyf+1#r&aq`#9?*A^}m#{9HdEfC*JuYcTXc&8^0;CNvcsAwO<`1byN{o_RF4v5(? zr3H~C-{@T9ZN+kNz!&-DKPeIVaG-#ss)jsw31Fq1$i%^^j6WW%I23NBky{^2Y$b-!MJW< zRV6iurEx7RZKLA3W+QO`D{k9eM}wCvfZXL=j^&`c{kmd|YO7^LK#}^4*WOMiy5OtNwFY80} zD?YW+JvgabH!EG`U|El=#%OJ2$fZqTqD!BGPXqGbhqwHtThr(uZYQq=2FM`$Mplhwp3klZ|e9w;e^-x3P|rce05~J`LqcTk@y4gy@H7 z?5-$wF#CL3n5@`Uz~%ooYJ@#M?_1qgI%vUh&1ki?EU*Wxhd^H|^33EI*~}k$*5G(x zE_24joW|7t;%VT2thN)Q(3JQ>NGA%R-lWN-TWzCz?{X-#p@Tf_bSA8yqzBF90ms?g zB<9IsRsj|oMys^=+s_((U-n&nYZk|;pR^oxCpWt|!(wrU*MVKu4Zac0hI@I?#k;C8 z(Z$4p^}#pPLG3Vtu0sADVs7_K7yWIh7Ja&B3dhG|k4pU~0v%6Q9agdu9G5pR#*GSg zwdNQx#g)QC{Z^RL|HL<^N%jfYC=Xh0Vj4y1Q0@r9IUX^lL*lvup+X>902|@#hT3N< zo>(kW#o+4J48O0gM=Sf>PdV#;__>KNVUwl=kr!|s`N9h9lt+0U)ahop*%8%p9N!ap zJ?D4;kDExlm@&KzH8zbwt@LJMF(b(%xUhR_OzC_=BbPp5huC#RQeQ#qT&n4j?i z_b&%6e_l1HvNP@8y_*|%?mBo##h{`FE6R-!rfQCHdjaxLwRKSE(jQoa>P-c28CwGP zTA%Tiw(b#EoF2%x{TO9ow!jj3t9Qoo&s0j}QzJqc_;sa`Nh3eV=iT3cO5b+-ZUdVf zb=0f3ZT;f_Z8_P7u(V(gj;86zG>_+1c$n87*W+(qyPDFP!J?vOUo(fCx0`IEd#&LJ zM4K@3s(l+X^)tB>I?H$*H(p)QmjL`4fT+Xm%&=mrB;jK}uRU5XpHij^Yp#|zq%;RYR!*NgEH9h## zK`w?%w@vF7Bl+aV51r{Dr+UHA4BEsh)`MX8T_|qeN`{%Ez;XiysbquHW%=*gOz|fk ze9F=v>OH)0LdBozCURlj5NMm`?WN()MBXO8i*!5zAo|8A`o6~3Pg9c#&G$QO=pn$u zwzkc-dFPNtQ%++VBgyf=iOMu!>cEBMtY}P~JMccKUAO(65+$@RR%8m%7S1cf6`X;y zb}zy|jNh+Wy%65`1q|H_HlKDD5zOF6s$Kxez9lQ4)SI~08;j^GfcMi%3~%-Kr~hXK zxPY&Jd$n376>le1C=`2caEbZYV<&c4@os0Iv;wCq%gZapC1w&ux6759WL}9(Gv{W89A$w|2YS(|<~&7vdkd<%Qc@OUfc z(qa6OVqV+K+Ro?4U*dh|h^<+__3k&qD#KLo1uo6Oi`*xE5#AUFiBAQDb6=Np-1}KZ z?k71WZZgn&N}?Nt-rO?fR;?#}kY27QcaGDi6y zSa!QsM+)iLbjcS3#EVs`GUX|?rTG@y&jemADy>f%+O9WFC(hg) z_wHn}QB_jUE=IO|;79ru*#U6k{UIh~T#Tx)VsJygHo&-}-br%H8^G^uk)~U2_sJ$f z3d)A4$7neut$N$sJ8Hypda;w`jI#O;xq%qR{a&>c5ff)+m$mwBb)E~%viX7VJwiFm zW&>7ZSncpy5-d}^JQWIcH=$?~r)JNpuxg(gzeO*W>OXW*fFpvq80P#rBxg6&`eJ=5 z3xdz-+x>nTlHaD>oMjN~WR{F3^iQ_{ba2hFoWBA4h(z8Wb69N|vryYkN|?K48NB$y z>Ulcvp%@0+?rMDpA0W~{d6r=MG#J0$G}ViKajd~Rr!H8PfsPR`GiJ>a5Q9b-d78?8 z4MN;%7Ld+9BqxU?{po8P3_bhxtehJdRajmUZ@Zf04kM`;8It)^GzbCfJywpDMox!? zBy&9B>t#8$n$-V8VAr$Z7e4__o_IKj;cMEG@8)LgR@Wm8Q=}Ysg_X9^9#D zwJdfV_*m_VmD{NLUB&Re!gYXPYJ{-aDKn*QmLse#xz;vCU})JEjquF21dA16)X{9Y zGm9~PI0nm+8&byYiUr!?^KTb6@K{;b@cv8w!MHu4_5^JheSYy(YZTPW=Qb82|T{K9^OA`9Hgf zbm_g5Ve#XJ?!l*Rq951ULb`u^5YNMY2UgLJP}yJLT=UHwh2>Bjqj7p{`!Cek^VvAJ zuvol#`K20_WMs290#K0@yM46c^ls@0gltJ|_x$d;~?CEF`kB|ZNBap`9bH#oc zTbFvqrfW~*5cWr!S5@K={VLGC_*uXPf-dw59N04%gxc6={IOlkmbx`>F;ViF7Ag7`s^Q=my=@WuW~Q%>&^)QVOG%my=^gNGIShPl z8QNihpco~u;7VYgcP+V~BB=oW!NpSJGR zlQv1r1sZVMTnT#pG;TlFCLVYG&C)obn2zX~F-qdJvr+ZJ6r{SM(&&k(UmYGad~eTw7NFn6ab@L6TV0O0c9<8kKZ)MyrgBqb!Q zp(M_^8u>;5B^Ad@1v^_}QMRHsL110vueEG9BV-B7lZIufff!e~ejXDM^&@{^RMS9$ zo0meKZdyMnTXtX+r`q&NFYH}|U=4qc|5q-w4cZ86fr|*^W{}SFg#DC&Uxiv|{T( zLs>89)N$F9(bI{CyJ->|c>w<+7FJlOjd9sER3tAx5nkep_AINn-$Ns0Ugp>Tl_jF_ z^*F3zABpF(xvKkBwY}y#U=;Ku!DYU3PWdaoi!XSHsq6M8%e~#U>3~CoGgTb|@0pQE9rdji0jQO=X&=oMP&vm1TnZ zYMmj+;a|)mq|0H9!e5tsqe4O$+I7ox*2fvWu8n7!&NYGx4=tmaym%HlcUqIJ4|JR= z>)M*8BNFBzxo?WyhOW%InHiOk&Ter zOI4-=R{CFu`u@)Ko5qvX`G5HJk%!k?o*V`x7Qdxdk?%=OAIN`y5lfdc_05n^>rhAuw`%`N zy*T`8nNLlj!DM1GN=Q!oV1L;cFYnMipDnF{cV_4OVaY*H_PY)jn_W|>YP(caM09id zWc(;LkzS<(NLGA6>bJj8-+Mc{0nWbc?FpVa(J5+_?4-Sbm~29F$=;ygEO^~$ zYIX-WSk+6x-f<{6NAr+ze~>ixJXe#2Xt$<+z}1Hc;VR6=m3PAR`HR)Q@b2g0O#wIV zbVpxVc#VE_aVteVLGie+=6O!7!Jk5_O%lsohpO_9U1M(~c}fwS&d~tUC>G^?eoY-j>gj ziD(T|6?Sv~he64`m=#$&OPjVinD@~L!~XOvuf8-e?(tlGCcR{E5y@GYqklE^Q&lqA zxg!)5*>!nS4wr~4-6oc-5@52UyiR&6>z3-C&A`kG{XSWo?J!|mVoa5Ch|HY&mmAex zKuf(Bg>L+qPWDd7F1}W>DL>c50*|AWJFSINy|yy@L)S^h$%CuW4hZE~=*%FW8J_Q* zbN~?ES0wWywz`*_m#3hEES9i?yd7^g6q;^VVbYpCfE8L&P05AYXHCAf_j9Tc)$B*I zB6N32(hjLcs?v%YB9{BFpV-@>XU$}!jr{7ZEy-gWIY)>dtz*vPr?!<>E4<;HYXCjH zA{r#tEYmG$*y$?hV4G_+TM7_JDak&2icP3GgLe`azgSOrp_B!dcLO)dg_ku(kF_$~ zJCW;$2<4S1Fn2ysVKXMCD6O=c9(S~Fc6~cyG)>BT?hq+sv%;&tP_GImy6*VV(*zR3 z*!IZg!?0Q^blkFfL+{~ZiECV*KhJ-qi@=yyXwRk66^l(#(#2`5uzczKV12yXSoO8Z z-cGc;=|KX1K~|+QiN7i6)B8cugaP7?a<) zj~ZM2<(EwCHZel(IUAa;_)Ut{RZx|iT@LcxrqGT<*qA6mM%FDI=uH+d?yCiJMQPaBE_m(g}<;c zitKXu5*izW54hH!yV)QwLvoLst$vxlQ(4gQt(i|Xj>%@CYKfy3&uTC@vbJqQIWsq| z_>mBZq=sg*dai%&Nr)^Ix@;r^5&O`5mUo5{RyPT-0fbNYx2gpz(en9t3H2li6TWjw z7i0_+e+Oqk<~2hyD38o%QBR}qmP=1_4n$X?4cyAsnMy>r4H)jwkCa-qWc}yrF6?S4 z7ZM9sfjO6*_;>@%z#iP}KKGcbVR@1Rn6CP!!~ z%_CXVOr%h~GFH#VFta!#R&xB`4VJIjp=`!11$>H*sHSNWkJNtZHO^i7p{@H}QkE%# zLRVp_)E7cHCMfb9foH!wQQ?eXX_ps0H>lNRV(Ir85WlV&74u{2x4KQl9F{HqhWr=G zH%gRO4XB``={sE(T-vOAR8`J_$zGDeEWIt8X}HU^q6g9N3ykk%eINMgubL!~BX-ND zfHy9fkC!RB6;3I?1ik^D2__%4$`A@$+ZW_1#>Tgs9i4~8Hjgevk5wLpWM5~&he}8D z3@;1DM4EBZH38Y%hH?}3w=4wcb8TnmE^e;e-KY+Lw2f)DC9IZGem-PjE6Of$EQSP` zxp(7Zzn!ALr(i2Y3`q*7_b$YvaIcczG310(Qn#3y?5rYRS8HiFbt}hi z^@IQ$5DgyEC3X3425ok?AgZ`v9n-Aok;a*oomQzhiHTq?yBB;BEz~J0hKwt62!Dt# zMyhbV5Wdd1;gCXL89J!tna)2t)H1i9f8|GO?rJTI-DO?-Bw*~TAqmKWhf9f8_!(b> z>A*TkGd2M#wFi@}05Q;%I1^nM6j!tw@Cwowu?mWxZz*dubqQaL% z+_Ky2Uc5|Dvb25Is?#msXT1!ZAsDToG!jnSAu3FaZH3oW4JD-SRN-Pr7-vf!nV>(E zx!sy1-f%BOQQX{XUv{TxTaAF(e+ZG^ICcczAD*ddiPQVxY`nb42H;h-*%^$UzoHvI znYm_%bi>KTYP-L8SRPxR;n-c-1NU$qo7P(k7T3#&y(KcoAuI~iCXz_WvjB9G0Nmo? zk(>=;JM0b+17&JWd3?^qpRy>1Wg~>nkaCu?)VHis3N$2O*?C3eiS}etSn0|`^jppK zc)P;p%aGKxK@ChFYv4}CBPbhS&g*Dfo)qVGm?gx`SCtxeW@j5AC_3FNB9A~!Y-iN; zqq7kkl0iBetFkaxU)33wjF@LSo>v(2s9Q;3(LOE7~Hh@kKM!%H1hy>1;@YJ z=0L_!<<=qDZxGbv{64R08%4pj7R=td<=|tZ={@pE#kGs1D*r=JO%VnC7_{F4Hzh?9 z_qeAGF1AoOw?wTij#EWfD_S!GsOyIhO(sb@7N)neesBRq6+NbaJBc;X`UY~QjM;Iw zzt@JOY%WB--&0c*L9)dVzpZ9PH_1%6S!fD2z4MSCW{g^yN?cQAC8* zoBT-s`~lZ=)HN(A52!~Y!e!}?GpQujoay7X82G;i z#o;9m1kDUY08-y$%w5NJa{5Xc`IMP8_=Q;iLvXxk!8Jf}8Ogw~T=i@^8h_Veujt>% zpB8@yUs1EKm%3sbOwvyigs5&I&Vtn$L6gU<=={>p~@KP;Loc9is5Tfr2 zhB9{gn;PanBH=pa;&V?DNnN}h+$BD)*S6w4(g-W47c5d zOOM*!pneFq z(*NYbp6*`%GYrbitpB6tR5Z8;aKG|NW1}0t8~C{*jdY2KXL;g~CLS|ZJ&IkT{AUYc z0h80xO^-wqr71gak*j=nCDUC6@}2C^GEUROb5TR0kGm@IhNS*%wET!)GFWSO6+njG zlN?xHq4kqkNm|aH)n;k{1hfjDbM)n;Q6fZ|8$RsnTxZ`rjT3u_4<}zqH0^iEzSn|syb*z6L1;Tf+Rz`*bxr34 zis2slv!2>2>H@_Q@0mW{mv5I>UFi;U(HVCD+hKWGf`5*UeY4mbW>k;M3>_n zLZ1k+W#*mtT(jd%D}@9D2nFt>ZJpls`m&=b^2^1=?jp) zE*aiJQEb7C;9Wc2yCDC&SEg_Up39T$gmYELrqdOxRARvpEn>4!8finMK10RipWg;r7T zkrG@2p0gzsTRP=%Q(vj2H#Z#`uA7#1>>p*HDZc#KDxphxAO$!-r6+&ap2a9WTAA2? z!ow#e>yHJcJ#u~Cj4Hx+X%LLu#qM_(%lQ0a1y%2xmqt_dDx5t8Lp6H_X4ZotHNVB=s5t~`9!tzSG^RT> zcifsOmw|0=T)5E4P=dxb$whZAU_!*1+MzG!rq%zF%AUi|`PjtRlBQf-H4{t9%Bx*; zm>cyvr~IH-yECjDO(qtP_Z`CPN%-2R%r`9A{Sq~Q|Q7e|E9OaJWTC5GxC@2g%9|P4GZEAyFd>&RR zWWE06vu8t)@tMy_GcpYQqrUU{ejZs}>LJ&p>+)dQYaA0SND%bn9luppyq{!EaV2%z znKf_N83QsJdQQt~Swe|sCGv0ml-lNV6Z@av&)Y>N(-dVxCihFEtfOe?_io9{1s#7%4 zojO4_FRTIVB}t#Q!(Z!b`BUgdN~J0MwGypiKxzWFGR_%a+-5dxXfn z-9JA~{#Lj^-7AdJj`mRKA7Nkqk@x3v{1C%XqD@_`pVTZrk96;mw{8qG{CwEaJ$^3H zcZ+olT}M|B*E_>sgUW^@x1b|>-KC-^vSvV)`8aoip(5fT`zf)Y_psj}>P%prS8jr( z$qveL%cwf;pQ3EXHwTC~KfRg_-LiT0_u#zH;E_JTuWo zEYp6~&UA7`?H<+;o_inSn8|33#D3FAXrnz=lnpY@{MEJ zfbVT}_MH$rNFJ+S-+mu2RoN7KVl`h3mCJJ54VELCj&+tbHcY$So|V)1yFQ}|d>z|l zSO-%mw-ccyXn*;mv2~rHyWm-lFO=?BOCDconwrzfg{J6FY$^dt%P z7lp+(HFP3E%U9%~09EmsHmTKNL1`hM$V*&qtDM=k@66oLG@i z$zzLwTF%y22Bxker7nf2>e&WzJMWeAC&G8V5AT+nGZdfKP4QB%GzAy7`x0{=s6^DV zV@|VKN5!t4*7?FRbx&&uI)m2M-1~3|(?$(wKXdM5XoFy-6^V0Vm|@wC6L5L@YZv|* zZbh@tU>&xc@7hNzTynYmqdC{=S5A5` zYNQyTD@%N%PgWXn&H!cKtAQ5MJg4VaT_o7!X_rsY?wIkNoe%BMPp+L--PjqnP!*YN z|IMjIqhr)%&=+15y)vhWl&(e6PeiDHpoT9Mf>GWuWCvD_wXw@?yAbPTd2%&e%%%~otjcVu2Ktx9Rl@lV*n^0?wFsNc+O)49j|alSa{@I&wOqbMVA(+ zw$t7H@z=mEsnp#qnKw5h6d0S{GUQZ@?Yc2qFogRWW#L@mL83)4Jm={81gGon=Vkrs zC?4=*#E@$tLM?tYs1UTx*@=TVHo)K~En~Zz2fME#Bb090ZveY+1@@PemliT1Eq~qSy_EE4|D_7egC7;!8pUu2()eCGlbAyeBjwuvX%>xPuStkWSfP`AS3p ztPSXPk!%L}MMAq(fzBoKk}A%=jhL1e_FJpcbh8Q0qNRmTymq0M;DuGgK_TUM)Iqt@ z86gYz!ZaI!`le(H7Q4P+{@7f<+3K>+M3i)GyClD=$XR2LkMGZS$_wK7A|wJ-eyTMk9Z$0@|aXxQUL30rciqFmlcV4?zT3(M{fWZblTaN;69bAd@#hyE+RTmkm`ML zN=uG5aza+({aQ~|fGYAA8%NvExz$)F54s^_!=FiHU^L3@NvSuKeJvkaxSaju!YQzX zKwuS_5%!yHbyAvfcVz1Uu|L_co=e1C%HHt_oJCItj=;az6bKbIAO!P|eX%DFKQ2|I z`oF0PET2MH9J}l;XTLEVS!R7&<9U@gaNg)P5rdEA@Be-G58+XoEko%a!kmC#f8cB4 z#D4+&I!;A;faALo*#qS)0V>t=iprQ;PR&o#9zslwMNG$%WGnnT*B+N}LKO|plIazW z^U(LPi(Vx(%^&8$)~DCu6dSEH(|Ze&ngA|eEyVZF5&m(8y1$9Fl&CPwNnoG@PeGZi z-BVKaQ9;_{)h5TzwxS^u@Xu-EHPgK{{N!~Z4@c4J^DDiEDc)?W(B^(<$&X}*lJEz2 zXOnKNcADBxRczi&I7wsEzT{6ZHAav4u%*#38a*q2s6b`$dAogKxwPdPM+Mi25F^R@ zS0wP)G7^(`rT72yiZB=_OBnjWvBCg7NFWQ}#MjcQ1TbBYEz!tv^3V1Ihc7)8=SG)APJ$R&jmv=af#z6~P}0I6ERz!PYD z3kw$RnAJB1`7Xh&di3+uWB_U`tEgWeu3J1Pg6)MFB$`R|G0H0#G8*-}S;F`E<&w`W!kz*|BPj2?0RN_|o zx=TuN`Lrj_I*OlT&$|DqAM*wxPvPocvIGof+$SQeC$Lt-gc>e;?dD^ZqByi-T*cpMlwX7v!9d}DTH@2@#<^{uKumA3+Y+*{7-qa zSkaVnAWdJX3B-6WT2cqrvUD_EgSBc(%da@kiSiHlO1|!M=TNBZ?UEDnOtZAtSll*$ z++w4u@8eiV{mf_+IRqF3%(sfn?Bm8;qt-&gxNlClW9L&`ZW+<&4T)Cu;xwPu?ilFn z^>DwSwrQv-88w7UnOIIHo4FIFLpWxoPJZ&aCs>dD(xw~1x1%X@tvy07D>mWr?W9P6e|momv*P?b_(5vLU9M#Tgt-#t)`7YQs0n?sBj;_*w9%nMDe+S6BVTa4Pb_J2adBy zCdfce=%Cd4I#;4`AH-nkf$lPUxhOlUgeRW(k=nX`Uato4tu&XVS-($>tBOMN>L2LGP>gbtDj-WqID3@8N17chB++*vOxKE~s-Q{nam~3j- zEDBk7igA&@<4U*8MUL7Yo?+V9r1P!z$2ZHSeM9zz+MhB_wkH&ze$j`SVRnkBp?gn$ zIJ)Bg2zOPtCuKa~Z$FPx(yL?qV{Nf4+%4DrRPUhwd2AhQkCWbr^Lt~{C$DD$PTjKH zT(i(3lP~@*b6_fVNun6Jn5XPPop#cKJ0#~=8ZbBp#u=h7dcVr8y@|DGU5q*_tamNG zsAjya#WA$xr|PpFq$MH2+BbA%aJL@qvQ41)QfVC1l@S+y`?PSg(}Dfbe(lM=Vi%MW z$v`?O{Yv$HR!(?swcO+W^!Kg?& zYd);z)a(S}H$!~yoHWEz`&8z?u4|!8d+{u=&wh`|G^jp(N;QCI(Wq)Vwd(;&XUdvR zev+38^lnvF700kv(e9{l-C^-}$W^ECF1T$R$v9hI6PAJjUq7wuJKOiq-4ijGklUTX()SmIF9By+f2+lTi1>O%hZ)C$TZkL>@8x3dgtEBfC& zEd|~!NZr~*F#(Cd}9oGjn*xNC+^ z>QtO2CA}%d!pL#Ngcgw*ck^=YkO^C5ucpb8Bb=eYaEyJ8YY^+q7B_Ig@e}9&^1*$J z!bMFT^&`>*Ia>nwERA2`iPu&ucsiSfWona;eX?Ef{OA~YJ_o(|$;l916O{*@nP4Rd zo?-qYkH%8r)?yD4nAO`vTXz|UQdz9@qBn^{l3IsI%F3ox210Oo$G@QL=f!wb`+yW| zhtjEQ!yix;pVk8R*($4_d3TV9MsCuIoG2GY-+};J4eoq_hRe|AaQ2MvpDp+SVbJ>z zt20-O#DLD>ly1vp>BOF?)Jv;L`)sd3zMhdvO`jK@G7{5D#I})72W5VBnIG6^?gq&E zG%$**{}>fu?H{F}bXjljeE)vjku9?H`}^#=Xz?-O6^{u~1G)a`6^dM~B^YhbtSRob zlKv-wLy73LjyIbqpq5RjbB^x7yrqeiz74|xgOph5a*tnKtax??g`x?bFiHv}MGebJ zJ51e$lL&nN?(;%KMxi*qcGS!t#i*!ayPl;?MF42*92@cV-Hd#&JNaV@+e956ohj#g zB6NY7m8EZsyy{{~dso#No&1@W^6v`92=lJlJ>kn@Iq*UJ*4lxL>&C+Xvk^GZ8kwDs z-%%r+uQc!~CN2nN*}bF%`?E7O`{6(AaH`Xg(4mv)T{ruDT`+RQ!Z;I;(Rg;2D z7VabC7$_T#Yk2X&-V;C2;i5Egrf40gKYOGI!>5Klb9T4|24B5Sw9auE%@?;$ik(uv zuDcuXe7xYqQH?hB{sF6xpU15pB)|6#gJbstw3YbD0cj`+e!~L4Xe5l3W9{&zcf>eY zg0=ivqM(=4CBuaDcFN`5XU@b#w6IPj*|Y%7D7AvWj^`=I<}YwQM1!AiZ08vSXW%t5;NZc^XH3oeBOl#-r*)E;#~mz;R3#P!&|7PBi4K(Nl+y9-YMMqIA4Ng`bDG0Q@{`g zhc9YWl*LR$7QKSSv*&fyM9w0Bji&s1DmJ`Ou8mgNcrOB#T~o_$15aa>u}%giw3&y1 zGME#CNDms6hO^$4r46CkO4fUJ$PKT0=`DaWg(=UFe+lL@yvoc;M-Nq=EQ>P}X7<1XFf&o^Q(YXhoOkF2bWd;ZdO1}enLf*|m2bz_Qi z^)m;OM$kKt!2*6B59-6?)LSw!{5veAc@hsZlfwi)2T}KLJEp10a@#k0Hv%@(kaPwu z$XY*AO;%@>`pM`M8-x#g%>+tY=$`xl^evRfbg>9+%GEQH(CBu4lWdQ1T%#}%`hB{) z04Vh3JHt7Mm7Z#&R)YgpG4%XFgKHaF?yPlk2x^eQUrllD^gj8oQSl#!;ro>vT3_9} z`*FZnPO|PogM=owjo|yGrkf*G{?4=N_{~9!F%Dzcg*tQ5CSKT$qbp14A9O%2(t&X9 zL!gZg8>RE}1#yUZJboCD`+{M}kJ#$;N&AcdZZ=oS19LmsaI7ZuuK#M^`sONra|4Ad z^iO_jXn% zTRh~hfhpFib-Z=36NwMJ$gM&Xx?Z4v`n29yUe!@8b~0ji9DATYEENO?)VirRZZ%Y`s98IJklAT z^NiaFTDpzAaLE^oKb`8`NQa946yIXA4XW@yMWm$*aJ&lBd9F=uVj~v#xCI7*lmSB~ zP7dD}&~b;sVQ^yM=3ZdZFy>U=YAflFvXl|pxJ3GELD5tp8N6o~**j?%yy`yB@?Qsw zUE9T$#L5J)>}~YewoccXin@IO##{>&vy=+TCi{ydVRq3<EoUq2J4konj|h%Y?I_*w z;{Tv~$7YvHY+3l1yK1*D>3vTfU`CcVh$&m9yEEY@l#qPv8w35nktG?s>btH1vQ0IhDB8 z%uI&Qm>40wpE=?jP+jF0!0t2ESMO5HoJ}*lJUtL)Hnaakwbmb%A2ZSm#?{N>RIA?a z&)40}o_+R|+A3G%w6Nz7gh3ebU#dViKbVZ=?-D);%DhQ~;xc;jS5@6bJdbB_AEPr{ zwr_3mv2lpodKW-`X$osP-+1F=?t(k=SJ1JYK9Oarmgi@DC@11jKOrb%&4YpDLDhMW zRQnQ-{DN^EJ8)Kc~3zvI~? z&Ik-dHl4H(2<~*a8Z>~tH6IR4BRe8O-*Ehbjg0hzY5!sHuh{+1k!FBG$y12TZ)%HQ zBAZ`zQxY;%i(>MM3g~%adp)m(V<}xFNJ$MtaIN((YHLo(%X}%1JU3*oR=i?+a|-=i z8@N~}GXD^8U5=NV$v=K}RVMyW`m6 zRvsUsVVF`xrnnAcZ|dH* z@o%20%;%bhzg+F&)7r;{-eda6F{=9SeH+g(lkeo~5r#q1pg zh4aYQ0eOWzOFb%8dB@i$sy;7sGh+)#SdN?Q?ym~z=a5y0f@O&kYJ+nSEl8gcCR>72 z?C0%j!a%`@Y9U5VXl`Pnk}4`qw}PMDGB-9elW8c0E~+Jtq2Sr%WCJ>rfZ0gM*wQ?# z$X`yeGWr}s@^VHIkV1DR2%@?lwQ3ZLTcF+Qo>>sny-OgSYrJ!`KN(TAfz0ji{j$V! zKmebveYI~LnC9iq{W5t#d0?%F-wV+^q4ebh5v1EgA18urh^*nm;akBgR(Zv5ai*1B zRvFo9KN@-QPcgjNg`DwX%him3qK6GZ)?s*Lj~Dzl>Mqg*K}WWK8v8ZeG0u6M$Br}{ zRdH@aE1J^zu@|TLIiL4l8&_I0;AE1-s!j>^d2uAFe+WbE!c?+a>-9>FW#2BVz(-j*PXk6&C600v<{xeg_o!GTHtT<6NT*z)q=dvnjT)8gTF3g4# zyAzemj^EVe1lHG<+t((e1>`prYoQ~w)T@rV|6%CzE2;uqVm0axjf~xl!VM`>Mft*A zE(={G))2vmLFc|!xyGo?YK;{uG?lC9sFPrFD29G~%a;h}+2ltImp8`~P8zj*&Kz#; zqYq*JVUcrK3O4R_=Ud8PklNMKwO$jyGI~NK=Gqct-DJaeudb~P`l}*~B|T5(YUycx zS@?5xSC=p9n=5O*l)+X_aKc$4{!bKjH(zuG8bU0Q zm&~u=F!-eV;r%2a`2c$5oIOEusyiJyYcwwON3MS%WEM2}8MdgNj3Qs(h_+N2P&rD& zn0~vJGhfOA;INV|q@_+3oqOaTzAl z6ZKJpc|WIZ@54w1ZDF8^Nu-@)kNpmVh~_%SfZCy-akekhn>yH3@2qX(+~nv0L^!M` zCjo)Wid<)rq-h^AQ^!cAoPAk^{OkPM1^?jSf9Nlnimfq(LZrZn$vzi!ivKXS-}`ig z7FnP|2()=ecfWw=}*Ux%aKyv{s zyWNI$3{tPAz8iNgm^!m1oYhveD<06_?{#N2|Z-^z6s z&vI@n+QNi?SVh=${pijCO9-ZXhg7hZr5R$CN8D42FXcEwkCQOd)8{=hs^^D8tYVIm z&SIq*bkFOr9%WW$(82{_9Z(vMW6D(#SDGw!=jdMo&uQ5di-Sy+r~X>-G;uglY``EU0?m*fHWO%f;@6nhd-Qco+Xhli)3W5w%Ld?B zvJ_IeTl-uvN1}rHp{5_M?OW=#BFdet0-GxHaUUwq;R!JGUV7PT;^~-pVuasp3+~`jI5R zv-iD0he?&5{J?gi)|`?jqhXto36}saDVtywn%6Ko8+j&&&Ob26uc68LW(@lACxu-; z*LaS-UnGt?A8CxO{U{;JZO3SyR9W#MJDcq_EwNk0rM9Zt^aOc6@Yrhv*zTK!kR_tc z^L`sS*HuFX-~d>LhW7>Hx(I=v&pqU@ke>=4uB^9Vxzk?GpjH;9O?u@hqXz57C_fKM zNXqPJOkgYsLZ~)-dpi8dCyv!o%~#s?UXcLpy_BG%LzPpsn3#a%6=?50)|YvQn$&0! zfNtweA(DsXE1A+8Js$_E9tov=7`Ka~AV6!$pbQKaCtzg1Pn*9|@p#XeAMQSeHy-RE zwA$HDn-Y?72wu?3Sv8(B>{-cLEG+GmNqaj~JLF$t9MNWs@!Dd^*jZ6o{>$lhy7bKj z$E(CqFZ)luMhBfR4KGGTf=d2eao(~7dI79c*SLNj`W*fH1jZMiCK-Cl<`-aTEozgK zYRU6MaTymH{PBw2%*NJ~Ha(3*%Cd@b#+`>sTL#Av$_^i;9W=v!-oV!}v+Q>gs(ZDi z!UYW=RT@{`{5yU!Gdp{z=${R@=yrHQan_V!JGPFLx2}oB&_?uKR96K=+tqe^Rzrxi z2`C=I@fjk!h^F}|*$E@<1+F=8>GOtzvHN^xic>?4U=DpF!uwe&bK&WGqZE>rX3f<> zhThf}cs-`FolXvEwJFtZDk|z~f*(maM$vIfoOA%t1kaeYv%sTVNWfa2%M{W`VCSBY za8v+>!`htos7i7mzMhMgG=1dPx6t{s*b43WW5$`r?S%^89yZ`N8ch6%mBFj&G=e_A zDS7%nJm`;EMH<#0vyv`i%sG|$zMA?81E9J8O_S)`r`T?sY1JKim3&mSKgQqrRE=h> z*Tt7Q*&edS(KdgTjU~-ID9e!WOqq59I*sG{gyBWSj{m$zzXv--R7`6@?P6t^;ytSD z#&eiuhgGF(WLPP*i=gSYKdTXl9$wSr?G5N7OQOTKfn3W=esx~K^}kxKt?*IbWpwi%cG%<5%jLgH<>rN;di+*hR) z9IDNR^zL@gMrRssx3lmdYky*_FAC`*ctGE5{B(tIjYIb_rh!VhXv%XnAa0>kt&eTa zCQ0YnfywNtshdgNu&o+zV7^IQ;sX1Y)aHj5CU_WCs@}xpIr0QltFNFh-%toi)gunU zZI~ znVIjpi+TKcKVxNVrV?Q~t9|)KG{|JBJM{zG&OR;E8{Pk^NM(fa=p0x26(>wA$e#tv zvo3e+$0E9~xR<__!o(&-N)ybc20sqB!Z@41rE~>Hm7lvl-8_w5owfB?q9qU z*1OL}RIWK+;8KjimS)__h!jeX9eYH}qaS0w`fUq12kNgw{uHqi+IAjSmhKnXTqG@c5UErOx_dH28{~pJN0kf$L~|&rT0N;B8f?mjlto;E!6SBksO@!grz0kd(ZMk zf!mk)YNt*=6`^)+ivlc`TO(tpgVroV2qc6*d+R-e13r0ehs>cG1%7P+%+--!rFC2& zBb<#Tn?;t+DZeeUN42XRaOI)8`7d>n*{8 zrYXkQM0uknmgiwrlAO?5dU2-rBT-}y10^PO&J|EMch*7k=;!d@`{T_yTF%H5pc(fl zt1)X9T~7L3&tWl(h1I2ESA2lOzDBHlq5v9|U3h$sD$typk&V&i{pU;FePMS zFQYKCk|H#FE;@`ciY|05jgxRN%-C(2<0DNahO2{Vl4DPx(LvS2eiz496t08w0{=W5 zgWMB`n2nZ1FP=wZj3)TwzNcaS{xI9zJX6$qnA#7aXMn@U#&lht;E+x zIoJ|785@U}+dXvtcOJ-D!|=y!XfWy|c13npnoS9nq3zX7tW5(4HN6%fs4#_pZQ1#o z;au$$#kSuncP3c*2$vnDi`{UPT^D&l2ftnOPS{D5RXS8^OWWP@^h`&HZn)}3{>F!e z0xEj?=?f}RdYj10OipQeWy7!0NtqKZfT7pBX{`MlG!MK^nCTlfykDM5T_E%$5?u+U zX)_!4DPw&2^OT>6JCM+)r=#e^--WnbA@ElD_4Nl8Rw67!hY&j0=k zGoq1I@;$3T_+w2G6>Qutf7 zs(`qUbk$-)Pe9sTU;qeYB&1a?0b#}fdT+9|O>{RGw;rXO2lMG)ONIS<&@maq$Y&=i8zWMlL#2yL1#AdzH>+ii6H@Hw@U6Q~3bBWdQ zaPki$Ph#uB&9Z%SX|^7ru865buFHF061ZWZ2-0N9m(^57(@RsilnBu@a|qZ{T*M<*VH>9N1MEi+;}JY-naxhKK8VC%6|Ec z{U_*l`i)=Z(K!kgsC8MCLKlBFlKGL@mb2d1YRw(%i(};~sjgS)@svI8(6fq|MD*f2 zFHLZ71LF!a>lpmxI5LWdf+L~cmU1EKrQBd4T`iyAQMhl1vbx%^lK&j%{(eEx>TRKw zVXp)C?Y+;|v(lhSTo~ENB@O6Jeux>yg3@mvx)0n{>VDT5#PH4HA67baa|_RfAxj!R zObXyeS4RAJNR}#@eWQd1{t@_IR)yU%Qur5Q-aJ!xtk#}(zvJA19)5NGFc@n8#%$u| zFjd-J_e29;^r~Zb7-c<^jc*C0UmTTB@onoBalpUHT-Nt}Ca8At)%bbI7 zx8D63hg$8t9f0c4QqoK6pCLE%dNdZg?bG2!6KV>xwb{o@rfgG_I6NG2&hZKHJUm|w zFrO@MlAg~@*Er6JPuKmbmT~JoFnF$S03=?u>=h0L*HX}F4VnoW`U01-jNVGAaT7p0 zUd9d3wc`ynIjK(aVy@Z*Zli*T6cX^}hK7%%;$b1pR&1Y9;3;g`=@i|UI>7_<6{b~% zMHX%|otM&;!z+wbNQKmtwX=_(v-4N`x#gL5=J(=7`Gl0IVK&x#-GfwkPo|Zo9ss+6 zqKw3XG6LS;yH@kESEW}`vAj=@>pc=Vi1N4(`(&*l#i_|5?2$t~K&uim%y3!2^!wQ9 zsx*R8HvPIE(cmfms>Btks=Rb@r4pT8cax65U4Et;!p_h9C>sUC^A!k&pfnbFx%p|7Uj%xG z-dfY}!!8|?3|lHv@hvxFJTGYh#T7R4IuHW0e79Hu3(zH6w1f_kPB6VG`p?dpL9xMz zMov*yoN3>y3vQgD*IXA4FE^f_|2inss8x|B6K&q1#na{PRXmzcqoBnlXM6g(Gz8Fl zD)TuzF&)Gz<<~GEzZo5R+59+7=Y+tnl61YyK9l3{7|F=sGvJ*9>}oQCT6(o$iUW(S=|eiwnH z(bG9k;;D)71E}=S!1j;w;2FF+i5Hf8?J><0vOry(WHH7G%PMC8wMD+GP=;ltIu{Q$ zpPDQ>!*!rYa)<`se!S~L79}4|wuJeLsO&@GMwhu^&t)GoTUCAB|zienbw%kJ=*aXx%7-IQqid$bS?gew2W;Lgjl;}88snFekOjRu>IxGe z7{JJU?2%rPp0&{(7a@Rw+a9CC&of33+SJ^C+N4+lB@MtDw@mc$eByj0E z_GAWUR3=ZIzb1U%!B}6>B2u{(e?u6zAy}6ayD_Ix1Lh?U)tL;sMm({d*1Z7T`J*(Z zssxVoVjuvz*YCKJ=ITZMfCUl&QvPhV4gH=(oU0#(-JO(MJ*(BLL-0u@;S^>gwGAx9 zr)14^5$H-KIxa5d!|gu|2Q{DS zJQSMjJ;a$55PEgV3Dq{JXVt^rG`IB+zm46-4SEURN9~XY)?h&^#wI+r$TzyXQER4( z8k1=YgD1bsiPm0HTI?_HT#+QmgB5INM^_B1t2CxgMUvFbJlRq(_Y5;;wpwMn!o!mM z*Bs7uf;Wtn4l5q~|AU_(bbe>perMq^c`4|QDH6X;1yc-LXa>$SVC*K(?5{uFqj|rr zm5)(fmIqrqQ;wPVtTO_YTUt*&qa(IQZZRs-=CIqT{-K(av3-)l8YgNiCOfXcc6O$H z!63z#&5!{}0})=&Ney+Lv%n&IkU{6tJGJQ?V%< z_TO6NttRHy4;*=#aM#I^M7z?&C-ff78!=0=!*PsgZ0h#JnxJz-73_UnDpd0qDZ=nc zePe1CF?&kwL%QZlpK6lHtUajuJI{aiTO0;Q;P0 zh9e3aTGjC6x-sbQ{d5+^yXl&S)3mxCDLq={c+js#iVs?f%04>U;71}usKImtyzW80 zhgX(!N9ZP&AfL@U>cXvoMF&{fNaj8VHx;&0XZ8$gux*7XRz!78#;R1F=SV39YHXj|8qog{)hC#}RW?(CR}K^;3#F z9m|kh3m-P&t)4FGxh43}{Isf~@}HMOLOICYqD;Ijb~Xor`IRN7c^xzLx>ObU)FUN! zu-!B879V~$&V1V$fvGKn@YfK`=^umo_}z-Hs$S%@)nAprE(|o{yX2@_m2NW%E0zmg z$G2k=Le*R_Un^mFB_<$A&-sD%|6>kh8BF86_BARx?6@lazSeIthECE`Rb=}D3N*KM zHCRl+Y|-(vJt!0nC)Pq}&+JPjRLl=bzs>x6*)S>|;u)m{X74@}!ZrH%h1HXQ);gVZ zanX~|$-!cQOnf!vjlC^fIhqdG=tY0zLwN-D9=V&$Cz{)wM;<;jGNpWdgIcZj^wi)w zT&QMieNUu}KhnfY{9$?d>#=GbL$H8pSl4`R6xQOkuJLs7Ik6PLRM49>J~lNu6t6MS z7%goVXndGe1&=79xOyqP3uh#shXxzj_#dnAWZN-DAkr(0IQ)@=cYgl2`QysW1@@$N z*)E-k$q77N?|$*5jOu4G^9T^{{Bg59VChHq@|H3c1}@YAZ|{s0K){^-@QbR|a;h&N zz_MPhAXxlc@J2Vsn?%DO2%(?&t#XNE*B^~Zw`FHa))TVz;*)JZXZS}87#-4UbWk#V z3tR&e3@_yvN7v>w$P9+Pr*kdzm>T~!N`@3< zCq#&{+T2*u0;x+KQop_e$)o2R`{>?1%ak_i4bNiPqGCPTEJvTSGu2a1Q!e$b$Awt* z4JdT_JrdZ^Xq^~Vl_-?nzNZ%&x9?w6^rcFunm@e&u;98_B*>)n4}-x(D;HMlJa(!g z5b&N4A+ue(wxQa(pBJaJyAddYQFnlnQrbBJ+ImWsq1E2i_rD2#=7!sD|ADib)tLs9 zwYR>r>;8{SHmNRt-ZhFP+tHb*8gM(ZLT6U&gMDGg znm{pPK0(dUO8Wy&f-^eq!rUC$(@Sgql)We0y4ZbmyV6RX1p!@yIXGUi;hBt?Pd)+a zxW1sZM>?9a&4rI3-sWf;B+p$-%EFFPJ-55;?@Vt7Gv#_ogwvNrgqIAO!i8OZe&=ky z0SZv+71evpgC+LR6_OWBjbW@Z-mZXz*wjYi7*($75p)(t9-_<)sK0?w>rm^wF8cm9 z{L+Ey&8rWE;UrIstt^vu*(DJ&c14eJQ0L)!{`?I-GTTqK0GAIZj3~fL^Z|pqn!qcY z>&&)8v{pYe*DVbMSsxO>ch?hDm#s%ve2)t-9C^XmJl1w4a&{Y%;|7@ZhSdNkSkvr1&wdu-H$87!=slca=YF z^p`yfpMDD}5Q2?c!IYmcS_p&`h=@SaIi|Y=$1+_lTU= zLM#ZC^F`b4h2l0QciZu~v@>vdp}Xz$tXRvk3=Ik=zM;s%xf2Uv{dnzgAzm zM8B*uZ5;y-Zm7CEHq`sO7OR#q%Fb0SGpB4$d+{UsmA}-RhP;OuaoU7aK%bTr6lYP? z0-I8PR(UCvnGKuu;@5T%=AVD-p7^vZqYA7-ipSJZ|7TZQ`Ar9zUrfz~nTFk(P8(A& zZ*&9t`3cojQQW+c^elf;_ah;lU5$m_%myPa%cHp5spBa1K4#wbS8;X+x5U*}|@o>tSf?nSg1=E>L@-CW&5U4S)FbZ$hEp;e=dG#1#tS~iH3^?;Oxy0G7#O+U{95s!9FBhEC^Uw7D^n>Cb? z3D2it6d7!pWi#_z0)OvZ<|xamT_dpho6DY9eDuij&nd8lF{-R+k0{*|T@I zmK{w4W3;At#@4TpOG9>6s|DOACXS)9rsrD}Q>s8U+9qtkR`Sb&p?&kb_CEp7kuS4| zloQg$ICb(0iZ&9lWfjFn&JCn_8BW zU*yT%e+jF?AX1dXQ(wI7?eFNZjxD+t7+f}So0p{)`mPkvUhFaf9{P$K`r3L9^k=zv zkGj~CTWn;Q9bE)V{*tJ0qCwE~u%y}gbDos#A4ah8A$ZyuW?1OZM2=m^ zz5Pd`-_>Q~2L4~+JihkuN7q2F5kAeO;@@uU#6EWB{Voo+8zYw6=n9?qD!brcT&`*= z3-bC%bdgDW`o%1=RiL4`_vM2qaY*p%G20I z0ybP8d9I>o{2XO}vzO6!N3@g^;6cj5$*S#ITzsV9X2fmohE?J+XdiAy%DQ#xQHFxo ztnKI2;`%eYnI$!MehDItVZ7H4JKA3!sWK|y?BsaIX`M8~b0#*;+I3aF&y#qK9oJ@) ztGuP2jn|Ph3ApHARwV^0M9hg01iLQ=>9Eil5>#WdA*ECEr9(8{21d>_I=#-M!Bt}5 zYf~#?zKpcd69l?ViVYIm_o&Q)rVfg&;4fi1yQH*FM(a{ptmX%Uz`9e`B4Ny+wY~1wBBYWF~{(j6W% zlD^wO9^7~Dy(UqD7)dLCz?=3K+M_*x3h%-9zY?{l`8;0^mbGGeZK01%Px!+SOU!XX z&AcP_9nqisYxHrK=XK~={xGy-yy$vtAWXH<<~UgLfd4QgT=7@riW99m{k77dFVsQV zW5hG(N(f4@{D+Zvve*jyhf#O3SjuASt9i26puX^^+va#P`?%2N$d4C$8mWiY*!`$* zZqqnftb(V%kf z)?R*_*LE-KYC=ancEtSH$@mE$+KYu}h5UL_gFC?i#4b{skT`U+4_3;3GJy^7-kUbV7S1GI z)~0|N#TEn<1y~vj8#Wdd|0uJ85aZjf!HUf$n0lCqJ-;uP*d)=t4h0R0mJGoVwiLL5 zxXZW>5qP(vKLgV#2~6VUj$D~SUOdktDDwjNQvlk}aHi~B8p_`ltXUbg&%3_m0GLnZ z!m&4sz4|acf`YC6P1YE&mG@qt^I}*EQp+>Sa@{J47mHFlh6$8a+AmKkg_%;iD*Y(Z zPK&75Nc&>mx(!Jmw@!;r_V}lf{{0*ydMC|<4bHZGF!q633DQH9<{uB2*$9DMk*Swh0+tDY6CWz+a>hf^R zwD8@Purs8frM+hHxhQWlN;^(^W9}3ocZq1R1xlO=Rha84USHe~_F)@$A6T30;c{uu z)ShgIOb_;JDVA?Qf1421oJ8-Ae~17p^ecqmaswba>>80_G$rYds^a;@OesuFxEWAc zggUs34Za=RW{}vTan^}{)y!|~FD)~cI}2e$eolPQb;)4>u0Fj+m;}a8@R+^Vh9i~X z%-VDjJGJG{YN7eXez6ZYa!P$0HQ~;AgByVPMadN-M%8=2*j8q83iAe;70ad?C+XsCsP2!ZLcQ2v0^!s~ zyCx%r+^I+uAGB*rbmvVvU1Th;kL;oO=QWpnt(_mzjD^;EQ*xCh5xyxTz_M7GkFqw& zHf?lxH@fJlOsM6@uz1BK{=#uuxUR41tN3>azvY}O_L_=!W7d|@>tSsHz0BEUHC7&R zg*|WIi5f;9PMu*Gs9e<^U|uvAR1*qjwax0R#E3F)IBN5tSd~J#GGR34ySdGZN5MGNK{~56_32ip1-H{ey*@NIPBWiw-b$s$ya9taklaoKX>y|L^OF?lqW=<0EUp z{;u%?xz;=dyC?C9#(1h7W0*KB^kDW-UyjyUjGd{PV*6g>FHvPfX+ZMEc{#1h%UDaw zA7cUnBcI5RzZBqx5V2BiRHLrV?+Ll91GhLih)JI}c2$y=K}{D2)?R6~Q8y0n#BN@3F8npyu)Y=be-JI$5C_yz1S3 zimG0U;$<;m;QK9ed~QQJj*kAE^u}qhTHkRy1EaK4Flk~c!H~P9 zkoTa@Jh|g-Xuoy#{*lURKin2j9Ie0On908n zwj~cu_jy?<)HCDhRyRGGP@0dm9FdPb`t1jrEEPBC>&UAyov0eTx$wt3mAPm&W?~{j zJ1b;6)TeDR>vjy7`VZrN(szD~FMd7qW%QG9Gxx8TXv1yah9_|Y+~wDdh8Lw4R}Uyd z)9ak){g{W-J*^_exO!z`2=MaoJr=v~&oFx%JW-Rje&9Fjyzx(S9yb<;3^3if;z%>oF;ZEP>9E|`z=+fe z(QjKRFCtNiDP~Q879NjK2u*9TK+mslUmf$qXB~i)m#T`i$=lo;MDS3g#o>6HW*DjV zpnU|Eyb_Pg??t_LjAKQPJ5_=^jKzaG<`&cJHElaXw0w#~zL$6v_M6WD56MHEA|F43 zi>J=WvuBY>MyR-fwtnaP{ARrjd2q#$&^?8=U+*<#LQ*`qB`O}Kv$Uu|4f;`GVb^z^ zuZTwtEu#*I>>a$ur&v^MlOC*{=-&QjXvbukb^4_N&fegR&gCz0K+H+z3EMK#cgBnn z1iVs?T%I6Vy*a6dgGgLoFX#B@!8;TV+DhnEuPtk_c{UJGZ`~x^;4WHU0{iL^i~70Z z?wI4_74NALtlkksOB27F_RtMAI09$oP@rpO$5a{U57l1rw*bOX^=$meM43^QN2}1So#%fG|V`?$o=e zHq@@efr5%>I)jO1LAeMA%C7KrHJt|@O>U-&~nE+gD!If=q9yW=g~ zf2Zz9cnn9U%0cW+sJ~x17=<=O1vTvQNuP`QO=bJnyo7@nPZ|VXI8|O)Y`c80+}nzI zD3k|B@OR_-{Z!+>ud@*&qu2>tVl-C;vP%o=*w1=1(u!$BE;OaSEPzo^y$bw!+>=6f z`O6eYkV(YpyE8GHL(l7Y%M|j8&e})p^A!94iv}Y8O3y#xKjTb2^ZKyo8TasZkJ&lM zQp-v{gXV&iLp_MuKBhJ2oT>dG7tM;P`}PKnKh7J40m3%5-qZ=iTn+(r2f&X~ylZon z%ko~Iox#ou3B+mm#^Rg3cxWmaM@O7GeUW!}di&x~Q?z(WZki$62*mQHOPqCAGrYb6 zeo)fja<*Ol=QVMwldfzQ@#y{UR(CX5y@@%CV`6bD`h9BZ9_bDaz$7B3cEkcWHd5Vg zfAod&B^ka_ibd(+LpWYARS6q+4WA3X7*4p58R;uYP(} z+C~~ISwx~7hCqs-WBvz1ux1XxEb*JIj|6HR!) zhG85q-LO4hSmqa=`}X0KqcQ+VlcGUd$?i!BP8dWBX<%tKwsLBV77$dA#y%v{mTp!zC%bDSAu zy)Lhmth_2=%#FGPTr%%Aft_LG&y)s58rAVdrd%<(bmP=*^X~Dnh|$<4d#FPwBS_=0 zgrF00LRxSe2&sHEJFEYXE!_FRj-*Sr_3HBEOHs;{&8pc3MH>^KlYSk5;YBKR2_ImR zj9Kcsm~9&K-8KJ4q$^_%%vwuRrYqDA!(acAAOCy_d8|u}n^~FB1QxhL5Gg9K$67Q5 z9veh`LOuVz>!nJl0%YBH7H2-MvasT&l650^ zXGe^kG-m9A~tNG-Oy6|zI#<#iq%DdhWo{VmlenBS69?#AcJO9?S8YuF8 zlL3r=t9%%gEes}eToAy^I0CO|_#zp`g;m)la$lhg={CCVW-(5kmFbiP^4{loKQfIc zr&M+Y@;a`~>#my$#grXu{GFDXkeNH&y>xB$pxxq5uB#T7<~p`XdKJEh>(hH5#PvWg zHxmW=&e({uW$_pCP#A!`zZT~*VQ(1R8(G8QYr{GUo>4~4Od#qn{O9^aD1_Gs4=m|* zQ?!Gx@m+ChrL=V+hJC{VE&Yob^m_6UPB%ycej;|Zk>rnDf7{Kl);|vmuYCq7EtP!0 zx0Y??n=dX(9cN3#w{B?d;Y~mN5NPC_VH~8c)}@KE)LH0-*o0IT7Uli@Y4;)`*eZD4 zLNuvZ);QI&yYs$a_t*TVISO})qquiLlXdDZ5SCT&)Mk=y%7EPpM#8y%Kx9I8Zp`uW zqP)>HrsGV1O%3Vy$^m2exU)%Fy>(NVVf?#=ZH=Rll+>iQyQvYObc+7PUUYW){c#;Z zB}lBC&C!)m(aAREzmfG7P;qq4wj=~df(Oq43BlcEa0wPHxVy_>gKKbtySqbh7+@f{ zySvK(!9951c-HO=A=_>Rwq(X`zk!-r}2F=LOe%Jbt@UavhplzFNftA&LX< za2Obrw{XW$1M@t{TK|+b0!;W_%PkqW%t=DnvbJp`0V9fya(AzO@!BiS;`9(Z`Nq4l z#05)UstwU)ZOs*3Min1bBRZg|pb_~FM6`b+Ul-!B zNlH*sc%iQFAupuy?gO62QkfVDoWcmSo}yywjmtU{njX2#8je>t%EhBcqzI^y_yXeD zNWN38PCX4JomG~^aY=OS+7nz}QQ?>ttFEwS<+$%03 z>bYL}x(+BWmzU&~yKr4c4nR|2F1w4M!W)d7Cf537OeaZkHEX6{E}s*�R;>;#1Up zOi-ylyZhhKW5~#h>%9~KOnL`@3RpRkf4R6@ec!5`oImhUylN%)qEwG4Y^iAD<2~!B z4&iD_;xchS(2T!S`u82|WKM~>2p-LW_VWCT&XGvSU?b%Oru$ZGrdI>(oRxnTX){`E60Q9fiZ@wSxJ%stQ$^S~tlPNd2u6 zmpY#bkmz^W7mY00jtsRU9RdYF6xAMe4L{eHK@&S*_3ry7x#-w_6ClMw$ZI*i^*Tc| z)0z0O`+Qbcax=Eq;u^m``Y<_{D}REzV3)4taFoB3`KIx~$}U-{msoQJqH;p$>&PlZ ztsUnPX3D9Ol3Ot2D=3$r>_%vmUUq|L8TqkdNwS3ZaO%9G# z6vAu_D|_jWR2k~uamNo4HkOp~NSc5232I-w^=bA!*PT8&%LxuR?-rDLoxk%5i#<;dcskfF_p24E68Ddz>RG+n zDlB0$Tp(dN?4@*>&RRBTNTo~u&U&2b&1lN$BN(HNl&C5{jlVqG5LU5y+i=pBX8kY& z;i>Ymw%;$xCS}l>3|>&FQ=BCPF!LCw)({Op7Q5S~JzovkXv=<@ul0>pYbIPzwFNx= zs*f!5Bo->4DPn0M#kNjFvgIS}t=^mu`;uafhV&%&OnaIIxfTvbZn8XARYuubPG6d< zjU%wQS(F}L0zRBAQyi?gn~AZUYQOhe@kkn6AtMWZT=vEN80d(zlT+r*<5TehRN$WF zTeNfVR19qB4yk!{|I4KRO4HT~;I>HF3~xAMnrGut&7G0w#EDVtz8GCRXtBys5o zX|Fqbg7b^cePA6=*ff@)Ce0~G{#LpX7F$_olCDmh-IXvoJtOI9$bSS;64CX8ASSE; zjo!8dWQPoH1PVaC_2DsD++13ov|#sV|+>D zxVi1;s6ZM)c6d(1E4#}~PMKw5&}>gd7Hv8>KAcTtgeT33+!t3Rf#X@d>)oZMSBOWj zAkM}>Alr^U_O9zeY3YtJI{7w+dn1ib>~Au4$-1Od3&P7+c%2URPWIA_p#B0BJq0_f zh(8Ehq?k4={L9v;l_+%_#N95j_CE6IhaaGl5nQ((iQg>VE?xA6d4whDZr!rW^Kr>J z*eXr?;vLmV)}Ya>>p{|{R%KN4Y(@wgb{2I3#v}o%B+e$6i+faks?};zKDCjT{aO=G zth(YDV@0e~DH+*vvc!kfye{_=5&k8X^LQr(pYELPWW6R=8^?Z)UHF=nPEVtaRiM|l z5g6W!|6ql$ED^JO+3&C`Qy(k(JwLYlzxKV~Lw76B_y6u|@XvquI;&#p!ym)CGy>Y< zm(bRWHdpSp|Fs{#g*)7-YP;(*0l<;)8py_>aD>(GdMWjFS6)NsB&W5!&UPvRe)<6F zZtHeo*Gj^|P03#JUmEP8rYVlao3M=2{jp(*jVxVjWWx_)+uW%f@lE zAddiJOEj)0-^Ma}VRP)ssQ4{CykkQ#_o@EeAB5woL*JYE>-Goh`_n7t!}f{x+qL<@ zse^I$rw-ILH@VH zbE2HoA_C_c-%Y!D+f$>;rC$L|PeTFLV++yf>(sJBQY91y*G^*exuM#L&YbKgdWXwP znXugXMrux%OLap{;-;#y`G}9)=Pa{z7Q_4L3Y`cxnpp$@jWUZB*4L}9^=1Ku(XYvw zM5CfH;LWf%xhECVG_nJ2sSd4ormC+O`9N~Che}hEVib}D7W~Swmh+ z-bxvR;?choOEfK?g6*HM`&~N8NDP1E#IM5BrTn|er3CWB8Rm?JDML}{cRke%NqYw@ zUF~%mHU)kpMB!=rjE`0S^JnHBNb)x3jNnaM6cPG}cvJZgnS*RqW%VhkQ@c~q*s0_4 zEeFGfva;GN1u=G;Pu-&Oyw4td0rlVM1v ziEFSESYI&rR_uKZ>2&#?!|}p2Z-R~snl}#22mH$G4AG|jh0fp;xLVnjjYRVCO1_co z2fC~$u+nCWL8WG>FBQ-VtYe>QZA2a_qw7NqmK7MPh~omXf{Al*&seAUlthU?8etEE zR-FI)U4DoiXA;1xxNwK{&R-m#io~!CTsATI$l6r%Yj&&L8GS@{K2@+qbV2JPIG80l zR85j$@3Dab^;N*lwPc(LkHzqWQxOI>ELC!S26+rOXzL6c>#{`S50CuC&zpfO{`kEo zz7%L_1Yd5~58`HnwJ#KS!gT=*O+%}uVO>w5y&*}fUs)b(GPEAvtwHE5%Aj(5t7SdA zL%Z<0oN3iAaJa5-_|5=G5Y5S?HZUiJMok9d@)A5kCxkFSAirmT}# z-gccoAz>QL-4RpCgr6088Y6f>`D=eo@dr}g&bE$c=a+@K9mJKP#TM3fEm6^CeS?iD z65#1D4|z0)mnkSJ1Ji{A2wtk>nW;_;R8PbH1|YFt>73$OyDb<}D#~XNaeGi7!5Ham z7e7Fme#a)j8kt+ayMH66AWWU>EzS9G;EsY_ceoYOnp|29Q4Q*)P1-LQcDtwgn53UR zkQBb`?}m37yYct%^CZ6<6D)N2d*jp)u)myrD=o@$$6G+fZ4=YsBk6e9MjLuTnpEA= zn6WohXn@~~onm_Ej?fg{!M&-Do0)8r0D3{H!|V>VU%z2`A10l(zfF!RQx&q)aYzT; z2JIy_wk!3`lem_745a%@>zdPxuJAZ3Nz0=dTzpwS*2zfn(#ok*+Zu=W-1Y{-PUIdr zNWQNuBJa$Ns?sp>@==VaN~raDn-Uf!Hr(^5Jh(J%pzr4GHJl$ilRH+Y=J*vRZ(VFZ zz@L=)SS#F)X+TD3LYf2!F9f8IOqab?rj&k;?V%cq#qDaWZIe6O(SSpg3QT3l<1N_{ zc)-L}Cx>jc+&bYEZ`7&QW>_8LQ@TdP6rC&N6Rkab3y zBXVcpx5wbsERo7IAEKW|U#f-6LBuLp3ec2SQKt|_ z6Ga8!-5299;s4ckXmfkVuj>2bL#Dy~z!SLFRN_F0Hf8uL;>nSQXt^sQsEm#j_(^i> z*;zFKLX6EIVUD7pb_X2m;noyqe$%&xX<}GznIvM4MxN+1`(+HzN#Zxlnznw+Mv2je z3>T1`&xLa#_`1`JZS_;UIcMAVXPqBzY7Un4R9yG%@sX$DjCEF)rAdlZ zXK#NMpMQWlP2WbZG+RDOp6GHslmBK)^TmFM^~PDJ2mmLI)?XO4Pbvz#ceD43b=83P zVFYljr6%QIOxE#*&eg}|=#Z9OcxBth{SbXaTRdPfM2R&c`K_uzZdGapg;$38Rl+B3 z$9zzE1wf~?WXpxtsEt#S1e0t$>c%Se5|W4kfr{v(*O2=N@Kjb-@-$B*Nc1CL2caS? z)Kpb>tw9h?N~l?lZuZJdSPf(2wQ)u~TxmY}pTN-Plw=oPMP#5+>a_;tjzR5=cIpvZ zUdtzJS#*O3ATeOE2-kr{&e}o$Cky=a`qQ_Etl3&k4w^VlXsMMJl9s6G4+LT%P;q{@ zo>+bX==Fz_b+*W4N;`GWr0*AoZOCh#p#9vax1P(EtV+#HIP5B7L+H^TOAq(M^OsQN zwcHDw%YJwBuW7BRxGxjF#lXQ%7FQWf)G_cFwifH0a+D{dIO%%nta7a=Xz5NxgEWaE zZubfU-iD97tqS*p4lU(9!=OwTp5`!<>qBy~{Yr05OFGFBg34Y1*tB8NV zIQ;yebieEk24uKHRYg&V7=4l$qk)zsW0pUKgfji0)YP~ru>Y!7)T3W3i)%5zLUmYl zSSA$Ks+2aKfq$y{tU0M453j*v#Z!B@&+%~%I3&LwPrJ9O*2Osv7hEp-I>XYOnbfuN z*&;8j63vLr3=pGzEbok_p?9pa?U<>cvEsn9i|ceX+Kp?};ZRC>k#jlMH5Yl~QDg)RzfDn|ZcXBE`?Am>mv4Hu-Bmf?W{B6& zdAD2xGAhE~y;RP2sAF8cp*pfTs+SGpBKd(7hD~g1deOFNWAj#172NOL3U+Oq5>8;Hi#)z;#Gs0&)^>wj!$e zO`X{f$c@R&+$zS7Rh@a-@jWjM?*+oGI})*_9f3@5)^stt)SBlsmP>?js)m54yY=ss z4|$liot=$vq71=8n3IZAd9f>Pge$O9NzFzRNwyXe9l5wU@O;YE zVWe)JnKltSSHm9BQlcxTHb%f>N4g;Y7;JRrW$9GXMVP})?M0Ru~kO`kSMVB;bXWX>6EJd6wh9w`z9JoEa307dMsV zfGvS2(3_uQ^Zy_m0D2~P=ia-(-{|wmYK8awMlrQ%m$W3x0tQ$?XgWV=X^rEi;)nX< zy0*Q54vSFo!XZ1VUJVB;DBw1&OBlMA-$}0Pbuog=63PkB4Nd2WSL%$==TDlpR-mzl zYADyVo9PnrB+C3O=och+0DU#?Be^TnCkO8YqA9fP*?ksIaoNfrEO)-^)Fz$l&R!}j zGbYEU*Bf%Dc8GZy+@DhWd<>>n-S;0CA9m2vHDT;o7>VrLHef2aVrK0-Vs=$(PYvxP zzNkz2kayu;7%)T%vOo@#Hr~WnnQeeoI1JEiZSpMgeNI~Pi%~u^<@nlf_~SRk=S`TT z9PM=ghm|+SyMcqqA|-BNT*VpnkZZ_N;yoqcS5xKWg_~{)5UViz8{MlbuiwftziH^U zY{xDet=1}3FpBphKny1hU(z47eV0yI=Vk#rqI`hc3Wc8#!Hb!PVdYasg`af}jlMWz zM@=W0UHZ2^^;4rpGF#3IHW3$S%3{pSulKY){N41XMpIg&ITj`EUEgRO1TT(q1ExLO znUZyCwVx!{zz#@_urh+8@?-!;}22cn9cZrSD z&-Cl4l+v9VHfyp4F-AD<7!w2FQad@@sa$Ew{NLs30RI zQ%;=(Xfo1^ft^H&k~p;FvB=biz!(>tJLUzE+kut?+YS;df*y$!>7)JGRHR|bhSkjP zKUrxktb4!g{YiGEFxVQH6oRT_^)oFy7zUyp2w~@QUG+gFCjo-8y`O#zmNZ#u?EmJd zpY+1w=sDKGJ)a5J{_=AV+b5s`*qjNZ|@p`RZ|%ERv?;C3^vjimNU3AXlK=j z0E(Sl8AL?GmkWxXF6SKSDGSeEq65xSN;Qr|%H_c3)fl;Fz0#CO=V+9EK_#(SS?P0RG? zHn0@FvZ8D6P4EgjIj4GcVptQ3u1wyuw_!n;Wvk$ek2SRg1(H1bU`@dWX5g8nxJ3l1 z9Zh`Y%7;dq(eyT=r%_TB4qK(SGX8~5%B*?n64PUVu8jk|SME^_RlwKJWlI$m=q_Wg z$zF=OpE%#o;>Pi`j{8M1@n*EsgutH+{vgo6*Cih)+j`**CUY~J^5cYwr)P(BNW|H{ z7l$eBzqzO6Dq|=rh_{-Cv)2fOwFm9td+RjV&3+i~1e6+YhOXjlQ#QnrM=$)%54Ya2 zNuShb55CdCCTF$TOTnHuN(Hj3NKLyO>)YdfK5`hshqV@F+@H^u+kVU1GkIx;xg7d8RPD73os8{K?AH5l&!k}z6uQ<3 zQq`O!BU8cPd=o1~X5;l#Qs=|AAcUNQ)GG2Q&pJ8W5$g=w&V|zLLJP1|&u$QTw|-;~ ze)_M444p$3%j1%7VT(5J#j}jcxY;Yqiz6}*-SIz(piYb4V z4pVbX59=T~pvnH)ucq9BE0UT8>%53i><&I%5fN3FAzuz&$t&ITtl<;LVs|VkE{G7A zj8dc)r?*dm1;L^%54XBozLqMKD`;HsIh<;1`0b!L36y&rs^MrH`NLR-e5s$egS(VNWt4o+ zReK`h^St1EkNAwrv9+wNe3uw=`)7(cdEJw}tyxKNq-u2CCdM55gh&?D;@Hj$K}@x+ z!K=ysohSG5+avDk$AI=O+Oplzaw3ennNs>&QI;VeoL4%i2JjA&Tyuj97tZrrJFrUY z?B~L9coR@~_FE}Ddwm89zvb)vLAd@znjwC+9QNUy@qxIM=GF(AA8?@a{*KJ9qg*nl zIBJw&&lyQhvkRMz&gY$F2WSL3sP3(J6V$oB34ds?gP~ckXa}xSz!_LB+k6v1ERB{$ z^kx~moE2aQ*DU9WvCQ%)g+;g?Vw!j;8M5d^ANqTq8o5_WLKR0yHY*dFS5i%K$Xxh! zX)OB{y$}$;sA4{xNd~O~)3(9Bnb8fyaz(VOdGJx6u3pewP!CXmFL{QUvwvl z@-v1LN%toS^UoU6w{^`!O#HaZ<+toxl{~CDOY;&}ku`i>J5#L3_dj+Ov(9SVDI}I& z;uw`}>`Eu?02IV)4q#NX>KyuD;pbyiu1f5a2I;^94EG}0)wi$6sOA%1%#eR{nH(XY zBnecnfl@jsTVTq$^f4T5wh1EyQ~XoL>L+`JHZ#1W9SH%Y5085`kEKGvy( z9+nR+3FuzauyY7~FENK>uG02#VAaq@>z`)6=XCg<7NTx3f zTS~5(k{99QbXgmEt`=D%-zkWNCRNAa&VucG&Q!O^&H7C`SIQ5H+j65U*a89*hQ`o0 zJxZxNKGeo+VGMsBiUYcKoiCNqm8_hSZ|v0qgUy+2?JYe=&Dbuo23v(0KpFuM?(M;Zz8R zKTb3;jX2r3#(g=Fq3P;EvkLvV9OJ~RLj;OGtO06`9K(uI>jk=Tn8p#RXromcJjy|% zjSwh3ii!fLXQv%^W8n|NNQD9}3+AL1V_camwey_&UF@>&fDcy9MFx+ZGfI*Xn9PS| z!jT&C-l}1ZZ=In$KPYI-8W3p2&9CmMnvZ{ZE|B_zMZ@8(NAW-(%JvS)uNjD2HI8TF z*OFgl2Xqu+DJy7V$=9`dGRpSDEBIE}8+V0?lS#+~D@Gq_EVscK11W^4km|=ga{0$s zP=c`|NrK%r?f2f{Ink@SuY3;n$$zVhd}wa7`_NqLFXZfm{qQ3feg;QicA^gc!H=)V z-f51*Pw;siX_CFu6vvA|VjO9*vD3-sOtS~B`$y6Rz}3@7aPz-*@d%o}F6m|%%AER| zuh&b&qgKkN5Z3Z-rZ^-zjqjyn*BR$|i)>QO?z>Apc!qiJJG6O!s`tCxPz#nW42KfX z(QKpJvbjq-cFRjr_Ersl3WD`%IB>KGsBbefoeWdDElhYO={VMepk{Qv1Of81(p>m5 zalQU#y;$94DyU+U)!H>$;i%3^Yf{+OiPyeK=qdq8W!N~;3Oelt3(nH6LFJVIy)N)Km`E2}6$ zYRdSPhH3voMRW{xxnI|vgw}2B-sgJfQb$4RIKFdrwrBS`Q2SeAn3wFq3-Hdl&K$dovty=8MK1qwP6JvY;xwK@D61)V5qVFk5Y^&Ck4E zIfxUk;g;Lf$oHhN{L~4^0`3W|m6bJpa@)B0@VWn|e&vnItPV3j_|7%Yb1_-9>g=)E zV2Zh3%>m_mu)KwRv$bVFW>7=zQuECU&PR-DV1hUUx@UjGemy2t*h8&ameNJ1D{x4Y zXp}mf(u7s$&57hlNc%WOSsD+aT;*>=4a>5P)K%F8+)iZ<2O{(o(lb_E(~{U&2~O~; zL0}BD%D4{0vPp=JYl@BU*Y`Q~i_q4y294$Vd+t&6A4?-zMqG05T5I5sy{AKlf1`DG zos*;5h@{g-B$UZpi7ewFd#SfEszb_=L}Gm3 zL2S8Oot`ud`%dAJZ}&Tp`aLj}3(?$=*8!8MBn4$q3X z=a{0W9JwUK`pB+ha*qpTexu@NlFR3lmHtbetWlPXc->+xn~I5ZPFTf99m8f)RmK58 zBUua-XxEGp`E$Dzf4IVjez2y|!#7bTm^`&z3)0Y;Pk$A z^KBvNV6o&E<${WAi_<*hP#!Bzb-=SQWU>AL<2rh<`Z-)jSTtBFBpy{Wau5WNBHb+F zCcs46fiPZiqo6vY9o`KHBUnTmKhRBt_5YO|8l)#1j0%~JDdK^%dG${h6x6wdUeSc)t_ad!&%Tn_z$(NBZ)z{eig2sK2f}>7yl3IKM1B> zg6h~VUHOO%TWnwL=aFHY%wN_Edfb%EVnw6}i>(`>_NFR!u~Rd%5pJ3G?C;6%K7)+A zSu*$g_E0j^hc83W`gJiDD?H1YmzubIP>=~)A4_U*ya|x)LCWno-I1fMmEfnLuy+5& zo#_T`L(7JbO@xw0W=t=inp9(&JWtonw(fy^+zUc=x^gl z(Z{L+ft2}bCqj5#=zIlsYegBqa8MudB;TIR?)5yf*51+S;cnO{q8GjS)J`d;tckpk zghq``I^o%^%7excq3}O+hD@ASWIK| zjwe%%h!hnPnLJ5gfTDyBQS7Av*>V}%;tetzM=lo$JO7wzJFy&iD%(u?jz6lI!{Nd( zy)uuoVf*R5Uy)x=Isw!S-h6AB4z6%$Hw3^jSq0HkS1~qn5Z|ylqqETXS+% zzg%d-cqsdW;0j~40l^zySTa_HE&AARCMl^83V)8GoID+u6HQAGLEWv4Sj!yu?oQ-M zGlo+L?dxIq0A?xK4~sTQv9pAc*+=bM>)n_i`TO=4Q6=wj@d9>F#&TP8`J8hb@9_*i zVp$$Z-f5Lt71ZTfK595K;kLCH{w{0M9*ZNWccZl+wI4?v>~I8@>7f?ZLmWpikPqOj z1Rv*32|*9Zn9tC5>*=ki2d(&8yR~+t=hx=(n{#(-_XnAB%ra6($a^lQ?cEP8PPP+) znui=kJf3RPvyQ0eF3?6$)l8myJV~Y}U!w}*+EED2It75(IN|W!WUk27PVhGegoX>D zq}|Q?*3t^Epvn66mp?)14qHodUfd1RC-(LX6xtBOqGJB#xGIhY(4EA6xJ4DEFt|GS z8=ufgfE%0N_|QUjjDCbFTWY%~qnFxL-leuOePx6km?+@Wdk#h3Sid8mssm9qURU88 z{D_xxZYpD&L@bb+Jflvln`Bgx zFWby0Tq3n?#=d8&3Al3o=oY{$UP?4P$k_MNjBcV*H_jZq-6xSYg%{vMp1EdQ`?%3YC}rfOc<9fbbsd;NX{noW0KeZ9 z4DsCP#`4Z-z5FuI%f0o!)TP@+94o&!=QA`_n_;pc$hzP5<6L-LP1C09B%D=5Jj3|% zY^blb^|LPiPZW-W*Rof#J79PI8BH2Y`0EY20lLKmW|D8b=zv3d3nIudQuw<+IM%z4 zjAf>qxHq*Cz-*LaMHZ!leB9Gv) z9P^@@mnf_ibO)IcL|M(M$tX}%IV;x)5fNF#Qx)Z8c3RnMSifD^Jx0-`4Y^bHf0g!p z18+a$>R*^&GyGz$!Cb8Z{2Jo7uma?I9h^)oTjzJJpyjfpEAn3dQyPh@w%}!dm^wm% zGlOjkd#TJf8{M2&*7k+wujQvcR6N9QkL5Hk1R$NX;}u}Bg9~X$u_|I$L1rTQW}RkR zEp@c9UC*xE^e+p-Y4X44ZZpM7k;jgNxt$|C_3{kT8!xkPS)*<#PD7ivBQ$i8>rmfw zBMris)wuE_Z^xCoWoPzS=Pg#9{q@rLGxxG!Uw=zzYu4LG&NpmA1&J1D3*o^(t+iR* zE~Td4gRkKWsC4IwmjfT;fPQng3QMJ>aLR9`5uIT6ik`A(ysC(9N^K~1i(2DdBetD} zPVkDYdI@NynfbdeK~H7)mb&;keco;2fEmtOD0&Y!t^+u;Dpgx$Ux#*GAyCNqXniF= zZ(~7kPo)Jd8j-5bcd1FR@!K|YR@_Kp#hh9t#-<*o-_)qwkP|gE56N)A$}?tKa8i_9 zE<3usrWf{OgZ`ZRf-q)uNiMOPu?`ccH&>How;XV!-XTgb%YqV~sp>cRqV==cZircB zci5dj4$EbrZF~2qUE~uhjCRK(gR=QH#rUGUuARsrI7n)$W-y z{qA9%4FNF0MsTWTPKHvfU2c(@cO-&c8>!X;OaXS_1~|W&e0pQwnwyooR+vQJmW_c$ z$rl!G$3(N~;AGRtsi(1U=o~cmLW^q^o*WUW8BeD74H;=DCTGrUd#PIGvQMqK#0dcu zP&X<`9!=aoG7rm%EcoQ&Orp&|hh9+y9!#3-!7%XU z`Z_Hm_H|LV1z+H3O)g>4WH@QP`IfZJK9dwR{ZzU9iiY*FV={OS7KDUk-Huyn5QmaEMlRm{`(D|% z=4)*p*U&tRKk@P@eb6n(JHudMbVFLpzHVys&NF4{T(LDdS+KM20dF5w&p)hGG| zGnn{hs|S6;zn$4RZwslguL|^|)c7&;Nxz&LxRcfgA4rosFXQL>z1wx?%VHY2ek)~N z5N9!L+nuAzXO4*b+tRwOdL@;kw%J`{1fAMme9nSe3DSH8>Z(%YK`C{#xrpis?N@49 z+iE;-M4{~V=$jrsl*Ea~@3M_eb9J8@)A+>&V(RKl6$uGA6pQ*+$5yb3D6X`y9gmo{ zX}s3{x@ju_nGB?06cSimoLDm?o|ahS`NMhU2^ z;gQ0I8i_;gQWllI{f8ODsVD>41;M+Lhna>~yH2kSkmkRJ8-9AWzSZ{I!b4B+uyAVL z*cARr}t8;S(*$?#0?1;+p%xvB8F#P zUZF)LhIrP|J(8<4$~0FQM2*I>zaFm;bTjr`T6J8hAkM9fZG2_bz}dLi@M$$?-HEo0 zB4YYQ@F*xeHjZC>uEDm|f8<*&VYJbJ!Ruqw@fyPj&o4Xath}O&)xVi(EfJZds8vYx z-z=xEbDUB-EbDE-j4G3{8~g;{VSG^k9z~qz$|UBxNVw}}eP;9;vJ^yIaR_t$cw@1- zXU{z2x|T_tBM@y%fH;%C0km?-AVQZ3e{mhH1ggIXeqf_LQ>iJUmi%eClt$T}9|I|_ z`#v{oUU}u>N-wqnE$##>`0r*TjS9ZrdWDqcwwg@x!rB2_r-Uq~%fOeEY6-hcx z<{0jSBRvHz2c>T0H*eMu!Lk<}M-n(Yp7KBbAPC`gloxeTj?@u0A$?^JvhMjkx;C6>^lz|52L)G}-Zk058i*sJuxApyjxhLOdZpCY93BK%NZq?R0+3 zLgT*4@px9lMnoOpOCn0sIFclPN_4X4fzy!eVd(QX-gPIB5x3dHE<>s^fL@z}^O=jN zm6^kT&w2cFuGzIR^RW0|8E!WXbvo7Mo0q@73}MO~E_Os1`H$+qFalni!@w2g;MK){ zEPkytyE6a9hJ)(zCCmS{Klv+MPq+Rn{8#gjpg`qn^6xs-Pu6^I?GTQa;& zZ)Xbngf+I{_Xgtjh>#;INN)<>5^7_3*^w=pi+`b9gX=W9czR2C%7-nz2{g{qW@ zqfPEB`|zBkP^;FXoZGb&9Z|Z*k|yB_6Ov@-OdTj3I4-^yCRAQVUb=5aS-2|wNO6!f zn4E7x8y{<9OFdHJpCzlL+=7ythnqi#UPGIISX-J3E(@;C_;{Kz$TxsyA!)c1Qv2ij_!qXg?uiP?uV z@LvpkCjz!Jm(6O#BB@1P^+6TwI6l@3HCrrJ{ELjVVKjLX%fL;fZZf9{ozBpABwq1i z_ABdrJJk`uM!eIwFm6k-8N7z?W55!ztV3ueg{!6z5W(11;u?@5ZQXmhMJ%Dd#l_2M z6t$qhjXhE_T+Wq-nr{OHXdN(5gN_Q(`$$NCqbp~ev2FSKrVsaq)EE}Go^7>^h1s}J ze!~(Os8YG8-Z`u=o?AKI4+v^-AyM%vGV-imI(UrF3~jsmNZmI0@N(-W{GzcG5Yxe= zXst7kAD(fgK!G9E3?2>;wqWu*&oM%tQmuQ#Sr7jc&-aenuhy@Nm!T~EO3g~}fU{mYi+LtFKU z`W#G-%7(=B@+j2y1!$A%P7Fd_Jhoc#PNhnyPR4z#vkO;$5?%vnZFSV~-BEh|dw_c~ z_}fh$D~OnzF+*;#2F0jd1`y#yc)Vh@0w`Els;gB^9L>UGj%ePmRFSloYtr4evwh(R{5Q5jBa);~`NR zRYRxGt`5@OO*!Sk41spDkw*$yR2kZ=iiB(2PvL(MFefn7gk+SD=ASF6{bmYG0#MVA zPBM3>kxAs~nKOJ(5-+2lW~cukoK(Vtgw9Uz)Pa&U8%@i4dFv{djIJaR?-bMTTj6K) zhE6F^Prbsf^?+ps$VGIY!xMd`Af1KLB8$=30HH?e)5#QRnCsTkF zRnOKSYXq|!21SN|MTF`03yU4i&x?pqM*Has{K%|#_N%h2$wpl$R7)-l z3E9f0+Y4hlD<{NA(?;&`s3hNumWlxQ_c|V~WU)g!mJO{dIyV>0)+MV{0tFz(Y1KDi zon01fmb`{fgd{$45IM`fT@8Qx>!MmdXr!S9S3_xTW8Z|BBMeC6 zA~KrX;w7J3_WJHYU2BA!o%N#NiBmEHhIkUoZ*4*z7K^Nvb0P=5!4BZ$#d$#R0rh~M zF5n#OtkgRCQ|Clo57ubk*4U`1zyi|y?Hq|a2HQ?R5U*FoaB#ygfG=6@Lp@1S%;?P` zKs`it9mJwHceS2amwukBAAWI|g}ZAuVoW2q_0qEfdy*D5Yg@w8Sn3VC?QL+`@LP+> z<0Y=K#*TOsK8U%hTZG#Vj6O*19Px)dcm#YD78r<{^A@ zwKfqmR6>@D?o9P98x zVRSHUUSRElNyN^zvWRY-9Yd%NQayZKmbHmL%fca}j`;Ks!rO}6jUr_pTXES_An#+#cy@%mLVMpT=@*m=G*4r?a$EGO{I%={#y&we!pjcvW> z?D+L~LuUp05r|RHqk*A5{+kKcKRc)>KPq(*fz^vCcVq2+i~{i!+6@HGJJ`;I3i+a& zOAx0u0J~+a8b3RVMzsX>B)AgrxXZtg zd?h;BH_;c>QFcIj(^^Sr*jUE=2f>zK6$=70C^j(mdUVF}KdFgZ?C9u=TycJ<)bDqV z*-s1QiM~)#CC1bmIBP`Bjd9dnD%@luDlxf^ibfRUFi@RTpXauuy?VzkkRlq~+?Fv3 z`@Z40YO`U20pXTPwJoH`2TZd@Ol1^_`d~lidd|?mfb-!IN0KsSpxeWjYuo_1>NQMTWaQ-g89t!H|n+*yOl zg%}7~m7ZWL>aYH25;JhPv{S74Ago3hkm32#q{3 zKA=fYih{9t$pd?(N%yK79mJ{W#q|C#ZzDB>Wn{>hIREOK$7ahD^3(7)MJGk;4b9&920PJ;RAaj zLpk1g8on3BTpoN#h;lYj`o;vGuMZiPc;*e=lK<=Px9``M^}~wrFAKhpl1>zE?C)_v z9H7Szc0lObL7Be~R#r1jX^n?uys=9qUWjz6)}H7|F`WXVB_7AsiNDN&RQsupz}jrb zOudQJy(L%e=GbEN>YY8{wqSgQcC>df8@K<8C(KprZDxgA6R1v+?Jj&j8c+Jr7fazt zOYcCT;x1zmGtshy3qxar+uZdA&iJ6cV|>3(Hm0+=1>Noi_lNC8L=&h~ds{~2=~@BjMgoQCcF zV+F|eE= z>7q$DoOQu3wy?rSss<+fVQd8!3Jx}u)L4O8mp`1m<`pKUJkUr_f*I9FiAh?)IiHvn&I=>A9?#Z_9180`ehuy zy;2Omn^LtW@hl->7UU6GgcKeC+|(JW9lLwC#l;*n=Y$sS+K;1z1IGw9tfdq-~!??%2sAb z(^np`X;8bPx#_^GJHU7LU^Izl3(wCs(P@4%yGnZ2kL(9a+zciN!>%;Fy0Omjzs z6Q$qJ=3E4FcUr#X?PI>RRrf>IzA9j0F;v)22yc(09h~R(=B=e3;R|qYxgZ_&{~_!v zz@lom{ZRyiRHP&nK{})xq#LAb5Mc;`VFnnwlopWgR+^!kp}SKWhA!!luJ6D3zVF<7 z&bjCQ@3S||8*Ba6+WQ$c?_Tc;of&a7HD0Vx+#gMO{6}iNtz6c#X&wAUfrqkldVBPZ zO>^s39jTuRpit)GiJbUmJ!+Sa)sUQtC6~IU1f~!i9D%wo)+ou?q{pZIOLYvB)~s|1pj9Xh!Y%H>+UGGS{4EmvL1I=(z)|0cqyPGSLm>C2zJ z)R#zr<5nehJuk)(H5%M`=omRmU;N_@=L12RIw1kmdc@nQwj?zOo|d+^Qm-44`bC<&NX-zxBqsvpWhrxe^U=C zXnvB>vuQEkZNgkN8EwC#DqQd}aEFzZwX$$3h2~ic4Op9d(f2aQTuN;soFDJe0Op_# z`3oCCSA0^V*_T^~*dHEoj?`Ltm3QjWwVaRvj>}hGaax2?%Lr!3thAm$Wx{0L{4W;5FADLWl35^A`gL?I;jN%0M zviP=%>t*bM6;azQEvrgUc0^H-ENv9#n2-@Ef!h@!zb}WD;x*NPqug*8jdD!=`a`TR zWB*j@=f&>v#8~C2CT6*R)=W<-S+MT(38Hsix{v zLlx~pr0+8)1h4`R7EvXn@3i!W+1E_({nzW;Khru+ofqO-Na%mS*^`5wYG^=oWC~L) z-<^`0noFNX&!zZN1tZ@gztnQZYc<*Bc)p&foX+0JRg-u{Lh~d$v}~k`j{MDxu2Bx= zkJ%Ee{2eK3ij33*Zc_yWddCi~yg(x6qbZ6M?@+B@OKGmA8n{+wMk8;WHF=V?6s1CmxcJ;tQK**4l@3yv9p05fyj`2I$uW#mXyR^`(XhJ$zz$nzw-> z8Fek37P8x1)Fe61WsM#4SoA52nKqfWR&x%&d0+jO-^K_WuB+{%AF3@_KO%=;5BYV8 z#`@G3|4!SBZ) zBVH(`8=+jKJgW2V`&w^vx=@ax7xBLUy`F%JGZxBu+ zKV>I`PlI0dPYLX#yT4W5ka!!bs92u4EuCX>b)hwDzHPLpuEeD1W`X6S{N46Z4o_(f zL&2wVJ!WQaAt@~CQ(JFd+j6Abi6(PI`-P<4GL;WEi>%+Fbgxrq^OEth^;Hy)t^73k z1d89QUwFd~0XFui8lc8jDo=_%X;rO?RdiromBp0TF8_pvU|X%=iu?rs18I z=|tlQLg+r&%lmk2TJx?%-Nq$5y8FX58+w#)(){iCyJq&CH4D3=PU+1laPw(3=Z?B& z52;@$SeFdMxzK)Tam?>Cmf=rj#$NU427G$RxfM!hTAxSX!F;9NDE75F%6O$g!#GHr ziv#~92}u!Knx)IMP)b9~G?&1fv%R8w^iVi1{!F+ITL4C}Ne>x%I(VzpKVpEw^3m$- zB?I|RhLw(RzR!{ab*Z|dZBL!xy3m$h0{<}CS z0V;nZLia5mDp(tyNV{X>1)(>lIm_R$a>yPd)<;~8MQD(5PAK~O@H(cyf!_P9D?|Bk zh?>I|{S7sBOmx4+9KyY0KR56G#?x^DUMX_BlD)?VHHH(9kH${pnnFyp+dxP}}F z#)<_SmW!!6wW+>4F&C9zkp94B=6GARq8gbRnYT9nJc>W89r`&%8_Onm)hSYXH`@5Z z=_ZxY63Jwi{sWICFoMiLv&q*gvoI&5CL!!S#$JersrzyCp2LqIbcp})dA`+4-QHFH zmA8CZ@s}aB96g*Z0+=!7#dwJ`{P{o9nmtd32Np$Lf0-S;Y_R8a#+$Dty?(f_JT1Y) zWNPy?=C>%Zk($(dTLC7!+Via%kuNihvMDSYNoAz$?{ACu8Hu_fT^i-YjurtvWR~3n zvw=UcZx9Tkxl1Gm+uMN0$|2~b#GrpfoeQwtndE${>g^hD?2Ot(GYlReZ_-@Moz>)g z%|XWbbaJ55dzj^+_b_v8aG~4-wbG-mp-(6v$0_WzvedQ|K93RO{}No%Ouj5knxxj;=ku{;28#7a2; z1a`PCE>bm3C{u}8}{`Wh&^=`R#e@*}*HV#3j zSNWN+np&|tjxqKcG6&uuQ5X?z66J`)5Da;J$GuSv6evnwa5@J_I)-4i$bqxZK^xVm zJALN2XG`rqu+03a_Rg7T&<5|^9cJo+gT2q4#@a$|^^nVquS+(>!V19XU%Cw~-)Sb~ zmd_jJU>|a(Eh{_@=>0dxUmcx#w|oK|;KksdS^mB)cj`L-d1V;wWDdA=p00H+y9VZY z3PB?MXD&%3Us)*JVt;DeB}3oayXc_k=~CjWG9Dwl`9HRqoxJM7lj#vvx0SJGdZ&^a z97BpKq?i#TT;ao0^*Mw2eGzsH80wHXF(KcCB(HPOd* z)7lew?JWQHEM;=UeaboJx6!ipKtP}&59J%68@)JVGpSE)7feby24z^cvNkL>e_ohv z1L?@QCvZPMA=GP_Kg@o8kIm`BDxKkRx6 zA)k>zVb~W9qRg0E#ltUn+ZFsCUndWIpS|aV$yj^I)t zofURoVqoo14l1kgd&r3*96~bEyLC?gYgU3QLPXuwYrt|TEMQk`)Ba%!*Ap zj$ytnT;G<`RUv#Zs-k=}QO0R^MUa|6eV%-)AN(jAMjtf~>@)#%w!u5|(E7;KM7^y( zLvza2OWjwIp{3sI4C)MEuW<($@pMTMdi^tX6+)@ZAk`$OPF@Wg`0L>8F1tn1zVUaj zVQcrob6C(6{AGg;+xSZh#V?YV2&7AR7lO+{qilFW?~32)R@0ntPzKXc%cT^wW=0mx zzUDBfqX(BDEvvIvA|5d4OGfrR9f8O38^2)DoQ?m@a5aPqm=I0Kxy-v7H=lfIzCJl! zy~g_Oyy!ojxfc(UYdLB;m;e3bsHI~K>`S-%mHgk0JG!t8Cg2eH$N7)Xy8(vOZ<`Z$ zIRA;4j`ds7*P_6_47*>w|9Y5bY#Wds8j$|y<3CNj?BE=^{9$kUe;&&J3G+~SRe$zk zTWEY{w&Dbls0(jmC@PC03gH>JN761o1L-532%Xq-t1i@X&3U(BRMS4+_29+SKCS;Y zK50Y%74n0*^LqIjVfQC2?!?ixCGHVx9+}85`g*w@Y(UM_>0xo|#vC<|+&)!|Oo3Q( zUVTOqNk#tDGEY#|JMy2*VlN6q2a;a?2zXOEU2baiu`SM9L_q}`@WBZnv1E=YbR%b8 zT(S{=+T7ViGEztc{M{&N7?!i6ck`Tx2m7AWri*bJ1U#s6%m+3ndZj5c4)swW%ng%= z`=DpS){UuHK2>CN6lv+RzuAGnFAUkOP8&CDy!L^pWV{ZW$D&G2d#XSfJWkh~aa#D1 z3SD15CZTH4OZq-ht(AQZXO@y9ThBtyt4XYnzt}}hmw-3h{X^WV`%5`6wAl`Ffq2f{ z)k5Gu89v_@ZQs1zk{b>+&!J^FmN}8<^3qMypks2 zf`V5fYt1?=Rh{f7v-s8XHO$Ek_&|u74cd!c_*r5N*$3FX#;rI*|2liw?EFNlKm)?R zwjmnwmi(0URm85$QB+^$q~KzT`(7!!>EJoDGCjUMXx|%`_1%5s!UGDA?MFO7mze2( z&jJQ8O%XJMGT?HFKHCar)is|&u*^cyMF8%5?Do613eV* z>zqx$1*Sh?QYb%GWVgWr+tJmfAX-C0^=qnap;9uaYFn6IOa#+s@3C_h`LT0WfX4I5 znO+)3o=kDD>)^^1a^XI*xA{xBTuhT#k-H#d#nJk9NG1J#%OA>)XK8d%4sfg zYA&*yTrA?txXcLVz9z~y^tuB%&?^Ykiy1rz>^}cE^{$D``dm&~wq3^o#uj)Z#@!i5 zb13+G{uRH{0C%~u$v2{Q-to;v2qPWA1QH5LK}aI1+x~~DM8LmA~wiF#u1D`dxVI>w@ICkE5m~PW}Vc>B>E%L zx4W6lJis`I{FljlRjf<$aqs7^@HWn2t^-{Nl4y&L_g0S8Lb-rVz=Fx ztD@3M06{N>utc0AW)4L-HMbTk%MJairgsh?2aft5Sn+cqvntGht*3NU^Uy*?Ma^9a6N@V<%7HCik}@U6|Hmoecx`!;QPL^;YxvBnR~@{CwWdU+$k~ zD**M375K|K{S07_h71Iy5)HyBhkA>a(pHU|lMBO@e!pPUqp)TzX&s($^fb%644mt& z-VQ7O4N240z_OQ~+aks!CgptP`oqYtw1zt#1v+``O|L-PZS2svrbMuUZV3V5CK&dI zZQr1D^bs4ZuI(G)f`n~>`#KSDvTt5)4v4r~vH^0x!qCkaP7yvDw}Uv*MAVK~PQJer zfpxxq+)QQwIV@gdhm4gRS=|sjxO0@ofDdkq^N9YI+9{i=Cri}y9F|II3LYpX8IfWC z+EHPBP^a;9nVx@}+{ACtDQJVx?{@HY0xE5aH7_IE4QwB2)UNNq%&k_s+PVpj!>Jh4 zpUD6x8&aY3blO}gua$>4t^mGXMid)Ts)S;{=E-bO0WK(ndxo@%SG>NRTX^aQCNod7 ztzkYc0=`uyKH@laD1EUMt0gpZ81fvxGe;6pjpK2b=n z>Xma-FJcZy5`y2WHvy^ay_{3;KjWbl;n?8H>FN7umM+_;;-#*jygb-l)?r$0R{W78uNY9Od=&>e*s> z0v=W~O9Vy@VMlfv80#WAvVcHnA%h>k&Qj@biwQ=zc@AT_2aojyP4Em$1|E2N26s4{=t{mbcB`EOl07Os7_UEc~5Rfm!zdwLH|G7HYn!VB*ibyli+&Ehst zh|T4Q2uPcPf&V2UsCLU=?m5XJmz34)jGxI6IGwZ>e-L&N3sQb%Try1evqOmsX3ke* zLLdyh37(1#=lFOyCmZuqOz1r;W-2*jVRh4fr62sZ;&z_=>{iCy!2ksNa|r@$NpotV zBLgS5G^;MbzpZY|(o9L*%=nYFS_|KA9D$qXlKmQfxhS9qgIgyV?XJH;ks5>0h?<&n zmx!CsbzhS#%a_|SylH-=#OaxitJ=V_A_kxEK++RsS6N$cE^klXZ#hp*Z&9+M+()j) z+yuMOj}xR6c5WUh-Y&Mh~IS!+jkvxQiGfx{ePznB095S(_X4lH2> za~k*VtB=Yv$^Iq}jv{)t&0wAjrg}{*MQ$`XseYh1U2e9GCr94V$Z`_hmE0veS+V;S z4QEQz9w(HYLUofJE;FC$+|Yg{U0N0ka`Jl~QDHsJA7^$ETx@IgOk+RK3hZ76Zl!Ru zC1Fe?{|PN4tEPv=(cc8g(M3vEpiMy5;DX2RtC-oiqM|72;DDXyChvrh86q`+jg8yT zfT)a`8SP#c&K<_Q2gJ==2TPy5>YN!MS1GW1m$KU`AG~b~{I?O+)Z$=ttWjcsn{Zf! zzt9yU!A>X$9B`yA99PiWkO=uMLzcrPa@fzf9jdV`_^{t_U{@tpO9tzp((A|Mh-jn% z+4{5PqX5hhj+P(l63=ZLNoi+xACHO@F|2$2C{CRk#WPX~B`_C!qw|hhvQp(+2Dix*FPXHUI8wJ_=Hvc3!h=1Omq-l8fst*%Er-u*R2P zsKoA$M2?=917iExnZ zWaD8PZGJ^=R*q8!Z;slm)y?8Lcxxfhk3u8!8CHpow)J%uYpm6!bur|$e7?_zSZC0S z>Z&cvM*C6U6W>$N2(^u+p#sL#`?NN7gTv>N2hHiG@{&8Nv`1?y9tun)%p({r^`_=n zkZAMGjtGQhvhUi}*>n00ur5WxrbOi_b4@ivmfw%!__s_qiqPvCTq;jaJ$1;FO=F7APjn7&G zjHpdYd0U~SeA6|dR@q_m2Aslcf!Vv;23(#;n+f}`4;FQJ=RO8$A?MO!K&!-5Q+2T? z4cwW6F+a-ktT^ikN;!J-%1WxAJ}@wYlnn(N4zOLK^y3b7V~RUWD)n;9Pa4+{YxtF* zHAmUg)GjtTrnGtIvhdKgQPB?jqC*1);9!cA-zOXu?64m^)a_l_)xsd3$k&WNFR~tT z9k#WD5anz1pE39LiWAw@6eY|vF&IEke%5u^XW17SaMo)Byg<*KDXda&JIih}ZMjz4 z`Hn36bI@jTt@&M>o>-I+NGl;~Ic`W;cPH#8AT0FIfVy5=cAqf%uhw5UpgLj~U7>0u zfK7e5i{dMJ~I;0twZQrpD2nv}gm_!DlZ@(z*-Pzb0yaHk(|b$7i#)w4@A znAeiQv;9ltbC16#n*LPdzo&Wz z>_AM)O#Dh&_kzYR<0|S2tx~r>otxDy=XdRT$ihR=gmZT5l`&44P^{H)9CzbUB)<$} zm#aC={@jHq%OcymKHg1!NulE^I1jEE3*ddq$0?Z#xbwL-&zj(4=-XdH9Otd z=|qUl90oTJYqg$0cFwTwi|3l+MG0{xIj(Dr*ksH;g@WzYw9DruL!XZRil)%kGtYRz z^rS#khpl6a+6f*}(@yA9zIEMuO|${~kbXj(+aR^Yrs^6zruv(|Z|q-2{;ea_@fYFW z!>JDj&4T~G4F3SFH-@ zRvbs|-wA7MEy0ShKhc9Yb9(J2^lZ(KXzC=VmTWrRMBgBX>AKL{i_sl}aFX?9_k;9L zSi&%P(Vc{RH^zERgb^wQgg->STS!N0>z>Honx+&~g~C^nX~uh&H(*{wKm~VjwlcUu*!^pPgjrfdq>i zu_WLTaRVtr2+BCyEa)pVX%VR zgd!c%URk&EPY@_D_?INnJDe5sadOa4II6Jhv-dAlEw3|c$UIgC&`w+YyA!{U(eLEF z4oJNNkA<-8>lq?}_k1YeT>|LU1fbkO-pLeg(W$6z3hcghW>?Wir+MLhQsK7~$(fP3 z?W?!7WwVsaLG^~Kbb$0Ee%p6}IXCG3E_!mQ>Hzu5@k@u$Dl>81_|SX{1*SLV`to(% zR<6C%RgGyByFYPRVx&wIqw=5O`Rzsoh>zMc7zkpB-4

8-!C>+{y^jVs9AnmbF@K zw(LgsQE(L`q(B@-*J4^qOMvXx-ZLZJ)4J}w6jslRus@B}OtB zE}XsI%;IC~`P8lZfex9&JfqIQC%Ntt`I<2u%9hEk5|NsSmx-D3%P{!Om~RPR4v z6(Nzef;5m7AFJ5cysXh+>0w8cYQ3lN=Lt>2i_b`LFf~Eaw}oHdM>Giqd7PVVkapQ{ zIuk)P^d#?7aWN*P1`toXdv{~?T>HD;-svz)miC=GZQ*&wGn&^jYO8jsWZ{hYPr+NH z3>5F^Q!gkt4QQX8C(3O=4^&Kr4WyOV;zD(Hh9rMcr|gA{>(j5Fl+1EjR1J2miBn`> zGk(f)9BaL%+HhVDm1WQud|X~$84b(*7$j4*mSIOM^R+JT{?2GJ;10b+N8LHNdb_4T z_QqZ82(zYQDrYodfkq|AJ>%&b&&17Ugv|5uDQs9D)9LG%DpX(jxO!|bhRm|GcEK?R z?YHWk-=5_137B7qh4MU@d}LU~0Xfw*BrG;nGqbROWYrkd1x86I(iu4s5t^FI1( zSFQQj1#Htw$nM~6KHdS5oQL=huHn`*4wW)~wu$KR4rPOaKP?8tOG-n$6daXhBo=@2s? zhUEa$TjHCus*PY=vDX|HtI~0PNr{iv*CyzFc<_~K$Y9Yk!Cl=dDpl%Co!j7ka(Alkuq*U9T?yXyKq+^H z+cg}i*o+3X=$GQIsm2Rx$5~7y5DFFIfdi3dGMq6Dh>whXb1@uIjxKBX@>Nc z{{@*Bj5h{)V)lzKh40f$jSiBt3D~Y9eqWY1HSj3Zf_;Ms%zA>`Dn=U0F=FeXsc3DF zziVyQ+Rse1qiK!jP0eR6MTw6R4&2X6@Rz}?FoJ45>Lrz57Z9Uj`@+9?O33so^To#W7=?@7oBuBI-CM^mgZ;SB#9kRclx~WnRNd zif~Zzo04S1-7mA2V)hpBuf{cA3?0r&O&6m%Lc=M$KPU0Ei&G-r0YhI560t9&c$pD+ z^K10QS4UiUU>h-Gd(`Ai&Qzli2m80yQ)40ui(&5J5>m+|_LmuZt^S=lI_qQB%}D`OxaPZWuR z^5YsGZd2PxRpvqWb)d(f8L;|JXC7Eh;#!a$n=ReLRl7uVPep}&hQoMA7b+N@la~wL zte#HJaf*TR*7Eq*DxzG+Jm={=owE=ho1%KsZ2v$j^Bas9^k2FT__X~=8(ZvNJ$o`U zFX}Of`kbSwduH0j1zxF=pO@=lZPig#{KAQ@i}tZ;a3rY9ZYpchd4rqF8LPmgH1`5oU}M5gM8_=mgF~Y+DU9uulH{ktM+2Nu?$Hawcd}ZUFxhv z3&kcKLBw+qR{qv&8yVHPrWrOK!q0i^eU$z{YYD=3Jfrar?6^WO9`U)<*6N-hTCeM{dTG(CPFq!iVLmFUtYRL>ee z(?c~iW->xWeAt)RQ=cdqWW?m!b_b8IwCe#U6A zw$VcX^2oT-n?lWAY5jrrT=(mpJEyjl-)$M2Kpt~&o+ZfknJjB%EL_L4l;hQ}{(&mf z-u{&D4v#fbHLguI`)c8DBH9h63AzTc-dB>F6HG8$5eXXDBPNHL%sUdtSj77RM*z>?% zbH`q#+SZc0FfBt%+?;O-B1s`b34sGGJR5!iXnA3qI9l|1s~D!TE4xqDrNF>lS03Oh24D(rMI3|KD(zzL$hGhI07B^9 z_u3xLCBkd69^sb$i#9bSKInAz>W2CdP2hYW|@Vuxw zGJjkBdVaO5hxvD9E&Cpk7AfAYl}F%E03CTz(F(l7V@bFy3D^r%Ui+{mjogDvq(v}V z=Z7S2-}B&W3JPMD?4p%qpmjHS8)x2*&e5)w(_vXgL(4yNsJsmG%S_)OfOq5_s(?e9 zNncNdzF&4mp#sP_dpg@~74;xCIdkoC3VBTG!2QnmhJFdD$)uBWKLD^&wf{ddIe$9r{i~M$ zt`M+I3aIg~g8vH}5dOJ^Gj1!S@BdWep9s>Cfgu%?5BhOfNpb0Ks}o*U2O(C*L`+h;&r%sYtI0({9`))xZ$Znb zFJk2-B?+*!@_tCEKEB}9aIC&Dol~D6lHVY^CzDUGq=0kOnCJxLKh}8PGu$w^zeg~r z>-`~_o941f<-=oX*$Xb~99W>?H;vvu(0(&dD2NEfRP4PI(|q-5*tqAOE*32X__a@_ z+ltdjD-tJR!|9DDi_EUuWCon-vJl{sKb%?q^7xVTWL(V1v8`gUDJgD<(J8{7UuD{P}epwSnk-RntT8j|DV&%Jv z5LTeYbAglXGbjEOsXhQrT=miN&fk5+&w7|fz4$y>4wku?WCw8YTzFc~V3n^iv-7gq%$%!WzH0*(_883l_pe)(X?x+V!eG&~!}ztiOeWVJCn_ zmjDv{VST~r(rJ+dtKfJE&mU+8fNllxvo{XzEY%Z#N?&lX2hW3A_HDaPoC`XA()8A= z7ykP?sJfw_v#yER8~;E9bY94RvHq9Re+#nmSQ~)V7wN{imcQe7C<6bfsCL$)HOQFZCL9`2tfAH;St82zG-atED?)XKO@6% zr|xqb&4||B?M4(ApD{e{5s9zB4B#_FYIv6XP*?SBvnB*8VMpCnH^1qH75sr#9mH0+ z4s09buFj04vEOtzUPN`UO{@fLhgApZ>fK|p{;e-l!ShqEZF(K3)X>0Ne_dV|RTD3$ zexBH?EhLm&5{(0=Wr1c5HiXCWfs8NZmmf3RukJ~C(=9_Yo*aLJ3$|Lgz&(PKLE1Eg z=C7U%S6%G{b2CN%oIj|IN+mhtt_|mqUTJZkYeTGJcr6t;soLlm#<4BXJqW6l67UBp?lv9+zLK2hCZx#1SWfDC72<1x>#h5xO zSk!kQjtw_wsoP=xaoH_@&oL*_ zr8=o4T8-A1i}!Gxo-j6#lFbqI2Z(R`z^@6G^Q?4VwJ!devk{YKYV(SGq+olrKMAvp zGMo5Hoy>{vXo}zWaQ2NRj*EE|kZwH=5muAaLshQpM8{ppoIJ)!`pKc&NiBYb7*kmr zKKZcWaQ%XW9GW0uJfkJ`jpMW(ieNAn@ntW*e?6yV)yu~^mALo5&Ea|SE3uT;_15k? zM_HK@=gfVzvGwVhP4da*EnD@$*Y!z{6oLb*oCaQev(F4L>Z)92q-&iZCDZkZyp=#c z6j@WAPAZQT2o~a=em?Qxeh;M{x}g(qgAJtfZLj%2Pbu&4_WBwkJILp;HykqUMje(C zz$Jo!u;rTIhSWhFigw#}K@`*!J&_zc6(ia*Z#(-q*^G+{yk9Eejy^_y(8g*aA+q&k z^|&0S)5oR$a#R?Z7u1B=iVig`0^E@WuRxny%0v(LX`THA*FF}rfEp%syI1D5v?#}i z(69TRa|(xSx0e-$>sK1~ky~H#N(!*kS$r!pc-7>M6B{17K^^)y3EJVrzq4=oGK9;p z(2mhqbRCoc7G2lH_h?FMn?=4Xz=sfX5X40NnyVnxL3Z!9`3$;eX?#}x1MR_{G8u#Y zMt9DQ(Um&FLdPsH4kNx&#XWOxNeYsgUR3lgmg>tA+x1r}vx>*_^z>?f~IbD zHWZdx;%FUYuz7V{_q7(^61)B2s+RY9JX58Y4+LTBpOb#0-xFWzC{+B(cGy%b6 zIR=A{^ao_QVz!RmCoM^>p(W)W2~?y7aYi30NK0|gJ%ZHNI5_w}(AXPKv=_EV;iQQ--;?m$DNfx8I_G{O_u4@>P-KhlIf$5#{_LIub4%-y-fjDO zl~c)XRcUPMw^Mg_^;P$E7sGs1cI%>KG3%?sw3xotrUNL;3ZnZ9vgN~Wlb#tx=bZya z(T-n1PKyEO>x8Kkk~Zsyrf2l0Y9cI2SY&>e4A<#dzZKr1bxVl#Dc#SV8J9oPz+CZY z7E0lzOW1nJ6-phu%!-BzUdd170}8)>6;Nr_$U|tqR zhqa~LG7^KEf29Rx595y+ z#ERAv-@w=vQoZ>=_Yj{`n$v(ihn1$I2W`WnbxTG@l?K=O6DB8w&tCFH&hEE5rOKqB zTOvb&D9Qy`=<<2VG$;99#In*4co<*yQhwCO*$7;*CS$+WYzcCT6 zPo26xw@F#^+-o|vd1MRRd*i|K+YN+is6^nx%=$>lTtskFgLzjRp>J5V>uUdj;Doy1 zOku_OYg4f4zD^oG#lVxnK)?kMRrG7^P-cWErXU09`k3*dogic2m$_aE4D}=J*_9nC zwDr>Y_U0{Vw{FU&Atkicu!+a#1F8CEulZC*E+l_0P>k_hKFQy{>D51_t6~;W?QN8Y zmQ!76Ju)+bhcYeI>?tFRAa?sVZxj~J7#hoO=jjWNqpgeEf`xc(pGc^nSslz}_G&13 z6v4Z5Z|XJ4*v`#14?Ay?<}%`jy0n}$nQhyFbj@@#&r=+w+U=muS=B$)h)N>`uJeUf zHL-GMx)Z*Eh)BIf_RY{R2|ix(h54 z=95msfCmaa8M391Al{ZT9myK*rpaX+AUp8gVRuaXk($O_om_At#YEoBAiOh3ao0Zy zud2^Cv&xOhIT{_QCKaLdk>8_dsaDvJe_}%@kBqb37BIJHyyk7UNXKm))3j!9`?Q3!kr`hv zW-wwwkiF%f+jnE1fU*B3VQwz_2l3w%-FHqO{RaOH@{e&=%YUW3-**>&2CDoYlz)@4 z5E=gufkfgcnJazfBe)K0W~#Eg|Hhi#%7{g~7$`hpp1>_&BRk`ywGxy~J2f+BF`4kQ zG;@h&&N!xHu<8f_%N9inf_K$!T%ND|fyTA5tLPnDY>k~k(4|&+w68I@vBPlk8l+Q7 z&a)i6&64@^s{vsjNQ0}A5Qs|W3#*iQ&f3{$NURq&dwQt(a+pzCt;w8W9VtTj>}#zV z9H{l0h$zMaCy7}Zh}_7QJDg`<{!(g*Au*$i?%ca|jY#vgEap_2>4M$5M*sP8bR!<} z2inTZ5-NtckLP}Efjv@k-0wo-N?oo-Us(ko>?;Niw#@E|)7DYCUYB1*ENAUHgqID+ z{IX>~?f#Oc%Gnd1oVrb)4NpAl7-)$87R^2ouJeuIxU_kcpz_#>VGwK`_I@eS-mkuR z=Pxv32@RVib;J-|#xscEO zGsr*T0ZpSiWP{b8asW2ahI0}8Z+HOcpDF(=f%NbC{DUCdZ1-y7FQwf7vvS(}cUSXY z;QyriKjbh9%?)h-ub1^t4FA;p2k-y5QGY5%AFgs*CGgg|Vqkjj`diAcsP>@(0>OZd z@BO@u$DTFH_Fu^FFK_7uiseN2D!g!weogCt#Hnehzo+I#fT)^m2iYubtA!#}fJB{` zqd2JqffJf)>f%##kE<(z7p)HYpJznNo*-4HTtfrSbSuu*IZ%?kQ6xzh_msVA8L4A` zwZN7rY_{XQt#Q4n-0F7$D?2fjDBo3=)DJKt^)}|xp$7uGlT>o3lzHdO(UgYA=HLzY z9Q;OS4b5TGRHpI?RZ8T;*$x`*wr_fyrMo=wnT@d;okibUhtkR1WrH6jk=b&uBtKX3 zhre&h_*!NiQhqfGOEq6hLxmC2ZS%Fjq1vozM2<>f-L!EcZuVG4tCga<0g;(jDR0^J zEzEyIQ&<@ectz}jv;;B(U8>YudxMf~ygzX1B+;Bz=>%CbtML(wJ{o}Z6`j`jB(i3M z=gIO=Arhpt9koc&oxmg@sd2p{so-fA7WR!FR72L zK>d_sn~ZeNcOGCy@^|nEqIhZWg_Bhs)B5oM4<*3iAp!`34CYQK+bD8fMLsKodyMzE z;Z&|#9O}!AiBH|8lpWUE7b1K+=RjOns?i!9<&;%xl}BHz^j4~5MfkyP%Dz0?sSCD1 z@DKC+g2VkVibSlsnAFKI>K~9HkLJz4XE!vCRIU`)4`RJiJWL{I|=FyJc&AX$GhqFV) z$Mb2Bz}(KBiE>7W!dZ)y$s+!<1Ch}2MWF0%kiZDgA#maSzhfK9(^X=Ga25jS5l zI-%aXmmThTQVxXhhP&3?0s&ipN0$LXVCz?3A8vT|*$Q6i^Ec9V+Te8`gz|WNOhAbW z^UTIwv_2aplNDj)#b=lr{YpU~`J2Za(=~lUllu5}bw^&Blw3FP;#tlOxN+=NC`;Y0 z8B*g#^1aBU8VXIeS=3ZtN*ZAIDafORJ4Q&mh-qnb$V*~}p1W!2zn3Ew9_c1_VX0qmFr9w?L(huafD2V*jfJtvp=<(8b%OeT{(@x+n;<+Y|eE zV;nN8Q)w6YP7_J;6~8 z*623gXcXOU_{(4J_6;;IHth0NaAG>X%?P5yQ1}sJS4Jg`_2bf;)K>Gd7ET}JO09MA z0|$CfYis%``R*J(wl5JqyDw}F3`>oWBuQ3&`e^Q6NlxZr+)6mqdMlN;TB;Q=}gTil^an6Wx7ZRlZ)%`+&&_q z6oWu)KYgwHP>$3pjf6~7@HzOfC19w|ykxcgZn|$&f0DaIFj)b2SG2%vWI;q{;#s zOo!2<|4_Yw-Z^?~u|DH$A557>Hl^pDLOOU_+6ju}J?cZBN#8pTk40ARXdcSTu|xXE z&re-bGcPRzswBF@`7;!cm8Z+J*`pqv8lz9Az5({TJ1C^lTIb;7Mo8;c1ot?noC;|< zdMFUMq7hj)j`5aAae*Gj-18KzLCIqeq$+8;3nQ}I^eRrZsvQa9gRJqR{ID7oIFiI9`>sG zuv8X({LgYcz0C-#jOLwcSNFq3r;4^Fdf!>zu~Gh_Om81e41l>kgz({rd@X|97v8d(xJ$PzLLU+(zV;tm~BBfkw*4j!L$hzF(1}=REywS$VU~ z7GwXXPdm$DGeL+(kk7i@xSwGCp~6WN=rn-8mNKhB>ZEJ7gHwl{uTsx!QBb^m1+dr? zo}K+*u4We($k5yV=4MLWf9?XUcBP7H2(ZO4wpLg*#*R!^ZkGfq1%Dm6 zN3-#G`^ni!apb3o7Tiii4>lNGBm(QvH@=e?>nLkf!8+y%VJMy)iR0S9>t@>Q!*_zB zZ$-D6RXTQDh!2#TS%Nies#PJsdnD0%sU3^7JWYUw%`zKW4Fx0=e|aze^--7k6f*Qc ztMndGbsm~h*_KL6EU&ShHGktk_Hw&7o({ECDT^nz&QV13@^-^s3f8w`tH$I|+fxeh zBM6;oQTEw(W4<}2(xG0VCl+(>JxV6#H-619ENt7@>T1_@R^z(6d?W&`E$?T;?hA&l z(P+Vw=!6|5nX`L-jKXgB=rY%P+8D;=e z9X;mn*oTLOBD9R)zExd;gN{seKynurh16wtt?8Dj;;&!MFr#K>r!u&{)rFdXrc&1s zlZ%PE@%JEG7_$zPqnFjjFk_A-XBt$6@D$sLz0!=i*CfpNzKz{*MQn|mIExR{mQs(% z&&qQaPpmh)bU~sBKBTT$sjGSdpW+b98O)T*hSwP_Ty|8!fh8s-fQZ$t)NtFf${Cm3 zO&MP7rgx_J2?pf#`G2In1yEf}vo=hG0KtO?3)x6;cMBo7y9al7Cj@tQ4eqWRci0;X z?(QBSxa42toO9pzy>-7^x9YEg+OuZXboWdxnbp%zKcuma^*S~#Lr7L#+^OF`8C3@Q z+CtfghM!LX<1ABdfBA9bhB}?rV14+@q4bd|q9|^aR=Lf)OTvMA#L#VtU|YWNwD$uX zi<|Y|0{0U+DxKMdih-`zMyuGpm>@E@&59=Jx|xfH)5 zU<$Na&EH6J{pXi4ky#95jiri~77}3Mf za{`O!&M>QS{xacK8$>*PgSy)8^N4uun%Vgk_MRh>$jhC(u{{v-6@~tUf3!?YAAv?%BHj=#7h9YG3yj?8@2uH7tictVS9D1z7imYzX9+Il zinRw66D2|{U#Q0?Kl7IC$lc+Lq$Dd}MN&9LXmMV$8r-1XpapQUS@EATA?8{pO0D8h zj!?6$pJ)cKxbri#V+d@~g|{K*So`cQtTwS-|Hr|H!@l#TMB%?k#VmoCU=N&sJK(`# z3{C1C(%WWqu+Z$I(+3Wp#H6l90zV`FP1L{SR_l9U@Zvk{|B*HdJ67djp@okl{6~;I zE;#Jz;2#<@%{~`8eLznJV$vw=kg?A;bEiFS6B`g|+=h?_FhTxp@V^@IR>5IE|LFx- zH&*9h3D_1MnxnTn+r;))VeZdB^*u11!&{c~;+_WfXDt6_%zs(+Phsjw(jPnjsp$m@ zmRcAp!YeN=esH(f=BpPxn_SvL$GAkhU{`|Lr@2AYyp>()s%H9A8rS*7^qzOR3EC)= zZ!gn8o0ZxG`iG3C5z@QQCj_O1aJPmqCG7_~C)*q;e6}Vmae9)h#>Q28P5!%$hI0^HRoROtM&fR z_%vgc>2ycRcvSCoA1J(2CgiXwOc=xN2cGti2h}vo&Er%0GxfGuhfhA2YDkjsj!ni) zb0db&#JdU(^N(A(A5GRboBDFA3h)hTaebxq8jk2Xtbr>*E^jG-YFAH4o=ll*S-wj@ zHrpd=QYp=~dzsTeV5Q}(34{(#f-|v(u5ZGQrJZG)%!|qFZSi6H5-|>83c#@g42X@K zjiQ7-?=Hp9CbHDT-baaW2Zzng6&xD5R}#=2Qs=ta7*sSPr!O~&l*b?B+C`T2&Aqz~ zPV0~gbPKOYp3U8ks8!#~qXQm44cK2g>TP6XweoEmJ+pLJ>ER?*rHS39wLmjs@1Y{s ze#>%>!!=Jy<8*Ac+zYBEhMn*^>M788>m|*NTQB^jZh{FH7Aj_gsm-B? z@%AA!y@MtmEl#1+3>Yd5*gY^f4l3Ke5+yO7UsvX<;wxt zbPGo1kJ2P@>_ZHt@av=6Qw}uFqxgkX34ZjqhZ3GC(|!KrJ{b$;#9hj)Q{|Qq;Hk)- zS*^M)x^VXp=sB}-%<*+jQ@HaOA71tpnUsHQI405!BpTV#(1N!;qH(NiCygM<0Zmy+ zejWSJMXBu_ZKzPj0RDL6zSw9 zLHa_S=l~`1@)L|9Y}qZN+oE*>7+rDqZ9aXK(01!N-nzC5F{@q`@y zO!$0X?fY7h@ZR#&x5XK@UgeJMSKakIshdUF5k?csR<<}7@iOs^GSyz#oY}LHN^uH9 z+ZeQ}2_I(+#>`Qx@a*PXUD(@ul{u3uhb%KOy~ITm*pK(+J}teSMBl)cZpXJd{gWyR zfqc3Ue=@RweQr!FtU)4%_9|b7)c>@uj4$FN?efyTiU8?yh%&>i^1{+(Ic9ntibWNN zPIx&4npLIuE8c*kHo(zZR)i-qf_=(jiF|q!(equ&3j?NkJ4S-*Qv|U2I2LKV5Tpxx^ ze#UxxS&k7r4lau{)Vq1{bFt`Mg!81}0K0v;V0o?$DfZ+myMkwpb{C4HDS1QD@g&(a zY8qf&E>5LU=0&xypAqD)FmGs`joxxA;=9=+QWy>Qv|ZU12BKMndxUpLdz>{g5MNiV zuwvv_>iP_ES7|OOwGmmpfKCj5DCL=jHBNPImYedTXyfdNQZKGcqmxHr%($z(Q~wKx^5f?!bwq!ZXf0 z)SC737})tsf5>Gy<^Iu~*f2Vp+^T0~$>XH5SU!pG$xh8dn>=GTthc|;XM3)8;RB$4 zq_T^*CgcSpjT?8f%cx8BIE)XD4@w@IN{ELi2qdv`1%)*79vJ zLTDr#ROzX>RBf3ds}56vzfzl53)@E@ue|J8pt^6nkeFSAaoysDPCck z7QWNpGUhxX@3>Gy&c#f2WLQiHdYR0=0)H)9vi)S@86xnI7c8G}W&xdBS zf!!2qa__pnFM{}Y3*KtRr5$0Ai2|^a2G5*v)-=4^u9{Rm-in8I9#U4!Yw%r|88H)< z4SyOkSKEgTjDfS;TI1_=G@sKls$3(m3MfcnHg8I#mx9hnpP^l`PtO&;0C)QQhDp}G zNT3Air!l{55VC>2OC<5OlEM|CkW63~9)E0S;;*=})iWwd0f%ygrp`L3YTze(Zs`(= z&mu^7BjDCSEYhW19)opA;L|_%e`e7QQl$`vlGn4Fb)vzP1?B(J7KG{Y1^HFw*lXxC zu>)(lgCx(w=aE<;n=q&I7ByYd7g|=Q8VODt#&$Lb*s5lfsm#_nDFo;dZ*?(Hi>F~Q z3|K6f*i(*@8imC^bm#I_>3k9tM)DQGetFrHaumz%(+NG%cqU=u6)>dHsT=UT?}GI^ zUHBtnj@$0ik>tRc)YPSPkK>@?C0`;2@b$I*oIv@tnPse7N(Xu;VyeBpZmVTW;`jp( zXLPyVUjw7gYDhJ^Pp+0_ z|D`Tx)%cou_y7{TwR0_7ewjh3!N` zK@_Q72Brx&%eJa5bsC{)aA9)W2OIt!V@**R%-@zTHbegGDI<}V<(S}-ww_w}Ph7@b zSA}vN;$4+R#vn)j=wP^}ArfWya@j%a@B`{WtK0lh2V$uv`f>#j&J-e0M}GYivHWQw z0QB1mfPQ<|4is|icPdt8^u?XeTwBi!{xLqvyGtp0LTs~OPR-jU`7u`uTQKR zb?8p1?~zUpqE#XktNhIbhvnTk%-=Vu?9VAAx*`*!*Fked#G|v{0|I@`g6vzVw{TxP zFXmP&(#bK=CpB4_E#!~}=yeX6R%6k?U0-7g$&j6%iCKI!JfOpiNuU=~!WcZ7@x3`! zw2aOx$32E`DF4cx5Nec0@X4N#dXTX_)=}&0_3_5)ZJ5@a*WM#}J$C%K z41?v-_TbqFap~@UJVKLz2&L=XbJ7!qgg4{(g-U?ab?y>Kw-sAYp4f~#Kwht$z_kOq zA@~g=TR2B8nDQ2#v65Be^_XUf?OxwPEjc#BbMdX0G}xi<(9e{GXSn5)b|wiO@W@wq zfEx$Hd&^o2(b4Cb=Cs$JZX!a_bf_u7uGV*wSJNd2zhGY z4gD_xe`$J>9Nk8pYu(Z$43sjca{)Q5;@ME!v3fHFRTBN`tL*h$BKW(4w$xw2MqU*o&Rkde@6YsBD9$o zOAk2#_zUI~11mrx6xNmPi+8lnG}X#ZIYCZ0;Bs;B%&@VG&q3sL9-Z5kqK2VBn?m>k!@hJw5Z$1{;`jDJohC8`tK(dywiQ@aV^?H~RSXi`0lu5Wns z(KRXkyJmcSA^8Vqrvk3<(Y~=^&Lv%!nt(O~Dg5QoWu5+0is%Dq09~PXC=3U8PmUEa?C5J9Qk8eTIzC$s3ThW zxxrjFAc^X_VB9K4s^2g(V5auKeKwj{w(4sy%0-e6R(uz=)CCVU=W^8FFc>&@KAAkH zyxg(olnQxibKmSUj|<-FNh4cf0=HMtnWZ7cv|4GoBIoTI9;2DGro21fR9#^k{=z$O zEb3VSU&ei`z9Yr7yyPpI=a))vuq_S`xt8$Ew7w;3QC`V8QlA1Kl7ibc=9Wj%Gj&Ta zzH737lycnz@D>98q?GNT&`#st=^Vpw$iCF^Jph?6&7dFREL^@)t2UVO(R3;Ek~Exi z$9QpBK+IB)(@5;2!*P7n#g4JIEppLzOjAR3#|^yr99*x;BOk;^tccA>X{>)B#)!u_ z#gK&e=Jm3bMT=f?%#{&rq$iC1VtsZ6eJ9|&U~tuxVFZP+84+vXgx6|#`ZZSR%(=}r z)v5Yfg?G#iIejnV``{`$*6qm%2{^!{LoxkPHzPpACzZmZbVg#Ok>CcbbU7|y@fZeW zZwUQZ6K3W=%2$i4WhICA)_CPQsm`(X`Zp{}hs=6WDYNFEHX{s+za2-i?yyo}U(Z7_ z{bkiR>grY`q~Oea!8(Ds{y-*VV!hsW^79_O#e2yKn-jLD??nB{bSz$) z3u$Aqng&o$v9q8IuR!vwpjvr)KGa!JfR=l$o}8aKBjpV?)J&}?W6fy;#Q$756RV)t z^i%~zcTtmH7@+ciJ!qF4=t4Q6Xs@2@`T324jujIrcdNey>8}ZedbahJ)X8xPq}p}z zb*G8livpHT8dMkpCJn|zbr0oCOk~NbZcnxt-KKu&%Ymg4{qklY)#imuu#?k~hKTGW z8_fCy?fl28hVdqQ4UC`O@UD>j1DT5tZ?{v2?vY15gYV*`>3*U#8q~05tPh{=E=WZB}7#|Q=Tq<12slUEiQF=$FPC+{H%1vttT6tI5AD{Hee}fIJEUE482q*jt{;rz}`hAuhf%DXU)6y&=of zv1`L&-v@Tkm$iZLc`;P?#E+KZK59pZ*~MjE_oba(5*hpetpEqf5H* z?)$-ar;mmY#w|7akvH*c5&a=%jc@yTlkB{bQ$Z4621w|M!usIB`|Du}0etyVZy(F+ zRJJVqQwcbnbi%C{X1#3|l(>`8?xr>Z;;SyOIUWum#UL~#_4WRklR@H(c-ce{J$oI4 zpf?+CtM0+O-7or1{c*G&;(4ZtxsWrzbo+T5~a7!|93EFuUb7e6kg=Db`F61XX3{3roxdoTKS^4GA zRFs@fP@Tve95#03*eTbIR)f0$7UX{BHc0(a=8MWY6j$x;Hznwk~I$j)zJw*XCTc^ZMO2>KEeh z^@s(xG+ST-R+kQy_+&f*{+UODPka_xGv-ZkvONq{;gzq6OBMXy)1cR&<{j-T(idAf zC?rSnac+)858>P*Bl&B+}UAJFv#2a5HX?`yfetLL{``@8rTX< z6Xv&0*3T|3hAapUJP_3p*GUk}bO^K&Drpq$#N@R}dGl1y6(@`jlb%|9b7IFZwys`# zA-ecAO;#Pgyz1P?7A7j9*kkrqLQRN zw{ZZjm4$@!rot>qSZ{rI0&OxOl#%0JD~)X5*N@%!(&+n{`wf4*8~P+|bCn>}zYbr- zlA(4TRA=MG);#!fb2P#I;=IVL8lQQOUzFloKGvgMA#<9ejJ>f-Ls&thq|@~z#>IaV%_eab$q%^I%Pi(Pt= z*S1t~bj#Xw=B&whC7m!zFzmRRVA`XZ8(*6WYyn9{KmWKAZ!NKU=imrY0IJi9T_A1|{nlps$Rr zVK>Tq8k~Fp9LtlBA{Oi;klx8h*&l2169z?L!n<~J4PRE%-shc}q#R3oZ1K+^r0<+@ z^h(;bo8}LFfyAQ)zT%hECLxZiRym@#Olr%#k}UKuHz&@g`wbJtGSSZ%g{lN5A6O!w z<0!tHd;FQKg1q1(Ez!4Qma2KBi)^{|@P<`MDS<4U=zw1LvK$?NFZ_m)_sPy)8_Q5? zwVhP%tn4G1c!h3Gf`t-R@+^V3@aj<+Si)5FU((z^<+tb!Vb&|1W^8SYrn48Lo;v*! zv)uFX<13_gF++Tjn*_PqugL(I2*5feGPn;W@otSpx;j{1B?|Ly=|vKM_d=f(n#oJ; z49)!wBfiH!vCRzTY}EyjMapvx%W8cqSYr*#z~`KGOLcht?I7^m#CA8BLv*&=-`2!< zLcXA!3V??IFcr`az@6q!=)xQRI*sv!PUkAt)_Z}d`6&-&PY0^57VcGo9Dpe5yBqwl z@YMWd#6RY&xISNnZB|ClyeTdF_6Ioy?2(*7pR@r=0clV27fxtyA?ttxM+63L9vD)) z&tFifC!>;9T(w~Uk)!_%?@6-$GN2St^GjXBJfgW&YLxm(&M+_;!T^5iX&P4CfgCpf z($L@b&8GVa6Dm`q--_fK>nWR1fdS%~MqX3rP~{C7|2*gnA|qTJ)*R^}3(dJmold0@ zKD24Phfc3;HoJM8v14OzEmsYPm=X_%SqTp2^OlBkyDL>f`A58!Z)GI3jljXFQXk zTR&`Wfl^z=5pxU0tlX>yo?EnHC(7KO(V;!Kw@pG))ueBe@uAV9IB-QWYV;^TAz+UuXe(}6sZ_rxzbVi;`0vjFy%WHA4w?R2Oa$Ut;Y)-Lv&#nb$eN*b( zRdz=H?SNRPJ@%-_?9y{)o3If_QJw_CEs@0XbfQC%5E(JdaqMHf)SqJPex1T&S-UZowmbhK4#If*djr_OqG^b-jpLAI z^mKAyDb<{@WwF`Ye(tJ9f1fqb0`Y^UFfQ_e0YUUHk#RwP>J*y;j_|EUjy$?0M6$?`b^v$(@Mo!6Zx+#+a7#{H>l#UyR7v#)dQNq@?y6;ue3yFl}Z^lF}9U z?c53>7+B^e@@NaCr|+_n_~(>_pZ72f4NbBlLvq(#?u$mA9|zASR-tec4w6|jE<0(z z+co5iu=YWX!R9%(MVO3>{1upPxok=Qm5>$ZRUcV-(e{fR5%mx;YRY2OjX_=P%AcBV zO;(IrS_Wu1m8%o|8o4AXVC52xhxsCHn=6?K|Tf&c+p`1xH$8z8Xy^2hq?B?&m{Wu>~7wT-B zuakf~ryy)V!shSJ5-I1&c~VkGtN;K-4;tT3)#2XZ`YK3)iG!v z>9Ly%^)rYhstiK2>nXV5oXv6~8YaX@b&q4Q)5Qx%4h70_nd%!95;$r%@chQFaPZSc zHwEM#6t1YW&%ZX_`{Oud{wlV*0*Zc_O6__D4;o%0RBe}E8>v>NBdg?R(zqGZhHpQc zl$1@bT={otodSE0RYXb>w;vwQXLHw3F#C2HwKi{eO2Dsb)#?Xp&iWs$qk;H{+tNh< z5fTXGwSV#X%<5KSO&w2ld|4SRqaN-}V%ijc6 ze<`PlM88i-Jjkq4(U!+w+wNiye#Dj&m&w87aUzFcR8@7q=V#)RceUEAY30Cx+HMg| zJ`S=tzlvmBy`TzckQ9<@z2EsX?!ix)fMaqQmG8e1*N>gO+#b#6qz$S$3ubWC(wfU; zqYi)TvTInh*-Og@zcgw8=vkcI7VF36&`}F-b47noTfeno+Z)>Oykd0~A*&qs`vZn2 z&U5WO!QU{K(Bhcfc}DcfgW0TkO+EXxA8zg3;2ilNI}e$tCLS4x%3~`u!#BX_%(SRa zn!bBg@gBdU##J&NCXkzm)?Eqi&&8M@)wf-nh#!?fWW`R2u@+0CPLxLw&wQkY!7 zI1~}Jy!CW3W(E~`RogGs;jmZQ8F)k2yFC_jZU+L+k6m&vJxdHZX)RA|+TW(edsI47 z1R>AnC_rYIdb3cqmm>-SpO=inV;-ynd?xTMwlPVUWq~e26Vnct z>x71}T2c_g*`p!6=Gh%*3%%ChNns{3d1AaWHt9MIy2Jc2vYYL0(D7p@6s(x?jez#s zwV3_cC(qpXFCL6Y0(-^vk?e5+Mke;AZNE`^rvd&Hn^*_PUhjs>W=t2Rx{*Z=ZII}W zTSL7DG#5$7-VBv{&f(TYH+&R*1E3t5Em%-csOHdAzh~0>;Y^{FBAmk3fL;T3I_NfZ z@&-Ube^Xu!LlUsTf8xWh5R1P_$%yNRND_cWDdzmy5;EYmIE^UuoUpIwM6O#4Vx&@4 zg=!9tr9-OI!#vB!yMqhn|DcEbG&Q0Qg)`!>x9}^`lJMg@RcsWP4e-3r?AypM3Z`+@ zU)b6?{)oP!vd3bjPUcP-3(+t?l*X-llSweMKJ@bK7iipyvDqi z1L2dKw5EuN?)yjT`KR4VX}YS>qPLl(fshm}_kYN(wr2aKr&+r`{bW7Z7xv8MhM}+R zqbbS_HM%y8eHKe37$f!gI;jhv+Sm(iJ8oCsK_)(J8_tL~ATmA9rl?|?nKZ82o_}FSGcFMf8@(?IUIQX(} zy1!Zwl0l%FHpfWN8lANkT2|boH?Hr-%Ic&IYy3C9+mCAeH2y(RUB(jWp9Wc_SSUCCM2&N@+XCg z%z+6i-osOaW=f?fo!@qknxUO#Dj=vG!R9)&niB= zh~@ykG#XWIUTkky4{idvnsswfaU-hokA@?ygbLaHIFzf)U+rO}$E?oPM}*089h$5Z z9Dk9KvrV6WSS^-DVdi2}(5>;F9tNFA@qo0|G^bMoL?6YGO<&c9kzlpu$d!$&TZ2RLc_xzW?yhC$+_<7Nr z+RDTge&b}CGOPClOigdVjbdEdXIy+6|I2G{bO<2D%W9_Jk#yzwggoDt#6#S4oaT~5azSk8X|GZ(;&@Fl)Jp85?#5c^rjo8TbD{?qFIXHwyJJ$+)T-y((M%^% zNRV#SW}3`#8LF~};XysJ)s9zX*g^QFeIr{GQ;O9h7~6A@pa38l&`W6p$pR0lH%N<8 z?RGjL2#nyeW=Y*4=dbcb=6YVpHJUHB~_aWnn_0Jr@RQNdJ8Lmj`;nJxaM1zdW=na8wJ(AHFF{F*Z2=)Aiq%`jyZ3& z@9S;FiI~<&V|9N1aTIP@7q zOc31?{qV#HNbQit%HeOTBno>8`OsA(C|B(6qT#Nes%U1H@U5;J#|l$E?}Q^52K zXq|C-0Ve)*omF3r_(tg-nvx_!W#4XRY%3q)6}8FDtXOTCDc`v}&;{$0>Ko2d9yRb6 zi4~ArfySh_CO)auUmtf*UB6>>akNTG@p?!O9B%%0E#pDibaKJ~q4hS-rau;U;iXsA zdgT5of2)|#X3df2RhYCjdC$s;67G8Ru!ZfbR$uP=TgQTVcH%xpy*VW1`uZ^;(#g?; zMUuKIlh#UegE{>I2O3XhhAtNDDM8E(IhTwbZG#^xuCkv^wL((#LnI6>&f6PC@(bha zve-{#+U47KsS=aZr3Wp%yO6tbQ%nrwI<)XB!v+>Dip|n7)(nya)$bz&R22Bfn(W^Z zO`7<#lt!INJjlYCy|5XK$j^SqC~dv?gwH=SW)g5}R4tg`ouL^nDlK$^7VI^rtOjr_ z@{6_PXWO)VOJ*AYd3!^cEU)tUn0IZpP51rw$TFOH4*Xl1XxTi9@OP?O)L=>*CrqBIwI8 za{E1gHDG2KWU7g=R_WkWC*Sd=rw3}>#1lq7xl_3Ki%-Dv&cuH{0>1+5hd)b+f2|+R zsUNFnLg~4lq6@SN5EF33VQxeJWVk7prq`=f<8fC94_yIk%XNUM>4|a)z!(9jAb^G` z^a*p--&7h&xZ$4cmA9u2YKC64D66)pfSy>RDy#n@Q3ARF5TKGLG!?)c1%SK$3mde) z^X*X)X3`p9je2S}+Sb^o14y7O^nniUnZSw|KvH>5BBr}LJwag`-x2))Fiub8P)`Cw z+5cq(0M=Ukga0aNS(ydX5lxr>7nc-Z`2JIeKjuDhKmn`YQv$l@J1&~1e|W6M|E84U zof^fyE#dqxR;+&;P~R>jm=L(Z*iNM)@(`6TX&58|5tO5?~wvoM735lIT-weV4s4qrs0TT1?9n!K00 zrR^@f6+`Q;{?nOLFLX=*REHnZEybzpSWcJ@WeoT@bK%`iR7jSt{*s}#8_3{>fjXNC z`=LfSe=c(n*#Y?%ll>tJk1~IPBEP%-c@#iq;a>z6y2FnfXQ;P1hl;;pN{EeEb7kxS0YMf;0-!z7bwNBEf+jtWUQIYuyZR zt-QXm!iq#6ZQoK1^}}bih7R0C zF-20wxs9r-zYvkVulq5wDCtu5nd3`ZhTu_eX2#neVq7m_HHCRTt^bCJo^sS7a<1b) zlazUKD{T$CZMWK!{?wegrZWfPy9QIXhV3@B7jCe|x`sZQfkVk@HZ&7os9&38(Tfu{@W?$aPDj(i@-fZdi6R%ZsMwL*0;C zWf?rYIOD5)+>wy2VP(#hBE4t*v*4hlJ^`ol+#O~H99G;-Bk3tNQKn}z9e$-zOv81F z(mZGds5Rb`G<5OsReIDUb`b=L9Obrx3Dvfmv5rtO0_cikY|uxZGTuThEyErxiYcl@ zAZEGobZ$@yvhi;hes31lNaOnEY5RU;mBM4GXPVOojk|IOug2lP!lL>)DI5-`@clPt z_%dJm0@93QKd5z*-LZU$TU`0jITUyAQ5A`qeBS)rpp@+Urii>tN+2{%%J&gig1z4t zdE;u${(7QOitv=lQ0zzetwBDgAh+o&r)}S7O>9xK@%;sl-S+Jyr3agl4I>R^p1)y8Ll^o<&kzG(>m1Qo9=?f~ z3~onh3Oj$;D9ffX20kz>cyC!w?&N(LJ$n^s-mnWyjU#^x*fO60Scz{!L z;;%O;yOhUgP@N{UE*-?{P0k>{E)2g3E!zsY2H3sR=gYhGDyYlTG{8v5U|rn{;VqB% z2XQ|XDr>kYa5%o~&rYhcgV~!yc9%?=fIv8$Y#Xy*ew^$!YSfe{2PJ(r@uoyH8E;E1 z8t8;|jeCv(@XT@3CL$);B;CiVwB2WaN~is^<8kwvDWX9((4!{NrTZd^&^aihxTmCui#yXKv;_3Ckq%Iag` zA6T72*-On7y4RW`qz2`4V*QecX{#gc72Q942j(`*mqmky)|7iLTDqXrIR3{V#EPap zCKW%p^IbniTda6bKkmwYl%iy@aU4S$$X5C+gfeBV&@!#EA6Bk%bd21WP*4Kg5UEs~ z9$T00&O#c%71-yg`*wHdAzFiz5M*#mmYjVeI{nQ~vkOP^#MWc=uJ}>G`YirD^H=va+oQc zYL%M~VRA_Ly(PNZlE6E-6|2)EqwZnfvF3#`N(pR9(LFnHuc?l%?7J1?Rq%*9>r1n0 z)SblKdvEWXBCC@o3O8XzW>yrM`b$`VwG4#`!|2;|Dx$sX@J_>U-O-Jyd4~;`4|=Tc zfREt*vB=9$+QnNnEb=Sh7xEg?OLx$g)yd{xwE~r&XFK+ZOtEYjAL@rO1Q?BX!4CM! zkKdYVtH6P^9(9_DQym&3&A&v9Z%Dr^b9z*u2W{HyCsVvq0k7Y8!IQ|TD6x-0`@U9-2(M9g+r?Ys7HL~EiAfs~8wds_6jDiV+J zWVxn-$LHYA!$#oG$Nyq zVrZarTm@CO(%iJLm*%LfO}7HuYlC$PTxo<&MQ9CyEV5`)UcVN}5aUK@7`K%;Q+MNG z`$0Spd0H*f=L|LMRQe1JTr03B6d}OP-T&$=cp@MCvldx z*BFe!Esb}5R**}v`y$RwLHY*Iwrv=c*7BkFaH6^S97R3WKJ{E2NY~^nJMBKmy&i#`%^)6OqDCtkYvE z0d`chNQ04v0-;F!v_omWr+23?Hh_XoQ4XqC)-zr7?fuZ}zAe>)jj-Og{G+N<#`t1e zAulE4#0eagMoBUkXkMgFXZlkmIxS;LH|oZ`WtN1Ho!0H$)E;tkbl0(((5T~mr^i&i zlxF9)37-frNA)?Y`l;d0L4Wi*k=)R+a7t`8ugTSYgal-12%(U?1X;Z2!I6v^auUEG z^cWN2BbkRY<7FN@27Zpw2n7P>$v)3(M5D1gYo8lpA+;pi*Y$J4q3C`Ln`k@?t7%5W zFNxjp<6zjNW0nd|7Vq;`S0w@3Lj7p!UBqE=Bo%K~$pRv^_Y|>0x+({jem-o4JaTpXe$D;9zd$nThWY-*-gIdCgf}$Xz z+B=&nYM%|)XEDN>r!(2~p40@ZXRgK7R4Pe>l(we%x(dBp@-hTr{evK-PE=1ha#Klb z{k9L0bQjs&nTDF~%!PUIDWHiD}Z*86L~a)-sFJ?9538l3_nJ~;E0 zJqVHO#R2amb%-p#$xjicF7KniGqDUXgPR(fC4NU&YiodoLx+dEm$Iy=R+hB8Ab-Yv z*r?d^c8~5*wXMy(^_ZWCZD7U@h9lWh1&Qzb7Y;R0@`@u0+_`6P6vHyPx8VoY?BTbl zBgvWHJPeNQH`jH|3YKO8FwJFZ3=M! zjBri20IUqI?r}bFKm?vI&f~&r5gLsbYOcwp@mY9&oYW~bX0$*oD2th|pIhmM)?0k1 zwT*rZIvn99)(B-)+tnbg!5po(yVE$KL^O+@LHIu3S3`vB#`|4&z;(@-^o211B^c31ulG_-QF)=hYZzP~7cJ{UDw~Qq;1l6Z z!|*qYF6$UR<6{$O5U4G&W{VcHsh%NMayn8m4aYGK;?d46Vi!^rnNz=8SaagFD%A1G zz-iO5(B3cI?5>VQK_8~}(<#gG9+(xOLDYYZryoP5;H{||-LkH=i zL9IGfJe}kxXcqVilW|<|u&?IAgb=pPR(ISR9}CLQwW3XUPe>cY{;9Yg!Ea0{Et%|` z@&dMk#<6@R?p~3pnLv-psRLhP5Q%SIkD2d&$wmrC%4w|Gpyd&KNzaa2lxhu+sK`sgYDbKTj4jCM{)@+ooyyXnMFeju5&+y-gS+!bO^}AqU zOG4BpOc?bkLUL)$7DivZ~K5n40n>pF8#rAhJ>~)LGr0Y}Sp{+}NpLCHJqIROpX*K1XZw^)SC8l$h$ZohBh735 zUt#gSWD;FU6cwHZ}5@guea{UE52Hwx3T+P3UR!I=QS2av%?5MqIvZ^<_;3ijEc zpip{kQVpBT&g^*2?e7NX!1NoYi`r0jlqTnbXsEXtQ+h!H#U$`HSouDe*eOir76RVV5d zEypc+Mp>g6qkk-%L6adY@a7P*(ra`U5hSH%&p6gDa#!>nTvhY9d6ar1jq~mzXA8F6 zWEip)(+po_f)Jo;y5-=;IcC&KCJ-Dr8Kz3rcXTNa0l6PJT>jLun0lqEiDbn+Mf)y5 zWAMYg-UO*OPJBxCeF|Qb;|#pm=8;wBTonhSQ#}KKQSc9e0%B8Hm) zXRi$p`PUV>rl`P3M4~mtS2trrC25ZzyWJIj!!Wb(%x^F2!ev^-`led(Vu$iGh|WTE zmEA?x_s_MK`i{3KzG8arr7!9?hX;n=TOMyvNz({A<2T2p-wQ-*#?-$_V_Nv^eqEzx zYuKLx3;%74+*U-d4pBQ~$iGlM601;}I*Jbb#Z~#4abm{cMX?9UiEKZC&oP(32z~~< zorSFia%^7mLR@qW1GiE`+&uKs&5jcZlzjiSsaT|iaoE(EYzb=IF;5<01$u42mzSFc z8JX{oDfIQDEW+Ipbde;gl62RCIBm?dS}7<>$dcHTA;a0ocsNE&dt}J7c|v`%161Ik z2vPe*`&#mslWiq?_C9MLb_M4bot*OqQXK(QPfiZ=Tssf<6v!+mda^6+@DxdHU7F|Z z3=?zV`$45*P{{tGvK(h*B6Kb=wsE^rma#Mw%EY0Sia{1b!Hg){qfa5*$c@yjXGUOc zPNm#(=H&Zk4OfHGsJC&QBi0OGjhV=>lT`PzSqYW}E9QnLI`$pYr9rWtp=5M4S2g)RMqeB2FTM1)&`C#M~<` zEpCEW^93q9lgg+*@3&qe`?=YJ0zBm0BdM~rS8kU2x)<*E-S*BGprFg&Fb)H#`v$hbZO9zwLMWpQ>=3-+8tu91l5l++O9K;BleW~cIX)Ha z+AUwVT!T9N_r}rJ8GHzpmJ58UzA3@BJf#t4mzx*VvsuVL^;Qf&lE>MnA67~hJEL&% z7_B7(^v7e9oMln0{V(bu*iGf~sA?N+n-E>L=!j--xdXtDt>6RT&_Ild1Nx(` zh-;ztX9DeS4+m7fC-iB=t{5-3dYnqH%ezlC&)30Qsx2iuULQ7i2J;j8I%5Vrf`DYX zBQt`p9tOl@HG;xYz}&14@{dJdmD@|Srz-YmKrkxyoxBGbD_EldAgtlvJyDj+Rhl~Z z)9}lSb;Ex0sd%=rJbjVl0uH2pzf@WXbpJ_NBk-JiA0y0!FBL1|n4vgOP4s$KeM9-YkQf(N^I_ zWnI(8rZuO@flHQvvofzb^y~sh(K&CipfGQUjXRYlGH?bZ^A9_gesLy1Ey>t(=_68;~=CAXnniy((hUB8Nr^AnO+_W5g)y-Vhm{zjeOKbreN=9H~ax0s4&0N*ZS}hif$|`{rv7daP z$l4gdEE)zwLnXocCVmiG+2gJFI_nun+1^At!=!qN%B8Cm|A@{3Bam1ZO4# ze8S-ua7{s}lVfLMH?ojbys?go*lp`uC1a`KaOo<)?%t3_OVs#a^zFl&23hxud^4xhP`G{Ho25+hha-(r)Th zX15N}>?YBlR>%mcDoYMah3T61#Ze{$5q|qOMK_dT5=j;e1ACJrt)=vI^w?N-SG&7c z2UpZn3VN|v7%badDJrFNvB_w=6X~FM+O+KpabHz9BR*Hyt300jU5l{Wxo|g-GJ)|( zV~xZ5=DhQY;d;nHeKl0I5KiBsZg9Cf%Uug&{2LASq+3#*hT@-ZCzId)9rFIbS=UDm z^Zd(z6=B7eN+vX$-uD}V8~#P{NHx&)E>=%tvrwDglf-2x;C2wO?H!+L&i7UODdD$%%oLX^S$+pxcvifL_&nCHIBQ=UP zk7_bWgcH=ZK!C-C`Gt-fSguo5yvsiztk+yDmLsPXkb=!vu;y1ZE?_{GEG&Qn-npPG z__S7P8%J52%C-l-+reLpu!#FpPg=W3@L7@IvMumNDBdmHi=N?r<QHXt8xyPt2v=r`iXGdYxH)%^QTdHx5c_5oGe1Zwr*Lfa z(L)oEE_ALNSxM|MI0g$uwf~209K4~x! zXFDEAlEY@W!uRKy3QC%m;GOopyO1tbi)PK6?}@g^-&>|hQ%wYq0?l)n53nl_%c^Q$ z{aXng`;n&MIi-`zqS{5Yke?6da&<*(_Hct@>k^|9)draWaOAr}GQL?ORQUj>4aJXj zlVXaoxSgfiTlT0O3*5uyEf;D17a=U~3}9``oKS`ewwVdA4h6qzbd$VB#_Hmqva1IJ zOOGVzGs~?urjgj;eek;0>{oFBb&|GTSj=5}yi*@tP}rFMX|Xr(SSYGnBmR#x{8y6C zHqK(g@Ei`E{>1iE)w2^bIJr4{SCi7zhe&j|BK|1NSu0_Wtfw-Dph)q%Pqld@^N8oe zj?U`uPOWW2e3h=kWH;3|8hW;w9iS~OzmLh?rpefi{{S*wNz@TMU8&U_XA6E!lL2gZ zx-mHNns|gGe-N> zRO2O@)f!G5VHrt2RH0MVz*MZGF6L+ zy5|+C;>pEov{|h<^5VmMkiLo0^)~ldZ+jifRhiaelE zyHq&!8q9{kXAa>UhTQC#7lM#J{~-zM6CF8IzLVe>X_-~H0bD|L;oaPUyp7exO6 zD&&x38Fr{9^b)krV|C&RwvHCI7#U#f46%2$R+4}HUrzO5rsb~@v$Yl~l9HaU$s>xN z5yRdURV`l&81POnF8m}a_`eCdx+6?WM44u)PYcTGY=c>W*1v)Sf+jOUb9K$^vOtsu zw&N!1%kEge2|H_ln(kE0X&9X#3RtkdU7bt8b(KW!BWF2&3w>gurE6`pa0HE2O)I1^ zwhjBrsIJ8Qq;lYB>{M_E@@9)_{P!b85yHpGfv$F0DoKS;CP3)Ol;zD)(Z@X7zn3o>txtAeOr^Bp}?-etmViwL-HwQ!{sBc3T;!RCA=_u0Po z$$#PeF6YU)+KdXZt%%`)kh(ue?1{yF{{WTJP~yTRemM@dX#Rc+g6en{OUp-Q+X)0O;@F=8Pqiw%KMi zunU47^LH0SPwd>d4}+ZSH1!V{`*Udf)bFRJiWwjPvCUv=;Da-q1kdz`uH9;-BQv?!Q+Igj&Q?k*e(Z@ za8clwx?mj8MW2|`%7zMt<71(@2YrLe;Fw~8kws8LUe*f@R|88$11a9=ZRp#FLfa}B zYH8)Hr;0pV2%Ctwo9^~}7Y9~wX9HJJzBk%Z=qw9=o2qJ8lGaHOE+bo5n=O=-q146J zYy&)Q)kiP?0HfoAoE|Vr%W2zSsod>MZTmh;+MoH6?!A-U*Tgoa&0mWfxw@)WkN9Bt z{G6R_Afp-4+)o>a6JuqrrWnE9WHxTGUYOm;*+|nRx`J~$mMlmWpj@V_2BXxoCBuFE?`|4vgm+UFx`CJa^Xes3lupxy3n&jPad3Eth~~300&waZN_S5 z=DDc2Z$Bj_+4kyFIhqryY?3{#VCzIiGZ|e4lF!d;&f=SZWY+Og0qX+q6Y_P9{{YG- z!F6%Qf&S?!;g&pb&xxCuio~jF8vUS& z=a$@DmnxUjvI|jJ+}hV^{9{jTgnzv zG&c)m&GyRoMrIkNl(z_c(ihluW~!>8Wu&RL(BCB1RJ5Ef#M0McEj?hWhWbg3M@;En zTwFS?n><@r7BsdtzCz&`?CMigx1^XfKiQ|-`CQffB^++1YcRso%2UG?G!e-5a$F+< z$8tOwFmIJGfZkSEL#~Ghj6PB1Vl8sM8z?wBQr1;NA&_#i)c*A9N})>_0i%+0lE-@B z`UpdI@EGyu)Y1>ypbUP>uAexhO`_pBY2v2!-rZkh+FJMQX<249{{TepDp6Da0Eh<& zv8*Brc;D-8zGYH2X5n!K-X`iwSxy_~*L68EiIYGfWCv8Q$4bK1By^ntdgl$YJ#SNAG< z?hKW%*VE~J9oV6N2|AvZo<4J97cWq7mm|rU9ktIwKJ^%;cx^;4#LQY1va4+@SX>SW z{eIG*jr`^?18`PDt0^7gxRA*OEwtFT?D;x?eu|Cb=`FKOnS(VW`*^X%laV3Z?Nys8vL2G? z&evoUq<=Xx$~mW0M*j3$7dGg5tysE(+05*b>RPQ=IdhjeYPDGvs=(VDr*?$mde*GR2~fSwlK9N4rkIZ@T?5g5q(Vtbq>uDVn zc(vtnzTY!n$uTuM8NcL_dw9mckkacsg#)3kd`|}MYuju5Ra`R4>ow2MT?%ask{Mxn z!ab?f^yiaKI`^hL^V!LF81D01Gk0pRyk6m5oYTid@BF5Z48Bfo<$j`pY0lQwA2T!^ z9$jcb2*KByv~9%Vn%87jyhF`u$z-!xWUa?>#gffxf+&*vy>d9Nu1(O~vf{DxF<~|d zrYz3>JIip}WJ)IB=5+ZSllHdesqlRy-&AiXv`vW*HvVK~=ECWlBYQWBn%c7LK0ha_ zY_SYZ85<)stiy*z37BN1G3E%#86pI7lXjU&+x^kdA)TZrxsJtCB)C}9s2ysGEwgZ#Z#gGNWVlRAD+Cd<(2QD@4O6AZ zRAsSfcdCpHsKZUO#eHn+DV#}4BAIZ-bwG#T;p`OaNNpQ0@PGIGB(pm9wXqN!m<7`*f2uO15)dw z49qTjsy3~|t8S-u)uHuVhPA-8!`Z!1M+8y_vM~kUkS|4&*HT9P?J_4vEki_6v=>Pc zzN^Zhkk1cRCR5MB0!X6Cjl`)Xi-UZbu)6QTYm_|{qmj&;H-$lY+Q6Vg@4CH}qI8ZgbBx+b2V8IAw`%bE^UA7-6 zqVii|=H_`?_O1+@9vP@`^04#3-TD6j+MW3%UfwpI4LWnjT7}P~WgurbwU|{!MI0FR zgpfeKML&c%LB5y^#^2ITma<31E8KEZve&0A)q6OA>{eHHOC!W%)yHz>o>i7Px+Q3a zTvAgL%826jALrxpdjNB_$|ZR}syvR6Du2qY_~Kl<&+IG#}`9ARN~kn;k$E3?ei zX~mk!S#r37b^4LJt(pTB__E@-;ucx>E35H2fxrTR4#WPsF z3D_@dZcesmdL@+tBh_Sf&MzHyP5BVm^}54R)x|vor=;|e{r>=W$;D1J)yT2>6@{DA z2+3#EQ|;D)jF5%RpWnrA$phtefkol>%IS|9IiUXlaa0lgBIEE@bM6S&sQ_Jm)g!80 z<_ThR0JYS6eh{gtiXuG@9J`a`b2e1O69(+Asa(wP%rwlZqve&*nU5|!8ZDI{3D(CS zR>?;^Rn-{U;{O0i7X9g@krXXBn&!uHRF4X*Fxt`mmus`Md`bf>SWT6RNF z(lQse6;9e*woOrht!A^5xEo=7D?A?6wRnxwmj(e(H z1Bg{Lzc(5O9WL9WM@uVbsH)@u(yJxmTE8Zyf=oD@ys8-~>K#?V^)JJU_BUM=xqs&s zuq>H}0d^w$fSP|n)++8G0jVme)4Mnv=H^E#!%^6!ov)yI*q5?6pLaFegO>!lm7{4~ z?oj$54qt&>9Zt~F%9pzRmTlJvNwZ^Wscu7b4`4RBYmTG?`TGk~gZ}^|vB>USC;C@O z@LeW-%caY?be{#%d>2XZT_?eGpXpsE`cXHz?&7l@g<-}q1(eHaEAcsPDrCVH(s+#Wm#_0Qw&#t8e!e!Nc@qKj}<~gA|7#5OJ0mAM{Huu+}s&-mHLRRDxUWFQ;PQ zuPUcA`WNH{_o^uAXbciMrM{4j6@6uH+EQwZ7|6}DRT$~(VRTHzXFr^TGeuhfAe>Kk zB-ujQnKVpvyD{3`$=**5e2<9oU2aXmQ$6wH6#zC&dyR&QmRB|VNn3M)nDDA`O*Yl9 zna1*RRCLAdzmwtQoV8Vy-caeJYd(#%u~h7AkkkogkCF;})N#?rOQS&=fK^2CxsX&u z;fBKFMA25$QD+`+AfDvus2tb>`CB;#GO3KkvQEZ1xSGr-Ae&Va%(YLHiMd)eSH13Y zCS#alY!hYDV_mQqK2sW0O3$D)?fkE;GLv7=2~IRB>aD2p^7FBo-G$ zHo6P@Q2zkpRNEb!gPFYbW|^P$Zbh=OuVEG;!uM4YQo{qMd)(;#7;X?pH@PyhdOB(b zMG21#F1|8Pa;lm~4<}{CAo?N3?pzl*Rou%JqP?z#h7uD|97ORF zIPBr(f(~PVplhp&omsnc_Ax zQdZJpSxz~P>sD(|GmIFfL=c#TGdOgC5ct2K8qU1EYJ3ZK2IiJ!Db3S!A)qI}=*Tb^<;_ZM=_-mh|-(ZwT=HTKa?$r~KFXx#IMB2;Xr;C3>j0d#J~rb?K|!_k}dbBcBu zq!AZmb`GTsc(FqW*o(welLn=-MrNTK7(+ z{2Nr)u(xPV9zZ_S*6if+lTqaR4_G_*dAze_c4x<8?A7-zwME2ufG4Wyk;o);k7M2% z#$P7tj1WUqUfbUAkOAuNRAwg^d0Dhz4EuaPIr~%p05HlfvRGDV`OSi|^HU8D_N;WW zhxTvteLRB~(L^_q7UqR>d!Wz>E-1`f%I;PilFdOtFbj=U)!m}x1!Ke^V6*JJk(u_{ z5hHaABnZ_3b8h96@?7S=+N5nUZJ>? zwqpPTtroQ6^Da-FHa3oGb22zeiZ?N>XiYFO#SZT~J~)8-NEZDbD~(nM+ZS5=S@&nG z&BXyT{FYy%A(A^_;HRU4 zHnfs)3*xeg)inGcPZUxD`55bz>PAyU{9M_`=_-h+4Ka=6Z0_rB?oOHrsVfX@V@}g6 z9PX$MbDb2sXH3ygm>wUn-ol3IO$d_JfJMNvZ0ENvyYr8(JCju4(k7@drkIP{7z+yNarU0so5(#L#lIX*x?5UvCz|(df1M> z77K-BF_y<9aaqJu)&wO5vwV$zZB3&#MT{d34myikpOS2tV>o{us4K^Ocw`Q?`QM zaBdsib)wSCcHI%P_^c(CMWL7NL8d!)tRa^`82&23mq2XFZJB$njQFOUH@|8J<)>Tt z^7F%?acS(y2F&3g{XEufivA1H2m$TQVDgMDKk)Kjjmc(jaVo}3+qGb&e<-HSJ1)?+ zRVR>iDbi7!U1o+QhSo!HR|u|2!ksja^u4PCGkV%NgfQ_oDvnEl)pBRD&T@gqNneX| zLT8&`xkHNMir!kUu<1NiC^C@#Nr| zB{?B~KRzZn8(5&$f=5|cU774!E=}=nTS?p_9i?Jx@ih@cTKM}LC6&Ci5!%N7<>|OZ ztOu!${mRvxCnVjDlHZ&BHh40%q8%F#fAssk&$}#JklplN}R2umlTO?v)#(KS1PL@LI zi5nSY8G6Kj1rRcjC56S!@mw8KE1J(KhXD`$712DwW6OwLNrAqNuD35IE)}fN(%rW1 zQPjsu$4^fi9uD$yRq@nI4t*xgVl^d$KLYa+uu=HWxC^Dt7z09h? zwqVso1Wm^0Kae|0F-O7-lDVLlK&fJyNJULSBWHZtueXEWDaUCEu-x*QYYRklPL@Mv zF{RGz0Y)k+12(bk8<96^6_2Tp$(_x9EQ&9qm`VY$wySGVF3LAZ<}kQ(@ajim^39;~ zYhv0aNg2By(B_`bE>>P-gpc~;3<*{)$+!nuWW3g$b(bZ5b58@v}rxrK8SZf1F=_k6UD zb4~{t%T;-s`xn zM}ody3l7sIvTLppEq-Nkp0kjyd02Hu>7B@TrgtVLv8LNu16+F-Q0hWzbIKihAYRyu zoBAr&i``hQ7rL?#`&zVv-2N+@2e`SgdyAU~xT&F+VjColX|sENS>4JG^zpjel|Smo z_Z7jd8925;JP^ijV7IHp<9?&PRyH=>&V|DYXOuH${5c0TTArEG8)7&Df_b2HC9cHG zYOBj540Np8^4N_&IlQHWw=Qn0J$Um{Y@Ycg+1^X;JwY;R??FsCRy_Cj1?7}gQF?nb zXFGHwcg1jBECG&VF6nl9Vsdo@DyUw|xvehL0=PZ_TLm-e*=rwK;Tmb;l*tJoxs2y` zASvQ?J=$Hgmy#81HJC+-7Y6q#n}dZU%zO5Do$BFLxR3Sj;>kMzy~5y_jD*MJ(Xvb( zwpg4b$XHq1lPOqThZ{>vk8X-nO)z9bkXT#ZgJqGDL`}?CRM5wUBFf@+d+ezuoZyZ( zT%*Ecg$a3ib`?ugNnUCtl0$a&WUXU<u1Nu4XLX0k_Vak|;5{{RHd9J9+Hg@uRu$8Y=ni-X$*d|V$>O&M%k zZeyF3?zl22>2{J-Nwt~?+y&Uf+qj!4=qecKrlXS%2M|bM&ANX%aRHtc=yM&bMy$hE zFBUz?xV2a(V`OL1aJWWFxS|m`l5L%YUk)<3KyZuR%I8ytvC@uhIUJMr-ABQ)HjV!P zi(+K7?6J!$9{&K&e$@W}IyCMxPr)?)Q1^sD zOu~NtXvei1Akl8hD`q69Yq&e!*d!bRnQGpN{F~e1eQ$p4aEf`r+!}~C- zX<+@3Uo)rukY6#S{fJ*MrTvRn%qf3j)$`->`=B&3fEEom8@!QO!5 z`;;a+K?X+8AJ!F1!ZC)+S{bsEH+sFGBTu$r@~7R|WDne;E|1beT^qpMjQ&j%b>TSi#0EJ=4pub-qlNej%{{TYSYjh-*7P@jcVtz}W-+FKCS6Amn0i~7_v zmsECl$7P?CU$I@!nV(p%NN!qf`G^1s%|8$$KRK>(u?hS}+Nzj%LhLTLF5T*L0dd&3 z79uh#XAl}BLsW~~#bM{R z+Mywe%~(mZdX`$C>cg2C1a8u4-SAF|2?>a!*0Wb)&sAWq5Cp3ZAXS~J&qUdw+`T)l zZOvPHk#V>b>^8&M<_8VPlfTR*tCF-?@n^(VNyzbS14(CE(KbNdP}1tpk41}TlE?tG z3DUR=mC9)z#fC6RR(fMY`EFQh4lI<9q~;CFJdpfhw=3rjK(?X2D(ht4#pw}n1-9(s+ekpdutsxeO&j>~;?K-u&VZ=!3t1Nph z9>UCTCh;LF_(K#@KcKgnbEfpyOFLw9##T4L6jE0k#6fAc`=Z2 z7e-^Vuj?CXpGfWud)zM`J9?!^?hmHLO=bY$rsUej7|D)i%FuG%nD`?n;G*_^gtt<< zn}S{%+XJ+9vrnt4F*IGyYj4&LUld~U0W8kA#k9~TjuW9blx(rzLD;0Ejv`Ff$00U3 zC!4zKfZi_Ho^T?OlJskUPS;@O)hD+5Z4O3GH*t zvBx{(iR9lC0m%7~Qqf3YYnilj#{Bg7d{dcQPc?gi$?=T+tNJ3d!GAkmnvzgju~=mUDb1IsG$6RZ!1f7vO4j|ZE}0lX=`5NU5k(W57}23h-zCa!ep;r-3`MPOg33oh1_w!- zjh8Xr3z%2q1DtX|w@;NSMpQe|jTM^wlkEGaTaPlbSHNw@WXD@Vws~6$#coZ|**nrE zgOi)N2!I{DS**CPxm+$*YbBBj+ZX7$4i-5KiL?X_)QJIEg zdM=9CRJ&&Zai!DCEr#nNvnwYqa?d|H{CDElh@!PkGqgN)EEMrIhq-p3()Tu3X=1U- za^BR_$Cn;iakeqNG(S8+GW2;MjD zD}*L%Aui-JIpX%YO^eEDq=$1IOsQ&G_Qx@gJ)3ah+>hgvXZmV}0a#fhE@i-TS@5k& z0C1H>fxq*bzu{@~>;C|{0o*F`2A|E=7VwL^PI>%ODJGmtCzRc%c?jb66yto=6m=!z z1sh8XcP~d;=d-MvAvBdTPb(hW8%+jjucve}iG3}Iu@^^c3^2oN<|=s^B!PlgNZ@zq zq7QLvTH62}stl3NBX!D>XvA_$ARO`bD;Oa67ePJ~ueqw5uNuv??Q}0#>^d zc}ELRV9`xX=!2o1&U@NT?oOo#&k1wd(9EQ8$Z5Yc*x_Jf8Zv7}Tv{NSE17c6Ynp6A z*il9p-A?j&{Gw<`kmhi^BAVF77PMFa)SnGQL!x-Ifl<%5sh!bZWF?mnW>(2TMBw8L z1Ue&rQ1+?jeMM76MYfD&wri{`nG`Jyjes?vZXYhg6N^c5d6mV-7v>?}pWo*-*zntT z%1707+jV@al*?6X`GaUKJC;=AC4@!;RolkKIB#0=@S_-DJ*w>00(stMYT;RSd7WWp zqR&-rc)1~2*(_7ZXLTn&nb&i7D{+B*khuh{%O#oO$#aV5m6V?q&qmI=u|y3@$*Y%U ztQ$;C>_yL;W*oCzFkrnz%pY6{wkrgR~UI0?N>RhA#(ESO~P~*&0LVSt!^Q_4Of*{ zx0X%V&ZTc+f-*^krQ1Inqw!x$*r$QV(cripzsce=QHHX8?a&nFzbCiVvb~O7Ym=W4 z3EUrCakvgm_k?NYdw?9M-@eJGXwvm<{{Y+QBzHDAu5GJ`O-DKz{;8+`6b7MntDtKk! zXa#OtF{UQnIo?Xn4-&*%h9i@e9W8V+vW_rqe_7TgQcV4%Y={d#XKa;R&*1+6Er7^L zd-Blcr}7>Hj!2@l$r|LPX9hs%Uo)aOFxuo57;6X(1JwzQh+AWcju!1zan8m)qC1RR zvsR;yIKG|^E9c;{&n`M+D?{UGa5o$BPh>*_Y#s1Gmf5FA5t5CLqM6e}9vj6auGG;S zRjj`|6vvXOO*3kERzfjs#Mi=_-@zOr)`5gtWY$l?yeB3d36n)N6cm*-&K#$goo>A& zp3psOu1kxX)>Jp@ci6HGx$0_{7#zdutV8|_lcUD?@e5*Mu?vJ|lCq*s52f@snb_|C z09iJzoFg?Y9Cvfw7bLsHE(oQqH9|?4`6bu^wIFjxV&HnpdWqzw+L$NW>TzT-cNJe& z=euJ0ut43|S(W{!>x4X>XEtxbq8N`*Hp}9v+jmA=O(xzG>c|U1Y!tv^BNK@ivLd`; zc;43PwST&`f4H3J0Bj?13OTK8VNFp5wvDg^i-z3V>xAhkE7@B-FbU$FtQ~o`EWhr! zHI#3|3*a>qWqgk`eZP>$_5S4l0I&CcVi|KbOIU2## zQ@pD_)ZaUk#v0vKroM@t++5OEG_4PU(5(v4t^NpN`3x-ZLOFSR>_WC#X~jHZ<{2Cu zGTyAu}ygn>8O){3^8r{KcsT;Iwy|BzAvRL$lg?RZ{k=Vu#X}7FuoB|300reS^nlp*sR;cO@In5|BHvsDC6-6| zFDODWc&aDg8@!q4GpgX}9Mcb=lMugxp)PrG6OUk4jj}@M=V)!W-8wdz`K-b%qK*j~ z=a<0pWbMsJ9_cTQ!c4beOs$$`jg}D$ZPx8dVY6)DH>a6-PL}c>`>qzAF?Y3%8KPOe zj3>Uz>9v(OUBT{t47Jrhn}aQAW4xD8)lu2DxSJPRW2*9)>t#?J+*qSFzgpn$D{Ewl z@M-lzbu3Yr$>mOWH<~V~q+~yfMG?;quCn17D=G2KFEO}s?@XEvoix+YoF`1~6%A~a za%_u(W(DTig(XPg6Scdn1h&fgWTtdd2eI^#w77jGg{>!4(T3I=)KwTZxG%{Xm1fbr zKH6jc3GDJm+_a8=@KYb76_EhpJBp5)Cl_J4E;_iAa#cC9<(ZOZ0+ zQ%reS-F`7EW4@Ow=S*KYV)@G#&RD*3#q*XgoUwf6i{~-;tg2XjswXgqG^bART-G-B zZmY{UE}_))*28B=SbhpO%fc69UCJI%;-fqrS|VdxpQbH9yM#rr{{YN5s&T>ff+Em% zo|w0(U+|Cr0B}?h(pCmf9kCs$7hlptPyS)bI3TSJsusKUr!+_5A$@*w<>dZW-z)lC zL)X@Z3hZ6g1w~K71Ip!;yOp-n;H4T|tA{tm869f`M-XVT4&<*_#co8j1X%stO#ts( zVEg2b^>v>f7OWC0apt=f)$XnqTzad$V!?>4H^Rkz+;(f1Jov78@jw?G`%uRG&WiZ5 zSB<8{a;_|}I!rz3&Bu2wRqnGZ@rG>`gm@9a3HBiRh7iHly#TOA;ox^BzDw$WZ`iR8 zO}iDHsVS+Q%3kDq_?X=@Ozu)90(mLmaS{Qt7vjxbWyfwXO3R3&n%=QgI|{`Euf-Es zP79{HEfDi`;v7+TsPJ0&6F#a493ZY}T+p-&m=`cCnh`_JaYtzHNObcsyj{D(yJ@0n z>}t#d>|UCkj`lB_F!mhKY%LMDaA>mJ6p%|w*Wfy~U49GG#VlvK=w7D})@fdXrWre& zvh#FUpH9oKnnZiW)^s%g0J95`M^4ZAVN^!fVhwrEh%o3-?Ec=n8L%{^M^O)|>-Vfu z7e@W3`DQYQg%5+w+MzP#1 z_sHEIW6M=~t`!`S$+ULO0Y42{ts(5Rd%|ax@Zgf1I^~-@%4|^Z;B7FzSPkxIj7vv1&?Z(Zkq=^)^4EvjRk%3!_PGP>ZlUz-%R&#^e_F}wZ6az&BPP*p6^ zwBe?u4`aQ#s3}`3L#iDfK<1>DHb=5(b8n1Z!zAbg#m(3hqf=FUzQKa+J+hng6o z4LKLT?&EaQ^G8ra8z*B<`vm}VobfQYb4Ec%$s9}M>dhD)*S+G{t=x;@YnfwW2;;+k zP7{)&%K0C;T(D=oV~do;{^WR@-kaUV-IcXt{2&?p=OvZqr4Z$ySa-Wy+Dt_}${J^L{+|@kj%k)V5JH z2By63+?^PSqa@G*3fZE|^#Th+lcPTEK>vC?LgG3pSzgpSNV%ut;99jeC z--{$JvRS6HtfmZ2FCjQsU2BrU!mzkzjySOsy&QM3&>`mK<~L`~UyNTSrgtElWp`v3 zp$j*QuSu9(m7mDnxhyhrf-QWTHw|vR9ZYBZ%HuKF$9jp`AA6UeYw8bXi1{>eLf-46 zwyJ%)o07YUC%21Ru1T`=RWdjH$ZfDp-q3)mh4FTb*W$G?$a=4u%n+|6v9NZzdP=4r ztC~9qWt!f=zZ8ZjhiJMxdZ+gTV2LMQCK1-N{@#%7Jd^KSreLsG>ICIH$0LPAhrmhjNo;(%}EKi8i-qs=dh>3(S5HVZ$+k-plf4*tWS;1!Us7V2oqyu z<4+8d5N*h1?2nU*m>>ErE9cV<$28|uK1n3Yl;XHX7s%FaA{N9{?Tx|Vfr8_?47JG! zs~pGB#`5Mc9PhbFKL$87P6pGIyp|wN9QEIH*xSrzN>CeoLe1<{(^hh#f)N{wGtS7@ zQp_3*?igLwbxTO;+p?ZKSKb#0$t2eDXIKXB3WkoArbt^2sustJ-HTUdIV!< z1&0h*JiY1(A0E#U5r%dJ3m(R{K)?=4R+4XP7qz-5orJm@SUu3+B_H7#1{-o(1(x2S zx2KCv(yjT5FRY#Q{{S?x<3Osuw;%ri5GNK}F7$EV%Ww=JUofdDs^OWAwT7Vv;=EFf z@4D)`xz;Uky8?8N=RDl;$@JeEhC{oKPplMl=9V^fOKi?+7^@B` z8a)|rSwL4`YlqO|(&}lb<%GWob`tS%mr|9J2I7c}z_suH0B%3>l?y7N+LyPIZGIx$ zjrS*nc$?mv-Nxl5xS4Ft`j)`N+*o>%+_G}nN(L>(I%{*ZO_p8zxU%B8U5hR(mAuBr z-AcVkxNuL2+_oJqoas5P+_14SIrJ&cYb^U}vss172s%dQSD_XK26d)F?C+|$Zgx&# z-Nll`{F<*B#0t-dW6@`Dd)3X)wG&N~S16`!16(^-q>ZiaN6GX~0B3Xo7;{lvjT7Cv z$mP9gQ%MIRnBr}clFqto=QfY2KV{8LFE$GdLlf+sHLZzevh(v=-;6)0G>73K66a!n z79hGNmvz}i8{%jL^&%i>VX#8qBNx_8EYP>9H@Re*gneagXWgZ>aaV0TcshzWTWLLJ zARBxx`4Pp`rag(aIxE9a{^C#-Ft$_Idm;p;7JU{jRo&X;+hnrwR&B{$8CV#uJ=8-dWZ+O7nO?raqtbfUoQ&5>&hjxN=C<(R**=i_Zezh|=M}eb> ztcb~rJj$bN+z+#-n+|Pxutok#>Z+I3NfS$+asfUm_#m=;y%?18l}lQ1X^zaBM z@i)CQJNtoXS~!&Tai)rXiH z5X4Foa~|B$5}QuZy>gJUX=X)6UUORKWd8m*$O=25xP-?$Gj!W^DLAuD;%}ZD(}b>) z>h8^YQ*7>=u`Fzzr~+8P#w~zNL-63inr}e2tRcqHfjm-*wfSEdC2ADsgr$mapQvYR`)4t2|2St2|2S zt2|1j6F#ZYnOln$^uL)aw-Lv&s)3U+?bY6@j;06$TGMF&RP@l(dca9%^{2}mFE8e| zmWh%n1kv+`EmToFJ7Dq1Avi&D(083x-+LaUCnjEt7G+pypB`c{n~Ih?a^q}(?NG_W zSluM9uxoO%j!4{Of%+4EV7g9aRdi)_J40`&Lf44Yd+P27*5&Fvl^Shlx_b2;txNJK0dynR@;T1=_GK? zfaUEfNL|74Ff!O&U3^K>a73~}ExEX|DmprfX$J|${5bm22Wr_`>?C4MbDZ))7rT`+ zWDRf--|bkzJ>FplMB6^WaDyTkfB1We@499z#uRL&+Kf=rQ)6fw`w^)87VVAoGAo`B zxB1gNql29uA#v#yqM&<^>q2Xp!S4`a7^K<)08OWRe-nnOtp%;#y$pw(L$bFf$TDQT zbyOQs*EdQ_DNv-PNPqx^;>9hv6sHs@P~6>vyA*eKf)y_kAVEUV;_mM5QnWyU_U3us z@4M?=_pYqToY^^ZlKe3<=j{CxNTI3jIj!Ycukup55XgZ}FhRS*+j$W98(*M)Qo(yC z$KD{pAJSSGN^be1QNX4>CLqaBRY$B3eLnFw2Hf4gMbEGk$%a6m&Enj*%oe_@dK*4@ zUWczdA-3xOqm#{i#LX&o_&{9*UUJ1(x;#zuNyRp2jNmSi$)dZG|vfFRYg2vQDP;ot1>aS{2KRj(R8RHTq+fkdWLPcFgg*?tf9#321S6omjd}cq^21!v7 zo%|ftX)Ri)Dat6DDZMvzPD#@HAcr1P4&+VC)MZT%aL8Q#QJU1084444yIIIs6T@d* z#4fq2FvcRrbjD7|HW%oqW-*Ic6uH<>OP5FA+uwV^i9=N~gM2oIQ^b_fXaA-}qn<^> zMH5vz#@lrHE?{3`uf&F0Vd%NQr$>&jXwB*wc}XQ+#Hqf~j&Rhema3}j@{ggOtq-Vt z-=LG0+#k!|W~q5ou3HsO?~v8u0-i)94*+gTZ&@4kUIo*px*E*10d+5~Veb$1-+kH4 z($k7p{*^=_^J&sTEHfx4ZB(qNgY}IL}5U$twvz&K;~=8N<27Q}20Wq(>SNP*UoG@Ys`sb5(mJixZD(7Q@*+dEo%K_}2CK0)BiQ39Zze`Uy> z5)^f3C)7K{xKNY3rW;|DG^j|*WgI?8L+aYTxs7IfK1KsFp8&HZCT>nxDZaYa zbzWRz;DVCYRB&g27F3sUnh#F0hO|6M$O!d#;%btb`QDPWZ;AvZiD(KI3S4R$H~XQu ziV=!sJ-*aRt#r=4Q;B;m6tyTFsMhlx56aw6^g) zKe_3BiX#l=@7`PYiL1j^GK>pkF;Uw@m!9YxK2vs%-NYGEj&Lz{MX%PRjNx3?qYd<8 z=rG?tkri0ji{Fj5+dkbMV4YJGV@;Q_>W`)RGHIN+j(`0TAWluXdThyRSXGZBQ@9s4 zfQLi9T-q#^o8mhy+*D&nJeU|*L&N@IxgAyg?t3aDuJCxfcMe8e*$M^Cn zsU{j_hatW$lhKhX<$647@F#uVC(RDYJ~d3+cdToSx{FuQwxuWF6uX1EvvSTf-usl; zZzS^7c&a_GfW@bc^_^5To@S~9u9%QCedP=PE=w~yndDLgNgInxqLSpJVABRav(u?N zo+*X+gs@7uIvwQFONEf`5x5ZRwN{CPA3fgWeJYPj7E>2wKd5~=T-U+hJykO7d}`(W z^7QUAip;$bBC&&huJQF013oO^pXw0LdEnv5Edb_MTD-Dn>v70x|Aav4WdOvJOup;C zz009EAeFirEsq=FY%-y)e8Xkx4EnXT`$l*OB^3lle0!s03|5ucFqls!V=w7C^T-7H zK4?%(D3J^-6Ov!JDJ11C1h>F{F^@)_u=_&1hp-r&?P$%=0E4|+jrQyT^BP}P6BB17 zO;ul02inW;BJ^48*aR39ihbGRWJFmR?FQ=$A1CsT96!<%;d2;Ic9$!S^|CI2F-?P@ zB&5%_zRhZMX~*d7+|>k(5|#YknTdE7&_kQ7l;w2P?9N)uRozkl*DO|=>&?#I5UX>5 zjalG;-Y)Gg4bIsS)4-6Z1!$XTVb#kVig=dNw%N?URS1WJA;F3|g&q5|_ApHDO0?%o zMDygU!mkpnG$LMqVcG9^US#erpy*Cbe6=3*IjVtLu;oORt@4Ehifj(uFozHiyI6Ok@bf^U+poD?9JR^pRj$xlHCNfzS#qoWRF zX4JFZ()gWBD4(U^}mxSR| zT0Xm#xY6Bxqj?sTRpxkyD}ldE5A-(bqGD{&#=WE&5I#{;iO;DL*^??H2Bl(B&40VY%<_$=!{#6clq58m2~8 zY!G`!2viP}Ez??N8sB#Xo?ZOKh05Kkc1ScJTuO4i%_)@ZgLCN6bl2fr0jP7o7tGZGZUeJ|kI zate(10J8p>I5V7CJ8y~j{fofHEnzV3RCy`K(Ya-HPTdIqA%ZbuNKkS}`E}aQ2w@`s zHWSiPyIf_#1a##tc=G;_7gLUbR%_*VAJP_f-9o5{Y!1-~8VW)awByu4WjN?zEhOaJ zoD}+H1arl~6$+F*o!2E>odoJ#cvU^ivGe&{2+v(3SmTupKh@@S$WH1E!7&czgTG)EUD^EXK`n%W>NHAq1N{o@yo*8W60ob-WzD;$BXOWg~c@_ z=qAS}TdDWr8^$i=r0dh_pj-t7zbT+J(r@sej&b>BFNMofM5+k2=KIddKA(T-HPT-` z^j;&>_mXVldz`Wg_(mKv)Fk)XaQ67mr@DV=KRkaKO=;vmNp<*iY?61_pRrJ?htDxP z0sL7zqH8ipJs41VI))I-tarE0&3^d)2#j1{hs`4qYf`*%8luOOsT}=t&9}*w;;{O& zl$X+5jnYL~!-QB}Rp*VSgGFlI5zTT3A?>raC z_Sl*zJWZs?9g^jj&=^7h^Qn=x_|`D^W$eXHsB_Lq$i73@9<>f-G>CEl5CbK&FkLif zuk*0eSNxnv<3KaGJg*+y&Tn3qHtO15ly7Yr-QF)=L zXTtK2b+-!8%nq}n5Z_){PLkJ=CD*PZ7v@W@yXFhlbza`8Y;=M_;}!V8t#$T)9*8bK z%MPw2_6uVvK2NJQ2dt-kLRaFugU^-{dx0VS&Ibg9a_w9j@R1;?xW7IGs^6F6fg7q;8ttoKby(z7hh&t zv*w=$@BTy&Udi3iF^`v4|8VmUlcAR$_k(4_`duFB(H8_H`Bx_qjKuIw0M>`)Bt}UX zr~)8m4;2zqIhg0;JM<4-gi>WZ|G ze)N1zTT;`22~+2e2+~Ov@XWv(*H^0e<&^CT8wXVil-j_)hK?w)AJ@_j!p6$;y)8Z? z*Ie&>-$5rzFMfLyTNZ>KxHgQxTlex8{TrX8Ek_?mPcjv4^R?#1`Abkz6I^*YhW8iq zGS2`x3)TB)bqL03Wo6O9sdkCAO9&tGSSgSB8Lj^0Ti1ztWu{^J%$HkLR2wtt@-DpY>3Ca+4qS{7(s-8ur zaN;pgQ>UWznX%MsfLf!pC%c&{xVKS7Oj*$H5)_-BVQGvp)M^_3@khVRDf| z+p7oTd`=&|ez%QXgCF1 z4xYpxlhGW}S;jGBf^!=EP!xxqf;ayzg2MGIN+v;7$4^0n~aGZSuR7GO517#1;z)YVMqDqYm^_$1m`#v7WmeDcNm-S(zVX*SKBa zq-H6v+Hy#!=Qob^{;S`c>>!1#)+RHy&&TaoxFn;9|v$n7~UMl4LN!ef;-(ua572kaWauH z$v-2h0(6RcqgQIgMdta@n`e?53QmOtQcol~IRd<7klNWh8bi&!6e_exJ>%WznpG@r zno#e|+6_-_ne*Ht)g{=-FA7yu#vHuQDO^4dUzotFS~8l&o*V};4C0xj1Vl^%QLt{ksWen)Qt5(5kz4^njRaE?) zjxQoD&%F9g)KpWw^i`e@LjVrxcMl&t$E7SpP`2=8bzf<~t6&~Vq<;9*A)?HpCZDFm zrSy>)9UHcE30#~DJIu0sdig^I^JllJb3)?GH$cLQZQM*P&#+7HfUS5;{~4dz0%G`2 zZNtm2AH9?d3d$3pOA>cAmgNRiI@Rh)HbNII4kvQY1U%V3?GvX&_u*T=(~H5u7}QGU zCefF$&8{n}mAi29kAe-8^eqoPXT%ga``nG?(3~L~lS_`EvNNN|z%VQ}6}6oRB`3Fs5lY)QrZ@foehos91glbwV3Ul>? zi?@lq$jm8L9g|_c^^?GR1TIK_c0>#((+}_;{HSJ_wPu+4tA0j0Hcf7O5*Y`|L`_TE zF%}fa`{O+UP=&EvPePKyC!<^639q--zsC=Qpqw(X3>>>jm3!R>a#EIJj z&K}jucA3YXtc5Oh+aynPiXmhxLETZECgA*KPnl1k#Q~cVeUVlUWM<&y<8H|JLB$apH>W2RLpoT{}e$Ur`<}*@F@8q7HuUfn^oG`1&aT^gTEhO0GL<)vwx*%`a`75I@C2sG@S|8=s9FC zo}@)dOL*hU5(TTL&-}(0|5L)2dEpJ!tkOwJWxL#Srcr_&_r00~v8{^F4y~?yryV|F z*`lx>wmd-6M~;x zeu1Uvlk-YgP5%sD^6SbTS=QE~4hVu~_|iHrJfVp!n}YBq7!-%V0k60s@t zk8GIpju(C>Kz;uV*OgCtYiDbgFjl)kA%ZJ_rCN)E2Y}1X_)<6<;yz~L!{t7r1Jl`> zQ*t<63RUXbN6>TDpZ&UJZxNeD;vY-2Nt3x~MAqZ*Jm@vK?jaa{8x**#i6c7LgU z63So~d6<{G&&@d@!S9kX+;oN@5)XJ_cQJOWB9&<(M=rHJo={QuaJ@2B$+8b%WE61BN z8K5@gjoDzK$`~ykJJ9ZQlXIroH@!AHm=nL7`#CxnK6YE%s{b};$i@iB84J;PELHz& zku&w~ij~{P)_-$A@iTb*bRk|W-9R`U-C2cfx25WadO(}jdW9s2q}5zgNLgKhQHH+6 z%`e%PASStsyPeo4B2QE2=*wj~L^ojd6Twt1FW$rWP(y;R?!Gnl{MhMH2W8V~N97pT z45w(AkRkqPzU1J9V9>eYS=fPtI2NZrUP+gqTkX9F`#`SYFI&qYe(l&Rjw5-Rw1g!zj}Z<q{LH2-w7>uB&| zX6+&5pkwBXc~uj+Wi!VO(R*KT=l5n*NV5kq>8@WL^CV+0<^N7&(zU2g)+$xQrg+-) z@z+B6PO5|9)(Lg4s}a9N%e=&}XH9nh7PQtXy0*;pzQs>#bo;^p9rHc|wb#!i+lp0* zl%sD|Z>}n#tduDO%Gm;9tx>7bH{Ss&3|cA;sAijB8M^bQa-+@VUK0ae#deXT zMQa+oK8pmi$vB20j{^a<%Dz0LXrhn$Mdnk$(A-zPWh8Hbh>>K7HN#86&tQ*}xayGX z0)VnB^1J?z!-BHREP8^5)xG(TH&^hNx$LfDy|&htIsWX{5~#Ahy}_S1JKr(6Whd9x zIU7|YY2|RL26FVEHIJ(wm6Sm#=?i(qiyt~je*jm%-veX-ifX6Xa!ZwW?`xQi13(Fg zvoDa^hfgQ8ScWRmiiXSjBB38X3^#&7V3M`NT3L&zv%wbGrQ<+h3-qUt4lFyJ0d}(H zrPDp;(ORz3(1y9ChMwp4a|mwrlIsyRM3JlDC*~}tL2U|-84XPA=@c)zy55^3HLVb@ z-@+f4(?1o=x(xMe4*D7ITjoDhzuvezs=#%pD&J%w^VREBVQe}{={ zsHNwnOtxH3SW)B6OaJ@`SVgVagaZ?;YjYklIR8uVjo0sL=GkiIXE#FyY}C^CI4eSg zx%$W-m4Lk&n9b3msba~a!gbpOALp}4DKh~HijFZLBab25H4K1 z>E4I>x6s+qHVlLfEf&_nUV+?i{aihSmZcCTn67VBZG{CfB1upZJ_747k_$_F$i6t? zpWsCaW%iP2ra_OJuth3%wc)SJwpDsjKNg#GgP?YyqSiC&LMLh_UdE2LG}U4(`24SJ z1@2dmmWWN-+y#NTnm!jMS)QhmJ)P0x)uybCu0jm>h zNH3qB5uU<(z7wN^FEX(;9#_*=^@VzE6mI2$U2!_Y_)(*Pgob2VNYHF`s3Co=eDg9W z4Z&7fPwrRegmWq=ROpdTmn$hi(Umj*$=DrEBWr8>J4q(b4!B~kqBe6llMDCkj=t4N z%hHc<=3AAYk(yK-I@3a#fevMa#Nu+rR-X*jlAwELbxGj-c)RF6OZ0lzd%ixn?887JH!w6tZ?6|6qmBQlJ{k|?q#n&!7^@Wq&YGa{ ztcohkw{gN{=fpdmm^KM)&45a|r7S4wu(TmswmrzeL;u}ha`E346?XbyXD zgb((7psa*1g<(Cte9E)X{>H2RR^zpHR^wwMNA-W9KhqZegmaZ5Gj5k$g_sMbA0T-U zkRn~_4ps4qTT(w62+WYbR>1&?i~BjTr@M*0GP zG`>vcRtv0Q`e(fC{j%~FuheL7+m-Q!=*m`6_YgjWfWr8H=$# z^;l%i2gAQKL(+N7E@Owqp)2q~(xSaUf<=J_*YW6fTKDLC6co&*r#sTUT3LX5BG(|359p z=FekP^~dHPb#`vThHZe*xkk4!w|F_Kpw|LaoSkhibGJ}7GD@0S&wDMH4bv9Vvdf0m zU@KEwxjR!Y`)4G93M;}%o$8Ej7DEBk$ClM6Ezbv_nicc9Pz_iW#?UB><*iPjjl1zl z3!wvu@SBbdJ!}S{4%F;~31%7YkEA7#LXHlfQD#QlCmNYgM`he(&E)b)TnoTDVA+t& zIUHW67>V1v(kDH!p0!`6F&_}FhJa-85=Z9T0*e|g66*mT?;)-^pLwR$bsJUA82Qbp ze`vHzm9`&t>~DzGOc|DFRidgA1q2glC7XoEK9JIv>BD7vB!%6@Z#%sXUpw;=FTe=6@vo?LdpspvTX(Qyqt@ zg4dbpJ%p)P|{L7+V@0&#_u6A_um7Yh4&7Y_(;9-|ye{&EVH z;yNzhWj$1hG~)9_88xoapxNxyu12zMcq8k1MRs)LAXNKRkt z;0%3O4qWgSen{Rq>jr6n$X9whGJjr!H@|YC%M~S@bO4vB`KR&PQfO`0xetMLfjC-I#glv%D#CINZ0jqmBpqU%~>+4+hF9cJ63zwsD`?a^D^OH&hZnC>Qd2Sm2Bz#lQt2r2)YR&6DaKo z{jTD8Wo7Z;AJN{}!DBspH#$-~?CfRZ*rNZ?=raggQr4?&#~#$fuH?Yo?xQRaKP{91 zZF;<}pf0{*iqvh#va<|1~^D&+xj!%?KHFnr?;@fN%kRl_9f9vBeUvIpAzYYOV zDSC--j;X$5p;~$5Opd792j_+B8{x^GOUH_Cir%&u0)A9p?3c7)oTFzJWQ1M$(=b%` zp4w;#UK^FgD*f`-dx2rZ9a=21+UqV~+h)jR!JTpJ*O*URmd!Dva@>rlCaz~mOPQCS z4O?3tJjRlT94u}=z!Ou`i&-oYM7f7o zY076GRSUr7c%Lz~vgC;#n4<_A8GC{Y1`)$~$II6Vq#gj1N9uXQ^-_Tn*0?c@IIKPS?lc<*Y{6yy1ukX>X(?bK-#J;gCK`>3LJO_j~-`TWXv`#4so z-a*>ygdt(1(t59{yiU`q0|Uu2`95?6xW)~P=5ql_LK$zlS#t9agc zbka=@2cIw13QaW$0$k!0fq5QUonDb{=o%0G8!-EIV8^Mb$nx#8ftLG@h%7p>&-=!p zS-+VYNZOTYyS>(E^gYZ7#Io1xH&ex%`Z{ej(%y?}#8LByx8uup_Ln{==UoGeRq@sq(ns?433f$%J&WNcxt5VmcE%uckTA%V9JqG zQk*+IP#)NVU;>}7OtV;ogG@m`Wo^znDV%t6E(yv@7Qar146%{3$Av633yj0GWruHB zwX@%xV99;nZ;dah-+YCT^Vgk1x+pUG&M`R1J&qDQl67H>t_*(jVfdboI0Q>gf2SB2 zJcg&kp^xeL7#thXId5x?=)-m5`c3V$4Hd(F;;mHg4Pn~7VSNic9MooTgJ!!DdYt`8 zAj!~bP*xO*65UOc&bzd>kPh3~VQ*|@QRfBU=)QUvJCkr#rYNPsn-nKAKW2VmB$(3c zx2HmUl_jF}|3Cb?Is2OSozZVvk$Ks1cNbmYia3mSgR1BsA8wTar{9j z7)WoR%qp7Bk`FkU7vpet-MR%R0-Bn&+j^&D&e)Stk?kkQe*YP}n|PgaakZUvlQZAw zTJA~-hQMpCJd@_+rB$3lTETKbb~bu_$t{hekB+8kr^niqHM-q)H`=V7TYa7D$^3(k zY+A5q#?(m5ev>mz(-t$&;JR?T6d-h^jk^29FfHDR@}sG_qw(phxlvcjjVeCFxEicR z%N!}F0hErlQ`4I6hFzUPG`iEsQX_{|tH>Gjkj+|HlqjJ9qqq*x&J`$ZUKIzt(S%o}C7IGBsJ&umQ4xXXM3$}7*dj%lF^0QaL? zThH6FsrXTX%YV(@?cODxFxw6L(S5LP?_VObTb#A90(obuTOj}nmurvhj&10>qsZ!# zrVKL>&Zb8+z5a)`OJ3gW)1PJNHB|oR5#_3t%WSL46qh zkO`L0Ou2p_)mA@vXW3jn-X%2uvTp+~iXCg#i68srS1L`+=DwrS5AFJwJTDnPR1UJgr2KoO|ItxD z&%uQb-r1@4?v7f>nBE7b9%IL2o&A1Dr?7NV%NJdgYWPMo-sv9^4WP5v(zZLR->cD> z)7-F(m$)GR+!%yRr}`HzXxhcg?<1nmVqG)6WumAH5!y~uM zrE|`J#b1N*Ryyu#7ds>7(3oY&z(1*!qiMSEtwTg~-I*~lk)^n`hcgAlV9Q|ui!>$% zvXnv;QtF^T0@$@Kd?fmvzMNJFU~7CL7T+i*-Oig=9^Zm`JQArCQ>8B3fJ<07^BJhO z7+p3vd3F?k#|y;+HZ8MgqVLFB*nDSd9-j%51z!jWbj7Nmd(;686T5KQ7PM;p-X#Z z?GZEjTqi!)MB}W@MU}w=K>V(^6Q?t!u#BlKGl!hG@QeKl zT6avN0s+?QlwSk^+9PI=#-R3?xABr>rP0?C1pd$c_~KgnY_FXcH{bro)Mm!-MZm`v zq!JG<^mw1rYR}*VGcUKXgmU;7B2sy&uAdUYEEeWoby6?1_m8!!*k;W)c}b1t;_A2a zmx}-N@49MzIF%b2-+31!IrCe3Ov~Ud`jxapKjkD-p2)PVc^Z_~g~KcedC%%%oy)2> z@p!jb%H7N3vLt;BWQ0iUD=-TF;-}{(M~D{0_uz0dC-sk*Nl9FN_&86d^B8(ba=FAU zW|A1MhcBZ(W4J)o#5FN8P2|BLs`YiNXlhD!S)l%==0nk@C3oI!!xff-x+>LBRvK52e8)@>ax$)29#OT851jrqjXMi8V5|jJ))s*}YHj^hG)k1b!8k(ov(=A{NUxr0 zq(gacxy5vCxy{iQH#RZ^sJAKXKu0>$GGLuBI zJHzpoZhS7Gwi+AH8IKdby;Nd0*hy9k(7D)m3fT(WTy-_SD~eiJ9K&>3=o?pPVwB^t z|9zZKagLm)PLHYR6YJSzWZ(ViZ53`*?>zqVk(r@4*$BPHL4Dbv>!czKTK~Bgqo|Ti zmFNb~LeXf@TBP8Ry&|7wky1Wv)R)WF0jZ`c)GUA_(F0~@TPWRV$IbaV%GaIidt3t) z*F0lAX}q{}Rd!mNLGe`Uwq}Kq3gC7ck;QseOf=CSpvhIr7>P4wO2rph4f2~axdA1A z-FQ|)APy^;hei;)Oj+t8;N_@QXpV?-?+@D?Ox=Uix)ZHhJnWD^EkA}?U&Xb_3uE;L zk>F|Upj~>FgFI^Kf3bUo+WKB$A87Aw|8f|)O zCm4vSq0x-fI)A+nXA8eWx4jb~_rk#uMnzqQ&{6YuOoyLnZp~U;az9C*)IezV@lt*V zKgkPZ^N~cX9p}`!kT660GnHNIuov8PF8(mfyCV@2@~57L2Y&Hby+d5`tP+p+aK8&| zv3Ra;FN}D4?8!5LEC^l;`^n7k>fS_c1pIB+1qx9zr}xi zye>w@T*2**f4|pi_L(|QTJ;_52}mOiEb@WOwBPKSTA?-JOm3~!a72dcyZiF%zp6yS z;yV5Bs{~{-#L5`Btr{gRoOD~^Hj9ebA~|+{H1m5E&?~kAdFGvGt-9*(3*xoc`f(*f zxm-~wPeOX9`no+O1Y4?R@0?Pi4VhKcTS~tfS=n^XSV5vWD(!}v@CEfw>*w1j#N_Hi zTl6Pad(9SbS$v_99J*p|giqK0tcbg@(j(PS(I>%Mur*M#YZAIWD;(-2(2>jmsVLvX zm8k{eq$ufc`*&i$FR6H>oY8|grcP?X$`ldw0IYLuU-BzEL7dWNIUmeyBD$!~QBT5> z+y(N7hEfR0GXdb>#}?EI78)kf~gm^`(&VI2gN(`)cytVSDt8( z-pG{&>Va^QxbBB!dtrmP{OI4!g#=BawOr8l448(IUIOvwJBlgJxq|B$9koTan2{ zsRGWd*Z;-IReDg_K+d3m#5nxw@9xWPSw}fe#e?_N{!ZVqyZ?Wi>H!mfcaAC+N$+bH zp;nbW&Vu&aFQoHcZX~?%)!aRTKA(91x1Euf`C}i?pee?!Vcve*r&XCN?X3~Ukdl+z+yGgA~Aow%Enf9s2GVdfn=%}ASKr>x-e)q-sV>EpR+WY-||06D{rbKTf z8pGzucXm{DT|36TC^QjkP(;CZ6(Hk>D98PoczuHXGqx(hU;-dy4Yg-q%hQ$zrb4q? z;ZI-O40NF-O6N=S%4}1QW-Qf?y#$Wjc6RRcfBx!mq^DJ{jU?Gv3M$MRw9f{?E}PGg z7$63p)k>V9<+W3suVn9-(!$FZC|B~~9`7gp34`|WRxAq^c`+g_#pKEG-<0@SZeOhs zT`PC0YO#-&-Uns_uto;}7LC9AujPD7Q!K zwu;TG+kdEFom*{fsm5`wW58L(a1y8%Tu!mMQ$9nN`+o6dGN67>RYU=F%s4C@lXG&l z6;$I3nO3($uSjRk+9g}9Znn1!i?efSw}!|HakJSGCU0z_OyX*6&0S18cQr+a?75=9 zyY>2|Xj_}sPQTB&JJ_~*KL;3eviyf8^N_N#W`{8pEnfV6~{<1E^`Bo~4=2*c@1K`Q-f>*8NCY_PY(6T_+d#j*#lQ!CVDlCwjZxQO!iVGH>)ka=4w$8Tp!nF@}jY zr`QHe!czxAE>(Wp&cRV3Z|~(6LYvw*zm6&WHFMl0(1)G7-Bmw7$lgCAJ17Y15kYuO zYFDo({$;r<^JEq&168p(q0FiEi}rTvwigDE9rd)rfmM*6UktP)8-!)fNG426q14bO zONe7~&+^L%+MtChLTw%w(t(~`23oiNTy#X4;9Pf*_-BC>P6A`XMg#9c@{c}tE`8ze ziLw>n7IpBy?Qz=pS^QI$;u9N6X>_33t7(aP+TQxPtiP?kwyYvI=eANqj1%L=)PeD6 zC)%)qI5DjB%GqdyLivhL&EKMI=pbHSr&7nb8`6;0Pl{m_ug3Q?#~@34NAOIyYMLQ& zfw#~M>5vq>nC3P=Bf$G&Um85iQtV&Nt0ve?*lV0aaxq*6U0~5F@vmtiiJyh~in{ zt=a(T%4pXmK4G>o8N+1!vE2DLEUv&jN8QCCIs$OOiwlt&v(>cUw&@>Ud0W`O?^)yy zZzi)@rN~4!mo)>1o~k#qk^keRBl zp<6^{mT%nHgR)D8kC=rv#G$-7M-dJo3(HxC=HQw;-f(q3BEHl5{4p6=%fkqXOc zO_f+MYa1i_K&A>G|I8vZ9(=#w=~D3*XFne!SMMoEQJv^l+GNZ^1CBe>p|f%SF$Yso zRXs!xzv5Rq&Tr|=!wSfX=x4Z1bSVkRuf<9Q7X9@}hqMkPLpKg&9y7uv4TqI(fvcd0 zYSt(7LLBNQx5iQ^c40tp8-0+A8u*=Gb>zdYo80>U8+H6^T6}3tO1_e&SmMFx{^K!t z59neKysZe)`}U!w(Hk{)7FI50{)dLWZsRC7`jFJfro6}8fwTUxuKgWS+#&|!atHRV ztEo|dd+#_yEql-r*5~BP`@8fnVMofcnAJ+j3F*mFeM4mF# zm!Y=Me)~iQy|>W%yXus!YC5dCFGw2G9K_p3F2|}`*sbVcpF^i;(iJ=G1rEsouMQan z54`{vq6a2F(q*5?VFCBGCz0~M)_dM*_x_wmj{;+0K&M=p&4wSPl{*Mhq)1R(OkZF~ zoX#*^FkUs+*E!c?%W~mHhVKG47!D|2=x}S+?=Hj&u(|t*W59kMFAYv5x-wrNtNHcx zgqIpKl~Q!)k}L{$psypyl-rfJvlMR9nxGa#SEoI4l+n%2y=?|M?x+V1`kvAa3e98% zqy|^Zln!3**u&?2%z&~9z#3EQPowh=VO&2CMPbnW{$Dtuk2|v>2cRn?eQ$7sHiZn1zi}MwWB4Yt7N5N#@ zdqD99|Er_R%NC2ix8({9*d3+n9fc2L|7Lq0Zp>qr)ZEMULNRj?h3=mo|DidoBmd9NTf(!jJNhYRU;M!H%t#QWspfemX=`N` z`wPy-Cm83A|1`WW{s4X&94`)-go4^4RibTUL?N*#^|Jql|H`mWW58VGA5_Cj?O(qu zR9R?u{fE~0Yo+mP^0s@;DDA0|g?-TH`V%Y=Zvv$6Ten+dB^IF4Uhl(jsNp=h6E2vTwlbKI5iCo zhv+phQYf*vd)_OMce+UC%*n*^b9c9?K{T;+Xx)Gr0#H@IgrAe`2d`OTTaFpH6{K); z)-=moY@`(9!iIp}J?4k575x+~vNsWIn#F9{QLgf9#UAJpX}KLTD(icQHvX28q&siw zs*D0}#|AyyUqnW{O}VpfIv772D}M1eKda>6H%c2DcA2!U-QP2W`^6*36!Ep+bm7h^0gnklQpfz$!K~ZC=z`a9cu=g%a<$qKT%IdkIwQZ z+4F8r10w33UUa|9sNjXJmtE=}U`#p#+CUODF-q)h&dwTLn~WWp*v1zh$i=%b%UnnZ7E&fhA4$D||J78Mo z^wmj7U$%Hm3q4(44#GYtdE5WnJ4`2f$ud*+Jdix>kKQy5TC)QFN6I4xu6Z|yU5xaS zw{9vdHM|^!=~}M3%c+O8iGz4cS#FefHHnhQU86&p^ry62B2!d6XV2&!4Hy$a}NeCQD^GH@|%r z15@wtpad{2!(0Rl@GIZPyfSC^&s?~8WmQ^#&hzj3fLx-I+qDu}ojilSZk+#fvU zU&wlX#RiXnIvv~OXsrm0!Bh_O|1*4a!K~zGzyOzY-_ZM?t^#0q)w{aCADI1qpi~2( zbw|Hz811upB7sZC`*EmYj6_h^_Fv}f&O4m28oQcY1gbjbcM>puSK%XMCwj375VQth z!baMMKn-)h?iDCTB{c9z+-hE6Na1edEKEE1bJU$m@G9 zzL1^bnZ{<|H`ajUD$hBWR-v`}=1BUdL^$Lz2hX3KefXf{^?-qklzq+#eEYxL5Vbza z!43j{r8orJ^Cb!Y3}yQTH)XTebQB$2i;eoU+}AcH)ZKEa;wn+VNr$ z#9R3Z#jQ+=M2sM5A|H;y9` zS>8cdUc9(mW(i#T=veGA#BYgD%dv7EAUq74}oJQPr!-_+R1MZk7vRfc9!{UICVcSg;v*3qHa+i0+@V z!7fsUs`Oby&g^~Xrhwr)us$x{*datyvE_S`=- zxM!(T*Rd^388?*jn2;=#Xg(KQUX0-2a_jSFWHJr=j>`|y`QV=u)>O^?n}KhtsVVnW z*ZW~8uD1vCGi#^r0u{V=8AaaFo`Y)~QFUMCX!$G}Ypk4IbSSRUPyVX8{ZsD1tQ7IY8+cHFBgh zBSjiUcS}o%cc1U~{?0x3+`sNQd&gey?d)u?*Iw`E>-l`d&Z31EFPMrj_{~Li1GyJE znUxhkTfM)Id!jODc(pBv>*{uJ>!dPgsB+`fs661#l=AcnGP-dLq5MVbS+bs-=iF)G zMZa5ok{bs*2S0Jg_#--1#Evl}@`SYZc`?nxlZrgyF8jLi8bDq_KO+vdp7wB8m`x^5ix?ieBNR@%blG=@;r1TxY zOqnUFU{H!J^7aNu28wG>=b2O*>S2=`fRG%*wS83vODG;VQdlLb7DFk}X1Y#9L+qmT zyKC&BHhIK`^d2v09WR-;wt6B;P9(}U6b0XS+|Iw{WDYp8QuYE6Zv%NM!m{a4I#6zn%3VPYv-sR>b%?ihQD3 zGk``a6Pb2Jn)a3B+jfn;e^xhH9eSRtL%$OBNDT#A7 z`y$n);6k9>M|ai#(PN=!4*AxJ@sae@_Bt?OB|DU`IqA677F@$kAK9^btM}}OYtvM_ zwr4Fv19bHn$-ajcL*1;$5rlk*t%u@1^AAw1R-a%Ry`$PXvfS$%7o8M&XH%S$DTjz$ zblmJAy&1(^*e@Lk$#ire8_cNvX?0VyoI-&o;_(5H{$L_%UD&-&HtC0;edWuxql0wa zcGJV#MkVFpyyL}b)bf-xKZ&EQcU9?8<)z!0f~v}fB(wf9cDP1U71ANC0kouEpCdG2 z>i-Od&_0S>$V|PXv#k1f#PO+eP_oxd_T4TYNZkt4<3N1Qdh-zS+i4jr1?F3!bwbbU2+gG0`3m6MGylQXg!hBdH5Cj zN>NnlmR$S|nF$vGW&UHg3%8>G@V;hdG^fXyIk?7LYDtvepE3Yu?TTorRV4@n-p2EI zgAk{S`Nat{Y@74pUr-Ar%UOV@0t6)X%12=ouDjo(9Cyr9lfWKYI^BlTV)GNOSqAgq zx8sk^7OM>hcDeHq7#bRGX7UN2{rzUWAH5?zsO(dna|zA*Gv~%d@#K++an+(?^7)5# zKjJ51#JnWj-y-XmkvF+U2{B)XOPR*Z8o??M&k?^uv&VZp_K2aMCcVZLs0VdAP2>Zv z8`*Uk>lDuU`@SzV42NYt1hbZtkVVraZk0H5#{-B!adX!5->oK|-p$FrsuDvwM4)dQ zRp0JE;i)_D?6`T&u#;!!Ub|S@)LDm#N2+v?}_$J9I|A>b`^~ zmy3=3MZpEVW@P+=p0t($R0J4&9O5+AMx>ZDaFSllD$p%DgT7dETvLRUj&5OEGJyGd zsgbLA%_2HXvD9Fj#p~YF#;)&L5qVz3TNtf75;J$A4QPYhv4m-ENjrgHW1Lrt({+0! zb)HwdtlTcq@rcvcS0C^$DOf|(N{1_WD?UyCHJm3xI0VL0p1R)%F%pgZe6eYaE&t;f z&9BlAiyk$MXOOOtY@;)Weyx_Uan#3%_OWJ!&rwEPqOT;UR82*2(^&u%XOJ+xt_1jH z6W&v&?vrNpET#$*`NO8i1NOW_Sw=PdId|@>vht@8VnLncMr5r%jT?pMhg-RU4a*7~ z5{?@@LC zz5iX3o|aw6xf2^W$dT2BrK&D+|DDeA;o#zGj(aaf;6Tl;`W`fo)zcR?MJ$np&57fp z&RB^l;+v?bL9Ih!BvW>Mu8*U2T9h}*^pc(p?I~gh$gJOQJ^{Q3okHFC&cPkqSi)d8 z+R=1>gp}&9h6m&6w11yBSGGz;5hc|;8ZS|y815ey?G^*QDCt7+pU5rNXtl|PhuIZO zIBy@JZ8(U<3_g?<+C=Wmppx4-#+7#7Atxl{ABHPPQ_qvVE<4DOD%;ZfgWR<^HWiPt z((XFY5moPe1E*5-eQj5VQsaxx-tTzx{5V+Q9M+WLQ<8MjZBL3tc z-(&d8>#a=Flg;{U0hapDOpUziywt1KOy1U+u-V(JBY^0|9cYNdar8NBp$2bLFev%$_oSXqrioDfd zZNT7zLzrjalVV>~i}QKueUeJ^BKdI zK4|3!J*Bj_7-tdO$fHaHqu+5RbdmQ;kjIbBz6kgTwbwCrb1Qu&`~xrFOJRhD1$=_k zXX{ny5i;MkwTH`rIui zQtW?Pzh^L}anuJKft+d2XUcwey-)o-^QOp&ujb$Yc8`Z}ZZwYi^Vtii0{b14rM9aF z`~i?t?W_4GEJepiMX+uCr;7r}M$13;Sye6D%6bn&OxtV+8|{I*8O%>ydPAVvT45^j4^R7{N_D0YeaR9eq~14PijjP|7+4zhiaeyH1UZF90BBV20iuHhTWti?p8G zo%NYH&0V}s53v6E7D91P8K@;x;X}UEc4rSjcT1kPe=gtW`K5tXy>pww)$Rbx+Qjs zeqb;urtzQ$9+u7qI??Ew@`*{CWjbXI z@~>FeG7x6~oQT0M(ceu56>`_3taE05=|nhHAwQyia^L?6`e8`$?Y{^9i{ApcD1rBX z(gxq4ykJ{H0$gH%O30w$WriVGhPQ*BE;?4Z@Y#Kw3P7E&2+{BS`{}oT5x(&gjlv8h zDWVDhr#XW4TVQA06{m=6M0zrv<_4V;sf+8WyP=zHEwSv$3*6^%1G1ez*~*|(y*Y@# z$KkD|yKD?cd?jI?smP#(y?#uTE<8N8dsrJpkNOgyxa`mE?OB=qx2)f5G4+nU&UElY zdI`sp)Z&q8Nsuz5`=64X{2Y7B)+{Hg|6K^DiJO6cEtaSL@3X9A?Sr)>Ji~{S8qePl zQxiStitT=|m~Up`YLmjy1CT8G1>#(UL=A)~L|sj)k%CAQD)MrYf0rpMvLo~f)%mcH zYL(5JRuQySx6Yra>i0ySgr?xP6ra3+C4nf1rk_`|Wyh9*syqoC#&AP@q72m(s)Yh4 z_aC8|{$=r2pXNL{Ka`px_0@%U)t(p5WIW>9lHmmbA8&w?!x$pBhTF+cE!(wI+oPC0 zjCEaSw!EVaTk1ZP9CtlZ0<0g(Ha+o~wD_#S_o;sTluhZT!IE6&SE>PVp!MkR zV5A7?^eH2ZC;ISRNmAo7-NJx)Diz}8{4Ei=(D58RYC=PIRbL#Q>g58t|EU}2x7#><1*4&=)pp93t`lxB_M^ocg~SEm z$5)(cN9hI(ieqL3rU01s4emb*dowcW&|~Fv3;W(vnf8IW)VN)>*v>qvC9C@W_r#(rvMxZSV}ZTVjJ9UbdK#pN`#G5PeGl0 zz_+q+=l)vH1->c#qc=de5Q>|YUNe?g%gX!eXsbBq^WaPNp|8z1X*j#6jPWSYl&_oD zxtqP@V$b|lFG-l{Rs9GRajr}7|5vMTI|Ge}uiJX(!kv~X-^4m5=Aks#O2L~%Q9hSL zD>edmDEN779hO;{8E?>#=b=HfRtZFeC=A0UlW+BY=TLq>He{sC48%FM zm+@IH6xQEum_j0I0A@erOS>Z5cR6~8&=+qD9jUpae`|+^XZLJUxxU zj}r_N`<&zNb-}erBFU=Rp+0}WGcx4dZXcU`Dqci-<*X-^q#l&;Q@K}s1fw9SxF7$i zYyPU`k|W6IYG=mh49JTjuzuWZsMTK%Fte?9@kDHFu+8vz1~a&8iM{Nzf6T}__;?sr zPQ}6_yvJ&l1AsxUXzRR6vP8*#@M}~L{8dT3H@N5+JZb#ScrKr1$BhgZR6|%@*2YJt z_Dn^DoW(S@IVFDfq{)wG8Y{0ls~3N;?0TN|B4av1!`_*GFIgx|yV;rnn5_Av&dHS5 zvjN1M$4xo&OUZmYyNSIbVlUV4temCQ?EO7+7r}Fa@4un7H)RSejy1ot3(f?E#Tz&!|b+d6^bG!ft}#5!WP#weQ){LG#uMXBi&#E3=(Ea&r6wN5gL zccg&M53L2dKNCJsRHOdk$^XNXq3p~lkvZe~q7t7xOhO;<4MK>5AxQi#DV45MK179< zGHp8=xlIQx7ykigOO;!q2pi6Hv2=efgmh2nzbzgvg*~VIc{Tz695{M2>nhK8@-3KL z@N@CrP3rCDhuwti>a^7ll0gR=rOT1StrVn7&vE0%tWmhUjiI1RMr-NNzO+(K1?0XV!~;8}hx(S|dRByrUEI2?c!fZq8gMkP^p$^FEA^D1V0 zfF)@3srbi_KPpiiABV>C_c)j$)<#dpLah-vy=(yphfYJr62G-~3E>V?Fx4swL%dmQ z=q3`|VL&+`vN~*8BOUnGv^2-zH08_Rehf-jyKX+NvCUpYc>mEiYwsj-&#bV@D8C8h z)LWcN?xam6g`iQ3=%o)!iamrR+`I%qr|wjKAm8Tu=z6dqsHF*V(|-??DwAIsoVQw^ znrSV9&8y*Wo0~~aLizvSFBsr|<^D;SDTz`|nTk&lcHe#Y!yB+itlZe||D%<4mw?2f z+UakmesQ&t2Lvg_JBcG{z=dF@|g(rVA=oi0*1DiT@wP zEg_uZR-&b+?j*^1Iw*A3Uk64X#&f7UuDg-V*63H@3xaV!EubNUtu_R^JRH}1!~o;N z2sCimqTYV=sWD-OiPLyk1Jdrd6pkuJ?!;Nf>KT3k-No*Pf{>f zgZTuRCMS)pH`wo^*Gr@7BfBCJZtpy-ub5p#q$QGFDa>C^5fk$c(KGkjLAmbBHZC`B6vdiBWW?00H^A|^7Z2j43I_MY>0dnx zzkaNKp0F;wYu#cvFhte#P)+@iEtSPda%?lojeif0ts~Y;HFS^NOx6jp3p+Ta-bt^G zwx`(4j~s8brAiUC+@gE!LZH~M!pG~A!_Oq0ChPi<@wWyomj!ibRcou0X-Gh>fsL1o zgByubE&G&eBv%mIOkH2wZb>r!75)i&IY&pRGnwM8k%lHq=RW?ak>zzPkzGc?>YV6@ zQp1RtC6;OiQMhEs-vhkNSA6oUgqk(Cr<_vum}bq_(q4h@30Wzsgl77*U$Q;SuKOj? z;}Lrd5ijH6_z8U~KK3C#x;#^W!%3lO0G>ZU=p9gHpDx#usoC%i^bNv*(6WVgrcC| zP?P2*ZYCdRd_&(ATw{IRtR)9Q?JqNT*;})Gk?}M0d>Kgtp7L*|DlS1k0ScL)PC;Xy zUqlDC2S#u!S(KT6fF)4oWhM<3PNM}j8jL9;daO}e5G(7|{xZU`(rP5tR5Wq9&5gYy zU{m2V0y1LthX;ZA4V_T={eLbza!XhB=;_{GuXYFxm+yf6nMD_*qDDiEZ+KSQ^RxbE zZz6-^*HHd_bu=4<+n@f!=p2>vQ^kQ20pl6 zp@-NQ#raP|dJ-^uSsA$N;JGY*Ob>$Bq)kyZ2pFfSze#^8miTuiO}PrT_@}Jm$%83GG~m;ZI!3N8e=g-s#H$ z5p(&r_2x?^VY`#zh{IevF)H?+YoN`wN{sczX8x#l7Wi!TA>>iPVyWjP$BamF z4ar(i!O;w+zZsQ3KVP04bqzu{af0hnzDX#erz3@ zSUJ6EZe5mL6K{nh^SZ(Q;RS=e%Jf=YjHb>*thFq9&>T;Fxeh#2rObLPrqDZoVh$r5 z;#jYkL#JTp!B^*H7V5ow3(x32@w~Z*+CqxpNb@`*iX*R6Z8JlsP+K5errA2Ekp^}< z?}?!S)j^4uqNH>*I-t!zS-{;qXZsJi4nD%1d!f;jwR=_0~-akIs1yKLBqSJd2C#05; znRHK~zB;hX&VM+tVAd*Pt}(aYgUTdru7BU%ZLuC+yy3ix;N4u#;@si!m~VKU1zLNe z9l#>IR3a2&IUy`r7*|g+v747f9H&>+Om6Q{RIz=3#D0$4%#+1+)!w~o2CucvT6hyJ z0*3fIb?Xjjl%HH5Z*7?ldH%I#zbtcpljz=35~8-gqS0aNm!Foc1@4fQRY@Nnt27Mr!4Ac z%criW*UftIZ-h!GaS(cARiV~IxG>)h1w z(M-3x*32Qt;_6*josf2%lwN9o?Kz0;gt3~DUwz#)Otm;{hcmbSt*nD}X1MvIZs87v zsN{in9{0PwK&M2|6nNDHXMN{-oy-$M>uKJoJeub}6n=1tRDXj*%r{RCN=4zr%Cocq ziB(Y?(X+wTit}uynI3&rekD`CwpU#^o*NF|Pjuwh-uFOB>ccS~*v^^cxqGHPy>}-2 z_)~*`ql2+~Op&7_{h-^SKZofm%HSJle>$y2t7Vw;hOi{Y45KpeWBK6mR-N&Q@PO#r z(EV(SaScf~>l&!rPG5qz_oWc$zIxkv3p+jM8%e1NSY`%c;t(0!m-5o@Mux z9^6o-vg^97R|Z60%zAUfp#edAWuh0TW0lW)NXPdoyE@tix0$!Zq{FR zIweSJ`p3Js>TV@&cc>9cBngAp=eAcT#r2;)-iT9CKvuDoTNKwceN=N0Vukh|kQx{_ z&iY9^^eXqUtsCPF^tZjwBe!;r#S#lLJ@nnqwI)*`sybBs;dnjuGe$RfTE`i~a7H&4 z0XH}z_>kE`rFcZ}A6J!;V8D)ulV#vi-NOaP&-_!N)5Zb617;mVC05Z(l$Aa1DeaW$ zf64=KNy|xxW5Zkhc3h*wF*GM~X|+ZM_l~mETZokV9gtoPu{dE@vi5!t_?(a;QUW$` z_6`i0p`!FVQtUorM~F0*H5IKQcOou|94jnYUhTH3_LgppSxOFy>~=mB*KkY{cixi&kg_KnGYuT zO)d;*t%%CeUUByMF-!H85I%4y6I=p=z_fMRp=pEgBg4ZnlYTc#@9mmlKy@ks+)!@& zCK*9QKlq4Rum2AcB{#6f`eAnz^7tC~-AS+E2nsxwTzL|>mn*V%n_paqqYCrjy7Zz{ zW-3sJ^I-MMJ0{WC$^@sLPKUG~eOLK?t<)oGat6cU`iogC=pM&4&tO^y%h*BfXnuFi zWHi+A0SW~UY)}+kzyO~YZfCfg>lOOSDc2cs7aW6}UtSmX(S0Tw7ql#PWi>1EVVJZt zc~bZ2<;%4?fGU&7fx#!IaieI%1=~UH$P=H1&>|czwn}}L)>xdzw6t>>E$+!p7(CWS z%vNVR+1z0kM-Y)-=SMX^*QB#rlRQ`e%m<3S9e{wMro|OT6X(!Juq!I5J;eD4e0UVL zg+!c}O;y6S%1zLtP^vO2<#KN%;>>XM%$SAl?KW1gYPPkwkGOgAIC*e%s2R>RGbNIl zBkBf2PR_PIV$4KjsewP3I5fATzY&^J_LfQMn|Zy2uzCZtyn%?waosnO8`hK`hmG_i z-%Tr0DNgtT4o#w$s)WlfP{>>V$Bje0C zjBPdJdstoqHD0?RZfV+YY68U9(Ypj58Xj9$)J#X2aN_N1%YV=b8pzb!AY-lUaTz?l z=9u5%`mdjO{4h$7M0^;W1D)%Y95_1#iOzk|$VL=|>6;E~eEky*e?EhkVCBWf-NOLb zhE1ql8boL?H&xX4l`M7-0ss;R zdktzvISssRh)=Fi1A^T@UsnUhs~GlZ+`UQn;wUc&Q4V8YJg(*+^4wgOQ`)%)Cwv|BEOx&_@Bt6+Ed}! z)cyewWn7J>X38M3I*QFp^S~38nX|LUmdnW)7H^OS*O?R4inpdagYY)8it-68n|;|6{Z`x zu8XfLVj7pQneE}pa1l-=lklucNtGn}BmSeDz{uhI}pk z@o*?S4!Vt-4kY)Bz6Ncu%@wZ%Tt*K%7@hpXJ7GCb2AJZ80UN$c{2^=~7yPA^>Av7T zfI@Kys&ah=YkgIP+&NmPZLJ|U6$g_(eWqjGz;3p%GQD+4htF`y!X7?4bbH_-?BgU! zV;wPkWKglfR$guqVhB1tJ>`ccT0Z|`;~orlXte@hW@}%rC17lR8~rWAxdP-640A2h zmPsU>+gK{~+oPaYSpnWR$?55^!e^+#C=zZowA$vyHZBHdt!AMM9&t%Cp#RdjS4ae} zHXVA5#r=-ZdlQXs&U>t`=;z~UK2LlrPA%A!X$klWWX(Kg=&_|)t@+R#H!qr;-nEF_ z5?j*cQFySl*h(otI0fZr-Z%Mn0YWSh{1RC(7HW;!dIj1=w877_-bIO*Na}lP-wbX& z`%{r(O8H9}J$h_{J~qTT5ytF&4++zfbIJ_cKaLCvIG38}U+UIysrYMfcFF>uO zB85LWP|i^{C3nJUm;kiL;)7DR&J^`9xpDLGuQtdHimh?k5<1&$3uqdXxo14`sF1~d)j$oODAs6t4Il44sBm< zdb3;;heYV0eGIXuMod^GB(V2ZDqPwI1WN6Jo^GPDprh^Z-acq+8E2-Iz0IntLgi$e zYd}}R=e431e9Nw;L3Fa5T%%q_gbz zZwz&%wef^i4hgh=My7r>hEpHjS5kkxfv|CmR$D!gn*1rU0Ok8UgO2%a@G8EscloJ< zWwp3*@rS__gKrPeg(iZ~WgOE&=6-(hA*T_y zCCT8dP+a_BbP|1{-;Mqn!NY=dM zeL#5litPp1>2K7y{1X1jisAma9Wly-VNpJtNam$BGHv4pc>Zm{KuSlQeziB{He&UNo^M+#L@z*X*j?Rsg6V@XNV zS0l>R5=j~{X>U5a7w)M=6b>8)^|;@0^iRX;OzqzL>xHyGhhdNqU~+^NEiO=lDC&h+ znWvc%GkXaMvsJn4V5g3D<<0OfLM(;Nw~Pf-AAS#A&IIvii6CoWh%kFmtf01c*&Np8 zP(fgbY_$oalZftT=;>svkV)tu$^F%wa(BAf685ld)|inqmAq}E1eVuRx(B^FR(d7j zmo8|d-ML5-+Pb?aOE5+DG=Iiag*I25=q`QCXke`gBy3CC6TV}0+WxRi9ND~EMyU_I5vFtGnJ&ff%Uw|) zE~fs>7X01^0WSxW?zNlqjSCW!$h3-l{=*ra-~eBjNL+SwOhB>wl*BUi3cOsv{C*M5 z*Hd0=L|@ITIFFe0&yP#7r~!vGr7iS4Xx77NPS)`Fi-^ec*G;8gfFcZ&2UtxGO;G18 zkn+{afn!681K1?yJrsxt9*jx=A$%%Z37qt5j6(tK@{8wYJqf;&uS3ntOM$QMF)RX) zRykXYRjXlt+${MaIB&2(-2ofNDjHY!Al6|z4H{48Dr@Rd!wQP&9f>fVhl0csqEz(=DQrNU2ph%X6mkBf~tK(1BCL?mNd%-?K~4K7IeA zPM0W1NM<`rd(2mDd7}F+?fw}(kXK<#5JlTd9vX8NK8{JD$Y>o0?@|83cVU7)eaK4r z#{Pxh6bBZ02oD%utneA|GN?#rqs7zZYg{2YFfjPN;$MiKGG-#?q+QKsWE#VJ^#Yl1 zKYZ}|$D5|9&mFdsxR|K913sckFk-7B`2&aRgg!t^Z8sHMa1Bc+0_BIuWJzQQ>|W>t z1Q*OiE3(3~C{DzYCu>1)W`QBwc0hnui!(hbPU|$ z4bThK6TL`29WecRXewFo=WgTw*J+a}#ZAiCr)0Gy)X-OR?l^#`GxI|og;y2g4~2J< z5uk@-XcWDpf53dUw>E1ZcL$XO>-)M>!VDb-g)Z3RFNJA!i&~k)U!n%obX^YZZIRpo zmRkww)nb+F3&LDQV!wG$!8s5G3>iyW?a^(6`pS*If z@lrtmJ1l;-XOHbB(;;ITNC-O=bmaO?c!~Lt!&K6V#1Btjq!cU-GihYizBASBKXEyg~1r`Gl~~=F8?<;|24^ zvs7bVlOFX;QW>~Kns0_>we+7g7Ah{x>P=j=NOx{tUdU>cNQ-5LkGi7`5kdLDR{48Z zn**vmtq_-g1(@vVxgzsPfz6}E7!cg$k}SECz6iVGgL z70`yWK^S6YkHO#st54drlXJu0WOFxEk&c^ffQ3Q(1OK%k*}QQlS%=S0YlYcvCx0<| znkOh(T@%T6{1O$$HrVQQWw}l0?Cg?pvN(f`&G_e}#KZ(}630O6wG)L(tfrM{*K|e= zLb++Ma_GaEdRO^GbGYJ8w8#eAI0jfnKhUe>SnfHPJo4U|ttck%5L=O@#ezu~7?v2@ zTa8$sxu2Vyulf|Zrr}`U3peuR3OMoD zrr#ts5Jy;l<1c+4cJ>j3@EXzfn-%lc5GgN~y2@OM^~B|k&=y~6eHRTgZu3I&{mfih7reqE)#8s=9iY z-z^uqLHY|l{zXQwcyg#X0l_h;oW!6rT+r;wuXbeU2898e6(V3|WKuW>$^d=q(!G@Y z25mB#V+xqa*8!;ZMU6FE-^gtg(J*FQPkflDA5*3COp$<|lB3r9EMXo#tJR!j(J%?i z^O$#jeWV?AiVS=_jpD-$`31o#rc5|S-n(f17_(iVMO+@S^Q`7j(hg|~9}M~t9J0@a zabO5e?c{vW@5ICkXgD7ZSS;fdor%2GoFEWC)(71xlfoI5$?rZ`?0z>=UX>lC5OT4P z6`v&u*{ExnLyZnuF6vZw4gqFYZ>C58;a$i?;v&SmzGG7voS^<45Er}OF!lue!~2J4 z@u%#{^B*2g`vPZ(^|x{ru>=$g3_CWJkin5p7NIUUN(}GXe6Nxu|6sMM!HRWjBlNQP zV3(bp&0jNlc9!PhKRgK;UaWc3y70(Sj~$PH`JQ&2Itd55$S+xRmS5Eb6Pq3~YkF^X zZc3e-E}Hopd%t%cU<01*QziPPq0VtVIj#Aphs%?8Z3c&TX>RoH3P0N<#}~1$ynyCR zY)dg{lOBZ!EcdSP$C6XX6pQ9RjnFrD@0s_i9Y-C+0{hg--Lady7& z!P$qw49ycC#71N(6~7=$o|&5wOfpFyruKN4YnEjI*Bz9#oRy0Jfo7a0BP62j{pzrF zGXNyaH6}c$!M7Cu?BKr0<{@NtZZNkB)8gx9qA1p|$KVEgHg;whN~d@s;`=Vany|0s z`9cJ#Gozx>6k>_p{YK7<2uf=yGxd_%PT_n##DVo?z?&3sse|qM^Lh90w27O=NzzK0 z2~-IymLtw;{;}(~l(C_)%~_w6USXM8kMv7j}gaCsR>u^(KkO5Ux~@@)7vqe zAg;;C@hRLgnk_9$&pke^RT~-%Im;+>=eu?L#l+9aO?oYgN$gju>aDg)@uugM80OyZ z{a&5)U_!4i(lX-_Aw?c`d<*@)ElPmR;1jRTKN7*Y4&=TW<8J3f={+gICg zue}l>1Lk7z+>MJRrhe*>?Ul*n?bE!3`6`GpoQ>L(_q0-PNLvT^9?xa}Kni@kjGscS zPDke=rfHv5w!*;;jxuDcN zxK5&CV*Wma_YY`JAEKp)u8$_qu!~t`Q_zjMoj(LEKNp$^@XG_TNqfeOd7s{ zwgjM&`!(uRYeAE%HkqCYlQvt;C)|k|LF7`ZQjg@=cx2z*c*bS1%Ekf&VVUL8k|^WQ z){=2O!K*hk;g`i0uH7B!1j?I=Kex}SP9qCS@~Ma3J$Ry}k)Vumj~Q`DKb99H>^mb) z9bREPed;(Inx-)h`$K!@*`GiqQBpZA*1fy34b|d)JW>;g@lm-qKl1xsI(*h-7X%9;Ut#Jphr)BaKG7nk6d|(y08?J`O>$nW8W=o(IZeeYChn6zFXA_FzzjW{t0^uNmwvZ@ z?vpFkJ{u8nO(1q~tx{Btj|Zo&gS7r0y1^rRWWHM@$^h{kLxsSNku zl=uTwUn%^ANa`ErIfJXaMKiot<^JM0KP@*Rem!7){b(mD<`ig^F>(A?9|$q4b3sa( zO-U2ACq^gL+BHyz>Q80+$^F&vbLY>V4YceJ^?UFR`Gq`<%0@PvSG2C@xo_yf8AXnPi;{H*#~zt!v`|&;9=zW5 zBxg??Yn4EvCLUbhLK(kAW5m^HO458{@LhyB1yqC48Tp`-W2<{`hZ5c2KN}__30I4S zob(BPJ6K~mk@sy$hG${F`q|V8ozMzV$?tvTzlDPSH0y17CT@g>kxA_Zkt?+lR{ckv zF4HR=9z=w@LCfU!Q=Xl{*4$5^g;WOFlddnwyYGuW%-~^96n<$``U6j)hxRJQz2SK$ zS&VuJ14R2#wCf}Zd6`hUH~RrKg$WHDonl}z_-)r&mNOUPy%~$S^acQEDPxsB&xE|5 z6+6Y`ih8^j;@jvDOv0v&fD`?i(Ka8Z`BDxc4<79sSdPKr^2hDXI5?yw!H7#F=HU3X z1p_dfN)%^9h|`Gdz?t%dxMtqT;hdgFIEsV{yzvJj@+=dYE8+bHUhJ+PC@M6Rmoqyl z-R2gkxfGYgNR!Uxt%e^LWI1vzdcTT8<1)ivBd3QjaIEoSMWy>H%D+Vqami@E-r6;X zO8OqYG>29TYQLpWpDp)2hv}_}RT$~jtBoRG?wB)fU`$dH|oskfG9`&kg`T=<$Jj9xQlD;%FE0lRfbEV4o`3(HJW+ei7bw8D0g zHUIH<9NwkC^kpe?(y*$m&g{;o@Kb>`hi1(~{nf!Jg^YIkF$axwFIq~QY_L|9k$9j^ z(^$&8g~e)yIt`caSE{TYWaJUY#*C?*l%HrdgiktXM;#!!F~~z=;rp$u5>Mb)dGzNs z1{Tyxn#2i!UVA0wg%Jl__4%xNVAN`Qg!k|JR#IK(LwH*mkHom*^kwL&S7nBr|GeiZ zhm18Z>dex~w{UxHsyAC_o^ zh!UHAhxl8*PZ4H68imWHR@iU;=beSZ9qh-WlBDIfp{e%u&kcK#8n0l*8y>0tDIrVp zuDx&F>9DLu(F=xbtFo0*{MD|Xc}3uTYAuD1zI)b2;h~QBFZ-}yRq)gWG9x@Dy{sMH z?K>a8k@}#==LB9GE5@|B?hTZ}LYatT5_R$kUuUt@NIUrTF_=A@T6!iO@o>45kXqj% zoEULLIqDs`l{^AOKtyqM_*L|V`@pNryEnlX?d0%RM;w)Gk)r+9XJ%1P2|d)*N>(%t z7hFyGKO2C4g6@BbM}M(avJcIW!WOZ|)|Wsh);1fgf4yDTY47mB2kSq)Oy0={{G}WS zG~WI74-ai0pojE72GX?;p^~$IA?3;R$>q?bv&~50_|UW$rLVOEk4ST- zs&;!KOiP}r-!b=DdFcK5iomhKK;xQg!p5pHGC~PM-?Jfd3(Ci);if}?RXD}~G1VfA z{~BZN9`bdUSXxzt;QhCr$tzVmBa+7GOqs9iA~91a(&FQ$8cV0^3KYu_7OnoEC9f7C z)ir62s~&0}PG_>zxHB{6PDU0&l#hN%8h&?zn4i`q)(4V7!6Oagv~bu8D~8rE6M zZQ&b-vkUH$GcpHX+HZzp-aLy!m^HrpAxoU}u;gNVsA*)5DTK#!P_n% zJ@N;=T?-X^1fDX&}Rw=g)%(CAPTs*jit)5u*!q{mNID58hSc(X|L zy||`b#m}GoEV!rHo4jg__GtAn-&qi+&7bz`b|$zaEYb3mR6a)JTJ@JyLc>|cXZy9; z?E3P2xRd&3h#K!xk*1wRE$z#)fI!@`jLSE>Qv$Bf#_#vL?9p7uHMdDhDI_QzzR7V#0OP&)8OBY0HLbspI{2CMzl{q)h$zPyCdu~kpX8Ght2w$89zA9pXF zv`6d1rv3oUaPCM#Mh_s0lSxj71c?wKV_Z4qPS)~}Q)N^FO7(tL^(-USUm3Gyq_81) z!assVQ~$&3KaVeEd_FZYyMBFzSIHftgYI_2(Y4iOgn2JM2hIUB`4*4~1m_BkpV>emqlV)}|oza2k)M!dCp zr%w`O_=U!#S6Ck__3-h`0<-Y_fifo!3(gqCVXet*=!KDy8Mb6I#YU-NQz&6uo!MqQhDp^bnZ7PVCG*zJ4p32`7h&z{C>qe(*c{oX&gL#%5zcQT-c=b%<@FEG>L1>4?>HLj1$w{Ye8Y_(e|X-w zsc!`bf417FIZFXV`Odmo`uxDHSpM{-`5bH#xCkV7`+Nnoxx6xVS5|kgzKV6#_@~n9kdY>-U@WiVoo= zC2Jn)34HE0MQXxBynzXh)qDj-d;{+ale6RIf&tn5ck86`K0HMfM(RV( z8qXStGwQ3my)69h7m6q?^{~Ekq-7&c(0J}CFrh^Jii!#?=dHK;^~{3v^!24EU5!=a z0P$^qKrF80xzK~QMQ9zpyEwLVH#~Oe34j&gMoAsCtd2z0N_)sjVrndp=#46Rvmv01u@ttImxsSDl-q)? z!Mj~UOh>IQd1PtY&bVn_UKNJP4%XXkW>b7d2a2e}$WN5%rY_m8VBijH)h`7b(70bB zxLU~A81cSY9{kaE@^Nac?5O~QwW^T6o9PpVY>RfLVVQ`vhA83;VoggYTZRvkIUA>T z3)iZxn&{k4`Rhn7S#H%>Zyk~Tm$qHm_V4M8Upa4ZLGB`#o4$MiQnDTjBekoRgee7e zjN(o*b`aR7HRNoE4 zjXbHt994pVPqF2+%8+{dUnaM3NAB7NR>n?A4!ezO=GXl|HC>IVJy1g>ds&Js@l~T* z(y!N7!b3xJZ~51}1!op)GLq*3^{>H1L?Po7xj{xjsJ0ZvKi{8&#ptGBuxxlu9T7_? zJkR*Wdhe$X%_-Bbt{YqNienQC7z2!o~?tNSzd;6W%vcXRXv>x_j z?{ZeRf4|@6P`CO#A+U!I?AD=8oFs9p+c0VODcEEa|r`N)%Mz35(BbhccIqAg6s~h}dH-OY2T0CO;huJvklIQ;y zYwrQnMD+HJf{1`flP*ON5FsJbixfqgN|R0?^xh%#A_z$Dy@P=CUIK(FCG;x2OCW$$ z=|#Z1{=aYT`@VDM&fJ;%O>#omoa~;QJ$rWdd4A<~HR97Cmfu=TUF6r88L5^HWy*}w z2M)Mjj5@qfkLwUh_!ouV9`z?qJV+3kgLvK}=ox4T^xOUGeISh;pp|p-jO}H^O|n(7 z&sQ|0SEnYy4Gd-Vk764D$)ut?vf}UcGf*z( zm?hH_OQ3#XTSF|HwDZ_Ps>=ae0gkbpl$9?ZtEt^y%HehDn*7!y>2!ID8)5QWyC@`X zDf7uh=zRbg#1JulqDG+EJmSS?mX0ATuhl7*s&8g))^>U@V!VPGZ|pP)$}POrH@AWC zs>FlSTeFS)*CQl^d?oWb49L@Fb7%xlmfUN;U)8jfbaI~|J`Ty-eiTh|8B8ZY1=?;e z!Ig09Bb#c|likAvFHm+vCdz7z{m%B&IG3`8Vx*b1wa3NQ=>x`ghjXFvttULr?pztH zFXQ!9dIXdlv9PPy=oXfTD3k_&vh!XwYJARcE6#cjR!uNt0Uyeh_KxRoI9Gnj4Zdig z_&N8!_WNZuCQg<3@z4E=TATD~au3nKjbP1|tRSfX@$v?mfP%_=v&|UI*c_Ul=Z)mH z1;@D|v`zHNE~9m}*_$WwQL)-WfX2J&(1xI;QgGxPpl*olfa<4h|8!lVvWeHYtV1u= zfxy$h^X)~;Tf4V5LTKe84EO-ovEjImj1-1(sAn2@*~M!HIDy)Vfcb>fVZ+Is?qp`c zCcor1_WONy4{!YY^GbDokj4(zp!E1jz(BRcEUP}NnXOXs@g!WMi*n~S?n5&d%b`~{uU zK#Zz4nQ4s4lEat!B}z#W`%~kdCs&^h*#H>`U8QYFVrM7#H@6RN@_dH(onv$ahxHzH z+!`DziMD1Od?Y)Sy+auXzn_uxOB28^`~Q$R&^w^etCv9kB5AIXXK4|^m+Gt)sW@BC z)ea05|MgqFg+49<(1faoyTjeREE+?NwNODW5jnqMhXGxz)v&Ws0OfoMes#2WZZs-7 z2o@XtUJ3Cx;+UB3Wqh|~8Dnkx4TNhC9vmR=^95f9G&55z%?kk{N4C^2GAfkAr!Fg< zj&#QuBOu@aBq9CbScy>~t&_zjA92Ps=nOf+(?H#*x*3C;VO!nh?lkQ&f=-a#@R`>{?gho^9Nnt42RMjyh z_!ieekcl2=0W34IK85>(+xw$!(j&V}hS44AC&Ahw_jp_j(eX@D@}2`B4h(ZkOhtj> z-Eo)=O|z9A*syktaj*6T<+xapFW6J3yd>#6xI&^i)CaW91Hl1#T_yfg<~WnYHkx;!Ov%=-O6#{uuuN*BdA`HfPF#GP+T58 zbTzvFD%YaNKFkKL#f5H6>!$^G)dl-NnKaoSHC^EV_`{Po_ZXVP6?2#SrRw?~PW&XJy}yInu?ZYfGO`e4Bqoz`;`2;sX1j z&hM=9%3OBQIrJ@aXWU-z7WLD%S1k8k_GmwMn&s#)pkBA(-kFLfSR7|XQyDglQLnW7 z{l%&QRI2{pqW=a%RsVc)%gZ{>JHok+D_%=oR%PYP19QDx5&)`9xlx1M)+^E92{ImUxYyPJI|7s)n^pQdU8Tc-AwoupAV?3u}Kj}}I9yxx-bu0Ujnk$n$qm_p7-?=;v?#CKG z*O-o4cgjb}A~W;{4@*NY61i0HKnfF#YS@j|EoNUXC@wSCBI%qZ75P5%G@$ngmd2bI zjSeiKRCmLm5VNy;8?CD~B=29=7`n=b%)onpJ$X>{V-pYhR(Q#jb&fqf*{J8$We8ln z`1!4=giLq%8kNHMd5(IyG4ZlSem{visOUc<*J+4<(t9JM-#oCwr8hWv&XqZ-PHP`l zDe_=rWA4H;f1|>5_Y1KvL1)x#g@J0Fj+1F+{Rxkd#vtukIY+^-a$6`=LY{uy?H;6Z zGtM>ZyLJ|{jrZG)Y2${7EnJ^l#li;&jQhXPcdtNduO0%K`b|cVbl>YH zh@yxdDFX(E08(7MGp{K#Ye=krpJasNVJi-HJc7o##A6VFh<-pZ?KR;LrXcS~*` zg}_P);Hl~%avs%&;dX0}MTd7pZ6)O~2|?=F)4*}Q_BNaY8SQJ$X`QO8NUj(3RdALN zN9sv$1lG*_8^%o`y48Vh_)QXhq|Leio|D@ax~;F~jj(vFm@m&DPO^yNFo($&a`cJd zEXQvY>odDln!sT8voCZKo0;@w=A}_Cd0Hu6+zj3?jh||Gld8DiBsE_m=yj6fr-k!Z z@)b;UZ4yVW%!BH$sAPGYsj>QH#)lq$r;Bpo(j(VYK?v&%iEn$Rpz*=UHUb0d5BH~q z#r-Ez7{SX%JjT03;BRAwPqiDP!JjYAs$e_e&_8mw`{Mb#L#cMK3w%~ zO0k{rkrytzmyu^R>^E`^TG>IlWJ@gu@lYi45GjI^nKG5weV%~pPp437&E6zy*}DYy z7l{N+v`Cz?TJRqcFrNomt^d|sFcdHQ2ZhQQRTXyD$5x1t&H7+tY)B>Lbtq}IwSxdS z0@glx%-N@oyt|2Alc+Qh`4!i`R)dj|eK9Q=)A7A}Pu$R^@`wsldOM?*P9p|-h4j3- zi4NVUBTT+`YRF$^Ue^;?*wR9UAAqt2PG^Q4f3Yh5VohIR>#&4!JQ25)WB7~3y7X_=!!nqt#BPtZH*V51MfIugz(rK9YT z5yeOKLMAkZumqEe$wyVl7^yZ{Ylg^b?H9krqS9LIklb>tnSo&q9F=^p==A3|AvI4j zlEMji#L1YzwF#87HQvHMuRu{l@Nups=)6~PWF6W9A-mpGn0$!u>J#bER<6c4>8qUS z5$aBZCgiuR#F))hYQiL8MS73q*y4Js`r@0QPI~01NIKB9a?IKpvGUcnipVEte<<1idPM3G1-nz*b`< zV?i3WF8PP);?GAe&P}T23T#C+E@MY}e7BgPxKV~yt*E&Vzx2?xNh_cqO)dPk&48=B zO|n95*k0V6Z`5UJd&fp(I2GDEJe+JN^3P=(P3zI-lvGs+HAe(JUR#@dOUy*uh?()@l(7kflo{;&(U!Y-6kzL@I!U^+gTYS^YPV@`5LE%R0u7dU9Tg+(4al%<)RZqGnJ#NxxF%YUlu&#xHI@3FUPFk+02C zGbAc|io05LR<=vfe5j=ON=WT;(=sKDskp2D~YiD^WnrF-6H56%J^qhU1o$iDeF z+U`31(Q$|#f#7IumoM@KHSWNSF|Q*&(z0jS*KZ6zYgI7`tlifU zMOhwF=C^7_AN@by-eN8@hV-tXW%yEmq+%DirB`b0D_3BPtDCPHg3_+{vGv)FYCE~o z*mZUf01N@6AbNWK3T0h;q8K!z0GkOaW<(A8b-H{3W8kB5l)$ND@QxGHC|=-VWJazf zy^5P?_ZtZD12VSG0Lh=qhS#qS7LQnOiBn=NZ%SoZ%_AvsZ6W)_cPeEwDvOsH9loW6 za7zMWVO04s8dYgk{Wg8^BQ||iY5#(#LqZV1TkZ&57Yj-BsElg|B{0D-87Uv`{gMm+ z6|nK%6%cmt$!1=>;*%L0!~70OH2=8w@-V8 zp!Xh5bWKmxEkm8oDunlT$rhT$*iW_cP(Q0iq{yp|rA1(R0JpQiTC+fSGb%y6^kw;H zb0|rCh!WhK*q+iXtS2Zl$R)_^nRnnpC@hf#@WLrb9v6n{QJVDFmRD@*`vh1dWHx1G zV{p=U6G{#Dl-oTaZf9u)u&?NcR=)y}0nhFWXn2{ME> z!zRAlVyq1O_@1emq#nPS_%LJoT|GedxRGMhl>%IMA|eN;4Kj4@NK3DVmOWeklRT&? z(qkE=@Ey_E)O2F7e8p%rO+ovg%$QN4F-9+ZgBPgz0bw9UM)NX_ ze>c3)Hs^m93#L8{D=0#WL9NtW=YP z_U6XNeWh;h-A$qUupzxzyaW5)wclAv6XBL2>Ali#$1HLezpaOErloR{|A~yh~-F%UaY{v~1mEmC4Luh;QxcCxJG{g?QV z06RQQxKhlie{3@Q34p*B(H*UZZxii#s@ELazw>W`!mh551aEBut7iWs%gZ|nOdW#b zq(p-vg8g2;oI!Uje?al}+bmR~vP+ixfuN(h;x63$!6K{J&1L>VL`0z=y}vzxEao=Z z)uRC(q%ygwnm&en>ioLNHX0e_2%Yj19q>e_VRb_MP^hjtVdWE#x|36klX=*Fzl<9-4bC$1!RO^of?s^ni&LQHS`M)yicV6rpxiQwH7hG?9Zh3XK{4xInz^sH% zr0ODMiqeYGQqqbT{aF45`U(G0lo2|Bd#trE@W&c~23(uV^k1S8=xLk2A}S;E&o`NT zgRGqxZO7Hqb|vVW_K~0&6)6n`j`g@Xr~Q`>Arwif7PjfD-?ZYJ6Q%kgsQQlOK34vZ zf_cIt5km;^uu9QB1~G9dYRb_wR!Xyxp51`dOV&P@!}9d7#(v!Q)TJ|Mya?8QgMl79 z-)}Q*xg*zx#lPnB@p2ZomgN^zq_Y;DBce#s7TiGl{!i9A;~`yiOj|W1Ka>yjr^c*J zuEQ-IROvm-lVP6EoBvG07~HYV(vP7dVRGhsjo|j_Uqo@Ft-|w+&$?p!cm*p5(<1(GI<`04VN-FAC>m`IYvE4K2^XxPB-g0G%?VvKk1=GS4lt^-3c z@jt0WES~++`cRkT(n0y-MoZz}d>C69XTc2m$6N&DV+a3(QoxMDF|hJV>T(2p1zDEb zEHDu?5tL};0z8~419|@us+_e1oHgx$e$os-*JjcwTNNn9PypVb@qrst`K(^gdF9|9 z|5$QDq0CpJe!YIP$F6=Q?sJ)&(dHI4vaGHDXq z6;*0Zdlx~WSVE)6`c~fcUfP))MUm2nHbo2zsC;hokH(j;?uh_p>u8n5<*GOzWj^m(*`j@J~sE0BE=LQ)4vSWrh{n8>*lgasJfOc^DSM#oZH_D{doJ!gw((C zPtu8yN6`N$avnihEPxesSpdtxQoH>jWl;TLhu5Q$$lhItmD+R8kVk2CHHQj&1phg_ zJ&-mUap-BgM|rpJw)(0_AA>^>ri~Tb4VFiV?`XV|gDk5U-`%4Yu%z0sGaH2+Q#pXL zH4Dtqb!_@QLEhRR14w}hosY)CXKRdr>A#Gu!GjNL022_AqPhivZdB>cwGn1MtWFwA z0(QLHCPSX*pI6?Sz-j< zEq|}jEb27%xcHX_9=(LPcm6x*L!jQT!6R_t7EO~Fu5FUo=%_^H(zv6LNRq?7Jw*%r zarKXg-p(Hdj`FL2Pr8deV$HkJq zw*Rn{iXPHs!d`9)soKDTS|Fqwc|eAi@p`FJhx^U)hq zp=s==Yz5t`@rlFZOL*=>j2NbUbPHUvZsWHIWQCfuq)C+a=3{UoT=vhV#^j&4f4Nlr zU+XSauLSb>AN_e{o>S=jTR*vN^txv8P?J*m9PyMrt?F>#sq7Z^RP~1+KVJ2v;<%~| zF>Mj%qT(l<-vX!UROo#kLZ^3|7=K}(sO0C>^Yn5&EuqFNZ06d>YTf%b?0dmy@UJ*T z{i^%i+c|cSDpC3Ln1sHd)mS{DA+s-Bg=c~IGJRgQcC-#4@`_07h$nV5JCdW-2?(Rd z_q->LhjigtQLbq|$uwYe^f>W&>67n))_dNA;BSpJJbptQ-3XzbBqkpI<76;%JBm-g z(|e~DmP}Qji+OA@R|k-v^WtXrWhNdOQ4KG#`egli{cN$?lGzT<70yK^K>>QjXT#MG+CA2xn!TO4HVt zVu$t|HL=c?4t$vbF?&t}P=&A^*>!XiK( zhcZh(*_Bv7-W>y6mVl$QXXX!Yd1oTebLW*8{nY$Un}cYW$`9zX!Vd zU##HQ2iAqj8TeVzU1;9`S23b)3KgoxPLipX1NGqm4)f14PIXp-u9FklxL!Cy1qj|KHS*vWiyv=8rYXw8xRm0=Ut zB4Fu{T#C?3Xe{FJGpyIK|!^;Tmy4CXmu5o&HO`m=jvyyD`^a`P0fkIkr11-Uzd#h;?KabU}XZw$hl!DC^=Kso&7L zdwzU5L}E8>_VVs|ksJB*7i_pQjWz1>-xI51%(>HuLBfo8m@etv##+93KEJr3t;d@=SxQ z3Nb0eG55qqsDd0$(&)XKiqR`8Om;mhC|~By2-n=@D?noX$?Mf)S0clfEb`AdNTus$ zD`u0gOwu$^u04e0Ux7-&yLWOKqC@r)5l|Rw(?rsAM5uD}|nDNDA zDT^Yn(==UowEcZReuk-V-3jkHT~hbR1lOlQw_&q3N`Moq?>1@m13S>-!8FB>rt+hX8s>Jj3AoFu0ub#R0_8UCai0>6& z6d=p-eWLjH%Q|V9A8+?F3{)|eC|LCi5IlQfhYP4?!O1fZG}#c$#)yLqHGAtC3l8IZ zGtjN4s+)&rW@LNPRqqde20x~4PF**KKYi9bA0T5Y%O)Fg?wiA^DEg4o4Al*9*K1VD(E*h-FEHkKh=pP+mNE0C<e9pxsRUN9(C;k)Ti8>FyByFIP1p z*O2LANe8Vi%}l8g2h6=H`(X(c1fo$N5I(8OHV;`K?E{#|0QF!Uln+WEZzZi)`VAX$ zuXyr$6j||l3-+WGMf%x=9lQ)$DK<<_xOrZU( zw7{qqwSRo>7CJhYj2xzF7@+E)`~^yR@5`t;$07`RkQLDR#|o}e@d!dT@H zhQRlFK$E$?xgQy@m1!9;mg$QYqHCJtQ27~CVGY^|@}CjS36Y+JU%PFvr-ITyJL|wi zshL01l|Sg4D`3vM?Z3*n8M!mJq3`;wws~+@FntV(jCnWVMzJZZ9hj3%R10(`CSTbxdf(dqe!rbcg6A^1#( z*?oPa>dT;RQ$=nw?wh!G`bXQRc zP8hIje@B*LZDU5v)^Zt!6?g27uOsgjaJt7O-s-`rLzp5B&iTwQ3hxJWPUI`V>9Frx z&lKz!d+ys35h^6e(pz|KbRWGDd>T$Z=8>w>&7X2zCc<#=l}R|pvX&|YU89IEG4;lr zlGf(E-DJpi9@s97-;I6#-XG(Yj5c~i%tu= zT5YEG@ojJf8&zW#F6vvV-P8RmJ`ir25NL6WKl%8hjjZ2N_rx`XbKNghlbuj-*Mzb7 zdGVsisl9?N5sfz~PvpyK`cp=;=%2MxAc~LZ$W@scuh|!iVa0RXA(Vg$uW-7YPLD=! z_^l=5G`xlMwO7xFo~0zwsv`P;2>0?k`sRU#!`yEeTQRD{F|<#l{z6cgXn!o}Kfawpohh z%5?o>LZU&zcMfbzuumQAOri^KV~OiKXMX0o=(jj*LM=8CMe@b@rgoSp6;3%Lnu)^` zIV#wjT#!G?bWhAFF!pVF7OHVT(2AAUK>Q=4P3f~w`E<#nQ1DEpY~V|t=v2L2+eJ6o zz`R6{^6bTnLSz*+fqyfu74EWYC|`WKsr{#cuAYkexMN89xNSohL~*>Ek-m;fa-2uI zc5EehSg#YhSD$4y;U9)FK?H;y+#5WYVyF3?uux+s^{Fh0&*x(@Uck|mTBu#Yiq9M~ z;9vE7?D1z>ZQTuYg6gd9)$bE<`j${^pf=a-a1-OVO|lMFp`g-fb4_SozmkZz(6e8B zVsfOz+xEfC;R}y}862x}Jx8YjlR~QGd|G?z1u8qxA7!>L2ti6jJ-tzaI( z6gzaNehkcv6BXs3l9B-ty z9&k?K=s7Z_=D!51gcu;Pg!eeVS?Tz^vSWEq&giE~9&+-$2GM)02hNElc`*6X&i)&vXDV!<~&FGY!~#@~m25 zDZ46mD8^i|GVH;6)ED!qh0qLl9C(IuZMRV=;Y*%zfr5GV!A&|h_Q%96H=QW+L=g)V zq4)|%v=g!!Nk~k`ST8syNl5(s60}^VS)o(@V-+_ey^h(Km>Svy66iDz4NSLsFeAMK z&eTRzzf?RNI%H<%4QE@rUX4X9`!S>{~gNOAXlOO=0NR}E;C|d&h`27w|nJb z?#~xzo)I-))>3O1^}Dk8mpzZc9VUz)p5-W$iPgk^CA(2w$9yFh@5$Y;Y7z0&uBvEj zJ>(l6>pZ8D9Q@QoqW+Mr2AvQ8H3H`{Q`b+qA6Ldu zam_$2j00th9}w-DzbDi%);OpIv7~QN4uaI}?KMz0Dp5U&yqeggYw0yw6C|(VEq>7t zI~{55T?umUT)m~Y?a;ybld(W`O@L@XBj4`)Zkf|u-`63b9PV4H*f==S!)BcRl-|w9 zD|5Qw3VuL20!nS>MFyF6Wq}q8HD!L(lk(z65;elRW+EjBdW1BFwU>sB7;KU!f^Thz zA1osA5cvdx4PjM*iSI^Cho0ME;i&hn*<)96ZevZDnucP}WH8mZt8Nz7T*>*IsPxh= zu^_Nk-r*;c(o>7KXfE_ih%Pns?i|{+q;T|E%4tSeipZ=BQT)oyn%$vGVfpqXgSkP- z?BW?y{DiLba^qRi%aum(;3RMDP0?ShRlnVvTQ&qXjj07kfiq>bd4cH` zA*ZZ??#9~J$m6hu_scC;d-`cJ1gZQzU+b#+C$LdDX=&?5`ya*AK2yW_SMoY?av0Lr z>zC7CdLqTNrm-%AS}4zD;B;TOJb-|vQP;zfC_OqA!4q7BvC>su-+ zobPa@DP*l>%sDH&%cbcFTGmb~9l=8(9}L_#jhWCg6EnO3OOqHkz0n=J_*v z?O>Ju=N&YDt)B22UpoH4j@N^@E}w0mAi< z`j;9n!Tzux<#Qur+r>SR{r7J}XLTV_-8C@T4H4pLUGsI9@hm6gs}UAHd1{MfB4*|h>6}mVA>Bmm`$V0L&!Zx34IVv~xDNUb$~Mg|ay%mdBF5iW{)4{Ez0yzZc;Pz;D6> zV)+~DWOWt$BekFpG5>4PVGJ#Mh_@1Hp#m4>I9@Ia{}1X?s1{wJF8S7j#}Dwn;AQmD{!J$Wrvz?*X~WdW%O{dAoTD5 zLdSfsA~1QSeKo%B1ou^5TBFglQ39LOo=VKb-IlYSylP|RySri08;e`NoP!BCx%H(= zif>J?yZcqJb-+tx86JL*$zQBtbIVuBc_Mg5W8EOGi^&@4gXu>jhr(z3E9Dptsyn?T-%OG~T&(r;s@tm$=Z)6%*Wmt3ofqFGThFYt(Gw_NKB zLho}-s`9Rvm2eANYJ^;93^76E{WYC|#O}i`0V%4pA=ebPSu~@r8a?YaVcl=(33WLE z1d*G`TtQ*DX0r!!Z-qjkBv$s95*1GC*TJ3Sw_Ah}RXsaKsb>OLmrk}@S&@D!9OY)x z_RdkCn*lu;T3R5yZwhh$<{KD+vqQtMQX|P?>Y%GQxk%WZIqJBh`^dyv=Jyc^S8+7m zHvQgM&C_Sa(caci_WEkxD^gUr968UozQ|BxiX3#T{WJKeqQn&P481c2c%^%#-&_WX zxE6@a)3Q0*$bQRx;W!`XBX7C-?_RFz zlaPZ0U&-DQO;+;s?98$pvwx@M=C5b*RVyU^ZAW<}CcTlA^FTZJ1IoI-Em=OXTtGiT z`o0%H{7t6({I=6}4)Pi0$Gc)^@|;&zTy8TY`HjizulC3v#OGDAj3-MK(!ElC+Q;Dw zGYY?Qu4PP})LOEK3di2hM1Ej^Vl5R?JR6X)R=_5M<7yiH|OP-at{@GW8}=j z>Dc=}y@8cp+5|7m55&&B&(Iks&-s23IA~^9-klNv#DH^$Ck7t{RuuTHm8PqOi*UmC zM#=(=OH9m6&_Xsry_E)EF4?l>R1|)GVtf-(YMtO9PiK%~siD?PMJug@(XEl<%QZ@o z&}dPIu`4z$sLW8bva5`G)=L#TIfj#IkWSP&wvD7`GL07c%z@ z<^b6&8UR&AgiCDPRg-VVC3B>3w0PQf=EX|yUVz!FVgzE*BaF{;Q8V>u47(8;-yni5 z7CrE4NBUtpd$bHfiD>9G@1093<2d)WdkK$?ujp!2W~7;I=J>cqWi2cry*`~Xmd$9w z=-~krv?>7-ir}u?r)F}}gC~pk1LEdSapB<;0{fPZD-mcKn7~seM|sQ%2)wX^n7I32M=`8VF%uwd+gCq=X(l`Hv=hJ`eORpMLehs<;6P93>8 z%L0TwD^1M~cv>6dHsuMVeFC#4~Ai% zA_BHbeMeuc2?=)mFbKFLs8xSu@d$3jT!B^UWt813SofW?W2$5CqqpzWDDju;7o!~g ze<(5;I8GffZ{J@!IYuwRzqDo#Eh|g%>CDf;U%xLiruRwC$@;RRb}3kVoR%qlh>z&n zcaza@R3=6Yhqg8gt+l`&eoOeg#`vCsRb)6acx4nOG5>^qmXNG@Fgo?IWt5s}@U`{J z3&_LbQeXTuG9==9_UGt5+oZ=zvg|+WbY3o$lmvUzEDW8Mpb?|=EtBRcJc=|H2sO<& zKQ7c>Z4j;D!H1JKA8eL*yv>Skm7^lGXt`kWG}kr%zBI{-^?A+v>BxhbtHWErIr_x- zMRF|&pD!lQ0zNOk5cRO$%{u(~qDDBWGTbl8U?FD}<)2=uZx5@TiT+W=NbOE(97Fz5 zn+1k27x{8g7R~M?fE(0Y`LTH(ZRGwD1Tv@#8&ui=XAj>;E>7lb>W+Tu4tw_f{)NuU zm`IG{#;O3t??XXN5dW@aO_MRU?!bat8%?<4P+V!v3(C3Lw_5@!WId2DTJXdQ(yJWn zSksoo-I^#lt6@)9hk1pX!!!+a@(?O3*|)*Fy1B9|vpwfSn*3Nt+|UKYV{$vQNzDp{ zA>cA8Ac6jB*w=>}7*ufKbA^?n#>bt?bVe3HXhqq_)<*x%2}gYrZ0k$z6xLYVra-3P z(lYn38;6eED|OL{szoqMQnDPof-c~>AmZE3n`wbD8~Kb}mM~P5jgyUGLn>YUwWgf; zOdVB|O!CBtm7iWy^;FM5h&ju!ux6zhc}}kD&A<=*lw>%<-Tgp zq#@_HY=4NF4jwHTKkw#dr+G~S72Yk#qDP-OhHN$D^$0s~$~KteqRgU^9jSSn7rXRj zV3`(dUy>n6Ix#vRed%gn{Lp`Jr9mBOP(tw1T~wdFWxK?}*W<|tmn0J8E22(;qm0HG z2OR)Y9b?aw)ib>(v#u5&kDsYa?~@r_y60p?8|eD$l`NeI)x2mZv#EjIx#G7X-^ZKF z2T#hDR@)@f3+7hooCNw*D`qmk9Y`wIM^X#TC^w`)!FO-^jeEID6Nx)S$_-hQuo5@* zyg~Ek<;!G^2Bcan;e9eraZoV8a|XpC0p+}Dei32fXFO(8b&>+*)Gz8I$c~}lfK3X) zynYi)&SAs5zgX4iK!@lB3vYmDfrM7clPlLq=m@SkE=90XIV!$j%AAbjw0uxyRqF!h zuaz~`*-Lm9syDWy^7eI^p*5VN*!|fuMKsgTSoDMb&snT#v_yNE`<`{U(*xd)&c9;lzOXH|%Mwd+{KD}Ol+X@d_d$RH zw~;rGkR?t!?uoX^5q{CLbbra=DKI&fR6oBq zdpg6&?nHdLf^q!TG0xF=4T=}e>LG2U=HUH{bu)G=AJ5fufMADjmgvBE*jvhPqOA_k zs&_KI{};tLPpE?fkI=llhS}#t5%3Q>ZmKe~$VkK?ny{;KaY!G4*XxuKgB}Gq;)t>v z=vHWEPdW5-dqWU_lxsaS$k8JmN6mi4;37d|ZteX3YjL|rDt1mQw~cowQWxEKs2IlZ zZ1hrXCALKD?NDMLJ3n{XPY~T=k?~}>{HJ^AdZ(Ilq18_J{x!ww6>x{M17!qhU$Q3) zX^hBJOuz&BA>YJC9*$Q$oa>9YH&S4Q%9?$C4u#}>PCl13ts%|0Z`%@lHdF^+$-K^l z;K04t`&r^^W+ODhMusZr5C$?|l9E5n4p;~Cl-i7j4&iWfSL&vdsM2sn5n8u}+KLR3 zuRG}x=#lA>L3^}hwfGA|WHa23|6;Y4b{yw?R@{G@os)JoYv6D$k+GZTrwsrpaKFOF zk^YMP^j+!rLj-{ED-`ihgqW<>ggCfxbw`Jb>dcrbLa@>rX!GVWV8-Q4&HqmWqkJZ5 z1cpk`s4g>tP0{P7D%(7Oxh)|zTT;GJ?<<>%2p9pXGQoqR+E@cZ*ccEfX#iH>h?J9_ zN$g)Vig(E@*V`4H16>dC&+MiDoE2CSIraY2h0jk& z#+3hJQC|SkUBB9qa%V+jIXe`qWyd^z!0lw&aK}dBVjneoIC`fOW1Of53mVa~ZVR6b zKY$We+Ed0h4}+MfnZ1OPEJWKL+-RIJ$j6h5PIt6%=u%3Tn}x8xW+QlhVR&nh;vuXwB5F8lf@ z=ge1akXoyY%HR3z=6^g60kcD3hv{&3J%|%Ah(rMNoy>Y2%3NTdWop%KRQq`aJFC>) z*O^my(!YFyw*`baB7hG2^Ys07_c_b;`ZD8atd>y&OGq+ui0;KRu(gSy<9(Lr7A4S>o)#*sWL}KH1G=Or?Jh2)v1=f z6OtXh3qSArzgVSzrrD=XcyIbzFvllPm6o%I)Cjzf%an zMQjC6P3w#!l z^Rzj?I5R4@Z7K>ygWW^?0jN{LTG9oZ=ZepMvCR13Rd+n{$h)*?Fmtl5+m@wG;t70- zihi?vnYuYr17c5?{a?ezVhA^| zj#ZM==Zg7T(?;X<-B-9`hj?XfEj6fF~Kg;$+bdfDID1f*yU}{wsq!` zC@=isb5&$+rP&B-_SI`wNnEM4x=)AZ=P!t!1LUVAh>tHiK&Y8_wjX;VUjRby@p<^) zBKqRnX*Ov+79F5tijUVXC{$l(Up>(S`dm}#R^?_<_d4ZMwh=I%4iDWXd*``M1Fl;2 z(YV#J_(FIOyFpTYDukOy-Vs14M*O5==y{nTbMP_)b-+x6gIi&C;?afzN)Ii$l#UQq zT~TCCX}cYDQ>cGbB;(hJocs1pt3f^sFCAH`qvBR!T(u~E1@Gn|t&zM7su#H?3^Pxv z_!VN$5&x<%UH*)!d_p>Pf1*L&%JJV?{B6lXa2y@W`S`_LN&hWqcc5;LV8pgsdi$@9 zSM~bnPNRSsM9K*If*L5Kriw&{OZSjPp*h9>s*{oO)C6WrQcK`3t#>^9S6vi;k>RWh zTq94&cu+fiV%he+25|m7sGj!BHvtro{;k8uv3Hhet=KMgfNSPIHGozG5FG{?CFQOc z2mSBgJEilRkQhx3{EUCwRY`wdEmhwmVleNO&Axa?``&_6agFAv8Ah-%9I#Y+1h+tYWn;(X#+>YTX4{}9z}bt+p% zL?|uQsPU`F8&%(2>c-0**hW;Svcape$GBO&<#@(b$~JU5sk4(7$}TouL~p) zixfJDYV?)qS8OmTz*GHGsII8^`K&MdlXY*YTG~o9XW0Ae9nt=i0l=eHq*A)d!RgJz zfFnDGbTY>XDUu&gxGL`F&wV`ZKWaGN$mJ6C$8+E0{I8khS43h>M{H-sWbV)2xN9Za zLP?5t4b_|Fsqt?DT8rEZJQwBgrnY(W<{2COm37x-8QI|)S;gzYj5hAt$D0PC+l4O4 z$yHiS*Ci7ZMD>B5BF~rO=pq*H%@0{x?7X7vzen5LC2CGB_tkNPk6Mei2D(XMAMkeO z6WvbrJGzDjlM>SHWmdz@iP6TDK(r9v3DJK|r>EVYc5QgDbS^{_<38eDv531x!%a*A zEoi6~UO!V?If?ex8&w-&?f}Oaw_^&%UmSm+zVDzNR!3Ys@DaZd<$YGzM~FkS+^Nxy zwX0rzPZnb=rY58feMD`w`;cA9;e{~YO7*+(pYEhlGC1$eFR$ZzhM>BBRF&tt{Fpm<>GjATz)m~n zGt=$+6G4r8=)ofm(pM3$!%qvw{Iox{deJt%;OZOqv#9_O3*Sgm@$9r&3 zS}+e3hL_emKsryWp1OFFoZvhlX*RG4=Bsc*=@BksW1cF-#8r)rjyE_c-?ykWhxZB_acXzh{ zGr-_X&gA?5z0cYA?o;>HsXEhL-A&EV4E?P2%ClYpe3JKGRz#5$+q>!OWW^?nBCW=4 zxryX*E)mYh#dq2LwD^0ev@EHWAmaf`G<$P5E3kNqOkqMNn6l;MlY!md`ogi+=hD*} z5h-G?&9h3*^SIL{eb0SAPw@+ebqx{GE2bB7JY9|nL=GpR`e9i|SX>jpw&Jn>@(--PskK_#kxNVL zdVOJf#J((cCZy9ik|M$Uj3-pcQb&+4a-VCVDOYujjiShd-?5u;6{I1dLnQO55xeg9b zbQe2R-%eUCiG)P+H?O_;j!aWPH4_(5n>nB$|Fa2>wKLs_>dc1{0liTMk4DE2x%p-E zRHZgqU(vJARX!Gva+~PPXAT8rg-oeiu)oWsh$%c${k))*ZswySS0gFb5J>Vs~Te-3ua7i-M+REFOd)@5{I_$V>HR)F5;M#=yo*?T%w7racs;Y?rj$G#!OgN%6}k!P(FA?JH#4bXwo#`TxKP z(Xn6ypDkuyjD;2;nQ`Cg-WU9xDbcuzYa;2J2$SdP?#wwdGaV+7P+4}-#X8ZX*!{&; z%~F9w1b*B=@sQo&XjkNjei~RpHT$5ebC;28s`ediw~p>{-Dhm%;1!hqLTekA45KbK zo%caS4cZ7x+l8h=HbmJ;8^IU}&h68V6F(&}tDSVb5`Z)T?Xg9qyXXqqy{Mdn+>|3$ zjy*Pd^H~n;wl~USyu|xB3I3Y5)TGS={5UwylK=Sx37t1?!GL|nQtJ`3?;{X=o&n8~ z1Gm#3HXolW+eEQb8WXCezdp9!V)4|yjE&Nj+N3p9Z;TNobcj-LJAMsGnQ0)AzzbNLGjVr-r+2H z!Cwmo~hZ9lOp}xaTI-`gtZQx4-LGqQx$bAW5qm9x~e< zzSTC)_QZXZfS<|&mqMln|A@;-Cp!9J)zT>C>UDiaYb2yC-5G?Kiwph4SjThdD=0JH zL+6g>r+(%$+#&BkYK+{|uA)1&%?ICT`MwioUm1e2{T5@~n?&f;eWmS(JK@NQIlOgX zwH_&qoCoQl|ADi7CdiW4gSt+0uS)x7uE!}mCB^1->}x$v#l!!|^iOm8Bz~?%LNH4Z za<~`qlVsG|8`nExLNf=v2>W86Cw)(F09V-mzLy_inK-tYYFk_>(6vHk2HL`vUTIvT}g9Y9Q7Fq zxr~E{gdSK1Pom`ORDH=0F&SXx3!jCT7_djO_&ZQTF-XRG#u&&CScv{mWmu1Fq$%F!asUA%Qs%Rr&NsRBAgaU(vhWf5Ho6D?+6`*`LkBTtwe8z1A-Zi1SdHWB_Mt!&lXBqk`s~tYS88T*;g8gqu@#a% zM{Ti>UOxk@qrbwxvt!;q&8sV3*)y&&_nO=SDFJ`E#l}?CwRQFIJ}Z^kej575XW=!M zp*|(yC$R!47qhWmV|0kWnFTF!HpBmXeJX#WsCf5x>K-M$RakGcufM6*K%1N)G$eo3 z1rE*mm8aoO4y!o_OK?b>x~c$H3H^b4p>8v)T2Q=xu?G8u(tYqITX1n4p(Habhf9?e zy-CjcwvVzzS~UBx-=gH?(7J$9slP6%X7)LEAC|RyYSmBjg=}3tC7>5i>J0BRr9PGY z6wV$PV@Lb@kmDjMm28 zCLra%$Fk7Js1R$N{d0T#6F3J)^74A_(0se`8i^%u1wzVL!CsSb#GACDETNt@C*J;Y z?YBCO56dQYl&dv_g>>6gsvVvoDPHReX^j)fgkR72ZFO04Mu|A9qed3pTzI{n*4t_^TZ#`;ivaP2zX_6RlZ*zV70?C% z43Lk#kKL56(vs7!mUa1-vBdkgVodp@r+~ep z4&$J!`N3-aIOC9%`*&OJSBZyS^{!0aT6tB^2O5wp7;$)lG_TIn{N9EpSgn&b~Bk2AZQ6(hHgf~}eRV3HaIg%NYhO*Qu=`_0ah3hhwgSN1;~5PwT( zsH(M_o04$Fj6YTIt+0$*xrZU%WDE2&*MxjiWFKyG`a)-H)bicrrb+y#+gbU3buwQ5 zxn@x^@@x|>X~4$17C{A3wL6J|@>QrgY2nM*PoACjHQ6QMy2>#v*nmQ%~6hjU%ZKIfL?XUwpUcWto77ghGl zQB`_I-mG*xq?(^}5CzpCNWXX(XI^C)p@)Q%n>0TuT5C0rIX!ewb$z$P!HL2X^{V=* zI4lV3A!i0l__7>!Xrt6xt(N(AAs5WKxaB&sRq-pztrTrssn+7KK;eMdS+q%W+rb+E zgYItyg1`NQ|Bns}28;Gvf8dIUx;umxG#)QoKhE`xDNVYik(X@>F;viL6Oka|3Z}>YW^mcRFIDiMi znzbuS?I#L>CwdpvDVwMNH%_A}7uCu4EdPi5Q)RJxd-1!mx_DUkzJDQH@#446Qwbb_ z-d4bD*R493CpRoRV}_}H0Wq5%`uONA+sPF6N}Y43rU1SmptR=O4Ivtk-)cKTo~wqAYh!+K^CpVgx>8?~C85~#)!n_4moK(bhGVQEnb z^GeDf*%Z6rGtxXa{87HsZ)FVRHj7=#1FH%QE_buC!cI{Cvb(82a3NoQwK8bu6fwug z@3JLzWaiXuYklaiCaST&Df{SSMkv*@+kg6_SBHd~e9E>F((!XCk+%GM>Gn4>!WJrJ zzZ2#9A3+}qFl@ns!@~Z`6Z=qw1^|iipif6~{n}d;LY+3^pP~J;Z;ghdD(i^((6o5I z7PRr!k zLuwAsx;LVX@88O`Os{7Bfol@7ij-91`4)y4bBA$ru8=5d#zx2kLE7o{AriD zBcP0>r}UAS<$P+r(X+A=LeIYn-%diRp_QGVuPJ0MG`3rfGPw{GST@O}r+EW>)zhd= z&MbWM<3tl}(46BmWh!mZ`2ehY;-ent?y2=wDX9e>>2O7-dF}WuVLzsb%K$6Q^h(_a#rqb8)ET($ zfs*dS=Zf>g6RG^=g;kLSlZm>bW-|+$#l9b$8ceOv;kM3ytL4FRW;IR?ZW&HPo%dX- z?EyGNKjZbkksb-IT`3OYeO!~;9!is3Y~?CGcL}5;meDDnIIYM?PWg0BH0dzMDFP9K ztqjcnftwi+eNCdJ-EU9PrYw#wDlv|?YExR~(V#s?{hL$1#_#nv5t4PWPlF};3mUzh zAAh^5hAuv%J9tCEq~h*sz&^#S^PX zD`2(x$y^orWbjyhSQEyVg>T zx0bkis=2wu+vZg=yj{L=5NAsExy3vCsa+N(=Sy?(QyW_)KsqC2qlsAoJ1N)fG8qnQ zuXNErFZJV9UmCr-Dp`UOn^Yb0wuUUB$2>X0(p?L-GmTFeXa+8Ng!2Md$lqm|+wia* z*c0gVrl8Eu{;~zsJZ-4?g+GN6h^ZCoDkS0bE%YG-e>*PVscT*hdP)WfXEDXu*DCzF>q!p+j3KqLyBftx>d9)Jv5W{Vc3=+Lw-;QgpNGkL(r82au+uVBaF3vb?*s8cW zsSn+SLeTkPy@XQs-Pd4{Bp&tRMa-unAEz&3&)B9FM!6TSqTy1JlwyzC*)YPTXxm1rASz==`C>Z@gPR|h*Q%X`+~%ZJmgH%=GBK0d zzQv)*k|;{*otRln*rKr*e=^o??ZEU91pW`)bv&#)(*PVR4m=zJ0z4uDGBW(XUvRjT zpG1_590L+?3hHJ+@7a2Hz+V&%9sKiq{;a~if`^BL7lx&KytwFsO(%PAW4sJx(w^K` z?isgM4McL;>~AST7I*CD9GbfmckH^iFlEkJuMTcr!dm*y99qsf7S09r=l;t<`6`cq z|4Bik5#s&-IEZvN2>-M)Gh-roVHBXSJiX1W`Cksr>0E%TdFDYM*y_d9GT`k^kguO9 z?Gwt8$CE6rMXi0yg+r*WC+jqDokEKHvAQKfYr7Y?wOTo_8k6|A`}q$X0AUN78fm~$ zq!%rd9N^v!P!8!sJfvt;f3lw&iAW*5dG3s#rTyyndU4p-_%4~`4;{}=B&8uzh@UVEo9ubrDv&}YtR=r7QwbzWM!r9mpTx{>{C zQ{lmP3%>Y8_~+gU@1$3#@Gr|cvUuVi7H5wPRy*(n+geK`=dWWfRIGHdQe^_swUzol z3hvl3P{7%qV67+>d(BqnYA!$uXXBENnB0cTbcEGp--2X5q!?C8AwC2V-=W}OAwJc1 zzx#+m`q}j*GfjiZt`|vwQST6QtNNW$=sP2H7fqHcvmdyIs15H7d^A}yEB0<9|9K~r z&IBpab+k>w;w<<@^?i76i>YN>>bHIhN|38P{P0zz_Hv48`*e+G0@yxq*Rf_B#3(DG z25tR&*Tj=+11r736V#}e#e~h(Wxmg(p2@9YegQsXfqO@hQRGwm$d8M~nxkZtB?15Z z?{tzWPqkjD{p>YfY&5+cmA1}YSE4-A3RU0ARXSroG;zsE1K zUl_CztGFl3++!ft<7a8u`g~+14@@Uc;71RfFKihcWmSl8S&tH}EFbCQ?RXo~d0e{4 zsY!B&10@P-cbNkoC4+wj;~^gMCM)E3W==kXFkaQaMu7_JQ+I8x-V>Wy=V=W6=;+0^ zU=W-_Ql9cQG1PtcducbvOYboe+NTF25yafKdR5MZ@zx+TgWi`rNbW6_!VL_sK%5D6 znt)-t`?cYABjUEYeTT5k~>r>kL>5c;tM))N@ld!w*xxdj+@ z*lt+Z0XW$A^pR=(%t#9wSPTTFw>+YhMmW{O4ORx zkU~46)u1H61fIt;V6aR`xmY@daYs{#hnrA~KZefw=+QxLk()h5jmO|u0#?cy!mgV8 zJ%FOn=^6}pj{s={aPX@%!FCor5=6@$^P{II#maHl&7=j9n(4Q`U^C&cB?y$davP9~ zC!MCqKeV`~EuC0JBE zM90Eg+&uts`cIKtKfq)Z?Hn}@1b*SQhWh#ILbH`lL#d@TgFcD3NapsmBey{?ta?9v zYPJ~k1>3juu;>e45&6Z8J_1Ol56-aAEcS0`MEU*0Z734bdoFkE&xGd;u@Vnutg?(R zHWxMem2(^LX1oW;_pCZ_?FZ2FHka{MZ4DCaPYgzhQKqA&vsS_fXT06 zcfj!HQYkQK`AT8n_9aj9T=`9ZhsMaoWR@2!j1Q&V%^P@DxzCIA!xb5frbe)B zOJ5LaU#Q>)sf=j4lSD$&Kqc*CsPQ83L5?Z@3L zj*VBtI&&1nAb+81X`#UGzmeAmunr*GqjL>;mbTGAQ=5L4Sb8^CIJ&|7lweDkU0v>seshh%aJhrZ$WLnffG$~jEU#d*=qByv-kpH7gOctGFN}_b_SyrsyFojg%bCdua|D&tfbCbeY?y>YC@~f zF>hFYDr7UVYaGuvw3E=EJ-iF)mF#cbgXer6<(XaZzek?aPkdUhTQn#C{)1{}k>KD! zmwAae!T@`~1#lMMA#A^iRy8HXX_GP6%%r}Lp&-VKCaC?it|_#Feg&9IBL(C~7$Cm6 zeQFDOxXXs+Sv@kpGLt?ZE-P}CvPl8@>qFo!-+M{A83yjz9gNYbU;KfSa~@Zv`Yksx zjM$`O4+KD?Y-1z%e$SLf&mb*+ao4w+!Ure-uH2~;84^)Q( zMLox9jY3KPg?tEFAt$B8WOr8dYplL2AiT|0ZPLR9AGsr#BKd?|h=lyxeePDn@k@m; z>HVrKqTvWcS+x0~le5}#Ksv;*gB=~c14n@Kd&Wa4mA5(dToAsi} zbbaFv8`xbc-!iTjSrt+M!;=%4BGo&$H}?c1&L6AIryj@~bfF>T6Ku3bzfnkgG7wB- z1pH`c-R-*Z?VV1>zLt}H)l_l`{vBGbWNv&fFHwEQ)J+k7{4&iR{cy;O?xY~DCQz)= zKkdx&by2Meb#B!N{IIeI^9PknqN1AKuD^S37Y7EBP5SFKU=9>WH+y|~>0qw-2%Fm0 z``7`SZtW86LU*&o4G^!0IH^a2UPy!iR>7V65?RzIz3zWu@!D?wZ3V;&7k^^3)eSR5SU~cnN&#=WMq~Q& z&B8O2wUvsX!7$k_vYjaCSy=4gX!rSxGgugV<_{d&99wsN_i$UQ&zH3L<| zpVP+T08byXZ#TX$Y{vKv$GjuVxCA>8lME9GV8fLB<|q5F9oX&z5_IT05UTadJ3>=| z%7W`S3hab*t4Rn41TYP=2y0jt@(qqUp` znR{As1h`4#GSs*s-B3e~yqW(-K{-IdUxt&n^D=!d%i5)v?j z=U`dxq7xR}-Rgh0>X+}wMvFuX{{zxh?D1pvmrpmHJMA{@Mz^1_d;CAbY6SG9r95rH z`3OQ=#G2U648-*Pae2bWXS~gz5__0mDd`&s{2sP*9~*a{XlYaA>U94HE|tUw>nc`r zHk;^iALhyqw!d~d7)xW(ZTrvD=+}o&untK4DJ)%s&kUc?>pfZLu(?6{Aq_~TXvd3L zFI;Q3U3$GuTHj1E-%0~Z&D%>jBbK$Pw8 z&BgCmvx(^fVAq12>N728wo0Q%Gwg4mDn%amHlDP*-hinew`I>1ssLo28l3Z$FSY_* zNB3|3z#$lH%TRpQ8rgM9>1X#STRFQBx)J zmB*$KJ?x^24Yyaos$CXkGZ7Bl{95ci_5(Jup?Ug9!Moh0@8&riVK0(5$-d35_7 z0Ca5@P1|^K41gZhR=+nqXK~!YIcwHSBt_URpYSeYC38OJuo-w0>xV7@$SSmZ0ZRo3 z)`r^eaq)ja=pVcsOJI7#pCU+Zs!;cb0JA<2jDYkC=lz#}|2P@Ov$L>TIAnATO!0LK zpA?&`bd~mSzH-Nz>?Q>ym^D52-~Ywk@k74wmz|s#inQKhAK?_}$3Jiwy_<-^4Y%;_ zpgQS$r~9UV=2ic(v|M?2X597FeUbw|C6yPwP7okLYwo|p5K*O1x6S#L$1&N6A4pWv z9fD|!*+r!lHDkTywC$b}R~`55YM#>-tSx`li?4lP#XrB+xQ1|mg+*vEt;^|tv`6`G zyU!yX?`EHX!Tr1Cn{H&Joe;FKgBZ^KdS{RV;;ni?x5ytjiWB?`q|VSm?e4YT)Ezt7 z!{QE8<32l*-kr~kE?48zsos9Wn^EDM>4w!^LmHKYPgnPtuGtP4w}9ryXZjIte-#}bs6MPSI!vfa zNXZTp_z?59y~d-rUR+4)e`@*PrJ~p&*BwFG{wFB^g2?#i zag$qDNlhL!=he(JOB`y=v&DfNAi34~51ay40$Xu^zX2&}dK5$i7`Uhz)th3Zag}_N zd=m(Ag&7VR5Au2F1`kOO*+TEaike++QJ;`*C+>tODV}QmruxG&?g2Fc)pwkWdtHjD zeKXe6ITeEWOI48AS@J>iMqT14FylTvE7-5x02U~MPUCu5K4awNv%FzG z($zVAb5mdUs9qtg1WZbURU~#@+h+2XW2%1y{O%$njN?Zd(-YA79!CKJ=MqW)AhHhY*>uf%fm+^gGKd}<04q;T;ZiD$n^`X4fy}Z z6=u+xe?1v>Sq<=oQAh=O<~ULzmK2jL-6!1L4+(gPC`2dca|G)kKJc7(pOUJEdsGDV z`v+|lUi-R67ms^%Um6%WgAR$(4%YT+-7?t$ZSe&|FnkEF?;Wm%u@^v;?W;j{ECGo} zb3!l0b$-aYx|@PM&YlzsI4&mOycKl|W{BrR|HSEsA?(t@8?&f#MEl>-#?Bmg4Ar9N zCm`ZYGonDoj^DR-+(?F#IZIj>(TA2HB zxV`G)1R=7pE8Mu{?(F-Nn3zNRq+QxqccVn56#jp~{dZV^e7)O-K)=xbz=dB9!?bF$ zK=5g|^1uAytN;Eq-jW{o`kYSVh2=es=30Eg6;N{tyEnClj`ag^NU1plK-;-;^^9eH zz~@6zOxjt|?Jy?~MN~;Z(wAJn{qh!2lNC{NCvr-W%=}Ck4`9Uyrt~4d!|>tp%nO4_ zK(tqZT3Y1ax?j(c11wU?I03L`B2wfA@M+qk1|y)ciA=#7qmsz;nsp?E(FH0 z!bxWcz<@3XvlX`+3AU>hkok+C9*~r3e81aFF^7H@_?BbB|N@ zURj>x@BaW!S#G>ATj%~=Bp>6BXy+**p8A8(-U4tgfrNpl{~ymEmET!B3HRi7F%P0mq1mpN zd=)}g#(byI;|7xI%0t#3$9j(}gYP(!l5mVC1`U5n86H22l48N5h9ty|@B!Vxd*rrW zZrMS|hBr}Ym!DkWPejjHlnyD+(o zx~5~9nfgfWTbHR?U)59|0+;)6*AxsE zxQ4pn0&#fNr zT^wOa!uQvwkw$Vk1O_SR#2)tys#j_BWe8=L!f{o{hwd0_DnnZLsm*6I-;u`D7Zw0S zWF=1V7_2w4gq3+~4<*eR5bT!HUc|)R>5B>ErNyo~9bFve6Y||L0ZpHTt!_V=RhzR- z-8S{1PLpR@V+jBBwNK%He-YpPtlt4X-6ME4^C1+La;&RfU8R+g#%?CcKJLfq&NstHr2g#aWTSgF37fNNS+bxik0P@^+_p_{Y zXQi$S@*c1cg)?>o0l=uOzk~b`yT2p4@%NWJ?OZI4(p!SbG4Uvf z?$ON@f}`UAovLUrdA$(Ho&G0r!VeS8NN(eT$gs*;y=&WcXW^VHu8#_Vahv~PzO}i4 ztqc@nZiOTItLAn}_2Ushhew-lQ$EHz2wHmD$5VR8!F!QF(jM;akw;@W=SW$lTdfLf zU(69qlis-&RrkG<}^CEc~U=x_K#ceWi2RAvhjGsaa(7P4K#T@td$zzORsYahB6?A<%55=2hY71 zamZ;{E|vXv`7O-D2W?q#8HO5-ZB8UVjaR}39^z#S>VVZxjOUF=m7R0*L)9*rB9yQ{ggm^dB@_ zFD`L7YQt~tBV|n|v0JU5GjgQ2282VWR1%&!NINNYJi2{*>D#z|s@R^S* zoBBK2h11aqXnnr;I?|3jp=4tg*9MPTf1zN zSvXe^fMxzyC7SL8&Icp)UmQC_08!i#_(}C1NmqERzLg4w@^HbL>EPM12r6p2oiQ7W*1HFv4Kec$brrGf=OT zEUrm0Hp^;A(tAUNY%pqlBZPcNN!G(<&-rukSV6o;9ULjOm`3}TyAWsPo3yuj5oH}>ncEyoL3aS z(z+H6pFT*`nP!9;bRaqbElC=tFe%1e`BW4Djxt7kzEpxq=!E^ zj-;jCPudFeky2hy#y>@)y{v6|N48V!Ds8XRNSV24e->a9>6mbd1)YJF8}W*eD+}e} z=gt%{bvX95uG1>nJyK@ftXw?@uT>FDVMzSJxW+St#!f5QlB zqp0-M{j%DZ}_b;O9LaeBGR!;NyX z8#0iv;Lis_Dh*iWR~e1oa`k-=j*qhkf_#n)r!j`UzaU$`UvRx46ceP!2s$?@onFXz zarTR8tCqUbE^CoKxxL-d`FD<979qqaM{lxCn zn%*k>`m?9nV4Zl~-ka=Qu`yEhxpcM{!4v&v$<+0msSn$LD+5mchC>?q`C_F&QsNVE zxx6!XhjB?)&E2;}?%g*X=wKFo^Sgvws<&$a291en_U$VEw>jNYE0|f$e&I1K0s)}c zzNIN1IbWX-siVIXPe6+r%?~1ivq%%?W1FE#$5Z#ku9?R#ieL9+V37d!?pWCOjH}im zS-REW<^+&7RHOP)Q;%?jxknX`8Z`GyKQ&)hY~2>!>rFpG?y*b> z&dskrCC4#Cc2rgl?1aPsOn zg=xpkDSE#rtQ4S)r3o_?EWM*}Ev0i(&{a90`@!3DNnt|hulpS~Bw2WV?U5uS z1@0dg51huM*m0|Mcw6@3^w5j_n8By|Wr1!>@YPHyb)|}0fBtc6lvrcJ?Rel9Dc?r* zZXqVB{3~TrLL^?jLWzTQrt0XWNvoeX3H^utrL)ChAhWyPQBn8Gkm>B>OH__tpx6{c zE&CZ=jKoP2^0=YmVYhJn@e8<22R100)%;G@TfabCcKF358=GKjQ@{OR&p1osY)!MU zbn%Akc@~m*h&3g_=F`DaSw>Km9I;?*_$#(SAqpNIGKuHA@r~?u2TmNlmdH=7Istpp zgI1MxniVZBoRKGFOIZS?JgU%mWl4H9-%p5DgYvZyxOVvvv1@M{FbXlk-8DKhO-qs6 zF8WPKyUVZziOWckcS^;KB}4(2O`JUhq7=;;*;`5wJ{CyWWE?(wgQTm46<9x9$~;!C zT)n!sWH(catGCxDUJ{A&o~mLry_-R2guXh>z1+=59Pp6>geh`w=pL$zubw8JmhSL* zAaT03LjcK%g#N=A`}PpGK8ps0jFzi?bi893#O|Y4t}@@-L&{5L+8>>Kqp4@suE^~J ztOE%8qHQYFL5`(>xhmJNu^+31=1ufB#b?caJg17>G8_~N?Gz-Fc=dtDV{ zA;rZYJZ@B-vnry__rno6Yj}w^L1!czXS_me57Oo8kze|(NVE4G&q(h&ur&<^z@{v1xlF%l zAmuBJF#GuHA2`&QF~^IvRb80;A@G9?3c=rl^EjcjN}g=dkNut~{DV)EX6VRY&ln-! zOZ7*F)N&qnSYdDtU4#`OVA2SPs~^KRby-p+ zpjX*W)p2@YhE(n(UnEt6-_R=BT&!(4~q}-lZlT zsM$D<@pVS@75MSkR-&+>Vh@VC)uExJ8d!&Ge~o0{IloSp#82~rzr7?Cu;vF5O&GmZ4#VT6D{QrmmBNS+MjMJ{w~}F9;KgJZ__C|PD??AC$~w*IPJ9<@*9_ig z++%;>Vrxg3w|f~6Q~jg*3kY1?QOVLX7v}HJW_4^95Qx7w9(iX}=;A zz!6%eoCH}YUz+cGizR7r5>FdS^v3$@f2$^-mY${67jc*vB4w%dU6=8t<9NiqPei86#h;HOV=bZ%3- zDhNE>oQq^T23m?>LD6E5tQw@ht{`Q7x1)5C1=S|=hEeQg+~4tZD=vh}(OOiD+ zL0y;h{%s_D$830yPt&UMh;g|+c;jgG?UAj+4Rb1r2AtGS?{R!( zs^q~vHYMpX#JnO$@T1b&0i%>}%90-!!Q+Q4;>~D7L+q^FSW^Ex5zGvg5aGf9hCtK#ja|Q2m`;6>39@Cl*~(8&CTOsVv*%U7csnP zQP3I)W?10QeY@DGC+=@TSKTEwUQwo@DBxn;`AZ$M<|~&5XU>F6FxUo*swRWZ+t2jH z`XNQJtncuy^{oB5XDh<<-dLQtAS{XK%~9i-Df6Z@)UYW?>zwpfTGL^y^Sx-{*kTh} z)zyPUk4PZ$4%>X;1!3cAH~1H(ky37hBFpK(@d(R%RxQ8kNcd}(Ygo0#;qg|GqPLvi zvs#M5lLU3nfQ=t`BIEz{iqK@4tqcSjY4nKIEV*V5f2xjEgUAZ$6jE9ZF);kL;&t`u z{k$RQnZ2MRUbmA}HN$6L=)msW8mUy?cgVc@IC_P{QEnvyEl{xBQbV{)n^oc!)Jg$R zdzm*j{JL(-U1@bqGYTVC8|CTZbHuMh5BZo1OC&9oiTo{ah-fc`wJvQ}TW0GW`At0< zg;)d#{S+B3yX;Y5_9;RuI;UFq%qcTbX?|$CR3|#XHdXK=vN3a5bYCZEt7?uI^TKk` ze8pyza*XK|p(03sudJ?_HPoS|l9U;{zrFB{C94VAhXL=j^a4lLf-A=Xv2-x2hI)qc zzIA}Fsh|uKvX6%K8LG61Gpx!y2`v&G4&0I(wpCjs|4o#*W{6(5Qjt>8X4mLl6GMlY zJ1?t%0YUO;`okA5H4MSMmPr~mG%$h7IYG{WtDz!F&2!k(Y#%z%GxY67v*W|2F-#{< zL9Y%Eq*EAF%l}5l{kJDD4fNOZ8yY~RqRQ*#NV3x%GX$o|Uk2EV7GG1NMZffq@Zoco zY>j68qG|S{>hf0bSc^M0y!npbK8Qj0EL{@f7M(|@pv{UQd_{%RC)y z`u(!0-;V8kQ_1p7z-p4C>&uy2;txIja?_bRf6|^+NYcy$3r7{IdfxCX#oC%gF1rc^ zy=&o09lO8^-dDQX08Vk6GahZj&)b9c8Q=rkd@$_pGmbD~^%^#6INjf7>r>dEbMRC#x;@DdGGg{hGy zu3ney6FejkT8l%P@KKkVJ_I?(Geql^6n9kwTqwR(YKVs!FBP*joO|utwTD^uV)%V< z>DB@HcZ%tErdkit21U|q$yIDizN5L9bl47C*|Or6PTwL!n~E)2i6Xr8zHcT@oWTjD z@rSpnt^p$xcd{zAUY&a3E~|gSvzx8ohR7mft0`jX1UqRMZq{_k)sAaA`5yGwwez=M zB9u50Mm3kr>Z}+J23rc5;Z_pB7u&(kQWoie=`-!8K&cGv%4~gzg#l zfoWGKNbs-)h{soL7Rlqt553Vu&^s#KV?Jsu}S6<9?xkH|%=s>iPG$#~H~I}4d53`nad{q^0MF-PjyO`y}M;qb7Ar~2un6FvIX z0LoBopt7Tou`j9YWQ1GbflE$IQqvO8?+Hj+CS#L>aavSc7J?L1W2uKRo8x!oI`Xak{s-9^_;#_y=sBCE(o^y}>5T^PN=>^; zK(j$F05qSrS_dD>fh;Lnf3=B<0Y09n$fEUvn-l4469Py zT|)^Kpd6{BOY49|R}25SaH;&aHAo9lZLAzk-{Ji)>=-JP)?6F5E%KT5Usn=3!(y3F z8%1DN9IW{ke2cY$W>eJ=!;=~?!${R0)@CdXWZj~-yew$)>i3)#c^b+uOb9}m6>A9% z(3}-pu_}-4QATJ|FDPPO;KPMk3SL{Lx+rTaU#PFHQTofSEEoSml4Xw>oc$&|LmM;9 z%#cJXw4h87Q0MPXQtmtzdz;(B>}^?{^p=j7M)H5~_D<26d~uj=Y}@RlW81cE+qUhb zV|8rXwr%qZzK+fRWM-|IS?ipOb9Zj)qUyG4*WNFl-{E?T>&5xw*_LSy`a*(0WX;sN zV&?uKt_KglWrEkrFpV7?&r{HR1hu3_Lmv6n#(snuqxO@*Qq)SBSA>Mj42i`19B5wx zC85TCS*7*vr7XkVI*rJaozUP^Dh^fY(MJGHN9uSLov}nJ?Vqvx)-8xl;H+t_od02*1x=(|^fx*vJ>5@D&YFKY&PH_d-O=2oE-R%N9|^Fc&8~q{^}q&{tv` zI~;TQlr7boC+#tZumr>gp;CI6*;KNpsvF*35>T|Sd^Yh9j(n!ERhD7D9G`Xfj9kL8 zqBX7i1Hk#0$g1+Ke53W_bbR+UYRXjA8){`UN`9e!VV?MrX#U75&4E8*E%6_%uxQ7M(&rER1 zPBt9%_>}4gyNZ)l%`K_Tz!J%Ya-kB=7xy6Gs#^_YKsoTo0aXsVVn5mpI&M)G(`h2! zL2Fpp-1^al4kvSCY(iaTc8HT9ShM$aB$p_)*orS=UsH8q$aYW0B8-1~_xcdkqMdq@ zdQP^ZT!@wpd^zb3SwM@HeTXGh@p}*jl;AGdE<57YTv|t@Z`m%_be!OYtl6U|oevwJ zlOKG8ra@(##Uagk_w_@A3fFZ8)guZk+8>LbQ`>B=+9KHyutHg`C?&(eFTGP6P#!Bt z2xJAKJy%hKaD06Bfe)H>$`joM0tmJ=ATLP^wPh7%_%l5T8rf)vblu<;WCNp3PV?Av zRLiBDaJD>i|M;mleK&$G?R@>lPtwTHgb*0Sl1KM|A6fj8dLNbP$B!BPW@m^}V>a&} zdHm-c>i#a$*ZE|%iCaapcNZkV3e??l2*W7|BrI?$D}__vMm0MVyp4d%xWb-f$F{ZX z`AwN?ky(Z-JM_nXvN`mU6e6Q7>y3a{4HwJG4zc4gAyMMbav)7cWwmj=#(y9kUPQG` z%B!)$(4a%_AHvT2Z_|M`FXFcQTgsK}8r!z>Yp@_0OJdiyg<=9u zC&yERk*06qn=oB`sWy7ff7C7L0s?l?Rt9Ze1_U z!?p)KXZCH4rQZkqF|7HbM(d-akDls9sphBUpO#MWy7r*3I97J+Bl+5Pwv=HfGUb5w zrFs?_-M%lK9YR|^W;S_I$zwZu!Yo~G;j%x8)XPoy76rs@2JJyz9-usKfIJ4jCE*Cp z$iqz!_X21#q<#%gaB0>zU!kE;fau>SqwsGkzh&jb7!ST&!G`G6M1+cW+;c|(K8Z=r z-qKVW*%h46&@!eg+NB^)43rWQ;y+}R98wA)ASNCiu-Asxx&}L~`aqic)W6a8h@?&p zEv6|t0R?16aH3VtxH01_CvG*vCA@@a5Ol3JO4S>HKy+T{CLhC^!-T9)#D?2!R&RXD zTejC;EZ&jtsaDPsKj+mXU?z_2T0eHqQdR`#W)K*qhFa*@I&~) zPhXl;2SgSv0dVXNpJ)|M2tBYyB%qk?#f(F=#MdG)P9U-FMaGyREgXw~eN;%N{WeTdLR}J+sj#d1N=N${_2`)h`Qm5yaRNdsSq=riCTDi!B$c`MY*KpK% zZzCpBJBwOQnq11MNd0LzQBN=8c~smJmMINB@haE__z8;aLftUDgof()c4Q=+7MJ%V z35peiv9IHZJ|KSMP+Dk!bK0YY!hp+RB5Hfx{T)sG5$H|_Dq#)e5ez$oFK?8s(g>)Z zS8%c(kI^78m_q4t-vA!@aLag%~py)pljlmi#+{CN~bTGemN$?G9~p)0UPHZ>U2t| z?TwEyg#^+^3FE|NL$wi5i@3bP&~dujdt(yz(tr9y@D}FZ;EI-(C3s8P4&Un!!Kpf< zS!$9b3pEwg&rBzE{obOZ8mir_^vdG3yvVGi?)K2}kndx-w=(;b*3=3adr>M_^+s2c z-ucMZ_MrAl+y6S#?`2lfxq%uUsWE6tJZ|x@*g?U!5GFV>e&ReR*u9519jzyxUGso# zR)}P`=?(G9ZdO!O0w89dq1PyOjwrGPI)TjJ6kk}S5s_=h$I|bC{R^qI+tXlvX``NN z`n)?OLe@U;GddRwW5hbR^IjZ&VRrRCBJL==%V48Rk>nOp`UF`&5i+HY76Qu)c&;eT z{@OAy@`)-iOoK$R($lO(HClh2%);dG<|X=UZYl{L1U_uEjwq1x@Omu97BV#Br1cMqay?r>+W zlgm;thDNMg5bk!G0%}87oGfFVHP0a8Rt1dBE%&>Fd?aE z9HH9H?QRLo#HCg9^8Vjc%G-t5Y_zu&C+(?sEcnS&K5+i&?ET@(J3pN@rO>5Q#zhYw zx@87L&^Q7MQfjEzR)3llr?xt!JS&QU51h2w(Cc>fn!4d$R&(=#ATYKv*vR*@j77qO zAEY0s)IFn;g}>i?H{#;QXk|GC&@eQ8^*aU`?lGmsn6`OaS)x$ht90;G#qbJ|?T^abNHJ zN9{sBFgFj`@qCHUmI4cSnOp_!|AF9CCQd$t=ZU_%^9DEI<>Ga(ck!P?V#{V~LD;d{ zxo~|5iyK$)$mb^j633M>TQkM-`4LvQfAy?C%$>zcYH9b<1fGq!8I%T}aVz_gFA~q} z9KIarixE6S&c9y-_RhcK{s$sTam>Eu&1Wgty+p6cInMIPx@R4dLZ0kNG*fy_Qgfq{ zA*sQgDJkwc@_42l-qIsu*ebFH8_GfybEWvgKpN3-LSEx>3%y^Nv6V@9Q0J0d7H;3sV9?O4_41RI(OD@FgLh=8 zsRM0Sk9o{_w7bwt^a{!gm*Ir)weee*%9d;B6PYQ%JBK%-GPzx7uG6-7a>2Cz<4Xi)`7tSI32Cn8u4FyX7fsS;u>|}Q0Z;al|wsO0c^zw}9GWa*&J3j{K zX?(4q#B_Q47?_kuE^|C~qOIIdw1NY9S8HyMDtjvx$Ur2d4-$x95`xqyD*ov)T7J@s`f+Q*120&yM7q>fNHB1>kh!?oIT2 zCxii#kM@ldzx^18IIPK4`CP%FqwPxs`DwTr>e{0%#{|s(GEREy@^~q6K4PlD<0K~~ zbRj?C^V}1eTR@y<4!X+UmOtOVf1=R>f%(YrRqm-EPPm;iBNKT@-I|bR!JyngN*X=_*KG@{n`U5JPH<39NSuIMrOBcyHHYh}hnxFhuIgYVm*g9~W$XuXV zti;#wR!(DdB(#P1UqncGlLxggatZzmM^8KJkT$ z5qr-Nz^7fVl6KPJOH(#05rZB?gFE756m7Zt`YO^ z&xj^MH^yt+uGzA5dLWmI>_x|Ll3lg^y&hsB5LBQ&B?ZQgMQn&sh< zs{KMZIcuBu8XKenXlBgWW84X!)b+`i(5b6uDnEwTC*4i|RtLO)8`rfz6tXNsDKjkh zZ_WcqU=_*vU7HcNi!bGV4z2PKoc$G(@FDPKxHlDp-(Qq&`97tBa>oZ3zTX{QvYO~8 z`YGHvx|d`J#YQ%UEfd|%Er|77Mnoom1tBXm5ng{fwYmelWAi6u>T{l^XopjNE36gm zmy0HQK9*u-Z<)Ln&x%$fJpCo_o7jg>*@A=;g{la5*v;$s6hcnDvb5J0G+UpgxzfQ} z+n+s+=?>)?TEyG)4-cQ8|A7b!&JT*hqYP!g(!QXj`>X6Zn4gi*cv~I3#QI= z<4N~)IzL3DQRpl<5^xWH4Hn5+kIfp~eUDA_5M&tca{e0i;sq`%QU2+jEO$uvHc$3K zZ#x+`58sqHb=rOM9`_*Lc3Oih^^1yvcUUSg=zPv}>#fTlpHn(_R^T=zqJx|j5SO*X z#x`ePEMAFU)+NBsJ5fCGnxeGc`w4$16uM2o^bWwRG2KpFDNHfS7?}QGL6i zug48|L?T0#%_c}#!JFSPh#}n*XNb@l*Kfa1ue#D`2#*o2C2mL$3pHdUISV)=%Ghe%F ze15+~PzWzcc80Nm-yE(-??57F^wOZ%6zAJW|6AA|q97lc<+3;H?HRHScJ+EPRzbs>dsh7UVx6u9R%i|Xv}K5O3&HQKb0tD}+gUh{Fh(tjD@`sG0vj&U#H_me=$&>)gQ- zuv^NpLC!MFnEe_}FP!G36)%00BFH#%bhApiJfnOG%hY|j$#(EB_?u@8fLWRkkaT9B zps+@!@UZFgk}T_`@U;;d)xLe_E~^TdwAl2{7cLQV8F21mD1#lzi-6-8=QX99s8o4_ zzp7M#$KRNT^U~5L);nAdx{@}o9l$M!b5fBu*^B);hgq)WWR43)R z*>3}z&4dUV`--S*m)a-=}nhypEBwrW|m6^Q0-*P2K`8XxY_1o-HC8K zK^BIaDE=PF8H<6hW;`W2BiLn+=#O zH&%O9R7hHM${t~}p`N-fCe~Oaw=JGge!N(g8mckY_(SkIoxIH)3#8GGw^UM?TGO5? z#jH~Y%C zVD>C-CF5N8U_j+)-b{oz-j0JB~ob#v|&S+@$C_Vv=gGJ$bu+8;V!Fzi2P$ltD`_&ArrL1fs;MI5Y*>tmMkLRL(i4noR%s(M z_u&R$MH6t9x>X7^AT?Ql9cK`FtO>iuQq{5So)~>!B;6gg`$7i#qc$8i@4d~@t~g*j zM_*|-2(=q0O19jY4@?W40t#W6rNsG zxCImyLM;WL8T6m@#w=xI{qFV;-x)>q^sQpR8#)_XI=}{Hj zRkdHg(|HuS)OL7$J_|h}i$FGyzPd-0^?V2f!s0ji7&M+odo7md)BxPT6y!M-!*gq- zDl9{$rtg^d!JfIX)5~gNNokeHWpjXL0jk; z!Wk{4?yhVp2_ELpanl@K!~wO5zG(5|8h^~YGbkU~oqt*eb~-PdvVzop*b`abV_1La z2%6Qkz9=@|i)`6ELK*h`2D|wGNWeGJZ*RdZ@`SQ7DHi&ACr&GO)7fq^{g@I=3jk_Lu$4|7>$0vjb zP4)v2o$g{wH=@OV2sR7iuQGWp zLrLBvaj=jt&0JS2ppnhiZ(1Y7bi z(5TsK$ez{St1k&J zCe~5Br)hVrG$ZC}+NB@fQDzqTjG(J}jmP#W)J@08Z}~N3Kn|4EAAU*cyw>M*^Xcyc z#WulThONlwK7Js2?n$_HQ56pt$0fBJnd`Ry-4!Z&xF4g(8%c~-*I!(35-yF)%Dv`_ zSv^rIH`6A|p-?l^rGtDm+jNEf9fABGK|9EIK&fK28T;ZPmk!xmr*B_Q8+~TK<3>2^KH~;_*noB-jy!0^@(3RStTjbOj)3yj6rkV~J zCpX}PB)WzI(u>hT{kErite=*f(Z0nnVsB~YGfGyVLwRGputJLIK4O5yXssojWO$&} zij^A>nComCaZ`&ySS)4N7{tPMcFKZdoXy?Ol_nqtxC*`eD8oQ)(80cx7@Wq6TFR#b z*<*6rFC%snZ0el@^VvKqMWDi$S!AZ(rn(4V7G^_3(SOHdzpu0ekN*HE+C5{9ff$5C z$TBLgnbV~2g%#7n=5F|4-7;B~?UXIOi689Wmi?0a7lfaXiWxvh;$QfeLtIU=s!TMI zbA;oc6Hl6;U$-$dh=7)yf z9h&7&bX(4C_9n`6&=eZd@fhOyUf3x_l(-@ZVFTNB4^_RW+=%Y8vf3uPzx`n_u4V|d zRsGFtP|xg`b&Mktt#+y&(^ig%an8^!f5Hwq!B|0@9g>nob{N8S^#P=~)u|Jsn7L0C zEb)z6^qQ`D6f$^Jgt3weP&15*IX6^pLa3fI;|`Su7|w_nWy&aOd^juxK_-z)gwz{< zqc>77h{elyKE$as&g-SjZoruyWvURKC{abZFixJ*3v(KL26_g3U?tD2CY=5BpT=7- z+wN}75vQJscWg>E#S}I<=(7Oic4G(fF}A)5Vz&4!!IMajt_V7&huH!t3|!rn(Yi|R zc8pHHj25SWgeH^>WSlEpm;Ww2ng;Pmi<|!atv;_ioEREoL6GkiHa8zDqJFdg5Ct(e zj$BM+i7p5sl9Ozehe+37X62TMCh8zDP^&540&uZmnpEE8TT8Ojb74lDT4|)O_K~;( z&WHy?efxOlG_PQu#;XEDPeHC~Ty1|I7=m>ada|5&-azcfy@{qoW?oV2q^I@eq!%hg zbEfTSdT2(gq?}wfhgzG6{s$rn!_>qw2EbeG2$iEga;@v1vh`Im+JB0R2e>>V*^t?+2d1V`bh&CPp{&}@_@CK z`JprwI{MN2n_L={%yN1~_1L4^8vcP%UERZ0Q0Q&3@RUkvoz{~(3{AeVwcm+QHZOMfPd039XpS`WQA%eveWW1!cv4 zVC8rb-A}@vHk?3lN7h<^JDFgtw+jkb*H5BqVZaFD0SJnbmSH>5z7Ven*7xjB;!kP0 zF=8@c+WO@y0x*MsI$^X364HTGc6Y%g{)&54@sVihFC+e18H?-1Igin1BfC27ktO;| zi>3HH7Cmy$_M;0l&2|?{+GE9r3Z{+js5mP^WADW~dPnJyUyC)3H17(e z60jbADh@!88+Wylm5n$4{#4nu_}hNR*J=+Mr*rL0VANrRftBE@m-?NViK zAOTQJ2pfn%z@Q)D)GY(l@b`T#Uy^_fIywY@Y z{#RNp(z`n*d(BjLS^tb&zf`AeBjn$Vfk6OVf!666+M)#O5R{e^NRIg5*N!0VqvC6U zhv}f!Gr?RLr9}+EKgYv?*j+5Fo(WcH^qX1lL>EzzWVqsO&ZRE z(cKLV4Sj&zSVVes@eK+a4(U2t?u=f$>K+Sarw?g$dS)85DI3FJ(OFlhXgB+mimkZ(r=k3mZafn0p7-ac&^*w(yyhwQWN`m( z{z|V1#dgx*K(FaNGT2A9$e<~$-XE?<=h>goCBXN{JFNX`8FH58&UeIN)gSU98}Aud z0JYQ)S;v5-igN??O@vxc%(d)pVE&`H9`;e%=1Z?&fWj4d|x`)T;v{Mq#1dtu@*r7E=o+@jG2%|tdILyS1f4jX1vi+bE@=QkOE zR*N?CQ`XY9Mw9_gT2@D4Rdn07e=*L2HJ6Nt((}f6<3?pR-jc7o)LX;snup!%x~HCA zYr=ifC5qfXq`H8Kxvhr-b0&RWLInklJ2->Av$nRo*G<=k3>4)GOj!}-d?M%rY+>I3 z?n0+8)ju_|&Y_u6ODhUoU@N7!nHDhDz9kMdtXNH^&an2G0P$G<8;q#Y)NaiX0SglWbA*bvxzVnGAvuMF{I_)? zvEL7?a2}gV9?e(yL|E~k-l<%3-vbo~$nf8w;Y`&OY-W8=VEWEhM@8(NhirGDeh(vF zp%27W-v&*a92XxCx5$71(9ih+!K_#42OjCSr?_%A7ImmM0K~S=&ZEWag+9Pi+NlE5 zAo_u0hpQh)Jp&V;e)%NL%{;nTl{4Cl_aLwLod(p88s6E%!l6CtJ4z6&u${KTzrYDc zo64C37DZ;RycpbWRkY+i*mm68gQ*y9@@9H^g`J%iIg>%?<-or+&FPj3v1R6N z;+@We`K(UIunZ4>i4Z*%2+3#i1!=Uh16`8m!vo51s)hQE3x%YwQ7O5&ffy zQ#Y{gS}O&!jZxYQYgAfx@&d9+eiXUgPjZ2xCvR29s700~uYaW%@jEL&^;dL5$OW@C z@mC;?3IArG$R^kecbZG}0l7-<+OmuyFQKjIJZJE(dZ7Z4~^%&C&Bdtt~0S;NEjacu}A+?1!j zKLyGXMMRO{dH9X=z`=M8@%`J4jk6)ZC4Gzk1o__lww}Kz1sAT>cgToi0}txkY4Xzl zvRgE?+8}+q4X5YE23Ye~3AJav?PGfJwu>HG1{x!|?*e(nz#y!$#9aI$eF6ln?d1yJ zT{^r+A2il2CQNYfQ4+r=c{3JU%T>zvPl&9QyRGe0foyNH{MLXM zLCePa6itSlu8rW9P%pj_WGmw{u8Gfbn2^=qW=DkofgEfM8NgWUq~ZVr z{_vW%Ltu69z!Tv|5D;kv8NV8jS%QRS-#@^MOX?F^tqkubHTaC6J7s0>$(f}l!6PCG zH2w#|*5eNjM3bn2oZcoZWv7S**-eXoK;WBh7CtMX>4Y3UOVkz_`N{k?*1V^%_HD3e z3$M2T1YBq45C-;CL;kIcH6mn>x83b>4v zjRm+Y%;ju@6|Hn|E-!xZhs&&@P`QrPWOSTH7r1zw>jV0 z+^g{#CnqBLYyVq(M?LwdVO!4HH05tDG%AI0)G%9I*WDm2^5kU>${QISQsKfrN>l(d8M9@X^HwW>66nxGx2(#~?SiSgoW(anS zs;+E~Wd?$7;K_E*qn`o=jHWe-zPrJf7n|gNjDB&OP{V_2gKMT zwtY?a+&<|tKLJYa;cC@r@5}gCNn4YToyvg+&Q>o=d@h9~Pn%G+h)mQm{&{6I+PWIPpK#|(PZ60D62>$WB7(NJ7i58?#rMUyT3WqFO|D2ixb0VZYrnBf5ErHfnFZ(1OTn)8S&!)}YjsA+s$InP9rE*x zo6lOWY4m`d{Ss4EhK`_ESGURG?E_w`?urpfaWauo@tO`HoTtgrHS5QbcI zSr^JBEK3dY#cR-Q?B4+vP8in3Hdjj=3Ij;LgO^PGg~2o=OQZ-&lRZR!DRlh@BBKX2 z(ZCQW@PE4;^&5dyTyf=T6!F9Wf@vq_pK7Gv^g@9;#^FW zWXgG;?X{N{8<3neR;>Z#Qvp&of|EvcH(e!N(JXyi9Vn=WJQyr3F%)b(#@2}EXmqev z>fN?_jo0*Qx9u}tqC*CQbm&VfG%Aw2638FtOrxRiP~$O>$>Zr)oM+G(J>#k7TaErB zTou#5H(Pg--Finy35T9|O5-AmN+OBxDg2YQgF$*ynIWrd95h4`irnE$7)u%5 z3Q)(3maHi-^n&0>PeZ#LDfapgq~&bnEp>VQWoZlU!d$N=nW#t+pr5-To>$|l%YI?p zKy4wQ)+MB={0q~wa~K;LVTac3`;LgLSFz2)Q(3Bu@=kN2K5NMY!&lO@pRm`t{G9u9 zU2-7cH&OYT8T0xe>21(q@&Ms`sv=8@M&zG ziRyT>7-vCckcy)2b7{suaelL?xdff2PLf8%Wr4xB>ACdIioM6@(E6c?86L3xwCNOk zhStzirWZ4P=tO54^l?x2iGu#*?ad6B%@|(bL+-l47tccQW4Q{-cdveU5 z%hg4fExn7YhNvfK@$cPtuWNTvsI_$(V4XfkL}P~Kr!}DJ9@19x8Aa&YrtdybYE=aj zV}R=)@qpzV4C(ufrqhU{dce*~?A$Z&J-}IL3!!x0UeMQI>(slm9Y94f=4-WE9VXFY zUqBTYA)?ABE^&=kQpBXFdN+<&sF~X;ps)6i=+^4+*T4xfusj(UY2FC-aYiC*d0&(H z_ELh9o52l^iuW^+_vtLxOFI=Io@#IQr?M&zlOTe&iSM^d{=a7r7?5972ahdptK;Yjq4xZk&vp7Z0IUlh9U+0RKuHucXkN^;H7 zt~G84Q6pdAY=3mDJiBmZqoMehsRQ-3vBXN{Iae9_Gc#!FjpCc=7X^fR8sVUginVZf zsBM|#76cff8MN(^u>W;{5*T~-e;~NheL88M6Ka!QgulUS9Q?2CGR^>w;158&x|_s) zq9U=-3&az4`Iw>p-Frc9zi!UX!Gpi&4f!)JH+7E!uFA z@+m&YXZ)C==!~uif1_q4EdYp>(-uynH;9>KOP}MkJC|QsGqFdvxlyjl^K|)6Qh&$3XF;oX-0A^hFR^}u0HOeE@%uveE_LBB8QbP7h`)HZy9UF^4o7CxdRUt z|C>_NhN9K0QX?MH@t7{I-4i*Z_nD|+kj7r3l(j+(I8>5a*BE|1(&SelzZf92Vl1Ci z+G#&W?j`EKt62J8xsEbu$E z`|MoQo9skx7Xn2pW>jYldQed(38=n~T3R3Td=>gZM&tHNAk7oK8+z}U4H;sGk@bbC zDWecGu0Mv(DMHO0H6iQE^BTB!eKq>XvrNFk7ncY#Ow%IrnuXG#Y00|B$S#Q_?&5@K z25oI2F?o98YBau1*A>Mt_|$?>LuDN5YJ81yC_1($?l9lCW4vpp25G?(NR5KEC+pF)C_G~n!4(}AMgjNN}hK5spjCmwfWh}u)n_rz?SHKyc=PB5vitc93me<{L;b)o6t!AD`&jfvg`8;}XvBR=HKYzx`jZ8VH!<}G$S4&SK3 z2YChRuf~KI++FOEob`)1+(rU%zZJfF2&g}$n;?-!H?M=)JLvfgC0%xXY*>Jds$S%p z=kDfWo#`*CyTOLHwC82(N^w%d<@(NG+kEd zL}A(>F3)O}jj8LTU(@C%(Z)OFLIevI9^DLS8~l-ZTB|DgpD}{`4QD|Z>Z=wJM}1~)G$Rb z_xF?-o@e&i=w*n)Y&QPQ3Po4S1w;BI4W~^h;{v+G)T(5PJ-~igk6{@DMA&-=1$el=m-=&ofADU)K|L=@g zTv8Tll~CAE90XojDGz(@iJ*;yO81r2hIQJOxR&uT@`}GOScPo5!mydoIIXW83#tCb9Tu$rUAfY)y@C(9j_)lKM_hlQj_Q47FK5@d zJc^onVSv7$;5C;4E(x-)aTB7DO<$kLR1OwT`!Jl|mG;mOQYP)4M)P}}^`t-ZEitl{ zZKSMDyPlg5_O#|hj*EMoNwkG7{8i>ao4#S<6Mit_ zWp6=i72QzJV}zDwZ0{!PBzKGfeg@$ve6E;$)QR80kno@;E3ot>sI-Kvj%uRr!ZKWU z67p{qk`c`IKL#j*F&gOj?x`*W$HSpuYXQx3MA&s*TUgTQ} zkGvs}%OhvXkoznj#c>RS_YcKc;~UNd>{$7RvHFgMUsHpHRX-S%{(IXr-^Sp~)3y4+EBwmXxPWou^@m+%C)NUkudUWo zZO3kiBE|!z%yY=c)U zXrmai_Mq;~aT{YTUk$Q}aWmken6 z)_0kpLUUDAH7l~JDo-i$Z{O$OvM5hZliL>PU+eaOOXmh5|d#6iTFR6)(Ix~FdFnQE2}QjgEokkXi{I+UiLylBqB4}jeAh50aP zU3Q~;JQH|#)<96|>YKFIA6Z)(elIjGkuGA|k7_6XyU_=*u%sM221emjDsLJMtH{s_u-KTUc-N7Sr|nXMLP% zTjzYsiJydaPoT@#X{}U?ev+SJJ>9wem;q%#a384vyg>82KLjfcVH^Y^=MU7G7j&2U zqnl?abiahK*GYxj$*_^I#8PGr$~)9w;Hz-=kdH<2!8GD!un-z!ff9;WcJ)Pn9{pm_ zc<`z5o%^-1)C!A&p}=)V_ln`mw_}5#ZjzIM#7>S+XHJHR&Cn>+5zuf0x)Rk@L zR55J^Hs0eukpKNUL1^COzY6R3o@&KqRqdjAeD*&2Qw|qtAc1Abv;?B{pm?|+y~$|O zE)dXPE&_Rz54zqlI1;|= z_Ks~^GqLSVFu_C9$AHMB6MsgaM3azYNd}F`{0x3`RBILy~Da>Fn~YkbB0QExk2H?M0q{Rlz}O(ZE<4 zLZ16seaS~8h&=InxIj5uG<5%v(rgKPvH{77!qU_sXEt*t>JwG9SW`8DcA!#n2dUeW zHk#=*m&Sn(cB0PbnO;4{n44xmGmxV6)l-%|wZhz2-|jGG~xO< zEZSPVUI80;*1Dq_6C*%vaW#O=VA+OcNS}e&QfI4bBL;P*Tg<;=0A?074+CvE5wY2S z=Cl-?Vfzc05vdLjlr`JA2!U5E(V0I{lq9piK1{$OWYnFSY2>MJOFaTZVp-hGYP$%^ zBhMjfE(?w%L?ZZOB(n_dFR0-2f*}}^V-QwmR|udTtp9gS-N?RKwENuo)?SOg^geUO z`Vr|h_QLg+nd`Y{>Z9~9KLR_cqiuSm?K!PQ_Y$b<6p^_VO>~y8CrW7Lzqe+0=!`lsEWLzm?L)qc9$GQx@jMhR zIy8RFZHL}q?2w#NE6~QDeb0#}y=hzyUGbM55XeZ@A__%S-YI9k5QdQ1m)=7;bmak&qv z+?z?de+cCGikFYBl@eEbbvVuc{O%XvbiqPZ*Tm_lP!Q};e3}8yaH69*>tMfNU&nL+ z`KT3tvAPm{B2@HHZ8c1U$<8>c(cn}bzO-%jEam~i^uh}ElNoP75GrZTr=5W0H!Md# z8u39dELI!1v%jn>eVuN%&LkCMW{()mqvPh~WmVH>@LJAlBgDii!&zA4+@?IjoCxye z@mI|=;;&S(j~#?Fp3-sy<6Z)8A6f4K{lTD5oZX?k36{%Abg=v?vO~AAV?l#wCtSu$M%cnMb*9dT>J2sN>yxZ~3fwUjH53 zLL%Wi%Ei1{FEi)0N7780lfPDP7+`f6#CxR^f7)GB4|6Zycw^zDca%>hxd;l67=nOV zyrN~2Hm;jB2)&y{x~Okl+@nl#DM*lmt6XVG{i{p3gI;vyi(i68qEGi=*ln^Bp<6RO zNK{#Gj!mF#MmF64lD$7R(y^Q~sFp_%q_LaQkLoR2XJS9At<#L7#Udd3z<_W}{2U*K zs=kDjrp`_GMJ&ecJ`i5Av#1mTh1<4w4+2_$LSNR36CyZdVceYgi>$SoV#E(EnzV@5 z9eWN&Q5Yfdf^p8-&F$Kb29N{CkQsM>O2M*{h5AW32nUU94=5u0oP@7k1gCdLXxgt2!wS%UPH($mMX`O? zlU!^`U_mtgmP8Pc^9E>2n>441yI_9)S!>);>Jvx~ z3qSG(z9~HIkTuL0FDb~S^nqD#`;uFw!p=_x5PmUAb}Klr>PDNC$w^x(A!QHKNZXEQ8l4{@7cJp4aM_;W0@KNM(dVQ4R-{sW2EWZ@f>nH{ zEONuS-TY}Fk$rzKOV`ZJy%o9w5$@93PO=!!PYKvMHSQ`0LNtQ>yv1DFntH@3*_h+= zXG#H+r;Xs&PHF$^Ka>uAXX`&}dkfBSP>nWwrpQkGa;2O*Y)Rfqox4p-U^hI0*uNeg z<1((1D2ICLOk|PrwuW){8v_ZBsR~LQEmqmxNqd&}c5mY7 z_i7yshkWK#yWy4)^*Pq0G+vxgc~>G!&(V->om+hQ15~}@vzOEcVSoL~e}t!0ToQ_| z;tFb@yp+)c_;x3xSDXavsyadq6Nvo@W@|icjGLTPQ)`3#1qRP@rZw6HO;A*gPID(a zbjjdn6|Y3_=8fInf4HC;UZCWDK(4TPY<+TgWNU|SbFh{cLEM;O$giF7*u zjx9*vC3%}&TI#4~o@Tndp#CdWIYKr}ENG$J(*75+o)CLi3tc}aCCdQwa55D$l?`wN zfOk3H>Q(>YV;*F!rsI$Bs%xupgNB99iVD^b7Pbc*xrU4JX&9@h+&eOuGtxh1sw6@G zmBwS2UPr_23H5xhDdf^>wtFw@;r`0nVCSd)ZZ_9uq?kp zHg~|@jQ|4N#T4abhou2Hnkr0coYt=yyPj#NQ#$Xg^flInr=vDdL#e&{?&oYzPDe1y}$q~PPOn^iCjP4XyLI-WRa9nz%(N<`fcvRJ!5e?d&F_U_A$xCtG%8Ib_0^ zV|ei&1)n;e!+(0fWR=K@40ap#Vm2;Pb;de-~09nTX>@$ zyUp~K1e!_6k-YyI4!hBfflJcl;> z7jg%(w2j=d%5o=9O(PFh2msKM#XZdy)hT*fJX%E-5k_c6xip;KN-c%Eo#f4K?EnE0 zJK;>x$Ske`~@C+P&GLR<|@nCwDryrQG&`!>~)CO2g7~q4&YZ=>haT7|z z>>xOn(z(!n^`VLw#B8@J9n-g&W0v@1ukEgPfXYhk2w0_Vh9EYk&JdUTW}esd*QQ?v zsb^LpvMFyNw-|L~V{A|zl6b^zVZttqXP)oVFe4bPutxeZFQ8Q56Wh<-p z(tRHB5tE?FSdEnI6{UqQ?}1jH&USA;OZkqgJACBH$;3o2fc$=KQ1bbLgntSHJ>+4Q z;I12Vd&S!Cl5cs+&Z}eo6fP`VlMWtbL~rS3VsEK~OFU(BOZtto z36rkPFG?*sB-gW5+;Bt#Gr-t`Lz2Q^Y(G^gjiVm5S`RBf2m4Js3{n~wJH+wiSB&8; zZUAR`{(Ihk_7upoV}`=NSmCRlUQS!aMQQm zv#q@o8=0Bb>+6ESJv8i}IE_-;eN`d`G{~U|!RB(&|30v98)G4MEH!US+Fm+``FuD{ z13ud$qW;b`R3p2`s-uTmpGkO`k59+gHr^&EBXl8SV^{ureMFSYq-A>?g@L}|7xnK3 zSc$9SB3Qzs1t}hO8S)EWeAg^-fdLtSoaaN0O^Y96s(%yvDrYrW3$GTO)Pi^FJ^zBt z^6!gIE3NKSy;Fq6Ps_E9^{gJVGw`bPR1%uBoJuU~;5SqeS43UC2ibcJ44 z)AlVlf?SJ7#PJ|h{UXiezury)xLWlAQwJSx3Y0UumZ&kz+lBcU17d68?~4yW zG0bIe?`=W8KxbmOP-|E)nuWDtisZ47Nv5y(X#yW&>T`YRhwlJWM=m+wqQ>*@Zg% z=`hl>IJ(@o%+-^*sNq5P)8=DX>mRncvmAR!f`7@HiyV@Nqpa+@;4PxeWDDBHAkC+> z@xGqqeiGz1n1sT49&<&5`Yj!Bglg={e^{Nd$Q{7Cl8S!wW4+6N)7h5re_#P)j=mFL z@^((*r~3OV@3=yZ755pypzeq#=vkboWi@>tj$r+h^>D)Z%gTPlM-{ zw9sjN;0LWVo%g)xtpk{Pi4qjsoqu5QlgXChH{m-YsmKQ&Ast+bi>P#`VeSs<`~UV5Pce5Q(QQ zs;__CA5KdfiyL^~Yh=%PV}{izg*7tS>eim~*5^Wta(;v9i|LsiT-1E)7LaFl=RKh| zEAJI4`|}=~GE^hI7aC}36F~YVj$b~~27YYsBnCOVhan`5{UPr%`UiseMd~vLrFe6= zI7V1uBuTQ=0^-t5$x?Kr`HyBxq509Oa6L!%N~_4>ZVP{e8DZ;FAljJx?-i-y-uMT> zwM&!UFxu?Md8Hm+9wiazVslfJR;9jH%A}0K1bF8qha72M`X`yfXEjJeae_C zPw2f#)FOI|5;@dn57h*9o$efVKWEA67<*jwRQLdQ7DwhGS-0oO8u;Zq>XpJYenQKn zzG2f4e44CHGOayb&F)ZNQIr{SA&A zTP-<1uy|fmAX2G4s4~-xof3=|)Y}?w`i5e@F_iJBlK_E!V3mzZp4&hBTPl&cn6b#f zj~SmM87~467TG}Xllr{Z5C6-L`u5%rJ$lXMp_DfcGXF=b&_58hPHw5lvP(+Lr}Q&N zjfUk4$y|D=NO3`1ZG~S@8Q@8bg{MRvx?dt{Ss*!!ODmVg7+p)>iX>sNm);uIRjS9* z7kIR=u6TrI#Fvzm&}@+2Kw) zCl+F<{v-0SP#kBh44WSUBBdaZ^iAp^5th!(jPD5T4_uOHoeS2)a+1@KMk|ihdjZtO zt4nNq++=Q03dCZ2O9n|p?W!mf5NsQ2H9GMdy4qz0q?_6TIdZw7cpOsY^R5O*8)ELX zJvY@I3ct}OaCgqHKGV04gsgVg%eZ|;6mhdi)HrI4l96h!ihm`u&)4AR1`b1JGhuhTQDVvgg3ZH*N#Tgu`mBKt%xf7h1Jq7D=Z$IM0#wok|FBrif3!2im~ zI;O2t@%j)ONJNGAENS_p`>l9~B^WI!#;_AQ2WgP_cF^1#c-Fg^pKUpDyh;g#0(OcvOErh9 za81JZ*V9U>ca(tzt)JJPWB)GFqcr`$^mKk~x!w@TA)B)VZHd0Cdg+rbv|!{Mql1kw z3as|7+jvQ$jn^JiZ8D%?0@ym4P%2s8%`9CDk7&q4aR4W?;i!e;8!Qn&zeN`ad|~9^ z?#LB#wYF@ZvHN)@w(OKzzKQ{N!)5K9I)iFlaR773(6X&_*Sw>(sq52>?HJzm6YDT3 zgAs(FGF~#h!{B&q=aL##n)s3eDZX|)(u}wh(W4740x8JyYH25on%wctDqsYkh#1_W zc1^OnI1-UyhpG7PacJ=Z0&*@D^JSLBJ*6;u2#SwgienhlJ~T1rDBu;ywfKLPHU2<) zI=fPyipB|y4WpL#gm_CLLXVb-dX zNg`tBL$&Lm*8-l)NUaYSeL#*$T%VDiv+@oV@c8Fu~OD;*C|FzJGr4567 zU}TUbS-n6;@V$<{W}`(1({p{W1}3hty}G^FEOn?_lBOD13GgGk?b^C`RwqNga}w){Q}MxyhqGeCkX2wSX2ZJkVJo9ajsO8e66sf9IW;b{ z9mROKS)PTJNhc#M)&?s^vw>1W%$GGx@>vc6RuasbUu%)g9=k-C>PfR7!B8)Y|aWWqUuR{N7yEMX{ajoN)nlokxb=Fl^ zZeXQ>GGitKmzzuG$wRcMa3)e2@!d@NV|9uEhm=}9Qt16VV8_Kmo_YOwVly?oyG291 z>Sa3NUZ_ln4Y7$v30drJo=Jd)7H1nsD-DTANm}b@-wQ6~)E{lphH*EJC6SvyjVJ=NuxE5cs_LoDA^I>K#Ftoidt70;N9#Z7oFV=4|k32WTVE`OPhOrS7*59|tHOKp` z6(7c=*J9k3v|oX~PG|;PT`S(}oK?L8_r_%7{P=oiwIi^IIq_qet#ok6@UU;W@+yE@ z^6_+Xac#vp$W|j{diUzeJKAq|OvfqqWI^mT_5AjEE)@&|4MxHy6eR6yX5R~C7~H&~ z^-um5-3qU96FdFz+Px=>95bVtFu5R;yV+u`$~C{zy3f@XrXmu5xqx)gC{ozq?UTkB zUhefnp!j{7Kv(dQHa1KYuhl7RgvRMz;RqKIJ-iv*z%j?O6)!8)#4#d z)AGa(`V1H9hn_iog(%^YIulRl=7z}Zj_&};5LtdFn`cjZ#o*g>6K%E7)Z4jym6Kip zDzS!A%l(&^gAfHW$_|OB=VH(6t=en7GFM}fkO0$SM|C~e;}uXXq_VE}l^kZ+rfelE z5QA=?-OH9IoRoMcp_n4)qh7~5)#9eCSa^@#IK@%u_o-SOk# zZmCNh&89~0?I}vt>WN)@>c20~!qPMLJ)9JFn}0)wLW;6u7k(A6bY^rv^dh(Njszr* z!WQ@l8>H~9XlL@CYEcBC3Huq<3-y=3SF-^67C>)u=~o7)g0KButi;u+jXFqP0g

zmVvqg`9HBX3pIi6v-MF0sSQEdE*)ZV2WUT|;_BvM+%~4k`xzQDG5#Ssxy8r!i%{s8on*Zxi{pEslzbf#8sPZ{ zA_S8^kl-l*(M^^ynJEtA&!s@cOMz#UmhJk1a;GYl`lM-T_By@Z}w2Qqkvpv24V>DR0(_g!m!j|>4>fqs~EBpGGiIBBXRC& z#mpP8V(B*dS<%stbxXfNAet9{#grm1QmN?CQ-)!tTQJu!pvU zDHEWXY@)L>T}EDZ1do($;~yXxSICN0Qy}5yHHe0p*2+_MwQ*8owr=h?<@EZ)5vtlf z(X{(SaIDUzTx1+iOqg>lljsFrv+h4i47}SeAq}e zr+gx2i;7URojbJl9aKy?yhHcy~lealO)fO z2;gNWr8Sq>uW&pV8sX#0m;~9luLKMN@sK*X&X}|XzI_DWPnbhR$fl+OPCZ6FUB=rscRTs zbtA~lFnIzp2Mug}fiYsz+cDJG{0E|>{9Yb2WgW-1|G*RvG~#~EfpBbQB9S&~a=I); zfVyHLyMDW_!%yV+tZ!%xtTJxa?+P)kw62@(ykPsb5hGJ3GN2`PB5Fts}=^0jUCURMb3cevQRFfLitav(Jo+41x{>cx|L9cxHGt_$B1(J8UF@ofDn?-<^ zPqSIF7eZbMeU*j-jgPcj37U?#q@H;fb~Q^_JlWHMAmxl9i|}EU4q81%in<+|h$DWy z)VZD^Dcxa4iF*j^W)1MrUMubHWI#^R#2E*3i!g#O6S@Qp;)6km(6`v>S&G`8k?gf+dgtN^}m@&5hCb$=-IK0n#wfkLy!bBbPz zRlLA0JIef%U3`1}sVDvS(^Tv4cMMI<-Yrm(O)AZI93{nE8^i8Ve8EvHFJ8A$15KbA z&_Xoi^L));FFgDdfB?Q#ta9dvteqCvTF-P!`L00p{~c5kjCIVHc|NBus~3ll zUuKPq(iF_1Qe+e}FbTCR@R>$`W&=dso_L5Jg&Y4Ai2f^reb`ibyt)Oz)GyeVVU5l% zhd8|X{99uuKQY{cS>9MbZ>TU*M0#$_=+sfn8BYP__Tg}#}AZ&>+yQxofG*2xkqUc_Mww~h`|glHCGeW$9+V| zP`UMyl%ODA3Cze(6~kpD%fE+%nla`ZNuQJJw^X!=wBDR$Q^pSctEHjua5R{+7~T2~ zKckubn9d~j4@B~7B+I#qL0$S?w30Ols-eOwb|O%X+#$!mn@&E=ySIRQe&KKmld$&13eWqAY%IfCwU1|BqM20P6^5qn%IvoO>|KKzvmm#M^&@7Qow4;@ zU(fq9YZDhxV_LCfb4l=O3n#3t;LCauNsMc}dD36_<7$9Oq)WDyTSjpdml>|0PBk6A z5exCJQWuT+J|C9{@qJEzvo}}`hJ(ror2_v24iixus{+oBUfb_v(ds@%9H)S^1#3da zBP@N$Dl6fnWVCXciHE8W(eZTqb5$z##~8)|w#bvT+y%*gQ>n#zA4RpsLy6}}!dc^@ z0;$oh%uta{lf1}^jfLpAn9sga^J#c_$TV@o#BMb1QrRJmYgagT%9hKK zD^{Kac?e7qoJvc80S=m+!^6oAlV}UvVHL5FUm9jEq`F#2oX7wF?KDaZ?0sIyUD)Kx z!S_JSzeXcFaFfcX-6PidHGP(dwLsiL) zpYrXk9RIrg8JsSy?W~{=3vtq4xjbXw#vMk4ThvQIVbnOal=f@R8v@80klhzw3%9>ChkB3{n!5U55&mNO{CBB zUpt`S8|sNLYfaZ8FW!uim~;@Es73`NR-xz}e+q2pS=(q@r(*NK-6aQ)RbEr6p(~!^ zWnY0u(Io+3H?X*cIzh=>0;%&sj9%}Ii~GCF!qp)+QVTM>MI=AUA$A7;(Uv75_(f_4 z$X_u8i6C!tu)!4)KwJ?pYCB=Uah~DcCpe17V%D|gIL)1xxDOpPHEwrFI8ZBCi-cp6 z`xgKu`MV?2iH%N4@)=fPJliRCLQe`D)y?NCCva-Uv`z93V3 zpj^`JIZEC#@u-YhD_Y}@olV^#HOXPmA2y;XdnUed+%}7zFMg6_^$SGi1E9%!4Ff(k z3_CSxlaSZQQlXsVU%DbnpPs^SAoTc!?C>ZJbq0RSEkb-FNA&z9V!g*X!C?zMH-1`l zNHG`{StBcKW+a}&uQXlfoV1Cotl_)nm4bdPIWd@aI&RzcdDW}sfyqOicT7f{AWQD> zV+8`nR9)`vyU0KTlE_VSJBV$b?yt%XwX80cfN)vqLmoL?YQ0x&*vJI|ZgUW%e`NUi z4t*rHk_%?yu5VvHzXKnc1Z@k7GF!<{YKglPDUWgbr(hI5c{nG?`X!d|an7p>#* z&?{y9Fr291zfxnz-L?OTw4>j&!8f(w?34=ys)eYYXT-m2xHN^T4eJBLo1!V?l8T0r zWZJ0#iT#2Brcx-(CqP@Uc1Y__W5Q1e$8r_$xSl;yuO@p-Pj?mdVuO-fy}|32?q!OP zlblyMt>OTxpxpz5;B3sc^?*oDC%SdZ7~yX`H`BD+%Bpg2{QJ=D1#{>0 zd&bV_{e}yUPay_h=!=5eAd3{bHZz7D|A?oKrE(EXr8v+3q zL3+}HR`h6tggMVdU&E||<2oBId?RzeOmbSqw^SI1_v}0AGPF%#We?#prPbHKl?;ZR zsda6#Wdn`MZ%aaFqoKy)R}nVlu42H) zCqwjxLQ7pj&T2=fF4j;AuAxv6^Hpa^0}J%|9OrRCGn^PWbG6=*VP!FiV`B@V`&L0> zD7JCosJ{zIqk~XzYDs^yaj!6_8?!!O#XGBOVx#)zOf0r0ST(6T)d`4NLnz78_)OzC z4XH<|e{o0>%vn;Y$tfLuOidiFE3TL)2=2Q^>ltLKwqC)Y`v;;mpCRzkpaNDl$N+N= znG9i)$F^Gh8Yfv*rL^4*Tiz4yXNm8NIM66wQgsbQGb_E*&bHcPWVMBRipwz|QY!A# z22FYO^G;R*mt3^k-%)JF42wS(rAy+1BFdBlqbP zVgxGPjiuMHGQ$#5OdbY1+-*5`!471URwI*)(@L9>2sA)qD#`y0!M5(ETkum*Wy;4ZP!eUTp;MhBmue-- zVtc?PFEi6+)4&P`W^(`2S{{`-Cq0RL2DDWLiq8*O` z5+~b2ZywM4u!y-TOMK#lA zIO5>wg_fTYZK*dNOlEdOwJjz>GqKU#i9HuE?c73zx<_g?dJAJ5E(}~f1d{pHBkECJ zwU7iYn0IZV(_uFv`zO*luT9Gz)GLWDgCn!!|JG;fTdK+(iZqw2iRs^@tVM2mIAKF9 zG;>iAy9^M%P&F}oZ0jd|{d!V&(?&4fvRp`=;*_CVR0sePWT2VlF5&1VmsI}BNQxRe9V&6mVW6Nc4x!;B0rPcra<+tCdmq)qBEtkUOUKfJ1 zRy#h5w;LXLb4$;(VA}u3Z&;S@ZRm#OIs#@R%ds8mstm~)c;MQN=TBC9lszM5nWt6zi#s~c_bBRVxqC~5|35H0Z&6c=f2y(|ZARxMjt4*#I_zOePD zc8XOy?ogL8PN{_K=(ts(YWog;xhHI!!H{WibW-ds;_QxZ(|0|nW@9ve+SI9YshBC$ zQ~JBGeu+?$a#-@<_oZ39U-+8@_dYbJe(59dqm8^}K!B<(CVXPq5dDDH=p4nV@5)iS z46nkQqv%bo?o5-DZVAC038ZI^CX*sQGq~%WDHHfA^pIktt?E`V7WccFZ}!)|=cjcD zQ+>CmRas*Cp;OIn%)OF}r06Q><-_`D%>)_qk)LS&1 z&u`ajB48phOPhG6iMP~oS=2uY=T^0IslK|PbaF84-Gc_GYZ6K5C64-Xcc^?b}|O$U`>f$37NGyp%k}t$o!F@{;5c)LFR6ESL(q; z`C6M(mJW%;=G$SSt0lglpqmjsj~{L?WQppsUuEMJf2K@{HH(rN#;U8un7usq7f=Lu zzGdpDGrRoIT3Dv=+plS0Ue5gVvRMTpwHcSDZ!6!XzJK!dT6L#KdOIXzeZKLPyr?a3 zzQMG(FbV&~E0@9`j-DZiZQSu@47m8uj)MwuH(dX^(_sn7wvGHdZR$9sUGp=VtDdw< zpCj*ATFffj09?F?AfrA(-!3-l^@5Vz7{|RtN}&QI-0kqN_PH)`gHt^@GEJykvT;T{)v z0=DA2SI%Z%Gyk{{)BU3?ul70XwBxtlf9*vdywvH9u+eRXJ-%?&23IKm!|isyper_L zAQ)wjHO~Ik%erCl|3SUM7lTJ~6X!5$?bXYS07w18e<0X*sM3cQBfsQDjgLjlge;u{ z5l-eGGYB5!F%P3ce#iwC#IN%+>Y^M7=(0|4*K2#2I|QA9JoWAHp(?NwfV17$0 znlZo_3a!$ezoU*Zn*EjoCSzQ7uiSh#F09fXK3}2J4NC<()D`8!CMtG_!3Ea?rKa)DS7KTxKsj{>MHoa~1wN{5XpU{| z4jF2_Du2B$;l?W+$!nhyp0ZHQ&JnWGit!zeu_BMzdSC{Y6Xg5M!ugKnJ9wgo4vP{b9_8)LmiL(Nj`Hq*EPKJ*|yUx7p{=+0#~~XgyNr3b~Jj zhor?ET|Cpb3iBE=i+OCNueJnfqpa8o@l5hilG-!QW1G}iPCEA;&?heYs(W}6Gm`J0SrOqqnOz&oFOA}MkwbsHubD41juJ(vl zkV$TLU8(%q_Hmhq*r7oY5Z6Wrl&BxeWp;fXmzcDs1<2i(pRwl)FS_4S$>Z#m9&*Ff zL~NJymK}Pn38ZIbl0P4rfc`*-4>RRh@?)RI&T)xz@Mx(i#rq6W(!_Q`wmCY6q(a3y-Dd#d ziy`c2))tRFEl5| z65^o^<45c=b0+;#Ve}K^I8^$pk%czG#>_E%p_o(!J`?$MeKX@xkZ>S100Z=ns)Vmc4xBekXF94|sw)vIO;ilLuY1jiO-Kza+Ukmt zhbC@tlOind4z)L}1`{(&oO#8NRX>U`HGc#3LD%MIz)~cG$7*$iv{%xZz;G#tL5B9v zL@C^T7m~p8*a5en_+(GPR8XCu29h+b&TopOgeT0-$G z^fSqbSY~|feH<1&+>xC0%X<|Mk!9I7TwvussES&%qL`Y;gl=CX(mjz=Vc~T-H=+Ul z)4nU1Bs~2XNgv68mUKbcFassZ8w5T2K_jH`_J2%lgwXu}21H(=+ zk6Ex-i`zCO7;0^xps7<%W%|b$m3EPIy~V!Ogu?*7#sCyr+VL==v4fXMhD{|>Hms8^ z5H*kQM9y{fMh(z8m@l(8I2E}e@XRNEe!oE74r6nIrQTiXBG;ik3VYv`qlN zd4upcS6BNw6+1{f|7=Z2X2(%iF{UEb0;+QD;vsEhn5kFp`S(rwHuL#z4HP*iT?ZZF zl;Xi;!9!$6sZ;Metp$+0=)<`?Oj?#J@0z7%KBnfSF}I3$RqWEa`%h-|jtcM3r3ZD% z*4nouiud`>uI%Dypw?*oZof0=4LYC$yjKI4Yw##3N{s}uNglwr(Aim{OWKz5nLHW# zy;fT{yel)}C^cnCLI^H|mh^Q})sDzMhaB<(Zv!F9K@<8&3=8x*G&<#5BGe!S!vE&v zBZohNU0`XY_cLqyrj=DeCTUI9$R#$7Rq&$7^C%$qQJOw8X7FQtXyK6OwSm8V1OAgu zqpz{bq;n_JYZJc~S$m%f6^qS+Eayc7X~5Cj2aVLs=gU(@OxN?T^U!8l8%S)81ZFm-~2OYrbXVIxi=OqORVWc7j2U;U(!Fdr9I zo|`!h`#ok5d5&|yf7f@4*q`YzeuZ-#egLeTzJYBYtT~Sx+C+h zse7i(4&YKZd(TX{gwF@4IcJD~&A3CjXGKN0gF*W1tJEy!Sp#bpf~w6!l=gn?AGI;9 zs_wr&)LM%_D>-Og>fnr6rJh6)aL=4D>bke$OPR-XuOFj-r72nlWRRA~`=3ljWSxoJ z3O`Hm!}@~y<<@O9k%61k3~nj!mF52M8_Ips2||AkV8uj?NEIjSr7k(F%2fX`5^%`c%$Zn8P7E?v#aT$3o$#z&o{mF*q;aKS#Sy&C=!;0YB&CZN@$% z9cV$b$0?_%&b|8 zAZC__t&1t;>3afFEv~32rLd2&1a??gk%7R(~!E)e9XE9_n_a^F_(}_rmgRHVE z3pRcH%93#DU>cQxr1oOV03X?0_LiQN`r*M{@uw-1VOQ{>iVIIv? zJ%&sYcNG7Ib1C0-*VaGso#dT5-qD`ezQ&lYXih2q z7q7E0pYyu^z@PW+=jf;S@U(mVjrfClTG)VnY1(AR%7S{;^?y5%u4cFd^Ee4Aj zEM{hAw3t~IGcz+YGcz;OO0uLCGn2&@GdlX;_e(03N>y^1RPDvgZ0*%fch8(Y=Q;MO z@aEmyCI-|&lAh|LJid1|=KlcHrB)$Xe-3d8{i;$S8TaD_a1`+-XAUB;2yH>BelsNl zVOV8@pMHc{tK11@r(Cvr$riAkQkS|6=nDzwVNS4FkQ?2hOjvNxK99jMzj7Aa@ntW9 zdQJ1l8hGR8=(+ZX^^@ACSVtzAAIi)ih;L}kdLjRypCOIgWhUl23tFkB5lYn z6UHx_LrGCT93NaT45(xH7TuyU;vXEsp4e3JSt&aec#KDk%A}eAqB2TbGbXCk8jkRv z?7Y)TZ;kGUB(@`}RSGow`YnB>8{AzV<9e#aWw>S95sJNX`z7C)rA423B3BV|jHxvo zyDs1-x6;j7Mcw1){`;)OxH~g=flpLar+Kc(s1wYtcBG>BLZXo>O8#!s`(DoV?71=$ zZ2CE1aB27H^mF2CMoghO2fCDO{Y$~k8=EK>5K9o9Bu6UXBEQFUj+3psjAC)=r<)hPp3P^c(O;61Y zCVM_IzpS!GZee1R$xN$I8bPuH)ZG@^{(7xZyc6zK1@^D>bSoHW=?v(g(jqzraf{{c^X4?JVldDtHnLrKSu$X>Y$2o>vPbePXVeIQPZI;3oYRa@ktao ztE%q)*=YbpSDtF`@@V6f8hgzQ3Ufb}T@%Zkeel_~Y=PL32Qx8T*u9izv)sqys*tiM zID41B{LH`_XdUmp^T+gRRwR=2lGE8yZxzpTOm?W8O=pFonOozrl2H`#!wpI^B}V9B zY=^FlG=$)R0W*Wx{i?|-3>Vi-sEbAB&Fb{4Aq@ihs(aEf(%%hB6l>8CVdaPvDc++z z3ZhGdnUlqD(Lbhs(Lb2pQm|xz(lBRghoM-`R8-m`TyJT$*RGgyM(5Sk{*E16NGJ$- zp5$K{zSqS@cTc9r<8)&BB1ky@ToDIc>nb#yizrBt+konyp53IsRJCUE}ff_@!AnF3OrU)&Yd|jhh98q z?{lU$7oQE|Ka`8{VA#G<%`}%inR*r4#Ifjnt}|pH)Dn+*NZAX;o#cgC?lqlZ49a$h zfb=yr&J87807Gb(hmIS^&>SoQ^VWMLjg@_quzwBhG-2=bBn_HOi5Ne6nBMc~de2;m zD&AJXOtI$sOQijfPWK6CGdz9B^$(z@Svae7@jaHfOHn{XJX(`2fYG`SX!5d6`11w8 zFUMvZpCWq*-H!M{VI(?;nHI|hl0yRqXg;uxNegTBeXCxAnxXv%2>S%hF2XFz-&8YUC8M+_O#E=#>6}&k6Q^7=#EBck5*~NOrP`-~6^bCxCgAPbX@FimuaMh{o*}8$h z#L=5ndoi6USIBk{yO76G>8;NWxdJbAS(50*muDr<9wYeJWBEo2hBt!6#6I4sz8i|g zWbBrh1yQAfW_=2I<#5N0gAoioLclY8-DKi*D$`;>004`(M!#`#O1G7OPKC+^HJ%6G+!eU6t}};eMMn32HL)326~c^}sG{<9yZxF(c6xO%_V%rU z0dF^HK7P*r9hbs~&y%Ssl(FmnF2n6LN|o9I+f}C5|38nE{lS7TEe<~7RhpSaL060| z#^AMoz8DMIj3uTmP<1QLahz;o{Z($OJO_^ZCQDZKx7AkzK^0yZzUKA!^}c;+>2@Ye+Wd;}^n`bVwCPjS(|ii0#8bvSAZY$s(|Zcx#i7L;?B+%ahn?|$vQ^$>Sn!Zut%Aog`b`_Pic)d(D;uw_qk1A zL0%;^Dc{C<26=QnkR2}@SuOgS*0El)-=shnRiJhW;ZD7MhU^=rzstPh+Ao*CQnz?2 z`3Ais07zB%JyvZ7@}S=OJ$#%qk^8SbG5zF1-{iI-j@IQk-bt2Hd$%NLyr&G?KGIKA z?Etx;7dIvvI5(UotypuF9CRz1Z1My@34y-a8mWM_All*Vi1y3mZYBkRDhv z_!E2DPBWT9d`-yjXV2X2J+2*nAqE}hP96n1gQACF+U^XMUda*ttGuh?eHWMVSLTyk@fXR+xfgfo~dH%MUlX$g?G$iNh8uQCgRIept%{| zd2storgI8=g*{(>j@amoD!CnChwuxt;0o0b%&v*zViFy8+|Ik}&deECp-+9DR1v8Y zS!s)y#3{by3c@5=H6H92xSm%;jKg^mCZN!lneP^EZHDsgs1z+sE-xdI0x~-sH>rUWU8yp(HjSS%zjV31cW{SfF?~Vm2fS(%1u+f4 zbznnx?PU_GE8|JVDwoY&I8xca5ec|1MD(xV;P0kkNUrjczi3yCJV*VKFs{2TFfN9J z9K97sq&;K>L{X9Bb$1XfqLhHqqzlpCrNHlr)pL17%IcPC9g6Xa*>UUaE9d3AZ(t}6D>_*wc zL&lCe@2*gA1y?g{i|k4O>hNosF5nZ($cGUsoRxw^mZ@l+Kg-eXM{&lKo`QErTp=|p z=>0Te-X^dlB zntm!6zt-oxiTuSz7jBCYedYA$raa^k{d9Ic(uSqQ%JL~irx8e2bM`6u-7t#Nyy=0V z=1W0qFMfpWJ&K-2P<`#Iro4MUF_>g^O?L-(m)-)CV9h6dk0G=RZRhD)gb=cYL~nHi z3v0C|GIP8Zj+mvgDE7|5VJjmOp$&}{=24-MW9J*`PgVaGT6x?bp= zh7;=}+33PyQJbjM0+-`E~(>KL<$bNYbs)Z8mVV)rgz+s_$v?y^rlMzd>;yl)Z_Dzz7T;0(*T zl1&6WEA!Fx!Zhj8pfr}HFK@m>)w|L4yNi^|9{C0LPJpexBh}@)=w-VrH&EzDah-Ob z#VlDW0UdN9MB2N;G)t48Tw@Q~ttp(+@F>wRY*Oo*U9Hyd&>4Y5<+N&&o_SH`3(xc!c;g!d94tEp}FjoBmhrWg>z)Ml>2(!gg-dcjR|N6mhMv+{cn7SzRN zQ8_~aZn`;14ay7){Oy17U!)PGyY4jSx}9d8Ddc>HPvl;)7~S7{sDXUNSc!1bQreo^ z5J$DG5O%wA*XQI5_#f=jNX(}3M7Vlh(>q*c=6)Fwk%hft!i=a`C0}L>hXe-KWp#o( z$)w_Hh$Ods{rR?%8CLDWMkS?CHV{6j+Om;n*-NM`$1_a+NVR&msXI5ROFu!@b+{5C z{U1Q#KjG`=|1P?IF+!-m*qS1)R@`Y$ls^70HaE5ploOx$(EMgG&#@E1#mi=J5xZXB zd9adGtcT!-6&`4vlbzOHmMN+W=b!66-SUYEA>O=YD0}h-l!8Mm=FW^fqV3)S~4w5_d#98KJ@9Kt5}NqLy2#MLD~nC?rI(Z ze=w<2OglR@-$%~$~(ms9Cu0Xqs9<;?GFAIOR|@`lPFX$|R^QoewiInVm* z82aHowk3%vYj+aN4>l}Nr}oQgS@tM2kB@%3D@#jx@6!H*4OEmr{ z=cJ~k*0qtYGF(u9o`!o`0#MNM`N@GPh1qPbm;2cIMZ$OF#<>ViH`N!2SqlZ2lJyg? zy;``Or;4t`dN54H(OAs2{1=bu%!=GUxtF}AOYn$WJ?+@_qt({`E>q`Zi z>9v#(1#BVOrW5<{6u`OB)~jE}ymGLF0dA&+MHoNJ9_ll(%L=)vheyooO6_mw36|~% z&5=}QKQQocjC<>HC7;tldb8ji)%_`jnDHKv_eV}X%cg2T|)K*hl>W?QieCjNrXW=91!m3qwI*}RD=D4uYOt2rSBNDPfDIab;@@YdYh!d z{{S(`bPzub1sHy`*fGdLxdaB3u+yDXa9YCOIVoWn*{E8hWqw2CkTrILfeY5-K2{4SPZhJS{99hqzX?ntfpGVL zHbXESe25QsG*umaqe}JkE!vfF*CU@$B73GSQlFXaPoYl(sTF*nd_^h#>q~p1)Cx% z64qU-YEUe_OS~45ZuDcJN1CR~p4xg(s3R`n_Xzj6yHy2eJCUK4y$C0xZQSKvK?q00 z$ZYVQ5~|?e5s<>+P0Zt6&@O<#pJ!pwSnhrvTH#DwY7_S_cZ}xZ4-b9}5*B>UHhj}j zLyNpTiuKF@yT%CnbeImki^!%7H4d(^4f5h6XI)VKjKG4*GpatLHQGkB#(dyy*#70= z8AHidbb@P}Igrb>{uyFT{i4I^xP{C7f1Ul}`0cb4)VrJ?MM^Y+wQN%v{rN^@P6Rb2 z(PQ@Auc6bsGVi49tpdTPma~|8!;evtRGXgdG#}jKxw#8-cVpST!}DT!V#;!4SVz zK=+sgJ8firPUGSMaMvtnK!)45IFAu8dIq9itF4}vt}S|Sg~_Yix4^6xdB#AKp`)^S zJV<$D`!Kez(t_ij26H=sqi6LY?15*EU!4J7W|SPk?;Oa;mhGzMSJKBtTeC{9w9UTS zU3Fr4Gxx&vM5Sfi{4*99fmdy5;hl(;GD05`g}$M*t+Du!0U6D0C41tU?fLlY3L4e9 zI$^i3b8%Q)%PNt-`HD6Ht%JLkHP4KnLp|N<<{c>Rb_`sg)Rb^7)HRX6>?KZsmCeF$ ztM1EdN~kRd*lc08*3DfOBNghhC_29EdFPdrEwl8% zC{;H~jq1{mQiLowP-mi%p)EyfH=!+Ke^KeBZb zJ>b3;vI)?=H!6y|scNC%_Oa8%Fv@IW2PCyF z%c$vcX|Sfz|3sd`hi;dTTQ>(WN>!X;tvsQ9!hIz1MC@EWhkn%#QjK!*o=ed0vG-mO^URGR(EgF!r&N8;tg9Y_yz* z3t?U@xL}SMmF@NvD@K62)7zw#B}qOPpP>iL3duqAEg1?-Sc9 zHM9=HSBzFf^Jf)?ZA~Z|6YFCU5TfFDVZDo!32c%{i?AV`R7tXZTe|icqPS_tC1FhI zS+9JER1=CAwis$DDxcx~2PpqP+F;%Ln8dEr|tl+?XCTc-IE_q;S~nSY+kZmfB#SwkP4ku2>f~I z^d~i#KJlop#69q9TiP2f=fX0J`&7SadnU8|*L1563zu;jm0UuU9(gwnoj~c*b?Bh6 zPSDx?c*I8mzp8-}zG~S8^SZbEAT7JdI?Iy?^=nHzvb?Vez|Mx-_rvJkx+>Z7R^nbP zXl@X*_C{;k+h7?h`H$?5_LZWL*H<16L~JNLfZj-Sm#`t7ax+2LU5pqb+;!@HKzQ>A zQ$FZ^!H{#!Fs+ZQPDy8|c zJh@I$rk-!aaryxBo8yI?GG!97s1=uV11A=;JP|vME9?}Wn@Z3>W?NT<%9+H>1NM7* zT03hKd1?#K>VgF~!=akd7P&O8+oNufi{b@3SE!c)R4v7zb*u^%oR`fq+{HRoO4Y0* z=Du4n5Vm-H-1i6d>%-I5IU0Z{8NRmrkq_=ug8iRUX;kZDWj@$xR4bKB|I-z&Twc7c ze(0Y1rTW_cN5}+T0I!PFv5Tu=CX}RWP(CArs-4Rf5|4H$d=x0K^|Wc)vAU*@Eq@|cz*!u5$~5KP}aXqx@Cn3?XbVl;pZ8=hExwV*p0gV>5;?3u^+X*KIFjl7Zd@rk!AFc?9 z6hYB{ja@JTf7WoW&UKm^7d7KJVLgVJ0@{7!4&g<7l;uIa%GkTlc+hs*MK`)hSJB` zy?H<4>HMShi<_9ScO)0@25t-^y9XjwS9@e4>`LoGcppX>+VOPQecDt-Ei|1Q(GS73 z4yuY^_6oNB=1_sKd|p6)*ll!mXzp)r2DaLWL|lqktS(Tci~kbhO?+1gvlBx#oX0VyIh`UU)a&i3=5!JV}v6_~jAhn(O7Vbk@VH z!;rT_S@sH{w^i14va(D6P4O%;M*H2MFroGs9kcv>S=6`aAfeKsi9C-%@GTF>Oz{TorXMwM}HYEcFs=AWpv>jSj*LHQ%=;?wuxhv_G%_x%J6wNUe8 zc-7e(-+a*T9(FbL#X*OS(WHAi(B6il!oA}*%U?FpIpUpaC)=JE9^nRekWmv4@ zKY-vXWn~TzA?%~$%?H?pE`e#*WJzfjXB2NuQWL9T-ZQe)BHMuQF2V}5;eB_8Ri}HW zR~crOo?)ynM{IG)fy7j%MLS4srEAwis7p%$^eVG`-7UHRgp2*T80_2CMkrE(?5**=0{1}?BbqJ~r@nLq&7a#+Gys5|O_Pu*?Az>>aMy^`CqvJ+ zqiul_I#HjjrtAzW~kZuSV!q zk6M{awX3gB-!<4znjQ9zr8$?0uIe-t7R1l~`G5oB?YzkUZ6GSVMV1dogxL_tA_f z-kAO>>EJX6&xRjU<41PntVs~sii2wnbDtXLA7c6lr$4h}>FX+Evggf-F^lbZLt518 z&mfG^sG5u(#Ww|AQDW=@zEq&XL1~L&uuTbxZR#cI2jA4GZ4|sxYk$u9t$~W5GN^za zLnqDl&_0bTdpV_2eOq^Hb7*|JU}2$E|D)m>+|4V}@ixD=SvI{j$CIjyTM zsk4^30}aT&Z(a%~AyO9{cL>xL-`BZ_@)`TxR$s|*fGg~~Tz0mNMt1`Xf9=4Vuqnjb^7b z%6;6v-a=gXabHR{YS$qQCOZE?o^#yx&7k3OV9dZ%evIXcdVXJC^KO)LHD?Or4AAqI@zLrVQsud#$IJNvM6Q%%AV;ZxrLHlp@c+ubsi~G zSxYYgKY5j`ImTU((w|==jEs>lDon=KnQ6mNx4wITfY52=JJuWP)Vk_*mJe@1>qeEuJ=w*UO~-_QTMA7!;8i$RYg6SxEh0lw;93-*5* zs)xt*7C~B0-B3@H#(iU`^DTnsm|I4chbse0r^Bc%f|*h(0j0}bgUV2^V~1LFVwqrl zL}^rnfh|n<_73y~S7zX9I-CM~c7Dl)Dq1F8PRH;g%} zq;0Dz7u!ZZ;dm&(sS$e#9wTwmxp9x@tsOEIV$m*iD!p%Mpy!kQQv4K++ZxsH=^wO) z@Xu(my^Xm`?(+(~rpaEqE?T=mF1q1i3>ziR4aeZSoaZfF@lzoU*M@lxKg zl3)!8#;;RDe-(;M)krq8#50$NIQkj-R!_O)bpiQ9%P^H2#8OQ?)mtkJtp?t#^Gq=k~wG{|{e@Ed3XHzud&s&xtYoz`}mbnv81Z8*M3Nj&U&fl6bzL=SnNI#}(L9;1bb z-6Q%%im5eod6&Ia?p21qq^6cT&ID?+D$}OuQAj(MtA=<(46WrDb0Rn9%f$CypV<)S z;o5#z(kYmtXaXaUbO)wJ8_ZjLNaeLU3HI)@3sq_~snmkLc(#}RJU#v<(r5$uAaobd zv+N85-NCtY$bjB;sDAn)foA`)1FSSKL)Ms3$1$|eGdYHL7wycbdM&+D43?^B{N2xm zS+%LpdCXGn-M{@mIVr+pkB zlE;xv*L$oL+202Tb(;w@IGQwcD>#AnQ>dIC+v(bad=(!d>~K-#iZRzvNmk?bK41!M zgr3L0VkaBQIvzUogTg?B-VOZReVxk;o;V6B_e-jTP8Lhqk#cW9iuv+}j}=~8SsAJ~ z7t1w2R)r6XPY=I`0$%fl(nMZJ-9;TFmi!Wy^Y(z4w#xI|U>Z7g4OlwntyoD7?y(FY zg5!{@*U?_aZf@T_+teeE(IwYh`8`(TbQsD4rwP+{fd+lznK~~i?VE}PYDxaGba{W2 zew4Q88;0`jjRgbcCUHo7Dl^!1eEHD%mODQ$+Aq8Kk8gV7@EtcY6(C z{*@(qr@#&1*{1f7u!q83rt;7Ds;o>ITcfIN?IqRaCOx+gd}Ub*#V{zEn#evgAZ>d& zrQ)}gJlr=n)gu)*|3NiM{?{yZE&WHrFo3bH&)NAI`18sbR;?lwp=`DOHpV`9{G8^r zz>}$h%i45!#H#G`CxhqrN$~#X|Mp^j_o$ATMH-yCQHpLGx@Xkw`=r1+7Vn^)c$*#p zNqI(D4_GiWmTeukblRoPG__Y~h1^?SeI;!>qG|sOC6oml0MoJ#n9;KMrjgO^v@fdk z;f6S!Au`WKuJGJJ+>>eyJ-omN1&Jm9%#;j~#s#>`(_-Ezge4LIZNEi>dE*S6Tw?T{8kq;i82UFQpW~eTIfMZ)7{Sojv*KxAbVs1{9CH@bUIGZ<><+TP$L z$Uj|Li_^%Lrx&e$o!tM$?J=3h*%rLkx~1~Dg_IJs`qH8=Jo71$Gtv{-S;ke0Gn?A3 zfK3f2l#+SKTH}yzP63z$7kz7~J~$RzJ7x?41-sAGKyL%_&p=#r&aB-Itu9~ks~$X) z*?~G_i_7yh{yHaq%EJ3#`5?yx{Z>}DOV=8YI59gO=cvQ4Iy@%X5gFXxECtHimtaMk z6(%UaL$)4+J`aC+&Hw_H2dJ?MH;o7TC|{~}zgK$sW#7OaQa4JE%lOkVpql3=HUd!} zyB~2qhvoTK&gK6kT>OuIQ7XAFKk=n&{EwjVzdGtTg&igbUF9Al#xd1>B7ML4####T zfMN;&re5xu&gfhu8q&@Qs)?V@m1XMVN$A7;ukUcQx*)itm&gdJ`h$#?zK);}OelfG zR3)pz>C&Bm4LSAcOkNZv4qpKPuB%Js=)hor}24ag1y?sUJs{4PzX2pN0^cuiHz0Se~AWJk8ls;-^oh-H%XHKbL8oYxc8@ z>o6*{iODwX3n&W_V|P>BpLyPRVoUmp)BKz4t84gsgp02;{El>6aVu(5%T96PW*dD@ z#1b=1&fuhHL#>8&+Qnvpo+^si9;TkJ?_p=AIE)+-*X(4iPP}Z&NOmjMxZ-ZE(3p>g zU$ZT?Ay!yM6Iymm?zl8VLtsx@&!BppBM1Cc1vOQAeM8 z6sl-lf;U{w!b^-Y{*gHq>iw;F(-4?~H>h7)>ppo0un20wH8Be5jwg_~t0yn++iRkb zN&9P2gnefqF2mHWT*RBw5?8$-Op@?3A4J+vm7Jok9?+BKrB7}*^JY}E?dm-R=(@!nd#1|Fo6^88 zy@=?`EszOP7}9v$hh4L>^1F{72BkHf`*j?ET(X2FUUQW{9kfK?6CC(we{{lI_%-~d znVv{o>>|fGQCvh^Cp5%Fe=<*$YeR z(1Fo!#dcYu?kKkVD7IIuMQJa?{WR9MZ9NfW24ZMV_Z;*S-spYqFXETzahP~jyG=TY zhW!Jm>1;drhdG0@MN8F}Y-Os{R3FmDc}-M9M2}%xxv+sHK46zXide+~Yrh4fBXo}3wUpC;fDjJSo0_w+hDDXXLI&H?8y|8C?3mA;KK}q@wxur0x_C6Lm!TW`1GJ>5(SSB)h4jSQwUATp^+{p} z3JE(>9wNU3mk4R1yo6Iu^23>ylHOywYFb>XL|g-u_`sP zfJ;yP7Wr-vB6fR$+cd>;I#^OQS?OK9@C=yk4cP*}Zi*VDh+Su7;&zRq2n@;53~QJW z<*{`X4Vseom2o_YQx%{@A=cNMN>C%z{V(=pTOqsD{IAUvF+*hn%Wh^qb>heJKdI-I zGhMAJI^CoW!%Eh+6h=#b6l_a;6^<7VUvpFTzqd+H}uFB|OeXNA@iaiMnVqS|S<-&NC&iiFEHodn(C z@j}ejTL!sm*JyaxpK(v@`QqIhp9tzG;?P-77aGb;np%HBI)TayRgnQgsfPZQ4(3b& zP*2Qss5#a2Plu;)iJdwuW6G|4v!5u>t#^_*GEhTDzkvm2#wlqp;uRCFI~IF)>Fq^2 zMw-Nz1vSR%I>#k9>0~KL?e`fiFb%(X7hY7j1D2Q}R-@woZdMQ7Z^Y54F%~VAZO4d7 zb0B(bWY?#2$LBj#V-?pMfOI(D;+qqXist>lto{l=h0p6t=HtjLrv}HPVKlB3E~r4{ zmU*d2Wv!7>{{YnhOO%bBh!15A>9ysV76t>6pccDYS+`A+CEA!W&!JcKlbcJ4i?#_( z482Q8j9~e+NA=R)SZLanW7ax?-ZFyl>-K&!IIePCWjEv212UQaWbw^H+ zPuPtf(KJ06)1Hsf#BvVYk%h7NG9YtgMPo`ce75d*3@|j@*$#da2CxGqU+G_k!{PgV zj*W$jx7zCGLtus3OOTN)Z-p*WrFg?i)oi6T8F{AG%(mU20#Vj zt>57PeqgAITo4*75SC%kcb3d^#mmDhZp_=n*g=`zL8TYlnf%mo$yBpvHrZ{peRjM{ zp@Nb48IwpDgN4?)QDwuwXUI8sb-nNjpuP9rDh{j~!7JOz`(UQJ=znQ2VE1ci%^1Fu ztR7TeIT_8S8SZvoO&vAbU3A21jGxfp0@u95L><_mrjR(#e-!m-P!8D!2@igPs&l?| z&Lx)#D8;*e6O>N48h1f$S!AB{w0(@Y#+&^z&OsQqqW-cCI>fW!%OU~8f$vL3_z)O1 z&PG`P3exmu9%(beaKsVMcB@(W5})DGEC^e0cASg1ZCrpyTXjwgG~h}f{2~@M{_#uh z4Kx593v9P#q%c0I0SZ3e{*{hwdf0sZTFJQgT|`$mmT_`K{{g6UWuBq@57Y&~thBqv zbYdTGNmS(QlrL4dZ8!Kz8DK?f2-vxgoxAd-FEZ`iCUAqWp2fGR7w|`ie131P%hK(> z#~M&+l($U!TsD4DKsS^-TCIO^#|Erj=V{Cw2YT#!S!elp62V$PN9!A#mB5_Xj6N6 zt&6`LNs-}I{7wti9v`0~iA}(_d=|}k6i4*?8fV=!P~Acs4yh3AlVMVa%38D*q`Qzf z+lG7hwQ}A=chq=P*%dJjEBJ~YqY!1p#NArc1dMH?w>A!```U9DS`7Vo2-RBMMsjl} zlG&^G7h|JL!{fVB>$92#6BUUTTXIN81Bh%JWl}wMvlfF<5h;$Ke>~0bF!L z@d)PR$7yMI%jAW6oS|Gi17JfS;r^P-syi;%X4f%0=UkcJc|2f~7R3waoMtGu{^7gl zjom~dv5OVPAO1I)J_VHE#XD3yRBwI>t)&G${vjA<6L5}_cS>Cm=)J6`=2fU_hTd2= zmwCakZW_U~OU?rO0SnD_W{~BFA?Fay8Id{n`47jhcOM@9_Q==74NoXS`z7+f<;R}G z#D0HOE+UnVq?==U)VBIQFuKWR9og=bNFW;7gu@v8;f^Z`lTUGfmB0hYPA44y%<&S_ z)KeUNc3cd3ymL-+A}3BoSU(43FZv2z?PPCXN1&EhdOI?8V^Y7q=MF`Owid^6{eeckS@KxHzB)L zDf*hO0wk_3NvvY=V=EzOk-`4~zD>BNtNfMaiI8nJH z(orZ--b97L)CPf!qjJ%hP903t-M}&gGhj2L0LlO+ z!x|Y%t|~UW=Q&V!=aZFB0%hW|$S>0<>_m40dXV9W1$EAwq!jZU+9YrU90FfV@g{F` zB9rcsSnadsdYHD_BdAWXOm*A-g_`~AFTaO;kqbq!z?ZZY9BEQKq8dd0Zlr4TuvyC} zqU);1oy#cvCgU~K)#JznhW=aM0~3u|)!)cvmrjM0g_p+ckn zlKe!k(Wm8xXc%{j!g?b>t1dE9cnF%DLhXo96-PJG?!7>*IZTf^-Cs(CDAdk`(-@%6 z+nMS{%}q%1e1qO?^bwIm?p{mN_kC4`HCJSc1+LSvLzL=g1^m0QSpW^6@2;Y@xI|Y% znsime&i8`Qb>E^whMmK0J0ZBkiUDo1qMVacJMt2A_No5gbTrsrB54ms^*=u*A|NFz zS%tp1)B0DAN~N~~^Zx*|Z?gVIk7=L77xW+D>pE}9E$xp)miB)I=66vL(sdlC<6Ir(eBK66!+1#g&HFsoNf6UsLfL zK9$-l+D3goC>Kwm)Al_5_DzlhKfaAxC+DrzeOW+x3KqMy7JoVUI7X7VbQybB&-G=% z(Pqrg|4kkKKA(#Aw}6=hNJo>{_K(?N#xsiIO-{jXts> z?8(@|o~}M|20^03|I!?kMsJWj?!Xo;bm8xz;$Fz6QB3)lZid00zDZh*yaY@JpwDy^ z?xYx|5-5#G5&DL+8+-cBNT2`xMoW zQ-L<3Xkx<-aMENCQgM|{)Ygfo4!xD&fs*-H$>1|K&%9wO*TA6fx*dN02iW=P@1auP zBlz0<4-mI#ISeoNeaFGljBjY&o63t7rf^baDbpLI=4JCJo=J_vn9ld-QMi~@V_N0J ztjsB{Rb}Z2-3i%1?IFcb{s{NA@3vUA^{n&Tvs7c%EMWjRL$bx-tI#}VI`+-8k9o{Z zo?wN>Kfnyj*qxFO%emrg9rFCQ(jhmhZw{CX)xyX64WV?SM1N@N&xFuv?X#Bz^i9f| zyNm&rQt zlYkXUYWY@LwS(@QBdhC16tE1E0Otipsr6C^H7bU&$#v_4Q`K4+lp!~akvM_A#?N!~ zsY$f603=1IH$kci|4 zGE-p`f2=cXSeBkop>*j6-p6IU%xxdYKdF}uN(M)-}o7b{m+)gPgTnCcKmsZ_xkpu%1|V;OCD*{*DXVa@#aB@o zNGvr~h!sb4XA$4;THpZq;iEG|vcD3&ir=F%giG*0n?+JVE7IYGAsuBnv+!Gy?|i}@ zv5kA-u*(D(;4}M9tCUQrfhWd=G8NG|!kXDrjh4(?a(piVe4_ir_iLW*HHX&_fr#-- z8?_RSG$nzTxBl&(N^A>#*f=pB?hLfifn0%#%(2df-eQR5%_$~Z!!(DHljy9Wm@|;t zmC;(!cUj-nKF4r(dcrZ_bCMc~*MMTCW0tPjPOpRg{{VC=pS*_D3YGK*kz^THHrGEH zZW|yAw&(W$#!hZ$yflgk;k{9jqvM&a#*mcuqDCD2WfqS^)p}3=3XWWL zuf^P$&sG|abp~vIl(I@=;vV-HZi^h`OhE)$=^%lF21I(CednhN$Faxg4*nkWIREZ5 zLS+wLUSu*=Qjri$NSPjSNAC5O%Xi%RPLx}4nul+aa+9@HdTh|Sz=<1`_qM;MsmO+b z@M8q7o`kj0q3M2T8kU&V)Sr2JsrQHh`;sox=XEkiPZP7sn0$6b4&mYaODw+2Asfj1 z1nIw>_=TDFQ^h$;T1J0g-yGS)yF#YGvMW%PnDB!;zrlEA>Sf$b=PTnNY-h~Xt+>l* zcXc3%@hO}#hM^AU3PW!bs$VL(piKx6>FD8_^+3_nTwm5=gF(E1jA6P`emSC1JX!qK zoOXm73>L;ak>hDhS09f;U7jgp*moz<4BVrs`)1_YQ3*b13p{HG>Kk5gCeW(l^DQGz z?^#$b$bieuZfWot^&k^YNHjq!r<9hJMuY>%<_w24JU`;JYv8 z9XqG*@TQM6eJH`c&TLP=Blq3G!=D|r;YDe2F3$oeERHAp zdT@7l3&9x|m3u ziLW}Cd@mioafjA2wVOK7V?uS~xp=%wrXmFaS5XuW^ci!d{^Ct^nc z)I*(@KmVSW&j_kG0P}K}E4*Lh3}!$f_&U5=aDC&g{Pfi6gw8!HPa_#qs2IJzLe-99Onb|;yR}= zeGha{;H;d>F(^AFz9QPIV`|C{i)3`@SrZnH%-?mmllN+>UjKnWR46Q9r_|eLnPwK#DLrK8~$ymP!AJ8}~iK(7^LzRd!AZN8iZx*T!crh^? z`3ngA2-*8Q0L==20Ww}wt9nC(ZJd<$p9t4$e_+xEdXGGErq3<--g(Vk=7t?q=k^_1 zF_+*2rivkHO|pOlOz<>MPE1|lPl7*0>T1&ZX5u90rX%lMKKL33c9B?qmpsh%Up=~f zfc)o@*Jw6-$)@_dD^R8Zui@ejRcJdImmdUZ0RxMNg~Z(E&t83=y64n7qk5fODZa!< zll%f{IIJ{-6btA&(Jpmn|CS;{>qCUU!nI}YKP+h zBzHo?Bt0TKtv*kX6w0n`?z(@XdgVFeTEHchDg^hbwBN@lZMoY>zm2J>03Ytt1vZ+M zu4Kf+_Q{IUCyQTROYsEO2YLjI%&XwEeOo&q!o9MTgx-5m%MJ=wS%VO&1C&d8tSFSR zb8vvbbeN{wM;Lb+tWFom(s@$cE_+QqeNxk|w?8pInA5ryQOCi~Tz z!Z=hqXVnbi@FEkA1NFaVL=Pk9J>k-~Yv>^YFoip1Pvb(+C9^TUd>QMW0eQftcAp&{ zQSA{NdcackNOlAt*3Z&|orBK^g7O}WKx`qtS`*IFH|hv|b^GxWLowl;g&_v8OaqZh z^S&dYNA*>NQ26YM;d-1qNg4=q46OcRUO6ghPf)x)(}#qM@YM~DLQPS_D_8@(SVKBh zN6Ch^OnkINg=AHp)wUk5oq7}7*G==NR+kbN*ep$LrJIh4a0KVQ17$yLX+5N1XyYt_ zkpM1zsWAZP+EI=?z5VfOiEH$|@29_>nKJVzAP|H zerjDhvLAmclexY!sqC{FRdwp+EX)SThp+qjT`y!wxeFC4ld_^$7sni&sOf7akusZy zhw$)FWi_f7$8yf|mD4TxiY%dQ^)e?+l>nIx&yCZRYGGj$2O3~1+kl}AQ`MVpH^XZO zXQj>a@dt7s29^szi5z{JLsD?Kyv2I^j#|7CwxF^Kb8O$<+Gt?R(vki$vy)%CczeTA zGzndYw^oU+rNZ1!U5JeAijVv`B;Zr!FJSU;zlQQRrX2rV#OXs+T4+2I=ydFcVPNlZ zfnkaghk?7JB(cA40v#>jbXRwzvx?-Iy+5}q`$tqMrw$4l^pLi zGnt=F6J@!lot+U*Hx<{cPK3dJ;JgIs6>8v}LC~5p=6bjEqDm_=}TV)A6AuGHZ za z&Ug(|b|M!RmH_SQq9WM1Hra9pPI+og`|oX&(EZh_s>RhibRgYK?@EB7->l(3zvxKK zWGf0=s^9$m+KzMcZ^h$jUK*Q-Ir;Nu?H@pE$0OX>yv~5LhW#^yQ5Xw2yR~3H^XV;B zW~C=tR)Q*u=&ZE( zof}EwY4;bfdF%;5fQx0-po z5z%Q8>G!uV+psvSMq>VjNNK&HawXZdjOo(z$LOOBD9KHKqIboizQ|{f8$skxs{P$z zOR|EbUX{={c+*|cBKFZEf;Lwi4W~L|gyvElLXH>KhtyZkNQaPWk%^iF22Y?#7iAKH zhv6jci2;F4*#peaM=x@i_Oe(H#e=gb!VblZfjGx7h$gvP(~Ydx z;_X-+scyKmPhcr?#A+$I6T-I4$=p4wqln5BlLB!${(`8)$s<#1q0|Cvq46 zR;0clhMC#{SYisEHQ-a+7JS%9>SYt%pGDS@Xbr(!BHk7-F}VXUDW(fk{R&Y!>u_9( zNsrYg#M{i`P`ub3B)-LPC=ofO*NHwwZz7!+Fe;#z<5!JcDHzryv{%Zue6V2p_@?WO z(`n(cZn0yz6o#k48pQ8QTf2UlEeUV5AIJ*?sY1y}xXpZgofB-aa0@_9C3Vk2bgGtJ z{8~F8iY8bs?73>LY_!N^Wg$-Al(A@sCqaicuY!etKv$YVGBOzTlInn44C8F3q;6Z@ z52myD^FEMHMHEP4c_E`F`{3~+SG}sHMD-1MjO2XU&|a9exZupD+do=t{BGK0>T663 zEsGSGw2A(JjqW1$RJfRHp4sw5beOTIXe#N-_BfY^In2!V_jpnE`hW<~%J+!r^3+Rf zYt1WS_*_;_H7ndbym@8gim|?oA1(#%(2vwV_NOiAA-&89_@g=!)~BH57uW&>S9LSZuV6^_)TDDtXN<3`;6$x6ukR|QaTl&JHCQO7)uq)X@TVm{xBm=CiiEEuD_+4wV`?2n9JTjegOb`s>mWcrhbV07h z5MnQaeB=SqkBb!E1Ne0q%c$mWBW!Nhd!R@0DZ>rZWIj1Chhg_nUb&=#Gitp%y*_a( zs7O{-2cFA)AK6aEfwL-+I48ICbbf;VS4ew4W4|%p1j2 z1#FD8Iok|5Z@WEV;Dn9;5D~bu+THgturDK`WV|2Z4M^#5SP1IpH9iiP zf{aR^qX)f%7utvj8A+{&__$((7@P#RtOAJ{Bw=8q+TKMZZjybbp_^ziLw1P2Aj~3+ z65s{p6z0pC&-7#c0D(BSC-+d4TeV#2c`5-NkFuN>o;^dA3n+~{CpROXit!lmYuU#r8v*}$A zN;G%~{6=}sSbXOnEynVHpp}|cnFxR8C5O0RlhWCP*Ojc5RaZj^t&Aed78d{Axg7lMs6QLJyeAZ)t@F+)z(P(BryhF2u@D6b(ucGxWyHN-|D*b{SG-mtK|ZrCEhD1bQ0&SN~@MaWzqcfF-K2i zWNj8(Pd#9Egk4Qv<+4_P_byHeEPcmnh9DVbOb3Wq!BisZm8lSJs0BuN1%H2X*Pc&T z+ZUN^mV%!TJSh=t9Lm1x=1{;8kr6OW*HrdGvt*Y0t*O3hQIj$gg(P;zR#$vvsF$cZKy)t@ULIjSq@31-0PlWGt&1H7 ze9YQ{TGgY0=FaguJc1m`op;!yQ4=sbW@|{De4yC;F<_cSu7U7M<@s0#l5L+S+5Mc$LSJ!Hax?@&HRe(}_L&)+>y&flCTj?wf#hq`Gx1(XbLbi6cS{GuS$ zM@h3BmI-?%QoKXsiecvpx|-`(DV4}wB8mKyTLJp~8s?qecuHsf9dykY5!et@=xVco zr`B|8!rR+GH)zs>He4P2TX?^Cy!isQ)wT6JgB9D)3)g*OGUh-`t(|+S{xPZxi7+<}V*7c133=wXCVPlZ+ z=|fFfrVHX%6z@RS+T(CAw;}9$VbvQjz)Z}yheVOJnXA1IIE7ur%&oh^(uAq{0jhct*{09 zTnUyLSX}Cdnf&uI_NOC-btsW_DQY)oecMUbm*!vn5I9U`@m3~F`Ja|#YnYuz{;t^p zKUjm4$ZHkGHkrSF(_m~t!P@@G>``J`eXN^}>5&$qAoqRLA6kIB!tW@@fC3-0%iI)t z_Q12I$Ka5Nf}OFz6P2}n7Ml~g1F3$%NSgLfI&AXIZ*1cWmiRPsSCRVZaMM1v!xwJ~&O@l@P+9RG zQA$GJ>77)@Q*Oryb56@S-!O@YO>To~ncYooN=|u7*NRksJ#(ck8lH766Ff6~spW18 zSqVyXb$(4ecKf;;8YBUKq|Mq0GmpVH;TH*tv}G-X=wyOj%|FQ3Am_}U?4;XuW#&O1 zU=_w(QyJNCr8$e#G|`A53dyA#mbSsNW7LMOahO4x5Kll?(HlN0$Bv+U1^qAdo1AZ; zt--93@+uZxYQG+LmDL2Hgsfn!hAH(Ry?JK0DdqoCW8Bgum_HgDo=o#0I`?SU88V?X zi8x^^{>4)sG}^e6uqh}FvXiCU7_5UmVO z=ggZ^2yy5-Upr;%uzRshp?J)Xk?66l_T^x zN;7RpsAJF@hK6M#QMWALTS%y3G}?HKgE;aU`M$oc>TC;g9jh=6Pct`KHHZ{{3ma;G zj6}t(EZ3mrh{khFxi#cBLEGFv3Lr~o%n7-Pw6|;OmERKkPB(z+(;P8D+cRxQEjyBM zN>VU%hH(mIpToN{24SeK^}Sd;y{{YJcyPiSIU3Wx;r&M2)HLxUVQRYpPFI=N%$+`? ziLshvnA=mG&bGf4ffMG{o(-)7v+b7Z4WZp=AAuyauhd9nPpv5ED1N|VujyL*nf@Ic zb~O_$<4}iOZACM;?_?mdWbYyNVv*=Zx%g?;R0aPO`1`|b=+zFq=w>+I$d-Miu126D zsZc??_@Qk96y|hpzD{njXs@-+nt{aejoCxI7)|DonIyP+m2v>eH1U|D)^WMDBf3rb#h$)h%)kD#U*TtmqP7knvh%$Y$YdAu2qfZABU^bL5Y~BiPBR)T`(LHiWqP;e z!fB256XZ2y*HMZC(hZ2tsxhgL6y*XCX@8c{h*VaTP5Nj7ByNfy^%o$U{xjVVVTa9d zQe^(|u8I=>F>%XKY<^t3ZC%dQN2*S7P(}GqKcB(Z9Js#3&3Xp0-hGak`>DeZ{SeHV zB&EJMg#fmLi1HUS03A3~z)Q$=`Jv6PeB;H2cH8O(RAVMo-q6%j`qXZ?Qz%qsWcimg zHr*oA4}tH)2g5exj&y0j1c&lp%G0t&Y3Xi$jK+HNr7hLFBs-g8_|s(Gv6&i zslF5i5tb6J80I7fpo@)N>;i+h55ISZ7uUyF9U4PBRYjsl_4G?)aA@H+w*MCm9 z4)m=#3>m~JTl^*>t}@P`K+YV=Cx$u>YNcVX(DGXma6Yp6Wi^?vez*Z~K31&RSmt%0 zF>i%5+29|n|Lyj2;Uddi5H(N;V*H(y0Hkhg!p8Zqt7;e|nUV}UnxOB?==MHZwog&D= z5`q9)%O0z^BEl`i;ZN~(IL_k6mMqh+DYZQmp`IIdQguNM#MI)D^5h?#TbgytGxlU_ zLqH1fm18RN=!9PL)bSuo{k;%!Pt??tsN@g^VcNIA1_Y2~^+A>UX{k~Zsb2%nLct;UUlL}N zDD^5rkh7|Hi$~O0MlAdnMznr>Z+N66{jCS_R$5Leoj~|(Qdy?boRALaM+{TX@}q<$ zNJBD+GfG|X9@L#hBzPS|px&XZ{9ce;XZ_NTVF4%=uvUTH>#!lnFO+AIa+vcfFc|LP zwqa{;SCcegNtSr)=Z6nr-yC=;$|^&FHRWP@gdCTF3hAcwcdvdG)nNVstPy@iCHrGd zp>j^>R*tla*^f`&h{J*A>(sV4U?z&tx3;WS7ub=_={7g3A8E(bERG|KrTajMcs`)g zyf2UaV1BV9_D87pFW@opoaBZid%38&Ve{Ff`Gr!QB8HjgM}yCjT5VTb0N1YfiDRY# z>3v$uwKlz$q;%B~<5~#frShy95}FeoQ4L$(ir$GhDfn-KEaX4(O5Ai*mL- zVwO)WU%kKCJI#HNM{67A;)dVM;>=3E&p~TTEX4`5g83~{=lK%mV{RL0n)isICN3YE z$D8IQy_)IgFRhiXb%VDe|GV!%4RXqupDiwNvKFG1u_@DPnE6EaFMuqhj!m)3O69jf zR%UqNYWE$)XwZe|dyF14?SjSHU%1i(D@u{P zjC=mKA?yIQyu_>>n7FH6{0>d z?A2a_P2{wo{AhxmVst`57PSsMwM$@({IblhKhLYAFveGda2DmjB~7>G^Ar}3h?}UZ z&rv=O5O|aK1460~Oz|%ubne?Kb&ay;u_dATxLzR^P!9);fj12RTrpSih2~Eza|#XH zT^4R*#<6%A*fp>ox|tEln8VV&|17ok&C0s#*da-j9v>wC6&!_wy1ElM-8Ut;`ayWY zd-f+nZihOJkx~a{Kwd9Kz-Xt)hwtL$6-9edhNWJU0-?4Pt82b+iBnT?h`HnEB+)WOzYITa4kq zb@M^Gbn#p}U8UoyoT+V*=zKYAwQ6X!<^Yf@|2D~q4AG?KhsayKZ|&$+po`o-VGR+{ zI~r&5xcA6_Dr#(ge@U+S1FZc(!e9yuWBGmqLEcetvJl;|Lz5!whzqjPPI79a^JHh= z9;Dz8!H#+Pv+K=Q{-k*PHGXJX42;(C`@Nc$bH#v?zDWEKPr=psD@-kJ^&J}C7>?;r zw4HvhxsMpw!>)cst@|0VEZi^HO!|Tw8mrn|>8%LmkkfZCN7O|GwkFhXq#-zGM9BN= z)86R1r%Ez}3MaEiJQ#r1~1tNTeL7C1!6mGT`-%KRSmZjtNW;uZ3yE-+bZ2W9a$2cCB;T*W6O2cS55 zV#+b-E1FiwUi3%8ywMVQ+PSSo-@E6mzko{+D`()^8$UBA>3b^}XVC$^?SxgIml%Eq zuljyd1dMy&&x#%HJUl4u%ahx1i0Lq8MMMMBhl-J(5&LS4ib4a#}?H&u=2 znWjtkq13>(o@{U!LYc~iV~mVKv4q#qTk{!=$K%Cr=X9p|8`zR|LMq?->;3}1`I8}~ zTb&`~Zwe^y4u%>}vxKd-a==5Gv2OhsjevA4aJD^Zz#TK4QL=0GdsqFt`G#?t3f~UaRDFS)P~Ye`&TCK>!wAvdjk+J`a5l?-4m6C?#FnF>ceNJw=&aB&BJPL zd($fR475ZrM?3C$Xv^$MT6bzE4 zOi!4Z=BL40t#;6iIw8^X5mFHsYu#wz>63UOz0jIbdePkQqgBC;67wr)lKVSs1ty%b+1g(_9~GbZRa-hvM{Nn z&JE6h4<69T?%fzoRek}*7-u{OxPC+X$+1XHS`Ui)?f@FzF+HvwpbS`h&fy*MfuM|d!>-Qwv6_$Iy zVuez>K~h7t$54cOjSlYuF@sis6a2@TgPCkN=^v_Y)WH2o?}4FEAwmT@)HAdJ*6c69 z^whO2$%@rZz4FP3ar6{8jDZ!j#%&FI8duv3Xr#}mUTX_Cef4zwA^akLC4vPdaBaXv zU8jeOkjz7$)H`kGXW1T>+qD4ilJ60x8v)YWTIF}mdW2xk*Q_C$`kwn;pY-Ul^*H0S4fQ;fb_HOL2K>h~%`a-?zJxJA-)x zQCeVIS{EA_zdB&Wi7f?~ANq1O;}(h#-yy|U&0L2m0!?|6cwsQ#>-0|;YcJ&T%b;)C zWi3@*$!+TFnLEnc?zYPZ169n;^M43EO!vE&|DpB_9P(Mj_X~cqzss4_1HBLn@Q=B0 zXb?_%lOsJ{n1&88ixt!{KvThO>X70+g}QpXS7QbWGtE65F0wGfa=PF121xRA52fDD zzxsvQ;(g$*wpbyh9b7vQsTyq_0s~@OMiUC!!XKf#M;`@^Yl=7oy{_>xrekmo_bbY* z*0y;`LvPhhgxv=j-feJ^FpU02Szw1e_Yrz5kGY;q^r3m{t|hwde31B^%9czN@emw$ zYCT_!KS6c6h$7^ibZ#;~g#zWn@YeU9Z_LkTsEbvyXPYWG3DjLhcWSMM>fn(+@8kTI z$cBld<6y!+i~6L2yGjeyJKOx`k92FFqf`_D3-pYqUw*?ISMbiC)&;WBlB>+f7|n50 ztb`Apv5On4*KS!gsxXgew!KHdb6A-M}fGUrd*7q3e<-5h4lNvkdYv}5(~ zH6h?`#gbtbdFM$(^ethR(kJq`dmey;;QeOu{Fn}A{+*z(5|WhE5gxA8t(>tI{(j!! z2$>nY1G^7DN8|4CmU7C`&AgxHj z`^HfQbGve&qS(w0sPd%yNm3PFSO30-MgkwREg?{rcnhtY;aftPlI~B(WWc zC%ikw1KYoVesTW`5VMN`BvqePZotC*VK-GX{TahaM@NU?%V?&)gS(0lDw!2VyCA0AV+Un+ts6 zgl8LC(v9N)u9n-c;PM||nSd^=w91SZky~<4X7sMsZ1td2Hfft$Hr7*>V@x<*_2Ju` zblk5`a-H1v$QMw-?P!_?(g}bYt|F@zxd`7>+;2gLJ4lq414x=N4QtiI&Og1#fm~Z1 zl-VX5Bgub=qQ*SiBVZtf)dtf;4aW0IG!pRT+9rwKAZWx{e^4HTWX(|l&j8T1xFjMU z$S^W#=}jFR25ZW3TdK4RdIctBCi}0%WN@B|zg6rXJCcYHU!K#2i^d0Vi%mBGWv{tW zX<&bBi2h)qP`lN3U2>1rM5UHlXMl5-&kAAk7&MMK zZNCx)=$K80R3N^d)bT{dW#Gxs;F6n+evnZgu>DagP+#?$?xk2|L?SkJyhr=ia(1k( zT$m~gq*g_JZnIEC3sl9=Q23B57R^) znaWDHHm>5mh~SzEJ7^X7o#JW~TUJZ?Igkf?0y`*Ec1c@)3EqRB5sLE(04au-zsUyw z5be-4lyDU=-1N74%xJjvUlQDS6HW_hc+AW6D?7-u9L)V$_e9^x_fNTm;4!}Wx;M{i z^+nL?kY8Y_?Ci&T(FKno)dlO?!kfsio@>9d{XDBr)Uia27SQYtfvFVTZm>2dh zV;g?GOJALB3@wcWsV>l6Kzn#S*Zj_QA&B^o*`-^QW^c}f|7-g{9sgS>T-MR(dIUn% zwf%o)|6Q9)v2?+-Hu*10|2E5D`4V826!t6tLX=4UGsypp`0oP3=iDYpqViw6_}`KK zIr#r6yo_x+sd{&2M!xwKx#2uh-DSSXJl%f&a|lz9p9_7@g8$q8e>(qD(0&X##nyQd zLa2Lxy2rJ*b#bvV{hhK&XKwoC&#~rZ`6Mr#l~Km81GPKoa8o)}+}1yMroV;9S`O53 zX03Uyz|u!UhDQM`xwwiZ@CeDSDm@e{_dvdoulvjpB5X{F%%@Gw-@&UtDWB}C>DkYn7>(pLCo-H?33|+8qn_l*38pNhZX6x%X>K{4`?_0qzF>MlR@dLR zsC>X*M+wmrXpvuaSDpBes;X~ND3~1m++huMg5dUuRO4&x6BowRMlaP8jbz{^r&Y2_g7Kc8Geja`0mBcnqyOP z_->Ct>{QAdw*VUHkk%{7S>>tPZ(P8ltc>f|XU29$o_2+xRRW{Nl!f`=4xEfvNNAU^K>o^*wtdTA5Hdnu{98b*K4U zS>a3~O2qK#4y->`oFGxJ+`w!X9rGl6UohE&3U{E8U|@ho%Srloy)NFhpK(-Ev} zzQ~m|RU6reL8fSn5yHYBqw7k{WtVS@Nnw*INOXLX*+oMWZ<`wfslK##;_|o<6Lg$G zBfTrr{^=HuiMpce^#sO5Kc(2-2X{X_|3@sPLJ2g-zH_l5$J8aU%N|wiNwi_e|ITa+ z1LgTP?XYr-$lID;z#us{LK5zqWrTN#aG-av+iQ0e2#Q@Okm*~rodt=JI1lcppV6`7RA$H|fJVl?73OEO2XsBd`oef%3JL>b9b0w;nNlp`EAjY%a3os{LXzl+@4f$rTQHEt;WN3Yk+TIL8MoCxD1h9$Xt^pbjmD1dEaxCru(Yf z$@b&KT=R62>&N;1bDL}$!^?}J^ht=(s=v~k37v1^2_t=UB`9BbyLRPnN-)!4RKd0S z+0E@+eOf`0tlxac6i9rwngQQMIo2sI|O`oJ-D>QZ&lSm5;Rx2H8B04{ki@ z2730ypbI&bwIz&Z8ZUilqM5n2c(rj=8J8N1GXl2J)PV8#6he?hsM5&8(m1V=r##2S zDx>Ma$on7DtSP}PHgTm}qwQty;cwqYFNmd6Y4ZG?%QT+1;kQ@btfb( zer9O%7eybj-8;dRZk*uRsro<~`mjxr5k{aMj1*u2YuH?N4(p%Lpv3ejHsKV%9TuOz~np3S*w}coPO0U-A)KXp<;gM^y zLP>+GW=tQ9b?P(YB0R)q5a|W;$zjd)raM566`U;VZ4$xzr5LT_Y>~kE20KQwm-j} z|J;X$ZodRo!FZ0063bpOiJjzZ{skCY#s<;y5Dp(${@Sr@c5)NOQ+)pKdRnV-zC=lK z<>B@rJz|Bz_(0H8j1;{NM%#)b&9LbX_z9~MW~YBMRo?6?(+`t{LXV-&D&BMjx#8L5 z59i1afA5&vi(!!Wc#vyP>505wRNmNlKv#!`m36@j4_oih?Np{FI%UmuKvdk>y^l0o ztaQ1k9Y{*(SQXQ3shdMU3jp|*BDtKODvoKXAV@LQ@#Msy(d}nsq;KFv9z#SQAp*)# zX({hit5&{f+&+n!*WGg8r_3d+HGlF<$2Da>A}_95G6#3>ovs>RlLQLB6Cg` zpFMu{I{3><9d=%p`(q{cD5WUOupQQ$3W^k#GPX8YP8-?)O92tZG&C|pmEx705!#o zgn<@S?Xl5^8J@gyX+9$(Z2?+U0WBV&m(#e47U;?^V1$nmSOlWRCbgd~y5{z$o0~e4 zjU5+2yndI2C}~3|>={%!h}Qy`KLfQ2aPGpzG96#~^OAKF`a5e?9)QfFxZfJ)aU+3X zFQZJTrEHB0s)?ehYXQSGKz#DapXJ$dKd$A!QrZX7Qsy(4q)$8#cT?66-L)5IYSY0^ zBlITy5?zif#;|pN*VGg@*z!G=zrK&z_pY;C0&}bCwC}vnWP`>L5pcK>g+*7Z4Q0SJ zc0SB++}nQOHU_%(w=kkX4wYa@L&uD*H-2nKkRi;!&|n}fv+6zN9pA|W2Cqd5{D;Yj z==Uu5_K#6yPNl_}v6Z2}08kq51yhDxr8)XOfxF!u@21@y!#pp4zmvZ1@=fg%5TOwD zq}PLKu6vI2ivK9=683hM!L&t@eg#V2lVW-<;{%R`NSk>-UovPT=OJ<$E7}obcZX|( zEJt7Fj{DeUy7s&ts|4-m2~~QsHQ)4uqK22{`C;QT%?IS8|6P6DBrn%*seCODp-!~; zeV*L@xa`A;4M{Wb%C#oCZhm>^8`=|eFAEi6!C+oNuXRZqq7?T9P(5Mq`G{J`P9Atc z2lR8MOQqk5*xNgvsP!Dnn7#Q(yYm?a?p(Dxq(b$lgv64h8Bw-7S^zF+T+nz-k+A1Q z41TK74j_-OFW@zyb3BGKih-U5WR@tc``50v{`$FXji|WmU%*^|GP#IGTcm7gXtq@I}0xdUHZU{5xoF=rLJ#c1Z*fSe9obdM394g?aOS*|iX03Kl zmhhN-KL%FBEa{OFBf6Y6nHzkmVFS!8gDKHvt?}{+a zAFsgNQ2zkaN_{#gWQFWEu%<47KhP;V_q>@XE=IwLgjk) zBuiKOwOh*E>roDaBO%2vUYvAgheYU(F#W+9m6Me<1p2~M^>u=R&X zEVOL*z5^!g!qZ>1uq~EpvSB@BHT$#-YcM+;bj(^vq243axAlRPsG+$!R4RwEiH}nIOVZoKQ_6NTq{oh6%97$$8)c4g zlXmx(2I-RgOEm;a9I=H1I^~t?9mw*8CJ{0%?1hT%YgZ3%H!w20C*KoK9ZZEuL%mw= z3p@3WUgaMz_!zG92A#4@l=>RM*q_ zPIXNjQ*X_!#e6nMlTXUW{v<4;EGb~yl~s$&x7yw)HQze!8!N)Wm;7$^$^I9BulZQG zR5P0kCtj4k&oT}*S6!xOL)*E3FzpejekG4n&N@n`>;qkdXpLI49ly$E&QQNCIB1-y zPpA4WUv7S@2VYAB|W7qj}E_n+>bw0nI2@$tE0>4r0kd06gKK!VGTkaxb zgi(76wJZ(omXQm|pF_J3_a=#%K&9sVLBK<&I!uDdFa_Z{(WS>CD|yPd_p6xKXbWIh zTRl1b)iJOxbi@ER)XN(PdGN}Setj~0D*l{mXxSJ{YE|cDKN%piY^`VC4^xHUD+a4W zP0E+0AIYWi5c^_&H<|Q|SKiu}fS>NO6`Ml_$^>DGhIOJ6RehZGNeX`$euOhjf#hO4 zI{e+Gtumc`0;@GbsCD3oflMsz%XI7*$K_dyfirc2xYYw$k8OvykGjuV^$GkgtWN-Y z#oQ;GDe}U0tYG_emmTNQ!o-Su@9dczFYT`Zv_XuIeF_kw0 zE$Pf}CQb>m3=t>un2FwppfmWrO3 zbjj=q{pwqQJbi&o7i3c!#*W8RMm0^;K>a(Kl2P6fEc2z5g*?i1CfB-|oeFMx)h|iU zuLUpSlPF)EPCKH(e?wi=JOEQvF<13&?m}Mk?V%yU7%>g#td-Qa-GjcIQ+rkXlCXf{ zMaMmu=ttj>=R{?_t!$d-99Cq!F%RY?`7+A~s|u`<)lAGChG2tPQn%9WRpn^OJ6DLV zjp56bJ6#DPtOIwROa8>DR(lmp@x({Sj&5dEyMmJOdR=Z1f{cyBEzqUJ{L!sb%M27K zVx~WMzR%F*@+{TRUNjzO*!AI2>#rQldX+&XM``~$TUl`%ShIx!XqRI0COm-P)kYr+ z`5{YFz6uV#R0AlF*HEr1GEI6*x@lwt91%7p!OO(#QDI#4EIcRu{zW1sCkPG6v`uZR z8tDk9X5-wl9CN3w%bL3pv>g(6hrfqbGPSD7vCZPT+mJhv8HgldUP1=Ve)QozP+BGj*T;6PKMxp%kXSOr}$bk z?%iNIhC1G|E2Dm41A9)MV|;Z?Q*owQya+7XElvgt6O0uN4Eq;6CR@H!cQF*-*iXtI z0_9od%pO`juNK)Y=L3C!)F|D29)$Oc&Q`1Ah57nH%z{9`DO~ZeTJ*0c_R% zZAw)N!m40N#O;E=!%#Yq8Pxsf*+EN!%scgA1?s81>}A7WY88l48n*o7oHr$^)5ZNa zm^~lk+N^&8*2)DJ%#1sU)!@ngCmNu2l&TJpuDc~F323y|w4=;! z6S1q}X1wY-&;$Gnh#WPQIL{+{i>X!bd$)_w@evme(PJ1jMkbP02d&jIn|@{3{{$Kd zv`kl?85o)AJ;YXV-yj+anEAX5QZ=C*SZQa}+p3Xp^F|dIgKw-?7=p#-O>4qEp9!)& zr8jsG33AmPzRq3rH6utqU-9h5PrnE3xGT5dJeO?Ru>$=!Wp%=}BwXFPR?!gqq6ej#rPeTR2EhT+qMI`jkYLl{Sb;e*Xp zHSjrT*G2q&Y16m*nvRt=$a*l^xm|u15vQL=Z@WHYLVN*M%kTas<6M_E*{x850N%iH7hw|l0km@PJ<@tTOz3y(+#L2x9>!v8fIm?9e)8fScuG{PL z#wD$$z$U-xuDwu@q@d0ryx$G%J=iT4p*XP}BfY*y)_j}%szrz)wGQS`QKdzkc z3_;pm`xt#=y!trm%CJ8>{Vb&|8+!^$|979Nm-pF=mn$BZ7{O_lj(b7vDG-+SA?;iu zO2np<9xGM^Y2aBi$;4=n!r~D6UvzYRL)f$=8H=Dha>s_uT( zZ&N}cMmu=Z0U4SEx-zk{IIUOAcWYZdit^9`FSxkg7|AfD{FH*IGzda<3-{(6bn63; z1W`BU=%bPiVsPw@llGr|G+8Yl(hPqjRA#RAS@xq`5o<$7p&rN1K*3i=HgI~1+xN`s zOD`^h(4Q82yVLIkFY!maTE&GhFtbVw9xFKqA{D|%PhlPHmZ{g1L!Mn>lGf&>9AQ$& z9-Yew<7@t)_#S80gV+>TzXQ53!q5*~BYUN+-*xK=buYOTWoC4V<0AT``6gXiQQJh) z-LniP@f=*7wM|rxZc7%5+P(cPZ~iW<`oCy49QGqRteiXWA6~x7{dw&wrQRyXskE*F ziLqp(zj2zqJ*KTvbD6enPiwv%%T>>q`6q(d=wXEJXVZoPiT>&g^=AY3X`JDjh2rk+ZE<&ZE$$A3yGwC*r@-Lu?(RFzygFE!jIp6oM``>jZYh{w1 zot>=A>}2PCAF;~aS85)6J$tx%d5+0Y77#mYB4%x!j0XHcZi;ce3jng0dA*HIKj&!3O6N+r(>TkZpsI z4&k>XVMU$MZuAAbD8SRmyg#Vg&JXK0r5s6nHb&BfSN!73 zKV>w;Th_Y84hGg`pJThOx}Z2^QYUuKKBaO!g`}((za%a5G zbV?1VF*5-G@XMSw-j}|T?Sno!MR7wf^GdJbfaCOqnX1aXBi(ERIBE;ibvk<-uCsgl05|r8K{O)6 z4<}7HA+Q>pJzlqNIcG3|oHQ17baBORDJ^GF)pA3OlR^-1jkZD0#+;>G#D+xvgm00_ zPV^UEu`G&73r{fLAaoB*hT!w&3&@?lCv^hpMY?}#EU#8zm z$!bgK3AmkkEHX>>+!8$g62@~uDSJ& z$0-w{U|Y^sO?Up?K>Y;nIv7u^o8p}hMr&=AI5cI=vyN7sh6s-0YpN<5ovEjO*r4}} zt)Y%56{2o~h4S|dKkXSSXH=6rOFz^bk^}y755p;p>h20aL*-}Ur!Q2eyE!8#6C)}Z zugHI>-NBm^F9p+=bPj^$iq;HjqT#HJ}-11KYgDdipfgdH( zEu2{C3-}$l)pCr?aU!>!hbB6P++3|%jj)sp5^GiSn6=AVk{)BlZ*&+?S1uQbZ;*g` z{}BoAiHOtk_4I%(xi6vJ?8?L>CI9A9KWr;)zPzwid?y+z%8KShAQ zzn&jE<~No0i|ymmN|{X49m!z!fOl*VDavPDW;*im|bMcR~Ygzka+8UiIAx$;gMe7>XrwCtM<$DKd^h#0&SQ26P@L#v{!)2cbzg9Sl^Nx@(;yX$lO~D#pa@8TW$t2(KAQ2xy5sT6xXoWhL$I zE$607LYnK$8;6SBitO<7e-d&(oBxIAig4#iNSh*r`q~zE*Phma=!zTx7K+U&3Vtr^ zQ9&uDM_h(3%3)S)h>ooAm$c=cM_1hV7UPCoXSK?Au$}(BB1c^oW5Y!-!#b$Lxy{Ge z=rlM4eodEo);jg6VkAJl0$1iwSzGx%&?8G^mN$p{n1kC}@=%0L%GqxPhgLUe+xEkx z3Tl_g5t;*zo&RBF>`>Z2`JgZKdxrTpAghmxW7Hp}7iR=8t}ri;$G&&eXBp{w8FHZ# z8h1h3(*avrZZLhgk_8EFv4+6LHTtqlv2Bf#%<3e4kKV~6ttCb{bRc-B0WDG0=i02B z!D)Mx{a|)E%QN(ZR1eFMa~U9pUI-x8ko2R}kNe`!^xIu#xcSb!$s%U8Tq#l9H65u} zF4+IlmG`c-#CT|6He9b?i!Dx?-&)t@Lbb~kds#eqE;@q`hT14TcRd4Zk;0rZ7yn~i zIV{7ueq>A@>4K4w5jUO51h#JcoQTI1yWRrr5|Km*tQc^~B!jT&((MbnG zT*pXdR#!6tyeiGJMYrttl!N=!VcBXfw##HCG34717 z-;OVEu!g|=&aHg=*@6oHLGp`#XZz<0I5B+?TisV;I2md5LuwOrN&nry5R1@`BKeu! zWF>TD&F1oOqQZ^8XGVL!SXKzi4dhMFdYw# zHt~=dv(xerI;bF#8|WD2r!ScLa;(e*jimtZXHHYY-9vv&3MG0S5L4-Pr2r{vHr%E*(@!sNI^3#4Qq;v(oiw%+e=6= zNntE{=x50?I2Q+89cC1gI1*%5-*nG@rODf%$K-9bNE{;vixL=tp;F`*KE$~09GnO&__C)nAc3r@2@@y zqp0P^s<}^3ltDaeUGp6T`Qtu)DO7{44EXoo`YMeuM&_awUVgYmcn%ewrFIrh0!zyk zl#IW}BBOGkTG)pFeSWW{Z?A-LI-h_a<*hUL3h8qAwK{_2`#QT{{!tx>o7m_f1GQ^Y zxg*k?Fjg=u^DZP|Q`X%Xq!&WB>H%rHiDL4A`697UlQbr<`H)beFa{l{OwJ=`P7m6? zMYus|!2gxOG9+Ztz-T+41++W6NEJ;n$;GFT*UjLv9q$TTjN#7f^V(pe=e&C9n)tDl zL{#0EOs&*2xs`j!*DvU{}%#_v<<99ox;REDgw96 zCXtT|c7l&=kK`{6&pf5e=Muudt|x~#RG~^2E{Um-Oh+CW3;_>NB|x}^VW0F=6fRW3 z(f@B z^~Og+vtz8kQuDr;m(YS;S;a&2P7j&2Rn0qdvpeJ#hxleJYkM@)k8zQ>O*GY}FN#H; zT1odg=#Rj!#EclD=lJw5{9)9Qe>*P(}(r zRUl7!cT4>!NUI*iEXR3>tgpI$ggkBU-&|J#IG>Rkwq-6+rVCM zpBUa&=A~b~j-lj9P~=r{@Ik3rg;7J-uT(VtMd+90!J+8|6KLJ9u(@mw42}Eazi=C1 z{oL35w!Ib*{i<{gunx{gjHas{KGAwUC8|5@U4XFm5tqCA^*5z2P+fEtFR!`(2^RN&kgVYM}kK zhfV`lOUsAo(M7U8m@U?NmmS4ychJmq>QZa~YrU(Mdg3jPq|Je$WN3RhpQ1g^M23m9 z9eNk8nD=yKrMjvdP z)eIxma1+B#4w$Bf)oMiA%py#HQ?l*$z$1GhrM=Itarx|0LBC%oHSKBRuVDX}(W>Q& zovs;v@EjS2SIIV!6DL6)o7ph2>w4pn)YL7WshtuG6a_tia~+NRchM<0YW_=6+MpOD zpe9peLoe!N5>+6P8cVIu;A_C{v!JuAFeG2=U5xXeoXFE5YQy9KKoN%)+EeSiee1e? ztJWM*!xdtff1-VxQTlWPm@)rvF?h?E!Cwf>IMJmm4Z1j~B9-z*8&1OiwNL>WH1J8| zf0z7!b;Jt-+z$VJel>Tf2#X8B_%F!=+E2$eUuI%iNv$MszZLw}dp^L8M~m9}mIt*UNcxMa zfxFj4_Y*gIp30!^`pTQbm`atVxwFb~hGUpVXv3$~ZIyMeK;xm-JBqYcvqh`y7lA=O zGrjD_WL0me%iTuVZ&^VzW+wUJrf&l)d0yiP8hA>V$b?w3WaZoGpA-k$pFXl~g8A`PYxv!e_EMurZn0hud0su1 zMIcPc`_)GvK&{|05>6HR6%EY(XMD^Hf1MJthBPNN$&Ba8K6ywm8WFL9pDNsT@j%1) zJV9M>!EN-AgHVT_p&K)7aJnIqcsQEp^J`H8_z47F zMS4uZR|$)2F@e5Wj!dHte4TXaVR@b6iYNjhH|2QB)qY#f^ICorGVf!)MMmn9LNG|M zk`KDN=Ct9SM=>~xlg@tX<^u)34xFBkiu4M!MQmBT?1O{{$rsQv7eI8|rBru>#WR8T z#ivb`WM0NKjB|WjJOzYJff4tP-JU%WTLIuhnpQyA(Q_tIW>VvNQfet#8>47qu?_74 zv{?ffUT1H%J(2g1(Ykwul0jTSC;t{0EWE%+&CB3^L~++)2TK0Ykpl`#A=H(c9&`JG z8>DNzNATko2~Q9QG5>rKx_SEwKFo9mr@}-pf=lHC2<188;&^_@a=D~qa|m=%6(r3e(1y?uDdG^!d;V#q1)siN z(a01`A2~^TIaWF|hi1zJIcoD94&-8G+kGu}-@rY3`Kk=U_8!2UuP2S{Rrs23c!0Wu z$3q!JM~uK_DopAp{sbZfZkU2$TtCSAo7d+kOu>G)=~bQV6rQ*sYm0H`K#g}(zD}tA zsV*Kk!bdY6T12zbp@ zo_ctgr@)(%I{ekRW1P^yY>wNI(xVQ&G2P{q!*bk2R=2bt%Ja@krhNF@s%3id^|O)= z%B#MsjzK|eCV%K08zA|4-bgB+5vf4;aabIe49C2-nW2UODsxtR&2V;Mcn_fA;{|q~ zYiLoUs6&7(T4CjF)-~gPmS6gXM!Cqdn-pjt=~0676ki`h|A}^%lO7*6$_3HjLATs- z4q?q7E^2HB1(@q^d>2A^rlWk?97tDFcMW3``NKa(%CZCx3U}r<(oH>Ix20Gr&bIx! zr@%b1#nR}gH0#K!p+TW>#P`!=h%ylPfHCmXATlLW+jWXx_iUy#G3*gSt$CPp1ovk% z)UT1-ku5LMK`mqCAjko?e(m!#Y0vK;^w(b)zA)|*VdbD|?Y8d|4yIxz>ln7sauWZ! zH@fc#+LGhyw_QF*?@Uxz!^kkW(+c6T-g*j?4NkGgzUK|ezMHC0&F4x}?eYCQnXIHU z-6$U3f(kj$$#o)tN+x%>Mgik|5Lb``*?57w1(EqfQ}b|m0GdM?^+6W6qANaS7bTW` z6!$%lrwU(b@(3JkSQ*m^uUCI2ZDKc^6v74?zVC~m(m?}%Ea@iVQ|Yj_U%zb~4ku(rR`_LC%}KRx z0v)=6!CJ}hlB(c~JGPR#go(ZsBr|K$MdmN@W9QZMrCLks*I;1b$mSoB6GNB%@w?~g zPhT$N{N~PKcxiiLdlqky&2;)7ww}wk#lD~+9FNmDHfumsJ%ciX3q+#%QoL?NHPxXC z{z5F(4NS)@;UVT5czO?XF%~YVEN~o@57x)2b!>gG0|j?8`GK z0LLG+skQ94tc{M{c;EXCEWwvNNPLtN9!A-Y?fRmv;Aszj!6l;6=NTata)^D7I7zGI zuIo%NJx~K9OH`0zxtLT*U#{ZjX#%}R7-Zb1>#jSySHGQ(+D$25a{iKFDvR$8Iz&I< zxCT}YL+KncpBclmySn%bhiszl!A?RFm?c*pI}&z?yVhP>>IFr}g~>N_KB+_2@~i5u z{qYPl_mb2X_jC0f9ZTiYH{T31w_?oC(JgG7!nRwgJaN(>O|jihjX8dZ`(NA0wBg zJll0ACXg?f#pEeL0z!e^GghDorFwRZyTD$?`zlIh@j5p3d~K+~TS-p}Et` zc7T3d^DudFtYA?IJ`AHT8mo%}NHcv;KWMD%yv>OEL#!0bud_9C6UVf54p*3;k~vRu zo_0WPY>VshO$TxztmsU{O06(Cp>ARjQ#I(IROrWP@$N`_)qUFPXb}7w;~y+IIr1S*aPD(r`}~=})ppd&_AEi2e8L%$cM5tn%4RQ@eM9n0 z>@?$#fR|Q5ZwWY?af6vD7))NGnS{wflDjpPX%E(t*Z@{fi>P3o4VAUH%20*ORhh@x-be%9?|e7KTb^%EG7f3EoONvihKD+DPOGHhcpj&6IggAHrp3^U*?d}E>U$ZzRaQ^P6LV(z13}%&1 zDtR=2X(|U)VK0FN#=J}Pg`PbgW`!$r`m*=~xCFHC&0Vl1INB=Y90?Wna`LkHg}E%d z1yu_2?WR^!LDt`I&t_-lZ-7cP2vVfZe&?}GO}FN2LRQm(-ZQ&Umf#3WVt21QsqN!P z?E0Z(Rvm$2tDlZPXimE3a(3$2*iWtH*8CMsrNtmgxi8Ixm;#i38W8iP^Ri^|rFWaxH zBKKk@nWC2NmjuQ?T(8pO5!E8<45-D{+-OU_$AuEdWkoSlkW*g4L)ajW@#UZMtw1*_ zC(3FG1T8&=uG+#6nb52#X_}%&KQo_ktJeDm38!kk_r=*_WZFM{5k-cFfeaLWX%)!% zHhvIx^UIrwT#Q$9XSonX{TKL&)BQ|G+ntRLN-;6^pW{Ukg0R@$Ah~!HLy1zjHj}hW z1KXB2n=?w@J&8JMbvta_61~-(lW;eYmOvY(kwlT2_W(S<6yO(@(!obI$!w~ebU12l z=`B5m?a8@Tu{3o9pewkECx7yhhM z9m`;oo|2^#wM5S{Q9ae|^YB$U(P^cD+n9)i?>={6dmQNS{6J^w9x$I|5O(D=k>#PD z(9GIIZS8XD{YJQnJP}CLT1iXeOnb-9^v=U;V7o@i%*x1v^~p|A8BFs&XMUa}Yt#UL z1n=HrpJ_oo$-NK$dzF=yU4It8!H6m&ub-(ne=Da$49*A7o*=Hc7}uiR3jbO8w`42L}gSR~=KD$F1>g9}2%? zZhZ&R*HwOyC5R4OT3K1=_b0{m!GGbOWpJG>pU)~#k%NCB-Y%m27i8X*AjbHf%{_b5 zI9S)u{Lqub4BFs8Wm_M&=5Kkyn!9~p&VoWAjfZB8^G~s*``;e(!Zy=XR@3g>XW841 zJ{TBIU#2d~G`!w9pL!$hZwXHnC0vlF8!$0jhF#xvB=yorw`@`!2 z0xwXN#9xLVwK(6YY@Ia}f;Dk&+k(0{rTlu zg-PgD)nwQ^fjJ&7L&K@;jM*_6gtVrjdp5?-{j+@bn{Df&!)bZP1X6np8s2Cjs zPLYB+R*p(%$Y#-vzMWc8qx0KB*C7lY!nF#I$((Am%w1p!>eO9-8auvbocH&USbg)S zNKn)LNCdH_gg!%`9??`{xAqO=PrtLxHW!ck^UH7e1x(4-0*h|sk>Ffdvb=RMSx*!8 zxV3ig^3qu#wUf=|x zjB>lDaB-iQXF$}-n<07K?z2RI@VrJ`598GfS~V9K40Ep8R{p~y{OfOldWSNd9OJxH z0&cZo+_R^&HGmcOUx)#A2K*R2Pb~)BekOJrpGh82H7_oN1EJtw2nqQ3Eba~&YbEC9 zs+h~^TxG-cNT^36xYv}`*|YRargHxMosh`p*2iJ)q`uWBFgn^iI=5*x&+Ylm{nfvo z!@UD9)^lE67&wO}7Xr1o2tdq+7w;A#^#K+;QT`P|%luCB%u6%^i z+?hqc!@5W)ZNJh_{lq9QbP^G<>Fi&&uFpFAa$2I_XlrcM-5!yWBs(Q#y1KClSG?Sp zzR*1yIcVZ7ot&whCW}XRpWU+!SIq!pQjwKo;x0Wy?|ZiUJgAN%I)vIh@RTJ<41{}s z_WD!(hnHjG=nRaMIqFOCuhT-)r#2ittvcJpH5Ld(p@Pz^g^^PqGcjDj^LKn0T&=8 zXJ&9O-lw7du7*9IKcCmVP0zdQFwnZ?eBz+NUewI3CSxL=8N(o{-45bx=SRPQ3_`)w zeKgw>0uaUY8si`0OCD?&QE1GAE+F7c3Ji906J3rCDl(zDCv5O#&LwVYt51qC^~eK> zC**(p4&IE$ue8G!Z)UBQ$mr@^xKCRaMsHqh=h7uztS+Mj%+nuj3qR zhLRyjrnX`|>w*TAm~&4Vv&g%ANKO{+%e+}q^rl!Lq5arr?kV|S#%9R(mCvKvTHm{V zoF`cKmUF|QrFgxa(_ag9FpF*axl#Y58X}-SMByB_up&yO%VcqZ67{mgA@pgZK|)+- zXqYU+44E36a{uC-7_C*JX&X^8YOIzouS(IGmX;R9ggmUDCIS+w$5Geq)DfYVq_Q}v}!xEHOy7tpn;EZff_qJto#g*e_G?m%Ecjtn22LYc zXJXN}_WGFwi@}ZwNQ`#$oRthI7w-s#>S?w3Kfz@Ix)aBcn8@lI2f z>ew6oJ!u-gQpNN;YuRy8IV=EpBAQ(UPdXE~-;t*xFUic*z4m|VWXpFWS%Gc%31Epu zJ}T;U_aj6!ueT~zZ!VJb!K4kO`vJJe*7U>u>OHZyILolnx%Ks2D|OHB-mVLVF^ ziFiobr#3}>G%$~i)C$P4WGxfK4;%TMreLSV?=FHWDq*!3jV5L;rW2bPYeTO;YsYfo z6pd9fxbd1OzdEKN>D(Q=q2QSpw&&&^i>@#`gSoB<3*AkM#yZeEV|45M)rmD5f{e)= zI>Vt7M|_^5pm3+2CUQaC0**o)CM5F~0yP&`>V9rnQ_`cuZh46}kW*YqW*mQsV@G({ z&E{MD>P1u&^YG*RZ)M7m!XKPO~&y|PGa zF8|4t!aGEc1h2E~M8%BBks281F>&a9s>*em0Ku~5m_B_jl6wkXa#i`1aPx*E`a1)? z)l9EPhrOhBEk(WEtKQ`K&}h0%OZzW`weUvXrTA-P5|Zn%)#BTDq8@}p{#_HE4I0s7 zjH8oobxNv0?4aAX(q@P|`1f&TEE9%M?fV*wYA z!?%UsjXDbE;c`spd%?E!sK-31htBQZ5(vIxR$|%G*LMADWD>1;MT80BTfOrd+cm=d z;_Cd?cPZ2MIzMXyx<;@?G6&TU zulVvp+FUvan}MN(u9Muv03NuQooVa#McnAJiBGe(VvlkW6C|yvz0>!HB&w;~@h1j& zSc~GL-%B60)Q_Vi6@EqdHVILbbK1Qz{aN00MGgOmN)Xy1Hjh5xOEF%wG#M%_`Eky- zEjeV@^Y)c1K;UYl4VE4#9-|1W@XrX7<%|hz%|rW}ppd-8-rmyRofKU!SVyMQRcq=Q z`h&X;7~bTLHo+q3vVgwwjjv0lpTVBKAiL^Fkp-r8sp{FcVBt_POoqaZn-6Y{ z5)ZE@TXD*@O?t?#L)6*uM+=d9QDnYZJvOlpV9%VEa@5f}RS!0;GFxIds9&xM8!b1f ztJj%5%gF3hR66tBglm^MCAULLcM`YVdU6>jTs^hciPgIv;BqSm)>m;XLtm(%{`gDKCu691@NJjKRSh1{yB$#7vxK+BToeJ z{&QZ`Pgvk{_@C-Q_$yW=?J4&Obl@=^Y2ntAGpG7dpNy{*dOHP<#}#;pm~^3}H^l=y zWn099CU#02W!p_EeOmn0&6UX*pe&^<6eH^}0t=M9jISujisj zV8~0d8^=MSy}bbzYso8 zWzwYAC4Q&HS++gDGaL(_r97g|dwgtUJej%+(w<05 zje%pAe<3ROG4|s7+Mdj{v#kwg!HjA!Jg9`W@cJ(VtmM-%O{PVB4s}0x09f4d=E=ouK+dCy$uOR zi0l4pS6v0oa!=$d$dfdJl0yM&+#BBgc7!yYcONBOAj@Tgk%Xi0@0u3x5lnk@$0gDM z9{j0?8@C`{ojdG>9xN&7Eu%?HS$$ZOt`{_sz(2QfS!nfFMrIIZ5CEb?uIDONHo52PdLWjqDk}&#vLiHXx-`U&nkC?1EBg9p9 zbX))$t8CI+u8EbCXXe%=oBG)mzw~jnNGzr+%N@l{(VB%>XY2_$NRg*UoLS7BqbNXP zA;?*^G3M`qi+3;1RsyC(g%33&H3Y4DQz41+OV2ZFvPS>b7vYs$2snaWtE`&}6J@BX zQ}+5DN^7vg8=?MOt5?Lqa_h>4o=>gU9u$zZ%md~A#!{oHMYhF8&iw6eA*1HZ9+SyF zXj0Y()*{R(7wnypGDAth4o4(oS5SDV-Iu9F#&|-aQaaIL8qEqh}Cy88*P#N z)IHH@blKPK>>AJhVG#q^uP*H&HxA!~EMu+)*os};MsDZ?E1#$1B}9tv#Fqi1l;qmo zW2Rjm6OPEVqujgzo^jY{_Y&zJic}ZDqn%w<(NU}gzpJ9Y_^3WvXp{?*ovB%fp81(y ztyhDQpxCo>ewJQf6uQ@QUH40LUw6KhYE^|NN@r6=QIuhbGppG5x-IL8T^%BpGOVXW zM5RYDA|7wBGSk%yU`zEVZ%lgzCI)p{G(F97=(Au)K)Us&9`2inaj1*h{Lbg|x5t!I zOi;}E8g8wo!zfVzbNc39u97Eh+wGP=KS-G5F)#jgxT9d{QP@k3pGNIDMDs{byrv+m zDQ?1V{kN|L?h7(42+!2*hRB|x*jp57XzUQY$5^oO__ObD`A#)}_rF|?s_*W317D3R z#puG#-{5_X0q~;OXn|@BeNnSR*CdvEodJJXKPWdFHa3ZBmmAzp)xM$8`eqL?LmdF^ z#J$SKp=>VOPn}}UYGD9tGFznTpUnl6qHdyhXbZc|Z@(gBLeWsztQZYkhNgA0nOXS6n%93zbfbt4sN3dMM9#d;{P*4fOKmNmB~h zL=voR2sNYyhTUyCGHREIvd3x3dvWa+s?sOS8NW^Wb1;p836R$Io#-YZ^EdawP1PjY zwj%>@(me6X_fHtarscP%YSm;wTlVv^1x524IEEvwenq1njKvutKi|Mp3{z~VTz*`AY$3l~IB{A`B0>vo_fs^W)hiB9b7b>5|@n!Ig%OMn0 zMEvy?VLYUNAAY79F;j>Ead<`+(E1L)6RA?1Z{=7<;wMg`5fO(hmME^VV}^29=XtOP zUQSD>!w$U?Qum_ucKaEAg~sae_^Eu?LtfAxp`S@b&9NWfr!1Kllori?XMEi->&xCB z-?G@6*E;7Q%y*)jH2~e}{V}Qb^I#4UTieBt;0(t@92*QSk2nUOTd!yIZQ0~Q2#6HK z7JaxL`SToDqAus!>);X36Y(5px+q-4)M4|OugIXQpr`6eylv!=p>!U`5}Zg61Fw!} z|MD}MwEKjF6q?c&Q$I;QLN-h)T*^>BQqAg1(Oufp#ROQ%m z`M&4;$ny5Gl)$%@0&@*8_Ie81iF9p+T1VYGan_?mdipdqR(8Iq`C}ssTJ7NcEISnW z1cS?L#<=95y=PeMj;!c2Lt$+xFPmYOh-LPj))u$>EmHN&>3R?A<~h6XrE|1K$}9f8 zpsO!m11-4S*K}74UWj~OLgVEv0AtyozU=MGm0S!M-ye5W;vS~Lqnqo^V3*W~gs1fo zl>n2Oz&c*wnB<1JG6UGt0tI-=2BClND0w)Xjlm_U#x0jQT8-JHbAfQgm^cZmgsF8j2N&X3616R>=D#;R*IolU#X7JIph0$hSutT;=z zywWr#-Z{9QBLxvrjijoec3!2TCmJ9Sp+>M1|3Lm?h0&yq%LsA`io*}^uE0q-%%V6& zkUbz)Rcylt6EAd%bb{^#X0m&KBpEssXx`=zB%{h&n5~u&`0RacEFvX`!SyO3;i6}l z+FtYkS{}4N?CP4=l+@Wq+K%^Mv$@`Hbl;b^XqFR}=LXu^gvoIA18H>F_%giodHF4L zNv^<8vf%Bn6(t9Z9vJ>jZBBc>NL$9V}mkJ5tp36YpKaHMeN z(rBTK{MD;;;_9&(*kMg;11;fbw2}Isni@jo2{P|d5>iRl5#wrfUy;{K`k-?kog|01 z?3w904F9|xXssaV=7xz{gE_vC+bj;k;^h4F;UDp7upe`vzF;h!n`dC<9gscn{F`aTS^Veb z{ChwxNk9|o`8@ISeW0`-N2MS2j%N;u1L8cfh6f|KCyDE4p^n2Cgyb7WIPfWS&s^AY z0art^$6bS$rr1yrWjJ&?FWf&FqlYgfddOU5tA3mG?l6kJFF&YUhs=a|$S%wEbUasC zvWT{8V6~!4)4>0!fUGE?9kU*?8hRIAH2KyOa}GILU!FY?O$V%8YL8~9 zsTy8TUBS_ED3j^86o(TzaHpeN>pt^fo9&skQt>bWWhF2QtO503hAtv#Hp_oMP@0z< zcIo|wCu(cH>?w1<;IFgJax)^x%iQffFYd2v@s@|WG zkCJ=f6##k`VIyv0&@D!oM%#Zfd%aIyTy4bRgTe@5Ex&QUMnl$>@S~ofIJ*lZ>BgM7 zxt+3kP9;0&Up~U!tsdJIP{HneQG#o}^7(&eeU4T|?(iOWL4bNl1OMb(l}xaldw5^P z{waOg2^_lR4#LX3r(l^_Nu2uC|Lj=2J?}kM?N!QRd&-YqaEr!HY&s7(lmp%5QUzGD zGlpDY&%F`=SDD)IflG^re<9`>WoHE2B>K7MHk{S=BEO9L(NR7X_=?9A?MQ66R>tX%=9GhlvwjVH2$#z&3Rmk8d6Vneq_JHKw$Q(WJR^fs(~P z8A1=)5r}B+8v)|VRXaM7V(jWHqo>|hC85Kptn9t6ELjSo=0*H6%gL1=rKeCIfX6mc zeg7)|OYtryRq$tv)2nFeu{G_qkaJya%4P0wO9!H%5ikAs2FLm_c(#NbdTcxjXIP!5 z`)shqI?TP?lVQb$p)kmU<)P*y-gzcsh~P;<)4@(|d*1Z4ul}(I#6z|}dwcwRZU5@} zCWG74@!|UyLdd+zSJ9r-Eahr)!iZ79Y|+=Fn?YVzJdM6b_vbbWlE;k@3zYbORWZm` zl&;CO*+%GuvXS2M>OekQkI%Qbn5<(OXk=1a0kGGc=l*>?$NZCy>)@zGesA(yy6{?* zuSm4}4fXR^@fS0d)GsH)#u!cfB+@^5jAp>o z_XOGU0B2zyJA9**kQ5V<9~~t9d`qRqHK4# zul(u%Lcqip+G_`K@|j%cs=eJ6p3PU99_NFm3S=kYs4nB}UA?si0IfM>_P8Sj6?>&v z8n9VFZ>+c9Mi_%4A>wL=QRzTBlJ)G+zYt6TVem-Sz$4`j+;(&G`m**qHGpe7iM*C) zqq(~rngNxKelqnFTPGYcMsuL|@X`KR!00yS;K3^hmGd^vIMGJs_DoZ9K#x)rz5#b9 z7_0b`UZ2bj(p{vBSe*5j_GdYlIvJ}1efczn$5id+Mh>SOCS^@}{zcDp`#b(w=@05D zD$}mo--NC6OFdNWO6+s|csOLAW{$-_8GbNdyGw=)ptVT!0mKAN=NT<8@D)@tMh1VD zcXO(s+N6fwrTXVHY(nTcBVCrCrn0kxL$uwb8Vzf;9z>~=TIv^CDEYK=SSFMS76H9} z`I{a$riWZ#3fl;yw5mBzr^_;esB5&tq0a(j=H5OM-vX+Cag4@Rv%Gqix~f$R^faLU zWEXB4Q!c!oXT8`$YbL^_yOqA?FoGDmz~M7^;Kcgfjp$cof1+Dw#{6M=!R%(VrPSOf zbMMNGn+ixk=jh{F#BY_0t$dN|6f&JvJxE?R{f>yAqq(oQJxg*U&GgpE4Lu}>TBav0 zt_nyV*4mW5X5t}UlpoPSlPXnPLuX?vmnczEGr){?oIgik)6rds4r!*>()24;nU=CE z?WAcq-A`My>7x>wFGT+HtA}6QL1^egcuQ#EegB`YUx04EqD-5+eAws`)8Oetxu6VD zATqM%E$1n1EhhYKs0nOg)2XAsb8tlUQ_ZgB2Dst=r%9R z#g!r+Jn&(XE<0}V0{2f$aGpN}WPC2AzcmZN7?8?vY_Uu*1_h_~(cli@Abnw|5WO@1 zsX~h1OYRFPgq@ao_)ZpiE=)NuSgL1W640<4_LW&I<1YMkqcu`V3_gQP4Kg~|=8T}) zEFvHr;>tq#umiV*n0NJ+*q=V(1n`6$5czF^3H|3a*7yQg=_6gVV~~{2`wWLh^x~=~ zllQ&tgV}j^e+TjV%9srQv`_Ly(D9^AIV)8_VnaC z=%ME;&Lj`D<~?Hs*M0vNB0*kyN^&(_{X?aOqkU_a;P*r96bWS8mqYffG#dg*hR1Aj zHp5@`_e#)rIpg1Nk$Hc2a>BSL1!t{hyA|ItM~S#lD4s`rPyv^{9x`JWP$}ze3TL)y zcKdm?QqsSM5mY+p`pjYmE_0)Nu3iCS4azxp;(-GkyK9CHOY)UjyyP%!<~4FyDJ9cB zVS)tKbV<51Btgo=XPhwkt(SpEda3<8@^0(hlKB?%_=h9c7!>>ry!MY-lG*rebbZBI zDW*Q1Q^G<9rxT_8sv1M(4Cv(*B!xt9?AAj<03l~|0qssx-r(CW2`4-a9}yB-KNqLy zQI=CCsR$Bq&O%SJH&)RYmOsr8(!9~^O_-!38tn0h44MA>GhS} ze^V1$0C%F}C3eqVev#nilM>tNZZX~12HSLAJK3HH-D5T0Cq0KH0dFbW!QWvqH74FA z9HjS(@FqgL{3Tzk$~eOb?4>ZX`u5Nm=)a1fZlUE!7{IXfp&}bBj!bzaOMwl6LeQ^P zCXWeK4|vc-o7On0x>JjKp3<`C`EC(+aL#>_Z#I?l$Rlpivmq@oRpdS=2AZ7W?o?A1 z0BaKTILBHZLe{i^jXkHX2wErH(vE^m7ITCshFm6Cm8q5-&M-t){^32IkqC2%g;jYh zsbvS<(9Rw~_a=b+Vn%_xqAkQ5+oPHnkr6#AJdYJK)-RC2Qc6}eGpKZUbIIDvUReA1 z8GQP<{^+jb;rsEo&$Ib2LymbL(WwBQ)R>jsWq@t&STofBT#uAPuX$r{EA%| za^AFBmUmiD<;$gnr8w(;rwOiT=a*Yn_ca$5<{A1;zPiLU(F)(3Cw#ZGD201vhRv>qhy@w337Fpt`UK6D zb~XDSiZ?>4Z@^iu3f7$WrJM|VxgmRxBRWda<_c?_iI;)7vGLqtJ3!&v@364cDMOkQ zR|d2qSqAf{uX3p&B&|RXv>)6=sRQ}SUXo0J&bPh(? zy#@|xRLMy7`OK9oG!ZLKQ10Fh0?>DS_n@*6^O#=ZP`(3-JTo;#4kPO( z9#@e?(+%vc9PUm}@z8I!tl<(qYP-1lD{m>!KK5P)0?B+lO7DZlm`XL2T z+J*O2Pn!42|AuO}=M}hP1T|jKA%QI_8m;*RJ(3n)n0I;nQ*q!5QhsMX)qH2lM$5S2 zWc~3yj4f9_q`LwU#a4P5=zJW49$gY5XT8}zRPhRMu3f9kMC!0R40bso-pu`mVOK|p z8dX40e3#0=6wv5$?D&>xtzL*2=O~fS*6}Lw!xz2F+Ru`VRiDKU`v7A_6yfZoamnP3 zhDcxIWinMS`v-J_uB6A@Cjtv;SY6lJDv1XK^m1ZOM`jniN=L`bbkB6#-h1L>;+zGQ z;%WFTwDQD7C=wjZ%~^*B{s^C1;RR}zMcEG0SxgI3=$8zs9DeD5WLqD!I@$NwuJhRu z1U~E2CH~U?NM#VK`NOkpqRx1_nKYl5WQ34>t7P&t{DJG4o%#@3f1W<`xFcxC9#PJ+DZxPa40pWCJKg7!F4a2Aiqr^@ z&mfzHa6;$4O)Fc8^Z~_AFxX3z-`5uKcB*TQyc=opq^$-`+9z|}?|v6-qIeBb09=*p z!}_3n&c{jNgKbfvt_g`@`1o>6Bgi9{aA`m`B)fv+8l{i;AaR1B7#p^{JGF4iX5SZ; z+{G3df>sK($6}_cb4Y8PQCn5qx0aj^nT4?ph_CTM-m*>ki=6r6=VXgPobrIa=YN);Ki|I!&2ywN+k$%`PKz8XM zR9vYx6pw@C~A1D*`7Sa*VGGm;+d#;h6Xx^0qxK)qc*7Dv9tM%1TjuE8b0BqZI!%8mnbz0>4)Dp%;^E>2G?<>y?8U3hn2% zMOPfSix0z|*t?0d-x7&MXA&)3r9(=?*nW)%RI#};qHCskq(AQfv19WL3RTk+e`1e& z`=6Enf~bbtb(V#!iQVJ#0r7eUM#ovEU9Qo~07lD!!gk@|*N<6mL-Z_ZXV{Lxc$8DA ziAezoN}P_4#ZupnKH@k_zqa`xYYR1WLQn?`waXv%tS6g+|%gwQ6LupCkOOB}kAPH9ca!&wi8s3Zw-I8Cv8O6_fYqy6#o*8Hvs;kES$)QOLmS7pkhr9Mc6>8Ix z)Cq#UgQMWJ>2D>+15qGD!i(zR*}NGiFp1pvT%CTDj~N(tyA|U zcE->@D_nD7hPte9_S>!lA$;@|fw`Ufdc!w)tdyclzdfy|;;h*+7j97(W*BDlsLyrp z;OG{9T61%GlZtFlGomnxWov+HGar+t-$D-6MhZ(%YEs?w#lPW#y-%ilDXI05gYl6m zA%)`p@`{zJs?pz^o4g8Hyokr78PQdx@ir9N1edt`)1o0-2g9PwWNdrN5{judCsE*g zC8Z67UNVb%Y$aX&G?>OP>hzSIy|~hOMj_KMAGlzamt8kJy^X!8#hIJtzu5hA(U%+< z3TeY9&ulD)ScFg-p40%G;}nR8>U9Lp_^{q>Ylhof=$Wzq5Gz}MU{!-XWEwGe)M2aQ z17|TbOlBa;rKx<7oB_Lr@!ZG zg_z;d_T*Ux({-XM|=?nq9Z z{$&pB;R(2IUa%Z-NuzXLgoV+9l4vWDHi-8%H!Hi>1{sG>fN(lx6gfUM4lU#sdNKX8 z9lDFy-d?cer5jJ?mxBTJ?5)-49JS2P?S4Lkr9B^_Bj!iS1(8j@nyUSStOZ@HFBgcP zXfCE%cjCSiX&Ij1^Y@8CaW;`k95QD65P7P_Jg}JwC}o~0H9JkL4^RG-iJCH>03a@@ z@m1R8OMg%QUiPA+WL^SA+4Rjdz5M(WvdHjD*c_y**O|=*-dpLh@=aMn9HSbH0iN5J zn!G+4>GbG^jlHYGwuM%7drfnTIQ|9XSv>yMY$5+IpH}KjPtg$;8Y~%rl`nJKmw_iP zL(FO>K|A(SU-YT#YyBT*)37<=z$_4avsO5)a~Qw7;iWvU4kCJ}_tPdA(s~7)*NY6R()@g|mKDrvK}d@xwLK zdW~brY^r`6oNDr#u&nWvW(NjdUSOipZXjXIy!)+3f$}KIYH4>&w1eMy-3K`)9Zk^; zORco;wmAu_5YlDV%RXn`N1!r^+1DrF~1Z^;@fM7NaG|OYho0f>44Dg4Z}V z#^-Q9>l#{duzQcAcsK^susX!ZzF36uQTc>kQAgg1HudNmbyt-}h?DlwwU; zeL3P!!eQ`c5ATTu}~i z^{}(c*1jBO67+;vLn3~;u5zWnr5@Di#Qx{>ZXG@ zQ6UUpoh3OM#Hp9JTo5r}(9v&@*H;;Wk5GG2{a7P&FV%K@ugAd!SiNdjqOeso=uBeD zK>um!-D{{YSb(|zGR!WXv9pBopkx=S*oSA+J-W3V3XRUR+F(%L(y}Fl!X&f(RLW5dOxnH+c9lcs@IIQZUIeu}dadLFNF0U5SdZ}1LmQnq% zZEog%XjwXbfrk83bV#rdSNtn(k=w@lBF`@XB8bDK)4jD zX!b7zk`p^U=(-{cYwJblb^`FcXvOnsu%jIJ?fmI=1R~*1u|M@Nnk$TDE?GH7I=Pl3 zocA`{3(UjNR4MhR-YLc}VZ})+IceQ-$Fuy%s6o`4E9lffCMbFa{40GRQueZI?l+Z6 z57~^gyndxwTC*qxhKErLAK@~+(e&JqmD}D1JG_XU(ZRxo(r;?&bu?C=aGt*G+89XK3i&9cOqDM0&*<1Mw{vD`_I z2b(p2Mc|f9ftbvIH-$jVxx`JsSSv{tRj`=Lqkb{=$&5{xg!TF`Bw!&-_`71KK;nU5 zF!kXb4`8C%pW*Odd4eO@|+h_rJ1C^#Dl0f115fuF;( znj`@VbCCI*VH5q6kYcW->G&9)b!}pqSg&j`yD~WvAM$eNA)27!Ga39}5Hy8puqv8I z8k{@dFR(r*pPJeDV3R^&f1r@lYVX-{zFX=ps}qm>!6{{CKa8l;(raus+so@A$webv zw#*B)54$_=wGXl`c6RDW3_^oM-mm~R{{^8Rj%*M-?0+JYSe97_*(P87IuXt%iahpX z7`?acBR_hjyB&0QUGPq_A&Tm!XOq@8JFMx9dU7oo_aj9+oe}WeOz`)SpM34W;ooJu z?cmZ`!=W+*m2bRjt|^Q*V!QJD4{aeOCa5f(O_4}AG~Xm{UYE+a2J%CPC%Xp~(cSKD z=$s@iEC%nIa3&vd1??8u!ddo8cg|@p8s@IrK-ahKLG)Pyi!bE?bNp&Z*^GcbeW>j} zyeTdd$`V8O+l&%~G^gR%K_rCXg{pkQ`efi~OZo-j}4WKdHmMe?E zAa02UXqR5A42(TeyLtAS9(@;eOs)0-Put{uHB1-EZ@uTt;o#6XYnz@R?=P;W{FKM- zy<)=r*$+xb^ihjm$a}C;v0l76TR*a&{!(Sl9)7ox?Eu28_FiH+zH^n{q(jZd!)0ab zTfrd^^nGs7n-G9(j^m)NHsCgQaJN6SNrspoyuZS#BCmGwDGaRl^9aKLx%vA6ia@z* ze)1QB6pz`BcWdTTR@Lo#!ppA&;<2p{{$+)(ix;$hvCNiL&Np)&vC}_a1e?HQ>TXxl z78ObxXcr&9?0;=GMWAkl{}CixQdRbQ?NJ8w-)0du&)%kvfl;z3nYi_wdM$8S)Q^>K z!9X%#^MAKT`RH$=(TF#JP;7!*BC2K&wkERf?MH(Exg~4CoGxBK9E~8HNF4vGe-amh zoR9v#DS^wJ0%7MofJvn{9iqj1xBHsKyOcP!X-EH1_fFEH4%KMArG$5swv^0@xJA-b zbP$(WGCjW$c~rpYPvHvJ~9X`IiXZ+xst^)38UlwH45ed=pG5F@~PKOU*X| z=oe&VgCFtEE>US?qA0A#FKJG=))#P}%bA4mh^95J4vc0E9oq0n6sLn#5Q{2XwSVod z$Ffsh5WX0^HvFl0dUz+jVdiWTck%MsO}lR z_j+8APO8o@K2SK>_!k()Tg=Yuwi-YB>qssVs_OE?6kqygZZoQCwLX-T@w1_IRYCd` zr_DDAxXjv2`;0yF3EPmOq4wF3E5UHfVNsXuFuB%s>MKU^?M8h#3~a-K<5z-@5kP(J zAM>~W5R3&p?+x_O+CK&Wb*Wby(+`5+bjWhB!t3fs3!pmp{QnVbAExhF!6cSo5Ba$# z|LNhx6#byzWt!(B6j1(8?f-3W`Y^RSPrLXu|8Daagtp+)^h4u+N>A+XD6duCqHkaf zNJHM9v;W%O>+0N-a`~nC8xH{7um5cXmh6W+$Q1M)1pk=6fnEF$xBo@grc(Gk_YdXz zlk)#ioJ#G;{X_8{ircVs%G&{EvOT{Ya~6;~Nm=ggdsZ0`(hMvKY8>Ku4w!oa0rm*i zwlNvn3dLFzn@-t2Ji0nMg~(%|O6g3KE6?I~c4jubt?YMk(-ktL1y8$nSWba1)e=4! zKiJH^N=_*y%8DrQW_wS_4|#x?l!lYW(>4lzFUrjN;hw1WhAfA-?1=X?M3V;a@7~U2 zLl^s5-*+6IhA!`VQa2t5elwgOv#?8I-m*l(CGq^UenogB6h$iW)bCr49an&S^X%XbQHUZ&*XaB zX-@mrN~-|fe|r>F^pO^C_xQl*tW3fOpXe?~=U+?La=*>LpML!9NN`=$#ScZeC`a=n zSX6!q379nG{`bxKr@W1o?DX!Av_)8{xbMwO%We$I;67$EJGpd^f83vXC;o?rzuSp@ zoG&0lk;}O32YS!HN8}_tgtxO{$JPI<2|zd5MM;Pc+id+Z#_@+5OlQJs^>g84*2i}` z_vYG6hNu(zz+}@b74TZr-!;@K*UBnw-O&tekvKpHXeynJE(+iI?x^+ft2AN-pv``3 zl9vDhouA#(Y)T3SH1!d;djlwy5x*%m+Gsy3+>d?(!7VwrOCaVLV;!ofq7aBvE=tEl z%S#ogkeo3Y2KDOCW?57Bn-r$^?x5m;8N)I0i)`v_dDn5Og;4+aIX461LSE4=2$Qn1 zp@U?+npt;PRH<(s-tC8;1zRfb?LP*s;3#(JHrQCg)~5GJUg-G`T~=6|RP(j=;4u-t zTPmovrP}VR2a||*j`0d}+zIG$-#?(?=hz5n*mp7f94wK&C$ozhxEbMQq8Z}bOX%%?r3 zq*HW~Q%_{6{Td{O>pKDmzy zO9kaqaO$VXpiLT`65`mHw)@isXTRpCIUp9chAaGQT{`L=qfxUBPfGjTF27BN7C=OLsbGOVY>!o9AhjT4vPCS?*y$3?-` z5^xfD;Gc}y`ACIzkf!8b_LHI*c;u6Moz#VE&T2h!uQ)bZsm?Us{EHz*OS6{?Hrq!qH$BH#WA<11 zJL;E2(D;W7d2D&BA7ZIQ%NK|rHHtomsPeOoB)dk_eXwU}s2VuT;uW0P3 z4d{Zdj49K1R5{*-jx0FH#k?ybLJ&FzQI_qp3&Jn=8VK6*hfh%NeY;|(OV#Ex*VVD3XllF|oB9y$J<=S7!3i6} zE!HfAJts?;-qOma_)xxv^&!FEz|?mDm$`bEVmLTSDD4gRhD@d+4C0%u%Hla%#nm`7 zec;f2ZPJ?L@Y$;p6e5arM>Hr)Eh)Z>4yl>GsZE0NjzX_wXqmzEZBCXKBR|H(9PIWk zB`#&^KitDPR)F~SuX)}k_WR@RZ4j%1V=^DXSnyYn+g}ju$WHn_cbzQ8azg`$I*syD z(SauH=PYP5Ye~TUSo;WA7l%HM@6%}@q0PDEq0>PUi%d#zKtkznfe+xcxE+H^6~tPC83?S*YUa+*xU$#}Z=XBzL<8z8 zhsyMSZ&tQ0(sR3i;%Uqkf2ZuD`@uu^?ClaF6^dEa_^VeVge^!oAP8GTQWq$!?iZJi z(zL7Lvoxc*ie8_MQM-sS8<4B|KL& zSGu%EPSh&;Hm|;vFYtqZABL|oPI+wV8445Ve8Yvpy81m=OKN81ep_!>jA`=m)j1#3 zPkMya1#Eg%Opp2D``ddeQ4Hr4ntU702Kl8w-}m({TuR19MzDWPj{_X_^-EO2y+sOt zFr^M1;StzVb(hdfbCO^o%cF>R)~f^0u>ozki*SWA&Bo?FArbSmR^<65J);Br)jKJQ zRhU|&oAy|t;Em}*r%q^#WzT%utvr3Bi};|_Rp>eObUjngBA|5EHDp>J;L=-|g}Vh5ROAD8QFIT(IMjD}@F( zt6y>2{cu=r=D7qA7ECNxa&=^mzo%O110r!xYT!oV$!MgePriA;z;tT;joNrBQ2(qt z!Vn{wmF(A0*h%D;IlIL7?0bCdGu{92j(5}UbU69kaPHJ?>NT|gePYA)^Sd|>7#zoq zz5Q>DoG-1ocJYu03E7|Spuew7w)x#juHUPWwF7_i-!xCu%+Pl3 z6?A7)s&#A}`3g|qxQfcdz&min3mS2~^x@xv>Pq)P)1|AJKCmhdh-Uy6G&`~f2w8jk z3-&F0!LHYuZI9RFWBIH~@ekf9Foq*9I0yu6D)Lc&2{vXw*@xqNS-W##)h`fUgIkPc z1cBGEUG5@Etx-Iym%iA0&=DQ0>&G4C@p7!}G^7`pu!PI{_A%6Vf40=3u54!xqmsXH-dW{gKjp`Pju>ng$@J4jy(-SAY1(CFpMJv+g6T zVIX*^O4r;XPct^7B4Jh>jX(c576QXbA5}AD`Wy#=Tyq28ru%&l*8wqicfFo^glCn= zq9hC-2HrZ#&jzk4_|<-O z7HOn_Uzy;tH4keW(4}1`cI*`qb9?R;>oSR-9Wv3{$y2H?Dj*GMdGAgT_UYfP9`E$r zU2l5?CT}W}-r-@bbV)~nnN)zOFZ||@+gk`%o+nQ^C^XFBSH9qFGzf1CAp2gt4)Qal zn?m}J0(?-pQ?pQE(g|>w^1I@4$uY~>ICO?OJU*9(tGtCcGvXaf=?kJI;=DNpjp^Ql zg0~f`ZoML%C6BU~XyE1#HT`#b#ZpWGZ9>Jx_H-UY-*32NeMidJS|3;#C|6(8mPy<1pWmfQaxOD&o8koFpn>;gW*mV zifPBHqv^mSP1>+*a~q)WE?n*=^K*WWlZlXotP%|%%52G04{6HRdyZ5Ll71fne;pMZ zK8#lNlHSc;F^_h2E-V;)8X#XlV!I%3ZI5v;oN2Qp>kM<-Jdf>bn}@yemLaZ z#>p9luKqOFbUMajZQsZqx6>JF@#7@K0ba@-G_Os{GJyYf*y&Sv{F2gOTym#&(z-A$ zNkKZ&QUlPLe#!*==1XjcnrBerdLNDiAcf?qU!@%|Y+Ugtc0J17t@2Hq{6p-CZE^9t zt9fs1dz9<&#r{8N{6qO4Vk<+BC2#FIU#!Vhcfyt)7@CLL^H271gL}^SyxuB+8g>pW z{o~^QwHQ6tI!xu$Yx9pb|1ZUY_l6Z)wG#9H?AQNw7ydn*f0%(sX1bv%6S)jp4<@2* z67B7G31{wR5gxUavz-)=hnYr~HXqW~(x9XVLh$L%n|KpNX;(dViZ#-{*ba|*o2Sjf zs)j^bc*0K6BL?0$jS{aO!$P8|=UK_7?3{LF(ir;39i;wJd=2U6vWf?C;e#~2PNvV= z!MNEQgJpG#9jSPW@-Wp>E&4i_nFFL^?@Ie1tS4nZ*yC@I<9~>%E8bEW=>MlX|4{lLqHb7IdES5X^lzpA_dEZ+<^SRI z9}53}z5IV0)jvA$-$k%Pk&MxIqGYF>Q0DrD;^Z}yA$p)U`VxkzOtbGY^XOR2c|I%b zQmlLvfNe8s>%=`qD*08MP8!EY{271w>U{0H6H05Y1(u~?-#PLP_%H*|7336Oi|%2P z#dz5`--Kse;cx(9ZqaZ`8-Heo1ns(zh7y!c_nlI~W%2^lr{e`L(LdgT;0R=(+XMv< zdPbNVpF>#A;Lz`ttOWsjny(o_@(Za@{gqVdDN*kpqW+zykeZk$Ku6s6FN}8?#)p4I zijyZ-QL-HBuEl^8gwsK|L)G8>?rc1el8TeB=3akN@GF}5pmzcep;`~^0wSJ$^`YKZv%V@z2 zs?(utBR4v3zm7QRpQj4-8k?T7!@4f`_xJ<_KYdR5AkUfU4gHFGfC^hY&`E>Cfe|eX zw;@Vm#4hQ`tW3r_tXWp4N(<_1WH=(Ff#M?fF*2Wa8DJw!=kN@kLqnBfsgP{sMj3=N zbffh(bYvlF%fg4zM-{f49JN5{ZI=+_C{{(YQqw_B(F{I`7x;kz@9Cv3N#4CgJY*xY z+a4e*<~_;6SEW8%q~l>4IN4>b-eBcGNvxS-b_Z*KyB11$_T?`Kaz&Qr@n7vG=R}N* zZZa>gBWe3xZ3_*Yuf@$|%4j)!gPi+Aotk$rvknCYwh-PzLz0wWTqac7E%U?Be0~iA zok$=HGHJrD%(BMPzH>P|!!Yj;|C8bQ=#G(>{K$f#lq{K)qY*(mdW*^ybi|=(>DlmK zz%Fi-r4iJRiGdk#6~vfO@qo;|1-pX0h}&lj?GWje6XuHh)UP3*I)5brWs;w$&S~Wt zR0XbUvtgB&Flh8EoI}81^*{O?%UxX}yG3~~`t+URN~E2VaNLZ3Nvx>K0p1&j%5>5S@C!KC_AYI~fr z81vPshGm;>Ov%uPSkrYUYT8w$b>=iQA`zuH%lSV9)tI79i|-O!17l#_$Q6D&u*0(x z>zCgUKBqe4h?2oY0Lu$!RRlft^TX7t*_(rMmwJWq9=Y|ieZ+)5g9g`(InQSb&8N(L zMY$Y?v}}<5-UJd7lCYdwhx=;j%IP;gFAzm*n%vMEk1+wNrWC#3_cr{T>tCiD#Xd}R z1nfc6R3h9I zSoMl8F#ef^Lu2G?Tr{vN+3yK@JXir%K*||;V%3GDWRH|OGDkpYXmzOjvQ%vB);Xq&x!Kt?`MO86^ z$hccnJ26qHNMi=w3eiKtX9k%KDO?s!@+^6pm}6GW5aU4QBQ4UVf%n5y*UH^9ZR9cw z{^Ek0VFxB^)_k)+ZNqjJx6mr8u-3C|BulPj9*W1Qw}dy)r0*h5C90dh zHzSJm&sUQmNV?Wx`NJYy-WEhP7j#SnoD*v#;fx&-#b4hz-;1i-g6HE$-g`!qm)y}R zm~_^93D&R42BXN!_GE)U7ktXS33MQ#n)(Yuu`Qc_Gdz>bR@VNUzWtoGL4+hBMiiyp zMOwphafSFXsai*BU%z~O6|c*$^&S&oFn>TgUqzbO`t875k@k-^yTAn2l^K0@6GGvDX3O=^6`33R!ow+O~@rgj!u zFbDix9_qBQ+D3FLPjZEuPnQ>%zcw0os8uIVe?!djUU18K zU>CI!7h1RQH$?NNS9p{Lh=MaF)|!qG;aQ=kH5#I|jwCa)tdcgM#sp!(PozS7ZW{Nu z1v3<6UJloVT}=2uLi5bCYnyuBAC(GX*oJCGra1GMbn-W`MKLew9Qdl9q@se~ zBy$z%yU3^EEdCW^)jr@~5YX?zK`HZGpRQmPw7z!Ftqu*h1uGK|{q#&NFl-HP5!o9- zl?xoGNvJt9V5Bp|=F|#9>n#286r@3-cg!Rr7i5V#<( zpZ_$xdbIvVGz61f(%~9)OSXTm%~8FS`Z5v8A}}V0_RXdK(g=|=^l>cwZZI_uc1WG zF0J+iU!Na2o_CmiW{lp06mgN9pq;HxJ;CFsYSdi~v!7D`>3+J5;jS3k7N>UiTF+Ed z0LHwJe4T#P0Q3#Kc424w&G?XQ_`#pDzcFYpn^$qpxf)ISN$Q@(swplx^uqIev8GKs z{4O*EX>CtRZ7P;Mo}--%Mz=6^4=jYqd6}6`Pr^w}8tExpyQJV&YPTN^&kBxR})sjqx^lr z0I@in(8vfw%ZzDyi8M)La!IGOaV`Ai5)>ie{1Ca3OU~J0MK<#6S5M_2LV934o@>f` zAKf3f?=1Cd>eF0mME&yuQ)Lp1`YA$(Ls0Q*Y=N(YhB8S=V=>go`)~I#0n1{ zWA2sue79~Qnji4je#~YZ%R?17z~!mjG?F&5yr&qdj{+i#_j0n=dd45{Z44}z4_?i&yQYP zqwRA%a0qOhuyh;;lu?ukjs zf13aL&VP7h&ZNOf@`8Pwi|mh5EYmw^1dfhM*{M{_1a3&N6;4(WBSO_JjJ0vSiWs)8 zY5$Jy65DI(-g_$Xqfy=HPvRT3`osK`f}^qLZxG0;B2M^ba56N!-5x`E_g>QMCds3( z9}3(TjM4KJV?M-};8 zWI1>Uxtu|*B*+_XbH9S>1!bqjDlp6B?pZ@z5f_$xot+P--aNiuU@Hum^q#B}DPKHg zC{*rTwOrD)x3e(2J13sH$dNX~eZMOZ1-wz7=w{(P2{mx7~f z^cYpeDCV{}5MejVdUvZy=m{rBBFK;0*nI7*m z9_v5It(Sn^zPTTf@^fpmn7IpAbJCg+Kw>DbCTvO+SOu5NOekFGn(suVS}a)?`Z3Kj9jMj*eZJ<9CAXsz0$k?oav`R~ zlTWdbT%p_bPa6|VcE zq`ZoeQpV2HsNuQOJL_m8&shVr)vkh<%pmD;g^pq<`-f<7r5l}9UXp9v;DS#fT&3!L z_Gi*Os6(B@zdl>+Cx+WpvDqRYDSz7CMpb9I=>9!~dm1t`38UQ_-WLbaiyf<&j$ZVw zcvL;=9a9&K3L$vv2M|yAy?OrnfI2-0f-4;2 z`fQb;F*~b>!feET9mczW%1a90Q(~YSw5xQ&4kfr@yfPYS9%(zrttJ=djj4s@7TATn zq}iOj;NOWYP*?h3`2L65RA&em){G#^7P4oCaW*FDlO5a*9w|158FU+@yM}FTI_K#1 zREDC{<0;ce5d)6uU?dy`jd~96h^ld$LEoTZ@*V8-bnexZ;d&YeES>!h=Pm~@ns^CO z3QdEA;?E>6Pt=|Q$AZu~q&!n%1?5*N{D%iSPLcCD*eI!HzE;*|Qsv9+7xn7SKB7fn zU*0qh4duA;(}ZA`$A<_0X1BS_>+ir+ZeMi<3}c24A$<%yX3fo)$tKW#kRXpHuAZOM z7#d>Q#XQ{cw#7dDnjQ!57CX_9*&H7Xkfmk&Bb8Vj^SLDbQhx z6E7646%(jglc%~1UE)tt2lwCQl&DyU8@Dhs3HhkePh{azw=n*kJv=1C6#$pek~;_Z zqG!KRdR?qdFBw<^;4z)SA8!pNY{%d>e^O=FtxhA!47VW2uc#W1zZ z(AdQuj#1m!wnnpMd(S^t>{+oQZDIwG58cKT%8^Di+bE-62~pJ6*ANN~=Nu4rk4eCS z>`B(jvpsqGN~~`zY{v|CUh+D!Lf#VGB!yX1>9~i;vJ>-dCUE4iS{F#UI7jMBDUc?OmTkN!yAnPi)(^>=5A2m3Lk=QdhvDg% zeG*~u56mcIe7ktk-JnJ8R?NlHK9MnATXc+Pj7|k`QS&5bPwMn-QUMqDiARX1rYbv< zNmh3pHw1TV;4CYp&JF#hMOGRP=Xbyhjp5dl!-v7?*{EdbQKqec@^|bp`~B)|%Mud} zV*C`?o+6w+d&N(L1c!9rERqNbfZrEP&)3+Ekf16Na{Hx#2NZTjcUiHs5e@;as7XeHG>e2Dt1c%u(CYwaisuM(4fc@vHC# zJnk=^q5)`Y-N@6Ia4lPDX#Z1Kk9UhT(;hZ)0fuzd-}sh5C}%KVV?q_Ps)yr;K>!q^ z3<;Em6XJnx#|;+BzUjRTKyh)TLXWJ1HQ(A>s9mwsN~vscO`{l)O`t?ky7-cYE)a>? zEn=q0-xH6Z*mK;gzh{y$TYmWvx^xH`L}fRwqghZqy@%|@Z)jCED0Q{=Wn$HJUFqge zgS?Z<5QEq4!gq7Eyr<+UNNGa3H~P+FE}G#!%1-#gszW3eT7uZ#bB`@YY=_;jM@%B3 z7pCAL*02ot34E2Q(eVqG!MqC9ZrRy-#ux zVXNwmsVHC8)GrvN8mP08GzGN1G1~x02fEjfiTUvH32iaq;FGpgxEom%XzCf+CXsFL zE5-=j5(U3FC4P+dPdBL5aEFuSRAwn3iLzP9hR#{%9h4^Q&U-q}a|FrP8oJV5xj&bWnBF<4z{fy%5n2@f3&%?>_D9 zp$}qOv*_w{*3!c+!e=_`maz}w{Je`qm1ky!g#%8kK2g77yz?v$h6wxx0kjw`ORf8y zA>dqqaNe~s43ADH3BBI2FNThgo^piauy*=bf_YZW#lgJ)TlBbr%Q6#-A$Y34%bIIFOAk(CigNf8)A zCy`L;v=Gx~U~`xGWr?-EZgzc1MaW#BkeUgW&ssaJcR7vmgGyY9MG6uR;+s}Nn!jFZ zjw_NbU0C5964qBm+lCB>>#fN$nYUkV(iN}6({u&gRf@}hq6x@<_Zd?=IK)IQ2+zQw zDq`U7Y;I$Bl_@A*#@RnfT*g&=8$RJzp%fCx;mWsw>I2j4d?n;nMn)yDiSox zFut1A(k_xgl*2z5_h@XQfexK+Ad z$XV20qBuQp*@Nvx{__OPY1c|M#Y-6a7s5_k$u|tLG26d-=Lvg+YFg-omA14I5nQqL*rBw`t}PC(bxJQO84Lj$&eO*`{_v>DA*{!~(%{du%!W z(tB)Tb>$LiberK6Kn!wmy#QVEaFZjFIMJXv#|3d2@JHKzBMRaNt?1WtXk2Da;u6l# z5{Jck#fo~HNt;h*d+um`EIYz;D04St5+bYuYDw7A< zhWs-7=iH8Cjlu4DV1X4RMHn`@*@>GXNMagZcW9|V%UezLdm^(?Bi#mtGCrDQ@-2dW zC4R!@%XYfn$ZZziBs{40g0H*!AJ`wdT9~u*87yPXu+up%(M6|+tn!u-Me<>LYZJ(O z+wZJKI-5i1e0Tx`vClN%BAe!268BdmaRu1cgWA!$4P%X_$G z!QSD>+WU|l2F8#D0Hx~`+l^c;V5E&#k?GTpB}9KhO|T6)^8%G(S%4=?A&?BLcAjE_ zf~Y1+yt#xS@*4qqw6X?Y*yF252eKp!RVY_wg?h@Sy}xk38Ci57iPpdh^^2OkuUdZ5 z>)93_iSWbpkpAI+U!(fQ{s?1IW*oLwNsb?HNFdl1ZVHuY^k2n4U=WsJuJE4LJ^70D zbWPzJ+|VM*6U=y^aPcdAH7JuQsHRw(P{Rh@VydylP7w?VRRK^yW9W7Rzf)MV`&H+n%F-etjlh{g@jm13f$QVrCeB^%w9GqFc# zP(zY&oJ`^Hu!gR5l>)(^q!nTy5zmxW*)|=W&`7E?UjcAZ-$GPrP*|i`l+{e15~Alv zFFTi4O~A6@+`QuuE>1TJiKCaSWy|O}geDx@a3~rG#~!iB%d#z9!K1XTjlf5~w> zQzb-(pke{5nPcIF^`;N2}K`b#~oUR>e2kTCfxeZICM0jC6q+NTi?*_LdjAk}Rg- zKx6ARS}0AuL#jgrR15-Ch05e>3~?F>Tyi>(Z)oE+N$Fm>mWxhq#LlMFtTTheOV~a&upy)QfkrXaK(upwW0EZ!?#!3bFGX>$XM9@ssl^od@&UdT&IZK&3G+QOo}(-Eb5o!=3}eOA7sysY#!AtCYi~(eS(dIzMy@h4lMD zewP#ddH$UB9>xqsR1eDnWy-YN?a}`9s7#M3Zga8G@l_b6WtiAB!_puz(F9m^h$i~Q zeS!9VhxLZB8tKt};IFm_t2IHH zMX{(4_FD*>%v6j^mW~EAv20rdD-S49b-1-qhD!OOVNPWVZ!VK-3)N zxm+7>Sg;8Khc6KlLyMb^*&mIlh|ok}#B?GG;$}i66hg}ln%o^RQZhYYTiFSyg5fD6 zG$2$Zf;8Qe0~nbdAS=jVg}IcD=)|ITVTsX;&Z1llm$agK<6+$kyu(nTj4^#gx-Wcs z8D=%a%M{-i5$v6h^EUmz=J2I|GmD+-WksljLsFpfTq13Om$*Oq3-LT>jPaf`#(2*e z<2+}K@t!lrc+VN*JZF!@AKAbDYe~AlUBbVaL12H2#Lo)_H2`*6#YlS@=%rT@#ZFL_ zeV80*&8o~+B~WyLxTLuhFYCm$pDvmOQ3dI>U`@qg^3+zy>t8rdqUVCIq)QQf9<^SO z(#kI!5|4*mOnCN0wqed-6|inL!&vh$-mvf-u$)haA$AZ_Lz}AAwj6^!>UA^PX%;c( zvqTo_E^Z|V!PuS%x!`EW*%>xfw*rjV8bRTH@v>27OMr=? zTMf$*t47C}zPx-2aq@vbZA$?I9ZHN{R;UvV(_5sY@`UlA%NDDSf$E*xsa3pPy(M&x zGh}Gi4jYwgTa_QcLSA-rcsyM9qF$cB-*TtEkUtChu7cO!nz(zwBi zi;NwkO^~L9D=jhu*i=rx8V(3GSY>VR-d9wercEsK2QG==wiw=i!&{4o;uU5#IDOc8GGK=~03LRRfCP)@oSM_7nrTYHh8&<4?zP zzHoT>9}5?B6BvgpF6-U7cSjv!^wgn!ZzA6@{SWH}x@impi>@|q*h4<#!WN1FO@k}x zaDn>RO9k8}`Ym*hSz47=`Ho8O;7pmnz@Y`QXWp3ArtTL0)J12!F&41RTmo3a&E|L_ zTNIO6$|^d!mEdBcLs^3sFA?5ekV6Y4$kAMpOIqhfu8a&N_KpZ*9hl}i?jkKsDpEAV zgyJ+mXq1tNqHbj+^vo{YP4QI}>r)OTtJ&PpY9`X1xMh^0vc$?00-+2wCRnVvrQE6) zc!3SU%-76JTNc=f%tdn#6*__praVTyAzpdMiF+=S(HHQava;aQLfW;BW6nf#p}8Of zB{Ib1R|!MmT}v0&IZC$X4a^(=0Fvdw_%FfZ@Laia<;#~YU;Q^OT)A@P%lMu@0REf* z0OWL-I}PWAIrp6?CPd&zpsP^pK61aHzJ_no4oJpo>ok6+dDQa?L&>SH5tPa7fMS_d zw^y9U=H;4j(`zNf7w!;I4|sio9LpGb!5X$J;VXZgV~fz zm+1%QV+k7;1l3@P;RN76xPXFThJJHgc|y+R8v#k4_{#;W7rCFn?gTd0@qEFOXMH$s z^4L6TddUxvU7U8D$&}wE?soRvF_xNOeT&C!)xsF*U#0zL{e^#|{{VrGy*T~SE&hTu z{oZ9$dHZ98ao6Bx%&!b_Mtx#p5w0Q2oUsNfXjyQRXR~z2wAMWaUhaCv>gKh5F*jAw zIfYZM8#!0N18J~j`pSx@5y1u}M=L;}sn=oVcO}3nt=AX11AE`a{YykK$}GMrS;iQH zv(cG;qA^CGU1tr3CuXh_NHX=cF)?Hq7dcs?T8`|S;!vI?4f6(VxPE9GL9In1LyC`P zVsVbJ_mrT0@Ph;@f(git)i4xGn~6b)Lk@hx+jC;!ZKhB&sLi$^klR~68mQ&Fm(*3% zp>`4nDTtV^7~t~*Ak%WPa0CyzvZD*EsM0OL+_rnj-RcSFhyfeBl&6Tdg;S>7Rq~am zArHxoz!Yk>m|cx!e!b>pW3&pzW{K7i8H5GHR#aC+zo2_mYlT7YWRBv-wfF@AG8tn%^zP|^IexHY$ zQZMtD6UKclhMw=xG6t%=y`m674jqR7@l ziluO9`cZq$k4${!MV4u0oXdinTKsAdEJxETd&py@1Ma&%UNCr-PeB#}ujedDsnp>i zb>nO_)+M_C0CJQh$CO4eLHxsD`S@PdfGuMT(tB{cjPZ8+|vgU=fiHa>BP`JRw zXrPCMt!gHL>fR=RYBrBW$sA0I_eZcm$E$aMsJdspMu*6r-DPUqD6jm1{U`h^RU5p@ zn9onrQa`*A=-RGb`F}I9{P~LJl+*s81zG6R>lAu=f2q(1M}Mr?4&Ro0-TqmqO&a_$ z<@~*7OtOaxj>niANEwMstSk*j#IA$7E-q-CrH=V-Sf(M2^D5G@oV~)LIXM}>gZgk5 z&F~CgEZWZy(=4Ukj}(Q4l9gtSj#K`LEm~REt&Q0+RHza4IyiWZh`c@plU0mfr%tP1+ z8b@9Q;9G)W)IoO>T9z`~SS1}b0vL&6BJx$@23owmVATM1Qh;!E6W78L$~6+8VV1FnIA2GkSynkiiy$r#;w9kl8+nFb>%vzk+kEzlN737iON(`}j`tu` zL^KQxYtT$Ln?RdjRQEcl_n;eDfi?Y=spIfmxqqYPQ``hLyxy^_M!i4c{{Y;%a^?I% z{{Z3HaEq^H3kb~%%&!^8*KRgJYt0g`nN;JUoyCX(x%o;VOGFnlRdvk_LCnhW78u8Q zbyVe{ZhS?pM+TTKuX%j>-8tloUAzSw+f-_A4a8p@Fl#I3Hkf##(cC4ySX$QcTxwn)QCrr! z@dk=Jur=FLEF@IO^zAc&Oe$Mnto4Wc zhXJJ{Fyq%p+G_L|D&Rd}Ol@ggzEPWC_N8f0GWW&6)m|drQNTJy7ZPYeRL-9{RzMbghtc+U`T?eh>pO#c#D7PYra*Au5x3fRA}i;lEL-SG#${p_W4GEr=3HgjlqNe| z;S|%khPr2hCOWu0PLp)uhBbRN3bW2G0E@yJR5+M08C}&)!WFJlUbhpnO0y#$QaUA} z%-(RyZnF96Cjp+=+DXd95__VjXn2WvdrI*65HY;OrF_kS1tK@v1_XGIQqpdUl%>qR z?TurJP6c+$?5YYXKSXQLI6{J^3cowRE#*+77c4J?8f^o1EtL~)(*_*CrQvevrDo;! zOG2aHWb-Q?4t{lyK(M-sf^jKZmRwy`Dh#6x1R7yUhFv{lflxoo9%b2Ady6Y}Q!p!M zPEUAx+SLZy=k%?2hHI_#6EcLS%)%~;n2f}ZH61EyS=EPfWJmsFIgsrRAxBBKtibrM z#JO_+0Bh$`i+N^h@{~O$0Ppy}_&b*`;2Zw{;Oo#@`A_Ct!+7O^J#zVuA=@>%`A_cz z0rZ()BO-5AIa}hRR#a6`cRJB=H7AWg{{Wt0MOWeS$BMWfN!J0_$|K3LGB2#=T<}`GFyxOdeQLz;(T3IXsS}Y6*Kqz5h zXW0+AVX5w2sO)&~f_&~N4ndvjq9XEuF16t?U_hy6!N@>YF&!!-sn;_qMRbHf@|YaQ&UGqOw&Bz|I5tY-xp1`&NfZek z4KW@E6TsdP)luyqtmj9F%gY9M;wo`*lu=XUP4rWPSlyDMSSn`3wdKvvdES5l)DEe<$>0?hd;51ENKE3~d*UGdffx+PUY2nnF}fM9ae zH?EtBIY8H`fL_zz__CBcqIZL$hzwh4UnuS2pf|}oO`nCO;?eS?twF{DJ!+s=kjybB zg|}5uunQD;8<_VYM5+hr8lb>9s;7u#G@2sK=2@tfMS~B2;v!?vzlc!mL@kxtms)k1 zP`#x$+8kDCcq-lzSjtmqs$h$VXGu$NV55A>SU7{oz}0VHs`^Z}M~Be0e5D6p(P&q( z(kjxvJYu4&QKAc=Pw~IFb1&n(Ff1_KC7D!P2Unj>`b&uFGKJUNJ*DPu%WHpjp}t6) zO%tK=P56J-uk|0k$1`%p!YeIv@gwjt<0A3?B``JA{vnOw-!GIt-uwQd1*ca2Q3hM9 zUnrgQ=KlbwjcIE5e4%$--Noi+xBW*iR`U=uTVINa@+OLhCI0UZXs)|ytV^#J@hPt% zF0*k4($>F%fvJA3;~dr?#admVpqfRdE8Qal+{gJuEL9^=v8n>rGMSqWu}0DNul}80WREn zu`u^)4^}EJu229Ax|?{7#>se40_o{3Jdmk5S&&hv2W$^P2LR*6mbg3%SfWBU;m!yO zSSTsLR@^w4PkYdMBdO1fab*Oxw=p$r;y9^KXbw?i7ZGASp<=|Qc@cU!jkJe+`OM85 z58h@#Wl#>Bv7AEHCa^bE$=)=w+nDs2V*RxiT)BS*%a_?Z}OTfPZXJ#<{ z)O40_RwFQi`G?a}oWZE-@JA(cFMop^#fyIeuCnNT=tFrlJjd_xo*S4k>s7=>hn0F+rSY7}4icbD;a zKe&d0{PPndn#siLD_$lI2J&^6Jxno8esip<)Uk_iapDPy63R@lg)cI5Z=_c#c^HB= zD-nk(nEWE$_JicG>1H)7m93W^+lq|c!PL2GYQ+<_1+#Uysc)HQEWz!qW>xRzJcwDl zrVa-zvR>%$tb|V?0kGyb6sw!}gHe%NVpv+PCl#-VFvx@(bt=qGDkvOyhr)_=7a9&` zq|$K$X32_ZiUqM5Lk@yH0+pBrd97wHUeHhx+AhlVlpOs~&=ivd>SOj(i-VPeGPQUB zp{GC`5}$&YUR`FD$eQ`g5(bTbxmI5Od4Sum$8b3L=>Gt9_n+>*^ZnP}6&Sc$LD#&> z-v0ox-7ldt&0m>)eo+Va7b%ABW7LM%)-G*1BKWE4Pp3CNQkPN2=a2q2<@^JG`nTH5 zbix#N0^LBekR2GWnOSghX$M+}B?j(0U#u)lGLXP6p_im)&k(s@GxMBt&e-4Oh;!I4 z;o>MIv%?CV(0xcA<2EH1uo@z?(BafEZY#5yaqWd^XFV|z(7|_lOft#tMVRz=eDb>0TwqBSyBMmb7hc-e%|VlTe^we9Zdn zU2=<^9dI|Qc7=DDRc5&CBZ8&zUE$5Oc%Ta#qU{#4YF5U9prE(&6zSwO3w@MlDLA|7Uw!qb|(jXfDdcJN0Hg|%4jK)eVG8mqm%9Lm|| zsR-F`E56L;YQ7IM65{lN&CJEBwlv%ZoJOVQUs7QR8~vyCAH4iuPd;GypMsZDKTa#i z;0AK#_lCmU%&>s3F2ONgv2(I9%}iar^zkiWY(?`dHxD0V^9A)Q{O)I~?+aVAk%}l9 z89)_h?u(tcg2wfb1L~qn5!P6zRS4T#mHI;#re(}A)P)5P4bMQ;87(ov5i%w8?*ZF) z*@!ca&A@4u+~0EHQ<=y3)bZcoAO}U#FfpLRvT)Lto(TDgNoG#q331^xCB8u72@U(i ztGC`-CgpQ@XgenBDlTB9$n7|SwTCE@Rg@}W8?mU=5Dlf-FO@hkQE=HY6t%Wt6k;8i zv>|%H8oJF974i^4M%Zi(El@#tCW<7Qw$Ws@1uylro;VYOEh;@-! z#d6B_dM5-_?8D4O&Ix2ixr57m!7(ohaJyJ#O>qvD;2}lzBq?%+{ET zjk=g!yNP&%5MAdV8QpJ#NwlR?F9qa5^wHEF#(N9kg?keo2)sn&9I0bDf<5(~(7Wx1 zN0?2&KVmVX{CJ2B_t)*k3;dqb^Dp9lW&BUfzli(vMv1LJu76G2Q5LXP;?}rBaJECb z%UqsN>3*8i$*hVGULam~7==QNjJOdKf zDd3mW8XgdJzLf^g{x;?O1AqDs$XP)f(?V9{+dA_unvFqxK#`)enurxw99p*s&Kj91 z#KOk&d32TEmln&2S@jr=QG9Keb4wz@+tL&Q(yrJtAlcG!(sH?rWG2{CY3=V2TY=eI zugR#(2M@@GrstZ}=J}dBMP+8=>cU$H$nm(fm#+&;y~a7uk`OfV0HtdZ(ht7RmGg_b zyfsfAlL-*_Cc5fkUb5~CLXP%pC3KXhlz8;vq7#tPp}98J3`Gg@m)L{{T8UE;mT6TDJB=AZh6+ zYh_7E3-OCmxg92-l)OcA>#~-4GnerIG71#_V@F{9CeQ4xe!$=EKcQ$K=$=SX2-D-k zq$ITHmU?$b!%Jw?vUa7eyE@#oRElY!y_v0(WWXmJug0oyjvqQ7ouyz3msyJEP|npL zFOqQpn=dcoe3SQC*kWxrd7Nz-LdPh<9*MZw4a^s8T?_FDgJoa z6WpOJzz&Fb;4<*Vx*lG*f;S?b#iM*;=1kPv(`WlVPza_6|vr;lG&da{>H17zfMm|)HSmz#uYI7HM zZ#4vPyN}`%FjXpi%YqrQ11bcj#T9@Yj1_8lSU&KCn)rR`T@z^!j%61}Jgnl&mwYdbc^J!lLys2OXImm3vI@65ScG*lO0 z%(Q6L&6(VC;!uKKkoJDj`bnDIj`Hyi7H^C191>0q>mQmeB5DNckRvAnW18(N8Yl&V z%*a{GGz4$6GQ~)yi+IH1tB8+JF#~MIv~&F8DVgKWiys4`p?p02rD$G|Xh5LADfEXq zrw~S8&Sy?P6eZLl7BPrWP}*A(&Nwj>Vme%61ovTg<{{il8o`(@UEVFF9PxPUsgwFoGvE7BluP2-S8W zZC9(0NxM#77B5iGhEW=F^|fG_=5%~2trWjnoWjY~9?)fg^n$j7=_~yZ2J(1`c3kWx zLcNKQnOqBkcGGRKy9Bm3a5t}ze$$WqWs85H9%0~^01qT7AB(BgE4#1xGayol);}cg z{s`Za*X}~?bXQtzy{8){C_ghYYGla*CF_eG>L_f^@rYFA?m|Uez%>v9V;B3W5a}{T zJ1RT!R|G=FB{D3zm|fge;+NHZBSBD!TbPTe4D0lQ6+xK82Wlfvl3dN%E;umNY{DbO zOG7&16oUU0%Q6iyTCj<=P+LDT!M`}_8 z$SX6ZJ5q|`zQj^cFx252V!3{J3=Xl1<&;s?ORQlvsgro(IS}qHH6e9JqnN0g8xJM1MwNg#z}TJ4^onlajoPdJK^6X_5kPST4n)ae$Fu^U!!>8DMZpIvPdb@9lq*OU zR=iBLd5rlFh#52`RUS!BHF%qE+Ba?b zLK&8lgT+PyQ`n`~v>Jvxvo!G#8E;hVcj*P1fm+wvpLiVh!w$NIVP__odVot@6>ynr z6xt^zW#v$NLI@UdJ8h@5%4Vho^*++c;ViWf5kYEI1GH;cb1^oE;30GF zanR;)jkjm2%JJ<5Q+4eUsA;7-r9ucUxEhJUdgPT~BR#CsrY=zvVYF}NxQ_vA2okkN zSP%wn1_+lbSHWKeN|o?=N|o@ZfK=&FGK!bdzqo(GKWS83{XEOmf{QqZpt*fz!!ad} zaOt|4O7dTs+OHF|K4my7#H6prtHiC&wUW;fqXGu=uKS@+U~J69*kcgIJQ{0Xp6dus0~>S zr$j+zUaAxq%FWAA5*fy(7siOkMOiJbnTr8n%4|-o17zAtyh(xO97sFu6;Mf0H=&Fe}Zf2Www>Pu+`+8y9-D{OcCzH+!+SSaDKF=e)F-)zmXZS%|x2Hj!|yu}7> zidi?6n2e2KhM$O5SK1i9hVbv+H^3!r(r-j2jQz-pJxey+pmM6jIV<+y@%Yrku(Xvg zUy;P>!ZuB~7-3PkuDXGktL9>Zj{B5~*?xLYi1-qA&zN?jrlTlIZ2th|ZePGR{{V{d zFCxipN}Oj)F%XI`C@LTqm@#_8Si}V@Otn7MDY4;VvoG(PdL=Va+Qr=W!8% zc$F|p^#b!PC7K6lzi9V`*8_D|oP8n3NUNkM5vyaFu-ea`v_R#rbfGMMnaR^opzAT1 z1V>?FjQ!dj`T5K)rI@}%Q$Xx7an0)9PLN&))+E*=LTT^(L9a$Q$XfS@dj>9~wd?P# z=_{amFC9vhx}b5Do)DOiX?-9!$8}U&nAuTH(Yb%))-Ugsx)}UY9B}=;8dLq%mGa7HvrL9FOqZ& zC%PcKIoK<)pO$KINAI)nJE!AzL-rrpAF{O;{{T>Mv@AuPWxLRSh<;=Eiw#v~<)OvR z{{T^GR`-6<$RdRdKablVg^JkAs#0Dhe}J1uEagcB#G?Vs$_G+XO!>KmYU8xQy%RC-sqomMEBd9O zN#uz!^@Oz4!_`J1ZVjqS0mn&TLBbF(5DtenOy1~Rsq`5lVz%mDCG%de3r~1l1wd++ zLqV=&!3e=}pfPb$cpzUYO_TWAVo0~Gbxd6e0* zBD(CXvAtm{Q&qTI$PfzAuGs+E9AMPj=_sjN#CczvT=X)v8f^Ky?avf?04CGm@d$xZ;? zUrBLOrIA(wE;%jkY3|EcS#7FIzamH7=g%J4@ z0z?Mowaz64K|#`FswgKbU(ZP9PpBD6k%53_3lcDsQlD7)A6bN__!8e4j!pnX2t^BYVHNT~(R~Py zTuZ$1e((#;NcjHXOzb7)1jj;O0#`|*(Ztkp>c+5DbkEAiUquHEZWS4Fa1ScLt9B*2 zYz5j<;IIkhPS2yDMJoeiv__7T>_sq3z$u;_F)3kLaS@6)14N|7AFrVh<2HSuzWHWTFW!w zC7Fmd3Ryk!kOOmfQBYH>2I3I!%xe0xGEk|l@3@b7k`b^ljVFdOtoMqgRLOH3@x4b? z6`_e*Jc^YKlR|EV@f9-%X_yM9n9hz1mrgZMN=eULQ<;4+E&!Sdg2j5#RH-c`7g73K zjdKh)qZ1;Jv~7nrrWXdf!*z29i3q7SL>jn&>oro1v~>*>a_J9rS|+FtV-JqVAX$hu zrbH+>1;X387qEdM;xub{MW}~48HPA9Q@gBANQuQr9Z2?_!TVzigjg$x_FK|0UW9SP ziDXtIcroxtV2zwAI&Nk-sX$T=<4ImpvrnDJ^j>ZizT$4vfPq14pm>;{XyMWvCQRmF zu|Zag5GCCv(;(?#dhw4*$LNO2ESUA5<4#1&x%@;--H;11B|sYZTE9&Rx`ALOEC*Y9 zpAGIT17S4I_V7kD9#Bi{pIqZMhpLZg328zK@emx~#h5(I3LvRSIpN@c6FCmT0bq7- z+G8VqIhV5Un0S4D4}pk^Y(`5xp;rYf&YM0*sWjICOo>oRerp9osN> z{vg65h+7rw3JZPSn_qa01&mkJnz~k{J?2RmR|`L>Zo;Ons)yg+THm(0Ub<$#DE{^? z=kBK?sg8)w6*oH-g>@L-8m7hKqT^T(iFS`F0MF=^8A~;W&M(qYvw+&bsaY+jXmc2< zSmXs%rki5|?GD0o%Aj+ox?!gmt@a`T4H81Fs8-`U0n_IX{{Rqg79R7VQKd<{CQG|p z(c&sqTDEfv@!_zdwUK!-U9h&UAFXTk3-~1YYPADSmHz+=WE!kqCL4q(;vcg9$lvb> z)Ae?V6jaM6L=?Zk_-}=96N8V@2_lWXeIWJWrv~b=+6+3jMk%>)MXEMj_V$Q771}8? zOErO;C1AI?DtW5s@XQQ3>pXnr*x}@5q^CGL!jwaZU1f4S9xOw?Sj=7Z8^v*|GGLfSESwmQtYU{0t?x5Tijy5?|&^B&TX?bm2d z7#7B5DUByHz|xc!^dokuDN&aYl<0(3L>x{*1j`znjV4HwZ<-PYbcO*YuHwZD-lg;t zFD@Rkj_S_SClxY{b(b46<_oz{(qegRh`eqwekOy{LtyOPPR`b(l<|h2kq!OtTtAQ&6uF8IDIq2~Z;ngH6EUH49*BE$v{CR6zEK*oaY_ zssrfDvxKK5bub_(%Tp|Xakw1?%|&4FOd=k8z%;V1IFdA)hc{e7n()BRBz*nP@lq!#` zrog&jrKgB63pC|9dqXZY)>Ai~Qs4u1tM!)4wRgb<*CjotcEYY(tv#g%XpP*1n*Izu zrgRp{UwF-%+n-235aaenpTI!8F_Y>@k2alg^Rwn~*>^AVXFUR#EDbAyn?7Q3c% z{{YV1DF*)l?BO_kS@OQoRtpVX)l9PdiGMh^Oa+3du+0MOn`K64Mulf^lxeRt2#Z*0 z(Fe`f3(xzE7`hFqn3xcxs}ygq5Zr-qb1lH7gUU8M(vf}R1akV(m;#1hq&o1-0d4!l zx5Av1{w0@fhZQjSw?N<31P*Tp+NPPqIpk)%N*8y}^D?^giy|WO)|r1ll%&4{O0AE1 zm=^0w7ZmU<;|^vcR)*kECpa%w?_dF7FG^K>5m=E}JNeOi@kwmB@v`(e#4G z$zC3B!!PECaU-C2XdrzNz2!6}|060=Vsm5hq;JKmG_@5A+3shchoq9}@ z900OccHVbEGhAs4qok($ae(YlH9}9*GS^oe80@&!df$)GJU&T!p{{Sp!Q3|V~ z557@kzinTMqM!$)`Dz&5aYUsn98G6Iwm2Yf;ithbhTIibw&TFn64tIHcp;xL@P5h_ ze?&As302)7d5}Xu;B`tXxlEN=0XLF*68c%R3k)}K&>1nn zI3gF3%m!b98Mu!`%Vr-DP!_4iXSo_2OW|_hlp5-}$(V{14UAZY$a;UikhxKmfW8m~ zAiu*klKbYr@?(unyK9)ikR~Rf*TdDO6>c|Cg6Zo7o939{_MNs+mTdn3D1s#t^^C;D z-XOjpa)+T5ua(4qs)lt(5vv7vDRPFP#wV1-@JWTvB@KlxHuh>!(eQ$R*D$aVMK?`B zA)F+)qENC=UEHOrhJvqmDcl zS?L2wOr}#TaQaLKnVu7ED(g9=opUs|qGA{Il1@9&eTe*Cx_)Js&aq(7(KiQ0br2aN z02ge*VV&_E7!YF!&bZ7+)Ty^2Z7n;)$98x}5Ix)-U&6n5E=3)%8gbVj>?(Eor9DJ% zWLak;WSS5g&;I}kQl(0jDpaXbrAn3m00qL3Z~m8vgLDv_=kAmRN*fHX2P8`Bd_^9x z$Q=UAI%avpJ9X4GewrdywWzbkCgle40~G^-4zr))WML#Zh@`5M&fAF%*zEsOIK|r9eZg zE*ffaa6;gxI)w41I9yzSmvCJa+{$QVPNyX*bd7@^pAJ;-;Ni0A5%4R*wJH7uDAjdN zCOB2%TNr-@Vy%*RsZNB(B4FDSUy1v(pyNYLhB)Se!@j3LI1rVV*6V)2Iz zXFVYXr;PEJem)dyIg~CelG$5>tlpksl>)YzStnH>r(#Pk5SgIMtg+T(kQmI^b<$(m zIBF_TYAas&O?kWTeN1&hB&-& zI)v9RC|v!%D(7;o(M*b)-RGzwW8(}TKm96|DpaXbrF>60=RD`1=mGo5@jU08^Zf#) zN|h>9uZ{d3Kl3byJBsQht{kF3ZbtoOY;w)L9)$tv=&rVTJc-SF?kv6K-40HrP7bl{Bf{(&PBpCoc0AJvx zA1Q(8TB8K0Lk*<5D7a~HMofQ~Kg*T zDm9&m8i~YTj6EiCsp$LzH<8w6Bi3C`kwdhn6DZ|}+HuZVsbRxs;xV{53~;Y9i%OJP zE>@Jzs#XfiH!{I&Mws4l=?rT8In?Ane@HSQZKyW2PDxE#BI+vHoqeSNR|5wu2YbqW zAwY2n#wE%sSZP6t!JSO-)ZQg&E;V5~dNgK19|8e}?ilkp^1EQkf)Qv^wlAYF61~`1 zSq{;o))11-lX9%sXBLc9CDa#3FQAG9W2`3z+`%(1F-!$iaa%I$iPtP%W;sqkPZcg> zXPyMOhO)o`ZzL3ks7HHuv;!h%xDYZIi2)rUQ?3@>gB!zkg7pwQx? z>34}Ze2A6nY@4t&&80~$u@8FUYPkztiEhBfrE~&#nZo0=>9bepOm?zZGYh9 z)yI2{y6Jo8`QC+=wFQlKuB_zGmV2J_nBli#JH6#dKM7V>GL1(yNfc{E{NPHC z$S6!ZnC0&TMhf%VAVuGNrF)xD9%MME5EPN~5b*K(LBFT|MM{+_RIh{2;1Aia`>I#$ zC&Z~=^BZA+W~Nq|%%f2X;wr@iW#jjLXS4#TcM!RHvBeY8krn|R{7Rny3_Ta~m=7o@ zo!^~i_10|W6!Nr|SILFeTm2(dFBqk*m-v|o=*%Sq*~IEQ`6*1pEdXEhIjpZTFq#0d zD5W*Z7DqpoDeU%0Y<%XWFV(d(H8(a34UOJqx*hE|#2cA$o`z#ova)SGU~~pMUVcI( z)ENfKjqJ>U!qrzJKAx;# zr(p8Li@Z+Z?5i7%U~s2!Y%=#l{=U-Zu<*mLDZ9A%7%m&#?mO46ji-&_t+MXIC&GLdkm06M9E^ zI?Qx#E>O4bQfoz2eg?>hQC1vHpE$&&r`la`C#17VJ|VqC2A0GOj8#LZ4-o~#JVR|0 zgfSp(%2L?{)HOxH1TdnQ-t1U`;cDO$D@+57Vxjxk=8LW`At zc$H)&w)^HGiKUYPK`mCH8>|FRFh$IZo@P2k7sR9#dc|x_!7a;Xt;_+(8G|s@*qw~0 zOg0kwk%!wQOHsOl-XjJ0p9;Eh?;NLhD#NCwP)mE50Y^*+5Y+1PHGYRs*!WkIX3@Uk zDOt?08LtKI4Wfr&Tjha#Lj0KMT~*ifNy}2h;{2M zuN6D4o+Zs{6t^3zm|nWqZu4%DG%U%?O8nY&I;YPQ75u6Nf8f-qQoav375@Oq)VET; zm294mCoxNO=*2tw%M~w{QM~$m<;Vvw4!Ohfn+VzV_+t@4hc^q!8uld};e%<&EHZjB znm7b4SU{_AcfsKEY^b(-5OfLR1?Ra)Ut$$^2P96B818Y4MWMp4(kfCa?JLo|A9!Ju zb_TKO{KKWr71@QNO2`loIh1O>W1H9tF5oDg>7t65_!ur0vlOV0MKNDEirAXdb(xC{ z7g#cT%RFyA-8yNAgd3rP<@>PwXq{5n7@}i}=`z%YR?BQVMn!HgL(jlg&i?YFV(mdk z=U8JEkJkSH*3L{BXgRRo?7y@%7XJWbjX!17yjumE3UTcXw=vdZtjAf7vmItS%ypRS z0-Vd$Gs7@)Db`qvJ*#JkT{e*eiF6;rN8B3vd7Ks)_wYdBO3}~nF_yGWO>{d$3PSHc z&jDTChg}ZQ%%D|fbYjcgfDE^gmgVy;rC-sxbRq4;Smf78)nx@R+zW89^0H>7Yx(mJ z^2>K>=5COjFfe8AKXWOREfK!AePv3Wo9i@~b#P%FXf0G;Nv7|lFhdv2(>aH9TJt&& zXHuUVW!xtgM?zo1u4kP}R*y9i#FhkMtR=@r#{U2Y6FE3x2wwK#=zwt!f@k{WCtlK+ z*N7y=7YL=t&nB>=`iIln@9mQd~^cZCKN=3_w$DumTDJ;C4Y-D-ZWZ`e=!0v+B4TM>$WLrNNeiuXtusvey}TJ zIna#iVZFYwQw^Z)n=^H}X(VcoC0w@YP$B6OidOp~;^?MWag_BCp3pv1kNQI8N|h_( z2mb&v%f@Ql!jIz{=`(^*1}jzk#tAfsVLVRcllVS!NN;^!hw~kM*xYO|!atWtDSVQy zpUf*iuR7m2iv@+zaZE;_S81_c@N1@z_- zVepsHrXH&<&KQeLdCWLjLel$pfK=4p*M=c?X25-QD0L2tBl`|+Hl)IsJ;{_eZLZfb zMe{M^0_OV@47g0pB&6#Ahw30XdmfVyqy-(CxrXg#GjSell@-0cEkg?{-Vi7bU3rAH zw#~WQ^p*G$4Oj-hn8_hFJ3K}=C43CRBP?a;{A%U1#P{ve%)_-@eBlnK2=Io{Shoy4;z7&s)2hd;{lS&0 zbq<0th_Y1GhFYEgMztQPjEf8E{bNL{>R<%+<{QJ?yidXlo_fCVkSpBdOce6AAasj) zn1N3&$hl}szKMX-ubD$m3dCiaF+Cl|4BZ56C?p2F#6?UlcZr{xCVWQ#Y@Z||TygO- zzIc{dA@fC@RZGxBmjY@xL^T}DIfOK;YEzQ}dJV77nWOr+K_L-wZ7TW7Vh5U+qi1r| zL3Z&dG0q#0HioP7P!gK9K$9EP780C87ORLs?Wv2*;VB%xy=^W#}~B9(^e>8sIZ=!m>0ywtdVgz5iJB|v`AhVjkQW) zm1(-b;f1A8P<5MBZdw)uBCT+`>lRTQ6AP-YleBwGp!Q8!?SjxRH7=(kPAda{wc1S?@XX3X!Pk&3&hI#HDpC_b|T2M{1L<);H}lYlqKS zQR@L?Py_&SG|aI(5bw|DSQ>+SdaS-;D`g_xt!CdU5Oam=`OAwyuBa3a2C#yZ{{Rmp z$>aHmBnqyabyB{76KZhz!h*Wwxm$F!8aQC@!V2)QJAcL(DpaXo0Z;ybEC6LM6I0hY za-S^3W^fpdI~pIPToab;JH1I&6*1&zXu?<48ur*;-0qV%?fk)zBZd$2pOgTV+Ff~p ztr!ghwEQS0M)J@GBYDe(og=6YuB8m}IMyGsvX0_zkD@M8heXtVai#taSE-v<1n!?0 z{83P4n}{*N3QXOvKiLAVlS*}1JKs`XQdf5>5nS6-;XRp5hRGhk5rvVkIXJ1$;v8?5 zYMlK7rK-huj92pmF84SoE8t!Hqu1zride4&u?GJDOZpG_nfX1Z&Ax;`W&Z$-jX!DB zvXocKR>WG#U(xokhqnA?RzL+$t^vFJt$8o^k2f3I>CfqzRj7*uZ z1Y~(I-(!MPx%eQw(*=j=Lv;M?^ zL0mic_@O2IzDOMWp{ty8#0miRc$6oEuYiZ=<2Ab_D|#k6jYfPB<#maLj!`0ZDGGGJ zuYzC1Nz^pJT3if5FfId9&y=MM3z*Gw9U}9T#wWeN-d+sSn(!C{X<*W7mEPk}4zW6S zM1#VL12M2)sR>1E{-ay&h$65RGoqEuQPC^7>pIEA#hB(JU6QFzOd(W3dxn_)F%%3~ zgPQ4ask{A^l{(e$?(`#N|q_NR=XB+<%yVAEwV*T2nH%7CcJT zh(3w@L0qLvmNq4?O;p7symyEeEE?iivEbn8s2sg5Z8RS^!9!zMI!ik>ahLIrl$M5G zu++<3_bBVSI*UH6p|KaIh@x3*zf?_mgTV?MV_kP%A%Q3xB^ns{0i)qv?e2@@>!LDH z;`XVKlS_Ru4jSgnK2~PkS?JXE1n2kaRIh-i{{Tw0xYj2q&-cwZ3W~#zSW;qmXYxRi z$;3!yw{M}|;V&>&XxZaXNHjQzhe{Hw>s1B67BOQvKj$0;pqKI%gxUR<{xXsMts?}k$GqDK_E9V# z-(Dg3AeE|flj_8NU9SK(^H}lTT)jb#qV{EeVyk)wC4)W(5FnDw z59kx@BdDL1VuoE{eBD89QMd+KOk3$JmoEmo!VV(Mj$zyzIG?Iz^rCIvs}MT1?>)@0 z=pr$!_mn(`9<+$et21u13=k|&Pv1!O%@KQ&?iREQgU@+DtoI{s!B{l)gbyYrN`cgE zE9nM0B{6DT8*+oY7slNqz{9LZJWdqbP0cwyWuAm_%-OgiGC`@C&|^D`xkI93*=@w8 zh$D!EMJ)+{`pOgANVGT`A|PNGN>VLhs8-eVnhUsYX4C3~hnNB9E5dIaN{E|xmU`O* znW#nYtbNjO{t?_QT;DIO0v{{{DkJKIOkwX6sbSWvCBtJ)N4S_6iw_^knaB#UJJY>8 z@EE(lgtWer)Lg>UJhKjbb172qQ*x25T&v6zD>F%%>9d4<;$De&b2euq-s0L~y=DV5 zTA`(RmYRdX`9kbnKrq)Z!y#N;H7W-Kw&fk}T{W2Yu4lnhL+}N(jaKGx2-cB=RUK!r z=gvd~QZj7&_9tf>!e$~UAy71TnHTy{R|t!O>v74kxGZ@UPe{Q8h)6NBd^$k6t^lfKl0%2Fk_vWD_$lUhym6>Qx+@GY=jY^2q z)s0;RUE&hU;JI2XX zj(WoZ!Fd9Q$`<}i%V+u}K+Wxk<%^ZD{yioQ@CIo)hP9B>%BpKBRV*9$zxA7>q@wd5 zWk+W}w146wPutQKC07xp!%cMAE^?*Fk^{i?hj@0x4O%@R*M*^9nYms<-&jMl21Q3^ zE%#M|xnS%W)c*i8m;GnheG_3rlgFefQRZT;hxRdVAG$R9pd$pl`1FlZQTvkHjfSIe z(4sDJVKt~LnirX3grl6j`$bwFvT3c;+9h}@j$5zHyeZu?8BjY^i^f}&x9>);Eu@Xl$^%3$W^b-k#s+Ji!`iZZXZ5G7S& zCN_RYyrsE8dG9Xs@D~OYRoB`pj5t8p0cr!`k2WC4W-MV6W3@5izGXbhu^{ER#CL;s zy(0GTVn>jMEd!Zvz1KCDv~U-%5cpp*`87P!X&&Uz%07pRgIPV5h5MZlf;k2u!J+!9R4qKyf7$`>??*a*}LHgCxdSG1@$)j>0VFhCxH zf*K4T^rg*fiDnm?DDom-Zu!dLsE-EXoujR`-$l;|_8BvH=Tgf$0m$?<8#azoh*3ms znCUZYYGLavmqdSJ7uUi49RC33X8!<8J)^sSApN8N01-(3-)V`8bh$uMW9%U#CjlJq zZ8E=aGUvMy=@PK6Rh??z@rq8bO7BqR#@m0cbd^<0U2cCeR=T;T@{0Mb>w8L8Rh|x7 z?+pof9Z8rey6OB(&U5>fI_1|_?H6_1zs%IA>6hAC3{kg-q<=FXjZPU9TfdYNRTn?h zTALCkL!SL6f)eT(Ous-0 zys=s!8ARX%D{eiz(lKN@ZZpvJ7@MaUfmX}{7pzJ^yh6GH&sbm`6?ZtQg*00iGN;m7 zJGI8awni6;NH_saL?GK!gutPzjbQtL}~k5grVEpt@Ihcl^qey-IV#^$o!?pvv=6-{&^OZ>`dxJ*_aXL4v4p zTNOxNna*)-d8YtwiTJv|SNO85f5`wNT6Aav&Z$zhgtlV2kN z!D+8{XZ{J)Z&o4n8N!YK05X7qB4+fdyb#83dAe~;yE6oA!n1@pDW|x?gb&hY*^%4y zJWdETZ-f=uU!nO#;K#VB&lg=GW#BiN>pM;Ao0Us4dE7`U7L%W7H~JF!f`T$63`wf2 zj~!!-sw=+TB5cseA=qnEwZQ}5@wmTPQPOboL1Do=O}2~`%t`Ko<7?6W3C&eo>qT+> z9RC344ZyvpX>jQ>+1UM~{{RUZe&fY%<#@L8_mm?_8o!ua=2`xbzHzXx%9K|5zrmbR zI>k$b@cbEuOUUANtULbzd7IzH+@oKE%tcLgA%e^wy$RtsR;>EPnU9ta&skt&{5nik z;(wXa{GKOl^#1@d_2_&4qjL{q`ox;6AB{ql^uhfjW@_W`N>VrR(qs)-Z|H{)lMoO& zRIthvyH_}zzX5Gji0j))+`N+W=*0sQq{ZWe)7}U*4lW)lb==*jiFu&nU_{gw*^4Ry zpzj?!^#}=#8NV^l5!PCgSV|c?76HmpvMO& zMb-gg?`Q=SlQ`835MV11(o*v31MoL6@U>MKZC#s-U!GD7mt;fLDdR?B z0~VW4?5IUcil%T>sx{v+eIIByg1#n79f-+ShG*B>W4rd1#5hO}u)sAg0SnbZpbE59 z7-b{i3EEr}+_jxx>0RwmaB%QV8x-N%XY zne&i)65{XtL`de|^&bFr=2DzFSifqAZSl9uJa=RMV6c#0wP#<`(MKG35}ybzHtD>3 zAEoevF@(ByX2zhFt{5|L0D_GT+RyDhK{4D}ZX>E;;yYIEIbvZjfM|)lOpGDv9hk?~ zh|OJ+nI~n86-uU>i*^yF#EZy~ePBwCJ)q3)0xbFw6tM@h6fjaPP)2!p0B9dHH;2_6 zfXnF_74ih}&&ZUf0e}5_D-5M>gn7IEAy>c^oj#Liug1P+d&{+$mg=95lYXukj%r02 zI}?Gv@GJE_rgsg@NAP;VCmia& z>kGJA zWgG@R%MX3Zl`PjJvGq+=u0B&@PK}J^ANt5AKBU{nJHKfE0K!r~yI(}A?q?$D@L&7W zu1}eZ4Jg_9YIGOTE^vj@@E2TRW`n$_Yda$DXdLVjEH6{TH}EgFr;bJioPph&`9b$c zj}ki6)UR@^^3!$g4_ZySKi{Oh9f?P*b@=*~b7L&8E)jCc1T<-<2x`8+3|F!)hY7sA z&E4WqQ#fV;@K0_FnM&Z8C1Ls|BxEYA^z#@#Nc|>*FkMM!;p6^=W@VxB&__LN$Qrs1_dd z%WoUZy9%tD6{*h1YET;9c9bR05UH^12hCqwM$|nB(9@;nT4L#6Mwy>dZ(`o;eIHW}tI#Px|bW~EM2k z8O)Dc2Y7oL$B(`WEgDPVelBK*)(mE^(C775oyyX?!P!Mz(W-0=O6yzgEln(1{6)Lj zHGxP77SCa%J>705sf4L`1I9yG-nfa@^@&?o>mISKpJWKcdP@BVHbtKqAH^$MP#6e4 z15whK8FFD^Zs$qt*6e(s(ioy0I=3N&Igy? zS|Xb-ZLjMOpTgp_Hc{qS(e#P~>kg(!)y=IVk(BkfsR*j&nkeTNReow4fX-qcnFS>SsBB`GAZ1uG9kue5 z#rcTsvundYFhn`XtSYvlF{pHy#V|sN z0^MVONoEyAUXRe?oRdqh=3}qBkAeLG{{S;H{F<9*SI~sHa^=gHEh-`Hg3i?@{L(_O4iBTnVJN)Xb&{}qB91;=wU6-P+8Xs-Xgh+c729t z-H5@`Q_6-}!=pAlRjQ#aFgLWon+gx5HRs@8s{t~=wwl;Gz2mOdVwf>koyzp_$9jtm ze-?X6JR(=IIQUn7ZTd?uJA)IO;%=nRvK`x>os1XYMd6a0VwGi#3oiz75Y@vpT*Uc> z04Ytt#(I&M<0q3>+fe}UB~+&Md|c?IuM*Dc30S?XDh=Km9blVVzig8FP1r$;K zMC!J637eDaI>)@}xN5)(=Da+mK-3f6VfCK`%lhJvd;Ef zrSA@^cd-LKz{sO(=vn&NsTuy!(e5?Ne zuy=C-Y?z+e_ky-nx2dz~Ej~rETn11E*v{lxr|cuxgFW6o;B1PDZHMe>iovUts|T$u zYkgQ`XhCiJibnMu<5T#WLB6IhA2{&PCZP7nd74#VgV|Pb_`uEvmyJ)9K2m{6(W%O3 zL3h!?#$q4szFe87smBoFB4N_7SM@iD{{TS#CtP~bw87`)l)pb%e5g1=ck36;GDGVd z;>qkjzVUg9Cfrl%@zQs6-|M=V4G?$YSZEYpm6&}3_w4leIFFD;Pf3rQsdcOC7WQ#_ zQxmVOekc6wwgUeEtiW_f$c=ck;Gc{4PO38=Z|xBX8v>``{n0Sgj!y^O4n##9zG31@2K}dKao0yNM4@yuGr8o?WsYQ!bwdGSR9Cf{IczsR z5*Qq+$!6zCXz+aRv}cXvR{sFV@uFT6Kh{Sm8!ZqZn!=WLUzcga>H>o^JqIy1zXQa! ze*hG(+iG@sd5ajt*Yl%SK6m3lcX3Xy@;@~{U{J3aOzUi$c!_9?rP&bo$fsNX022N> z&K^&SgSsv!bgZOI8Q!Qq`K(UAumej&r$TFpzCTQgdS)~pb zIA$1TU{<%epH(}S{Z{T8EU^{o8+evGOcB*eK)4peKLEi&)PP3Drd^2{3{Gs|t;^3C z#vzTc4o`X9edE;m&INnUr1yatFeb0sp=3~Ih*{}6F<~g&Pj6BRUmk?E4w;TsLGCNm zMp~(=gXI_340ps}yO+EG^djihJ0kRD=_)!gH_+N(a2GBrw}JHdJVu($QQg$)kL9d- zLMs*qPqBYl_&%6?6!};G0AeLj`SpvrI6C3!5*v2`-gyOLNP?Bzz2%^G>)4Dx>x>?+ zc}MJ{!%!+E#&g=jx^QTn%-SNDWp|qB(YK>J_kW<&3YoK{?{CsntnuwUnA^XZPM*kq zwg$|g2N#a7u45Z6xt~~S(Xmsq&-~pj3ejnKxIXctxiNSpY{9m$b%tDn1Q?+CH#LKJ0 z_C!t?vBNF+>=64*WF0N!gv3ozm=*mAvn`yEF{p5SOZfMNyGuGqfZxB0nn zm;CvJW=xn&WxDDQXWa#Mek@ge-m;2l7UJ(of9y@LEUM;A?dcPF(UD881Bo6b<71& z(nTJbp_KK5GLLTa7~YP@c`PE!PB_FuNRU$x$U>s)?8hNjnTF0GSe_83l<2rcDRqGl zLRlDJApI6XLB{TxaaUlQilg3T#d1eE10)2iSM-bCOPiGj5zoQp5~YUaj=mMF2>xE2#va5CS#E+o&Fu>#(g652WI5ZtTLd=Stwc9mb$RHlm&=&)0mw0G|;j*ZLk zJy>ZD)tEHlgn9`$c42fqV4{y?w=v94-H3b@R4Pk#)kec~!T<*;gWhD>mL&cRDjFQ7Dv3B@&55 zqEXUf-O!t+rHazNakQnVC&0OK<;#~YT)ggIk4f`sa)@qom^2LSC=J%;oy#qqJJ^RBq~!a!?q3x7IV2Dhk{p99wmBC zgw!vT%S6T{d}`*d%bikdx5D7C=}i0!dau$@ozTJsdaw-!nnu4V(~53Tdcz7 zYg2y`Eba@m-la{iq-b_t;t<=IZBdSM9$;J@k@yqLL!sqhl}osSIjv$>NzpFtGHxBm zHnQxYG5{e;=RKxO3%+7n0*wM+M>$@xm_-)vkewc19g;`_QZSs?dR+GFxBgPd=-yED;&1}028WyU+N9_ zKdJuL^*`GFr}|&iKfIsqe^WQ}e^V_9>-|F9lrQQs^Ch>+FUo#i`IsJ%`K^veRm*_8wmS0~jyj;_l}lv<>kk+!0eXJ1I5lt(ajj*h zz-zr??LfB%n5_mivRt#WX!Z7&?DeOsa|7#f8CIn0$!h8V$|wc=DqF{_w+gH^Hcfj~1$ zq{-0#04gvZ@N;hlE`%#xru+W@Olw-v`YK~q{l$#vZODJqUk8-Wd6nP)03qfFNbCF% zV$H4Sm-(*5D=Xla@jeV6`~>~se+T!F7111^CxNc<8 zpA+$!*k6Vg_v;kJX6D*gB~C65L9U*Wm=Fm-TYh9$50CBeD8ux>czu)m%(a)N`<3-> zs(A`OJ!Mnt;0U+oIqqt+V}+u=Azwanlplz5nKrMxvLvv)gf976l4Rnyv4 z+G`Qnm}73^pxem{oH*R6m`4)yhYWLUF>f;LXxbE8;TcIIg8Y)PJxQMT!WkE*0S7sq z2(V^#h}i9vT+M@NYFdxZVDZdm6k6#Eg2MSyIN)s146Kdtr-czlYK>ia5GoWN$PHK< z38r3131>i;stw$4W$_4M_?9X?j7+(5LNw*mWmLaP-C&n*UoqHD(JDQ&JuXszQ-HM{ z*${HXyUZY3rN5*pc8X9+_$v4xg6b0PR0oX2=z`>lh$Om}j29Y3s4p0rWQQbZ(H7?B zV}#uR-N7tE%`nRvT5W^IwKH!uQm#34TAMG)(XL+ z5~AGKU?rV3>t&~0D%7JR9gM=wjN4|^npZ; z+JiU*u2L%17tHmH67n8Zsns)1mF^qk=<(?*p?trZ43V6;`az`ceeu`U3$PCivLa%= zI&KDNs_MS^o^N^88!sS746|G89Gz1ZWS~UsjIC+Dmu=K$rMOlPEG)-U2 zvv4ajh9Va!8kE-MNJ!BL_jbq1EhXzEXo08JS2FZ^Mp{-~!+M}?FQzR3DG=IBpNsU$ zDi#BiuKc^u(f=$laa<|B)S3&e0CjiFqE=5JwH;W!`@hMSv>qscLW*|M1xY^ z+|2B?to%NalcU4EP{25m>GuQX^w)a%s`<*&M+iP}&Qwk^=tK+`LSEaHgv-{Ey2}Of z`axIE$UGFq4@-7atCUVRuMx;GI&ge%xssGoHG-AkgF>lWh*pS1QjbU*QDS? ziqcG&MXK~Za?8QB11%EIoIt2J-<(G_(>_UDZK{6}wW?W%jDB)D_Jn7ZAl_Uuk~~z^E>d{tJ)kKUw$@ zYvMHr{`dC}g1_Hs^^un;=G76Dvpb;{_E*e3{btSAZ004Z$3$)tL(aqAG?3dWlRnl< zcAJ+*lp?#smT#@*3uX)Ie{)6$E9j4EpUdJ@C4o;aH!iVBe!ZXueIiE-bsj1`%(bZN zKRJ%8flPpV8FHjci(tL+S4Q}qrK9T;K%=>x3{%-2 zW%jH`UuAks^;Ut$659}ni$$(j5wcK4YHdm`xN-*N=R?*DJPP!c0HiU(z&CMp)NwLy zs}vfof{2mJwK(4l9Yn}@ID;L`xoFboc{c_jcLbmSzgQqHR5XFaA;hcGQ2Pivg$qQX zD3nO$(shN}JJJm#Qv;Z`AhYir45Wm5z9WAgv^9spX{l|PB2+@QQ1FEv$pP zJ4>ynVuA52ABb8MBw1qQsF14ZGxpemtA5}MUDJeIQmC1EEI9zPI!zTe2(7JA!qY^m z8McX=#0-28&G9RtFdoow#MG!l0>;;)Q*Zz$Pag`E@CASB(46*}N%ef+nlWh72x$P8 zQ^eO$QR_TT{!sq_CJw&@6EO|u)O`N2e18KojPPEQTnB)YF?>hvK}9PIcQR#I#4~<+ zO2dd>#0L44FB6gYbp^!$yTbUR>o8Oeaz@qukPDL$Q3d(05#9nfN`Ah}#$DS;S@nKEt#H%R=lM^BAhUeev^_2?x^u0LQ%9KlbD0 z@ZuLUbHGMk-Wd%N-;)cT4%#LCZ|i`*{x))V!oMZAR{I=*HHYc~)# zo0TV3zT8X;eP(#mf*TucUSS5sGv+=UU?Icq%m;-!v9Ly}s=Aj^OTEq4m@retMc{{p z!TrUUr#QrJgMvRP;yMj6m+^I5imzTGLCV)6YA^)L!=-BpTo5Uiij6dzF>u&fEL9e< zF3$RSP~P!MJq z+NB<>!VP{>Qr4a&%UYu0V9Z4wphPyf+c*3jU35RFYwR?Gno+IBM z6DkB{)heY8uqLw${sS;DQ?r@f;DKNJHPB$wkzV2JJ4Z6w(6#l1#H}?8Vi;BoyE9kK zW7EV`fk?KSjtp_z!qU`6iFMco$lObVwz@!n8O6WyYlF_n+~;55zoex3$?In4tP8Hb z(~-n;fC;w}s3i=etbJAsgSo__H#7R@CDy}S~5&&I5a8yt% z)urZJrx%C{sp9IrSw6B#QX*q#Xu+*cpwZ$ZVNZ_kVUXbdz93k7hPKflB z^nIrd;PD6Ag%x-sk^*&KRucPcGS3stbbxF$;!>{3l7y7pt*1`$2GI3^be{1CC%mK1 zJ3`Tn`G(aN=@%ENU@Ymxyl7**DqUsNFTpBxekWmv_@$@`XUxF9PA0huJL`s1a&A^7 z-jv&eBvQPYgHR7R>j?vF#@ql|#6Kzp%LD|wJt4q@1BgybP^_LJUgh?s;6s(mfgh1Z ziPdOv1K2t~Alenh%?=S4Oii=7#~@EQtY0P+c+MO5|kv|@h``;x1}q5^A`xXc!?{EGmSRqb8};#f*xWT#_AxyP%1A) z6J{bsvTUF{4~gVFCV;M-pjq}%N;KM4E<_^&h3?>!##yA#pyTp3)j34Dt7A4np# zG&4>PLowBbKujqjJ#f3I*S8gpG-I?7 zgs#)wQ2<3Qj`vyAz(!zi#1OTBTYJLGlTz%yj>R&KuUkVrSDc_& zTWF$C0m#nTE6|u2v7fS0%3C(B*9A$mH3!V~KN)i~$#}LiigOA&KwQnQ>2j^`L61wB z-#ktXdP`Ktfzg#t7YCSod5W590xL$@tnyX5OpNxXag9U=pa{7)TmvY3S360>7Cc6M z2#-0r$S;M7=P>br zt`Ix)1Nrz2NtXPtoHl3t`JAQSk1>7zCx3v?9A@?%7y&9OaWeuDpkorYN3mIOR=vR1 z4iVYqxB1UHU>VQZxUNKEH5_bH|~OZbY~Ns3?R?DqOZ6+rd*m zim00-V~No~;Q+iK?{OAmRM~0WH5}a#skZJYnp&a{(q5;e;E7U?c)1t6T38AjV6xS= zq=4)w%Pg5Hb&xVI$9RjadTIe>W$OjJWuPn2CC-k$6HRuPQlj!jl~bu;-lA3G1ZRIp z5WBQ5S2KF4nyGOBS&QW^4BW_$;p8#kFUnl#PYVs4{3c=9mcV9XNNa{-)!K#Tpc5pd zsk?Se6uf*E=!7dp@SY(63)IH|<9dspr4;44| z@fM{x(P<|F@!BtduZ=FXuZNy`H!*WPX7S5 zR1yW^V*r<#-}FbO`9?J@xI{*>W~Vq^%D&=dLANsxFxv+%^MQS&QRcM1_0KV-$(UP) z$Q;}9MXJJ4YY0N=My_|J?ZK~fJ~o4%vja5}*q32{JBZmUZw}KCfJ(02B41U`7kHYx zI*(9+UEaSNO>B?x>bTpw6w;ynQTB@!qlm3dh9>Tx&c4tCEcL668pln)yiPE20o3RS zrq9nv!KZpA3>;F^uTjKD7OmE$#IzZxRO0}+765Y8ssQVC5{4>Aur~)w;Rxeu)T5xF z>nvrr!6u=;AV;Yf-5ER=aZ2A_9>~EAz_po_1*Geuj_y_fr#}MFWT~_&W6W7YLr$E+ zX8TxF1M^a-1F<&K+=4|j$qWSh!*dIEjW~$CD;*&*GJ*4!$xdCRD46-qyMVa2mipW^ zfbXgXw1UvPWiB*Vuw-?ETMt+^@47d9l|&9MOMqu^ggn3aH2s07uksb)nIe62o7_KMJ1F?=TBG4zmUzG7Ic}8CnvjL0=)#Jrb*7>@%Y( zzeH7KYo6#{_J=v>PU0>NxU#k~5akyhgvEBKo?67`0ozob&};@|Nn6VozwN5mz$I3R z(~L(?q~r7@mQm|+-K*y_lLB=Kc4?yBO&sx!p{G|8$_A*?z`I9OTw0dCtEj%bMs+Jg zQ58EbE)xj##WPKKi|Y1{Cg-!JEAmHHxYC>4vKo{KFjxioW2dPETm$0_S-2bd%ZfP$ z8_BZAhT#FiQPbh)W~CD_(2i~Soluu}Cskb~U7pgteC3;JSSfB_O-y*W_TY=#)>t!o zMTZ{92a?4V3DOv#7X+*o%(m1zOWUt$P?dQ1L$F7PC50h~;K6hWXzHAj#aAd0KAd@( z&({Qa2I5LduVB=3avHh8Gg9u$HhdTrI%-*GMG1s8Fr=ykHF<)% zz8U2s!c;kd)ZfZtvxdhwiC%RsS-eb`V3;20Hi)Y<_!@2p05=Of6}Hfv_6V%~2&I%Q zSm0sB)}UrNTPa(-ooqVTbt9`0K)m8%M)C0;T7?USr0|Gd#7#9RDe@65WfmW{%*-?s z6}Ax}kOE6~eWzg(mBj0xY1;crlR`R&01mRCsOggjIWCbetKK+bs0!fM|BP%JFFXJ{bgag4Z#KD-*01ViQN z6&jjfFac1e^>ML6xzXBHYRi$Ipb4*s@WL~joh*M&b&&#(K^h9_msHRpq5b4oGoUr8AieeQlo=FbX5cof|E&l*9TM+}7Sx9YOZfax{2BxB9lGW)NhA}0~ftz;to{O*UW2T0#D=4;C zIK&!lT}q)2N2*#V@=prE3>enlkRse_^^WZYjZa@ZF-5Sqi@(4%u0pP4ci}Y#6PrFr z@|-#m3f+~vm%*hnYq>Jul5`U`7i*fCxUMcL$m;CvEE@r1h>pDf0Q4b^R5P*;;G8y? zG=;(Kj$M{1XO~FK%*@Qp%*@QsKO$GXw09ZsMXS^dv0&Y6;_=>Z=tev9XsP`r-4#2a z+jUjuQ$WZyOZjZGMU2y|S6>m1vDD=KAm6}PI)E+34W5(Ja;*1cH|`SYE_jM7>ndmA zPEH&dj+m5t60Qo-WI2y2D8w`qANYfey5X*M(Oyh^0^h|{x?UnhQ$@qJBByzGxWlxz z7jn_g{sQlFqD}5JaTm0sc!*2w7g*H9qEU%B*y}P`Fhi~}QQH}i<95u!%ypMz#L>Tk zGv-TIEOdpUqZA$D4a1n3U>;F=Y9z?#Tbg1#YK=fBTu#=Eh4|7R8O)) zF)ZF8_5Gu?sLEMaZqeZeNHoJU%FGrwafN&k2M%RzUfICNTt97rdT=Yv{{Wp{g6Q7n zJ6Sb3guIXJDmdH84kIg&f7Tn#5oNeIH}5<5^!QXWsl*etQo{9HF}E%sj?#i>LjfNc zF%B?T>`IHinaXJ54`Sh=&=Sdy2T6WY3V*4PZe3KXHP-buu*?kE_M6Xb^w;fpWT;oYyn)g@$ zIqblU0>H!PE$EJz^8gN)LgR3?6yU+)N0)!Woz{$+&KCH7{^3b}cVrk!H&c8*b;Br`&3DRZSWqjJGPVQ`58 zUG;>U5jb<1y%=!ZSZ-puOrT2~jbTw3-NNCcBmV${e`NTQbMSv?YA^Y4PeKOwl-3te z4$Mk(nN;Gvr=OIrvW}kex>4x@x?ebz_{!{iOuwj9-1K`)KggIanO%=*#)(qDDpofD za8DKOE4-(v+Yl?I_?3J4O|E-;M99A=fZsBzW2;^ZvKMlI$P6ljw8R5uPNVGvyne7o zglkqxwl5`^h_uyhUy~i1hcK z(cxV!j5i6=`#8IHg>jO6@#U;cjX5g+02`SRu)Q4upir1R*T;wz(tAc7s#iW*(~PuQ zyC6?HH5Yc_DNC#yXAdAIxb;ht%ggW^niH%A0WK#Pxs)+gVzG;jp80JJ5V(gsD%A}Y z4M1F|;!yk?)Z$fq3AiBwAECA)SHzbHV{y#Xxpyw6xZXd6+wJQR?ye@QQH5=8}Naq$ZwDslyT`Oi9RUAZ3lEMu8V!DN;(M7^yu4{>sO?3LrB~G6=Sxy5`9-FKEKohl~&I&_O%s?(=5K+xdbhxKf z67TIcCJ4LTxCUi|_SYmL&}TX?{MOxG%AbB=c`}7Pi;VvO-2<<5! zE{2(+F}HnD`9tGz*DisRGlJupR+Ygaf>4V^O2Gus!fF;HOw-8+%GUi6x0Gj6-|dnEwD#swi7+K$JKu9v_sj#5h@K+{?MiPU0>3O6QHzbzH&;c1$Ag zmR?3}JH`+ayH&=)(Nd**+)lCFrDn{>H(Qm{#z}6_%iT3)g~lbjf?r(TB1B=)vTB&T z)yjlLmdUm#yrfx>s)a(u3aU;c^Dk`sM8bUXj&TWUglggmMg>W{u@O*7x|m$FW@S?H z<>?p~gg^K<_J`t?@PBZm8~*^00Q^7$zvU;+eyOS8_zL}l^gq01F;k0$Jzn#gS-mLn zF=tQF7Am+Dm?gJ7=crV{j}UIEE3KR9&gFTefTAzK!F*x_75ElPU>_LVS6Dd!)6O1mi@_Yy;flU zS#VtJskVqY7Z6TXXIpYJQH$#0Wciv(+BbTXR%%!KMvz$a#*o1?-6_>?Q$)jQQE+!9 zVVw1JJ4jJb}vlwPE>T$4vA^owbYVQnS86kx_> z+IJGrl}dan{s9DWkz!KAO|wgk7*o(`R#7Y^34_u+WqSz4ddyAks9{dAT9hS7&ALkU zZHTWZRAGcK=9x)@i;BPrz~lK6FvJr~!@-b*v7}QB#_)VA-~@>}67V1nCJnjy80NgGevIN}O)@Pezr(Jam$>|kV z*6-nC8=XsY;sfS9rF}is^B~KAmGp@YA}z(um7N~&+QXMch_>X8F+E`M;09WH4ac!{LXnOfXr~p#<{zcAnF{L_C#z9lo4Fj0W13D^XM`9W#q5lBK2jKh#e(^{*{{RiH z0@%-SJ^=n_yN}u*rTx|fkufl*uZd`8cV!TluP4bK>3hB)(a_*|B_6PDCd+`hfu&If z3suM8&svN_oIAO9i-?q?EWG2quuHr&sPsRWmps1HPi?xRf8_{swG_D}4P{YmdcYEA zS&Jbf*8?d0Vz-Hl%+yG;Ek3ZY1&$h)@n9zr)zy!~8qO27T+C+E^K&2oJlm9=j(@xo znAFJW9r%}0lFxj>tyrHm76Py${$fz%_JQd7MAWQ=HB|E#J_(c<_Dy&c%Q1)si-;BQ z%aWUH9bFOJ)xfB(50rc#0aph-BL})x_JdlaZMNYrY6eZb$^cacd5i-efdpuP+TyEn zd;uKGCZb+{K^Q&^VZHGHaz)HrZeijb&2iLOF<=XDLyBhH%dd8ocMKk}T^dXg#9`Ah z*RgX96C4ZDA)=GuOF*b<3`&hb0E=%wFcBj1`HbQiA@^k(%2XkEB{^aO4q$s>1ycx1 zY=3!k?)WPajOUe#5|D>8wSnO&*^snzG}~e}BW$9#E5=cdz;c$8wS;VLOqkHl*zq9R zuw~TVV@>3z;56Jo4)p7+W;sI17A-TEE7F<87*BXxRbFO0uXq)f5ETNf$pvedS!H6fv^vrqDu+ps*%KVjj$i`K97RhHyd6uoP|c38 z#l@*d3m`2PWfsM9)A^Z%5&6o2GIQwwTpcz{=%+e~O#+?yed88d-}yA`$ux^hz$?D8 zkQI^4*AeclF1-!L+KY~5C_M}4UlDF_Slgq_`IR*Xs?Ql#zET*@PUOCfwhiH9#!Hl~ zIF6b*8~mtiM>>zZLYWPbz+E91SFE_k*Wo?W%JuUW6Qlh8nP)E37!w z!JKYpKn4sbt!W{E{3XN;+KUL;*kvjCNcoezG0w>oF*HzD^zTECk%q_^}T)Nj?PP1(aMG}~B+Dd>qUJ0@+%Gbmt1 zSnk&b*_ZHmm@ZOa{2UNaH`-u_s){Z*VHD-5PhhbcZPw;=F2TB(iBW{RoHGqdnlhR* zJIbyK5i(R2CQ?Veri_nN#Y>AvYQ(a@7_*#;T|vY#a^=G?C1c>)hY$}EU>(ZS6Z)H! zwrGJ@+u_KaEt$*Es`!^Tc8W|#VT8rSQsNKC|_rlGOC8m`gW@dk4SSo%;zW1IdZ@%ANikfb_phNJgTAzYz4Mk$mWKETYYMiE7d=D^H$>%jk44d$jtD(vL0M}oHGwfy#$Xk+w>D?zc9>%9q$^$>L;zGY3=_~YQ z*u~IGStF&>>W2iS&`O_4lE>0AXvwK>a(Jj=hGSOU3X__Wq%2lxL@Mu5_E33%3S@VJ zxynI`3Ub4`Gs{@&_lv)d=O&J-e4UY zHj{vL=M@BUTMaO^$r(XB)ZO2#;_iMK-E@HTATHz}r;TQJTOg-CLjB|Yf&up>PB(1B zm*%6)BZ5>gXa4|$Pu*VxzxZx1-ag`BGW0lqL|5tyg1_T2*+GVUB+U>;3-^~!LW4YM zhLqKQS&r8V1y|N!Ec?FjH>aMx?iQG1yYCSFid`PO!x5pVJKuZvmM>R7lL5!n*nIoP zfZ4CP7DYu$;Fyda>BT=d6j4t}p5D=#I8k4$&YayEh4>>zEaLw1q_D=8*Yu4esSkqs z%}$qb==b<=lxL{~H6*>~$V+a{WroOe8O-@)IZp^=2Qtx_o+b|GGWKxT`b|HAHcsx6 z%}yPjW$_9Tf-*qGHT(qXR!own6SFCH#8wE<9LlQ{-!l+0$BU_9W>IeCsA35|1~d(* zF8ARif(=T!UlGiB0W<#qm@N%=m!jBJPIH!~9|N9c0@4&c2z)|hm#t?Asa-)x0J7VT z(2}-sa5p=Vfy8m}3n-APSPGl?x*D{kipemkj$;zyr7=q}-zt?@vIi>9m@4Zq#4?b~ zydpszuw|Ym$e}BI96jahe9>B>n)X9I?Mn42?o?Xwd}di^q$CmDk&+B-#44oqin@9& z2sLcO1R#gBSWtYCK$xI(_GSbxT7kr5yb`Og61%Co+2#~ehqPV*@JjH8N2vfbEzu19jdrrgJ zbO7{}=zB_ZJ*7DZ(sezF{sgZ;^puuy1G_3z@?}bu-{2|muJWZyl`2%JUXr{1#^rU) zr%6tdrDLQi{{X{3x~1HI;ve00g7S_s=84HQ_@(}%^*_4947)R~Bd^^S8}kHx9!Q~V z?4Qh_m)UUjg#)YcxZKu(w?nJ#)?jQrzUYV!<9BY?{LA$5)iz$bJc`xL_8ZH*xaWh0 z`@Lg(le-IfP&zlUnboUZ2UGE(FQKw0G%r&bRCE9_&Gy&IELbKS*>>l`Sv-W~Jo)V{ zuYM#HAIIf>fo+O!R$G?lqwsu!QkSAv!5*V?<)Zgy#H+JwGSX|Y{mLoP_~sR>FA{=g zIF_1*)WR`wUUT|4E&`0qC96=<{!|qbQ)Zb+%gQk=N~()d73M9*r7L$GVToC&#s&VK zNWu`5XksPLNc)fiCZKG+O}yaD^Y)>t(F%7%!PnU;;97cK9IV&?t{@hV`0Q{CE60LoihlNga8}p=`3iE zbK!7bUNk%tKLjzaGUhPkbhx%Ejm_7>9C}WZ$tiP&%f9e&E-XCCJcKRF3#`#DT)&Cq zJbnTH0GwYnJ0Ip`#b*c325*=D0L4nb@EB$-J6&dASM&M>ev|aAf55BWWgNt|*TgaA zS541ZwaUJ!NnJ51{>t$%`=JiYGJK#x5%?U2qcU%+;Er(&+e!JT;Y3^3I=On&*9|Pq zzUlB#EohY%*=+elYg{vVckmHLp_$kQt|-OtqaEcLsg79c-if-yFBun|fFPmXJWA;iP?j9TuYlCK!pzIJ9Ry6plZcQmAhWb}(3Z8gnMTt$P9?F$ z%h={RY8ek$YFAK-u6`^Q%9ef*1{^d*hfKb)Nj9RQ7OjFLGIu8nPNGz$tW>dEe#vsa zZ7$EOshP&-8*IoJ^ozDc1|goaD<`D0+oZ3KJ|7ZVyd`q+1P_}l;i=5RP^-i}Gb{_s zaoB`n)CduMWvE^v&SPw@Jbm!{=mnl*^{O-hm%55uRa{TJGb*?_(Kb5b{{RtJkkeHV zHi0DV>Pk)~M;L{B!RubIYj3myXi>ys^&L03xT}xm79Zs;d-p>B0Le?7d16pg%7mYEfL=rv1{FSnRkr68`}31^)2L zw@jfxX9ws@{U_;H{{VFeCd7+vV1Ks{>F4>A{K@`g{{S+7nLo^r7qI}LdlMdoFhRVk z_$}*Fi*v=r{{XBPk>UZ#;(t(r%5GpcT*m6qT4ctE67o8_h?kqsG04Mk`*RZtTr0=c zU6TyL(H>@%b(o?7u~!5N+}`S3BAh{6v+#^hPFgjTZB8Z%t5W_HHwyLY<;)|b^oWoNzf>@u>(WxM znE*RoVB9EHVW(LtQ=M9)ti=ss=?}F-Gulhla+s8WAGVl-UR>@y$ho(_?x*Zg-bT)%_H4gUc5b|MXmH|1};w0I7%bm_d3dN^#rQ2 z@_Cwfg}{D>RC_(*v|6g0r=ec6H?F?$Uzg<=sMnO(zbSjIMbvuh@}}K@b+MuTqnVWn zz6?(Hx5L0a%@`)|uU$DP}{{VPb?>jsSX>J>mbpDt0AEo~Qyh{C}WkMjU zyZ9cdbPr-X0qF$jO8T8UpazOTIjOe`%286qN|U_K;Nd24%0Qeg zvXPyo%UDkXjf|orqGv2wGJ1+H7sg!+KVlS<`(fR?x-LZ zc#+4IpMb~}x~dk%PeFolWy-j$G-AwGCuSSLO-33KxaJ1#RaC}==#P;LKaPKgI{w`6 zZ;4^($aBz8G2VtLYF>NsA9vPjCsYClbZ{`CQ+6(@q1Pk*SpNWPIuE{4wEEBYVg2kw zOZA5%@15y?p*-#_c7sbkB@(^`9i<(nCOP;J;#C-P7}4!C{{Yo;<@`ba0PQ$2gFw1L zYknV;EbGXNw;^58sd%bQ%CgbV$cXgu_d|{{UgOZz`$MvF7=%}#!nVYiC7@TVd7H(Q z_QgV>$zp{*GK-KPyqt%<`w)=%NNwE1+pM#ft<6S6nt#$-r)k!LAD7l-*K7jV7U>#N zJ!1Fh++IySN@F?!XDg)lAA=Rfl=boR2>nr*9n`Hf`pkf+dmr5!kNv~<-3zMbxd_im;*%_8ikj_Qr)91YrI5t-`tk$_?ly%|F=Mx*&hceh9`<1B}k6k3We67WwkI!c;_IF|~` zABGKl7F-CpGU94!7ewI$nOx-E%6h8GUH!MH6W4lY(eM}1h>XzXI9L?WgrXkh3`;W= zSg!B@w=$)Ip{kOQ2=oyhcp?pTo_mZu650o>trj58C9GJMYO-zx#Eqf3rHom1xbu`t zH<>B=Y*1XKQoj%qTQ5@A;p&2lo%6;FW)!j(KSnE%<}3wYdC*6!=X;UevW+`dp|+WR z*+cAxF_(#8SJf`ibx;DBa*%Y(q8@}g1LTQKL3jnK!ZT_WDk5`ZYK)n-I=sBFdy0&%2CkL?`@6 zU`_|G%2%EucsOB^2D5$Ki#)S|&PBdc8QD$MFgk zUny$tYz5a9oZIUyS?ON~{?qsJ4ysXXmo?^f{+3mIPtdjh0BHmFZ&-_*TK*9XBTMRP zCC;5=jVv=&p0IuW=P=B_73xbq&X|K#q{D1AYQq<}3F9HYk&?+5cTwf?CX|vOs*4B! zV;ssE)XVo2IlEyCxm3l*CohHk8-x(W{13x&yTPc>DEvzAG=vd*xWpi?aVoYF;By~~ z4$%Jq9VJF!^qS{q5pS#Tl_n}Z#@NEHnNbSyv&`v))E3Kd7#wO^RJLkmfkP3aNzdX2 zv6d7(%1E_ZhXg4WqD(wgqL41kLSux@`#H|@wm;Nxim6RaV6}6ZY+8h1Yh$L@-crUh zUnsKzF6w)H2{4Suq{wbl20Ho8KJdvqLjc3324zt-VKW;t%DDE z{c$ebzT|2#2eT+YpILTgw)64)7g>*t`g|u={5m}bN)_{uv0$%;#Tek~5QzeU7BqbZ zR+JymQC~an<^Ten#!zWkH#XCMUeR_9Oz59jLzoglej~Bt{{R-{%lHQW0Q$7Fn{GBL zQ@_03OfKhha4HKD9n-O%Q6Odu=Ac)?onLwR8RaX!Va0p7*@>G1z5>7QAH9NfQ;Ard z%T|9=@gJj){b6uaRS(?@i%gWLBOWB4?nAv?IzWvJ>LL^^sE!3piW)k8nTVbfQ zKx>YE?0P~0*EMUIE~OrG3>PIB`qZKv+^WzzgOxg#CH+%|GTh2xTE`OML}@pfOQutU zt0eMY1DoQZYGblX#Hh1SdV_FctwUk4yb|F$3DQ}@SS1V-EKtno(Q&sl#%8fP4=;0}G#&c5kG3|aI{gpQM9q2YPj@qdWmFPU=4 zV-cU2E*=u19aWd4AI!N?6~>&)E?l@=(MG*z%0ig6i_Z7(X3K)r+df0-G)bMM=o$J> zvUDq1kn0#K#T7QQ$;1!x=UEySBY99>&FtenCFtAL_$})AB_ds&Lqo^@Rm+#~4gUc5 z>3{a0zniddlOL8*ckeEDez)L$gunW#YCjYAOH&q+l`uyl3oaTKIv6t*G8u(6ZAUBA z5|%`9#Kci%<}Q-DA$AQ*Lh!O&2=9E{rE6YcOWSIeK~5WmL5S;BLgRj?Yf5sV=79ui zZ>-i_Mng$=IAW=}j;=dnONF)kMg$DVSS=eHT&El-Q0ikwg9?r|WfCvpc=Gb|4h$pJ zOO)H|I*{yYVU2R5THa8;M!^GV4k)+Ev`4%(vk+O{wF-HTqo$o8T08wCTI!kNSlKO} zGTC+=<8i%ULFqKQMIm;A`FxnRt4|#e?ch81#~6i@d>s zYYwsaJ&y3hpDHxN2ckW5Ec9;VcNfNRp7oPVBa0rw18naIXK&bMIMh30z51C=x_>4S zuXR{8a1db*1e$A>gr@kYImo4cc*%Hr+Rm%a#_sOj~lw12c2W!PEMFg zy20%qNHt}i)AJEArdR!CI@iP&-Jb)wJCnI7#HTa4D(WCyzL6DHB!iQwlBR;(d`uqd zUCABq6j94lVIIG&CFyc{)gfEz?7Nev|NF5TLp>Vf&lyNYH zuHmb}b|Ez6CEUW90OR>(to4J4V#$~|k#$}2D_tZ0Y_=&4v60XcQ zTb5dd#AdOT4Qxaet8#IQ;kAdzEuJDpwTII495HIWzOQ(E7_a3+czKs`?_1;lUkAx00q9kO$2MC6P5) z9@)1~9mL>GFj6mZkZ^gNUg!?<>iTmqQ+NIvIOUd1@(Nj_VV^MzA6%IyZ+{NYAISJ)iWpN8zjJcZpO))A4Oc{Xi zQ#kG76=l1Z9L;*mSY%veE)7nsvT=nd^|)sH@`Xaj>48JE4>Inqs0c3W7S!M;QK6c? zEtrk&n}USsP<|?vvgM?SYWy!8di+gXrqI11WSy+EM*|#J=A(uqc$G6{s->Y=Fdl^} zsc}Qe6SGR|6?ibIouiub2_3yNj_7kyV~Jjn4FKa(#U6kre3z_sF<{+z-_i^0splC< zsH)}RhXyq248X*wW>u<k#d1P185N|jl(p8@lEW%ax+bgl`&JtY#ejChrvzGsm3p3%&M`#u zPo&nUo9Q{};!$$H8L7R~JW(9*PnU^De|Y9lYySXZ<-wOP{{Vx#IBdzeS1qC(z|NlV z#noQnI*ZdO!wCu^U^EaGuX>8!ri8MWdt(u*NV>!5{1k+tOmRIP;D_^rbvt0F7 zDb8A!3tyZ`Z^w8Bsmc^u$C*jhuJOE<44R2^YV!cw>4#|5tP9x6uvaB)n;z(`M+UoL zR@0(2N;zg6mRgyDN0EtR$py-vFk%>@o}9w_GTcfx&%D%aQQEeQ+*etM9oZ-?(QKhs z?vNM0oW-zPJ!g;}Cl1qnCD<~#W`mxPMb(?OW=g|Fz@=%9M@UIe5Cd+qs6A4Rj>&%J zjsD{O-00onGx`GZmd)3<>=OPQ{{Tuy_g!L`4_Yx*)WLB70O?A(O`O2EDk_eDYU2HC zQBnxP_S`rIEQA6${G)}q_&))Lrn}50)l$Tu^)Qf8%@K)fkBGE8%inas%@c?by0n&Z zs@zK9C00)ASc(9%5Kts$X_ECkf+;ClO$5SDW7bk?;VuVGVs;v+f`v;0%tlC@RfkEV z(PmgSx;JsF+r9ahKa+@Umg-nOJiy3s>55>i@hAzl8J34YTJthPES~=WsJK6hVdiBP zIF8W6%*o@-%VAU2ii6j_^2C@ifGK3KGC&R`${`g(qKxr(rn&)KpVHxI-Ycl?YR5|3;}jAu~hF- zvp?kd#|^U3dyv?o#AB60Epo@qnFqNj)*dFrkzj>YC^E4UzAPfPqG`d>a5pbWsde^@ zc-M$SW%!O(26#vl6njjzgEd7flAzvVI(R?w>Qt#xrAn15RIkuH=bZDNbIy6sIp;j* zob#S@&Uw!{=RD_}^PY3gdCxiLJm;MAg(XV=0O0MOvQ*ygWh{7A!yw*Q(pU_Js}jT$ zqBE8ql`LVt@#s^Db0EP*-J&q(U1cR3S2r+#4UB58Gq~If+97F?#JKZvTnm1nw1>*5 z?W$_EE%sI@o>#9)gnE+ppt{YL1B^%@yG3#$>gUyh1Pk1wC{Ud;EQz?UQoyytAh_f@E(&B|*FgNjU zXEG!L^aoR)+$jeC0Bp7Hocct&5!Juz^pDgHexb<3qmF5(LBdu3Wit z<@_8($i?)De+U3~N{8?Pal#;XmkE_ak4aNNQ$S@M)I?VDe06z^-NO1-Xi6S6B&O2@ zd-HB%4dtR(YTnUlpyF(>f?7H#_m+<4UlG8!tBDK=nZzQ*e0hFRW8!Q~;ORk~vFdX1 zV2A2xCh1k&qe~{(Ift|uidB3-cH$&$HBuXo#- z6I$0S7b+prKCt`==RVCSp~Hy6LPabUmWxaa%#I+7h!-G4SN8*j`bDfG%Q_c@B6Q{| zy2Fe4#|!6s9;{k1AosZzf{^PY3h;1ArXU;P(cs6sgM<8z+!3zt<`7@8~{ zVz2|%Q35d#x(5#lf)v2Ql^CpMQ>g|Xki?isu(c&o9=_6cA4vtde@G}bX7dVojjuB% zk5=XDby+h6w&l{2vc#q)O+{}F$4!W=FfCZx=4P&Mn9{m9>2kuTZli|b${vbyEbeX$ z7%8}GS)}S_m&T*D5L-%;t67-RE2OdAXo)K7g*1s}oh&xq8*{lxcNS&}hb_ke9owGD zxs;$fAnV5Zqa8+;bVTV0L6~s{Kac4>+$2(Ew7AZRx2#N zGPt923cHA1!O6M|Kw;Lohq!EvE?pt_ki#q|Mci!HG^R8&-ZhETz^Y#`Ox(kf=H~)x z+%6@y%r4QPEi-qN`z2zN6L#(iuU$c?H<6W=?&d|!0ujesa~EhP8`OHZ3Bog16tQsI z8PCa?Z#)9zb$cnORoZlt6lZqSu~Tj8Uw&O4H?K?1z;}ZgePADcJ@xVYh0riD)BJ4U zpQ=1_@6qIs-BONU6SzI4+VzNU2)_Pg?Edg`o6W&p`%F3h1d8@bgN`BQ1_KL<=W?wx^X7xM?em{WeVXe#GIp1g{S_)yuZib8{vdzbfBgq6InDDb&0c3c z8E0@rX+~Y)qUu{3)3R#;45&zbM`XeW5X@0Gh#l}shNxe67}T{uK)c0MPVe(652X$U zPYCr=a+@IG^A$sPYf~N*T)`2SaF{t1+m4;K}m5xQYBOeli+~KJ276|7VWpI?C=tCz?Q)G)`(12Ka!PyqvLD|Z= z-~J1iE??;sP75T6#*qu|7dn zj|(Et;g_#N6zTRO{Y2>evp3rf%Xq|Xg&b7=4Na}M*sA!95q<=7wy#zJ%(5l*pNvF- z7{JiV{1Uofx4?qmNkkwS#I&MUVhQOu7+4fS2}R2eI!r1b!=%6QUeI5G@{4CL<-|Zj zpP4HBpOpLu_@99P02A;Z;(i1CPr!eP`A_i?{x|+UI52d)HAhsHm+*dU`bVvMV*(2% z3$G_IhIM$MTre-G@CWO-{0j9wOH2=4iT zYxILE=T*mK&oQ|vO8i%Qt1Q$4H>| z++1>&v{7QlT4t!$+B%jY>x^@!Y`wh(31wEcG1*c8R1uq$W1lQoP@x_F$0T~wmJ#Ae&GiCux| z5aRkn{4fvcFTv`nf`-e=hcYC@b^;++MU|Q6J-0#y8^vJtV7if~^Rx4_f<0ya4Lrka z6s$rJ0;hE^#4E2!LDr=67M_&|+Ii_6F&r@|r>wdhGP1W7>dsVhZe9-#VMfWGw)B{< zTBNnHUjn5=F~mgy19tIe;lxnAFsi9{mJaT8mApClu8?e zx*g((+~SDe7;OlHMw_w|8ugT^6N?d@O1h|9xfrFm;j{0F;#UUxP$MbUk0F1xmFZj#;GXDUK zw6y$UelZT9V%zaD>!`G@5;;SaJ!-#FpVqSB_Q=K`Lpi(4Tth|ZiNS<7=8=OBB&~PM zW~e)-R-GYDdQ!Aq#2gXfJAXk@L&B*`H_n#2F^$nyJSd9G>xm21_K-*+3<|Bmvx%9?YFjW2IXLMU;_$)m%=^y# zKlE?#{U$zt^ErMe{O0C*O!S;ni-(nb8L>r#uyHYcrhR65O@GO67p#F8yu{D~?iq$v4&zO)R`)o?IH?LmRq@LfxVC)4$tjE{B1~-w+vqhSfQmVbB`YqxiSzJ!;U(P#6v|+saMdlIYC38{7WF*EAn4$~0 zO4hB+L5s^!x`9E!^I&QQrH2c9dW#c)6(hX3x-h223#At^P6*t^2%UrLR zZL+s37l%x_@XRu%8Qici_KWa6Crn?7N}#3i!9$7+S@}UoZy2QbsZmzJ=5Ci#?*!RQ z%qbg=7=00eVcvM>{$ts#p1kG#3-BLi_hu#q`@7HTAn$N7c1-f#=^Vij;}Y6_wqdj@qndj0ZZtGtVYzJ03(Kv> z+BI==+$G0Ar=|VpcK-nRjV3_u!(iSC90y`qIn%VOn|O`PA827$?K)Qyy6AkNg>3eY zg$zzNOa_^EftcTvejEgEb3kU;jA*DY_SaDSt&8>HscK(Tj`6hcs!sTB(g=)_g z2oB~ZP;qhK)?+a*-ZdT~8jFPUnT?%Rs+bnT&A^)Atoe#_RN`?06|s(yp%xp6*3N`- zju4{7^D{SVP#8`5nfDlMoJ1Os5eawO6mfi$Nd?VtL7xw^O%3aPts?kT!)iVj0@UT?mz7W z2$nfuog^YD>RSO1F88;?Ata{BLxiCDq2>y5`8c@M2H>HVll*N}b9vZDB@`Jn<#o{YaF;H#84&G%OuBTO+ z4jrZqj;evP+QeL;nxLUKXA$44-XX+ESgYP$Gro+x6;fCAN;}RHFQmd0&oeZE#8k;1 zl`g1dkC)nGbW|)qIu;NtTslgsMqd)xgkW)bjZ_-$nBy-ohPjQlGYhKpVM@`TSbKFk zjh6lqf^W@m770&m%!kJ2qH{6kk=Kp~g7 z)qq2Cz%830V8sjq3XYH*l<<#fEW++_+ z(8!dDQuq+R=4R{Qms5IAtGl+-{MwmI2Q?Oc_O%C@|;)7 zzfu61ZorD|M-LpZar?4LLYP|$ovxZXui6wj0I<1kJ_H-8_0(RKxa}yTv)S4;9Wl%p z%96U=tczC($qJ6y4C_e;Dhirc6p zP$U*w?(h^PWP8A<6u^UsncflDVu#F%V`&6d<%0H+Pk)%KGvkQ&VOS&9j{!|UGv*2c z!Y#|JwV75Oz9qosRtbV}B;u}&rIQ3!j#$F=A9=LYLM0d4Rf-Dbm6zEy3(!mqe{%u4 zb21lklT27kUbO`~I_?8}EHM{$Skp>fYS=w&UbcQr#mBV8$FyqW+EW#ou?`x!USkYR zfX=>u=+&*%6n6cB>h}-$f>c1X2Y3~h$&|Ymqh;_*nsyL}_~l#klqepKt8$M0P7G1N z{{UIbnO2jD!LH)$zTgJVF!HQ-tit16vF{F<_&r7peI%U>CUF^A({$f)Lr7a zOr7CDs04_CSc;rlc_lt}$NGc}95|GG>;nNqn(9)W8f7>_V(F|)KPo^(l!6SgL4sOh z*~}53EJo2nRKhklh)C&X*5+4wRl7!5Uq_`j8%;zvdupuUHF! zRuE1puZtK4W3rx^p%ySq=9aj^ac_i;c@4f}uMx~@?xYISL(H>}Viw_FNFF`R15<=k z)Tv{A1Xcm`LnJj`Nxj`0lMy}NFlv0HrnyGJ)*_D(Idg?a5OYBg>I62saVa!Ce#HDU z_=9WlJ3+qh*&fjP{fYj>zu1@i68`{VU+hc$iGQ&#_9gzrzu1<3D5wM8SJVskn;XSs z^qX+9x7vR@Vw2P2P!EFmIZ?{3H^TKM04^X61x%_-DBe9|82ZKYUpQp2(j6vfcLjVA zBjp3cFb?e7Q|%Y$h6k8F*gR?&s90qpfL0t+?VqKP{QHva~uhAsy(GzKgh0qL;$v1ViLrx6|Q1I)6B_U zV=ykvu$xwHV?cR>mPR-faUHgjj9Hle6kVsR%mWA#$~{gVqWI#-rB>VxGvg92$#bS%9-&2dk9sUNyuk%TOHLc-xE?62*@&69K64;?m;V4plk@xFzxb7IQrTVrN=cpR2K)+4Jcr%}ip^fq zvn;RQ7msK}K;06Zs-kuLGTu3tuou!}XNGF)71@E=PB68Ib1V#vMXfA+MS%gy&uLh} zaO*OoF8DoB+b}*dna=JK<5gaUrHYtTp$kjI$QLVM5;1MMJ4&fY?mNt#YVW|ojKZ6q zmO=d_*1v=S*UTGKzrOmo|f^ zFoxtBbJk&##OCUMh!rr+q4%fcJ4$veWt?}oKq@#fIk{JLsikpC+(W3|mNO#jdiJ~Ygqlt8=#YJc`r|FkCX^1ZkO&}mco}hYdOV$|~=$<7yy%|MW zimtgz+zQBT=^Df3TtH$X&YGF0KruAOH6A88`9~}RDK20gC@nb=iP+e~EzWi@Vf7`7 z{ppp~b5J0=d>K*%)sdT@a)OrbVN@MvR7+UY9K}2^jcB?$o#3NTZH1e5@!*s=U}%>` zpdT{?1I+%%EJau`o4dP*6f<33CkSR;0@#xX=izLuV^x&Bv0f#8V1os=$z~-)svNwm zBbmiVt%FkeR{X`VS4l{4kWP~zTUdj;-`UB-Fv{fT$#i`TeylB z6G+<*F;o|wPNGI*G^1o5l@Lg*zo; zl_SI^n`yS4LQTNS)O46wC)3E|+5lW5@O~4yS=((tIa4Y;*&?+;OJl+gd(m+zfH>dF zEW)FlPOK=F@9TYGXLWMB@`{CBam*bGZA_^e?-%VV=X9;kMtzNyJ|is9*G)|d4q~?V z)nQOPqQbGmF|7ly5b8J?zS|@J0GC$1Gb&O#Awuf8ZMrfEiO-B_{G(G&<-;$eEY&=~L?|PfyvkS1yxmFM31ChMO&1A7#&S0k zZtlpYwl&sRa#Ev2-g6THTjE=VxMHYUC{a@I!=nl631Z3u+?O4t6G9YfsAfnOM`Isi&)ed)&+s08xrT7^Z1o2RH;(Gcc9%u(axFG+~xlO14u7D!Nf26x#y&I zq+zP6-&smq8!oS;v}!ed_1*i$jrd~V-+3s$_f*=2{Dce*Tca}-N1{P|`6mZD=^cAQ zlhd@p*qojmOu_?^8$U)d(d4OHx^373DYylVc62i<(((M(F^YA=FMuVgRXiTbO60TE>vV)Ra zR6z}hhl$ukx0r$pV>~fO9Uv(8Y1uKue`7Z3}!2jh#2Jc zYj6o|w@Ani1Hm7iF1kQsiXmW~Pw5P!KGLJ+R(j*IOorh?9w=+zRXDZYT3?wDRlsz;{b zN2zWuE-|BtcwQymDMy-D!oaSxEeZf3Q5~0rOBSTIq}fp#2C)-WbyHfaoN74c2=9b7 zpOm0?Wo|vBa;&S=c9sk;q|GfSHdk0w*})`Kgfx2MWd$%SaSt)n*KTFSeu<>(2205- z-NBVyNpCM?M`_W93*9S>WZy75hi4xR%l;faKs{pNaiaN4D{Fkkw}Tn5o&Fqmk2RG< ztHbTMax@6hHt#w(ehG8wDjni&U&ykGwq}!wctm$l9|zj5!0P}EaIwH+Ra?;QD(LRH8M6h(Dv zUOY@CR{sDNkdg;3AoW_=Ni9vypCV_|7&-jspOEfUve<0%G-tSFrzwbZ!iODC_6-+? zT#nY}pZvcoiox2DD4^17bX{J_x_qLwYn;ReZS;sfl{S|6n2lvuOhLe!hteX248u9f zG9=_Ksn97gom(=Pc7(NUnW5r=iA1qSh9Y$(sv17Bz-nY1UZpVThyj)gt;Fpr+(13? z6Fy!gTvowB&o`tXLkw^@^Dc=Lyblmz&E`KEd;;zqMdZ7edC3i35ZG7S;c|gzEDu6e zePeveFjgoi9`j4J+E`cX4ly-Rw;HG&L}FcB@@^I_o?!~pgs(dAKoo2A)%w%m^Z1o2 zRH;&>OcmyJ`Aw{))N=jy8UdB|n+6xuyb-el@&^Rw`*;1wQSb(6{{Ur(Be#I!QB!>- z0Vp8bb4jNU%ZQW+L~xs$Em@!y%dS{+(zOwkMXoHYp4jz|OKgYC#i*;Y3MHaAnD8NZ z9hgDVB{@!=slvG{^?-JHwQ<}N9VW##@XjTuodB1c^yZwONFi?aEUnb&V=aZs8D0Lz z)}L}MGi}OCna3J|W>ua>O1EN2dQ4)47)PW+!LnW9kKIqg@h$ zMb1*_CR3QVs5)geanXh4j~UgfRBPx*$9`r`PBPt zL=KS}J;`x}J*8I8_<)H+Y^6jn$|*}h5c14V_6LFLivgmY(g(-R50mE*arJ)W#X!(cB-2tgMRTS5gwnHW1vz0f6fR#b=6_Z*L?E5GpFZlG=*$!>qBx z(pfDvQ3|n`Wn7mj=>US(KE;T$YFwS=Q=CoIr*U@}+zAACC%7}XyE}p4?(Pz7aCd^c z%K%{*+%+%>9xOP4Jj=UVTeY>-{o(!xy6*1ZIp?~X=!vc%j_{`l7nzOAij!IyOVi|DfTRogj5N4rI(kY}d54Y$quQ!hM$593$g*nH9W&Q@0lFwx4Mz ze(4C5am?y5uq$q2zX~U&dCa9=3}&cWILCo;!U{M4)Oo;SxaxlI=bj55;E$Q>fy~Al z1=!6R)LtgeKCf`6usPc*VOb*%+3mq%VO9B_VSkS6@pQdOp2ymM==LNt6%;2)Mr|fd z3|el1oj8~2nRMq3FG>b51-y`XJLN-ozz`uXX6tigvr5u0DyCc=p~Y5kAreG}Ztep0 zg@EekJ5{p_<|10n!=Q*O&zW!I+`Yb-@j~B=P|8^spsv?sk^MO=Um_7b>kaLe`%a1P zlT6LDI@(X)8-lBSx9pClwTtZ4tgQ=Y^Rt-ni7heW7^wP+c(e+d_q-E+yrhsive@L< z#2(T_#Neniv2Tg2%=Y2!8@`V=B8QI7g-UwA8?Z*uG&^k}zdbft{Oa_e<#=((wy8eZ zA2DWlJbI4~%o2^43}u^m$6RYuaT*kb0u&|le~y_{si`I#baZ!g{QO?{p+z#f$<=NT zJc|5{t#H)N8HaC83X(}yY!J^6--Yibe6VPt?`-5UU@~GAQ#bkt)Y4aA)FO`>ovG## z+EzT@qwaG5=9E@$UN~3oN0(?nS8P|#>zDdW%8t3KXb~0f96vkGKfB4Q-ehA&zogR0 z5P4)#+4m4N+rk8FS0w(G#ksm)~~xfvT*Jy|*7IwPru&zFV%VjCSiF7ppgh-Q8v8Xm`khYn18%9Hcuyks;T(*dO*1__slf5*M-{Cm59aZ2 z`P_6pc#Hn2YE%iAK-x4YiWz>84B4F!j@DzEDnkxq;*NvRvU~nUU-To#j2D6DM7#k~ zd(q1B0HwM%ce8efd~DQ0rn@i}=NDO?4Cft=nSvy^K$vS!{mj^S`k6Yo_fNX@wRc;* zRDorrRISFaWali6J^(s7Y~&KgOG+FFwqfyqN79e2MAxmm@o^)Ve3t9=5boCDY@sY2 zM{$8m`_gFV{W75ybyWpMqJp^~g$03_HaL4Tq;^A*ey-Uvrs`C1oITI{JM+`X^S$Lb zI%o_W_r=xm691JxMiitN9$1#VM}%ao#j_Bic}1L6gpd8x%P)ocHeW6%Wp}5O_nb7( zQgGTm{O>P@Hwkh%TvZDe^ZtgM&foNf8=Oyd$ewyYyJRT3&SyrW0-D!;?4*DgOf?+$ zo$uI%Dw<{ZIxSfQ@B%xeOay4 zwn(!cN>)oZ=%_b{H}!*wwN+yX?`F77Ld(3r!g>Y~Vq+yd$S&D)R!)DC)S-BW(VzA! zWI}1h0^Q|Y^X$gU#|sa;TsPf~Drb>UM#` z8G}Z4C7epfyj#&F?&z?w8%x~rO;m3^^Z7N12+@qu-1RBvM4L<+gu*U@Vs>um1Bb<>tyQ%B;cp%fiu%nxoa$KZj%M zf=~~os=3C5cTgx$ESEKe$7j{-MA=6OJ!_-{Y*42zh>pSD!_?CTrLo@~@cs6V2W3_+Hi)J6dPjeMPffGY+?R3o{ zDTT%%iloK$1EtlhiW-4Vj>U)xt*q(Z;B6@Hu?UFiA0wt)JJIjv50oaHEaiqxl`51Q z2~M)7e-d%30M$&5z{R}HaI7x*()YJ{m_yvd^}l~!gHO%F{Oi3$2D|YZu~x$xKk%!q z3V6OCL5#^jZJ&49G?}%dffc=Ge`ij%xI8chHBUL86N>fZU<`IXx$2-CE#)B(T`@+T zLP7aaK?@1qZkxs?vzr#$2)#5a#u35O6fQUSf@d8C5)u28`+ZQW`dUR?vyT?j7of+W zP-N~g-^@zY0T&??#6Mnyt&Vg(yb4z}Jmo&8#oqw$t1zrAlV_UbN*Cp`sI)4&_M(Xp zMguAXmawN6y60WiEy2<*gyyv^*$f71`DF#~{?UE#Z$VDnb*>p>Z~Rf=xI!@4&f1$I zwGAQ#qbVO3us58bGW`VzjJXRJq1Ak4ifbIzQ|0b_%ubL$(h9-vVs;m82gOv|E5INs zJsFnCkZFV@E^U&6)bE5DZMq>X{7&2=^!SKen8{HD6_k4!yP7Au2wBh=DDl^$#277~ z6zF>J%pdprsnHK6inDMVeYrMfbXJ7$XHfq<(-HY|g&m=P zH^M=Gt5oCg$n0Wa{%+c5x7R_PTw;&1jePkP%|6jpx+P1xILJQ26O%*|%X${~F{uVC{L1Z}SUKTirH1Ne*Z;)%zG)I$ zOspsLA``8H^H9q9!)Z;tM(LT}KUi3z4IrplA7qD-FG5zBmRFP>rd?!xg`Tlk=gOJ@ zGr!?7Hn(D_u{$GX7Ckcxdi{wJ`yRdVA68Rx^qezh+(q^&;!!Tc5M3JIsY)eS>dGel zjLS-mFyc8P_1mBL@cv^TYB@K0C#UTVG&`$mNHv9jLGBowHbr}y7QRbs@A@Qk@Qd3a zQ^*K3c}1~PF`HX6O-p>wMK@g6-WxW1NyiYaRIb=Qi%E{CWLaTFMK+3OE- zBh|ziUPU&j#E!XK)17=EsKLa>@+rvVwN3p=8NcYRZ)h8Q=ogf20WN()&Z|~T90uJv z`BXl)tNe|>Xp4R{~B5)VvqQgV8x0~Q>4Li=> zT^pX$>zqBWKK2ni?9a~c+M-=cbM|Y9;zF{%siGYz@-`+PS3oZNWh)w$0Bew#MC&+V zJEnY6jDc`zWc3#wSlKuC_)RolnZZAkWdV^aV8{+b7VnuByH%5&{!5OMV3q;1GtXk4 zw_olfnrlyOR&DxFF$!~`*4-#xBuW4*y~DS{+{#|$6$Am zPUNK;_?To__gG>2tW7(p%{nv!BlqovfIhw|3C#v_69(g-ae$%L-FdNBTRI~xB5elI z-*!s*qu50=jb2JG@Hqc|3~JvZF8zYFB^!tK(;B+jat_bpwsPESr|`37%&c!jNg<7< z`8-&aq$40$;Oi@rjEBD}P{})d*Tdi!3?ncg)d$Bgov`+!n)s1y%yafHBW^uH=;)XM zs5x`b;sZkmHLF)S|b9{xva(7U+Kg$KhMaV64Sm!7otXv|g=%Op`b1`T?-&_b0$zkz7I2BU=2j`$#*I%ly zOTLtyTWP^5{{;H;xJW@ZWV#~IIH{!InD{4OB^MwyB*Y;@%z%aIh3j)Kd z{#qCA63O`0em5}+{-s)|SLN1r{h*r))~xR8D`~L?YDK?S&5p%8;OeXd*AL_K$Yf0* zF8Rwi9BRznTqigde7$WRIBE7@?Fii27VeHQcksCqYYtE-?C+e+vIq!nqJEF2tsJ+va@b!p>?3>BV@lP~I-?qc=SRg>r>`Xz)!GbtQpRJ?Qfz& zD(SW2LTh_x{Y5SEl#E~>##MOqdLIJFj!R{0*)Kn)c+Ncz`i-o*m9Y&-5QNk2xc!2v zb;ALl<1gbl$nE7`5?7v$?Z*<;ka8nk#7slL6}uK*wt;7L2*W!nb$7K`JJs{tW={-& zacx?58z5zb;?5qqVbF>0()78?a&hC#5Xos_lr_Ij>1R;5j(6CfTul?gg_wa}^Tqo? zKTz^mSx~ zbr+)OYN_BJ@k~;a;YeJu$HebALT|k*F?xS#Prb=}6GVF_Dk9_Lzi7 zB-RNVoz_*o0V~e70Ht>f;Z!07`5z7)kTj(#c(Grj zOiZJW_{)C3+@+9Hu;6~yAKsOYSF(TA$^6COR>9l4)v2_|0g69EM&CuEbYWO+*{{eJ zeBxwL>jyS`o~60G?c4;!>jd$#3ki-zhNx`iXbd4nCT4=&mu3a>sXquN+OC*y=Z*qU z$$CpD2tUY5%ctP2@bF^X3X>gOoz75J^7X zhRkTE0z*)!4qXA%)0-Adf7-##6)WZgrhJu1uKIDy!x?DB<0pDAj8dar+3v-(^bL$0 zEFCZSN!|u`cZs2iVVPscE!~vzheo7cz&Rk_4+)EEOt*Pa_2GlaAZ(gjR!hyZj3%8X z3;exHFJtzayxauu*Fm0kQmoLYQ~Rrdvb%=A{i=`7Cav+aUjc(0$6#-TRh{mEPvYK= zdWcplq{$=eoWptPab>2nU)!UNv%-H({pE5WBCXwgw@}8r6{c2hO>l7c|2;ZfFkkV4 zuj?{?ewGR*8uy4eQ~n7W!w?|ZI`HQT)g@xB`001gI7rHZzI%%XF&U#)lh)k|c^{&j zMz!98^mo~@EZ2uOae|WmS)rtG;VF$1{N0A*UEvpX(3Y@iRjvzRYCp@8W2HvA;N`=c z!mp{6S0F@o7NVR{CAuYuhLIPdXM$EW@GE-iGnRD9cy=HjaNICJjeq!(iDIfvYZK$? zkrg)^nQbj{q6dpNa3?dIXG<(6`qv1FSLvKTx_dOZ@=c8Xe{%dAERgev}CYlAwr%*()4>AHev^ z(4Ho}k~X_uKu=!NfenAbd`;^X7)g3?pT}oFNEhSb#@g zpOS}EU5||V)x%R8Q7cD&#h>A{l9&PFxJ}%=mECG4JVnltj5g@341Mon{PWYLsc$`e z*`FA;qjEm3`S~PewfSeKGqB;ud9ZAVht;b2Ii?;gM3X0zlO$()MgKH&VB<>YYN}XR zCGjEhFaTM;Addm`NwbnMNHC;WGF)_sRhj6c8%h4rW@>3>(z8pD?g$*lrzFp)++vyO zj#amz$J03tzRTCB%AC!;RZtlOCZ0g<&$&PMEYbo(#Sfnz|Nl?_Ke|kVu5bkvs5c)Z zeGZ1&hyf}w?lU^9B|r%GlsxcXBB`XowGsYt<3 z<(7k50A>ceY;*d2A)S&eWvMmA7ZotFgCfLWG(YhENqWT}bv&)&tqO|RK{ephocFMh z`ntnB_c00~;x;d@VZLx#_(N4iV@y9cH~;YP(4z2={yY<0?RCDksO z6T`3EK+b|&z^c4G59QIjr+3NE-m>U0n-58flWstdNStay9_hqd*jRt3D#spy!u2f8 zP@Im#anFrWgxv_|C6*g5@4e-nM{vBW9lZD<=U0#aM{Ukz$Wl9@eZ}4)3u-Jr$|b^% zE1?LmAG~8Xefm!HD!tO$VZ^eQK>tjN8A-xnDW9?o#xPj=Nq?_k1i9o-N_CLb-;w)^w?~A-Tk_Jg_Z3yF#SYw^Lmdz`VVEFtVB~5H=R~m=P z?sDVJ{FEf+tJlpu|FeD%?iam+x3tYq1`tW2ez zXDENAA=Pb4qnoPGrQ-RfY9b!NE5~rBlSgN8e^_XzM&&MupB4NV%Y=kYWmzBW%-!B7 z6R4C+%U;{tngiqWY}TUp0t3}%>&40YvQNmSU49?xIW=d1p*;O0 zgw~|$XHVYjtE1w;yRVu53mCB2A z?lY7={JRlAc-^sNp11|rVBQ*;QiGf%aP zV~fMgyF>KDoE2bq3>*;-bzj6~qI0^ow-@A#=bcQ=Ad=l;aRpZGu{D09AcoPdjcGFJ zu0pS+`Y2@w4(jCew)6|7Kh&QxOM4K)8(QPt)LALZ^7PCx0#B~?X!FjowTmr%8B^2y zd46(%q2Xs)|5%t$!wbUa<;uX$oj5o8(^4yKLVO?X4&oL z>Sl8c)qqHb1{TuDg$_4RhkUI5vo$VEmNcQR71ii~qLR+ajns7y{ zbtkneFlRuTSrQS>5!JA_ixvu0l?zq@)CHFR*0iD*;H#`_U9wvJx?$vb^O39|i6qOp z5MO8o+4y)LKq|!I5n>r4WmeVGBKPr%GK3b<1Co8E@4YeOZBBUt z7@#Q4EAs+Ia%1TvfnJR$GB?9iZwi!H34%X{@o(}ahEoi4YxA$HGXyHl&4gcnh~eBcH-dZ zuyeK@WzK=y#mYtp^Kw?=>X{=wmka2db%C+_ea(pVTy$_*K&kCPhRSCJ>ks2h?v3HG zsvN_0cv=b4&V7o4L`HEF659DK>&H3@iHxm}pcI3fqfm`kNJJ0qSbyYM%?h~vleo^6 zY?}AeC$5mf`E)oHp99ison?;YyDX76`?1jDVkFs>=zk9$s=s9`If)h?avyF;=4Xj~ z?(J&`>SX631&MxY>dpHb_wrFfJx@{O^9h9ziO{G+cy z-IgRdowu|Y(M0d4ST{-RZZ%e`?{1UsoVN;spTu$*{&)Y}B3I^FYrk?U2MM~BXZhhu z+>)%8=5p6r-bl9_g9#choJlW4r4r!xd4HnAz<;J^;Tzhs(kS35TK4K#O>T_)FN>Y2UX~=ND1^y0? zOiPbs#I0(O^xvH$t|z(dmXj+D<=Mp%HU#{`sj%}` zuN|r0afch}3uNHT!bREU`IcCTEzuuUNz9;eA3=D=exd8`??lgl7vk8@c>b3VJO_z<4HX`~(wl zuZ!-11;zln--(li`0>`R*x#%%Pf0=I_OtS=jMSD(lFW%lA?4!DXdgS77mbAyRCN44 z3(_5Nms;AQkFh0K|1LEzRPPQ$m&Y>gg0`S9;hByJoSFN|*=^As20|8cFwWV(ED^6~ z(NG`5aJHOA^(>08xYS{)o_%D>hq@a}*m*4Jc?r2|vL526r=Vf1=1JSyB?Ikt zCSTg(e69~iiHY{Je^twBKQTg8RCBgHr|z#iuw`~CZ@KDGt5$Nce%E;(b8|P=z}>hH zUTVkd4U7cw=^aL9_w9U&FYh}h15d1AGUm_W-S+$EMu^j?BgeWP_KXZnsNmSC0^gK& zfb%0;A@;a6_u0t-=frIm)R}pF9`Wr@9&|G&^Gn9sy0U6EA^)S z_>}!w_u0Iaf1Y=E?t+hBA_LS;l z4!xW4!b2^C)$;Ex=f8?`b$m;91 zQJW*f2i3{EnLUOIZbT})qIVS{WK>kP{S)DkVgq{3bue!9x%vR^{w9uns2}r+B8Zsj zQ;DHth@B;U3XO<)2F|~>v7hM$JO?aH4d_O7)S$!#D~3qaJ8o)-zttqxWDbrJVheBbL=VyPRYTUu@!%f)OMo&HIh1;h3~%VTs59i5X~kN zYp2WcHGjsLwzcSclS+aGhEZVedWT9he2NacD=;aK$-K2uDKPS7YJitbRaA)Wg@2`r zf&}nNMIc1ZhbTCCvtvr@2m=*EFEMI?vyfQ#QQ1%RQDmvV<$l$Y8mxKpo@HzjjHgvG zTIdAGDz89JssyTJ@BLr!MSJ5@ideuC z*)2_sJ3;J~(!JajyW>6jG>&RSx9#EfG^xHH-j*c~W}@itwo>Fbw9VQX&8mh3zN9Nk zw)(zUWbuo5)m(O>9rnChY;p;Bceedbl%M8O_r;0>LwPsX#!tK_`6p3+`KjC+%{3ub z=ta$eSPcU}O7u<0>;Mgx*i}3#!}7k;>pXj%p(#Hu-up4x;QqBTKxT5o*L7ceO|n)| z9kry3PfFKio|ykwK&K=igm7e^eomAQH-ess*kwrq(WCl@#~L)x%>Ctogy)(pei*aP zLD{yA9|{!x-|HlIkvx=y)21Z6LhDPO)d18zZiW)<#g#Qjdc)jOlqLMVhHOKIhlG>a zR7QT!hL{9e=Lkl`oa6(v=MbWYXSaktzrd`PI`Bi(WK|!}o$b zMc!uX7U)5`S^+MvGUCmt@KLobKjwtpC>7}(gqv@#+UpVL9HkAZsb zfhyEAMztsZ!I4Mr03y4}$~)QcEiCtts%$}7cR`-Smm_+#1CJ&=)BHz~RU<`u1JeT!GObcIRq_i;m;<`+A}1gRlf9k# z9CX)DXQF>;`l}s>QE4E1p@|}NG%x(5wt3%WZJ)lqlCB z7A9J^v**Aqlr$va1^+Gwfk#7fF5OpeD}_g;Lv@!W$iI5{5AOe6j!_Byr;?5@N#m${ zgq$0LSx_`ty1UpR5-&uNtND*}<~GkDTgUTpHXe9z!utOM_f7@Src55#7t%t!t} z=@?n<@@1$dl$Vjmo4?nlbF?|W8^0+a+#|4C;=AlgVHiBZ8y#nfWHV6k8ku9LwJ>J~ z;h%p<1Y5FN)F!JJUOq@X$TK!+iRj>z{X)~UZu1K$=xg_XaLlt<*C@KuNhn7K-Q1Js z9nFN~XySoj-zGcx;}2R!{Adt2qe{8d>7IPq*6g-8VG%cXNAx4n#jT+Ce~GQ1`1I0z zyrjU9xX^%N1DHa)$iY(wkf!a&C}uN?(|RQ~HSoK}Z_AI&ew~d&6M3X+=e+Z}==4Xn z>yy0%VQ93h@;Nn8>?x`3-xF7m6@j|{gVh3wRUAK?8cw4QAIcA2k(8oC7SLl}85!zV zGG%vxc;(dz;P&o&I%mH0Q`|+5uHp9Yy_vC90sJh?&>~qO2`c4MvFDH&%$M)Mo|AyT zcU&lUO3;m~#8lff>7e{kpV9q`)MUZ%E;8L?OftLE!LMFL)N(3Q(GhRdNcb3ZGx7AE z4!P4jz0q@S%qNKHj?!dJcN$qQDMj_ifFIttP;FA-X=_V8Ugwzb7jl*HW++)QtyT=Hidf6 zVQi_+pFmdaj)ERWZ_wz&%gBVWv#E0XfUQ?3Cn-hxIf6vFa0IO9B3P6@xBEGMn|0rA z1v2EMXir5%EG5-~7@|J~UkZb3%;HhDP}crG(g5v>FiDgk=x;E_6XQ4_I~y5&C|QDm zlj-z|eDTIt`VEV;BqynW*xO1%X{AX;sF)6+o>`ahKqsjN{3pT1jWJk8@F-M|4XV=> zpgwtkndoza18yeG;h*Wxc4p~51@77|mgmMTP4^-^R-#*fj9ieUNex3E<>x&L-Npi#p#*gQG@Y zM&Bu7A@8}Pbsa%O7mUuD*9A6B^VCLTNTP4>rI`?4JOPCtt6~N(E-R4$_^T2ZxcD}Wu4LT&S!jX-$qd!sezd#y{_Q{s?yK5pgnPeQ3cpkwNzvgRGyFmuoM z30~Iz9p`ZqgHC$}1o`YY#-KY`;v2#K$b(UkMA~DTi3oA0Pl3Kh1O7ejRJJ&}n;wc| zR{a@mLto$M6Zj!pZ)nC@U(cCv$*ufy4)apxKvw#O$Q)SwqxHV}-!lA2`8Pri`OkDM zWF>s4%xY#jN13;uMRf*Bytn`NFM(mzPko>N9WU2MbNY%hyT*xP=0N{#R zP6_>6C^EhdU($K9DNhs{A_DrDp(Z!Ewd5rzKQT6acZ#U1f>ImSbe)}9$Nrik+mjSW zXv2LXqQEDq0%BzC8bO#x_ci9Mc3pkKmRe~a-_!JGhE;vwaSedXY%21#DbO^d<>~K7 z5DXDr-JntfmIwsN)YYrCQ7X5ro65MG!`DZBt93{CC`TfA2Pc=kgqE;T`K+1mM|k>< z?5d=!qtUn-92L&AkgUW1N&cb+-G4Ag>wKsfs;VO<;&|wd!5c%IEz=4^mbb;)E92}I zkd(mxAyO8RcB zpVj8^R_uoJj}VQDMmQ3cDZj^+^L`-oDyG$E832wobG9o(vw#&X=8K09AEoCdJDO@b znq0Q9dr_jIHojJ?4B@X-YZ#5-8Uic=->al&v*OAT@4x|0{*)71a7k@KBK`5lU$N0x zn#X(Zn=t8#E?99wuGIiPxW|3XXPXTJ{oc-N^5gR3_`Mx=A;EbY#?-~3k4E#TbLSOT zbtv|=wQH?lFx88^;OCl-wZ=&CeAv&-^s4zjog;}#L$&Ka3SIAF3~l$XaXtiz?-$7* zSyW|Ip*odXMvQ4|X??=Ia#f!r|Jp8NaMk#VS9joC{T((I3zl~KT{$8jyS<{ie50L+ zJ$BBsRHkPs9IZnmT#^T~*pKiC1o^;e!gQcYOLJB-(Pi-uS&gN4+0%H0A_z9v1dXLV z*=^c1^dD>PVm}wi2-_c;?CMtJaWik@n^cM_?ItLE_AR^`q8YPO*O=u10CsrrhyySA zTOCo$*=pQr+X{6BWVb~p&WRsVJ_RG$wAoaO+^}H0l&yqsxmE08B)f@xZYRiO^Hq6n zS#+QI;NlWx-WER9&iR}~uCBS}ea@VIF5#eJKoBYDp3BnqJ3rqu)e8^nkp<2lT2u4@ zx_?Nch5Rm7cEGx`E2j4zc5*L;VjFxlpfQyqB~&H6W7y{Z))SE2LriVH7>G(p8O#M! zHSa0RX%B5r!VfrQKE;`h<^Y*@3%OkJ;CbiF+4SyMx!(uB-)*ypO5~KC1rOQ3u5t4K zByp4@_)^o?mu|re7g$F&$z$ynNquEG`Cejp*aQi3H3Y-X!!Jyqs8bn17V!dWwqK4} z4%7G?0cajt#}Dc+)`%ps%%@phv0FAqcG>+V35K2B=t_X)`u0gEqgrzS_ z@Xh`X#eZ_VV3>z#p77hyxsg0CC-sOUv&Whj{Npc15W;Y}JG!G{#^K*0aRUaKdmn3# z;g*6%g>c$}#^07w(3mz$6EP!`JkD`@q&t$w-Uy-Sk7|gw1rvkxtFA}ryXvD_Tn3E| zp!?=Z#4LUk1}p=tLK!@m$KR=Q5}o)TQSX<9x2kUOS@{+0mKuT8tRoT_h&zpcT`pRt z(^Md_#?VWU(=jKr!v6j77$J!)D+5XPYBrAAH)Y$<1)rc>VNFCDIC-5bYh#w*@Wv&` z(nOfd(K3<7G>*^qUQ{`DV7EK{U9@n7rL<$oZmkM+m~GtoaIT^?bDddb+h8{RXbARX zw+>q7<^=@>93p3QnmS$e++P7qIzGiQyZhzPmYM~Qe-#Rle&^9ZjW_DMFyo(WLalYd z7m9QcWIASR8#I(UErW_GAnPwa!n<7F5iTIU+P6qq6R4L0ck7Wku}Pu_Yr;?^g?D!c zVO)nsLp5FZV$5dXn3^adF^|99rx?Ga@3I@ut%$p0o)arphlmfDAhJf@J_ z3!F)Tvq1IEcf40fsSikz-9S#Sm45lds5Ko!>zk?aNLO%iE+_;^0{B@Has zz?|pucAR}vmG=IaFjVE}IB@OV$=96=y2G1WkR5PVHr8eTlgiB(EKgUrR2z0z9k=pu z%1UFcwhZL;1%=tiXLoj?=n<`12yKF&`$gitsd@wG(cuP)ZrbgK3)eA=J?HY4i##7v zZP@K(69$(v8ElV*vD?m3@_~!1@=ILhlD2K@U6Llp8WAVXa?yi~V@SF$<|!ATSMnHm z!Nz?DY~?(nIq`@IvP=i`Y$6|d`sTlyQ2{vC_L<}UgR>mL-dL_)x^@NV%{`Fp;x{!r z=hKUW_(pCK+W7{q6#WVLZ!v#jy)6~(<*j}`?dWq0$e~dM-CjvuFced0`0c0t{R4UX z-X0!(@t6|af%&CRQ0Ztm54!oUF;K(EU@KSU8;x?5#E$wKI}qV?PxCjMt91Zga82mT z-0OYfY0zBzmDrB}g)uB}ZYCZ?@FK;$h|@HiGFT+gFvqh}*~q}q$AVRQJ}|SE90u2U z3m3CeZZg>@i8vZH#`>`lu>W>@-}li&*9Rka`(c=Gl~e|Q9Eka-T*~Ek{UUbd!3LSg zwY$_Mve)h7v~V5RcKvgv$@9iKka~zWqF;NK^?jM08fJb|y)C}U{}t;Tq>_!AP5xCU3`W6&g~WM?Pdh^GNa$?kK=@t%B8h;!72H-1*`enTNJh#hMLuY<8b4_@ex!fzcJ;|zLs=G} zSi0OWPMH{Y;cJv(0n=^_ayp>!uG9n#s*E>{*u!QHimxL!J$z#;lpA3v7es@K~?5GVxw1~+Wxz}GiUeo`B ztICan&bUr8-LqvU$f-oqk);|Z7<^z54ehL}w!??8egpL38-;>tMN;hpp~vaZ)Y_W>jTC2y}zs(n26g^ZA6S; z!TE>444Ao)S|LHfa|ak_K~rr(Gro_pLgs&p?9%vFPZ0&z^VH|#6J*`HYPttP=$^ID z4KAn~9&&zCTYCiDp#G_-H5Y2+wfSm8h{~ru2eLBG_W0&i7t_}$aEgxOG&KW;BW=V& zK>s2?gQf}o5j%~REsz?#bNcgfevQ4MEMjdjAd?{W{D006d=ahtvDnP1kE%q8%VUbY zCR^Xo+@N{J0`~T$>SwX7lTe>nE@xCln+u#zgxLMx))V}$zmm8#wIkz@Gf?@q&hG&j zvPWvW9heu4I<0rT&)M`XrG=*P{bqVqm(JW4h!q`a&>ktFyf{5s=y+pj~K(xFAjO z?J!$iVbnhIHwk)+1oh||8J#kgg{%{`F-siJ)b-#dGT2duo8`4Gr4&zrV;jpvhQ4|O zOW-{MX8dV?0U)5|+V5)X@7Ub6{-c#QS5U(-c6pJcHv=SD;V&7+Y6>`8uw})G zDn_B954s`aB)8VU@tKw(n#-G!J-QTb0(+eU$H=;Z65chFBT>KF*xoowJya*KPGuP8 z_5rPh5g|NKHJ^-0zAwSJ#)rOQ3&2h1hN4}aw>tTwaS;0oPl0zbPgMf7QcI?V4a!!R zQ;&H%%3;zt^BA??{hBx$l>MSmxo5MynP#TpL z6;o-pdLUR#(~jhOm zFNZw<0JioZC=5LyE87ubcF?x}=a@B@@qnwuB?U8Qvyt^>(k=M&iP_2dQzGn!pHyA6 zXqORiwt?fE>W=61-)@GY3mxAF$d zA9hp7QA-^oIhnD}<2%T#5UaQI3NLsQ%seOw_Ws_UY_bRgz^;P{CR2uPX}gt4G2AEN z?vGFf;KaZrsOFhe?7PWMUrcg7T45c3a;8y8ksaWT^|MCSCXFUks_C68mJEIiwD=I% z{}hj5{vTZDb8#&#Q8cxO$gKsG4@^BdA7Hx8_81WdBRJgklD^H-W>OTJTUaCzO?#IT;b_3wf`; z(nI<-fCfCS1WBI18&OJ|5uam+z0OsLCpu5nyg+v2(1Z1Xbwfd)jYI%+g6|~p^sGeh zRgR8)QewA%&OVo9$H1#_qW7*C2P!3yeJQL>Ze)*XO8p~ZnO6NlvW)HFyxKo?XP^sC{U8fZzmdH zLNJXW*NIJ*h1cXmefuTAUVVfEXsbgf%{Z4A7vf!%AI-7-gZ^EGxh{bd)gKDxT<*)2 z<=`;{{{}x5A@2Edf#tqKI5axeSb7biYvct2$c!_VQvLKt_)L0>tmFx)p(rhih??r- z%<)>mGoC5YLPMka4MJo45dxv>&R@l865Z--EFvEpU0d z`|O$}gCQ%f>`dzS4vp|#E{UVCx>EuQ8W~na*5eQ|_xgqyP#l9W>(=TYsnUFNK--&@ zf_`q3L!f%A7egkK^OYQR^d_4u&mY9ksBeKPAx|T=56zXh|AK!c>Q+vWj96QRTdEkj zVs)TA>fjhWE&%HnIxGdGB+8uZRA`oC=o%hcp6;O-{y}ei)sJ zTX(jfb0>;h_EW2NyW9|O*%VF2^u&^^`H+sB(eK@2h@hWI&|`Mi08nP0J}_9_o98+XkVdH7d^*18ftPaCk|TusqL|RYV?$mZp#$G59j%CEoj>tCaTaluOy+`J zNIHA7CBvgH+F;wSAn&sS6GIr%76#c4K3MdI!vHE-?2(`MqL&k~c}}Y1_`^vf`bYwp zeh+frs>}OKIrZ~fWS?pQ5_}Rf9kZ=<(XI zHjO7M^AYAd!louD4uhBx!|?o(>lLVnH~z%qu!)#`Dk zfEMhe!>neisz=b6EGWW*bsr0hFUjZNr)I6!tiXn>QI!>N9%1qF5U8Iy8Vbth`c<;L z)ap_lPJJxP!7F5xfs};1(cr1-I~0!o2bY!0t>8R`YnXD6H#yMw{h1LiY9)=(o_avN zWG&-@KWvQ{RZ&l~#GXL(WZu!&X)trmz?>@sV)c(Hb&|DP;_!9&1#{a#ij-Bvk4k0x zNGvz{*9rdbKJp)J6s>}Dn!a>1Q`6MK=jgG#8!+Me8I%#>Z_?*`8OUMcfFxUrqTV7j zIIwCy3aYzfv6rmI7z`Qv52L%Ir0`dQ-2E%k?JNjuW&~c{wdSgNmG1OkRc|2og>-=z zXP9fCC``zBmHa*-?dL+E8Vzr+CA~|S0cr0S2FhHX(9)Ga^C84qrs1X|59jqlDVk}v z)+yCd&EVD*O`qKAq9B=dEXCHTkuxVu-ci4;QqBM1@){>eL+eZp!a8zi)mZoSUb+6~ zj2lRjNZia*9Atg20ALZWdOb;NMLgqGU13LQ8IV7-qLh+n0HGa3qc%yU5 z9lp!jD|ll9t|rt`bMTH_R;@laVQCNQ=viRrz@K|ZPbTQRBiTum2Sz?8d0a#l%74Z} zVMU>`Y-osOk7?2DC-~X7=}(@ReVK~-nMzhlm#bvM|C~oCBs~lXfj0;t_q{qUJhq)M zfryjt29iOlN3t4p1dk7EB!qOk*?pFY+H;-}tG!NDa@Q|M{9o*ScU)9U)?ha@Ip?52 zlaw4qf`M)nBe)xI|~-+r_6cD`@l z&h8&`ez)(vRduS)sdLV)x^?Py)unhV@g#d^fy+)5*)u6VviY~AZhf_6RG**pN+DPH z=;3jr7eBsH^|MWI`t1?^T@131X_TvUe&orIg;~hf`u!~Q20am?`zaj8HV5P_s(u@` zbyu`P3S2c^oS#;_;ICedCZck=h99s*qgk4>91$MR+xWopBTF`g{;od;j+$z{&M47SFHa%q2=2x-;@XHm*sCC}p}=pS(y@fwhi$fpa?D(qN6xF2In2y)MY}v# zP%(^uvhKY>c90wP0Wm9aj#z8h`1n{uw*Bnv>}U+_^ekyaS%j?KG@(J{LFU%7u9>=b zA;d#Bz&n~b<%!r``W;cDTzp*T@39n$0g&QJ&Ny~F*)NI?*hh)vT35>pOGTXza1x=k zD@s!0SaZpVl_S?IA#+`18?1AzqEU*+MxA;FIw6I0cY{hPt|Jbd2^AxlCkV%k<%UVF zu%H;R=!{+sJui|vfRtUm6?G#a+xb{Hpz6r$ybZd30nq|qgQYArs+JuqPwkTO*U+4* z7U8_?s&GnFwKG#|_wJ(a4PP60?FhE!D*f<1TAkXEy4Nh(c|>&0XD zKr@20lqLJ@pvk8Aip4R`9O2O`y${t0UJqIJNoH88x5Aa5PibIOQ(Knz&Oagk?m980 zw7ToBbIPhBr&ZE5E_P5Xf<0e?z^&QXPv#k@7WO;m%N85xn?8)e9u=H@{Zz<)TgTI? zibhR4X~OoU3$&`Mi+DB!d+9usHR35ThC!YWinYhYp z$<%8$HaEg$oK&TkJfl>-^Bg(WUiF1JQ28PuchJ?XW{BpAW! zD0YKO4-;U^UDncJYP0W*$jcqL=M?8AtTTk6VEF`@U#uY~{KhS@ZI8-td#_9Nn!#qT zbGR3di$J%ko@ty^Y)aq#J7ipxl8 z+xavxciiz%DPGNSW#hYd7{&<}8{{$GJ4f+Do`yh&t|T@KXm;Eof0dA^DQY00S>X2S ztw*Tr%^JZbAA=~V;sI{H9-R&ge$2FRwTaz+?_~7=I+=pHB+j6cz8ixt7kT>JzB?Z= zVbD(!d6O(dvmwMBlbh^gT@&61e1iA7eQchV3?hc2E&Yz#7o`dc1KBF7%4oK}=J)6O z$c=K3-+8F&-SJUcBfi35Sue||8b@vviIgP6OczkJD|;=!6vyot+PVLrv_IEDyp zOzSR6%t&hf!B*JtvPV#~*g%P4hL!WT9(<#zsLn^z#7dd$*|R#h|Bo>?p_`n*n)%Zye63k{DH;svD2GlP5FVz?XUV^tz9E#Kt)7GLG= zIMd~9-Wuk~rb$Sz;kV6HVzZPryrQlzF1hHpOWr*dNK2_7*xlP-%k=K1=Id-~1E z9)Umccm}@|5X7Esw$juIc-zBQmP|#2??|!c8e30T5}iF@IEJ{V-PbsvGjknReT9aK z&oQ0V%uF=Xl2;1yk{ENoTeLqeU>F52EV!iih0EVcFFM6BLO zj~>egHJpiz9_e?U!=s{Ve8eo%7Rlu)D)?KpLIm%xa|8?XUA>=%Ju>b1NI>_+Q(lB7 z{w#BI4x|jbo?PpiG!1Kac5MHx0*M6zy#iWlm*n7cv+cP9>;u;x&jjDm8i;-Xkx@i` zy_);9zJ9wV*3!+`G!$>UBEe#z&Di6bVk6o7Y$cLqc5b2MBlnHPWVZ z(E>LqUc1We_KI&5p33Zaxwj;@nMx0ys&q|t>?=%wwQIqucyVgfv`>Qg@XJm|a51|s zCn&n|W*H}K)=DJla_*Te?hX#9Sd=AP(kc$W3l;p3%%NKqe+@&u2DeCNI<2pQg1v$# zr@M**E^J$Gau{UdhFv50fJ#KYpdyD%kMoUVVUSmkXJgOm;tgMryMR_*X`yn^i)oMa})?YJAFjtP2n7z2dEQd!}!}i})f_v6Ib0jUBB1S6ChM+vRU3)!E?{9oz6jwxtObTKgh%;@CBE@xh$rS_dR?k z=@M<`oNw_(&FA=e6Fl=-^uq_Wsv&1akc`{=Lzap_v$#n1AgGYqk`W3Q@IVV z+O!~vSRHku3wce<@=(n>_X%4< z=MDE|HH;@8ax+ZfIJ(NxJ2-a@FreW@qh`_D(>L$T>xF0TcwsYs+EY63&&4X&eCTqt z?CiXMM2KDRF86yj_@_aX=?%rCC!}Mz2lb=Y0z3w{&M6_-tgmqEWoAlL=ZcQ}dwo(g zxD-d}6Q7)xh9Q-8_&C~xp|-x(q%N)%5t?l_?9w<2&!CmX)T?Fb+2_x%ba)Na&hnMD z4@_b7GFI!gSivEtO^H|4`<-vi$Elz6BVXBuK#~k8%yA;)1FvJ(4yc){+}DfFnO37~ zd>HoR3NO2Tl_sc5sKNDX;t8_8&K$v;Okjk=T97Mvqzoz6> zG!G*!S(ESlC7EkYV+QmMna>qdTkpF)-_M}eG`*$%lLRRm7fk6$xk_FqHFMQ9L12u( zWRqiclL{m99XSJ5WMr78jvD!={uHOw_*B8#v}BXkWotSePn1|9A%(c=OZ9jcy^M}( z#vY-gsc^?Sr;wMAFemg*$l zuOnRQb}@8g@&ds3ZZ3C{xeMOWd=f~@oWD$p{~4PjWyrEp7#l2Dx$eA*S#eAEl8e4@ zttm@7`$E20^7G7X%te-K{Bq7uQl1Tc>vf2%(=_#AVII)1XrXhM6%X>o-eb5o@VS$8 zc&8wGFNL;}Irv?0Pc;K8vG+iApngPH!AN3t&H|ph_<)21d#!oJ9_diHYfoiv>ef?I z>D7{q<4%!QH^OT}97}h{4eBoMV12^!=3khr;nQH6S8m@?RsZ;UX7g-_xXs*!*;eqS zE^~3c&a?YoaQhOlxXRIYX-nScjz4i5CX;)XerDX8_muk7O0zAg^yI!P*aVr+c%!Pl z_vuciBoEp&bdNSv(+Y<1D7Lt&FAqqS2NDUBj&MxmcNVs ziv2q6u(6pYc*!Du*rrZ-kv!$zcIP>*>(IE7J0q+aRA#nGQ=aXCG7{x`+7U56Fns)cmStA{h-K|E!2phbP){6eI=jC; z^Az`~=I*`W`{&t8x~=78pX_iyfzMwD6`BOQOWQLF<$Li=iz`}F{JU?g)M&E?22kAB zcgCTyMO;es_Y89W60Dspa31K=9;Pv;`_QKCLqqcZ7xBuK)j66k-pKuecJ10NO0*w>0uD;#R&f<{aR}>ZQ;U>+&oa2}N zLg<0@y(aT|MyqV}DcR})CKGL1LEvmcqso&c4J^G^vL}T~HofJ=cu7)>LIe-Jz*-K_ z%iJp^`|@A=SoO}2GFaI_<&aHxJ7w7_|N_*z6)Tc96 z_WJE&byuCG>v8pq`x_HmZm6xb@fo~%Y)Wt`xGcJ~cn{l-SwV#-YN`V&<8J zSLxQ4FNfy0C^qxxG!WOZmMN4|lv7tN(92{#7ke>e?S68GSrdTIcKKO9F^vmP&|UJA zyHU@R2dhzz#1Ajki}VvN)3bC`nq+(TTQ2dKr&vur6N;@QaDQevxS5pv(WUD~_2xjY zCCeA4P(fuXT@>YJcjaYeEBA#Rj;L?5_%2%`vvxb5de%9#Ckh6wxE`_lR0}B3U-vIM z2q=L*Y7BR8eDGO(Ngh#zbJ>kvW?wO+Y@m?3Srqpn&eCNsq5&{2FRBw-l<>`sCN4I;i@*fcU(d&SW6jce?**qb`aN*;nU3C7sOQ3 z7-^C=vyyiy^5Zln4B@b>z`Z9*G$J|!7Ncm9uX}PGxvTaTuSC{nUA3@&c!J%zkqAC! zh84-f={(=$poN*9vf~T?95Z)QUMdjg&N5HzUC>V(dDoq?c$kosbCKWYt^<-Al{QLP zp?vK-Mm_;n9cb-A=#m?N0os4mNJVPgjiGj#R1e?5-a z=6-=6-$L>*VGm^v>0U{em?uPj$dhf-#&IN?0 zzR@Y&t=ro2Lu%%gA|1h=&+BBWJbWgU9>d`tsRH+nJj_d3*kmgvNlyy0%qgxb1e@tf z9}*UX&rx50XYjq0Zp^KhEy*!?ax{B*;P%-ATF3HDi`5A7|Xp_;MwNvS3YC*wu1VPj;~E6r#^? z*M5w+ddD!l(4Bq5YYk6PN=Vi%6|r&ASQf=0SP@E~boGi3>=a61V0FET9AS;VtdQwL z{wlOqmz^H}o1$w~zNUBXRV-MOEVNAVw#bgDe1^^?`qDjmv2Kn2aaN0yGpZzh@^80j z?^R_iYqVHA@y9-AHa=JFOOu_NeQDIfIQsMpWLnkOf{U~8DaL)S3eBA(JBK?t-7x-6 zJk`6ZYnBpUw}_!vf^ULAkV@Y0hhPrLPF0 zvv!-?+_rjfo1; z6_+Aly-c1gsN$Pb#5t?{tV4SG$@lhfR51jJqXf!(?;_Ffc zt36ZUh{^vm{;>fKT$TL_v~}kMYf*c? zBMDB}?N-cI&tC_PvwAXHDVw&$2Ys}*W_B_^q(8cIKR9wtajG(ohG+Ng6H+qnx*24% zJV8FyVWfu4rfa*)ZS5zcG`jDYplK9ZD;grjQ;kaTW44;*V}toUMh;__l`O9K-e1ll zmV0oR-c#bXz&mPvW%^V)+D;Uk5YNEjxap3!4u2d|23+`leA5V@FGsY4IH#qVcMX|=}ngWWi7rZ=EP+>G;-=o_csV@sryF?xCS6ZoW z6qOA=uxyvn<;>Twqfmm|<0f(qJEOc%z1+FI)DnXjA#0aANLofM#^dR{=Nm&GO>lC^&ULRQEL%Y;2qa>{ z-`@#7$f$|*Reh&;FK(Ln22!8#K?WBeVqV3)RDF&MQ|9Xd9GB_>qGw=x^5&ectd-dz zYHE^hP;y=`QRz=`m zM=zG=wJPBoq^>k%_iZHHc!N%&eaz3BZd}UuRSyiY5POW=DnxqB5#Sg$%`!uCO}~go zF?{Xg4%H&gzcrivs{d+zP%*41gy=k|abN~Y%9VBt{jjB(`b zldro6ENsrtNhtq6xz zEdk3bcj=gP_qz4`XVFw{H4LU*5inNM@atMDo{>7s7O8yUT@1Mz3p% zF2!b6a~EAea(JK6Y#X1)8tg^g#`Ggu=zA@){5ovsbol%&j>%A3p{P)8qO#R@16~zf z{}$!lYKoFX?40MH65cvhx}WxQJG{14T~;x>i}`@@d33m(vvLF2b+T3WIQJECj>cu) zhkf|A$~6Nxm!$(z3F0{p1vjW)gqiY5^)Wxq#H|Vy4LO ztm~&l+|QJLj!lrvINFNbO?Z^FD9=;BciV#6CpMv*XrF?}`e>yXyr;1wvnGj%S6hml z_RuK4a37$uP1k8|S)_^R2p4xW@}(~pbwKF1GlSg%%ZG($gL2mes5S9E;fH&g33CQk z;7Jot4`|Ap8RzQf@^SNl?8f9UtJ;Eqo42hVO7R-6nf8$D5lF&4x z$Twf)JqW%otn@ioUFlR2pU!}6l|Nk5xL(NQ7JEhB8`du`!(!t`@AolB7&H|S%T;)> z2bGONKFcgLNv}f~!;?MkRN~?<&zVa|e?`uF9tVdrF$X#=3;zos{ruX~LNXddyeUAHSsuFtC?!wzM;KN%m(g z4MF$A)+gY}xKH1OGboK~0yj)Pje6poA$g71J5`J6W6!7Ty zdc#^jd?F)#PU2AA@7nO*kp1RPo-aS@7`1p-Re0%Gxj|@UMxDX6ghhi zRqFr3$ZnA(39U_0&%UGn#=>!?aicRCFP>6Vqv$I&PT7E3NAjIf%=!~~>VwY3$sv0A z%}01aLqpGBePR;7-&CR=rCj-__@woPm!}!Eo@;*&wD6jktEL6!>uAV!^7C{nWAM*` zkm*&b&o3nhvX)i0um13Zsx(SS`<>jOl3$nlfPp%P+siOtKx*E&E3HcCoZ($SYI(`e zgi9PpKjl;nb&DR0vA1 z@ILjkuw*xwM?G zNi|d@gpbJflkdy0{3x=0RO{G(cReF76tOA%CcOE8j?E=Jz7<13n%^C+Ah?SA`o^rE zen8fFE&;(hF0uYyk@vjXN1^BKwe=RZ&KtE&ArgL_(_Uv_!{QR-6a82Z>sT*qtr&ON zbG60H`%4LHSlgVFM_BZpIPqpbZpQWBe9gJ6;3eh*3DPpO>^ z8XoC;W9heF)Uk4cp>v*&i(6t$(&y2kjw`8iJ8ntsL+>}q#oK{zgIQ<7PF?(7O57f3 z+w8eLtASkQ`CL!+6?+t><&zyk^(3!#D~uts)#B~)v9-f?&-F~>K&;m?U_H)CgW2f? zT%LnsdQHincfoSOY2?D|6PHw*l->gdK86glIQtbfmw>puA;+x!@=S~`R_0Lb1_?S-V z2d^KmX|J$MyaMC)frvY9h@S*}zBE-|0_V>&eXjQ96+IjAn;-A`dOTG9-~zI){5B=i zmg*cw)^Ed@>W$fY`2=e8z%)Y&^T^XCbK^V%j_ zeQC-s0_|s*^1)|)7?n&+Lmq+PPR|^#ro@Fa|7m#UQeBXqsaE6#~?SU4bp4LuzpRJqSI2WTvb>Q}!ij zk;W!S8&+K9I_v71qqTZ=e>LOuNVFVz^NDY?<&`hI?+Dy~By37@XMhzh6pn65Vu^Pb zsk27tnm>3ve6P7=)SG{xN`!G{oxsjXWZi?mPhd-D+1@DKuM^ByJ!#7}Fgv76oh!)r zTzbzb>yzX**I)T81mPn=@X`4x z>yN;uHX1J0H={H|&afY+fH68Icmk)3o@mJZ7qX>%Tj7t4(Ev%`| z>I@)us-G+=*dA@cT(QLuXEj`dSN$(#_1;Gr>z>tws4DSQ7TkU)&m(r`NK1SpLgOfe z7{1N?5>qlVik?;PAf+gwZBMeGZ2*Ss5KS7rjzKt;6>$27mAN;KWLc+HM%bK0P|Gt6-3N5ydC z2UMTy;UV&l6lY_=r^<=2StvRVpFd;YmnbGb)w9&VK8GRvJ?>K&=tcW7g3Y{mmmf}k z@n4@(G`7nZu+5QD*#4ki1ZD55Ow-ut#QOvgOAGDfi_#j2X+IFfC7D*)Q^l+F z9LGH6c-D|aIw+-ELZ>OH@+H8Lhnw#Mq$X*2x9X=* zPunQ}d|zO3^(Q%%o;8oX)1q@MgWHnn>)4>TC3sze_I4)SynrBnJR$HqwlevtKn)y0 zIvxIxVhyn5t(Ybyj(>v2@NdswbjY2}KUVF{R`Y8ne><-#%<#~)TrEvTxv|-k zCo2De?$--Qxo+)>@=1ytKGj$|uimY!DdwRD4>QW&wU$d;NI8fu4nTHZO0!!)R&?&~UZoCy z-}YT?&B!@+H|vP&FRI}5JLnqkC?DFR%=St-9IG%kk0YZsNE9Mh)Ge_!BXA7Kb+axt z#h)(GT#f)h{1mx<72A%6f4T&<<%~g zDH^9Sz8de_^nTB>zOEb{pWpu9+{}|kU#i8MHz-k)w(HHMS#(%7{-^T&wd`{V4su>w zjSI*Z&=K)~#-ri+%l4Sa;(H9)&oQ1Qcq3`@=+`|k(uGD`_L9b4YTsJ+z9j#1Dzv&u zD~dP5L8njc#q}{`%+C8hSHvAD_>=iVb)h$x)jmiG$x4^r*bmTRf;o6JvG%TvG!aYlv8>&E8my-H#Twu&DX8SdiubIOa%N)9}{W@q`4_2#@K!PSjg z=^7q0u)I1P0@43?+p>8*+;ydy>9`#N5gH~lzJPSf`t5Qb%JZJNvGeFF2XGaT|7uF#0+PU1OwsD;_Z{BgptEa+6yBDyCn`2gc_gcg2FmTzfvOl6jnb z6@1?q?C?I^%bw)pvF6eRBpdYdUqrKhN>yCZEJf8cUQ4i?y7irCb(w9S{o$?b9V7PO z@phU;uAo-%xwKA!spo^)&ql1iKL_q*yqxfmI&FF9;*|P>3ud?@;4^uvfMDT1AAI(J zr&Y*D)t)9E@3EbWU0-6iGgCPCcUp%^ zIi~=#2|dMxE^Nb95mi>4Z zLxq8?)eU@oSKX-aYfx{9_$TZ1F4(09C4+`thr&DA8zJftW>M#ibzb@@M7fQAxr58vX7erYjiJ0AkE0hEuUveT z(llXBPaJPfU|P9{#&V3);caPgBnuxNoxVb@#YCv1$$nl?mm%5ZvgH)6ubT~5Wfczp z^1k`|Yvb+$t9BW2xpio>Pj4UdRfG(SXx~WW~%Fc)nMae{7|unf>Y7)5bVw z=u~AfFP7t1&+FsExlh&Q>XUhL?PSRMNi41>lzcNSd7gD7Fj_I;a|Or_ODwCDsU3?kGg zBsLvMFr9*s*yo21JdQYtedhBdn?BkyIG`;=yWFnx+paqL(&-wDb0PLw98rq5-#lu$8ffRKK~t3W5oc~2p!gEk1F=5kL<{P2j_ z98BWM4WH-aeaX5uFtvv>VMBP=;l4e#_*&Ab$*lLJ&|*ENvaZ>(s2Lr{Van8sU?P2e zDr3lVW>q>K==CGn{yr+~;|0zRtWwg1g~-$_cs}Zce^GTZQ z&55{vN&muiYpbUUn*m%CA9xuRmJ+TfqsH7@J_yWnHyRq!DYhIHkTxph?g^Wiv$KxE zOUq|v-fb&*9l3$#C8qxZ;$lN}%4PihNgyBJMsX>m^!DOF|lRfwQI;RppPjvj}4R**R0a|8K$b> zD<1uw*!EI{CkDcF_1#&Y!l0N<@S)&>jPku32{Ha24?Mc_=WK>f`Yy9m@-HQ)5~i{Y zeoTJGqsb6HfIMa5_=zFHySd5VTZjCJb3c}5?*eiaCRZ~=HCBJsG=uaR{{;m0G27bV zX*O}}TdeVMx?m%^SGE0W_R)IUdGS3H*0Apdf;lT!R#1d2N8AadZaq|_oGVMyS8R_5@{DZg*91_o4|jJ z!954IqLcR*Bm%gxAE?hns4yns&g8|-8PQZla79anEfo0oq=r{&oC8!C5DdQD6Co|72ro3}7@M8aPmmkv`K zY))`3K5{;S_t;vhH47_SAz_)eJ)s!Cd6TwNtQ_C+8L1-TU?gZopQTGLnWKI4_I5N3 z5+K;_|E=N?H2F!;pa${NC>e#b0itG`l^@xb9f{f2g$u4NzF@R)#wN;i(p@!W zjPZF(vOE9mjk2RegZVl~C57+E47LU&?GfLMW%3*mUR(O3DFNXD+J~kA8qp#Gi8$f& zTilMUu{_U7cbgwe-NIFF8c^&Ln&D!d+UxhPzClrLho7BUQFqVf)2+xhYz587G7`U^s z@)>u0y=gK#vGLPkGl);>ONVAVj(Gi z>G8W%s+VhUPamm1>tmVG>7J6?;7Os68$vIaHHfquffJBpv8vs~Xba2p!(xGN_-W5uhP{OF@LJ0=+=^$+?!eZ<%SM z=RN12)>Q`mueC;(1+9uC8RAO1A=Z21A6+h8vC}&MU#t!y9Y%V1Xo8Zs7!@*TA5#>g zge-{@Zk1#2iKMr78u(s7Btbv>4UG4_?0`Qf>E`0<_Ow2enkvWZ0pBW{2Z5i-ORcp{ z+C;*jNaw_6 zgXyw^c;){@_{}Y;_$1mOM8TZQtl`T+`PrDqP4X1GxU}Uuv|}RMemZ?c{6~D3pwtQ< z7J|L4!_T`lZ1-pi7F@RX`0B%lyKX9UGHs(9}Dv4VbIq&$M5D`m#$p>fGmU|fg8 z5VAgfBe$=sHy5VnCojC>F(lp`~(@$uXu4SDL;zq4{?23FDcNU750d)<7CTlNmtQ&TRnpC0XpMVNwdFUoV2 za!Jgz1C}X>^M~5sAoAAR@568jnrpP22#BL32IGc|XueC0FsHV_mFWYO>7t!IpR%HV53m zG4@OO^EE?CZoB2aLCs1$uGjr)sfr}>kzj!q@Ly>xb57*!1J_<%mV|*d%bS_o_Bs|Oa(%@VUWyWwZK=R8uy!pY$Mmc*j(3Se)kYsIgDE9SZ_J@b^n;Qu;Q`|3W zb(}0J=iV8%{6C0}nQMv5R=I$Lu(W9*L925{qc|Yy<0`E*)-gHlbrtgbE!+B@Yp~4* z*prcWgG`QtP{B(r^!>3?*UJ3R#Bp`(X2ztPhRpicEzod zC3M5AQxcLY479E4xs=(o6}&opEE+@|O;wG{$f;+`D7`u%5}A%qhJjR&aXmCdmBz!u z+e}_ZB+X|ybH12clF%PnsMFzgpOyLBd;hJ3asFOUUzy|KcRyDa&-b?dypANB&zR0ka8|f;jGTKhW@YPCSKjE&PF!bq z{p*%c>0Iq6VGq6SK1!Qq*3w(^r7#(?_jCLnnZUzK_KNpm7W-MQuU+0L&f)lJFn)$j zDdTesX&>B=y?3Cb6;*B?LLwn?-=8lyl^nJ0OE+Be+K`RU$Xi7#yu$zzR2kx35DzrruH`uGkYVK zsXU^E!DcJM%=hjn=Qea*^?z);BEl_*s>rFz>eDYz7bV6_<{G>_DB+b#8^uqbHm)Q< zR6V{t^-6kkA%58l7kCPGxO%|z!oSab^wacybUj(H=atE6l^rJALtD|2~N48bW->aB{-{Pvl~ z*rD{k^BqIFNNSSwL!C+!BH1nMj}J^9B@fZxdz?O!KDb}?Y+0+~QB_^`CKhtyb)A!A zsLN$1$l?3(*V9HDSgyj#>Tm9jy)o+IHr^=cO zli#UZauwlG;*l#@4;#7W+Q2Mah0Nz8Q)e9@@C4)R+sx#x%-eo8^~IL94c7b%t_new zlCAF_$*xSrXS?MnM0mfGBbvk!i!cgTAy}T}I(b59Rv`I->qU$Atr7jz{^sh$AG0M4 zYV{H8ut6U_uG*fd$T`Yvx>u$5JePNGJJdS0RdgZw*IGOg@sX_}B-Z?qCH&&E zRrFe)$Pd{n){8>Qrk!up>hgb}X|!e?e(t<-Te!&+YM0*c6F8vkIsfCV5Ic}e#H)C2PBHJ?|v!*x*Os)wsE2sT8}kQM*H^Kc6?IrWwWEWkL%EU+t> zXE)7#g!KcLLnx>>!I4e2)?WzXK0Nf$YU3>D@^lkUN*>}hldQwBG$b>mb;0UXS;n>~ zH|%O~Hhyt+Kv!NDCJ9+_Ou*=CYoZ@7`>rL-l!t)bNc*WzFNu){o(%(PF75ovl}xOiBpIJ)^*q z|3^M{*TGxlQ~rI)A5WR`buuhldY!&tHNs28}PKA%vJv2nGZb0)dc%-@oDC68Qg2 z0VG7c(FR4uP@(oB#wH zh=bt4A$TAXT?pWfTo#?>PXZVyhZGk=jtjw%g@9TI{3;j3077Uv{0c&FAt)dm=x+hQ z5;!0+5Ev-}FbqQhVS*%d7PN#xUH&W}g}`GG5OOFRT2lykEMNm@5CI4J0weGW87 znkeaS@&q=3fS_a{0eCR9HleUzNpMgOz=r@EK%lRG4&br{$igt>U>Il)0b^`v(V^7@ zm;v?%0x%Sm4J{%(HWUQS3`oU*!Z84XEIKAe4$V3FuPkU*K{fv@z(ZFY0|EzBPzV@W zvuN$G0n!iz_yJ~sn%IEJ{S`0}Y!F-+3IQPnG6VpEaQv0HWlwzXbA2P#CiC09jyiY#0a#H~<4NN}cyJ6kNC3JZHc}`I*g3l5znL5`Eg(!l7m9w0A+o^c(Mf;}3@H3Joq|eX z0OpbCM->H9L4i;>`tlo~X|cu1!v7Nf!z=W6v|r5p!bGqIAlZJ;gA0Q|fjNN?8=6A| zT8!w10v8qls3YN|zl4kdh5a%)P(c_P4Ht$2F@Mu09K`)6K>eriKM4MghGyV*K;Z&w zL9>T}mJ(1O9NhnAa%e$8!ST!FaN(o~bP{-K$brd$8*rc%4Qd3=Xzl+7K$w34_-{Ap zD*O}hJKA5$0VSgVCkQ|n=nIBIz(MdAz|lm1nIa0^O0WUlVF1B`dnj7~u>aq*k3h!& z*`k&Et5Oi?UrRuzpwK6@#{Vn8hWaZuS|dOjY`;VViNyovgccV-K+6rBfjsfpVvykW zml8qK2b2!|WquHJUJMA3B$@#fI748u2=wJQK*t04ukrRhyECT#~sTF;JqlJw4P0Mh!5dtHJ!Xdu_nmQa5f&nt375%3HFcn~O7~u5-7!}&~ z;220anlT_iKn@p%0zBCc?KZh0PD{J6k2Ey zpqdyY5FL0P(b7X}_Ls^axbRpsCBPVrTo#4`{X1xTk!--^K$C)k!XY3#(EBf40~`#{ zH6uXWp9H^Zib59#M*)_QuoyrWhynsE4IPOV7kDlZ=vEipVBo?5+W|;8y2tuc&{Y{w;xjOW@xU__qZ9ErEYa;NKGXFG~RZlJoy904L19 z;lC#Va@_x3zJEn73?vNoub}haqJay+_%%%UZ)N^J$OMJ|6PaOPT!8u~@cv{JJTPK{ zk^b)r1qlByLpLEJwxWa{I|BlE%6@d%? zdoF0 z^2py4`KMz3Uai3LN$*7_O=P=AW*;jlQFWu(+iJ906zb)eB@Nhj#PIIlS+~6 z*LQ!2`3H%J|5X~EYWQE;UvxwKvJ(Y?fCB>w{Jk(zSvWbEeUoDYG5;7aE(tu7FM(aN zG{Q~}`p0O0n1T!cUnX<^N8TD{ClG)u^wbhW79NX4XNi%60srtn2H12B+3N_3hV#P3 zhLpvBjQ7VWsNa)e|5M+Je)WYxfO{MY3y=c_1{h-lhyhSoEEG&epy#>J6O{iLC=OKu z>o@bfZ2^-0LQ=s2U>#xNFX8@3NQu%E_6@@ z5M)E48HWAB{7)wwf{c2Y3HTGM%|0%Kux2)*ZSd1q#D7Bi=YsGUFuwqN^0;iI;Fb7) zu=XW@RTJCaC+W0JSkq8SS%hf`rBzT+WN}TfV8WtB(FgdHTP#=<6mWy5;t(p7)ex{E zAQr5+D>?9;pS9SZz*MfnX+PFb$~ux5QA2}jc!Z0 z&=&TTGzWlCcAGn@HfYv@N#&}m_UzWf{O0Sg4pprVU_9_N3iVK9AcJ}GRVRy zC=HK80aOeV?zW*D!RffyAP+YkJkTsWpg`vV5Rww^p8xNjWSIHiYdn2%fBi2 zokL6{6(0xvyZ?T^$Br%q*Jup8qrhe=YMPCx<1kmCA>^c&O^q8^BW&4&P*h=X8xz5X ziutfS9R#R3o5ntshBr5VEE#GU*PWUAX;v&&!w*d&5YR>{m z6MytG`Km4Xh$cEG=1-}iY4T8yh#ZPMc8DO<0vs zT1gF4eC`(pIc+jaPF`x`ggfeb3A^VunqE@lUMnxj%tU^77qqi1x22oI6^|JOp zVZSWH?1_GRuYNkEpIb{*gSE7ue!S#|ET z=N7$HzM$Qp{4ydC=EsHW}`!}CVLyZX?!rG>%cF5PDC;7w$dXO~;fWHrpb$Ht5sRIYOIl{0RlE_!0?NXdN9&**3 zTplB@Rd*0fjYR;JMw%K1#O5N33T9{!!fMEljHn(z0>R)ku_f0c2Pr9i6n9NT9}l@| z)<7QXT~Sq-fVM6PU9Q7&mGC4HbVDc#iT(u$o2jG9Bcd*cBvlF?UG`O1g)>t@W#I5> zU|aE+iH97xP%(tV;W!~plmLYjvO^){3lbSqgIl40WPfhf3xEVm{Udlu@dF3*%E`3r zkHydM-^t^f7;is=D>2hXa9c8xbS_7C$wq>1nTjPeW{@Q!>qNbTg)D@PFeRBJT*U;4 zROF1t>o_1zd#F~wA#8HKcF)lhr{8hu*Y=?(nro-bojb2WhK?%(2xVPB2awjpoC5`z z>S2YgE*2OBpr)uOxL5{UtgzKSmIJml@nON?(Ga!=Oz0<@onKn?Aw6Kdc1Zfc+IOw5 zOWS}FrW2|L6o@JpXcIA~z-Sbr_&QABg^@UD9Cg<4xbI4RREGo*fWp=2c<4rtC2!x+=Etue-gn-QhoV*r8h8uR-sN&EA=8QzCSnd|;Rt;3Qa~*#YkRgW$#KwCU?R@GBY;Te(rd=x+{tcHTWhv>0WJ&J3z4x^CPcT#G z0ZFf#HuoK*ZEeu0Fo}bFky{Mat0TqX0tSORu$=6cI;v!;ptLRI3&GO19HFn4ELW8k3TJ^^nAN6O#*Ljd~(iNSK0*mFu4ce+;pNHLQT-woNz_Q@=^Su zb^;KFrpyxQNt6@-2%rzPa>yYhP=H{OyaxcArHGbPLC);Cnq??S_jDPbd)`9_5XDai zH(dPKf8H3TVap+lCsJ0mQLK1v&=H5`2s(q9phy{#pu*eGL5GPbh>RwC6-JJ{!y_Bz z4hc;{_C}zbl>Sn7H?sT`wQ`>!Y<5|Tsz9-ttXtIlyZ4I{RCSNapbo>{e_7;ma>(=; z=8LS27mP&Ek-!8!i*Q94u!h-zo*cqeELhT;Fcr@=s!Y`^$}weItZfwN zOZV;6cj>J0pem_+Kc@_)wyTNi9g>~uQ%F`gEJKPVa4oww~5NV4fCId^MOQDvahWJk}**_yjb_cccgMwvTG<@rKlqmP=1#iSqDh>tBQ7Kn8P#STeAD5I5`^dZJUF zTh(cmaG1W)Zu4QeP*Pum<~CovY@l&y-DvPx7w_Eg`&!phZ7Xn@32D`o)paiY`RF0u z7(tYRH&kA~HgP?L`5sekMv-waEH#07Q7?5;p`OA+os+^T4$7E|hF8pVIJLj?PrCQA zKvCCiwF9;wC~98WYj-tK{ev>7?DFJ&=Wk;ntOnocm^On60M#*vJ4y*j7mTf}!f{mX zV`&%~RYujxhh~wAk`U}V_Z15*3X|_iEoDEY#t)=5d)E4;foC;6n7?MOq1ys~VIxW)gzHizeB~5n7p@U#>;VTbU6dRbkVi7T+FoD^@O^LO& zA+N`yBv+rBHuDuux-7LapD`nw075!cDg(m?8j@Ugs*WX;trEjkFez}k)}?dbRP!s} ze{J2()7Kw*Z5`A%z2f>(Pfivy3Xo$67+1QZ+I=WkI#*FxrDzC$DSjkZ+Rb;N9y++G za9BeEl+;+@F(1`jC#WYoiIJClpG0_IGl7+cSmvv17CF=^%c23g^!~w+e8$h6QlEH? z1TmzU?^uBgb}k8b$p&5^8%w#&$?K+jq$$=p|tNnEcZM^|TT5DGXcPH!kWtuxXz9sX7uKa2eFAHUjj7gz7TK4A{-a z@<3Slp--C{IWpQ2_Ew1aL8XKK5-eZgK9PV6Jj?Kq#oUPWQ3u2#f<&Xdc-L)H8q%Xd zT8GT9twe9V(=OBCFK^3W_ za1jl_{!)l-sSXsD7gdojI4CC>Xlp?oKl$;0{eJI$t@Fv3Ob=@NYcXZes`Dof+4ctF zlLrd(<6#qx*MuBJrZ7F&7kVZ_&L;TFgzpq9UKoS8eTapwI_;|Lru&jI^xGf%;8F~5eWsZC2~k;&;~P<_6j_XsD;04wb3nOgdmSoJzxk~ zAF+NINIWTF0gR4UEmX%`>wO!o(8KCb6iTG?^9c%6AFRe6L)gJXs>|SY;Ht|F4;7hU ztk6yn!?o_C6dAX+OYRh`5UF0bs}8OdymIwhXHAMcs=`UG6(Z9jg6f!SCRcmB-mn%( zWYVt*ZYzMP5A+8!JS4F6f+}@R(8^=#au~K=50Pgf4q)>`L$Y0Ay}NBwxv(wRT zMRr8HD{7VBM@EM8^j8WcvS4D=EgJ{Pz$H=#ke0q}naC~=F01FSve1jht3yuxeQ|u*FJ62BkjwYiFe4LeGHOoah{jPC z1C5yq87>!fN3U83;sfdH5*&oDn|Mn}44$OWMkDhdB~^lQY;+)X?O2$G{DuhVVU^O0PBbnJpHaxJ)0)vSn=A#MZPG8~So9V)yIznVc%7}*_w z7o~@WXE%#&X?513UX4z9rVd>#s{Bxk*T))&`sWJO?~n@sX#~YcvwRm74VbL9sOBd2 z0rIRK7#y`lee1bzNViY{#qcKz?*8aM-HgXxoP32{k1}zRoV+rD);p>LC)xEnh}FLw zGc;0VF`*DO#G!bg$_&++p-8)-rq_dPuIgMJ%FpB6M?BcSu0M4|-$_evzVd~w&+Mv4 znK)_oV418B2fa3rJFxZ`c7i8i1zS!4ymdp(r!4KIFq(W}~qG@FFZ8NR}|i zyd~+rFWKcs>(M^1KD9jS-*4B!o#@Feec*t8jo0tsrdK}*>kl7vranN}*$gA)cdVuu zO+B&e>ji7fGn=+}^O3THsH2XQ7M%}ax1D2C4kG8GZkJ*$9e6^!9sT#_Zh7{V78lN_ zsylc{TrZ|jZ~t0&R$IiR1CsadYyHqERVAa(ops-aLvoOMj4WOUz204L5P49qhxx%% zXI{2=VSd%TGuvPDd|JK1L!Mk@BM5K1s`9OkJS0x^{_=vt1w(qje!bFdLhO(nf4}p9 zkTcoEk395l-rlvhZ|q(5><#z)r66U3Tz#&KSuZm|mZ0R=gqNq5W^On-xA&)e#9y)> znV@!l6%*^Z~z=%Ct#4a~WHDG6}N0m|kk3>yR4bn|+QPK;j zd7<2hlF~OD8+&_-7@t%5&doJc{~R&0%7-ZaAVrmGVXZ&)_Qy{vsAtCP4}SaL#6@Gp zA+B+a>^p;~_d1g-?2ucWU!)FLX+Hee!tX|v9D@FT?9#Mg4Q`a25{iK{RI)Dr^0K4m z@zAc3!%9a_!wrkiQS0!BykcuN(V*DQ+Q%gOTvE2&H{ESkRDcoMkt!A}};t~~WVf$8n3y{s0dEAASFBJK9 ze1NECbEq+)BVyaH@0w(~Bfp*WBaKVY{PSb-=yFSKjfY2in8tDSP~Hfm=A%u3!snkm zvts`8Rz!h&PR0Be0}qrDD7BkI)h4p(=ABhXb-Jb9moHHMx;V-IrERy6sU8_lmZ>Bg zQjjGZuR3QX4wVK7&9MXrYTZLAjcRnG)PJL|8jz|oDoh<4LaJ3dG5k-CgYj#3xM{Iz z+P18UDoEf)*D7jcN!KR8)ab|3>;{g2O@%Pe87l;-JIBc3wwq-e0c_0#yi0g+g&Xg9 z=l`wMSFB&dL)-*v6pY(N3JdM0$ew^bO08Vox^)}#Jyl+v4X(U*t!bwaUVx~Q#3@yq zRFC6s4Kp?4UH{iM=a!l4REJbNWjN|}K_u*JwfUbvq1E#%c{8=biU8NLFIW(sx7kY? zyXehr^3s{IsRsBJFAFur)VQeb{68HQ73UkCg`2Ce_bAOqzFBjQxfIa{GbI2vd>uwh z%B8@;u85fm7n}Dr<`~DVYApzfLOp47?4NM!E93_8pMyH!)^#=)$`$XGT(a(=7<5~5 z`R?1ctwT)LfSQ}Kt57Xd~Ound@fH&Lj@w)BDzP45x6GCV6Vkv~(qy~e)8nDkrlAx`qB}1-C zi`8~WOt(VJ1r-o#6B9T_AgYg4gGien2yE(4FN7Do|Hnf1aE~I5b5+@~#$to(#mre+ zBd(XyNs6T^7hf@U)`IB4P$c%YI`UZ5Q>O!Hv$2(1$68y8%jbKQJFFGq!0w?}4vn{X z-NS*HXAXQne{8ocF!6wc*;UG4q4iMR4kfRZPP-a)N;z$3@trZqt%Vfrc%$9AjBQwV zt)GLWcDKp-wkrUE3Zxe7S~P(bK@nf)Y!C@oVIY97(;^c`cj*+_8F2!7`F8;5*-hSC z{M^_EvyXdf?2^gC;pUSYkDIaEsN@~Kwx>Uth2s_S%@F0a_o~qu+0KLH90l;P#u2^#3&3(Hl>3gz# zM6V437E}v}h)3MgL|1QhDul<)>q6_^BIGP7Z^*H0MMM#ASlyF&mpPP~gB;b138jOY zW|s{qVs2pu9>kzN*fMd^DA{f76a_pyznbDC8>v zO2vRl*YzGeEU? z)*x1&h8UK!)?;4EBpxWtR~VsGD!H=SI4r~qZbk9&*n)`+N*)3xPFHT&*7-s6ltCYp z#*O1%@CN-1C2J}Byw~@QmMii zAbF!|=|Wph4r(Ui!J@iBp5P{T_RzO0QU{;8)mOhIFphqB?33d(o)~AOKRW!Jhg*Gk z%YAmDPnmt$!?)Z$VSkT#iJth;Ve*KIWyjA^mw*_fhE%{r$aFd6$WbBv!V%bJxRmT#xOf(ZqGYWzOcVoyhbeI(3jh#&0AeX}8pj>0T zW&iwo@T8w&EYc9)WI#uNIx{m$%K)^=qbN}>kE%!qd=uo49} z!{(&%>%Uhb-gIUn=CLbtJSdE3&4H7yLZ)j38Y^34nRY!<)hBkx^X@M@E34>GV~6SM zNCZbv$9L-$5>j)^>oNoyg^nd+=R4ae!?6rvJ|WnYG8oOqf}1nbVZzSI^tdpJ>fTM& z3Q@9$@?KXSRUFiI{Uz3$j(cc)??FR0&3X5dqy#l@nLMq5VJA-IF>sOo{Te=$kKKZy z%dIuql1z?mL!h%}()*-1mZ~)lktvenK=5OIQ;;nG1ElVy&EM~QazXd|zq5-Heq?4* z3;P4)EaI7T*7RFE zg0IUL;kFET;ZSHZ=@1!6e*+rfQx70pEAPOswj%~BU1KSkEM3b(%GUtOngPpbOm!LA z$a?JSvKC;o3KzSnb8%fSdk5~*#_uA9*KpM$3O77Ld_u{;2^lZ$Pi>C>Ol#rBN7|*7 z51IG5hPGJCE!;Zb!}?$BV3MX__LrPsti&TK^b}+WT7hu|Id)} z{@I1!w5*!BxdAOza^84Q3RKD#dY11MhQv#G?G;RdZWL{C&Oyi#37dQu#+0jtNyre(a7Uu0zX=+aKpxmq&LP0K`iuTo_f2lLpvff} zru6`qB&st7fzh^?wLn=>%L3h8Sji%Xf@@k2K`qmnkQvB*grCj~c+;kkvbyOksAW4c zhO{EMgX}|+eMYywa#xo>Hh+9w%0;t&A0#A^&DJR+{aD3{H94iVObjUA3Nv&bxS#)a z14qu1#|3erArY*=wGeEoO$%B|CI2P_4mWIuI5`x((x~LEm6OgF*KBEiZ@*rf;-3Mr z)bZT6KP#j7&n#5)$vDT$v7n6Uad@9Jn2sPkbQ$VHfF43j$|?L!Kx+HQab)_TKp!!3 z$T1zJul&!0v(Fg(?EDHzqnh>uDVeFUr2JsCsAZA~$PL^8D@;`=unp9clzD{0iiP3! zN3dE@6nOZbur;c~S1aKVn1@9J36}7yyha_!n)La)QQyD+e&zNRQ>H%tTNEsso|56P zg?o}sZCWjRRP5J;!vr2maqg$(qyG8`H9Tg+t_s4n_HAtB#@~bZ<_m_4+b+tn zT23X;Tvq(Yl~3j0KJ$c)?)~Rg$sxCV-h=aAU-P%ET91_wkzAdqGeAaCnH^8ItRq>jyLaOW55LrRx7 zrbI*KG=v2O>jN#es1B)0By@%jp;%^=|L|*6c@fiG;tmT@`>@zLybj;tQN*ifnJ}83 z2!pr*6C90lm#yk_Q`^*ag_oRv&dL_i1X6~LefH!&L9@Gm_3{#QIBNKtxBWsWzz7w@ z=CBgF;8w^-lT>M|Y<$4UcwmsAHi zZ;41C>AaR)X>rBRzYY0e;Lh=b?mmCjWA9eQhm74{C7)Uk$j>=&)9@R#-4lwJ#FbxTm;XoWWVZ|*gZ zRF_O$ZgmkVCKfH?CUk=<9cU$u`8Pw(MD9BlK`Uu|#4wQq>v3GH23noAtZn5@ErNHx z&Dm*+c(<~^DJ;Wx>}!Y+_6i|GRXEqYOTy>e`sHP*SRpP&UY9tfF4kfT|~79vi&< z-shTsd6E9vP!SElHO-t(rULuK2^mZT%fNS3V4F50Su}X4cSy(8;Soy7bXf?G*cOf3 zEfgMSqjLu4j;ltaLx+`T)r2FPrYYF;hg!Dta#cW~(%hT^$?&EcUCvJs;Kg7Ts@{Lnp}p+ z@;h4}*)SlHEkh2*Nw9-{apOByJ-ukcH;=de4oYZbKr14=Ood=5fC_`?mLM=PRk7s0 z4XQ#bqtQWWD6jUCJbduKO(#dN}~9C(&oqlAcPpR$w!i+Oxef+ z9waycoy1KELYH;h$lwLjkwVgElS)iTk7d0yj^N*^ zW8QyhN%nsSwV8d))5pExmlYJjHErFJe={ms84m2C%D09Qt~L&+9u`s{lwr?I_%V)q ztQv6>h-U?oUV<^sTVhO(zk#PkJ4K8Y*&2$#Lu^WsAA$RFIsW@u9oLcYw+zyOXL))L9UxhTqO!U4prk?sntkr zPi@qBmv5W0d-XV5H2poGoT9Xmr~hV)xI7K%#)X1lW0*K8E}nwp>U93eQ&)6t-zjwS zUOo5uGcF!>r*)aK@xwdIpDff60{Oe%I{)N3KW=OBwOIRF6`~_dsP_+!8JQIgy9lzc zo4lPhN$=Pw2ay#As6>9`P~>=MC+Ejl0NoU4|BWwxuz!Ew-_CyN*-`y6Z`{|c*w?1K z-K%QxFP5rLyKvr_+lqeqZp-77@^2BuMYXhlbU3NQePs>boqV=&)#u-cw09;vfRF+p zx}+;*?laRN-=+px0!2(v>X6+%7S7%IC%rTFnIRYc{_6{;EN?Yz-^J6;*mK)tmNq6x zI__WRJuzkZabHj9jQ@=~3J3`Lhmf;K>5!83MedC^{qAHnV4nzuOG$95Jj8(+$jyH1 zk)Akj{`d!D@u?&wMQ?Z7u@2q7W!kJK`~LXSjE}#&(T_2~KHa0Q$tl`$*P7f#c}#%e z{{ZZ!JwLclG;21o$49%*YxLrVxF{QGmJn)li7AUSHA3oA%0?@E5w^XeqQ^csvRA*Q zr;qyJx4Ry{`j(HV!lVHYcWhCzsrqqshs=phSV*WQcwR@TMf}!kQY8Os@)*iK)+V9;q@yC0*Udhtq(zq<<)xeAhX;Ua6x_^6D=6v%BV#Gx8$k z-q7hz%VP}E;C*3ZZlH}}d~a^?Dm=Cv3;>w-(p%%x%;G`eo`2PZxD z)0lfJ2R!zqrN$B*)r|k!A$>E;yv7NX4$XflzG3!=xRub>q=Vta1wNJO*62oJ{O&Ys zwRu_Zs$sXypzB(u&AUABt$v!AN6UtGUNvm;YZos4le$_Jf%EYHrp^J>N|JDTmU%p- z=lVrnzpZar0_%odhbW3LoWEIEtFcMN|II?qU@^3Og$tcB27QC?8Hg;u?RKl2`%}(* zJ?UFPTF2@yAJvifKcNdVW78UtQSkb_k@FWHV})S0u|ttEqLrSTDsdgijb*EvYm+4&N9>3NVTiRH`F~J!M_eT8(f!lg-ME_44wI>g$gRk`6%%>?$ zevvg;sZLAPv4m^+4wDM=zECCsyiLJu6DJ-PwA9~nZ3BA^FGo1pfnGsQ#Z2tZ3YjD> z%t^5PlcPF)ir=))vAa4nH!ke`^ym@~*1$p+(MdP|_q8YNB$Hs?5;1g^dE=|0mZfI0Oq&N;yp_Xe z>LvK>lP@JC&8?|EGDwILdnMp%ogs`I0+ct(8hnKR=G}Q<`%#6@T{7kBbr6bIJZpVh z?pqC;3!+x9QeZ=Zx~cz1ZtmliGI!M^H+S@(^vVMcm4q=rk9@m}n#Y1%HMDuD43Nw2 zZhP!%Z~+EzAA2U(ik~55u(2}~7C${qo19_v*-~689=S81buTsk1P@u%dilz+&PwQM zS0l%sn>lg$5H3Kbc|zQH60KpXEe(lV<%J|vO=Kd8Ij)k8ig$J`+c;xIjLk6y z%R9M4Tl|l`V6$@s@ua*Q!_DzWV=p7%yR_cB2ZvRvZK+5rUMsW~Q!Jq|QF~q=%M_u~ zVcl&xZPSy=Z#;7tw^SKUwKUi$MJLH6aYPQWl25-Phf|hs=wi-kn^ldW=w-T=n#(hF z-bybKS~e7>Yvvhcn|!haKKBPV9}*NM5ZH$V<-4NmUiht1#ydA%JoC!#&s|}e?xu@d z@>*K#MWU10g1`IhUY5NR8*976MI&^}aJxLxX@UCe@CiCoZ3@8Tlo)Vlj1}0lP~qep zd*!h=#hi#gSGxDmpjfKH4>go*oRU0S%S-uXx`rP>7~03A)Dw0xc%&L&C_6%vY~{)m zkKgmCybV|GT-sQT*NGcQoHWxKlK+&NR|p4?cqS@ z#-R*rd^)S!piH8++%u|^2=Do=XM z@OZG883Xi6mj}4H)2QkPI>)99td+jfz5iI+IA*1&cr$Im?hqN~W~0!6^RVF7u}BS( z_wX<+YnuDWj;xN2fBEnpl#WZsPxCq+yYB7r#n*$XI_8w5wobFjtJe=0W23WW?-D$| zGt%rpUop*y?)wl}U6lqX;z)OB>mm58nOAS^Wj=E+?)l*@~0bg!Cl-;WsJk(<{5@6c) zTzJ$z1NZCPhhM#aPtqwM-e0Hw+Q4}zX|ex4-A?{IhVM0A{rtOX67ETk07#4jMwvFG zYD+=UT(2W_JH5EqE)2`sbH(+&H}AS=97-8{h(1o|3BB)gUFP)>I8%Na;c@Yw-Gow# zhp4a&HUS=$7|i!*p<6yvyZf19+>B3O7aF}clj$j;lbhk@m)T%GJSdiL*BfOoUokK5 z{?^a$o;rVSqak08(XE?DF7@r#It4pkpC=;47#IZY{_@KnTk>Bq8ooOA(>pE=x(Lrh z(G93uvks{Am<2P=DN@q7nH>0yQWjKoGn|yh$F6_$W1B|aRbgl=hj?W}{d(6v=mZ5( z)a@KMa&@fz%1Muz$~pu01PV9*wZPRQ3gvVhK#Z44$sI3G<2cXnm-Wro?!(hn_9h{w6*o0r1pAm$*Kh(pLKeZoA+jHX2NBQ z@>iXsae_f}GT#}AJp}POSFY8e9;SM=r%jsO zd32K}{wU`q19z@tmMaSzuO9AKB{KnjRk%!y?yXzp_gXt@)%amODuO{hCXG$cw5Snn zwl64h{`0BM*te-)kBDi7*aM0!N(w&2GV9yMN&T!T`9dtty}i9&xna40xI;mx%O^X& zjWHIwXd~#lX6>YodnX^Gw#-_pS+7KX?1uh0ktoFd&U==Z0-nb~CL^NRv~&#rZ^ z?X``Tw(nGEO2^ebJMx}9aI9ALi(+&|sH>Sa%T)NnV?S>F%dylbC1^=T>_wUoz+0 z2Y)(iFIZkQr(e()1{fmmbO~g>Y5_L#-qpZZcZ1n*~~%?Zw_^zxbEIkOG%%R zM27dPNKzU|Np--pkW8f1XoKkH2q2@HBundWG!m)Lu35v<+*)cewHy%}@$f+I=b!<1w4Gpz9Y4Oc% z8XDNK?iP-fqZek>ePdl=0YbUPh4LcRU?z}Y{qfUE+FZJE*wCTPmK0awmPsJIB2Y6# zJm%yXI&&^WSWNxw%lQ*F-Q!HW=Vu0&ln&sbyZ8b9ftNjt$Xd3M<`p4tmt&~^*dzAZX5kbaMZYR&eoWp-|Q_iNhMEv|2S=FKosf{QJQhn(bw!s-h) zs?3O(y5rd&Pf6d}oirYhF=yg1)8^qjPYM*2q=}(!OeMakn1{vO`25D-f4b#Og&B=E zznawGjWKVpjY(N56muo=7odzS>yoo8XBR1m!%G)xBi=^H+0{&V@u_uYFZ@@seHS z$1uex2tC5ZE8YJ8dJIbnIBGm@9f6EHv3ilNzI-a5$GS>8QQoL4RPBV zTpi}qA3yy`@AX*K-+FH6sa%a&exLLWv+thZf%}nHTW0Mkrchx5XMYdU(^6*IsC?w3 z5;!oztBdk@WGBfVR3(Bg3O%*u*4SCUU;5^wE4shfyP)soTGIUizVL(^sg4D;yH(TC?FX2)Ra0N3{J(&PZOfpNrMi}hT{S{% z!wOYN@F>p7eAH*3`qM8w^_2mS-1^PF=ezdh&nw%{d^D@;il;)Z+7+d}`jovP13~D_ zw?Fi0IVm`0tS905cB`U>86!qQoG7q@A#9q0MGR+u6S9}hl6QIr?wu4aY*Kq$%>$NT z?lAt|jq6sOdCA1acb{kTlS_a4Vp4~$A9dr7Ap7 zQp+^n+hGAQF=+SgKb=2RyYmTmCp<&FW9C+F7GQCc6OjOCArf4^Ft?j1R=3(K%)*LA z3VJLfPJpKcrFjW7IywVeb;W|2=yP}gUz25^LQrAjAMif~?Eh+l6uST0Nkb`3H8iGb z(1v4UhsCH(0rwTIl4W`qi&LhXddIQH{z(t7gmXF@7v!6Z^PzYUmyUZhorQ{Jj#<7n zU$ml>nIord98JPQxlCODjOhEni8I3I#yU+8oEqa{fXhK0e@gzbvxh&c47<%zy_Asd zI&n(=E1k;?;@IQNdjqRG1>^HkM*D(Z$sc35;xMbhXZ)G_+y~*Co#xw`b=!)^FFUpIHS3$Lc=W4JaycDy z)gdMlXS4}%VICj^Ib%m%t9l>5!nz*1Deo<6_|0qDCtI{w8z;YH=qTT|=4z~MCa2=^ znN&{N#lpJ4$J07)35Q3_^&6xvrM+2bseL{x>+)flca+FXDa)fksmiENSbGM$;XV&e zuk||!YeadK70h$QZV9@V&SDQ=|hT6w1DwLwkv?DhCYoCApQ0q#YAgMCjSe4juu>FqHGXeh_Dp5x?Kf>}zwOhXpIh#*nSaukgI+py{*UIU3R>13 zzi#7o2!|G}8ag(s>toB?TYSF4d>V;w<}G+*Xpj$a=`)Kji{e`{9SAU)#)OUF=M;xgm*w8}YRhv@ zZt_g-no%}U`)8U3GmpFU@}$1mMg^W`3T%Rj&b?qgIX=c3C&ClZ@B&p-F9AN7-ogA6aQj zVJxvhuaV3{oBGWtpZj}G%Dm%~{x$rk(W_LNmX@5so~)rc0EuFYWUIRIp_FYlp-u^T zcI`umut|Bx{`lz~udEpBwVxSdp|jk~B_ofE+~jHc$EffKCegB}(ReO&EENQMg0n>o zO+7I2=v`O+EYZrb7CCn|ZvCmDq?9oP4i`vYO6C9%DvQOb?DAJRZ2Vpe1 zYyb*wwU*zTwEn!I)31G-&gjvqILTom*;+x_xkQ7Jd6ReR zpl4CXXOEoF_wlQHFWi5|$9WcI#}*Wps0grPKd?*uV%)yIkXdZWeX+x4kAIs6b$rO} zW1jufS>f?ZhqhhRF}JN|;Td2g3g(R;|A#gTEvhzblo6Sn!BeJ`p}ct2?}hi4UB}y8 zy{BYG%cNjkPUv(W+G$mlo?}pXn%yOLfMuZadf3nvdZR_7*UtTX%k(9We%xk#npwEH zw;)xwRII!IgGM0bu#)OvkI$(F;;w8YOyYG--TD{OmldgJHa)rkKLwp_xG9=qwSszi zzLCdF7x(sPU-C!K50k4}?(N>=qWx7j_L=--_oTNY(J1ly|D+x>u#v*X%!#`%u3y~# zbD@}s>lyFvyT_VuiTwV1w)e#wt5b@~wj`Hr)L8?k+k7e!Bp+x^?etia3+`N`e6(}o z6`NRw*{AEWPcC@;TSAX=$4&?!5)w^bf;$YVqjThI)vE}#k(q7< z(#?RIkfC{&VV4*ri(AOqg7Hbd(Q(rtedq5L8SlLNAfCYKYoZvA%g42th@*emM(@Ai zP8gM;7Ho;O7)SEzHNARdPc6r=tt>rf>KIEM2=%z?b@OeN93Cp%Z-j5UuUj-bzu^-% zS9QFuOXV}$?&QKr8rG#o3J^=!k*Kk8Xq|c zNLlLM$(;Wlb5`FIUiiA_N6k*(H}u|{4q9M!RGx(7LmaantK2#H9UFW1)P*Q1E-fmWVMt;!Pi)Q#L4T zg??sA<*r5(S3SM{k8|feEbl|>gQ~HpOx5qLK1;fRSNN3m+>Wso|GjW;>d9aINx$t? zSlH=Lsao9dZDz=g2HBEDi*X23ZA3vfPS4TK#v64$YMaf{I$6HfzQxGO-UC)bQ{Py> zty@*u=iXgO|88{IybiZ5yd(A156Z!GAXHEHz;1b-;Ub(l9=jO2+GL`fG_EDwWeAgM zU?oDaNaHwF#|YJq^u$9Xj~P7Gn8abZ049&6U`yO2%~JDxP2+)b=EBj1p_{S#^vgnU z)&yN$gs2m zo8W4Q4f43*3YNPo&@Ehu+=_)LBwaPyI_d65zp{3Yo}dw@qzNOYG}r)^I7E9Wm*WIA z;IBd1C0xl;LUyArAJ5KpQg91kkMy}Md38=6)(ui^lC#rNS|wzfc7@?&)A)|2!d07@ zUUpE3B3Jd=5T@#+>TE9h@xA?^$F~LGgta-!vx)iI(W%ZuH$sloq*8GSIUT=R)S)D{ zyfjzjeA%{OzFV+n?wE)x^r(f+1$=7boHd9=y(k2eOT5pvoJ03MrHq}kM_DqF=Hvdf zDyRFLhsWX}-Bq#*oIZuA3g4WOzx|V~C~TpF-A%_!{Jp}a)E|1Z|6ssXH6H@5mU@T- z!yG*}*LkPR{dh^&wLw~XFp)RNyX21el)*8f3hP^Z5i@f|wFv98-W!h#95u|fGA2Ad zsS@eSjUhH#luTcf`R(KV>b!|_p8sPl$-sb+Syg{jI?Oolyek)FXRwLYq7HvhPjL(- zr?hXY|Fmqsq^sE6yZq`#FK=)v8b4o^VA^TeK$##4@=9jf6v2ZH!{I6Us|wumGXIom zGc(CScPD|`fXH;1Xs2Uwqhs!>xT5zRRgy!slb^7cp1-j3P2aYj^m(uAnLgv7!YAqK zLEjKtKZS0|vX_p30gozY_q0qG9{DIim2|Wnp*D(o$(AfDlxNC$Pg+L>0>5nK>m!~j zNSQ19c;HxpCZpXP_u(@Nir-63(w9nd03Ha8*pt*N_35*_{ruzALq>KVF`zseI6{-0 z^!1H5evnGdo2!#vEO4`eNvE_r|LoH?wy)u7J0y;#yxsc78~-G)B6>qMrRV%pAMTAs zwzN^Q{u?cv$W4VeowiG*Lf^~!T1(x(@Pe^!>RIFWELu@4(;FYB^JWfeY8$g&{b}K_ zs|LSZku)c$xyWIVvH}!^_68L+@;+WraLodH-I83pK`eDiO*&m?N36U-uk2DPBHLDR z-ZJCFOWMtJ@UHK)MVGD%FD1j~Mi&ab4(T4lC-GD-*_>1|yUW_rZhz7?lr&Upt7|i1 z8JGY2)p2~b7$4@Hn-iBDi9d9sd1IfuK~6OF6^)nkN^HK6UKZNph(iZz^3v!Kl*>rppI7Yl9PC z{IcWEO@EFAq(A-TSHe(k-nQhSD;7;Dn04>{A4dI0X!I=2wUABCys8B)o#s3?H@7HI zx~N_8(}zUZXn0Av5qnF@UrA0_kZU9r2~ysAdeW9h$^$pM@t~v!GL@hh*Tqk{s#*aH z?X|1%ZjNrXa(-%F&YI-xk^+?S8N>2Tvf93W=Z36CZC?&9Y7>+FM}nLIeQrBV_sxs0 z&KThI?b;zdCc59cbO%3d^_UZRC`C>ZJLbQdE~Moc#6l z)xTYBW*9on7`|J}9V=WuI^g)!5EXZ9G^UrGbEc4@l4d;fM4+&Fw+wIH=J}JF-1hCN zSIp=VM`)Tqx!b^G-D}d_kLQlhPuJI~?wxAE8WBq{T~j5o#_)16mQhvlG8KHty5AK$ zay8Wa+ztzSS;A(9ZiS9z=9WZj6N+cKO66@P{{H#?*JUmvOdGsOHtyT_{E@>?>(r>~ z_74dBM+W_);+y&`K?U zG(S>!VpSe9yowf+QF5)74LHI~D29=2C0))!o!NQ5d6v?&;g_8@NC9m7kaKLy_gcLE zYf<^rS({%Q{M$3K|45*`Rx+|x=&)O3v87#K%Ftu8i;EU?eQ-5RMs=in0S|Hu%+n(ACE{d8RI0T zcBE-L#w>qqSC>Jt1~E!K=e>1LR=qNIRTUGa#?6h^Dz97DPAddH-{ekTa@3#nOfqd5 zz{JHj?l=p3Q<%Qr_Y;c9r3OM{(y@Up(1w(e}h84t>lXq2BUj@Mf!6 z_q|h!iq2D0#?!hre2$y^=KFsPu4Z{6I;#3{j16tSK^a+syBNCGxbCGfuK7v_KIb_m zbPXn}O0`6ug`L)vD{sGH)AFxBkJ*jbX{YZQ{s5MUos+lp&Bt!Q*)r+NU~K zJXKtDXr&UpbGxQCNLv|{o$Xq@5DUCKe&%IuE)j9g^v&{U zy3=wsZnR?R4&I7WvNCkoaqCbDGLLE12-_f+%wj8WRaNP@!^>GdFKNRuDVN(7ybwoI{IPImkXhiUZ>8w^=CZ}+;OOMB|Y!s6+R zyCen7S2I)FbUg+}2yISdBM}-8C$W%H$%)~CBpvnn){*!7#Vp8L7L3EXWeK-LxU7{! zOAKqKK`nDT&g;s=c_Yg=#5GXo-`+PnE9r`xKSWJL3}C5HF}EWDkMUcNos-;s@$Mye z><($g&D*P*SH3=>AJLRkD{)1_YrGVokioC%Q>-s(TsGP5j*!dSdEfELP=0F1JqR=M zlX6UKnv1D}xhp6*=eOB+-*Ww<%jrF z7Pf4GdxlUi#Q*FisDkx;TxdU=`Y583Oy^&-ex85D_ZQ*E?&nsi#0M$H7Nn?Q%Qwz!in`XN0SLtLrRKrTT~zUhqe?|V+cLxjL)!j^qU246WoHelDZnTv0TS)K8g?-eCG|5*Ly z{rs`Zzg;aPDYjquRi_!=e?2vFzwaf1}&I;Js!GXA&z>E+%(M1N$Il8ACwggVxfk5-$&JL zwQGvV&Dj=l3QE}k1P=%BL5E50GqOH{;Y>=Jd+ye$D^o%{J0#}gb`>`f+!9K8csv&f zUYkl|Ox3MM*X5P(Tc6OOs9=_*VS&&@09i@&@Z!hEZ)eC%Y+g?1^ z8Myk2@VY&hFfnkBdd}=jFhr1k&GQ>i#U>W_*H)tM@JGc$eZpHqGE*H@#it2#a~8}v z0oyb3A})Apk`3n?WR)l%tN4gsCKHMkPWol`Y1g7(^@Q&VvR5pMk=pYA5%(T&O)cBv za0mfH521&agwTsb=^zqn=uM?a2Q^dyIf6(Dp(7-03 zK@qN%cseZTMB^S}4J#b(dUnwd4TXVzM?rtFZ<~n&bOuV? zb%zvigI>9SMglGwcv!&s{{aXI1R;tt#CVnR&C#aIB8X-fn&Tm}G(g9FlXWBrR1MI8 z;V@u6)MF5Yo`$gy2!n$90!wZI>IW|lEH$(mDMaI7FuWJ=P(c5}X^cMegB@N3veAG@ zcue+F;&zU0pp$GA1pzvk@qbe{;8~DhqqygIQl=YG7z=zp4@9H^_ynLLp=~pz|?_Kr`Zzz)9>Hi6Pz?}1roqL zk=xE+fCl*&#IJ(NV8(-IaPh51iizA{nvsA!yf^|!0z;7`?VaR+7CA=T@qvH=2Mz_1 zcfu>;tvMgy!$);2xA9_=pED_od4qB#rS&VWfR z{8PSvBjBn8vl=5aC1<{W$Da>o5QNam89j|W+Q;Q2f!raZ4HB6AM(>;We)9u&h;YER zpNIs3S&+bLYcdoG$BUI7<;N=spnV-z^c&#X+X<5VTDP6Q0}@t7(HVzJEwtM{36CA< z4+h~u@!I-aP@Qw%sL>!n$6LR7$={qGcks?no&xVtk&R->C?s%d7?^>9@w+mIyN{Jp zVM*`y<1j#4IG_dpE)<}9UmcvUxRZ!1A>a1=3ZgsX*Zk2eqDkyXNb5J6Fq$7H2(?R%nJ!J>r{Z!znt$9-P;A&p0V0h4AilF3a_AtHg}Fq}Vn;V+s0_d)hr+9hB;gjIKn z2x7Shyd(M@$WUMipc(!a!Xtm6f4Gb<9&!l{EQeYI1*;ebL4h4b91;xrm}dk5EV@=+ zPcrcOm%YJ{)PK|EGr^LUA#esk52R}*VQsDE2OUNXj0Q>ftvm65WjPQI*m&f->h$r& z3y))CyPu7?K}aYNm@m^R8U!YI7@XrH(;#D@8m&L5{l{G}4n+Jmd~I7%e*p*?dce2i zlzMB<<|(HmxYA5*BEX|Ms(RZthokE!U~R-p96g|X7GGtyuZfp zWrN5(w$vRcJs_J$muUnQAF<#zYMYr=g>adF0vmyTN${^k{#Rj$v*oYS>9%fT0lEDJ z%-r=rziqxanJek&~wR7s&4@@S#^V z3LCKqm2tr=Z7>Z8B$s{o)sT8+xAzBzw3`1p-`|LlxBFElhUFbBSQ{|b{w3b&ipWCd zp<{Ev%JsK6Hgi7-xmalK*yxdeN&NqWII#Y!?1=AujRAp>JtxB=H*-SUe?ZfAjuy#{=3A379Y7?>OX+3yk*| z*iWhc-@P2 tBFnJ56$;9tc7mOF_N3Cy?uBrm`$=$DEAUy#<{ZQnoBp#4_4A1(9e zNYHk(g0(^0w#y%Y1Z)2h_|N!g8uflfh|YBf`#*3HOdFF7n51~n&z(pFF#lno8zTOS zqWd>2@>g*XVA25hD&3Cysq)}IHRG@H{rfnEGi;o=`fFXaKPF>h5jR68Z{HNUvWs)0U=w~;X5PVJU7bjYb_+*Zv93b3DW*+ zF+1x}NIv8?{=dv}e=YiZSf2RJL&p6z!H#tYA-e7)(EcO#zrk{UQ2&z;^DXpaweF9& z?U59?+<;C0KQC1LH(2hEVt?hs{mfL`2>`tZ#{olwa;qzZsQq&+608mSM*(P}zkm@E z4E5p~^LpC=foC9pR?+_jE%%qQ{}M$0CA_mUFkAd~)_WTk3UvRbmOp_5{HVjls4@QFoaR5^-Ju<+A zMi{_u$ut5s!oGQaW&Zt{%zq~I)7Z345U3k)6a!SMkOe6ux$Yi=8gC=+0{{OP@Ut-P zbSMpms9gi1!EoX9GJ!7&=@Wr1sM!CDngM10iRE@A7Y0J(@pxjpOm!=!SdSh^bKa?4 zU*Z3ve%e13N&^8H40x%`+K2|iFP5#~8E=OMx*hDt!+;_Flx|xS{uA&gEr$dak}?67 zgK(WOagA*&yl$tLj09>yGu_*{;7WSXYi^8#Y;Rfp6Ey?M_?hLl>#+@frNE*qk-sF9 zLmy5c0%>wrk(yStSNcPMlj?xv616cq>Hh1tpIC0YK{B<0cFIIBfJoY)02>IJrWmLJ z6V$PtGqjXZs!+ufm|O#0|Iffr%(KmJJ4P>kuaOSe#1jtIgX6w^72@*w4nb?taf8xs zFdp-d)ot7M_zn;vAi4PM0HYU3(nt?Dt0CSBp#io(K{SU?s=w(eSDa=j$AN(16}Fw~ z9{}Xa=h0BZxc|31(lzm>7Q?$7w$4|P2=NGu1Nosnp$Z^v!-H4UT}WQ2qP zHpw>@1?-l81c*DOz_o#GY2=P~`vynFfMI&6fI$ZZ)ZicZ9|`^;E%&XPb{Gk$#x?-; zBpMZ``a;j#iv`p#5S59Ckb$;h1h&j~?4_TKx^G$jTX*O-;cY>n`Oz9Q5I6|Ug+gZr zZr78n4FaY=fcD5V+L=}WscDb^@*e>R&~#vc-)O$K8wd)48PSP-@M|bF+6_bjEQkAU zUhY_%-~9hb)wUZAx!tpjNaFVbk=xZ{)F#omX7XczBUnGP97+3oBI0-VzwTrLg1`v+ zy*LtZkctLWI)taUXGMZAupfp2SQ}{JZ=>ozW|QnZJI(Lyw%xyEZ3qdd6%+%9ZL=I8 z6q$g`YHw>2I35EG89RCYsT<87?FJM{gwoXKd112jONTtSxe<_7Uh~ao2zb7YR^Kr|5c#|JAMn7n|6Cjm@<-ja3*T11 zfb$c;c9ix{i2t4!Li$U~fG{BKpNhkSz&{6p7+@6p$6!Yoe=d#qdu_ip(eJ?@iHJWu z|GvBLYbQv70|b0MhK3f{6@`FlX#fDxaKKPlB+g1f+tMu{(3Kcnw457{-u6VuvY?yfEh0UV-f;}o7CpNiEHPLtB;ndRxGE$8poef?5j$o_P zH6u|m3y3q%h0dh*$Aredd^+AWKz^G+C%Rd9UZ*}pc-H2P#2u}exqthLmT9dY2snGJ zb3L zRY*U4)ss6Vm3yD0qW0Snk&r3vAFcR$lSip1Z82Ll<{1KVJU6v*vd#xomk#E0Z(cVM z|LkE*QsmTeM?B|{ap*9eSk3Iu40t&5C3Qn(b|Nd%>~A@lyRlO1!snubYd9%!hF{pY;x+uW!ur zvVpxfvYL9pDvWI$ z3_4;lsgfrWwK6)2gfx9lOqxE3^*@geo|f#+`sDxA?xr$ke@vB}V=zcSS*>0U$Kcvb z3W#Pj<8Rg}uWyr@lZTYI$B(u4m}G}o=?yy!G`MyzC0SY_d-FLCSh>br-#X7LL6_Qb zVUiFGH#=r}%N>_?PNJ~;awkU`);Y)h(zHjIW{j!c_1xh4`v#EKGm7|gZxH7bpgfPZ z&LbrFHgRerL)g+oo}QkEIVd7WaOJ+SdAoECLNDm`RO{u1N<^^ICnuHmL6YZI=#>!b zCU%1->@01-myka1$$t8|6;3Jym<^+_Yy%>)*)|BrG4Y>f`anl zGxq=M%Pw~-rs*q4Rmp0gbcr9H$DSyi^c5sA{Kr2g=PPJptM7>!D*b>ew^*Ridj!F+ zkRm43ie&P~y&<)LpF(w)lq|0%X{3uX!s>cW$M}{|ukSx)^Q#=y8(h_aUez-zmf%zV z96q?eF+q+RIlvk|`9lc)?2bL)-lsi&HFb$`;(k*`sUO!SH;tY}ai!OdoZ-MSR{Mk& zoQz(kyA`E~H8R~I++=a!sbk&T7j$lSX6_k9mG~tFbzS`9873tqhGTgl6sPNuGgy(R zi>5=AZU}lQ(w|ks;He+NnYMYIt4z`7CO3RpE{qi+koehb=wz#(y8pBU6X&sPTVH$D zfPFe7R>@g7FWz8UK$DRbO~5DeNfzg7=n9hiANUEKz3&Yv#h2E2PqD7xs!b?QyHmS6 zr65-ib`_q3r&t7}t#T$BqExR=IX||WO(sVdpPyYcrgN;toF@bZ$#hS#Ro3m72!-WG z#5^up=nIv%PHap&@zInwQ>Q23aqQZY_n=2Qtg`%xML`#OFbn#zSrDy~rWG>^vod-( z_v&fn@aO1xoPw%VODXlEo_EDJI=Xydj3QsA~1Xtd{_{ z^%?4Y9b%vWcZ5?oN>@YeP`D!~Rzci6&ycy22*V+BkDn-Vxoy${0@0+#cEx z^vCRdEbcZ@{S0n;e#x=0QUoXQd2VJ&7z10*q=j|N!6A>-=P~fhCCk3Y=ZqKBo8wXG zi4W|Q-^!%B+rI&;re%xTk1<3O2o6f8xEm~oQv=^wShdBD%jRDj`Osm8jJPll;Y)v= z11=c2VJvE_{1PA4){MOMTC<&3{KEZlk$pN94WESWr;zp}L?0_&Y<)7#BJk{@`5uV8 z)xlb<`y*y~PSSuD|B-G&UhZ_;#?@=0GD#u)ag60DUc+j7`u4m+bJy&wJ-^KOr%IX^ zZxK0-PUC6=?6OY9aU7BER@5~Qv@RytZ3M7=a_73@IuLr}T z1?3su`B0~}==##x=ajSuGA6wZ3=HJB{LjniAHJQp&*1)fgs;)&^b(wb+2ru9>}0Du zh>ytHu?dDeB|*un8&N>M`QJhWc^Gx1JmAYKilNdqH^UpmHTRW08dqe4b1JEE-sXBH zSjDS8Sxl~*DYMea0=`c8Ej|GFAoy%g!h5cvlA-mmB~_@nCvS|W;belF@@D~oNXXc$ z7dL@w)AwfhN$=y)F!EfNCamIx^yY&(l1oYGW4aLebH~dXQqqMCiAX?a}9$Ag% zgyEpcgt&zMv{x*)_p7ILJi=yZHKv4PjudrC+y%P%o%?=E|*rsIZ3ppcI;!BqT?;vIx{7M!JNf5#e8)ekH)P6 zk5A^)ul9|^%kWS~TjYQizn|1bZ<)if8;T@!LXt-1BrR|xMQmGQxw<$f>0$?!%S!)! zFz+nBu^?dnH%e2991zY59U(}{X-&eJ4i*6QcO@f+PMbpgNU477smu<$T; z-ZZ{zHfNj=DygFB%Rx)3QPDt;uGSZsszz%xPmY=r@3|ZFJieD;`l86`=)zY}279K3 zaq=3uQ+e&MJoBszdP8uP^VT^*fkxl(Fa_@HAa#k#w;mZnHhA-*fyNl?)9Z+B@zD3@ z>9}cb*&-U}%o+(OP8X+Cic=|btvvxU;y#1$F3-xsEe*|tCV?amU4PM-^Ui* z7;i9AU(>zm$fetQm#QzjXT5q7NY~@*l{TRUwE1CB`6SPZR&--SyY%Jn(4|H2FlJxY zx9DI!82fVOv(KW+)AXYmdY|c+wr3jA(v>dDqIGU1yil6dO zMv#p5ZOh^Hnf4d!X?DCK@nVHUp$S-MWjl*YZJ;%p5P%B*3gQjK^k@+&herBt`-%KH zy^!RZp4YWb&0`dM+Tzp4y9eYZ2O!t9y@SQV=-(A5mnXrgBCn!DSUWjIKQk<;E*bdr zCX7c!Gq%;7|5p8;xVtNYHS+sd0y>vPI6`}ZxB|OP7@eV-(%r&^1DbxJb#|*e3hme! z=c(zfkpf%9jQ1umSnNG3%)6^IsFk{j?alDuJl5IjBUvtXHYEvl1Fi1*Y|cEG4xM1o z`*3)fUC@8?^^$6uqTW0Yu8bobBDVqGZ++QaIy|{BFO7LMKX-Y}G1Rez<1Tn+xqWtK zLzu6w6YI071zu8><$92`s+@2~!UmC=f3DbLi2KjUI|B8XEccQ5>Edx=AJ@T42nI$5 zKdT_7>X+T<%Ut`elWg&qVv55ney*>=qk*d|$8Ic3e^)C{fwv`HM?J#!xz#O2RE+-H zS8+alkzaV+2p&;5>% zfMecrsNq~>!oPi~JF<YW`%}F%9hmbZ}EQ;jL(sL9SP**=w>`vAyzMdK#V#QbOP)? z^i8MeEZavO0`%4Z)iAT6W8LEW3dGYOiwuo*FTtqjoN-*>7_95s1E82u#R7?b%vrj_ z{{k`qNZJ1mc7x#s+L?}#h#B{mZgKfuT|T67FBf-eLE#0-tixQ~R0$9GS?4%^u7f(k z#ZQF|DjrDY^M#3}DD>{SaE%7NS@p5#FhycI{wB<4>S2myPsB=P218#KG0t?7IVmO6 zET6{fKuU((3?kPgS*e?Q;+4wTd?k_A>Ri$(pVb>haQWVwug!zV&wi-jVsx*?!ueeE zUSX6}oaL3)L0DiOr|FSfiml$dnaXR)w8k+GgHotRrIqP@RWh+3sjH9;t`i$QFQMfNc=Dfws0o{hv+c-C__F_ zk&&J;%2Ax6k#x>OFMbW%sRnA$3V+pKT2dv&7XBD`!Tw*b7vpU_Iq6p%V=G=9nZcAy z*f@yl$H{438yn=Rl`&k%$DY(#yHnf5Yff^scK2UV({xx&eAfM&g17mKzF#5?s(;G8 z6j)-pW@6QRI%rvg(N0p61$hNhqa-=vRgaZa#D3(fz7OegMUP4=uS_x&No|5T{ys3F z)7S5foQK%;MYW9kKdX?sDo7xVjkO8-c&hvQd70CdW^|eyg$a4dLms_U^T}4YT#77l zd7BYMDHx5^C=7CO@WG*xUqQ=z=WwE4t6xEc{=4qyq8h$}N-CCE!$dyM1}EP)y{+^W zG~o4tB5cJ_dzq^}J4z^+>t*_l;Tl8lvs|CksoPiVXdij4<%ox4ztW27;RTv1#Zbn) z$KuLVqic7@NAZVWMW6NQ?pta63PS5Brdxjnz30)7iUP0ZUt5oPX6&){;Va1C(`eMS zC3VgINb}b%6C+o+a<+PFW_(ZTh4MD+F}QI4D=4}wvc6MEZdp=7-ZsOH%l4Ubq>0Jc z)~+w?;N52XHot=Ate+f;9yJ5jN>)4fHBCG(%+ciil0YbUwsoKB_*m)}HkGKQR7O?j zndc22OGa`=wZNl$#R4B>_=FG>e+>M3g7{**&H6N}RMGiUuO(Ph*Oh&r-tf>!nibod zwZEB3`XY{FfI6A6JHM?l_N5+o8vX1mRAFUJ_Epx!&I_05$AVpQ;<~}tE00MYXN?+7 zAs($|-C`G6q}%G))q~PIJF<&);`0`L_a|UVv>}l2nf0!h_^{7;>X={g^(>(DHoB`H z3130YuMU%tx739qD$O67z+W6%b#=O+Pl*7>=%~@Z|a_0JM zUT_lHrALYH`5qT8(Tj{pNr7*?I#(QOYStg}Q0F)7Rjo!bihJ-OaA_T|P4VUU9Hrj4 zzN3I{E!Ky%xZ>YDtr@KqgB**Nx4XEQzbNYFg+`PjCi{~a5qY|AnTiw(z>3d~LPh0- zhB~v?nLOC@f*}U{=T@-SQ}E>cxvPsw=nsDMNsDmyk$%%2A5S`CME6&aZWDIwWi6NM z_!jak|E_$!*PZLmCBX;dy3EJ%GfCHGGo;N6l{Terl0u3TmULg{Y0*m_(<&B`wJ>_T z{}L-gkudN{89e=2#eEVhJo8&R_0iyjl|sg(sb1wZ;#BQiyU55R$tAsNU>Q_k*W~25 zug6rn6}PHm{vP6ZQ`)|T&l59S51Y3B;^~rf8T$&-SIp8)?CPma9hb0S9udkdI-ZjD zjMjp_8k;2_B`k)Q+26uV?Ib`6gDoZN~?;5 zX}yn_`#kWm=!0<{pPB@C{pgJV=cH44=i5Idwj57)Cl!FT+x$EERt+9gbK#TC_v&lpSkE25l*w;Bho`PNQT!^Zj%Wom9mySnzdw*96@3ACi*Thh2c=GH z!+1})S3b6y(L9EW_qsq#ptUb4lzSUkEn~Z`b=F0=g2c4!m!+>A;!vN4D=lP}KY&&k zTv)H3oO*q!N<5S)mB}mF21|+`6M}6LlJcxR)0{Gt35tv^*0IT&NWgdMC0t%l4k{TJHw=@Hm3d8@pRDVkH-!`n!x^@uu|GXM zxYQMel=tDZVo~T|@(%66yloDH?mNw8x5(o5nvK%FwU3QC$tnVToc?Wjjm;pYR~44TI*r6=2h zv`SuYUq!L;dHu&sBHp$29b~s@+*oBx;$G6AIDTeUXt)&a5jr|DznCW@D)2zy0?2oS zyP%n%2e(Lg)n~ZlqHJY-1(hY$@g%(lY^j2+B7!cC5-brt@{Ud& z%)5?W<}7)))R|z%qhl173_2&#HCz<8TL+WM}6J(S&zP`R&8F!CQjT(h-VfoOJ0UKAa(}j#;O% zd{+lLl)Ik{o1+-1M$e4JRWES+4C&!kI<2vi6YXLF-od(vVC&+H2W9#n;Kx!Jyd022 zCC?^xrhx(iWcT!M9-Ow5~rqCZx{Mj1_f! zFBi3ma!UUNG#PShOV_*;Hogwr%*Ot52p-{WnexaB9fi;r3F3p^z@c_iOv=y z`wM8PSh&sy#ARkP$>O9<`zv!G<6wl2MeC3gs|y~KJ?A~S^WR}xD5j2RVcG6kNI9aJ zOd}P4trTP&J{a(p-Cw3&LMt$)J)}p|E3NA`+tic5tOW2i!{4%oUZr2MTYbG1dZOo8 zhuHPohayXAZqS!((4K;%1^O0bz zGVL@M&m}pEkDOjic~V6zZMMsD66cDoA9yc1XV@S6*h`M-Slr01yrajiO*wSnT6~Q@ zPfyf~f0Vu6z1DT;6_1-!jrhbqmYX6CZ;liWEo|X#+r8nx){%5iDFMAV<08lP3StDE z@QPOAHCh)p5w~ZmVj=K|bci8DK}A-;sncol*#{+M3k`K$^~2p87}u5wF)QE;Cvjgv zhQRRoFOH7&sjr~+ub`scai0uo%9}TM%P|<|&|XV$tj$(wS4z9s`#d>2zE6Pkv}q4kz4ENvnn_f$G6r@?$CeOK zW;Nczu!dvtFpR#6QRFM7idUfZDB4?vS!s$Y1F>@zV74<3EMJJ|7Bc5)soo{9(!;6c zVLxL*6=Pf)Iqgo>Qp~h(0Yj{ULUpv20qcb8Be;&&351i0hrgBbwdty-EN8~X+U0{c z^qm>~lgdW)I0^c_340ObLPLFx01t$WPpCGky3Hy|xKzTC_du$QzCXnU@-|Twp2yY2 z%5-YwQ+Tew>xC`o(_Ep(l(<$cj!DGETw_!|f*ND%+-DOJgTT56?oy>S+zh3LUh;a% zssSBR+-vu7Q(|z2{T0|NC<3erT@)W|*A&;sy3yyVM4eZrdZMHKeO6>G=C&tprGY8KXxRQNUmEn<7 z?g0yzRvv`neDUubRPAZQngD0+h5XT3vKXtA1vuKi=KdtmxSEcw~OA zVZ$?jj&PC*9cg&X-OT%R zG{Qe4R0wUwibca7g`@neD1HUC#vf=<$Bp09SKzMnBMKyQgyZat^O&069f!QF2b%Yz z**(sdOkRmC+}#0({r)0owqt{iN4QGbR_2xV=?pcEP%P$`*;|d1o?y*qxvVIh#s!BJ zVVpknw_^|Z9ymkJqg|9H3~}yui-bI+*i)oY*Z{vSWv+9DBiB()owkGH@acHoLwfJ# zt!laBtt1w<4J8hB1HfdIn`5;&Bf*;JhNG~DKWdX&%%h6!9kPW~%?ETO$=PC64*SdTAtUP4`KVz7vf!>A|y3%s<+ViS76D&k|3u@$WR&ZRoL z*>KSUIufP{4D`qWgP^bGUw`YO;^4Lof{l2pMU8%zmrw8<~8u$f40t(R$|3m>?8Iq0@5ewRf~$73DK{spmG6@ev(I9Q(bh&Bo_X;&jSItF;CtkBVsr5^efSycEL24Z#~ zvQAC!z+`q7DY=9*qD>knl@K3?n7Y|7(9#B{9vzJ+1D*_8vYA*T_7!xv;j_x_AhWz~ zYEnKYVqyed7VLZLBwwmg@hf1~osr}Gv<@1ph)DDwNvBliQa{fa&slifp0ZaZoXA~g zwnj)kJ4#=4X;Z(J^Gl}_`zL2+P9`n72qwv3r|0w;xA#qk+JqrueQZpPUo3})Nt9j8 z{*2HU;*7b)|Jx%&F5mbVt&U5C;3KigioOY|1B6fxsy)2KvZA`(dv^kjzhKF6I$(Rq zzh*&`DX-H%ijd!?5j&-~Bn-0=uV%HFNxjF}{1liZK2uRJ-_oNJsQG zJ#2JQ_5z2h=|}61j;*r_%$x`_PVcXvV6l5!v2rrA+2{rCs;%DS)mY~{2ZBh_zkMbf zoy18x7zvWoGh-4ZC8?6UZb?*qRDf^ilKWZs!CV$xRZ**Z7h!eyNOOB%@Oj=cbE&<> zfSBt9++>%Iv0-&Y6m)Nk{tWi`zRt1L-n%S@R$ogC znuZRD$Srb$ZKT+3B@B@(bUi>Y;|{Y$wVH>XD*FUGZ^9Q@9(v^^Ic%nQ z?lXtOzCH#PqBbXGO>TC#iPY~6h>z>L8gk3;$W2O~iq+5|U9aTFq^n#qRpa-Q_LiFs zNLzWhKThraV2PDz{lng0ufB8ZeYeJS)NolBItP;X^XNK?+0y4K_n*mh zx;ypix||u;^E9oOQ%s>;2u*+0K=lcOH-fDnh0{0eMm))OQ31LLHv`2D54$_1BLzW0 zXK1a$RpfU^o+S8wPS!|O?(99FjyZ$&v8?lUzR2LVTlX5@-HJ0}RxBoF%Lb{5&qm6P z&RjGcF{J3{OUlP)__5aCPg1^busbmBLY-OaxDcqSmc4JC6D91>?K4pm-dghAUq^A&SVrOZ+TN0g`3QqQPwyqZXldWZCPo&7@RdCFZb z)gsn7-A<(N8s!sH7v<8bPF}G*%Og7}Kw*Oy_~Ds*8fIrZyx4{)H!Y~iX3#tiJ4zP8 zpOx9FG{A_=^FnM_#%j>{oC{OdUJ}WBPH?Ey7A47Bxsu8yimVfAJ$ZF)A?5r~ z957)x1_?G=sg5aSh5{7c8iFY3!bHX zXWqr)ndwt7^jAL%4b)y5N$Y&s{m5D|C_Vf*YvYA3Ho=mJ7_)VD?{n>G7Q!m~h;VA% z-eRDi-X3jP=z1T}lhBSMv89ci*g)MNOf#OFn9NJL*rn@~`jYTcz{5WyXsNSTCYRlm zoWm)5d(vIk9kZ`qgUz}?`(T;iUH*m%e&kD%$RxAri4FN7p5~3xIe~MUm76Y*a)xBz zQo&$tX`yD*mNuV6LT;r|&>r*HH@68U)ckuKS5p@F4Ei%p;UASWo~O+^yevubm@@}9 z_X(Hi(x!STRl5t=STnfO0${~^k2p4Q9eNWp5cX96cH37FPr1TcQiq#ilSo5rV!4L9 zqt`NMh%cDWtz0D`6!>zkD!fum(b&8<4(<0Mmb(tsxR}Ut|A<((@F?7`2=&o*D)m)N zG-0?PD|@L&7WRq{=_RbX6e><%9C_VfoVD}8dP76e0h?1P4VN!lOz^DTS1_uM;-OFG zN>0W0;d^tvAxsB3soXk_j~%YS^H1;l^CQV6vcupj*N5O?LX&^ zp29Afi{CX{m1;0VU6s999N^4;h$}A1OZT_3W$fvQ)cpk0TjWMjf~D!%^Zd0D$@KLS z*LA2k#0fP=&175xY;J#XAvG+?T4*^tS{TYG2s0#Ua!jT}LPgtnqqBX4w>`qpWkV9J zRojlAE-1cu*K`^6E_dAN4pWEE3AsbeylM9iaTT<3PSp2!0iq96f^jzAJ<6}?J0q(% zynkl$;+G@|7Nck{Z@6ep=4It2dAst;!9-jYx^92J<$zIqk+-(aDT$hlm86gmgbj&t zwliHm{zlRv7yIYBzMkDVzqRxlMPGTe!MAWrU7xgRtFB^|RrI_wk{&y3Qex|f+RJye zpQ1@WCCcP6F)3F&%uRUY5;y>2)^zabJmr*Qx^NLwne>2uHfzr0Y5Te`zT~Xx>Yf3-a|buT^~8} zI$za+a2hq5X?Ml_f}yI>I%P)oMEiv@$XfTzAUVNyeok&Kz-9|t#3!@&R={cNVx!6g z<6cF#hbewl9~ZP95VhKG=geLcJ1Nt9;bV8Vo6b1n)akO0o2DM+AL3*J_fue_x#w>i zT;Z@$nBP0Y=>~c2Uiz%v?`B7ss}6Z7zAGUe@+|ChLQ+7D$w1Ij3PN6;PHA9)a;G(! zFgcSH7(eKf;`zR_ZF$9Z`bj9+x-2AzEO3*#Z)kZkz=e%i)L|VL%K4te+J7~fSzn=Y zi{VBF#Q4(5wX~#YnVPFL-nbhiwpd^VzBOw$9j24R+h%WX>^PW{b4DXpY>^9Zko&&y zej*RGSH)YPfn_>E*FzpR)^>xCse4_Be6%;(qDYGFyjIb*?A@m8p}f(x7^%6QaYvS~ zphVTuCzaID%uB9zCWeZ5_h*(XH%a57?7E1Qlc!sKl5-8@Py!=+@S!m&h>N28TX;`= z8ei(ULHi=j{<&i4-BW6@64&q)z2}M*%X*Icyfd!tGQND-7l!yW6cR0}0(LavzovVN zXRUL|N%*&c{a2^8qF+AWeKFyD=tIsPiP!SN^2~+2p{wn0N_mcDHNra@3{*W|x&*Ey z@TM-e@K(^L1YRMzo)VPfaa7sOmT-N8tGzm-RAp4#Y}5tR`Bq!ZlUqgU(P&EGSCD}I z(;G+bpI7#Mj&QdbD11d0xnv%;v-~!!}}4c)~8+{pJS|A=nB1yRJ2N)1n>yns{fD+h3@oD(wP0shf^BI|g?mpy(S&`yIWZ6QqT64-d-gi^+H>*>oqH~$BtH-@Y+?UEl77$hSsrVE%An$u9REr!15s%b^Mg1`_eOR zl@|RQJA=&(gmp2g>C>K&mBQuX5LRoL7x^rGMWH{hPhx+0S1cu!N_SluA{w$*TALkVgt4qd4uG4EuAtL zoQ*ad|B{@XiV!flDQr+_JA^CG-{n&hE$s18gAF3<^o&rrsR!YT|hWn1l=OwBbbra5Ik zr1Lm71cm;>@g7dsR@^DaQ>DxLAc?8#hR(%4wV2@ON}HREz0n-bdT*&iy8FA=ojl&} z(|x}|&H;YrCH0)UrycOp0fH2=yxR4FV*215C{j?`A0Ms;}V$Uv)h6dRku8KQ#%fF1j6||{IIgpm?WI@-KmL=d(vERYH-J><6 zQ&^5#ojwYD_m>A3bz_oe4+R_AcdF98fMV~=aI9eRLjMh|)4obwGi_ClE$p(V5-t0k zEE(Q*a{@nD%^s|lJx1R;(h#J&A*$MJ+-t0g7qc6>`7xC|Pssj4KiJF3A(LpqFWqNCqSkj=o)Vmi&)VtybOX{U>BW3#SS6-te4UYratN|C!{;V-Du~OXrBb4BtIEXnqkGc z2r4n|eo5@Kj+RxpJgc;~g>T)@22p)4qWyvr9ZEv3M5L~Zp692()Mf=G5X#0SqFsWp zRJl!-t1v#kzAHtjD>2l|<%(k9m-N@2){IWDmoP2!E%nfW@64IL=k?oNU*BYqVp*Pg z9vUZn-4-xHA+NN(PsP8|Hs5p)tYV;AAn(=o2!aI`d=W~$DlXG>ai`lmUh^o1R!-;@ zcDZT#srI?WOEhD6c8dtdXfkNAR+-C}PdQtFg9KkI-WH}eoIPCPKA04NK&ja!NuHCP zTWDse4y&bx3bw9gpoz}={q_r2DIdR|VuoL)S6Wa*h2>=_uGmJ+ww`dEy*Im;BKI!I z277mfgX*j44aL0X;XbK)XP3OEv2dTlxF^ModG$b3l1>0F;iO0wzeB?S3HMnb{F4ID zb@rLoC%VQ8akM6jB;TP#uA8w&dQHiMu8NfIB&lTx)yRuNk<&=&Ptr@V z6N{KXevLBhVWYF28VbEi2)>vq|GYGIoJqWM=mTt$3Mjh|oVh9y9k%qytmpA1Hjfut za}p1SG7f}cRJ$G_TC8N|L5K^C&cxwO7TuD?VOd?Fns>7k!ZHjiB`pz0i|!{<2pLCDY$cr7ZCZW zlB+?Z4#icmM;>fy98WWD+|^Q56f8!j%>Z5=;KjbE7NGtxs zBivp=zOvG1Z40r(9FRfyvKSMldHQOS{xa(Uea2yw#0kHS?tDK+Lj%lZlCJk50baCP<~l>+J21&KaCbY|mu1Xl?6O zva5T&WNO1_>T&>UHN3oHOsRU$*S11hbdeZtdBG@E>{7eu7`wlk{M|`eJ+XS6-jX{W zHLco%a%1)Ll7rOE%ajY8*b^z4^Mch1lI|xMj93^D!t5e=NnS#=fM;XY12-9^-X)o& z$3IccXs9~+Xn(2KmGpv2yGSy@Td89c;!Re8YLXmdpB)XwMAzQu>Oz&=;O!spGq{7T znPFE~3+-`g;Onz4PK##%^^m8=(jEFTK#j?xayv#QOg(y(ReA4ujgy*b5y|KWd~0hTenL0 zbCRU@k%Zri@} zDNte9HK=E9G}zX=9iX9wDSQ*84P7R;8F}5}W01LHKPquwEzY-3?(7I;o`UfIg8X@@ zu5ObE7AYd;uPGwXbvFYucxMG?}qv$jNS$Sd*rKy4$3y zVIqKMnQhlge)J`IUyXg0IF8!7cT8i9&%Oz;QCg-n_Xb7(XLCO8gB!it*CHRCsr}{q z*fvHtgwj`dO1K?hIt_B8vUdq41vcbA?m^&jBh>W7@^exat!X8Z{)(DEf6?v>9u;3k0ZTXRjXD&bI8l)4RZE6y*XAL6>ArwN0gov_~b+%1_NAtrtk2+ z$vj%I0dWC&L zDz`OB@97Q5Q#pb9?@c52{BqB0?Kn+2h$N_ z_i0SYodr4Re>$995DX8Gb&Btcz_ps8reVnFJPu>3qYC3?h@Og^oE^Q$85Ib0`-SWF5(nuoEbw31Bac_dGUWMz0uk zyfT@ZZJO~+l!ujc7+&OT8U5uRvaBTAz#Ct4^in_m&F#MD_QaXoM1U)l@Kk~NwgS{C zwZ+(0cR#@4?A+)*sF#xVPkz?zDUeBtk)~w9MX|mK_kWauG|8|%8**}+l{H8W^7D)9 z+!cY`T^m;SjSS0CH0iq`D0_d%+#u#b;PKmrR9bh<1912uugE9RaE*$3@Nj?UGN;BN z>yQ00iJNb%ap$gH^O{iu?dK(zRJ&J`n1#OEhOTZrXWU&+U(;+%;cU=!DV}k<@7_yT ziDy9_?t~1>sw!yW+qC0?Pd&}1zLa6LUezsvo-s)bCyne_A=nwTKW-{Cq<1Ro8B0pR z1)mLW-tI!bMs%al9Bt%K0<#+r?yG~IT?mozDkaoGER4kCEgKkr*_2b##sL`#)QF{+ z`{zb{G?0uNx!SZt{yZjH4`BSfV{}Ttm^M86RX0ggqpIl1ny(V;@uvADL7h?Z(CNM5 zks>7iIb`c11KGe+74C+TM0Zo^mgN4(N-w!-o!{JmAOX9_PTwKV%IQEU463z*WuzXm zNnVJqj%pyO9M3<@%bfXAQNrK(d;$WOC}c~-)j)KN4eil*14GyA^almA>~#zkAFeSp zDrv6A{*0+))ZyP|#S5vz9>yPBSFpvC5I;0TUvP}AgvB8vL zZ5KRNYf=UlC$3P;-8nZQivge2{@T4B?zCE@5>TePk0QO4$*$T(wl~h6WS0He zKv?2KwIl&qiI0o)FNk@&8g|&0gS@>}(7La&a{==HN3x-Qvm>Pu8%krkMzySaA=Aq> z)8XbjcD(5>h1kIfw5mk3o8d0sZ5y`ktDGRMfqO(Y6oe0Aq7oQk`QX0eE=zulJ;qcg zmyV|f626!=WGG+6O|=FirjUQ^5%<_Er-OLaxCE*fd`5Ok@{He@o?K}(=c{ z-4&M&QFZm98`p%dLL(W{^DUR62cLX6=ZzjxwZG>7T!hO%)jY6VB$r9;%@C7~t>X## zUVTAlm+u3siktM}1X0Bufh%H&cERQNYB(jCdQsiI=fE|mby&`GCFxbaGd(KGS*^-6JuBzoSfEtLl=e?7p6CzY_+1Z=$u zH25mte=OLPB1a1am)yw=!DePRBW>^hQUS8JpY&^xd3^8oe&fwJ$$a{-F8aNyLfLJt z*?krE1-Em}LrOwpo|^7$t4+@N$os3)vo2}JEzrt#40lYMGl|g+ z3WH!7N_BD*2XYNEb*D9hhqKCKo|inzGEkz1)o%xkZ(VnfDl{tNA+dHeqz)9CEV|x} zf;@3Fi`}Vff5GmuO}BStQ%=C$Df5yS#a_#Z#JS=0h+>30tB&*gJ}P$HVQPB$RKF{d za;dg-qhn(gL=+7Z1q#M@i(rL7q;FH#2{UgyB-+HqBMiI+4TVuYDn!|(@{=7g-cBN7 zLRid~nmY*N2Lj{wg1(2M`z=T_G?0%^4W7K!vnW6lPJ_lbI0ltM@C9uAx3&zQ;281r*5m&Zp| zK_O9E2j3JjR{c}%pACn)E4c;$84^ZIQS@{ewYxNg*wbMm%uM#-bUkjS_T?qs+@ME4 zEq*JYH$({yIVBLOWiw(|{1BUEmFV><;IF$TJ_wt0^_`jZlslu5W9o&xXJu0OA`773 zcwDt~dE}_o#NPIXN3>$0q*KaDaEmpZh=!IK!)uFFk3(aXhDk|s=DfUM>8_i++NSiSh~AvF=@TZ|w|Q8j z;+}Wt3RkDD|0uXW=q!BN#6I0cH$SJ`(JWsI`%zcJel(xJM5m+s8&7A{@CUgHA>$ij zre|5x)OR?O>3*V(x&mk2L2fNFA@ASD8EKl)WWVURmGFgpMM>si){R7|x8$v4L4t4t zNHKtx9R{L`)im+8%F;u`vah`au4S+#HI3T}Vff8S&MAD&)QtM*2d)KY$Y z;NiBCj8)as{anvOR*>EukVoUWm_(2vF!G_)pOo~V?qO?$^O}{1O6frAYkVh-c@%RS zF1zPv^~N)Z=Vr$3^_wws=cG~U`w^SVIKdxs4N|f$WDH}&=`NdKg>?O^oZ}-U$-q<) zsalvxr^a<{|9-=9Gu3T6$2oCzDu^jcE&C<--fz4p6w3@wIfU+5V5bU`8<{ZYnQm3S z&B6Z}|12M*I1RBFlH5=FL0#7&gk>^s;+L|j9>(5JrEGRKs1HS{Va#P?7vB`jdto=- zpvn;Mm?dl@B#i{xul!kb+2d*mk+9Ut(P!)IMxv+6g(edb>|pWQNdob}3no43 z9rLI6XN!&n-*LPq>#UZH{*vG!O`rxL@avzt*2NfWEiGK7fy&jM3;6#6C?zjUnwp;n z2uB|$-C{Xb6!}Pv5S88u#Apys?kLUpT$3>RW1cAb6m(9bFA9#u=x-z>N*V0R1)!c( z6?bFOASjhbS&FrRcTlsYE5Z{i)IB;<+Ebk$X1t3O-47h0+qY9}bixz*o&y!HYWN4q zjJe(bjza_=%xWf!6er>Y3@A4Mr-Rke-Wm5&(AZpxlOK_ zWUsBPe`1mEdr9Rv`&O#KDvV5-?hMs|4$erVC9S8T`<6r&23GVts|htCSfnBrFtd|^ z5&~eA0CO)ovuBb`LB8%I<^;J(Gb0RqNrx6EvR0wSCpHhuB+Fv25YYoou)@q4CYnJh zLuuZJM2OOy0jHEjg&fI#lkCJKaF?@6ZHaIWPcnfoU8#f54x#|k2-=a1Wx4ZVAm?LB z=#OOS4Q<|ZCm_nR$HK3t&|eGy$D7m4pTP2_LVK3U)|B7ex_XHOBFdL&1_w{$^jJyi zM$A2Kh?W~duQs2qL9s9X{*qJ;LnNv<@gfnUC;AETHZ{huh9i|%*%bTvljab|4(~hm zC@bnC>ziaB>r}g0q^F?)%v&8sVR~j+F$&)Cx+ext^ow^`L?5uT?d-v`7kp{9DO*I= zsdtQ^eK3z4_Xh|1>kj3ou584KHM(BmV|<5-q-SZo2-UG|9R7J2B+iNwNrmRyW_NA8 zDPuFW_#*m){pq+o0Ju&2{$%hUvl&81$$%4I^T-K3aAfN z;uAhghq1cT__6VCbh&d0peh(o8zpu*w9*JogHI5)tj&a%mIuB;8VlHQ{)=IBO{ zcVWt9EDDu6xHXE{?{@`kOu9Nvb>uM(1kIYh27<@%)E_b41063j%A=XqXnx~SQOHg| zvZsRK2ueyBg>C1_U0Y96Fy32f;*zxTJd5p81L(o^cyUOOhi@Egl8cgbKd4mwr=@~ih=%R=94c&>l?3=R~}b; zKa^dg;YtYjXZV?*r-R@dyZf)l#-5&TJON9e_7VJM4_k-L>p7{MHMO9JAQHM}Ev`=qqFI(OJpSMIPb^ltFX^F_bB2Lksdk!Ko+ zc!3m~cpedzMw~EKAal@|$$M$ujb+Nxr5=kmN6#8ggJkDm59l-hRS1t3^ z92F+0(5;lvU8H3@WLMk&#brQm*-XaV!4hM=98vV%+L85Fsv~r9R#G3^#xwg}`tg0E zQUm%H-ly~)_Ya@(J*O$aa2ieyu^TG*(6)cu@h38RcsTS!nbhrBB}(Dz6zOcF!EEHM zhOUub(*@S#7~#E)g#)~E!P#2!7u7Sg?P6vMYLr!!T*rt4ZMi!=ig@gBsT{wqW5fj$C0K6z=j8;gL&_?8$?hV$>g346bgKB z_a=X33NRt7B+f~`#j!EnGg7n>z+5Sp5LHZ_6K232Nu9!s^x_JO{B@!nii?gF&8mQi zC$Rg7rUL=k>*2&c!vx+MDzJ4r)0VGnb5a&h7BJMzgpahk7Ub2;hB8Pl4}fe}w$jCK zJS5?+o=T9{VyM>Zx919c=ABpaQX9Q|KF_WlOfE?7gphY%s?!ZiA$mI__A+wz*bq zKX+%#2+n7Bh}^uIcyX&q%DBezt@dmZPC)r)x^XcyA5Lh)tz9-IVv`UsSU+${;K*|# zpM;Udl2iZ$-tBMlsA5m__ILSTfE=JjP>ybMm!B4G7-5EQL=Z)gzB@SKRm(IM`ZV?d z{2WClv83ivv&5ADHPcXwH>x(xfJeRyWdw(l$|pR9@E#k;n8TN%wftlMG~`cf{`!VT zTE}(Q$~)fG{?F;(E#xJw$@1&IQ`Gfrul|;#}ygar6M`)Md zcp12VvQT{9xpwG?_?yKasX&e6S+1L)4)bq#^1@`uU*n0WwJj54;T2A zmndq$iEpL5%kH{R)$y1DZfk|2NCRk{BCFp3Y5+hbda=sqQH&nX8MtPRIhHt$3j~4| z6<9#@&88Wk2DZX$-lWO^VA;X);qbJd>9))Yr|_$R-YSCO)2a{BJJ(B4pH~|^6N6nfAp{&0Munp?;ndNYi8#6>a|j`JHhxZ^_&ch0zb zB{Z2~8icoulG>YkQeaAsdHeY?bdG2CSFDS+Qlz${&I1U5p9Ck!Sm$Hn(Z<&K^{lmv zl-Va@9*Y4*Zgquyw_c|k@HynP7)7`?0$2frl5QhKWL8zdkf|diVOdfBGUtq~al+e3 z<1VmV2dxaO+mtC&Yghs!BJl})^f6k0)7|r;aJ@l}6p8!nuw~h#%xJzyNjz6O%uoy$ z)^A|b-JfubgtAc1UUbWIrbP4PBJACEsDjn#awGrpeaY@_K+>PZ-2xQYGx_eam)t#f zMa_h{z4k6(@Oace>CL|2X5u@R2Oa9+s%3>7_9){*!Bzz>4F1G!y(z@H`d)J#uh`%^ z*P5`$n3+0Xr3ST=*f}AU{HO`ZC0rpkV`58rBczkqJ#+;ne%n1ldNZMw=8A_hj@ne( zl{As-9Pp2J1)}Qz3>6)Z+6YDFiU?m`+--Y~ho_(sykW@G`I?!N9(HdwbOe$9 zVo^kq8P@5Vk8|`=sCY93chSjrF#dJ9vQ2{^t5dPbNDQZ5`2$H=p2HIyY!dP85Wug?f5cxhq9;k-2fb2&)@A7yDWsy${ z=-v{CieXJtDVp0}(B6tp3p{gk&3!#2UozC7=8rxI z4i`p;t5#@Kyp**{I}%MZb^H~%+4PGSy>uRfJ3w#0EH&`ji%` zJXMQXE@~ofxi@q~H@g1n2clZ`l}uZo(99+!{H+!OH#3FzwMtcFb!eE3?fG4)n>br5r;G05ty&9HIl8!`;gnFXY#qtvR9Lzr7bQ!37&BUndF@`9j`;Wp z%k{93PDx^Q56;^fAqN)8g{uZ<=%(%a5xikayQJhN80S?V1=7jyU>)V`0PAPvu-Q+2@@TLUya<+&#VfoRakA7;Nk9=)2RdB#t!|j!+z!9^=$U;>C&x?5i+qjPjUoAne zA@>zzI*hyE9Uj<)u1!!s#;G4*QW%|+AL;ZYeAV{dppaA21@{$6s8bW^pv1c>`N9)Y zJo3f1m%j_k7+#N1Q_?XWYe5Ha^gC)hHtbQh!u7F)^bd~gfSdY1$pQ!Ff`WQ)#D=B?bEJcP$#^ks138%Utfup^ z^O4q#6{O*U_d^akk*Kf50u1$`98^;ar!(eh7aLcQ;cxFSc)fSe5g*SQ!0X|eipulY z4;QHol9Bg|U;a{YEtJb_>qePtB*?y+^~tPMR{)W{n9jx{d?np(4ChlD4C+YFC~ES2 z165mZ5ZOapM;zfL3?aZ1)IFuSo`D&rI_nP(p2e}IiKgA$Fx0^{jIfuR&^{HW(D)V8 zoeH1=aF1n7hy_MkiN)gV^{>WahUSYr1UZkXfpm~*+&3fozs6^AMa+%O??^=RFN(JM z1<%-(2WiY|@-TALGQQ`Qs6WA>lMjEGDu5fp;mBcOmalY=8Vw7!e4Fsyd``nlP}fsE zwMDhV*-(F(VM+E=WAKZYwtgcPgs;(D`sv9r+S+aSYU;$~C+fvED}uYq{9KB(v;NCW zoJd(@%OgcqAiT}~ke$O`Sq#@v9BD$k?8?$221DK-;Sy8YeW??2#nFf7eLC`avV)`j zjhjD?Y%f-$y)tWapcj)kg>Py(@B%UfvYChNSU2TDp(`L$FHikm6B^4x&kYxvwDK{+ zO69jbDRaHF?x@;n(sjU`E=%^vze82Cn3|tw*R68g;~U9<&f| zQ#&VxCgVa4;v{*t%Xo@Gee1rcD7)mz_CFk5fS2b?1Hbp)OmoO#R%NhxhsHs3Sf@^m zPQZ*+ip_vH@6#VfvapQrFB{hI`_1MX6<>Fv#&!()XvlXyQBvrmJZ@(9tecgTa^$PD z-4YwAmKAmnemxT6|29b>s{TEb@5nccydUD@iNQ338OuR4<15ocCvFvABN$kpG0u>R z37cnzeh?6~Tu-wXLLn_XhbAr~yt{yu$`QBq5%CV53lH_mp#;(K{z+nTBHI2rM|&jl z2SV)^2VFl7jy(+hIS>TdGhqE{fv*4;^h_wZ76F#Dq*lFgTU+P&Zw@9?0NH@0 zif*=-lSSvAF5oY~u+S#*HIG6PvXw2b8^-`Kznpr|a$ntY>J`&YyzMN4qiaJAIwbOl z3()HILjnvP06Pfik9-6A?Oushq8{rLxOdask-r{OzVqV|1$~b;x9-8$e@`D9?YyyTz zLt_O#Eu96}C4&Oxj+V~T_HFph`uY|#otfI`F@ht~+4d{JKPhz-Cvlp4V>`DaY z2rIeYct0n8<9!LP+<5pK@0&2dBys^HJ$~a|7X8NC0yeGyf9*{AH{L|_wFw~V0^oS7 zjiNVvt*^TTt8@g}1l;XiGZUYs2U4w*(x)tF)+(TQU(__T-<~eGY4mFHu&NuZctdo8 z3&9jB!bAw}+h+&w8M^UEUb|-`6*Ck;Y z^CM#q8(LbKhiL%YTq#n2y{oo^p5}|JQEZz5jSrY8Z{8Qyv^L`GIfV9oR6iQ3EUo{3 zN+a}sTo3l{hcLx2^pF&p{VUAOA7I|@ha$bm{L-CK52W`! zURymoCmMT?fH!IXXv`D(mn@l*~7>u~{qJpaai{sDawK0LF$L$(Ld z$A+f`Q5LQy85$&*?VZ@Dg@6X^vx^#B=pFWB^E(7W=TD@RU4Q)Q#J$#JTcg?G?3KL3 zf&84Do?l$L#@v^evcYIg_cSvLJG&IuT>6GO2Vb|*Hn zM#TO77iy4JkU3*Lj+lML9tx-qG`}NSr&*NO(pmFnY9?vTuXs*`%OSl>@+-GXK_k~* zs5X&ORr5uL>iAc|p~N=27~J1z*Vz>uds3{Nj-*G93SE8~ecOJLz*PA$hZ|Wg84n;m z5=T;F+2W%?ou?Z**h|LM$!ks9ZsIMX!pIZU_#3b3yE%fuOejTuK-5szGqooP2vvWL zuaI&XMwD|0QyWB)g}{3A3Tc@&RqL%^e$=RVG3o}prjtrLFLU=j(o78JkFT#+3gmYd6l{6%8<) z%hut0z&A!_;rM5P*NHSH-xdT?g-f7fsRX-U32_y1djO;dXdaixAfw7 z+%@=~|Mx)7TL=WROXJ^qBTR}^OMY~tt1PZY-Y{SYkePJ8;TmtlpeWBQ!Kqj?3=r0S zqLBG#0}I+jy)SRt0$O3oO?aT?sZVk(UK%qfr!_Z?-UB;Tw+o$jRq$cwP=*5>%~~;W z7M1-V2UjeArEZ|}qH}}n1f={UXGtNu6zj1>phKy}SN$*KpOUbc$5iB%?!Q1%qo=GF zOxQN!P|))a|DrlP+QK zdL+mhAc^h!g_xKo(`QV z#E>_Yu42$lp2v(>&||L6yG*1EOg|2xg!?M6A&DA2pu%5C_O`GDiY;be;Rv;pF?7F& zf$a2GytpAr4YvmX_O}0zw(6-QmC)W4o*q`>;i@pTe=FJ78N0TxX27(s^O4*5-JzqE!4{LSm#(jV;(5e>%M>`Wr70MN0qy?q6iy*t8z1$AW@=*wbP z``L`cVzs}w<0@VRPU8VyE&%qo1_=^X=D~azt)M=o3_eSG)X_n697nUm6$TtK0_5@L z7>`R+u`$84CRXWtlEkxhqJ0eYZ_PQWk=kt)a)LKU9al{mmnB8MK zrjz7$lOi4y*v1t8#?v$|%6~DPB#*ntqAT0@gcoyQmZa4_^4t|r;`@iBKN@5 zEuoprJX=A-+`-Oae^UO!-ZTdly8(Jjliz+=%hCg0Qraw-2qq(}2mdfqX2@y{rG%X6*q=9fQssqTQP zRc47b@Yl3`&&v|)(xEk7@~e~WMy;P=&QSJBUQ@TJ0(OwA4A#T8mWFKzVL_D0lF;Tp zB8mw>II)_)lhF703Mi0t32L!=&x>ejpKD^I!Za}<8|#@Esnag^B+hFq-m#RHjkEj6 zB72f|sT$qU)>+vzoZTRl<11oT0>K8whYb1$(gvsJnt4<`>x|RIGk{uDugE4NqjwiX z)+{5fRi;cFrMnAWgeWU8lLu(P)7FOx=0q6llc{KJt4an%JQ^c_?NqoxD>;RA`il3W z8YiOUEI64$q~-t~)i@KgdPd={GZ?tR09Rt~q1VaZCZ&OG6n<(KHt#ejql7RKIPujQ z5I-WDE)y|`H9j(C@AoJe{JuYDuh-DZN9AT+oOx>Cn=GLWv<9OlyG*MLJXI;nu91dx zF&qU|tWz(zzwsqA2ZAy3YDkBueCr<5bFRD-Fhb(_XmP|m&FRK|#D&eJd=k`SV528_ z4k_}ynW-S(D(z7$AFp1lh<6P(ev_2yMa>dVv#UjbIf963Cyk<1+Q8UK3TRTMtgTg$ zB+yKBTcGhe_bGvaR!J;c=3s|e)T64&9SVMhZyb+9j)}OpH)nfjm)y^kaS!TRBX}?3 z5m>VQFbb_~)pP2_X+Kl_%Kj)+-U02lMkXQBZu=pij+r=K!nIvzQ%DeZ=Yo|MxU)AVMVll#9`z!%qzQF^aE-2>fqIx0 zv=Umm5;#_Sq;jOm`!x9o<(tn?%-wJ!Nc)O3R1_c@Xz6^Su=u0V`v}<8XU#MLVKkQ4 zk#XRjpC6nUDrFA5Iy|_BrcmDAwS!i?#_A$rIzn#`1ywcu7(VX+>!KD&ScCRxL{&qU z%KLe7vOxnQv+9|Cf0vLS!`6>WASynbhYNLx1jA~lB2SB?$Dq8jU~HTkmvEEFHXE5# zijM9kC&`>%K!I6$*N0$+DKzoyiYK$qDD_)UT|H~*-1wrp$c5pC45KSufMZK$oS_sm zW=k|H6ghSb>Z>A1?BJ#|{T9QF28YXw?$k445OJ$pHn|)uEyU;mP%pdV!vw^I01(L; zwI9}{z87bGGhNwT7^fc^1|j3L+hZ7+d$kF2=VdA1JV4|3kaaF}%&Qj)PU^UwLykBit~K>uvfZS> zB`=cLF)y(WqKGG}3NJ{ufcV(3#KP2AcBrn}&4D1!((b8F1=Uhd-Avh0VEvazXvW2N ze?M0D7RH#V=`8L?Cc}*)WEHGdI)p4C&0NA+g$FDKsed(EExd1X8tbSZRf1D4C| zO~o;rEH>^Gq$@1XB}S1j1u(bgXAVZ+^`}z|6$xY;P6Ao;fctmp^!U{#{c?c79-k=Y z3Fh34iw0s~{wb+TJ;~w)!&pfB9CYrCg2i&@FPseAy~qOMk`sNw%`hlG)B785YPr1X zTYf1bKUL*Y(N;jT%W!Ro2BR!-a~&4W^E1pw&42C zBH=95*u0vUh<@`MkDFtfa`P^|GPSrn`{N!W5Mk;%PQFw~NCzL0P*9+rP&d6BI$oeE zN&Tq~i|ClIjzZsPY)TYD)1|XnSDTRwjtxs$=FVf!q6dM=Om>+7XQ@>EiBz^wr_>zl zvDj{k8T08$$_UT?oVvvd?v%ghx;t>{Jh8b7GiDUC%4VN564OCpY#3nECAhisiTB|C zO10F#`V)HGHWN9y3Z>#YZH5H7)Q$)XC8^Z+-(vss=}?u;#cc@*H`y63Kf=#v5D)nL z7pW-s80&fLr)%yZH8&4LJeb3)=EA65(0j^&aDsU%cji48HemD?u}4ANV?s#W+)n+- z>_di^eDQ6BG?RdLDwl)hET!1P%c?y$p^hX%C+_#}VpTp<1IFFsibe7+XQV0* zqi8IMWqxf++`)gx*ap^l&s;&&#x`_p!es*bv9U%lfs;x`&B2z(N(auOEVm>XeL53A zk&((IZH;moHB*q4_ zE4>fke%%!aT=0+BB_p)Wudt$iK;mii3aRolSxQzd2)5ZNA~l1z9%n-A=iG?l4u!1d?!C(!#g+#jq=|uzM@_riy?lkE$jBj< z$yq?HD-+|b7H{_mj~FRv=4$blx~^7%flgsa#b?K|UnV=CZtBIUjcv7P_Mi{~VJ!z7 zDdQt0N+s6$;Ua(<0hIVJ@d-VEgS#A}<$nD4E1@W<#oBXbQPUl5sd#PUP)c3=T z{2l|ML)m95mX$K4rq>v--}zm44@nc1V<)np=?C|IlA|Pod(h!$*N@dQ-w{99Rf`xl zYm9{{)9n1XlDi|TR_*JXYFH0?`UPYstM_5J@@V{2g{j5qK=Iz@7kSULZ|eOG27}|~ zNAy}D*NN;TPMNb!;naG!^mPSul@jF5dF99GI+c40$c+=VCrDWY_4F&ih8H9zFpwc2 z#_DN%d(cXEX3JCXBcsKxJmj?CFAhCDJNof0+ULv#sc}XbuQ{77kJ;0Z+&GqqM9-o> zzfMlc*LnRL@7!bUqVTRR|LO(zLjU539vze4@tx@f%))xj{jV3S@(X9myRh?<3$QZx ziruCX-P+>O9|6IPqV836lfFWGMy?HFJrAL0P&*FE?V@`eZI{I8w zWMOehh4S7-eA(Wyd_VD_NMm&WbwSDGi;kZmh^sWOe&B<;PYwkXG3P25puEG7xeLuo zATKua8&4&_K7jm(WaWJvH`28{&pon#qOq{=og5$i?p4^Hq4Q&;QW zY8{P_Qhl8=vXXV;na;^7mX+{kRNgX^VuuCp>QYzVazA4hK^Vrju=>dH>|gNVjuvp3 z`tr}xUYZjQp~}ziak|qRbjWr;kB~hcYr^;$DNdy+C9Y*xD1xlg$_DP|w;8N)2pyBT zPrd61F}=-3``k-1%~3G_S=lZ*kil&CG#q=+TBu0D5g=4V_UwVb?h2_76m6F!Y07Fq@Fd|2 zMHnHnJ21|M`aQVI+^tPJBtB%`I8|C}j!fX*;P83GAHhX?%EU)xz!zd?kJ;HKy5oC1 zGn7H5M%04YX(8uf3>$frzH%q{xtN`#H<9}lzuY-@j{sWQ4Dx9XaSc`(Wha<0?iCJ! zGEh_jah50EA!M>*?kVv%7f9=E1lSqO$k#9R2B0Qc3^lc=qzcP9%(?DIjCC~OU(sg7 zQ^>FAes3;1Q)3y1Zo{jtw1e(@pX@4c@1V zG4^cj3&xws@?4r08{;OmFwxiq^<}oDP|GQ_5+-b1BQG*}g15Izsl~$>w|0aHJsu6O z-P$J?SAZ_gWOI408;ABpn^fnqu3{o0GT(8=palc}GFYZo*9Tjx@o9KSyHOB`MsRBeaH~?z?B`f{S z-J_Piz@SJD>)Ks@W%i@gAI`o((X>Gm7X+E6>>8y+!h58!PA0j}!* zQL2uBgn)p65U5&52vjxvr&JwKsm{vH-xZGBkExE$8O%nn4`2`eE>%bHPpP`|NABKc zeWQS;Juz}0? zBid+p145zKVxq>@fGX9An3x#IbfIfw*H+{LQNIEeW4z0&<Ue*+7Q*Sy*5Bu!4|KgtKhO6DH6htl3&##iaw30aFxsID?J>*2VvE2or&!(Np`l zo8x|Nt3oOHK1vBMWvi2lKp<}gq}7Q4WF#%8nlsM)fZ-JsI*jBPg&0uk>XybMqNaAm zOe5{(qM=&Vl~a?r2S+!~*{-Orlm3_A7=4p3m6U4~l`=Et%(?%OPwdeB`-6IrX>U< z7H}cb{06QEw~rZUbw0c`Fh3<%^6!ft=TdRu;@LmN>B`>p=g$dIH=$>98Xt*FE_ zYMgDmR8E*U3iIc0FW+Zir)D&Hty{C7Oc78_DxISnyrr~Avcg)ra^i5g4r^q@zN88$ zCwTN55Ao(3`A5sbC+tqGMXJeRM7!uVeAe8(jv z1oms5@aD>`%ocG61eW*lL&EiF1cE`9fdNp2T)LCKBi-IN=$9bCZbWV+98;h&=;NrW zLYxY_B;vU1O^t4Skt6bhDufxX!lugJHKJhhf>2M+DRK1svpS(lqJJP6{{d|LjoSFX zJ&{(AmmhYJoXvcaOO6vF%ve4VhVF9Lj} zW1{N6{d`Fc2&*}^;c4z`JrtzPYe&Yf2c?|AT8mPa=d>i5a8WR9z^u*}axELuITJC0oAfO<9EvFCV)*&05Xu|m{c7Ix0gk!E`#;ZVr{ zE1js}%&{pbF*GPnhD{nCXO;EELy$k+?MWt7|7{uTxe-f?l3ZSi3n4Tw4ijD6$Y-#| z81LPxsIetha6y4OsP}RIK_;15P;f!sxvtll3x_=KcT>8rp#3=Gezgk{_-ilySt?LM zW3maLrnh?w{VwqwxPysESdT8;y}xE=X1^XuMscY>dUKzz7-3gJ`8i{rS<;W_E4quL z;ClvmJZ>- zg2^&#;`NN1UKW`{arW)Y?&eu;?`HYs*ulne9k0F%Qxx_oS`!bZ?j_hA^5;2epVVO8 zJB9>E@~e4HB^(*NloAASqV4wY#d*;O34*PLvx{w{hv13A>JJG&7+9yFe(vK<6N}37 z@_9LFIadjV0SY%$xw-r=@(=+L(J>5It4vc=HTZ6dkdo}(cL_55y8C*ix_4ps_Y-}E zs<2|+Q*ooCVu^y5pR+NK&d(TtqSc{R+4x(3QJ0N;rdYk@BKm`T;wSzSYd?7 zk5n|g5WvZ`CaFGbpR;0znVcr&CNK7#4s(erCgg1IC{nU1N@O3pJ6~?DXPx!O_n+dG zaXb*=k>62>cq8h>g}tEO1*#`3VnhwP<_5{~xe`*XeR>LbzIQEKFz*@MV_;+9cXp@`1{wX}kYg)1)#*@f zu68cyCDx3Cata-@WyPR5$bCp!lA1*n6AwHCf}UkKM^L zX}7jgBn<`H;8PFeve&LOZtagLJiq(4pWxOqoijnv?X6bck&Ryl!`wfkNu&2=8{{u#{^_t#WZ}j7YS=E5 z)F3XH8BZQ?pNJUJU(v=k)q?pd-supyKbYhGw^aiIrj`B-Okd?W>X=%%vLUpL^4sx& zRVpH0Rz?=L{`o$4<`dk?K!cQI=0PC~*B#ygT(b1WSrFt${RqStGRbL{80 zk;Yx*6|cT!C24)R24Kio5DRPG3F?FczMh=$MKZ!WT;?FE{onTCGDl=Vp6z$rPgSG? zcn>LG*Xh`(k$bKLM`5<-D?~H@)3DX*<#E1R{_JM~-Nf~>yv=q=KI-ywha){H7Ldt_r+<#Fr8-e}!q zU<&3l8OXKp_TLdnwPG<^!Q`6N|M$Xs*cN9RO1_Nrjpih== zv?Q0+By4?l>@?wwJ2vw!e;X7lI!XTNZe&T#)W^;)ft;)>@H{S;q-%{h>yZ5Y*PQW) z)X5rRziWs%?GoIkP}VNy|RMejd0EA98cdOY zYJldx@lNbB+HA+YL=0rK#=Bj}&`74GrR5a?Sx58)17oru{u4f@>NLabk!A1L2)khN zrRcL`FR{DM$Ms-&@rDG;8IVgK1=V)iaDkI|NYp_j`JAv z+={p)-yUBGh$?RH?BKUMv%{^glD=fkX{y)=PuE(vA6UtVZjkemB`L78 z3f$Zk86V%$Xby>A%$w)_XFYkM2c}qRd4bN zyQTkj-SfA>&51_pVRE5wFT8^s8$-5}v!d$(VN2Oa8H?pB;H{~g~>5wR;Ag#nYji|1MjXMdxD|(9LNT zxbzG&JF58{GCD6Wq4t+{m;F%jkM9=$>R*npyYY{;*91$Q zq&a6F*fI&~*!cfDgK~+o54Ih5_TIR;fzW0xPLYwr9M|napvbiV6z< zlOIU%{y$iI@2IA}t?!o-N`TNp4ZVb3mEM#Ps`MgAlO_VvMLU;39CV{7^VI!VmWz^B(oP&e-x0`4A$K{qDNIj3K@` z1?;=6tLyIZLjU%Ed<+80VSxF1Zj9%r_tKaCp&4q^M}@u+q9zb{j*U*lVwe4#Yu2E_ zY>zxVG0I*-qW{|g<9?-j`l4_Rd#!nfQU4y6+~u!lG!)y`<$ z4QzW!H!nke+@&cqindHb-|q?vmM~ebP~`8yYlG(hd#eARpX1ve_JH*7Q-Nbw{ohX3 z#At~b5vuKr*FXZj%KzQL%>-`if@s6>Ln++fdY`|$v`n0?ECX`2;#BP(DCAG-e@s^$ z@w6XuYycWd(0cCY{z&4HHbwX1X@=?0wULto<}V``xiy>>o4o(uv3e-=EOz2#K?Ef6 zOUz{B76)eED3kPmJ`^1>YVIs({b^KpQ1E}fDBi`gE^*g`=bW{YVfrude@1uP3stxr zRrH8hC;9R6(e+zTAHKKzhi34t%0D#z7d>Q81n(^png%5zw}DzW;|)15qN!ZN?aM8P z{|taWDv4y*MLm9%BxA&vq;zy?_vy;jk=N-DSpUaU_`%ho>8-OXM)a#foB!)O&dm8* zp&?lKNUEOApZfLqVr`wq%3qsa7OW8$a)@3nF#AVpI86wIZJQ23*E|@{9kTk zDV5Zk6_-U|mjCaqK5l<)c{yuRrN!S)mXX?#kti^e=o`G5gxCQ)ppnbb656z*(jI|d zOg-5_psrNcl)e$QG+U5wpOjQno2Fs#qk<5gaIMHNHjA0{L)qv8U(B;mN}iS0OTq~C zjE2jIl$G|^Nwyul(Vc5bVS`+XX&2f&1HRjAuJfK5X8vN#E~KsV)I!&7)GSS;llsPo zL6F^-Q#pXh2jKri^e?!ZrK4Ra`Wu32TouA|9QwA z2dn(TwJD!?`A$lRaj@O{sUo4u@UvOw9-^@`j#-l-XqP6qgX2x`du4^Y!er79JAtTz56E@8uz6HvVu$GUONoKx~!BqU3=c)%^Hu5pGecXX{wd-Cpl z^Z9pHnEp8gx$uBcTp#QoIF)U*4x1Z`=i_e68%4p=xf>6;3KMwzJwycCbP6j1Cp$wF z5DtINd$Fo!WhtNAO~Z62Jy8Agy6hjCt1p2j@sIz|%zp>aBV>0Y)0Z8TOP=2?cen}K zPiSK|U2zMzh^Wwl#o)ByyNTci!{V{5b^)-JoxKHor@$#=GjOQQ|GY2Fedph_U9XGi z5R(62Z=kZZ5Q~$1#){`&6Sf~uRzt|N_3>Q@loJA;vjzLMSe3#~RMM(9OgS5xoguTL zb=EsW7!pIR%^1LYF8sa;Vc+3OCx#x02^rDu{)-b?qCk9%KfiTTx<|92FZ3B(@#rp} zu2Q@neGg2D$=DX8;7Ui!_lFW#nBl_Y&-GQvG%`r@Ej78Nm^e^SH2&m$^LWbwCoGCZ z(`@I`m0<0mB*V;I352#G;o(iKbH09h#&_CET^Mi3w_&u+{4dU=xyvnpzCFlSn;Vwe zQ`%x(dd2YbBD~MrRn3b8 zYEaVdd=TONX=kPgT1Htk?OWQFMUO7|QFe^tOfR$;d0*W*9nWPPCl&w?KIApoK|EZy z8knB7&35P-Q2^>kF9pC8gbP2ZC)U|pan}M>*5J}k~n=TOXu}8r#WaU)3Z06mjXwCQgq8YP0CVV zHn8YvMWrSm9PuQwrGovWN!4BX)#qlEFPUG7!}y*3T!vY= ziJL)}215st19aa&U5O^^fS&Bz`1MT#fHD1`<+A{kzkRrL0m~$jIdtlV59S|)UZs7q z`5&tl`92Qz-O^pdnM$u>{0!A(=@=j_R|aa5$nm~1$L3tY^L*C0w!{zNS0MVRCA?*8 z{-bhtI6m7%6(QfCl~n@G<1@YBU6 zG&LyGbWm2h?v0+qGP)e!Ou273BLm2yC_)PBya=H60iQe!p^dc)U}@4!*X zmpk15hrz&G26}*x5}9@pg-M~gBqrDoeqPrR7Ry#aca?ZK7}@MwU7OVKbT>EK{mt;z zFTyA-9zE)UV|tk4*C}7^hRW_(`074(;8`}Y-+yIaTuNlm=``=m!Kad*?hs@BZ>qD| z6c!exdnI*O69mIk9G!Rqn#>W-CsTZIw zl?$lXb>{@Wz(*AI%6_T35yfh_`LRo1tYS@hzTrjX(eT)2ENLe!dSNr-nf^Lr#S~$~Qf7JN%EV49Z&?=TCTJ9x6U*p{AU@_p*8+B3pt6pPvVg?HT4qt|&y(^KdWJ!s4NDc9;RXqK;S zp=HJjpzqlr!Q2_9xq2v9p#+GGh^L;BHldV$wYqn!(THi{)cTR1mi}?`p9X%_Q=-A0 zb*lOAiqy+oysXPRBSe!|PT{$hYg!qU>rOrwdcWUcn)odyyQ}>Y7OlcpoFFx}uZ`|c z&m>`;+!P{S>qgor-L%|YLA}x|VXf(TU=o4LblO@~@)}$Q(0dJ08t%&HL?N$4^>{~b zLne84lB@T)aoRzLuD!t~dO+(0F`K;sXaKv#?P;k8tGgu2qUA8s;F8i|g?@%qxlVe~!(QIL3dPX}8IzLP1WwXc_MkiA!`1IwW z>f+$_z@7+-Tw__rz}Z_Y*mr1#FXqA9a&nPoB z!XL|`Pm128$2mYzR!H_r!~e^%YdG+Io_mtd9cQzzMe?_4)zksfsJ{+j!Gp^(;%5+#EjsLx=+XO z#s1>n3a;R;o#X{OaDbl!oGh~5Zbq-HLAttxVl|J3fi^phl-r;4M zshNh7{~p(~v{#1y)t7t7KF^<|ml2bO$-F^V4Qiwy!a@(I^!|Jq%H*W-8pdjVVm_q| zv-j#CGg={Z?OR#F?SiKwyIW%~h5MvDu}iB~nPC{MqTQHeIOh#_&SN^Ek^vU?-QQ-9 zdCGp%DDXHp4Aa>hD4F-N65jf27gCx{$a%I9UCr+r)DAx-p`|PZyU@hT9`VoAHHm>j z1x$QW@ABO$>K)AF-X3Lz-Y6<6I{CZhV6-xJ3b78A>**F95!}OyMO(jbNr=CR6FTJC z{!1=b1B&O5Xcc1dCD3IkTt?Z|cma(?d}e?W&ctNXTH|`3_DsyY6LUH6zb8`7`;vQT zop`7IobP->%e8RFJuxQwwBI)e(4GFs*GYzLo;;VEQm;$Y*E?)+;68R)SBVKI*_swy zsendcx51upWTNn+5QtAonY(qK(uTXHxis^2Ht!Y2=B#`4doAR8lh0>bow$#o;eT>S zlvwFkz#3j>xe=TPP|Y|HUEq=PB7fotiJ%NDn}sQ31)KI0udO29kfxe%36^@d_YPp$ zoZL2XoJcaJv-Gzw(4V*~dt1k+&+T;qU!&V`X81V`!}`tZkd5mo7yNF$fd~m3_}fn` z>M0S$s}r(pIi2iR5%f76p6&`UkM=%n zhsaV)KWQfgN$WXWR)2}kH#MW*^Tv(BoCRnarkqwMX4KZ|3pbN}+go0cDQw8lzE^?Y5lfO@D+1PH4cO4Yo`WbT}FG|1uBuv!F)*y;^-kwoLHJ-5-imvTEMIv zEjda|`<-kak~tpu`O>_)Z|tc?)o{xuMY=DQQfDEKK&n$buP{yP%7e0$d2?%pURbu7 zzXkXPIXG66_ne$ouPkM4*o#hhmP|7=gWfKI`pc`Hxh!m*+9UPgnvNIe5QafeM;GT&}wLF61A zig6KglDBO{oRpUK%E+5{>(suZlLWMf23316X~w}$9>@==*GZe`GA1?C;90o+qJ#AM zx0NitZJ@fmniJg?+~TF@$1g`2ym4juN;CV@_OqH%n~NOZYpVR%88f_blp!GE;Y0|j z5-;5?$(#-UGtSQz;gqVd+b38jd1{2nM8?ps<25v2)5ojQ0SaNE894o-Ha@kK z90++6uyr|-Xl|isu1_U3G>ki+A%M4XHgW~Ig95Jo6RE;~Xrjcv?4QkES}~$i;M#hX zI}+5n(0aQ~SCZZCAmsypGFE%N=abGJBYR?&Y#643)+Qt;T-ttSQ!3>Ra!&C1M#3nm zNu2^@w+&R_i}UobLhEG@O}z?mxH?y;m)wM|3URH`thvGpZTHe02R8_89Rb^cfpIvH zjS9!#2}<3FAYGPu*?#`HWWQg4s`d1dax~9|ZZ#fPq7RORCY;H9p84!-L=1WDU>~lh z{=BMQQu2s{GW=nsTRQ{#QEoruXnXi>Qh@T!;f}p?W`)Pt`%hhA`WH$HVbtqP3e4NX z9isOo`f(L+iQNGTHe)DVEan0ynJzkfd_cNF+7e^K6e1yotPq$ChB9qF5J1Ub;uu@J zSEVt#RrXW~QFWG#rA*PFBeBO`qg|A)J~5rj#cSKrNq16moYq6)4rEs}Fpx$RqX|A! z$CE89lEZ^&pjxz){k6mY`Nn#FX#WF$YE*&nQPeG7`_RI3g8mEqN7&l;7Q!-Oax<3c z4u2RQI|r0xYHx?P^QF9Xf9yS0P{cV&>4j7MNroXxa>~eURy7m*!<2e0O|VC90`A;_ zm2haHITL78y?$PlkfR{EE!msNUyUhNUc8hP&^{xAs*wT;H?wZz?qV>FW*<0Hnn7U> zC&?yvhWatxSyz_{l>yv8 zvtqQR1ikcwJgCv_L2tQ{FH8J)x`pS4qHWwG$idq@FdeDIOp3@zWjb`P_n1x&vMSc{ z*Da2Ro7dGO1DDvR%5vE|enz0%W+g!seF*zTclzsCB8@vXiD>pC7n94b)>>(SE{o{! ze@1VHvC525njf0#AK5b7Ju|$NE1W+1wJe%x?fUo2gL~$|xm$ned=<3oE9tFRW1_W? z=52DDoTV9?c1I}rJo7nzUyZw82*RnCrCmYpspirHRebmct;TvY=YApb(?em45N7N7 zQ40%798aW8`xQ?x6lr`PyB0JlnD%dyk%3_ke4UUFdatI|yj831DvgglB{WS#pq)`rH)I8tKxw?1S0#6!e}<*A z!IZ?rG<#%MyE8{Vb!$?-tDTT#?HL(?B### z=Xz!Ai~4j1r+>!dy^7zyO&X_J>lzt(d?%-8+*n5#8y$TbHXR6;S*3NdIzP!Lv;VM^lu3kbWQcmCYg6 z3N{ZRp$(qVnblC7&UxMRVLf+2Ei>X6=aiP}`ITZgB&WZyKX`_*N(n>8H7v=ex@g?$ ztdyeY5?D74&iVdQ(@ltJM}fK7b@?KxW+mJcye;^ht*`zZ-a$)&go?Z+A3~k76f|kL zQDFFnS?KsZHpqAO2Owoa?v4erRL_2GQA1(nP_~_PxFsj$DHKj5#RTx#FJ5XZr1ApGn<9^_xb#C^aG|1=JIY#)ITF5C&BfG|= zeuHtPP0mu5FS3L$^6T&}c-m~|R9XZHgyxT5y#CnIxj#0d1S_9;hNrY}X24;~DJ$Bq z-hVwXzeR&#sbr|?Kyf=!=xurAkGLOiAA{{Qfa~)pWnuP#qL6vs`Rw~W+_yoKX)Eyn zhFesTwaU8W8A73F<$~g|s5V7@IU`?~DN>dsbRv&mmF!3os5ls%NO6tBD|?S#WhgrU z*O+82>7<8Q>K!vAdJ1Q9+q{rGA#5H+@=0Hv=7k*%xVpGnwuD zLFR_8%6GF!3wE1bC~m)i?fC=5q^tTstR~>i5p0jCj3{L5pmb1d$nPC{txj`*E&WB- znL)pQZN3qZu4$gXueXOf?K=TDfCea;X6DCw-^lf72$kB|tHb?hh1pNT!sPGS>C?Jf zN2QACBz%ry8X%ttn+NKuzhES75tDS{-wM}OFCL?!*n3`=9~YE|Y`7ShJw|SSew9Rg zrRi%EV3kCis>*pF)_&jqMk*rr)tSl|W(5ClPF)2A)uG!7v{P(_W}GScY;^sz5rW|b zGd@E`HmP((G^0MUsdYR&t6W+eDOW0Z9C`0Uw!>UAB|3lYeV~l^hw>9dgD1~Rz5%?A zY5gU9&Kq})t}W4`uV`mwCF}N}ZHa8B8xVoJx%IO~*ZbIeGu8Iw_FM7gl;>7$j_&8% zEoKsHen8E%EejllOzp~Twv(ElD+L*+?8)YI_-DKcn1e2VlV5eX*Ia%fui8A0nz4cf z78_&#uh%;VU^CPA#ASV2}KgghAot%E?$%5j`lzYcS|Al21osBz}(kGlT zoE3+=Nv*3?i73l$#eCgD@>scCU7 zEpAsPOB@Ejc+;dSDerXLVF0Qi=A+Ww(4VcJda%(glXXhyDX*!S`s_5c5ccHO>(Y?z zq_oRQ$9sT3N9h4MqOx#&^3kLhqm~WyEO5+WS~5v@Slqt4rd5 zZ)=*J5@?lyPaCPK%qo^(8#a)p6AVnZaW{|5)<0teGlMM+q#tu!cW5_onEJw_ z3FCGbeL!(TFS=K`A zJ!G)FlfGb{OYo)N+gh|Efa+EFHF|22?6xc-T&+~CtM{c zj};TX*LhHNG^*+~n;i$eE9h}l)(R?`AnW7u$^dVk1juQQxh(pd$rR*;^GWKj1|1PD z;IF&sL`KKUzF;JPVmClbtK<}sKIPX?i0QC%Cy`Cpr$_JhW3_AdymIAfr`bh+soC3z z@o~(?HYkQzs*jwx3F>CnR9obmL{y*fDA&D7MKT;oh>IuEPr@2~|JKP%ZU@JElbQ;f zq`OG@BaX%v2`t-n!E%Lvwg*iR!`Z_NOMH=mGdO=2W*ymWBjX(t7aNdpnl}@D{t6~D z8~udEkdZY4>V4L9&&D;mj~ddW{ARSc@Qwa8U_Z+vnfxcPXjq%Ap}->F z?%YrnHw4m{8i!Gw1(ok2vw}#Pp#Tuml9#=WU06_8hmoP{KsgR(Ss^OEqEp^lc+_XS zlVfklyxw_@$36vgfg%;*H>{Qk?oKWSYlU|?<;lzlsdv{omZKl|U!~{hPHBQH0{+fl zZ1hj9YPa2cT06!oF$U&RS@M$`7xKz+P4KA|zd=ww^2@cugtK;SAzSHj-{cecR9*DM zCEB)y9@4ybf-(>Su5-pSHsQ=}Vat5%_yxsi+jMpfxAN@pdhu_~RQ(H$1!P~yOS|iCM$`0 zBd^t#^6cA?LTn!F@b4mdhOs2FSc69cn(EMdARKKa%k5t7b-NGZpww=ll8JKGv|%Md ztTJ^$#^k(Z`V1NNhevQjDc8}RI^znA)72n7&m203n=CQ$F_N5Vdq9|@2Z$2L|0Si2 zAnF_kCJz-CJE8}^KMkDJQY}Gvv;2J?CFdC%`oT5xyc=||ot1+XvxbUg=$;KhXW;Qg zk>{dD)y*S@p_K|9rn?4-dkYg98z(Uu8~eZIAh%oCYv>>`fYM7f2REWey83*NbZLER zg23HIrf!j!yA~l1UVcwhBjl_KOmz^Ck!P%T5Ps{y0`Kqg*u(`cs<)EXDP+tP(f{u5 zN=hr)+LLnzY=|$7D+CZ%8y@0!o$YP|VuDU{G#{A+;OCsgT*FmI44edgf3gQ#`+wRk zafQK&)ZFe(X{XEt4!L9GVWxp3_XoqarhV;ZpJVo~)@NpKK}^{vNk_xNE#}C?BdL-rml-VyU^{qw z&F}h0`J{)jny0HeXmr@kKdkIZt&4s$ly1RMl=0Ul^@nZ}YnA{JO*7Kse4-5xyNpDv zEYNt#{qeXSh<57Jt{2re6<5uq*|@B)pwF2ac#E0Z_<1g)Okn=5g1cL!84-gE&#y%0 zo&zNroFjZ6ZF|L5<$>%?%@Os^-a@``_A^8K7Qe%de7d+0;LOO zN1V)sK=W&}J&ko$VC;9twdRfHsxQVG_-DvsU_mgmOZF*bByXc3{iAzoGn6_>&h5N_jHr{XTaTVbg?+1#GA&X}jn>Z?;D2 zfu5CgnSlI?wpuw$=iCOwS`*nBpLT7WxM zMF(Rrw&fC^iQzj)18@I`7p!q6cTL8(UTx%=b1>_Je-JJ1Q@ z*yg$FpK_dC#ZaOLLH2S5gWJ31x`y0>;bhsbL&hWkcDM219-V&rFG)^(s(&cZhtH5# zDl}Q?Zg}6tR$9EJ#w1Xxhj}JGs13&{gu7ptpXU^$W1+mw9FCZy>I4f9^>LKWxYdR# zz38||#?*7}kShxy;7Hf)v$4wE!=Z^Rn(JX2?(a2@{GF)AL(hmPn(&o;d5Sj0IAI(v zmIZ_-K*6QZfJDp2U^K7-#hnldz{ZXpBz%%7%sqs?d7;p#QvVLQ(vUdTeScuN+Gl|B zXBs_KU)aa|IWH`hu=Ld}_<2|bL09<*d{JC2mngQF(~s+ihE)Cj^<*~w>T+{_#rCtN_A3(Wn0xHg99uZtsP@$ZyJ3Jdv0kCdCx)8?ob0@pPx$Z zbB4rd1H?dC0~!Eg@i`fQ>UJd4wxS-^(gu&{SP2gm4Ivwp*{zYqHTG4al-X0BMZ&v! z0GB9SkBiJ`>GV*GzaSKTHa<9~%}?!v`b5N#*`q2yaFBRqwav%?aZxETB}%RSQ;FQN zqz#lue~3tTEqQjI-MeF(-8vv^I>PsUSho8i=OtCTEuMt%WqJ-eF-^SpY>%Vlng?UQKo z%Nr#dNB}4LC+|2WII0BW`;%`Cpg6X}Uz{OmaAuB6hnh&q8nb0GNGP3L)|Sz>l8<4{*IFw}y#U@q6ykb%P7ph8<`YEO~ai zEf*50;D}CdrlW@4y;PfnQNcV`YrKpPxVKjjFh#X^_&r28!H!P5N&O{{S}4Kn(J9i# zv3hLV&rL}IXik@9iMF<7y{ik_cCRxo3-GFoLfl(}+OF|RH>WIchY)V%;_@|?zL8Dq zV}f6-YEEF<>hKpTXR6kM4tQSZ=7@0yB~h_^?ve&TLQbK0jLTNM$l<|LHyuCwx~ zsOMk1O^=LfT7Lj$^v^N7eM#7mzNl1}qvH=@cGs!r30ozb<2z1W>J`G}oJG62;9f~kX`!(bqv^+9Zp=}@<5*ZTt)1h11)mN=I9g4v z#wv~=L?lb0i*S7#Q3fU>nG(Uf+^U@j(~odv@hn+erVZw0wyJdd2n{rSrPP(?r)J-R zB;BgprP8g}Jyll0aU!eGx%y4@OqSR&7Yb^Q6&#q!OdQv7-cwESv+zpWW>>seu_=1W zEK%$U=phF)oQTo#Ay`@b1SHlW-nH6Eb(T5mNYIX18BetpFv(?wP-pk@A(?Ws7KS+K z(4diWHHB@(i!bUL!BR0L`<=&Q;c6Qf*AFuD1s3X7qP)5Mm%muPnrF2b5LB+LGhW0A z9EkbO-s8xcT%d*(3lJuCn2n}68VOm3okagGR@Sv?yAYS4%bj;AwMaU8EoAc4PNsA@ zz8#W_va@ZR^0~6HgXV8ap#L~av+SK`aM{7Y>vs9@k7`}<-HkLcS$`8mp0gGz&u8Nn z;(D!wZThk@07F2vP1PKdXXXd7p`F|pt0fNv?(Ap3*92+YBg=DIxn$H2o*Kik*Z`qji_)77u{c*e)mSSJ%0%t3Xhvd^ersjkPkPCk~djD2T0wmO^ zGKKZi%>68Z7>wyqb1?vycyWGxgFXpaJzB=3Cu3`D63p@xRLzu==lz*5FfxVJJ-DP-1=UuQhDZBI;mf|KYM5MkrH721AfoturC^uKw z_9OQ1pWh3xOYZQ!oSGnOhW0go!fGm%`k@wD?*#VbrBX&C59l6`JRYeJ)#KThX>1Jo zBLL@0(3Wg@`gL8w%7({(O}x%rE#s>q)v^bEAf$u1P+xLf_e835BT_tsYMhYzKxU#3 z)+_Q+s6TIA+r{0a2_E+J`R7La3y!WyHVQGRkfZx8c>B)uB=0DU|ZlA?$hAilnmSk+m*m}ryTS9cuPmQz&G zC|+WdlhImy8z-8;#=2Edl?pE5{+83 zUk}k!G4V{L(+&q)n?x`H0VUc%dQU07Qci9kenzaTTlVkKMK!iHoIi8LTRD8J^NK-z z@FTAa?~;XuFLFa8z13PmeEh7!tpVxV9C~v?JyWo=ZiD=RDy1@&mBIV`;&4CdEWWN~IAe@@Yd?>XH&hZvO?%k$g2dIk} zInri44fliEl3mtGr@H+w8t2YifMuc!$YqkB;?&^vGSbiGE6@;hiRh72FTU=51o(yE z4?eA=QF9hbCnp0lT6wg~AM7Uhl=;Jjr~GK_%&rf+PK^(w#Elc*2_(@S3@#`CW~7Yn zbE(Mdaj#lte1d$a{Kz!JE5@!CVtlpMy;1W9m}mbgQp4Icf=`3#eg(1Yec%%L)|IsS z=p?o(xf|Ja5iuHDhkPZR9{hyNx8-F+DGVR*Oyj`AX;-df%+r_`t50Q2kcWHn!003hs8c6&MyTM6}I3G}suz}waG9594RB-$`N)I}> ze^mR<`|`Z@d_L^*_?0bxrXTDi^HD3%(SlCrT#C)&jEU_!#%I*sL|#WT#^HnBT%Nix zw(PO=a1_`8qGz<6O-rn6t2qO`Dva7U@8Z?#1Oc)>KRD=5&lv-#9I&S_rwE!ns8=O~ zGo@8hq>FnEcjQ{kB-X=&A}8S4-M#tsZ(#JMV!jPsA(~-H1)0l%!=R}Id<+eWkK#bP zSX`{Kd$qiX_PGi(f~8Nr z|3v3Aqr|VXAN{VKfCP)3XjV-Ap;?qXi6|KWTJSwn!if;6^0Gt-&?ziLK+7RG9XYRv zX#~;oeoooVKl_v~Y=P0kJN`u+sq===!UbaRvu7& zbo2Ffg>Z=nT+$uplflopE45nxLSV?w+VSu0Cro{ryF`kNqicr;GKc2IQE1sayY`Je zV~HBuMqeI(RF()}S=3Dh0NShHwV4*pG%Tf~SIBml?E67)+gvxb5`q?N9mLdXY;E0s zs^fzM+C#k9-WPPJ+ixtYx0Jm3^a;F-5GoJRVB=0jp&G$lFgY$6am_vOt9}+WK>xz- z{rL^7s>b>egHperT^8~FjuEZ0NavelE=2v|mxZ6T)6+U!BpcUTh-#?{}&lw7xwl(WzhM2o~6pP6_D*rTm zBDp4^%HAef$uuHH^I^_hQibmOh?4bL<6)LqBZ+=K3H`ZergQtA=QwG<4=uT&;>XlX zwWBg`+_8lMe)3AP3p?{ty%oj2IVy%yGRi-ke|Ilkr2dMpshqVy)vLf=`Z-}O2;q9~k(5v0y~ecJ zS9~?4OhqKAHH-AfI__t)4CyE#*1Cc>K<26@fSb+XC(Y7GXGzzs5|iB0iV;nVB7S6o zbYubkQt72Mc`KFji#*m(O6x}DtyE_+mbleg@)>}&lwF&i1;238HAnjpRr6JCv?l^i z;Cjh9pZ)OKo+*QfP;)ZbN7K;9zphy&%85qy4ri16nT#b7*(|5}h7s@llD!-N#L0b~ zaohH8XpF$a(qPq8@AaxD-h#4952TFNoQfG$4u}JWPWNWamsdlPy*fosL8q^zGElYe zf`2fFMp@5pgvT&q>=Xd)Q$q{CEZ8R?TJKpn!jLhdPTPmOK|$g4NKaghsYbbGRu} zZ$*l-gILg5q+O9hODi^A-ohh6dxj;~KV_PpiQ&}1xK1aHqQP(!k5NCA1_`XArL#WP z9CBopnOR`f8P7VBe@Y(d(7VijEHH?t;)wm@wuAdANB4Z!;JH^;MAh7S zF4XU&jS|3V`a&(Fg=nphl7YK`0Xx zg}`&k`x&`wEdF>lAwNxPW-4=8BrC4b!$2kpE*w|<9SdaeZ4(Q z{sz+C4t0k9D9*&CK{)i-R_^okdQ@nM`J_jE<<)4N9~DLpDC;QaPaUc8(l&=&{G5)3 zsTmQl11QDL*AR8^0BqQB0B#%^?yxY`ejMjzmc?NMO3A1a6MM0}YI& z8s~4!*j_l~t@nR{tJ?qDmISdrPq~rXJYHpg;T9us;_d@3_%TBRUpx>Bg8?H$UyrDf zjN^s%!K@`>|c&M?rRh{*g!gf)CWjJu~3PS33&|KbFsK zoQ_nFhp9{9=3lCOVHcQRY*xx-Gr6aIRc7Q<`XM;JbWDEMRmKi?cXYTF^_XQFXa`+x zr>mmQ*zj!YebY}{GQq}B*)w)|dbzV#O3!wiAlEbN;>o59}s1c3g?(kpq;?yE#=h0Z(J#A+`yx)*U@K|T!pqpqoYyqZXS=|ff>#|&hWP{1FIs!PAvM@0jjv}t{ro?- zM6W>;*Ag-^K>g}(NcYqsq4@&n1jUN6!~w*bsGCt;zpobns10g$lhElRQ_k92pq5M; zpL9qK6m)h(-#w7q@!te;>^&TXe>ghF#uxlraE6tk_l%z>W-MyHLw#<@EY?pV=iOX3 z|GoEEe5UJ`1Ap%_$enrdTF^%?E&|#WLef+##=n7O%^vd+n*XN5hyJCj6Hfzu;UlX@ zA26j zW^LR(LE3<*gZw8tpyaPL)i8lB#)T}3Y9TWt*rg)U)?|A{sG&Jm3ZL*eDo?PBa6_*S zN&f-Gr96@CIA?vd+2 zW!1>_T5VG%K^8rY4ao8oU(vAW;b*0h-fO})XUuh0gx65lJGBXw!ie(sn)*Ci9H`sF zyJB3stexlDL~ys>IFhOumXuiPE^cs*0oYrFNiTR)?f@a*GWa0 zTv!ivzp4h?k|2=J`hI8ZWqIN^du3el$i(ick+JNy@$EdT5p_vboxM-f<@2aA&DcnN z9d}ElZQ2Lh^OrJSN&jXacMgT*#j72}$A0NO7jHmEg}3sJzw2VPu{}^FH*QD&00Ql;w6}W_<(-#%Sa}J$uG7ISW6;q4 z@#Z99MI);*aOHD!j|@C4Mcj#T>J9Gww)%C;m9txtoYT%*r1dmb)5zBHbo(+BAYGFj z9uJ%#>!82L&`7Ho00Wuybfh2>o#SZABp18!L{r_}lXp|Lz~qD}Jd-fG}vuo zsD6wQrZc04g)hy;+LYvA*Sh<_ks}XoD=@{(lT^2Tc93_s>9!M2Os-hx1l0QU9@xj? zADYr*yDCp01vVoE6EM}2-c8%vqKe92)W<*7Omo1i1zQ*-LA7+MO3q8&U z7xWoUh-Jhoxh#5pN?LOrDx~Du_j22=hCzBl=f!Ys+ZVNgw%#?K#a_)5-#ED!=QP+i zU2FIZKhPVAaKe@RRaW3x>zxiO3Ld?5!eI}@OMB&KxLmWXcl;~ZnZ~u|sz!G3cfXa~ z*(&;iI$d-AEdXRlW`TOb9Vfs>6avxju0Gb=5-^V=N{O97Z5AnefJ=t!40GYb;Hgpj zFX2h_Rce$oY-tG@K$~x=Ap=X+lWdnl%D19e2?etpnc-H?qukE4FqXqpY!b-B9& z+haFZ{FkWA3nQ3;?A2E`3Cb#G41{Wf<#Pm`dA7JQh9A`Ym3g$;nxCz{A=%tc%}hCU zFb6{MD|~=XeEh3MU}dosxKq_^eR`#-X%GZVvHS1@kSYQ&ON+7wg*3GNR0C0>sHAHP z*p3ssJ&M`5jglrc^+4#iZ)F{-*6A=q&aUfEOTU)V&u66DakGxlkoHRN?kq7uP)xu; ze*?Mi4qYYkC1Yh!rZ0dUkh(yz-ZV0{9sMM6Rv0JxaWvXbjCG&y1Jh6R+6=x)ZA|^S zXZ%D`#6L6*KRh!zslU}?|8S-f`&s!0Y~waK@%^W~QUuA$hn??&EfRf0GDob1TiIg? z6x>JfzrF8h#5J|3SuD)k26t7%SiZ{$s0p*h{AFqWS4g*|A?ZvB6T>O6QsM=FJLVNMw zzpnt8<&PUz;A67sODjyPs)F;Mid(6g{54H#`@{1EfN2(aPij$eN?iT3#9cmv(;c+? ze^`6#sJ7m&TQs;8*9Hktyl9KNyL$`8TcEfUC%Ai|K=A-YiNNZ+;i_g2likmBVp{Fy`MbKT64`cCs`?30U1XD2qTZm8jwBmvj_!fB!7h$ z)%}2$ww9yc#==+?_qVsEetOsu>&jF}5TO1F0K6v51OT!GR15xU1&1{dMX>c2ef>^X6{J#p{m&MWm*Iv-aC7!O8t+Z0oj*=S{5NpKy{E*Pfxdmp-t}l zwhH@X*i**0v0xa+tG2(Dij8M~&s-1z;_Qh8dt;Y^tyY2dJ0bpWFIrb))16KtNr4fV1=*6g_@a2sg-v< zS-R41Zmx?31A=ibduCy46gn$(&}%yGPmj<(`8#R-owo`_vGXL0&TO|R_{$X^RU^?x zz48Qx;cR%GqHyOBj$82YF2&&R)mVMf&L%(8%Jt$z3m8L%1{1ORImq_C!WN!q_PFgH zL%s;kRxuM%+B*?^_5idWWbfR1v9m=2XrsvXfjdNEln{<9_jjz(_AmV78OHz-{lEls zm#f?%kE956s?YKyuBy_&%&0tztOJ|~nGJ>9O`h>tmoTcvc0{IeI0bV>=gTl{<0QK@ zXh$`0{6Ks8gv8Vd4=G zS;w6l7D-U7EL*sv8C}Bvc;4{aD!7SU@5`HO7EzJ?w;s57Kk0o2NH{D{B-Uc9m%fTN zoy55=1s_NF+=sr>A%JaMy7gks-o_+II=S5Xjysy3(lG=F4F@#@ZOG6O-rU3{FZvv8 z#EAULYiNG2t&n<}unmV0jI(_F^2o)8a&GW}I(^@<69-#W!g!-$>Xn5L_^bA``zB!> zI@~ohbLfG&$D=j&iUV`K|9n43?jpMJU z=?4Hd3@SE!A4wal(x5B>`V^5QB*B1m+QtN+N1Nzy$%_0}#*D=L`t|mnm|lUJsB+D*LSd90g|Whu)>@= zQhG^OJjTps8@78z@l4^I19#!&KBzZdt!2}5x(7^WTJ`sy&}!> zk1A~v{+JcByg)n>@HZw|d_U^R8gqmrIJ^A?-JC3H8;w9YqMcE<=t78brpPQ|@D{HU zt~=S#UiWu$s&1^z(lECMxT3218Nu4fzzwI|gd*^TjjFGz>fNJ48~w-FGw1w9(M=In zSD&N9<8y&@p*z4(FX3Ite%5QagH|I{E@146TF8MnT)R}I;n?dt{w!mH?W@TCK+l{2 z;Qgm^yvLAUjGiF$w#U+`zAN4YE%=#Z94+ zdKbdvfj4`O=V6hGp%I#kHHLPYN>V~=QBx*-!R>EzuY5>N(?wExa5rRnbsiHWbvEji z-DWN=s_F^{C4q8o1t3$j%bael!dTUWLBA{i-v|Yls7As7 zF29K_!Zt~nM`$)$nNpC)M-5D=K?=v4T;-`ctQj91m%)_uC8E!}#Aase_s}}^R8P>- z9fnBh9UJ+KzC63VwL>HUSU5^5Vl0 zyT-Kk-?`_~Z5RU)xvQm;q^I0c9bl`u`bAYFs4rqE{@a%1!t(ewfHC8m_F}oQgmEBo zUqvPvWTjAeOvUNQ0;IOTO8ozl_m2b$^^uj><$7X($~{{F86gP(UfIR5$cYR339YA2 z8DwG?3`UTI7unsbOQ-`PsOz|7Ld$?478~H-GDj-$+6Zv!fC5|#fOG*XohnB}W*Jr)qiOp!ZXCnHGilJYwwMcfX#>cJhl=(-FLprz=c6 zGd;Sn%JpVy3TZX$WeJG`5fJx^&{&20AOWC;JygOaC`Op24qwoK#^(=+Yz~fyiss(! zYg2v|9YfJB`@$dJ56O}1JjsB&8bNrRg;Yy)?6W<=!q(nD2%cHv3EdV{aAEv} zIUtldsAjUoQ`Vn-h~AqKCE0UA?DelxgX2We(Y|?W4ftq7)*#L}trR3e@--zt0qPET z?n(l!7dgG@$AFyl*y%Q1oK;?bQc(=%q5py>9RCOm&qIU)5iNiqMgGm80zzjIf2XWC zJ(%>+oOmBuP00I zxL4X5Yb7H&8p|YwXiSe~ze!&oE|y6V*QuBx_KGC4U;|%+Kv@3FWn^x}z&&^}lk7sH z*b*cD3J*|`v_$2#X7`1*(3Fwap#CnW^VkvIOU3k7laXM+R+M?IW}}P{upek~j9-iB z)1>W0UrGezmM%UM7$R-RceaiL?K(g0t6^I=bs1g%&OhrHB*W zcfeb-0nnr`oQe>I8I;qW=k4JuqLTIreE<)kc|d~Zhvw5$(OF0` zt+RLFg+lDR)xQ>v8?l~0_^&ZzfA_0x#d0{5aq1|NwVarTkAw4#p9C{p`t&u++mjLO zMgtTcy~@cv+G6FAdQ*A*DGr_kS{J${0_FaH=O2;1Hu~=v7RNK`+JVDE_8N% zE+-FE zlptz3+u(W|?ai5_PIP+uy0AwtH_9X^2`6W&@BBd)W>Y`-=Ys4L_MvhV^0v>{G+aO@7`ol~J|OwG~J`ysAH*O#2<@s;MEN1xQX-WQb{7OCa!U$pnUd&R^Ag zZM-$b-$>-)*)0v*-~nTg`)y(&25hVDN5ryRTQN&Ix4AX6Y|HJazUXyE%aixmQCWS} z`#$sK*)tNy2;Y8mFW!F1a>h>d{<8u;Se4wmEFe=<$MBU<8$j>YK@N+7G3ON5(nBrX z-ZRDh!ykG$H^>@_KDV$2QxOH8Sxl=Fu9b;SU!wI&O!LNkk@29JVFDs4JUu(-Ty*CW zD#GQk3C3RmZ-SW0*qmOI{mt-zfv$(WDU>1chD42;LS2-`;e`2(4=GrXjY~=HPE)1H zmn-q5Dqm&NM#CN$TrSEU1b}7$IP?~(SFZHUnGUisZzW-85 zi%x!!MfdgEkv7-?dij~oA;88sw_b#a+WSZ7y1Q`YCb|(etU%ARb=RGT_-(<8pMKpfAega10k?83Z+`;c}5i5~br2*o{w^(Nr zc~ndsE-th$@2C7P$LGa6k_$afn0x6VVL-P!MX=hB(A9nUEnb5>?`o1y%m*(Quq$zK zJXR)05Ulu`|0-DgyKeFC9Ukjq(&F?6)j2>c*2e2u3|;ZnYcN44eB=aySUUug@eX(= zG{vq6xG-tX$IqRq{Wa#XTD|u#6GWsCCk|$Gzwna5QR_3KSYv$!5Vg;kqWN0u}B&dv% zx_fT_HD2L3(P@?5zDqyRX-V_luMEfR+m*K6C2Iqz@5^QcJ@LUT*#M}+paeh{Z7@i_ z9NlQ~>LUqd#Y=klLPH}r;W{U}mJX|?^|ZO|-vk#w;hM^y+3+>vR6##pu|&V|$_4LUkUZ6ug zx}q5qwBuxkZ;}7HEWD-zi2tdmS=7nkrJO{_@5niv4yzdqBldDoEz0}@5_p?D0hrJ9 z7KCOfFs41C^ap`(`CdJp#^u^4!i$V>Fq)x)CG?k9ob&^I*q#ZCC+;_PfOAiYNf9eQ zz{S|64X1d9h?ja2O4owd*rhxzqHj?haRi@xYZ?>t}oe(A++ zlFM@Un9E2Yp7iGJLjcgvr`BdD}Mx#s~%!xJb-f=9vXl zBRyB8SFlCYTMR5gG6xL`6P{yE0UrIa^Akx}P={b1z*lUne$`*G~j*AQ+Y!_4O`t30N#AhCj<6m@`w*}a7}mHJMy$~3vv}`;_~XBI-ATf2b!z) zwRk-QgS^?YM02F2UIa{j-w<|9>7=EZ=tID(1p;>&yEF$HD(8H0_zmRvymjhh7K7ld zoDD1qSKwBauY)h8`{U_aO@BzdpSohv9T=6W_(0__zs=#xn$$h%uA2{Z4|h-q(owL( zn5E4193lw8k>#o}{$8~8zL=WM?8O)Wgr4S#_c*whq?#lAvpGo_WfVyxCK$$tA7v-v z4t)A8xt_}bWjvkfW#4KgZT?G}`df;I%!Ua(O)e|g)>dyBU0b;K5H??)WvpACB~0ph zx0%Ypc>5DSZ;%FfF;VM~rdyM({4-uH0=!Xf^xbwfI(vqC8FzbiNRz-M!}NLpl{Kd# zpb2sKOsix@QeVT6DHl8*9i{N=C?t~tBzA`vLU9B4k5EPYv?ENF`8N@6J;h*!B@cS7Q&_X2P-)nIc zvnWbpSn0V$7zj~-F5X$MTL-ewI{s8+$8*TYClzD|T56J;^hNz&-=#kAu8m`RKF!2R zD}6)^Vq2p@_OBs-B@+|r(48GMh|p3T4t?ogaegH!YL!W8N=?j&7f_)%Wi5>9(_`Dk zJ!cn)#*y$ll+xR&Aw`(IuN#TLKaTS3!9-NlrxQasml7WM=NP?|eYc!&BdL%fMZo&@8Dm2QuPaN!VDDRW|X zB-upAkX9w9kMMi5AK0~gItBcGzv~3y9ZyYP_b)Un4F%yI!$YFUF8sv--*#o5C*e|c zV}Q(Hq-iGu9krbG#yjF}IPNF8SRq8wjQIo)EMoDmYN5K#Q0Ng#h;dGwkr+vQWK z#CEbdJa=0yPS`iQ6O%F9Angf7>e~yOc=f8x}-RdVlQ%>Pe(`WyUBa(+D!$pbB6b}!81PrMZZ}ePFvHoiemKdA7LD3vz zBjG=E8DP>c$>bwEjE$GZdQI!-`+;I_Op6V~6Wmq;(vvjRl;Gw$Ue)xaZbm10b9QDTBgyYO4$3%#8>=@ z?}P8?+c8;Iawi>6{MeMJQvZO)Bgk%&^=P87;Iz8_4W;EHXhICrZ=MMzniJscudYX= zY5MtPk0+a^s}Tf|vpqk0njFtqQ>$Sf6BL*4a$#3=b=Jj-4K?M*2^UV-#wa2cjO@KQ zB!=mVd~Z)rm@68d8@h3}${LXrCV_>xb^cxm3%8$SfItg!P$CGKpS>yY&$Y*9Jukx( z02e#xGh>(){YE{5Ly*fLB=B}oIaF(eR#f0c7rK~APup`Vd=Wg>BQNG}fkZd>9P6PU z%bAs(#mOWdO+Uh0Q72qiR*%+KLNa?1#xj{d_tALOZ&ec|<&iJS&&sL(!H4s!+E4Co zxP@xj*?R=zBf4X&rRFt!jb&wYO5o7oCxlj+VAJtE{E_kiVnD#T$EWM!b_>V{35iW2pO1Gm2M zS7NZj_wHbVnD_+BbOr((oMUFffbpUWtEk9m2nl$~C=8Ai}1?%?eS2qpxR63xf42&mik zSiuoFKyTw6Y0GYh4J}h=ZyfuEj!0O$2ZJ-KxDC8N+rIg;!t%Nz4jnjWIQVgW(r<7{ z*Lwy@2G(hcE!oEIb@?rcSPxhVRz$>A)Z#^@k#dfVsk^WzUoU1Y#%G1KDe)6F<$m^` zLUAchDxa9Dh_$Eg`X0~g$<-K;2PSLJn3KkIeDWpZaGKWjc5}b_>a%Pru^|QrxnBHL z8IM3h9%J;wGV!x*Dj>4>@gf1DM6a8N^L-(TI9tFq!5I}J!U&-4Y$zetHPh)ek5K!z zUn#<${+;a3CaaUJ1F%Qe3be`UGHNt1X5r!YJ$rxQn}T`f5hG~Q|^67IT+xC;k9ezn0;W)^u;TN~H!@#$-39ySEuVYG} zJ*D=Y(=QZ3V}2;Ug6V0^F|idqSi2+K)cE?yBZ+MyqLaWvNnk;TDVSg^qq{Z}P%L1_ zKK?(G^<)D!hp z^L5MJUW7`^462L_yVIdxMkkK#l2_l`Mf{9p*S_Zsw)ItTPYa<^&lLRw!mwas1S}q& zwD3Z`xr=9^-e6Mpl*zXK|}1GsDPF6y(*CnTw0#YO$kXx+Tnl z93v~$t#zJ+b)GOCkFSOf0bEprIntx?@liCh6gDE83JI0hoOF6X4Y*ao_ox&G{%x??K$h>6q9S;@#o-+APl3UC#^@t z5)^y({R&BxJGM{Y!Rc@^KZVBkD*cwgwN?|t)3p&y`UCpSk7pk55@B$kFG3VDiVhU6 z*HM}k4h8_ZfLNVAt&Qcknt3vIdDJKiBRc@0(lZDTu;)wTY_J}- zChpa?%0J@<3w3X39*KQjGX3}+Hn3u`&B78q3Kux<8XQO%vQL}=`wf;y9Xo+Yv6|Eu z_o$|ZwTGHS{K!SAk&E0fy)g{>&8hqVZsj?-_vD3y9MSN~=hsv{a~wY|`xV|`a1B`W zS0q^}4U(EiHJC;Pj+~D&%SrX}zbV+&WZ>hND zWo|LYMdWh$k>If2E7xaHMDldoqCu?drAAmaQCCzwwLfrImuWx3Fl3ro#{j*jEaf>i z1%qCo4E!5&gHTcI$hLPm>ycUgsPRI53m({;)tPtqgYs+B5B;S?sx)R7Ld+}la(LvB z=NXf=HRG|#`2_7o=Shq06nJj;FJGBmgjEUW6|>0B$;*C~%Wn{5`zppkq7phUH@84z zx59%jAH}FDh=C1?yome+IlaeiN=c*#jIut>bqQ+w9S0H+J!$8;W2(1)b}Zn?VzYY% zc_eTg-9Jh$G9U8+d@I;IgQyD;-uPx1dXRfnCPvvJr}1p6a+th)^F4dE=<{h%v@B(#sIq{|5xlq>jDK zwIvpOM-M)tF6$?a%O><82VS5hkD{QS1`vd}j6fz_@%>*bB0#U_I^&Ej{Kbz6m|;48 z0!o50)(>(u67s%eKwKi6VT<`}FFD{}W5tL)kd`ZL1BQ#rQ|`w1se#X*hX^vD+}Ru)yfUZ&ZUA z`5m4puSv-|We;)C(+HxO!e7?7&4cK&GdU@DiJrkvqulYvRrZh^0#=H3iQw^oACHBE zvz^y3OViA&dpgg|Nv?Za_>aX<)7k{-{dGP%DK+U^hjz%@C28rV|9WDhkdm5hNE8t) z+DPIlgTD9a@;oTmxe#K;J~TgacKPLheNyj-v63w~Nt8Qrx#s8=7Q$T}dJDfIu4VKv zKO&Wa{F1{hS<0IdTU+?`|2ztC$VE(?mUIy{DVYu#{B}8yI&XhAHy{nu{&pHZ*>;|C z!~$=%NC{HNm7tJlU@^wVc{(x;xFcpV~7;ULw|rac{e6Fx%eExHXYmr4JXPGU2in#wLRV-IWph zbah3(8K1gU-jPkTUUYEbejUB>D=*r^j-bNgYijp(XIA@B*d%B%P7~~Z7WLy7j&#>N zoLlCFBl|*}`^?q#O^SsFD1ON3>i5-H80Ap8&P6=d@<6u-?#6i;wAG};u+S#uRS>V( z9w}>o9rdE^CQZFs@VBk+xiHDK&g`fh4@HFBS*)Zf7KU#}+m7FY9{~wDyTp`q^VBF< z$$LnUP%=CKzC!QM?{>j2fp$GaA#zZvg?rl}FiFe>*uY0D24w$2M0Xdo)CTgAB!%Iq z02;irpx>cm53F(tw$Qje9ZCzc1KNvcAN$G?Cek09mP)^nK8i5&$ayNaUi*~y0`Bu5 z5ZZ2_h%?bs*3ut(O?vaFsqkmkIPz6+fP5;Y~#E4WIomc6UU{9oI%`oBi(xn~51_b)I+AzVO^hD*CQ(h20^V zD2!Ws1Y|}g6!q~Q=VAgbQ-o&6iGL->OmYl>37t%dvC5U1gF~v_DT^LEDUMVg+UKXuyKTwPyPf;hVP)=7 zE$T>I_+^-U`iai(CUhJf9eHqcjktw!djx)bKcGHuZ|6#04x*edUvv9E91+*{>tmgF z&=;ETCY$J$riJPLfP5xD_@3#k6S)~x7__SMS&NU(GH6^9!z1O%wJaqeGdRpSHAFUCOe&);zQh-AS=<4>S%VPQSH5gXrc}zEv|u+XRKXAz~1htOHuWz7C_-8sXCinHt( zw+SBpaB@LiO!vN4aXQAE>9EFXQbAs%5D==KoSt_gtii^udIj>_@F*p6vB&`w|1{ZcIIEEDC5tV$kA`|?X2q(h7F0lOf53K$7M0rfC zE*~1*HqdwqF4vS3Bxu(!1@Q}(WUF1wW}%ibI0XtkAB4UcFPvVX#~|W=u4kzcf$LiYXn=zg@41|bXM1N?5@mzoeU~|7#arAoiRHmf43*2p?>N#b zH)lyTS8%Y#c6WUVM7P}rtxSPTWs&UF z6(H{V4~ml0+2(mU@kiA<36awW5^I{GMsipZ+VVXg_L*O#5V`x@+MN7bpD{6gUK4g^ zM(w?eSaQ8_jYF`^gyv@{FzW)=@)wCc4riZF#Yf?8hUJ1|vY~0ae?T$@cVI8`YHlKr zJYSyL#TzZL!vGmk{oGXQk=FZ5RE?cJ8?w!^Q#x9(Xp3HQ!hD*f zkC3sAm$^2swPdauoX?C;w!aS7WUi4Ndi$k7zx~cDhS9HLzh=kfn-Hx6tz9#h5!7SV z=w3WW@zxr>3jGGPk?EEoXMKPOXc>BXGD3nya^XUo{2p!PehH)|1G^R*pHlUKwz%h} zifT9&nM5waSyDCL{Q>Q7_K;Xp8cl+#;R8fIFT?lA2Jk~U+&M4>Yg2lhigwN-6tnXG zfEKoBmWt+(1aVK7imxOaPXf52*xdBVTl4sr*;9gIH5jI?NMSnq=Qbj`9Xgj#Zb4SK zO(%a%+M5-=lKmMYI#05OZ*mni9*LarW+rtad+2l7YK`t7VD8_?;Dm;5P=_a3iuyL% z%zJSjUk(csV^yV86RROA5W?r!S3-sdN%unsqv<6=zKkq7s3|2j4-xq&rHiK zr16DePyKvX8RV3=rAojbrf2R#FX=K0C`&o`)M#QNH;j=OI?t(yNhGS^5e7cw#m=_ zpm1^P0#fpI{8OoQum8D`5c$TFo}O9pVsFCBK64aeOUrzU$1|g%IplbmiLEUtg$6VQ zi731ryCDt=Ucra*cS#{HP(Dz;593+b+y^PVjW^^nY0v-u;n$DT1$|qCxQEF{Tyh`* zJyXiO7wJcRP59)Y!VkAo9CtF4pGhbn+P-J)dwm4@tbqlCxmno2^e}>~+CiW!XI2gn zR$R5Q5`DQBUsZnUB7zX1^X=`ootBn8KhY&OhcIc%`amtvecbWTnN^roKkbW&yT+IJ zXGkXVpgg#F*}PO8$F#T-y{M~C*%RzGiZiw|3IVj{F35uGw8&|Qrs`#3Y*OaQ48pp< z%J1TyVV~@XH8}g9*yvfopj0HPR-)9s3f1+v)az@>$V!$ul))bN(;O=JnHfJ}-G=jx z0G9E(reEmI+Fp5HQ89XLS$X}4|56eo55;NnEv==oi^!JSMU_}cOVxgtF~jIHJ2aQb z;}CN#^v-C*xj36sI;%A#^MJN_DjtAO3E()F|kwEXDXYqh&=EW-?J>Raqvw?KU z+i(7Bt1U6EeyFjYEkyo`BE}CgLp0&q`&+9j@d42^L;T75pcX;5M=p_HE*^a;Hp#Tg zG~4g$bcekT*v9Gm5YAci4i_f2iuBzhq{4A32x4QLvU1#%%)g8q(5h^(%z_sU#Sd{0 z6YQvHSI;wyL=g1A;Xee_bzd$lY|-~E?@>XKvYyFdqZKsc?kui)x*qi&gCHJUIryXZ z9|ACYUm;AS97GFEJxb8A4)9(%SUJ7p!&{Or2a1%G%|mb_4T=)i&W$h%+++NJjY}fp zjT^T?YT|V1VI<2xB)CHmC|?P#=Uj)5b`)gXzw<^U_JK7-|x6|-195qNm}9hKtG#R->T}u;SLbD{nwwUyi(?}d-1&N5No&Dn%<(s3W=c{R3@LbCSt?2;F7d@ zwZ?B^h;g2uB75(zw`OjZke%(avNW)ffR?Dp)F&?sTK|Cb?(82_jteg#O(C<;MNy6< z*3RJ&y4{4yTqBG16aBz`(|}k-%W^$8&SVeJI?Rpbor_2ey5l;XpE?W8WF|}LXOeI zR;n^bw=;tyO5Kq@Y~cxRY;3VOR-JW%k^gyj0_Fz#M}@~UQbpvmt{zIkl0OkutVC*$ zF6pjxx=lYVe$P3Jv#1yq8p`U*N{po)iYWgXVxzTOsmvX^~(&(;k` z>0F{md~udCC%;id9JE`%FM_^TlYaK&rRBarXWDVVi0k>x#`jBc&k;9xb)W?QD_G_W zzRws*m2;NOe?Y~Zc_FbKsf9r+RbZ25fHXOvN(Qq|5bR5-1-R<`XOnD01vU~UA(_T> z7|_D$4~$9p9+BDla0dU8@neRs`r1L(LdzF1kQg4WMxpiGQjrvPo(a15oJ_>s_aa8d zXsaG_Ew8~pzfrt$x8@&a4Q+HrB^8nMRb8LnwXWWyb$pw~*nG8N=w>raUKV$Tlq%31REv>-*1AK*>yT-NP^6Dw`7aY3Iu0^GH<_?D!Rmm?@jF+-6|4ZKm%_ zs~pc%@E;Ilr@b+y@$&xl{X*e^PayP(Xwb)Nx8vs_W=M$NLrB+Gv3%#E&>KVWj)3ix zRd!-o01?i0Bsjf)5Kz2IugVSB6yedTb9aMGelv?TG=cYb0N&&i*i+RK7rmj|leX7_ zWYn}hI&Aus-wiodi_5=t?2cdDTSEiSe%&A4TY6r1^e6u^Z&hjO(B$z)yl=#W(l&!gD?IhB$~ z&yu|W1wx763|l5fmlw)?sY%uEezQqDs!9)HSR`4rWRju47F5=OcVDzsfpE|$CdIv( zb%Oowg@Vy9nlJ9``VV<*TnQ3zgyX$X)ycCE zIpykksfscXymSW&U9HlMQEHW2r+HVa6|Qp0|FS*&4hVhtdOtgGU-A9QWMcUgEw+EV zRTPm&I2-&^*roMzun_IyqNV!&8rH88*!N`d1FzV~=IE~YlB~N#>Y0_`Uc8Lb%$^om zv0dKS+^>SRmn}r#d!d0NoJcRrgYO)C%5&=_zJwYug=Hj)iz;$q9pg|syC&p;Oi}6| zKz0pt%Cupz88P-lmdUca!IX;+J+QU)%3p=mJ5qA2`WZwPwU&Wq-1wMK!Gv5Y4vDs% zyWcjlS^BMr_y-|rQSWb=tlJ{th&K-^zaM!Skwj<)ZwA!$Ki`*jR_6O$C@Ma#J^AFK zFlMKV##~y{BkW6aqHN5JGtS#0hBuOO+Azl{@3|zMWIJ-Ahz@7ubFQw%{y1Z!0_-ukHb5Y&Dyijopc9`W3=g=av@n5Uu#LcgS=`iklZwO!-e(~70@yE zk_~ipMJTe8Ld^x8F(TqHkd11#sL2NqzefVU`f zT*Z+lQ$xv&)BJluS`cExHx-KY^jIbzg@q6v*1MD)NG*72S;TbqfK6vw4#yW%*@A}P zRBbTdXVVg9o@)GD7>N|$CZ4#y7p0C=`yuuzr)|56_B-c135)1lOvDWRcV-8Y=SPc( zn-E}bM4Asgw$O*l-&=*ARqq9%q(U*Onr`9u+9xzry&<J z9p#FF(klJq>hf)@uIi5F>uTT)Bg9YQCn=RFf*L zdTX6Grfy+*Lu`eL2^`Z|*~XF3tY)*fUjm8a&AYvKrOD&#H8T693xT>%{p0R{QG{W^ z4$m!b-Xi$Do}#m7zj=dRA^xIg4?A~7Hu7V+UsTdLXLK<*y|X-ge$$oD|H_IUBPjjR z%w6;jn*8NqK3xe<*yHsRx=o%fEI*Hw1-hrNt~b*09?OXqb_{flkigO4D3*H?3C`2! zgA_)kc%!tzNmHb+zX$yRDf~NhO?izrYWddoC6fxe+ApmK+QjyJ6d4NxK|5)k7^5SC z1oh=h@r&w6#qW&!(2_H2Yxlz*-|m|ZP2*yIm6RjA;ZvMX>mGkV$`mo$LhN3rNXB=H z=lUByp5bi2YeLY0$;53FO7B2=5@>>Ci^YApU@sF6!O>8Zk;G@6Vj67kwlqR@HQM&= z+#At#!Q)^_1W#i+n4G)uHgkh>=Z8X9)@vR@K*H|>>}hLjjI|aY{JXlpky1R1uC$rRx3$LH+;ur*;)rJ(f`<%J7$3a8TB>l73 zFtM9r4!URzv_lUOvVK_Nd(o`Hs zhd*ZKHYD@>hxEk4S=MihkjkZFWa7rT{c6|O@dr1!?h89@|5GsOx>jj=+{o}e(ygAw62XXj9H=!V%e96X7`V^oqX5!e(&LF z8>U}yNS$ak)$wg6QF6=PZ3>&1))&!|eqStF{s+y(#gkM$^=f}GnBlnU`>*EeUy*MO z9JEk)ZGr!tg~iglO_W)tz;bqDiXKxt9jug-uGsIyW8?l!3dGR5m}`0DMzr#FT~mpkmnbXPMb>aHAe8#G1NtJt@O#vo1I zH~M0T=tTd$Gg2;pin|?-`E3!6%q_R zB!i*UB>dQe3B24*a73KwmO5cw&?gn`uIfgO=Gh+!VSAco@G`^m>K26^4zxtzJlF}6 zRZBuaX7$$ZKU+QpR%R>H(h1n@ZuChVJh<<2Y_-3z`@VS#_kAJ8TyLZj1zsUVk1hdL zOnFyGOc4aZm+bJ1r;j5_n9#QEYX=)ox+}rL#UBvQPF`?f-4@?&JD_3LxP11wZ+qf< zh-2>UdM{??mMkL?``z%_jh)~97fGn8Tv)K&!!tGvu;4^hkR7E1{(VT@f&NnpE5e2T zEWVl^2MLvtix;gPxM<99<_7ZG`r1UYDX6RtLDVQ#!!5KhHsV{Hjyl#`AF|E@USW1u zn8BP0no>a{C&k4cmvmCnfqy@kYv$nctS)6hLO&hb%PWuyt0@Bp!ja^>9s7wM;!=K{ zn59oHe8xP49tg`a-;gtke%>rP>pW*rMQR-Yj?TV(PtC+icAWNCw z_WdE`)+fhetb7kch%=}|_Ydfi>JuR!nFjZPmtX#X(xIjOzuk2&y!D`#p*;&MuCzXz6zEd<_y#^D+me z9YRw>pLK%5mCImX0JU21r0i4g-2tu0?OmT<3}3KsbVx(9NtB4n!tRLw=1#0%_fr-q z59W`}x|O7H{I;g{i8`jq3lJDz(!acU;9#~LQn*-U7oN^359sgKo1VrLrs8c_Ns4GnJqbCEtcdJreG?oSTx&nzaqJxVj9S-2K zJ-T{-*vhGgrQJ|eYtu7}u;scAQ^W!@T2Pq5)b{Twv8a|C`HST^V_R|w`LA&e7d|#T zC{X|4Pq!ZL{Eyg9^K~CqVtO9Z4HWb~m;69DTl8sh1V(J59#L)#%9y*?_^wAQ3N12; z-jgw7;dX)VHrKaf-9d;DGAKGm&E>CzAzmBDyRKAg9o+BbIFN+@L^y8#O_pUIQlH=5 zMj_wFU@v_^A?xE9-6k$S7a;YKiA1qw)#Et;TDBEyjbOaYjzfG zxXL1MV_A3du&w8D2ZH8k%gb|kiQL>upQ4XA46~3 zWD1%Q4wwYRFa3Iy0fQa|M66R|BAr{aE4vY&DO$2 z9ehr<;&67@9ycIQ5Y~@a$~nk%!qv5-;MW9X+b;`?!OGL+qNkOPy)KLSo3XN z- z=h;7!*7Yw#A51P$`2&<;7nUXAVvg2u_lE$7Aj8T1|fRA%%0|{e2AX zaE225CWWe^x)00OUJIk(rx)EaYU8qo8ze%f^Pcebu5b6XA-oUIZ+w5Hy!g%Sn|fiN zvFNGO9Y^W{GP<=bGOFlC_7nuh`#WDiv*~Ephb~!21s%mkM!~dnWa6?8H4^xG*7eM_ z1A*+2u%=AM&Yr>o2_b9Mh^u93nFhIPuQa#@Sg$-f`C<+xfhP43f{w`*xk^2vG1p>O z@`w?`?9ToyWJV?dm0jN!B6)E!b{V>ecHnc?pRz%x{7(tizAi+muVynR;u`vIunj5| zvtEv~3w9;i#zr9KYmQ>HGu%@V)7*Ss@YEYi_-xyaw6 z+;P6xxMBpXuPB6|A4$LH-l!bV#ZD?(u3gF=K|kk-8?+^B{1$ zz>x)>>v2&R-`mZd*QaRAy(dx)NNRX!zC&)Ory6DniSTeL) zSUT77HJM~BKOH;%uyZwfe)rlx_)B}|(*M^B^7JtjTV(tKI3<@O@&Sik=PwB6JpX_c z_jO(`D+LBDqAAsoK?(o)=^c!2utyl!ei?R2$ez~IH3I-$1H3>aE|UqEadUm@*3TcF z7mTD!(MjpW_N_}~c~cOhQB&8;y{|A-cS(wqwj=T$+2JX0UD$reQzsL(Ve0BamS?cV zNG?lHAKXPe2IX%7ATwvhbdJjIxOLHCLy*tlb?JnbcZ+HjYfHk5;YAD1x;I19a2Xix z8o60nlITFFIBjj=klolqGW8bcK|*~ol#X@^)n#6Y+nho^XLgw65lH*M(z{59)=cxX zvo;Tie7pJzlcI*r-P^Gr9M2vqfz^e$9on`069)PUZGGd@#8FQls?%J{sA3H+cM5)W zkHTpUwUF|>tE!%<>FoOzN$YkYwmJCtGh?%NF#Bmi+p@CQc(aI02scXY&i-6yS>`=- ziEW%H7xiVVamo$OD7n_05Q-@oar-9OdN$O$m9PI~gJAK_HN*-(XCbC;3Mw$ksB$5L zxse+_bK-IXS#;mrMBwGfV&+Bcm6N+3A|D-W(BTZ+pZ@_(1MDdcz6Wmo96b0(fl3+t z(f#e;3y1L_58)c<^Zzk7b%Gj7+9uGLkeYIW6Gv*w)7 ztmoO<#?1@XxQhA7tK2Nm>o|($^FF@bw0r%|8gF)fe3}G(Q6=!z;u{{>?J2&V%Sp=l zl(UI1+<1Wi|DgKElZI6$9l%BV*thtYu)bYz@}5R;uHdu((7@MR>RiHq0675tN(f4< zVIfud|Ka%luNgr*DJnUWzwn1Hhg_{l0ve5Xq`>{e1D+)U?&N>JPEkrNDWl#+RroxzLI2 zjO!{fsT1sw6xou16ofjIi#JqWy1WA_+d8)c!_M#Fi`U0U#ZHN6w8O zYxSz#;-J%%^{0Ehd6IDCx2BjfJWePW_;L!o%{@`88AaN{y!K;V4$3cB5K~1kBdP9E z##hT1*k$pQpc$+_ds;pnX|z=m59H8yzuQUW&p5hWM-wi6I73i>r z8iN-lgN!6Yb{wZA(k&OTpfOgxTIAn`f`RH$%)8ZGz2Gv2*YG}xrU6cL*oGy1lH~Sl z=C_^DC~J3$uT5fZ{{@h8>fqLn8dq*)t22R=eljMb0aEX_61>W}X$rC0Z%!WnCr_Bc zq${1bFQ#59(t#j>tE%yY#?4Ajm|IX$XT?o#}oM%ks`3WY;19xShoMa{W%JjD7DG$S}g!$2z6w zrcQo8&VF^TbZ0gkPa_P_4i7I`R2UmW!1zy17YP12HSu&}MN$jjq6CYAy!4o5mi zn_80unH}w@@WUWb%MYvZ&Jy8veE(qgTS7yizE2}EGI48}@bx2)ZYFt!-4l8JPg5P< z!VQl*7jUpfK+0yZh*(=UWCNxiU%5apE&k|LR>AyXnaGdc^ zn$?S&g;=Lwb{!D%Oy9LH57AZkP>L_A4{NM2lB^6ETs5$&c9OtE<_cF}qJ@i!`-$*R z^FbVA#*GN2`Nos}+Oup&Eokh;wH|d(WA3nJVnONyoT+!VFgrZ^6BRdXIN#S`?gnxr zpaH`FAdQ@#FsZZ|;pgn4HmvH3D(I_%3JO33PUZPGiN6a)mOwvtVCEdl*4`1rtyHJC z3LHV;zx0~d{T0YE3d)}zc^gUdG@d$if2wgC1`pbAeOxJ~xEAaB#SDL0u!NgRG$kS0 zpU{g8VG8rkceVV3zz{Ed6MRWyX#A*Zcv@B^irgXfc}qh);fxWA&Hp<^?qDBAz!8T8 zL0GE3%iTmT*L``1C!ELsAl7t1J!~}cZ9Y(*MJJp6WiJ5kSu!dsY0Xzj#m-i`tRx8& zaz{(cw5=WPee+GvQhoUF^YCF=`ji#D+Fw$6aTu1H7`|CCW;KoM+Si+yxY~4>1C1f9 zzmxSb-hyOfjY_Jbi++&s1U8Z#qoW=$O>-~t>;1|6U%6){yY*HZ6&c=anI&z+qO8j|`~^oL+_ydh|6(?c8VgR1 z)MVRiQKWRf8r2)LldL@BES28m`Vjg=pyQ;w`RIkqR^NXr?mEP&(|WL_d!OII|4dY2 zR&hUytijS}=>Wn1G7PlCvU!i9ionAn^ayUwv<(jjPdu4213}M7`^1tTKK!IH0L{Pa z&6NY~Plmn)iT5ui&YPieBBNsA@B3Q&+Kfuc)=l}k-OnOrFI|$64VEkgSFKN8@B4mb z0gJ-_-T{58D$Q+vkEi436fESja?sgxe55q9K_qTek?~c1kNNTbVXC>$!PI9Eijup( zhPr)fmArHD*s=H)HX9LIQGUqB#QNL69%0qHd_fv3yivRc&UZBTr`2ms;c+5)C^9ku zdIFU;-T3mv)g6~)bv8nRPJzUG>`xuuFYjKtTxoV90vbea!zRBce)P|rKTbq=)^|%_ z3fiXnUWsrHYLcY7mbUePDKlP4E zIk!q!8uLUIUE$r067WmiFf0)>!~wQRP#n#bz^Ah|WXXi7wMtAd;qhEA~t_D@w zQ2?h-(i&E%geXs*v)wsWBKd2Q`;*E&Uu<=QuGwI00@d7-z`CvIm+ymuj`blCFp99h z`WnFhGhv%h*0F<6zXzY&L2v|o5iT-azB4fe5%cVzWYze(KSxk8qJK3m>U%1|U=)Lm zZ!o|sT$*(I;#VFMaaj411&hL`NR_K}5&eNi@Mj>fV7UUz$$`&MOlBzi+18x|cA+#Q zUww`$XMFw3ds!@Dy7RgvITFm6BQbn?eSfZRAn6xrQ6j-mOhUh|v0VKgk>om!H1MrN ztH51<$V0;Fi?JfSF8*r!MQrctgiK1y1E~=IWa+~zWs_V&&zlSHs%&&1EM+{r-p$+c zePanwpP8#kx~aM)zBkcYHy zs1~`)Y=bCucH+Ei-bSJc&%RtVxYKxclR%y|NTwU)7$-z)0KC#}K0BZVN5Yf^2w|#< zth#ygGiDoW7no9gRG%a2`aOPNJSv4l7sGJ?b1`1ANP~0S<%74`pfozA%cflNYq@<) z(`wA*Asi}Av;;pK7>?4szg^~7P;#3Qi(Y1dk(={ch{|tP1cZe|3{wL_=$s`F&(|*0 z^*1R>g=2R5OOHidR_8w36Xdi`ta!4CJpiYh>a`r8nZ&yjb?FzxTD*=jB|)`FO}G@voxxA~9FacxGwvTi{@cyF-@{N;3Z>q*&wwNf#`8NW zb&Pi%%SFl}-`YHsZuTF5*bB%c&Up{xg&ao~g3A0Rfjq}77A^JxLTCw|<}+*9?O~v7 z@cwluImzjTJQ#Kn*gYtBmQ{qo&LuP0b0_-6nwmNgo^ECvv5x^};(J4<4}2!QB#eZ9 z!|mZ@d_0xt9r7u6=4m2KAni%y)#e)I25~v#k2e+f}zqQ_-V9wn1Hjc$a)!SG80r>nU zNsA9C)GeR;k@rFYiD7BRdVQ7mP*Ill*?L8Qnf|_oW`qTa2cCrSk+sN3YpzsYMM$Y_ z)QKbayx`ckw*U=*6jiL(H%(gq4JNf|$M=Ta658fR~c}@r^US3pp zo?iVhU-60e$&Brhy0M~!>*MJnj#}G<;NLq=*s)-$xq9~eHKyHvkNW&0y>9jPHgsF} zRE;7ZEnN>iD^KM_gAz-oI5{C-$M;@_?7y}{ZQ#S&+`J|8CvWho^4I*(zr>%{ClXXQo6PbmBrva#}E9M{u<8|1yh!oot=6ov(tIf z-1mZdKGZX}9smBw4WVS)0HA{X>d-scOJWC!9@szA-|c?1Grl9eC z`F9ijNSPw4&w3CY7)m5LBAEc2HGH|Z{i*fX@o0Rp8tp?cZ_eM;?KVd-l@Ng`w>7JC z@9$!Y)7cZej+8SA=mrR(##aWx^_M?Axi1fYeO8g@PGvlN43D^oX&?Gvd2|3Pt7;zC0VvOcbNwJWCfb0z0a!rw&7 zAL;s6qO`w-*ND(dJci46pr-5&Lcjh&C%YgFSv8B7Qy1MVt<)8*IovaLfK_i)!894B z)Dh-%E)`astNRH4V`fta8=MytB%dD}kIQpY_&tI5CM)zcW4MCY_RckgZ#MT zR7Z?Rm25qCPC;y4(YWgNwbvE`(PbUcWBm4a6i-mow+ctZ_UR&W{91``jfEyb=UD4T@5!6??)!z%j^mGk8Tq9VrcVOey$Q>2|AqBvNkeT z*KN?%@un2$ZhmN7BX>Lzo{>m3wHWJ9U{GzU?*KVo7yPg-B5D4&j zo9N|pbNjL{h+zUfik@6~ltCQzg6m6{nXQzs;#^08spB1)Jp;UMf6!eMH4C#0x>q{h zvvo1$KKSP>&8;G-6-IeruVOx&61F1_6naNORuN>!Y6dk}z81MnGi8oWC!YKe9icNR2lb zu>7r}Q7kLY^RdQl^>_&K|1_2>O_buYwneJKL33ardK{Q=|L^0Pbeepp#3}F>k!=M? zlWjr4zce^4Zx>WH$Sk0S<^U1~dbVUptME%S%LRHRnk|+C^L53dBB?k40`qap#<^Uf z-y{O6<1PG z_>L}WBuVovt|QwZpZPcKD9ud+O+>fal`xOI2!*dX?(mm6IC^ywCwj_c6&LygbPg$qPXTk0)uuzhJN6Vt^^F5Z3 z2B}%a9(7TX;L${AiW$jkd=Op11ms%izgGmya84@xhPYa_p*(l5gASZfe&A&mAbn=f zv|Estd^B{IB9HmUGVdB(k*VcFKx)5AN-pJ8g~BU*kM2r9C{_y@3`d>}GX zutt(Y+6fA{gq~!Kduy=ft)+(t)hjJ6E&O>`Ea0-QVixWV?O$CW-3fA3dMo<03f++t z+QoO=&m<8dQ&Uqz0l@ser~WF5$1RM_x1y}3nw;m9e*j<%tZT`c+S=N+-$Ty@f>{3m zu!`OWcqrNl&3B*`E?WOO`Co?JOzob3?J~Cuy;MQDKgBYiU0=UEPG4n!ImXQ5`bh%0 z|IeD1`9B+W%}B1^k}}onweFyo!7t#giRm2~+LizG1oRVH-2P*UWs_5jjQj-SNt~Oq zUnQzxiRR>X!uRd};|Av35{ZymoaC9&UM99;aO5drbuN z21MVHeV@Tr(w@6lZ%wCDpZniGuKvk{-XVG$=%5I{dw`CX#}9-3+b0Rvl#?e>6;RzH z&+S>9&5@_~z;*GUf;RO6$XN>H>Baj0CqG!3=4xO_x`rh@oyF?1`DkvQh)Z%U7ANb*yuVmKN56iW-`8C<8@jp>Y8P_9`RHy)_o zWFl*Yh+rF9K`}${uDYu|3}#EU3)dp|efv4gZAMb!FX322>{eynDXuO1S0)}h80n8d zxhE!>rR&b7l$nwP7v7e_Jy7&hwN4F7#WH)UuSV=W6Ly%F=%YwHwX6!w)?nx-naSyB z=O`Qie(m9t821+kcab=twrcJG8($yy@ekBNIq(uniuk812o_JNLk&BF-NRg>a*yTVH_%9<3D z52HwZEaoK%al$qvVx0t~BWUr8u2+MB0gP~ewP5tump*q$Cw1a|+s>ezUEh)PO@Fo7 zrytDlbJ*&HEyePZJPr8V7)%phc?%N_!!$c*bJ^+SM~&iD;}XNkirniZ8Zgs3g}aBb z-L}ibeL+*pce{$ojuKr7PXrWinkrL-#miF5xk>mvLrPGks@}(yt)Cd2sY~11gZL=& zyw6qoh?@G4^SsZtZ2JSQPfTctk6VuJqsTu1Z*KQid+CzC_l{mqEj{B=qjBT&;=@4T zKJRfvQE-$x8-Pe)hBG;Re%EXe40(k!er^}V>VsO_#~L>>H|O`nnOde*q1Iq%#ZC&r zyZogw35dWOOge;ZD~ZMWQ0bNv*@dc4VX~*)sA)l|@4G5^rBQ{{w7s>rpZMOZkf0Dm zTv0jnSBzTq#7BhvN4OT89Rw`_4S-BdS@UOP+r@fVj$lQ{?N4&4YyMw=##w9wn*ZYo zCcz~d2-SWu&&n5NF(W9b&GyEQbx6Nlx@rKXYo~00t7iOTbsWU{TaT3!wi8mJ~*Pn%!O_14lUgBw2Q zKwvQu<|8BDJSGUx-4Y1Wu)8f(mW5lrks=|hD5|5t;+r3zf&rE+CxKZs+@Tz(a7F>G zU&cBp>JI}G%IQ8T)V(&F6l(U|Lq$JfxH;O#1So6<*B*y78n~YsT}G-DNXk&PVK(iUvkS8>-$gk<~8r zp{!@qVSGOfm|cV_r1b#eyx&}HGU6L{#zR!wn`p%1V=j7*$#g2tNAc5SD0$~dBsHXH zcX;9qBz16Z2jeG~AH8a6l00P&PMD#p%ATOwkAiPe@P*>?7}R1o5aKuHJs3Mw%u2VX z{pAIC)jvBa5W@!jS%L*juiTBm6bA1A7o(87k<6nz8+WwRcy+laodsgU}&dA=%mL3 z{=y3NEhv$5EesBT93<9b`NsBBjxkEt0!uLKcB+W=I;3r(YXT|O5*HpP9esaAAGs&u zn9*UTQ_#RC6I)0aG6upt&*q|}q>&)$C#PXD;@Wp-2NRq!C@Z^zH7ii0L|v(C$iCU`gZvxko81hi*fK+H zO3jd(444tV3{P=MoM0G0$dX1EVzm4yi{{X_+mMI?yVRVXq%J>WZwYne4&*!o9heaGQp@Cv><~AWk~tb9j5;ez>oud2wFp14-Fe;g;uCzq+8np z*FuDNFDecH0k}O092HFVtGuf|f4z2Il1K^6dd<0=+utbhHkRL5>CUY^i=i0u4hjQgDOJtX*RXtNJdN(~u@vn1W2=BX?yy$&Gt^%wbWU zEWBwFi&M*#w4D|Oe~I8}EFG&hkh<8zl!dX)$G>5iGo}C$6FfxmrkSf5+3M7Qo}%Bs z{q$|1^awc%Wm@L1nyeQZ#oxgGQys$w4zeQrQ1drJ2mGH@(-=#jG zU)f`m%lPN2h9YZZBeVJMh^vSyB)C#L=6?oSeU%T#j;!jayEBzCkmGffajFxu_mt_| z=KJ{sp`dq~O=6Z!5HVF@#PoNmr0{;}95rP&mxYb-ytnCDK)sU9p>a2A=d;4mXd$hh zQ}z8jeIuB>O&k6Yu*?)|g}#}uayt^S%!K-(1m$S<>RWt@x5&qZ3-Zu$LE1+?%&!nl z=U+XxG+{7Go{W9fRBh zP2Xr$@Kl^-zG7w|B6EQC+~)Q9giPs)vw`O3evG42;k0=+zS+4t4ZiR*(WYBQz3ZT) zk<#hg8oD7?pu3Z=xzfA;KX4{2UvGZL^)25uhybxrwqC>{hn2lo=mLJN`(r*AZE$0zk%5@xGyA1eu%lGN zS9X$OnOcq^McGIuxlBQQ;*k2g~ z;*FxmbxBl;7CYqt7W3KyXSgweFFPMJ#y3#{boWMpA{6VmBh#%51<(=Qo`0d-yIB7S_)u5jfSMtfgOcern}Jm6~n9{?l#*Kz^@-cQt&W@N^kfW_dR zZ_}M(E|5jJLup|(BXAsDY+MmDV3v{%UxwPNrtX<(R`qLp&M#5KFn#YDz4Q>!lh^hq zO-?G&BXn?&5S)52dw$YD3=|C+{dacfC5#hGctGT9zu42oT%h00PX6lyYedfoDFldy#&R`y~T7ul1KNDI?K zDLB1CU%jPw>%1iJlXVqiX#2R8^48b^t+t^Nd&>oyD=|0rEWqZ+lK!MMa^SZcIifG% zR5-9kB16`$jn^hC8ky=kMklt%x5YWA%=cN%roBXO*hw()0FAPES9b3s^Pwb2SA&p!cRnHf(ky`3Qy0quE+KNRvO2gZbol z>g)iG9NE-Cr9u>|X~=Fz{~R$zo+Xk%X>r>#<;RlC<*`$ZlrJ~Asf7S-O@5_nXL@k* z$50`JQ%7Z$Zt7wtApF`ok-IC5EnK33oZ93>mc6V_(BmL*r%ul?y!!@>v4B91rs~M! zZ^2-WNT&vo?Ed97^{dbbNP5$9CK9&?oGnrq>hBfrPd^a(#PcrgK;Lx4O$F|9>E7X%jQ>;bBkf5?H1;p0eY z^TzDC?c`>RhQO^8tnokI#A-l!OOD3+y6(nZ&v8wKU*3KO3^c>DoNbF=na6Q=rL7}C z;;w3J@X^*%#rv`lF@*odh(ESL(eA4NjLmn>ud8hT{*Zcv`7k{dT9Vgr<31a_T^e5P zC0#B>lm$HMIW->L4($Ev^NbS}6@fFA_FIPF{dVjdw=6T^=f-pVMtdxB z%WzGY+=4jY!uYyCHxpccYfXAgHyLBOM~QRw8LbG`FX7Axefy2xCc<0 zno44ZWnO04z_naO;L3bg`Aah#?T3u{(E~yf{Cw9TsY0eTw zcm@Y5Wu0uaG;|QHx)*0>i86WCr>D{E+OEQ_;Xi{>!XlrbC>3{bj)XtT8ZQ5!*t`~= zgrVIxM=jZD9;VW$eMt4og5);^18a_bmjnFXI;~c@u(I}qVlV$_^F**@0owd<{zNr=FC+4h$SvrI|XGqucloEUzWK}gYk|hp8xh0PWskK=97#t(K8K{e#o9Ghukj4a- zORF*`Wp-gQH}TNv#58^;p_4wvGJEHmqDlCjz^lXUZii%Ikq4k3kYxH*x++Ae(!ook zI=ZzvYdeS~``6SdBx4@*Cud>x@|QWqU+aN*f-l)R2EdC}CLn{mzeS46=2wle@bCK{Dnvm%KnPm@$tW?7~c=>`F+svNZ?|c8Ff;lV8TJwq&=9>0?=jmf1w}8Sa1}Em zvTt&3;rWJlU>K<5-*i`P2ui}zzQorCX1O8@iE%GZZa-X_mr5G(s)R&I5sm605S9ou zi%fqE&5=mi%nhnE0cvYmP3rgDjdPHgFk~5iq0Kf?9 zx}hnw;cPA1BeF-r;6ekK*Aq;_Oa1H))xbxQ;)J_MmF&L2N3QQ0-@!o=DlVy>f%kYa z-ls#;X6F=;o+?(+{ZRj)&TOYY(h3lk5+u8dO_H#nenC~Tx5tUItxCU+wqPzJ(VNh{ z+32)U04hLXbTW~JKTj-YrE!nDWH`k?)*%mcGKdIe&)&XN*zPZQ6fug$W_@dtEB@S) zkG$N?FX>Urn8_Y8 zYlb0r;VzK;&^dj@|en+ppG%Ek>H`-^ca%i5p}QE^YISZC(&@)~R#m$;?k+w~?q@gmi3u;0VUa6DtAKoMTLH zeN~GdW2-&7-KLB!*ZmTG27}_ur0;=i^4+XRQvGBg(mES@3;}-IDbFU2^7e#aU@1~1 zZTbR*mpDVOlIS8>cvBD?i+mjAaC}%Z@_fso))GCY83i|6l+tMyXk0qvg+h+k9O2q{L zkhDw2$kr2m!;)P)N|&uU=no{H{Zw_VJC7M;x90>QDmGH!(%T`w`SM%zB7;j80AVOz zWK@t!O1CuD1XTv*<6EiD-w`?f29wS!dbST~7lE9CUup7K0w0rwpKMX4Q>4WDtJ_%s zJWd5!z8sm}(+t$JQ4&()ap6^B{u&BLk$Hs_!i7u~9>XDjql4|MN!bbBk;v`tsM6tO zq(Ty~AjJB#)M#@oaRXB}K+GTslQvp7?{pu9bTGaM#Z6TShCrOHNAn+PyLnajA}&~v zWo`9I*r8RQG~&OqHWoHqD_koC(8Z+FCC;k$9`Y{$&=T2a@X%tREx)N5q&6;lGAB5L zAfHH%H5slK;R%17KD>zy5)gnnrUS3iIV9p!Q00qJ32rh8z&lxXfl0^&mC`&Vp%rpF zLmJ45m_d%KHOAJ>mF$HF1N2L2?uG)Glb3vC*kxGLvXI%IA$WUP4qvBzA*8qrAcnQQ zh5Ko0J}<$-eKGevk2qr7@vqJa8=-HbHrY8D;1?>1^q1^>u${*2|WE!3-T zzOCZp$WD-`8v+l6xWEK#=WG)R)w_8Xg7p22Ed5< zsbp3lr`x6da;uM^P!0rNQh>t0Qxd zmZrEnwD0?p-#E*B{$AvRc>O;B1o@KUfC-LzGzh&jp>$5$;Xuh3Rt40$>sMkr-@Y># zCj(Jmm*59!S=wGlE8^bK^V051h(NaJO5?0kby!r`!$|$cx^#ec+5>!epS0oEG4|dK zA)P|LG`|TY`SNwFphDr1Iu`K?6Xg}0Lyt)W_7mBDbbS_$Ol8Qrw_Bp0D$clp!p(pg z;O}bBK7!Z;ESY7DiOwHE&XQ+#c#drEq< zWStGL%j~pbBppn)e`3Ksip7QZ1+%zr<}3@19w9`>2urE8HJ74o0^Sq`Fh13lCSMFA z$1k|Y(W0fJzRfkvXJhg^L{Wtv37+ZIW4-2M=(xoFS->wVAnW}Sw zg+E&t)0y6Q^&dfT`PFHxQTETy&v0HuI)IOXYhdwd$2v^GypE5@m4${hcBD#ME7L_? z-P;Z0I~awl%*n&jZEbe~99JW_SA5V4HhrCnN<6vC%G-{azR4B}!JgrZxT9d)ML*2b zBTV4%$f9xSQM@o;FIib8~U>cbfCO&sCGX6BMm5vbwzn~hNAgx6W0G+886c%~R) zq6hs|u@8<=_!^$+>7F7G8JZt9Za^!F0M@GC0B2M5tL;|r<34()mLE)E!Im5;{zD!<0!-!!Gs} z!3K!4$?Q04Gq(RjYB1MlC_uRqPQF9@oiosWZ`*FK_pld?)EF9XpL#d$_nKpmHa+9f zAXu6MG@?KMd#P5A2%711g#_!<8JN@qN_{0l3scz#u{cfzTjAL$m__zi2zRI!Nut6T zDhvYKh7I|PHJBYmZelMCR%;RL%&qD#ZJnb9@hnz|MV{jU2>wAeWu?+kjdmQ~9Tt+0!zd=mDE2p@R9X zrXV~W6>cEs-=&~2Bf{qr(Yk5qMj*~_%GZ_D+l?<1RP z{ZcxKA=iv)5!U?n%=Lpn)BF0_QXkbzIVuNkX_d5cvhss>VbU|?2j{0`Lc8|iZ0(<6 zT3=~|Rz+>Xak0^Jyk@VK;X3F*6QhzvmZY{d!-3p}@a&q5y&7PAHr-IvF6TOX=lr%I zNJc>G6+{%Gn2n=*x7ub>i&a@j(y_yP)rq)wyAri9OaWydkBnlf$?)CuI~TRi=V3sb4o0f;FxhKQ zVkyFauc)#+CI+QX!%N;+<(h6pT=0Wy*sPDJ*Z>FGqxdvImGK5Da>y_m-;`0$fxVY>NFJah}`#@Zp>lp7bA>w#zqm-DUxqk>rV98i=&^28+>;lEByO z(d%k4Qo!}yzxnES!3|X zcmm3@iRIY>X7mrH+9 zL*R8_az;foqVoVB4PT3`R%Y3%v>RaIc++>YwtxO}LsN?uQSm1=2{8kMqn7v4b0e*f-iSR6#^x=6Hu zr3U;sthntrt_SSmBN8DkA5r@gOB^YuLUqud5R2m*xMq#qGPGTn+ItqN zc02X`2epGPKWqS$&;yPS-xxs4DKu#Hv#BW6PvG;D4}_)^_DyacB_n)1WR6s!6*Tnz z+cie=oV&Mym~qAqr9KS=@(@UeNe8S6<7-Rm8s+p_t9#UJHO$(ZlWruiuo3Or)2wu2m9aKkk1T z8REB(XNh}=9+4XE%!qL%ZmML5lJUihxwZiKT+00TF45VFRE$nv!wwo-gbQwqiX@Y< zVdk>#7iNwr;NQernZaHdbl>S6XMosRY_CffzkC~ z?+E|8j)LEXWx`Em?AY0l#Xk38a|lbmp-+@p%sa1tlWsFuVBBj3968HD2>RMOGT`$) zzmw0MLQ^>rLD z(s^OmTUN6+V|fT({St}65ql2WO>A3|ne1B>Wi+4UX)XBNxmNHSCO!ts#TXK=7y@Gg zlJl6B?#C9VAaTy%A~^TXt8vhGis(0q71mh~IK$f&#jp9^qcxMZ2!q3wTOy2j*zPex zzD!Q_sKEMkegBO9xDTq#eRS_x6CX2L3o1a#3>(g6&tPOnx!eAuJj$r`N9yr~j*3Hj zR(F)MF$V2#ev|Jy-6S$EIj5R^bL<5MYaFD+0$__t`Ep z8{K?)8v8L?qvQ*?Na;5exAXOK_Hh_u_41ojs^bDx3=dv;5Y;#9=3*HV~Mlfdj}mN&G;{Bce;#uq!}On-K zr!GyO&ELDi2a`vSiU9b@fLoaYT>|MHJ(<5?gx;Y9MtfmS-@q6Md5vQODDvUWYR}$4 z5V{=AydnFm>xp1zF#uSDbhIZVJdeSte7fC}K}z=+&pxSoG^u=+1d)2)!)OY$!x9#p zs*8qv;`IlbfP&l&h{FPx%H{BNRBh2HHHsZDJfr!6;-YWOEVBGX0nIxqiTI}UiwbrZ zp~=XIRW&m}0o?MW=OFEWv2RQNt9n};R@P6#pG6%(p)oT+3jjBdVICZgtSU2j6tC)# zXV8XOtU@N3{S7w(^-K@k7X~j|$UI;ScVtzb?t6uefo7xcwZ7f^Z5ei^7Y!{%gzz3& z*wroXpvNKX$@nCp5?fI*KfW)sqgrnu#J`dAK?}ln8Bg>m>VrG@27T8Hq)IABd zuVFafV36mtIVwGBX*u4r3L9Z#ZbIl^!)FkbSw|>U{F-da=1cRXoluINmK(8*_)33f z4MNLeZ}V%BfS&WnMwd5pxjBEd&Le`^Y_&YR_X0$d3SIH@nHWX=sc2NIeKwQ3ZL)BE zU5LvX@(!hYC(ci&+^hczuZKw6-9*Ai@w~7_k+d%BJVAq;&|S8?PYNYuEE{i-QC?GxH}{` zEbi{GI01qaAh^4`JBv$jCww1%r|S71PSu&}S5xzETL0LR zWTLGB;EDu04!8*qH=8R?S?t`lhmPkENg1-H{{VXA)i!W0_V2p$jyyRQ(&a1%KI6Ai zfd~lvK$eMdE|xoyP;%T)q~H$H^ApCrWLK0X(F?DQhU$xV-4&}*M-WF zR#?3h6%a=)Y1s7VhVE zZHb271&g@uvrHtG2m>gQ?XMlqqZ`Q$Fp*FASU~|_19K9+hCI~h;#6y2J4OlMjqcRT zqWakr@^XTpa+^)nbPqXjY&qy@7f8Y?BgKAUq_`c7qmafDzNK!B*JFaiF8Y>Zo`(l3 ze2D!w%`3BDG9%CRP`Z&3FY!;foLvK~B=-gSTz>sMDev0FLFEYM+j!=Uk@3hJiL=Mz zZdn~U;QDiZv^&WF+d?9V=1kO` zCajr%=_!k$E2dVHu;ZHY08zZS<$tWs)N-A}-Kt(>^evPQX4#U!5?y;2@c$AxETs@r zd*hCkx>rMOy}iR*z<+*qQ-_ulK;9km5t~W1ACRuY1D&LE8FM*Ep>JJUWXHv$izT_M z{XW4}j^)rWUT>*(^kIXGwPapsfMqRmkNIQTzBwqou3zLevg;vikVLpr^zlVqeU9a! z@9b0RJgL;D#h~)Go0vt<1KRK@iO&@~xXfhZW z!9L=o4m~!TyS$bC3y$G}CD>5P)0RxbCu{VvjQ{qRt8RmF#=1F#{y?e@;#3m~QnJy~J-A=#+8P~m7#==hZgsA{xc59_4!XgeTQ zOG>=2Jp1ZvijBkZK|z1-kubSdTELrL_4ky0KtB>b>NCcKFWRn$&8UY}^g}+xO=~JI z^7wWb#8wpLRbuinxv*hS34{9RzJAW(JZGE`xy@~i%^i%0;e)LVd3zTWF=vzypJ=6Y#nEfatbKkv=R zwNTgZWC+9$+M(LP|I$l?S_V!_e`aSkGY9uWa8E!Xl7pYGB z3FanYJpW0VYX0p+FmOo~kiWVJb@3nI zI7wlZ>Mq{kR|EWM=wzmHW|OHxJ8egHeQ4-oSNhxYCG@GB2FIEYVXDKg*yT%e|k?B&>4TH zk=C@HRHPZ?Z2mR-eJl0s(H-Yqkpa(Jx&b(WVOLEk0I-{Ge|3 zvbFe;lVQ&=B2-l)YH_4Bf%K`u>#(OGLLyZ#;Jl4P{Unqx3ukTp=94~3PKVH2xC(PS z;Hr}vn836EEV_@KP{RfDO>v}pxax>RfdQ1R z7kvzeIjD9j$n)R1t03ZMZ63nCKvB0p&MGm+Q2e9R?02+o*tLuE&nrM|Ei(+zD&h(#xn|C220$%Km zl8D)rh@avoCXFXIZ7?&gOgNeUwDt|A#=~q$BwyPIyUJHgO6In=Ddd8hg|D1>Q@14l zYx(1uKaPALvn?L^4cLko7Ih!G{KeIlG6KOvH=?VRoXU|zN+k9SvVkx*UpgimG2T3h zY#_iNe@f?TlTJu`*$8G_$%~>~^iw_S_zzGJlU0dHMkjQX`?e-5mO~n%txtIMe!M&K zaA~l~pL{opv)u1BausY7&YWZxlON1Z73ML1PEE$59Xh5S@+SH}VXG&S&R_sP3y?Qd z7X)v;{Nf%?*D99@@Dn_agL(c6Z7cC7)86yzVzZV9bW!!M<_^_r|3uZt1=GY*ImSCh1INfrnyv>H$&!~FrjXZ-&7!14E)iH;UU}e1eYU)2lfWY5#tKR6x z-7wq=SzyptprQ25N@(!$%lYUxLIfS--V_+wEu$P1ESa`x2u&U}Nb(wz!mqi`nR~Ix z!p&`j3QUXY^l2x$)@ePAHTz6z_-nat^gCwhVY_XD{3O56Ua>00WFchSMftU;)YH&H zxncu|V!hd=zE3imk_pDQr1ZBwu&=qYDH>UR68JFltPl(Rx$ILzUrt2)bfwm~=2eaY&0Ucioq~He``n8m8(aLm zm10o`9y$l;723nda5%tPzc)ubE4gh_@+NJf5w)8rLpM=yyQVVkC~&8qe3lwFWY_M| zv<-^a2IXFPsZGy~Zov%2@!EzXY7vxX+sVJA)|YD?Yo(1q5|B?|mFhbx*jf9}h&si9 z9u0x0IcKkA&jSu0BxRt8vkgVwN*o z1cMruiKn-$D84M8^1It46d&qQ1*6V8I565DZB{5SqDnZxT{zg$*+DZn&TdZ8Hzr~b zV2cIw5urJjpb&83%fv0{dF~fm582YSIPri8%1g;KLN{qB9F<|XP&5ra`l=!JMNu#e zUgOe{smepvpV~T*w%X{>UyR~-1&8TYcdbGNGVC1zxcMy$xttmS8PGh-rZFFWQAlBe z<3{9LW=g9e)=p%?!_sYb6<5V_7xbeU43uneb2D=$?|f;j8t>Mjun-408jwRx&bV*N z7oY$tb+P8jaVaY%*&e3oB)aUx@!G;rC;fyNa^vF_y+6HL*#fW;&)n9w?F=hr^*|lC zyjWxG%`27`rJEk9_n07rbswUxX7_mbs5rs3v8&T@9On{UPh6KQE5`dAol+s3fIu|_ z4Tk4|_>hch55Pn3nW9yq7#=^b2pbyO2J5ZWhf>d2MBj48lzBxu!(ct~+CzW6dFhi4 z@OnRciD^`SttRQ$osb+8E2>;x<`%L|eBjS|bela}m$sJ!3n zbuI7uE+AoI>0i5UE>DA{ZtYb|u%-G11GCXN$mruM-@pc3eyEsQD{_`>B24i1S2t4w zZcMB*rco_!( z{OdhpkByCB@4%nKSzF_!fh-7zk}F>vX+|(;I0{MRw+WFM_^sbFz2#zD78Y2j*97l9 zk|Ms&HYS$IGi-X3up=NAN#1q+V^3w?4Gs*BN|it2+Sh?KlMITn7l)EfetP;WFzEoV zN`{`^ePw4}6L+xu3RJoZm7>H$K`U=>2bo^mfdvrgo`mhU7_pF>I{k8KZKHn+I6+G8K*gtIh$$!vWqiPFZ+|bKN1jx+n~nc>6^~mm zZ7G5v8dZI3RoZ^Iuk;@GdHSDUAX|ZAm#XumAp-3=m47$Uc|`CTXKo$aa^a|?iS*ZI z#=lW`ukXTO5;+}HgW1S_xFjvxM@3P1?uu>Sjh@n~pc*wBb|JXs&enN$`wzLff_27WR36^*pVX-o>+`DIK*b_@5c zh+@B|WD3L$lV$*(m<^*H`V=C;Lsu$WfcAR7KCvkZ_66+zF)m~b;UPZr0Wcy;geo&z zrowv$gzBTtmC?L^md)4L9%D`MFwT9dCG~q<5{D(xaFsC*x6$Qm-My}e(#(&l~z-fvm3xr zMelfrkOS5i!vlo)u!z-rF(^B6YRm`8Oa!f%4#q17Ea^>jdRd8P6*!Z`i|17(Ew=^K zPXz;$OTc;d-MH&>YG<{{g0`vQ5luWF(7FrlFI*h-Rca^;_VD<33KD0z3F+`1I!qqQ z_2_`+d{j59U(j+ONQ2eQe&4$(4n+f15Y_YwChgDfOjvdF;0$*yRy=yHoukYf<2HLVv7MO2XeToH{6Y_d=cC2o6@` z?n!rf4bxBqx+W7AtDzOmS_n>&ak#)@3b#I|3}gx0g-b-8U)fwF^+S?@>YhIt>i+}O zj(nuNOb7dhDZN6^NKIEOusP1X?(_|gfba`>W{3)u5YPUgjcmA`T*1tOG^*!zx$;Dw zdvc~nZ3evE2E8dByh01q(aa0Vs8#WQ+xhMA!H$r$m4qIn>vn&SI`vNCFyQtbw39=U z5ERKWP2>r?wTY~Xb5?f-Vf_5@eF4sO$@clL&lT#tDP1$7wv9p7@}e*VmV+b;^}1ZF zn2m?WfW*jD;yV_odAhotA@c0NAm|={v$5h$!$HxWZecXE^7VkK z5EHRn77+w8b)xl0!`CB3f|yvhGLoJ^N0uVXE+MCRw30tLK($^Iyg88L33Oa4?-sbc z=^Ntt-pSd4A=Yz=v55n{N`?oH{qKzaPgyN9U!N?U)W(#M9P}E1ffU;A+DfJ z+>XF}`PsJ8LO;YBiRiCx{5Y(i^~J!uDF8YjmW-^wMpcsPwDu-zOH)qp@v}XH4k;S3 ztJ!SQjdTfMhOs=tGO~!3O@mTOl&hqur<+$h>e)C@l>{Rywr%8*pS3QB;Be`S-1U&k zG%i*b{B>JT_s}&B=RwK#2Zqu&xq|a9nB+o7$`C=;vKktH9@9aWGzE5JV#fmcrq7Q9 zqvIgQH1VixHf>LIh$|*lgH|};-sj{;5CeR)?KESx!WVOpjV%yG1r9`XZfqRT)h!A7 zWX7eMLghJ6A331ylX&WR;$!c_NQ$Alu31KFL1YxZGYWt}k+GrG8h#DoEvL z`A0IE86PpuWC*NSoop31X>TqLuU1e%oD11@hrF9|bY?(!AjwBywzB7j&Bn_#0w(qx z?E>sQwu!)F0#UyP=!&>O4c?_CuE8FDAaJcDf$5g3uJoZ_N}cY(<0_Y?tP3$NxVyLR zk3K!bLFAb)9;=U*+1u+Bq^x2d``O3$=)I%&oK#Jz>eid7?sp}KERN{Sd$CJif(dk# z;`{u;0D>*4?RHHULt(%=CP=wL)=L?}Qz@W9VCd_1f^5J@8cy`)XWkBNLaid+ct2-- zp~T1TDZ{ORx8>c+CX(PgQhm#ZSp|PH!sHUfISkT80bvWP+SDp9ci8SM2+7@jtJAwP zt1qda5(blnoE-Pv<$%cOh@ZOu1KioJF7#`@u&ywzI-UeC+~20p8Z9ELpbUCW}AsH}+4gBC!FSw|zR)aA#Fx z8_@5(TW-Hc*-lc$FC_=hK7>UanyUL0AZOyWkce}#6x=P_6!&@UAE7Z#U5^h_9Z(8f zI>=Qw$B5dqz3OQOB@b5Hvl>XGs#thg!xOq9C|=v1fS(6Ud!xBt)eJbO%7cQ3kwRS5 zI1C0kz4B`vfS)+BdJmoAC+-za=uP;r66AxRlu>d4Cvz*+jf+6Q z9cV3QAJg>g*T9sBo0bz1{m1p1zKL2^4^+3UXgEM9+B?M<10llc5Z?mB2AbNvMZ1sXEu%G5NvA-i>&*mFgSb1g z?IQdFyd*<4lm+Sl1VU_|C{?+pSW7186$L~(&nj)-*eN@ppS^XA*3CMuiaZ;W)|Z=R z12gkt>m$z1hYF*4Ny5L>>Pyb74n8aoOZGDwXbG83P?f^@s6j7aG_{fsa(G~Di=@1v ze+SJc0p9Ptq%nJGV=;cK8o|M{8Mfz8?scZJM(_cEJRR($VvS6D#O~q>ve7p9hpHH3 z*`ulw@-;C@Ass<2~l{))?-@E5xPqw z@fDNGRSm5}Ct+`cb!sLd(hcR8dY3*vRiW2vcV+mob6GtgS~fUNx{QXDD3lhcj}s3F z2gbX#okG6$62?0In|PzK)vuHT7nG67a|ucaLb|KYAQzn7pfB}6*B1?|W^IZAR@;S4 z<8vIe6C%!{6r8-=oQE^2@L6x?JtdNzSngGLWZ%AHMR7+)ZR7i?jOh7QP1oWra$ZFb zl`l!|adj|<7l~LY8SD0uX1mG*s&tI|#cL-*Ctpbb`fy87w7y1$m6T0vVZ=;3{GJE( z=Sdjrxlitb%xm-5J3{yaNYi3iV?5pim@;J>$n8xJlE5XWb}WnNMi-*C?qvxL3IWt1 zUuBB!jcj5W8*^N4NohrUwA3)mUGzUWD2X{d`eHhW+AX2se_9fNt7`F#-nmj#1e+Dg zZ?9%r$4231BDX%J*h5mQZJ|@kzU3sXG!)JCEaCY5BaJYi*&6fB6?QU>Wz(HM-K5M>{X7g@C4;5JfDihE)Y8PMYaQ1~$GpPOszISD z8WvHDJ0teFA9EDR9I(lq_rHs@pD%5@PhA23I!Pu&I1hEqAz8}56>jvde@2ydT(FQZ z)wf4{fr2(+2QSDCpZUlJ8c70PK??>IEem-5pxM0Ap&9Z)N5M7S_|2};S(p>d9~cj= zQXx#ZLoK1FVf_?ya;$km2{=?0I`O6Q!~gVlV;U_P`cDF@sq3F_AU)21-FRtC6IKu3 zpg?HozJM+MN(T&Z0Y+2+x6%?A*4~J(rPEC1%Yt%?QCpw5vl7hLpS7n5gZ?NNI2cLs6C3I-8w=No0X@yX->dHF#7Y{;H_wRn z{%z(-uhkmK%iiHO0uOfdSNftWaDC2Gizw8cY&^!dL8uub(dR-BVTI&x zdiR-a+S*o?&+rkckLoUp2%d~bXy8TW{k*wn1K!lbsPurH`dy*<;66my*sxcj1q5IE zOm3a+a+Mw85HZ^bMC!cR$SeWSFV!Yp(CBj!N0|nwUGl9DpNE;J>c1{)@8wWpmu(r#l{Hwq>OSf~`yK!nVAmEkAZ%?aQ@+aTw#*6h{8_#Qg zP@aX@9T$Arok*VV;ZAa@eaYoG;A6o?JvR?%Leo?_|R`Px5{S5mD}7M5Z6{iTdpLaHsnX&pYA9~8C-PXcpf z1hosVmhEVbF!TyhMGYl6s&sh?7!N@wbQ%WZ6E1iRhHr<}J zUm>A@6u*CdtM1Pue3V&ZG@rd;LB1-FL8#@(mXF~DzH=LRUh%rTNmW0`Fs3w1L- z@o%sup%LeQ1!UqM*njfMu|toNktm)f>7-VhQ|ZkL!sP_>hlG7~YP^MyPvKO4+Re)o_;Rqq#zrl*S7 zgrelj64Q8?A<5RVY$hbSbmQ7u4mcX|kKjJac=0TQQUS?zUo1Vv2PWPuPf-BDyv_v#NQ@$8$!G$XYI&!lH!! ztX8?BLt+G!6DKIZ|Gev@!9#Sxg zVgv3hblJMQsMO$*k2%fG1fqO~8-mIyU}sBm@WP zhLiP!_|PO`FJ%S1?E~hjc)T#Ag+U(z1-cZa1D}B@!*)%V!-qk0`sFC((@y&xK+?)c zqJDa#lVJMUY5U_y3VgjVl>gUq2+9|W)_&@bhsT{#&%Q!Q~an_)`DCso2 zl?*LRF}h$37Z(%WXcJ&NNWk;VBbxn(u@p3) zXDe6)Z(28VX_VEerSr47VszJW^5MKdN zI_?M4=tpXCnn{G+LNaH{2)IxBXmD+cLQ#Li%YWEb_Zd%%MlO)%Oc>O;B#UI(_=$hK zTQYoZ9`B=c6sT^!20;55GN&QB$rmnTXUE^L7VfOLH8k_|ST)$Yons=GL-zWu7t?1~ zg}AB=FGG4U2(r&x-)X&xhPt;!lQ^7fZi#UySI~qALce>vO~fo_sJXSwlpP1wbCBzo z*Qpw9#E*kgauISbCI2w2l)fOP)eGw9bXM4ek$V~TuRToXmF@wuabI3N} zAhja_wK&$s0~f2@+kM_p)_)3Lz?K2K(2inYF}L@iH2V>buxiqu&vr{y>qsKW*o|!; za1koz&aJv?b+=ZJ6bapDI?QCQJ9=!Q(Md!%?G<&xgR@2yA6qEb%pjeEIKG{gW2o#x z@=YiARH*A8Tb)+Dv*Nu9VI+MN{Sh>RteEzBXd7Xw^SnY0YOeB>c`1b*6K1lBnf@QM zc}=J`0L4Wl7)j`x0TidK83hmFz_z%?4z0lXWsC!1)vERy>`3@$$b5hRPCHP<7&$g<*u%8Tz6!hRYmz;f)v)0d3Cn)CnsX+knnF?BVQl4)g$papkqn8q%U2 z|LYaGr&jU|5Unj9_RQqF{~q&M==*|wO$OB$EE9u;u}nfWpHF<0g>esiD_gDS1B4$3 z>Uc!)UMu4Hq29a9jz*K4cFTr{mN{oO3`CGTR|IyK35iAmQRx+K&lCUXJ~$n*sjFJ{ z@1$#`854+Pefzokuc)6G&r@0E>9sZkgd)ac06hFe(SeyUfIc0 zgZj@6RURKY#P>UdoS2|&#^&^X#Ie)_O^q^Qqb&Cknh$kgAYto1hzN0}1x?dpcG@Ey zwujBPt+TBoN1FOr*@IIfBrIV7B(zVyALT3gw{L(99xHX_-zw_o!!4BZaJ#|lmpX1u$P)Fs^<24pG(&WcP8Zoy!fYn2Z=dE1S_ z6O=2>g!Mo#!BdQ0C*y4)DPsORSQ5bUoCschC+l%C|Po};E2pS~O%&$0Q@y_?UCR}1rr9XNPO zdf-x-7X69f>HhSkJHdkFzQZ@uGyv5R+5!m0$V(Q-51LLD-R~WaR=^e0;8bptVuKdk7o};`Ui*>|f=( z9ASCuiUj5F-TYGlH(2uH%NxsWtpgj)B9+^W)d%!)6yJ9bVo42>e|SEBGZOVAZ=mIM zLR>heMw5r@#GC$iTdKgry?6Pb-|#7wv@oS%jku*afVOGzE-S)0IO{;1Zjf9y`0d?3 zS_>V-VfSj9rxn0fTTmvHPeB*yxv_%P?JP2KRk29qNmME1VWsXPG`cOS@2aijbr*>XZQ1K-#N4NMtIvNA<~M5zBKfxtL;}{YQZ2K` z#G$*b?`zSlNXr4>FvBF7e3!3(uH82`NRYa-%`YUq!4mk`<;!l78u_mC1r!j% zy%rpVs{zVapONx;7P>2_6YRvgm=@tSub~I z$@6J31R@tOak2oidrtEy)qeoqtjqUFgkOYb_&-(}H{LEr`9 zA|GHx1L=wjL9@TS45RC=MCvX7NSkrB`XL(s`GqrzIBMx{y|A^~P}xJM(Q^ASb;R?2 zj?0@SMDQ)BT%hTr{Fa?{^sVt>s7vRZl=&5MmRJNTG4w`%G595vil4t8q9Ln!Z+=OW zG1-+6pZmNR(BjVyblt<25Sl=Hnj2P2ye3MX;*x zk9G0y&JEH5bxKn?|NSzpIGpG7ltnkXO^v-4AUW~!0sZF@e0Ih3~@ z3MKzP0BXlDSFj*KluFEh0OLO`_EeFUlA<6(19jG0& zAFjl$HI=^6US=daYV_W8zuV9r5ztG)2QUz2sIKj?Eqc}I&!xhYXJS{3# zMGnVtt8J%Q<5KAX;;Diz^dk?`4-UOf?-vle##eCt3WW@OjM4hZmQ#@Froj>t16yA| zL_s=BF-LN zgE!w8#n?}_5!h!M&BFnqpNkVA6s-XkE+N^csd`;>j#6JsFQ@ecnmnNI8R|Ec6<*4X zIcfSk2~4xF_S1eMm57BO;Keax(v{+@`ckZT5wv1UjRLOomD$`Ayu4ZRxHKJVA5w{z zuNHb%-fG=HUQja?lVTRRf$l@wW9K2?f07})QXu|D*%qbE5+j2$pCM=(Wwj&snO`tG z&jgnQ4?|dIZnvGUV8X(2rSu}h8PDA01H=e~xbF+ohHx^K$4L^Da+>*pQ2gze7u^Gk zqi3#-T6(|a8?g_lN)F_xy_SL61J)Ve%22+*Ukea5-7hrK9a)h(F@P9HdJN}!uU5sC z%&0KFlL`CtxlcKz65Fy)hVynxz91X+SnN;@#)R>s$Ijj)sS(r95B=keTnWWrj`XxF z+((R|S(tS?Cj-vb?$TPReL4L8B#T)4w{uU{FlN_Zk&u7dnp;A#^>R_*DZacXT+Q35 z6V=$lU4n`SY&+fxH;HBhmySe7uT0s4kFc!$4WJ>K0d=J&HRp}f2q6Q9NIKrF&7_X0 zi_*-TQR!-Y=s*=-zIQ;*b9;QmeW1QUr{oV(>qE(n=NRg3dK8#OEEf z>Iiu|iOnAkVH`rGTXf+l)Sk(HL^op>RT)M8patOgYKHW$S+MjYB`lQl#3&h1DPJ${ z^F~mGh0=j3e9mD-=`dfkBBrJ%y#*x@syhNk{U<#gaGEZL1fbl=(<_nC!9n{2772Hw zFlrZ4GE%+m&QJtWr~#j{M~TAGbIF{uIxinFN3n%oD|p^XS2_dc8(5kV{7|iD0L~E=Au~tVEat3AaXOU8ocPpeSZZL4%Xm!M6I5W*=LU6 z4Abf|T{TdYF}5SeXCEP9Tf7HMzEDeF($$gfY3h7WKMwo-&?lR)NaO%72|Hf;ieF=L z4Tv4_%0CfjMm|ag_2g%4^^FPFBsan5`<2pJ4Bf@BJq?{NPk#9doXNfYPH9k2+}i1C z{v|)Y8w8uNh*Taz->@(-`|01&4bc`Ogiv+jKo9cb|b^r;yj=J+zL?>`DM%v7u#e!n-bX z>&`k|`DZ(H(koltaYlF`$oTD_TW{LtK42Y!0izCqwSJST@BE7D>EG*(;o#eQ!^v__ z!NJlt@InUj2gQPy)7KIaJ(>hB&%p>nxP#%f*$Pxx@YJMgqclXt7KSrvNW*deiS~!~ z8(DZ(U`12;i7Bs4!%#d1+Mn|sA3qD9jfe7KSUjHm_enFTCt9k74pulyyFNFfVUJ*e zWdsjdwy7f_!v6qyYtJHgnVUg~;bOEK7=lP$*I^yo<@|@o`0~*Hd*=8ji7Qky(>T-e z#e4bF4D4!L{s;1Hf8A1yNXq$?#7Hv~xfyPp)%pEXFnA)e`d zm%p#ac}O^&$-JWWgz9`a751^-w~i-7js)^`FTvYaR~2mPG0P$uhdQf|!2u3mLXxoo zO!?eT!$_V)x6k*7!LOl;)8b&tB7(XhSYzdz3S$!L)@nvF~OTz?#nloqzU%n*G1{6EVk=d*B@oo(^+u-Q-5 zuG1@*M#E;MP-%DbS1NuE{&DmbG~Uxdv!sw4DnzVV*xTuPeCDxu;YZoYD+%pio1~Po z<0>~K zl3ivfZtwp@p^PRUCCfarrt1O{Ru-aaDkJKD52Z~z)$NgdX=T{JRz3{F4j zesf};T@0MCy1C$Rdx`1DIMo2pC$eet9$nfEOF3A~3%inr`7AWv(o=4-#fnB92g3B? zwcmns-iZX{5OW%7@snR0-QK;$OlQ5@`KTkAz;+moibCi-fERbjP==6HKCr99S30Eo zE(BtnLJM{smjlqL05IjeI(d`Bk1o6z?YI1|AE=3;f47#k|IL5WwF5*y3Q@IAVZspw zcN5Z5kkefp&^3u;Z%pfnhe=?cWHvg)p4rl5-M*Nx7G<#b|4t9fwOPPMvr659mC*dj zXGB0}jfC!7;RAN7{xu@a2ea|B?DkczKRO8m#J4JW$T!nqW*JAIgoe%KMAG)E0FpWIb56B6-_MNhvDUl-@{Gipr}J zlXV0f_W0wCh;kKQ%dE5%h`xOvM2h?g{CmYZBCe5W=INgD+m}jx>kauAwqc>zr2<_n zuLF%ids0rMjS~SO$}OkFDw>Hq5n@f5%aagjP`-X)IKB-EOTAFvs#wFKN8u<2MMInH zuJX)v_C{yT2`Y46kL!me{QKw(L_$u+e>nZ?<&D0b)+SKMbPIpE## zbG0UUnxDP>1Y+!kvq!>85h%n^4j%00MsqlcpX`v+j}$mLgEB)w%k|ld%|+_mg_tp= z18}&v6+p6jRki&)nRs8g~k(l#$Tn%EW7^a zzAa4{fo?cvnW!RRsseu~fB~6*x+&pqWuS?ECHcJiGb)zP9x24Xr&u~*AtK{bPqzRQ zf)INc&u4%^`6~d8?-O-uGnYW8h=6?&xTyuaw#Fw>qJQXBhWSuwtJT^HxO_Zla%IbJ zCv`D$(I~C)Z5P!gb6!vIVN?tzVu}Vpj6{tkfZs0~&u!Juj6njS#~9d!H;A+0K3slG?i7m-4Y)flYByW1sksej#*nj5VypP5WcupVlCaoybn&uU-RYA z3$|9|2wB$fhWC}uAY|9$fl+o}#ue=bT!A#5RzJ#p+G{+Fj-uT1k>GC9qdd)FuzUT8 zufWRp(8B<9%~amy_gZGatfg^wb7-yspBni#^TXvhZkOpl)Z4IM%UV@eMn@GyQu`p} zUT24XKepM>KFIsFs>|ZczK{)X$J=Wg-ul_=m&<=hc@3NBs z?Fx3y{k#gSSE|Rv!N|myAO^_X-jUn%^*0o|3T1)!e~s=@lrCOkz8}v?)6dHA_y0z? z49yRt{l!1ljU`Mm1DYxs7g1Q1mWf^S?e9Nwyav$fr74Y`F))O(`ifB>F#@ZNXqBmu z6PWXVO-<2e^Uhi9&|r>yM?jr1VJ%4uzCCiZ0H3Z=Fr-`;F^BjO@YIz4Rj~|*?N|moa!TC zXN(uxoAL5BU)td!sMFS#HJ05vn@`y+SK#~l8MRQKF>D4WoIse$X0G+q=zdyS|MS5D zSm0xad1JrSlU6ib`|$j6NTpy_QWf+(H6K2+WCh=|DnSu0*?BBwLN0y;6Hq{_P5pPC z{_LaVSFSeY$ih3&8KAp6G#0Wa__gmiGsMv-s`C4&yIt=5bAJ+&qO%+~mE&{grKf!d zTNeyIbf(^|ZLPnlHO||eoYX!w0Xw^!Y>CYhr^&XWxu7g%lAsG&;_(>2_; zD%Hd%b~?Lj6s){&r2bN3)UiPcoT>ss^}-|{Tc#}po`$Zu_W^DUFvY+~>qmz#%WQK_ z$+NdN;AYiIkgt{n+i&{@l{#a5^YnC{H5-|hPPe(OW*mNgXe+hW-&GQJ5wX59<+Tdx zCsT4j;;R8TE}}5FD}8FS(;wy`C|kQ-MmkwoNZG_--ZYw9)t{>kOBHNOR}nyxnS?K) z>JS1h$jBdJXh{d$R9}pTkdvkD_vB;wScV4SK_Wf;g&%Mm2kczW%4%iwOYU0--Az|> z$5>ydk)bS2W?;(M|B8dt!mXlzomqX!WW;2i;i9s>X|=uJMqf+mu7eJ)YLQ|T<6FF0 zR%c2oOqV1)5?rbM-1tFtMf=9Q1!)*@1WAs8MVr+3o~C4Fn=yhDUb8%y(wv|a{9X^? zs*4$bO&u_N!R!R>AOvVG9Lc*W(eo@2P=h0pN!!K4U~GcHBoHPu!9gBVF$l&@!EIW8Pl9|l zKdf&b!_^->`aZy?_-9-t7XX`;rETA<_7xV0@5(*GaK$}8jb^_TeAPnqY0GSKO8yUE zol#`zsJTfXaLez^_Q$Oh-60xf%!qD?vQREBf+w{E_txeF28N}@lZ1y=G*#E{-^c0> zq;bMN5lEr%GAo5m&q@Y3fnIKnx=RuWJvMoOpxZCQf7Vzsg;_`>hg%1o6pvy1R%&l} zxL*%L{L&$Oh!w@roR-E=2TGpeI~|b}==?%^6=FAy3m!bQGU^lwy}Wre`9-fb6(qyd zx$+Q_qQ74{O!K+J?0sqIkcha3&B4%e=xsi@>4xrI@JA*%5GKe@qOBO(8ROEk_1Z_t`fx#V!v0Q2s7 z607 z(~=z>Qq$NvqNcpfM{beV;()4IQ`;wp$XIyf1Ap9SI9Fz3X=C(zYs7<0vyZ=2CHDtc8y47UezvTN#0ao9$zF);rmlBZ1I}@g()`K7L~-mf`S3FLY@q$4G=)w zP>sNzMR`LL&!)J~jMc6b9Ff9Y9G`G9eJ!NB1ZTd`-;mZS<>TXKxI z9E}&}Hg1yb0aqV%Z+t)%n^b1ywPK#=E$pSP!9FZBT)(^FI){<+!28ALC%^x?4H+UR zPVm{vS92xpQ7iJ9et|#=hwPYC{GjrMb*A-Ta0Eb65)t;OCJaX_v<4iEx-3ef)XEb> z9XNl=6ke1$CuDn_A;gKM2adfr2+`&(ZM zkp>13oIm1di;CTdBaZ+~kv5%38US$kin@fBSpg8%5oQ_Ykwe9AibS~9$k|kBNPUEK zMV8`>ct1i_TRJ|&qYT6wtFt?EKO8AimJnl62Q32Y2Hmo}Am*x8(pMWO;5AQSRpET) z;y{}wfNb`QJFVcS$YQIYC7DR$5X{F3(2H$!n^q*?F3PEz>8n8gFb*VoMp7%$V3w0k znM?c zG(b_&F?L6+4i;=wyGl6q+0nZ4?ih>oW!j;}uK_s(S*yf0tB~6_@v$0;{sdlf4(DM0 zy+G#l1V6axD`j$Oh&U4d(fNX66 zs11&~3@y`X><;NNvIcOPm72!nd9+Mj|Z@d>?oG5O9{LN~VnVH@xo zqr)A&>xLGuO__Q*JPpc8Jqi*zf?i_d?n>_|-h{K_Bl0K9T^Iu>Nr#qHXwN83EdnK} z_N{A`cy6H3wPsxO_0?{Qu=dN(PUi%uO^N|fF$@BuRqUD$A(IVXiy1Xw7Gf^es3Ww* z;O8*ZqLwnh6ySmB1h21^F$+WV{}MYh&B&oXJ9!Yh{Lt|22Oydhsr2)&Iy<8f_CVS$ zzk`Yei~&FZ8ovTJKb&I72dL6JRi40?l&@@43nUnU-l5|&QCgcpTo{;{(WFQ~eHjbY zTP}%fLwrSjw*=?AYh2htap#5@^BSds!@@T^ako)kH>RAaTci$=kEANTQpJXY=bzvf z6hm$xpT$kUFC!Ri-VGd}bVOa!ZvUbVMB)=u%Wd;Tz*VNhATu;bVRlg28$4{)j*qCs zkK}v3xvZHQx}q#C{JqC3f`38zOVRDFZ3*nsnkYSVWw|-uSdI=^yXF zZwhU4)89q5dJZvHO0lt;tzs36yuEr?x_7bhYpGz{(X&iT-@B*5z>I&}#>e!x(e9~| zpZB?Rch7Y{_q$5NX}F7(B!PzCZJ@M*^T9FnI{ShVlzDpvJjnt3QPx0AMsXQ=cFACy zab84(_0jNQ43RW|Jjg@vDiwjpJ26qzaJ5U}tR}=GJuy^?2O^0}7w!3weVE;RBoV41 z%l_wO5`bVgb;nNBhLqT8HJf!FrTUqxVYr>^mHpAm>n~9E@h=Ha_1zh*qHkruvpi)p zmL*iLGILf7@PaD#Hk1{l!LAJ2%IC~!*0VYg!q*XwRjYJg%B8L5;L2P&hx-;5w7!P% zLIJHk58NhZrBwYSkZm(UyU~o}aw1nEFYEljc;&`QFqFH|p{F;ztY@dfcYU<4V-J_q z8sHUbCQtq^VQM1Q7qp!tW{_&ruS~n7k*F!F(vX@LKju zp>#`|QPul`)qXbAMu^im4|_0qiA9eNZ=(%Y`c|Gsi#v#}qGAC2I^yVgh*YUJ`JmWU zI}Ssj@QXP@PrH!$Zyw?TT&ryr|IHwy!OozR*C|7(d4IqAi`gOnG?oqhRNP*$Y46cr z|K*fHuX44MQ8sAT$Rh9dU+BT@c<*3ou^>rAKWB5Rb~1~cx#Mv9v#y4D_ste{_N=i? z&xcEn5zIlJg!~o(dBQto7gT35FV|FszMCGl!~q~$?t=MuvVTF!{obFeKd)(~JS5KJ zUt6UY5j=13(}mlUw-iGe<6=;I&Q8~f^LS7uivs3ZipaJw zPm>-oh`dCZQrAQ`8Z20EhW}@X@EPy^vf~#^3dwd+G zfXqgAmkEUbM%ed-bAYPX7Ie6^K!i3l&UOFrbOg$X33U$g2*I8z2xu+Xq63+k^mtdd z7pUQpkh}eiqgA}xsACb!vhT)W&TTfEdqrx#T%UZ7Zu+^+ld0j8GkHQ3wknn0baH=Q z1Il;!q#!y>R4cV)BEX0?pawBs|MOzJECwT!k+F4tH-*;9|e74z4%9FyzQG}4d%>UT;4_h;m&*SJ24iOh_7liumQaG^t zA0X`i>pntN>6O?>=Qun~U?NOuQjW5}PHxbpM&bm2iBt71c<8So%PybqFE)njH#ri! zu+{q)l}0>HFFUNqb;f`t1rJD*QIe@A*`ijYc1S+HU{Z+fMX1DVkHXCoB0*WPXyu21;!aMrZ`NAJehH$#Y-OB^a)>Hl8@7hOH*2>@_j?T; z*rSX1ImM#wZH#8cFzRA%5xB=nnm_m9l+AO|K!l!UN@0s`__yx|Ee)Mu$k%EYxg2rk zuTD;nBakP~-SY%}Ef&|vO3LH?T>_2Q?_9RW{=RLpueE`41%6$4nBisvHil6qzAK$IyItxeyf-VmC$I&u*(h8MRDt?TP@zKztp z=3$Bt;?3DQMbO|y%AdmfiT*pHwco@$9PL%T&_Uq$1uzDiMOr2t+&F)P!V;;9I?tiX zv8_0}*{2rSfefvz=!MB&BDF;6-Ay-vN^|Qw-V?x@pJh#X(G2}uB6b8i94MhHb^p*B)=vn^ix)pGyOWwjA{-*O zD~BcdT80@^fDma$FuS}Zh{g2)6MAx!t`uqvW&}~U3WP!!VO1VYG(tvjUUuyq7n#o3BCA+^G5g@nmLgnW0yxLpASR z%-ZL8TEAP8D=GZmV$Gmc7+&x;xg_B6q3=t>wu?E-bi3@as);uzEkoo1i##~;Iwg|b zEZ~~~Kn#2e{hz(H@&KyJi+Otm%FA-TI5D{%4pxoCZA#I+|FRoetHT%0pi_+dySq`c zWN`dW$5BrKynkj^QYm+vKF5A<-ODCPJEIH=3uVg9pieSF#{@baHPVyM2#|jlHaK$l zKR_imy!ri5N-5?3V}GHqmGPArRIOVZd36#6raoT#m&8o*pWFxmSMUEb8@c*579iAC z0DMq>tNrJUEF(ZLHHD~BqFFCNM>CUmxFrp!dDa+Y@mKRutduIm-eBN8+yWx8=8YErfII6a3y^!t6+}X9wC&ffV;w| zjkS(@vLno}_3{=C_$uIRfmfU=L65MDxhnE1_th)?R)2$G&?mJaTF-E61$*g1whLy+ za3&Bb5Z)@p&QZF&GdZZ?cg+Bp{<>m`w^LH?&tF}X9wKW9dzODi`XVC_GJtitz0wKPUuB%21z1X(%O2?7)O*KK2vfP)+BCy6u?kx4| zhj0@sSS8&p&`5FUlaww!DnSGdsv(%8VUipcL9>$y86Uz(GUiq)*tpL?1SINN&e90_AH;%#Or=SsLo;LxwpW0bYVTB~$fd_>83 z57y?QI@|-rI+#)MUfeg6Woxf|=Ye zUo0E(PX<PdWHFIX>b32XOo!9c}AKmENZ(kU7cEIa*Hlv^WO|9i|{#Nu2vT3vhVv z6vGsja6s^7C;0r6JCsvzUK+l+N{dE^ft5E2rsGGWb1a7Gx%ezS63EZYo$tG7mai#3zOtL^>1c^r%nZ37}{1A3>y8_9zLKO5;Ua5)oy36CH^ zuU;|}>fNJ-%`zY#)UW>jNqMh^98&!4JGw{`2ZJkgtIq43t6yy`{FywMddLZ*uNJw# zW|e|!TaXcDJ~!P+Nk9j1G+|$>Sj5>BuL~o|7;qOEMA=h9HixM3=L(j0(ZgV5jO=(x z3@u6Z*8$IC3{1R=D3zjo^FEmW0f>CnR-0aa;4ADDqZjR=p@JFMv=pKar&bvP9WzO% zymCu&{=FCvxbb4j1JIR)BJvM&Qes^5Ht-u6vaK*oUbbfTq#bK;BOKm@TSw1de!fY^ z9y|slLE9gNZD_~}?A`h7sx~uphi!mq_fcSry*&EwS*_B^!jGAsUO)ZA1>d$puF_A3 z))ej_~oKB+}@_392N3(mkyoAac?mN6~VW$AXd-0CN zvFL_qNq1tbOnVW!*#u;9`WQYr7bvyp#OlsCpgSwRg^r$r6_zL}>BE^f8xHZVn#kwoyV6Of}?btFFuO#SeIpx%0@MM#R zrc1Z3A8U_}Iktp10@+e({1v5BIx8d#AQ-P($OmwiT`A{bMF{*t3(SymH?TLJ`E!Y8q7o^ydh^%FP9*X{%T03fryT zB&w^jD@VBPI66u0dGm}t^asIr#4Jh^Eh`*_xsxe@Hn63jbOl5B*RE3?=a5rZ06}Ht zRZ_$(4KU%4)EEVXRHQJ7xP6h~?;JmXrdyw$ZUY>iJsN)vd61?dlJ%dq5hri~mTp3{OsA{&H7QKocz}w9Vzaip@ISy5 ztsW_gsamhN`Jr@sqJ%z$gPX=qqtM9r#}TrSg^xCXh^N&%*aKazOX!K1&tTxi#5fN& zzs5;#n?jmOQYrWrOn&P70c%N`mujnfw-AcT>oBQUOx}Zvo=8=1&LqP z)pxhFj}PJc-@BmmX92qfKzPY7V>as3gD#)g{b2BIh(4LmLi(lAre)Qy#>*FRxwU4y zi*)})F-r|@i3A<>x>YWjc~X+@AwQLg3d=K^`Tm%GiPvk6ztcbQ-qpzCnAt2}8+zFq z&-o<)`6*)NlmqS-bW1sL33OJx;zcR=gX!+E7`~$;*x6cikKbUTP1AOl8O*AQvns5= zpq1-l)o~cNyntxXUv@*uzY9lR(vmapHH7z(Ws{V~d7I?V?oj7rF{DY5B5V2Ly=4`m z=IXz#G*JMhJZ7TY+Ko3xwnAt{G|Agvk7M&60Be;&II^1Ts}f6j4GW=dL1ISVteI!l zvU9%25JS8&X~Ox9kAGPJ#xC!l&E1^kZXTA0f76S!zy9DMs?RSnxhNxO&`+YfS6FVs zrSSz2o0jWT-6Qo#gTJ4;q*7XwIAoGhfQUk3*6xN=yvf{VhrI=fDh4$qj{_}QVd!5` zpcvxl99zipT6{;Y=eP8^*&3j(c8aR9Zcn-PGFbA*lC+nr-T;D8)FO1=7E*--^ z-vzpHj700h>4H}%XQqyHq)W>?Cm0oxuk%Y6|J!ZbJ&`*%J@Mc2uYbZHQJ9d`I~kD$$tP% zLf5?W5#}?Vv)*rg;}-tKt*f~|kc;cFJiL)_Jmf_qXiW)-7^@aCf%|eOY@@2ma)kNn zY&i^BJ!cz#3pppzz;?|$Qn~Ia?ozz-s;-=k(@(CKIyCU`utQoYzSyJmczmadP4YNU zjlja715>MIAWC_=EP0yA1;cUtn2k#~hcX3fEm=b65Se$cW5p9uP3Zyb=Z10 zmAF2n9|QHE(mSGEXTNLFl(h5^&P83i3|3{y?<^jZKNY5+;F-%UDjC@(th;o#n?{5p zArjH25n6@}ATsM-!1-hN^~+)8Nz?RD+&_H6Z842Z4uAmE?szpTwHRr>y;VqL|R#^0rN*j^XjbmK)2B*#oOt8cqfjf4YxHNGj0QB#}fx~{<1x1kXI)G6?lek9#WYF`Q zb4`do480DvvLkP4WDHnHz#dqs2Unb`lO#!3aZG<{UD9hMr%?gdp}PsfaH%VR;yA5z zjEkdp6E|_eiwWzjLeyLnDIQGrj{hsVA_f~=A}4e~F&`HV{C0nHOz4EZ*QXCNE0A!{ znw1;nK%}yR1tQlPznaaGkgh+)I11v`5G|^Hto1|<5E0hcWLd;xXV{(P7}9(uGlC(x zVAg4Y!luSIo2p^6IaTk7T)$L;%C_zl%hq2#-8F1iek5Qkl4so_@P_XoJF>Qq}Tr=gt8RG!sww*uonSl~^Srovzk7nK%+b zd;YMboXVlH$Syed($FxdS^o^(snhWY{o5~RrInzD4#Ama4(u2JrtZKux%hShoFI=w z+Vc$Xp4%f2`T$TKoIbU^SxQP5sZ*Bu%5MV`vQVLnpkcvyMWGZc@SnHsD>{O_wnt|y zXtBs9hqh-(rqs4t7M{2CB4$S2Yd#N*jw%VfP~0}%0RpoS5E9!FmgsmMz7Cg8L_W6@d+pVJ}D?@rW`A0LaC%g9oDU|BQE%Yp# zi1T5XSTztHVk>Nic(uNh9T>%A*yG!h`pNG`5U z1wftjFW2*Ip?IUPLoaKsj+CwNZSfC-^44XODz4R$yNj&6j{OmB|J5ACv=9mTRb3P0 z%m^GTHors=TIAp$YKrb+;>I9U<}F@qSzn{*#Gzj^Vtg7cDuHEzA70%gHDCS9P}97g zY8{7sCQ61;lDO`O0pW{}KD)!;<(##y{X2ph4Pw5yKOCYD%yQc!4$eEUvM}=|@w&MV zrWY@E)B0tWM^vP$s3CwB3*Z~WNR;v3q1x1=G*;gp<(wFY3&b2evAgWT^%O_!@yj=4 zo#um$N@#Ce=sFmMBtQE)5*IRPTWy-|SH(bZNJ}QhBZv(Wh0>mSx^aspY2zB#Sz%QD z!)PlfeM}Re8CSlpY@g+R5;Q>4C%}vb zhZj&d+&ZdREc{YHVZ1wJCQ3%f9nieI=->chs`7JPovPdhF)!QB8*&&GPr~@)F&zIf z4HJyc;bG&4G)L4B z_|4v`G+l#EhJeqgcK5OQe}vBuZUxDNG8(3{)r!Z0VU4^qO^xfo&!hJbBqAs4cErmD zLQG_gMJz8Y*kC&6G6^&P@|Y8ctgz9ya;dF@ik=%WJ~!xukjU-LRwtkNGf!CF>Q!DV zqA=G8B`x7+%)}_!jp_ym%%&irx4q+~HcLr*sqc(`xmRH@YPsUl+2tgbGB(lKfpE%Y zw4hh2s%Md-#>8}tDVS&O3GWqcZ^}FTCDZKOX0EpAg>qsD$vwg5(eczqK_J2S@o#KvKqXbgtIKO#?g4A;RMluo_<@c)!t)lwenD6xnTya`fOM?r@Tk^t)Rt zC&P$)xbe@M4{_crnqMIw%17X(a0!^CJ!x%&g;t< zPr^(!)nK0CF}w&6r$RP6p%Zm^JMU6DFb+lnqCu%yn4?iohotF#iVN zYrBqWWTcqK7mKLsUj=1W!$+UL#6zN7J8{$8nHGqaE0xS-9Q`vpJJN=808_cu5JU zxpzvjUcXph`w0VR#UzzIIkF`ey0MeMj5`a@GT)(Vv7|SgTkg^kVI`9i)A9o)@1FHa zT30x|aJl2vTeJqp_pTyk?`nfMBTE4PuAi^NFTh&?w1x+ItHJc}TqAB%jjl*Ia#xo$ zZ!?_~3vR;WWTArIFC=)N^Np<|ZYzY~-0e`OL#RaPv?$k&aExZvj3!s^y7U!!8X>d$ z^4dNFO`%B^;ShGW4Z{&&D0XdNv-J`+B13i0XK+CXS8;**j}`OIc|MfQCQq3T$`iThX>pX8#acM{2CGJ-JZdhIbVSmS1-bfNME9I@bWYt zPFJR0+2Xn`&5{C0kw~(q8K+K9+%irqJK#@YXFz#6>6$46}#kK@ob=^p{|8sx??#V~bD6pdVt-3klJC&VsK zV4qCV4LnQEfcRU>wrw1p+ac^69{Z!s*iFJ9#?R%X>c5%h;O)oZkMk%VYTk|Oh|*T8 z=}jZN%Qf?j?mXVAh{}k3{cV@P$o?DfcD8~6mSN6zlHkxWln0aB0ySn%Vm;0ItHm<5 z207DVe1LBx4ze!8YB$L5PTW|)AUs50@G;xTAnQ6d;mbyAq>CrN(?=E?6aR}b{t4AY zf&{|#XDA#s;&EIEe*YU5$4wZ~+s-t7VGAi_e~J@GEU_9EPZnRB4iz-Bh+6j#mIX`t zVt3`65AovR)1Z;OU-tvQF#Lw|YrNO}+==Ihx9RcS!%v};oQ9Fo>4*d^(fQoxv2vej z*XROl1B+-5tpw!JmxqH;OU#O>ZOJDL7_(nEACO+Smy^A5w6%D6mxU_VIhPF&C0y~ww# zpZf!PVIqsYes*EP)irNIE^yu1IO!aI=q7**-DmFZC)E}aAzI!eIki?bLuH52+oc;9 z&+!_{ClI4MivybAu`iv!BBnC@0hgR8{9*kToB9{Hibcpyf;|+0A%{Ok4U}X6s`rRz zo|E@q_0oN+pGTCz2%aNh;Qnh(GJ~p8)#rX=O?3@%4<6}p&YxD4`?j~yzx$mN`+wJ# z!B~H9QE5vmRvCoy+<#;1tbi@g$hS9Z$Q3+drb`s@rp2RE;0=kaVZ8tAjd*5@QPYc~ z7~?%5eX8?RJR~Sner-arJc!Xu%bXW`M@( z(#XhSja;3hjU%jrdgw1LZGOXEJ&h5wK|Ec3hx{LH_sxNNSWs?M z(kgkWABeDmS)JNX=y`d7)X*BVOU)RX2!kRkGQW@WjW7s~#z+*U*zMLnMkYd=2e?n= z;4e?xsdir4KH;gnhyMpy;1A|QNRXD;=$t6nrT6njv2_v`U%6wZ)CNL|{RP=V>TGs4 zGmfJkM8UexzAwTM>ihlx73F1vo76pWf}mD0hLrIE(oUK3k0yOh}#h1zxd5huw-N)b+2RAp(qT z@e;aLzeP_6nlD8#39w2zsW7z4(ejs_Lu|er%9Pk)c6FgY<YaSBq!fYd!ggx_vvO^*$mBsxqbIcC?C!2-D!P`t=PnLSmdf)!6MbQtE@$Y4NdGFq~9LFG6BKtXZO0oSP|nI>aA8DMfR4W zAo>RSqqvMYE6d)~`|H0?h)@yob9ecc|3aD$v|jdqy6vTd`9cdVbA7T)p$((?&&#`~ zbT|m@eZMo~NgSzTmEJ-i?G!DUNxQ7d?p- z)z`oM`sHx=G@rD_*S}4Cp>pSn3SL{YuZD0^2aWyq?e}%Anq0AM!7*`3*$G~zb!ENA zoEOm3Itx!PFx2te}}PO}j;d0VRHbPT&?B2c;5cFFyK zW$39};myIJ`;HeT=fCHkq!0;Qm=ADR>O9f3!<*lAqz2B_*2Q9A#u56#X^!9uJwQhI z_u>~|_&@7`#nV8sXe}Vq3#ooF>zi1OV-0$$^6l2?#(O;qqe_!zUdP1W$)edDeR8U6 z!ZkIm;|x|~O5$|67jXEVx*H0yjS@tgCuFB%P>R_jx~$rdau)+?{Od7|HFS8~I7NAu zBcxut#(m?K(Ta1*!pg2j8-W)JqMNrVPxMX7XIE{r%cU1F{_*Dr3AnQm@iX&wFOhI` zld!uC-6jnJ#<>3vaP~jdA>k3WH?v0JKLFfSfx3hZG^2Z;tv>-8{@8iN@hBmqYm?gPP zi72jMM-5eEHa~^fC>)hg#s2`($OwruQMxmQ7i=ba9SliF*7rkXp*jo*5*XRDj_{tK z=%x(>5>FE{11uVfyr|-aN7yu~St14|0})j&o1@M|*5xp7-tdRq!AOg~kVBbtE~P7V&VF_#Ol z*P<>)&lx>E+IiYfW)B$$=072qw^XVmL$^)G+j>u!T&Z5+{B z>UUdiLouaP6a| zJ~Gv(D?qP!9`gm0LYxshbWV=l35)1b1HbXyTjPHPqSAj2IKT{b|Nby2VM$(&Mbbrk z8V%z7NqCc9{qPR1>^<9Nh(}Ig)-UtjEc5WK{TQ~~dYv=^PvlCP7?qLIJF!L`{>;W0 z@G7<*7Pwxh&jo%b)F^yY8NMA7tw@OT%K_Q6b9$rI?uY6Pvb~Vz0olaU3X#0;6Zo0Q z(XFNqx^|<%o?hh`p<%K1>$}Kv--}PwI7~}kT4Pwg5N2Se9$n8LlNt?-1?HN0UH7N1 zcN_~ro`gDnrL3N&@dg2oQE!BnW2^JiakDF(1$L7Vuu-Ll^eUmYo;S-+1BX&*v?LcJ zj)U<;Z)pV%67kqp?_PGfWBX8>PopnDuYTY*H?PDqpV4zb(0y;)$x&JB)t-t+W&EIT zLOPr`s4CL3+O!OCVfy83efzLnVwlZ`fUUM7E-_P}@whXTYJ4n{7o5mf=%!dcDKC9$- zSRzpU{qLvT24XpW9AkEvlg`g?p+^XsN)_0ua_JM0O@+OzCH?n*1+}o^cS3>by zQd}+xJt6LBCskc~zPoOoI$%M%vAq-GJPFD37{_9v%^{>KOT5zLxlIKHWAL(#oSY?8 zsGU=ba%}?yleuW@&*XL-2ny*B_eX+i9GIzbnWDj|fHcPvdlGx?GKZC=WWaB6AN&Up z5F}WOCm2DM<>BJhkX@oC_N8{0_ zb-xc1(*cKcZ#ftLTVDY5F6m!*YIz$(9Oi`xsl@}ABUEU(-Ut|p;9w8~NT~9D3c(}w zU^&|`XmyM%%S8d?!Z+M+ZsXibm8H6JO={v+B!p!7JVxY3({+(Z0f9#!4f>mupH;q` zmG)t6KYVNRj7kLQ*`i)t+Pib_&#i)HxJT8jqcjbpjz|~;d>A{)SOvd0$sA#a7R36T zoB_qafH0r)>VJU1M5Bn4%^TtSH+w5x#(*e`$v4{NwmQyILLlF7Q0ldU)eJt=-*;MB zwavq^>2b6>1bS%BG|)gO799zSVS?!PZotZiwp{CBylrk}f8(cFSYw8C-2QJ2e;9^Z zk*__>633+{cC_=XigC@9vo9xRlUCwt%@SXvO2>w9R7!b&`n7S0)v18&ec092kZ^78 z&(ED@XVQ_`Wr)}0^4chcrnXW_&3ZI?kyobK-a)0oUIZClC?7${Nzi>*36?gAbAomq9_!u*b0nQ%s+qd(6fDflTX5pa` z7&!WWO!0sH9i+o6i90?smP(KjD1Z|mwpXx z+`v=HB$`1rcD&^WTjaZ7tMlf z_4_OiK2%4TJzp>el_VD0`g8}M>ol*MAt_!jMDyXpBumz? zTne0*#T2Y0WoX0Wm|P8t-SIny)tx4?4L_8h-g4FJpjWv>OeP{&0!7_r=Bj^I4H# zHmKU|I6DhHEN^!_R#pT%7xK5I)S@ZuvY=@0z%?gxyEZ5>#Cb3I>dgI8Om zgDh_6r$kk;sb0IYq-|EQl%!eq*%E>^J>rhyUxp?7Zi2+U_s^q)cIlTN{8_)&1%a+u zc#y5DAF@Y%^6H$DhNXT`t3Ra{wBw$NCiZMJT^e$jJg zS+gG(;pp-Z?{Iol%{y*P@QRF7A&D}CwKFBEA&f)UBIscxzI>C2t?7u4?>6b$9A5M{ zq^>WOSW-3c-Kc()hk4oR>OQk0q`8)pCM$dZMUkPU| zb!pTOxca@d{EepQ(+)-ceBKbModbc=go^akz8cmm3q1pY5D8VRk6V^8@ z0N^kS-1+VyxQ9ly*|ny`7BM_Tq0{QI)?x)F+P#qaZZa@hizzvl8G1>iqG^izcLiwu z-+?Zx-7(MN_JZuh!)K}}OVaZ0cY(ZiMnu+eF%S20d^qSJ`(tfp8O^ZS7t>azw7}7| z0AFW;q~WpgK%w^E2rYVR@SI`pRx4f}K={*Zf_&lsq+i`HPrY?2Gns^5l^mrbZjrZO<0<|C6so69>j-#6=! z1%Q56dOrap2G^ag{~c30r+mXgg1ZKiL(<8D8!2y3u?Fk^k?WBaV-qlrup~GhYV#K< zFbn%7509@EOa}#|kR+yZUs5nX`ue%}CSU{a{4E<$t-uM|Sw_-=%gahY3l;tH#7FNs z!LWWDH!j+ldPe~MT=vs%rCf?@s<_NakK!h44NaXhBsO6bN~N9))m)AHd1`KZsx%7T zrD~RLS19Y0WmR5*Qo)c_%Y2(|pH%iD1VV3p8^hou1YQLaHt#r0y;53D17^#>$8vjR z)M?WGXgUE+c9|(JQYLOE+lU`1 z;B0lJL4R#(e6cnGbY$#a=xI?~SP@lFMTi&x1YGr16)`0oc3O342?Odl{6^-1+ywPz zlX4eQ+o26jqp4LE#Z00${-x_PV>T9Q3@1d@%LIMWN_gMhpyti5W6mqKy+m6kojmSN zl+0w7&IG}Q>h3h1|&g5rot(9yrt-glv_Qfcel6!`9U=~rvSTkiPgEG57&`cY*J`VBLvKKS8fuH`N>3kxmY)F0P^MlZ>@3XYAmE z>ZcQ>M(B)Iv-;nxsXszzq}L3aM8+5k8uPV00gSS+fa`yN_9y=gz#l#T%q_Z!ani@A zFI?XQ^T2eEkr|WB!Fk+60!m-bMB!_fbM7mukXBElj9}<#s|P9MeMfPRqkoE1krm4RCY4(H$5#SUac zOon;%SU^O`Ye;V8KKrqPR!b!g)|o_v|k=qGnT)h1s zgG-2t?sU%E{oCE}qTxD5gz~HRFk$SnNGfGZG@v7JTZzy{gs%!AV{U-w|}qyVI_hL5c#(P$!o7hH<6(IS(fh`DOzrfaVWhwhfz4Wlrs6~ z2LVI0vB#zPTaS9P4T7vWYl#1Ph`~<>F}HWa$*H#3(GVTUW38K3A|Lh!34SjS_uqM3 z5XK~+UMa7Bce-;u3!JmNKD9s`jqH<55dEC^EiYyOzjdRP;cG-9q~bm;KwZ{>j@EB% zjePYy;v|;9qcs=wT{NN+T?3Joad$e(fG2>Lp^&73x_hMo+uvoNV>ZQ-pOq_aS`L?_F!1 z2UlfPG}LU78lC)KGxQJ+ghGDBOK8^0F-HxNCL-#3kQw3>RB>cOySF7|R{<}1non$g zrKm$1W@(M%I3VO0yI&A$19h8SNp5xEH4uj$Z)TUs6B=AVyruGBvRrxt%NM>{ z0cCA={e*X9E#hk(YY&H&>3;^F^9@Vp^J=yWJBKeSU4yj>!2A-jynGT+b&&2#=*_dW zk=Ct}jn=gMAAr3fv8rnd zzKmjWQv~31xr;P2+^}2iON!6sNc)W7WOywDmZvOLf1W^cw#gVB4V9C~$MSQ;5a@am z8PDFU8zFS>I6j2_Eh^R)LwGnVNxj4k609{5frc2(dU`meQ>*v%r z+th}-O^~{1dCf0}mgsWTZdSAl2W@ho;3Gwq(UCl~Qdw_$oCjno+}3M&tYwYF|yr ztMA|j#?D0Whg5tgatX6tCVe^-gZFi)S%vfsO$sOlGeG8Vxi3gb`#c0iE z`c&rZwJmLv*e-Ec;?5Ibe`~~AhdxN&a?>6uoISq5$-I$ALA8)9DrluA`OQTFh?<0!q$GxQK# z3sg}ZC`2Vo%|jFMQTaY*Nlis>gZ?|ks0olzDOQ`=CGfQ`r1~~Wu8Bg{b1@wY>K%r9 z{f@^~7yj_1v6iOX>*o!7w6d{9R9|(omLCiB%Vh`m#@5z$j%2Dq| zN)Gt4ZbQ&ld#(x5r480JWVdU1hHl!aWjCbZJHtFf;8QcgP18c*xQt7G`10tT4fq4q zX;dWm|4??8v2}D^mcC|YX66`UW{#PeIc8?OW@e0;V#b)6Au%)KHD5DB>~}n){`%|I z%xE-K(mAU7T{@+`*Iv(pRM@LrLf+~B<`=*i>*M=EVmsRV998O9xV8tqRhGg@yCX}M zgAt4kz|q|QedUU6SVXB{&2IS8&8vSpab1D+w9Kt4G(zY`p$;ELjVo9*>_J|zgkDC@ zQB=`?=CQQVuAOt*9180goa^=hkK4 z`R;6hC@!hJ%05C*Op&dvt*r`ZIW%c1uZdp?P_*Qg?_LgMiDFXhT;Nnd>P+UZm=C4- zK$Av?^^Sn|fFKwc)-r?}ox;4tT%1R*2jm<1<8S)lZiqF0Nm4u(9kp%1$?Ku%J2X>M zzgwhPm1d#?0e<>kfmY*#B4kJ;;p<+RVv$mR!gwG*}viU#pAGSAwUQ&j!>7#cq%)T zZkcpOhXV(l5pMw+6X;>xHWk^5(1AWut+{a*<&4No)HLdtSS}OXx!)q-L@&1{~ zG%&Do-ThHSHv_*?2+Ig+nnDJ#aIkk252Alp9o9v=e?pI(lmt&(ar;g=PwJzZqLL0{ z>?#HyFyikIN|sM3QayQCCin`m;h>a{aVG56*mm*Nw2;SJL0KphIu>Xb@C`M-B>v#N z15%LM`Rc;Ylr+(AprS`Dl8kkMPmU;Fa>4^H^u(iDV<)G3sr~D(3-AUEc`2{Zgy6h) zX059s(G%+XZQj>x*{6P#Mn9By1E&)kj|(LN106IzV-F^o z;?e~lgbo-v%2>=>p=qah3;UDLJF;SBM8wQ*Sl9486KNA#b z9+zmtVasWF5fud#{XLJ0GeB8&^iZ&U#KtJJ<-C8NwEqAOcX(cX^9Fk{*A2P(v(t+NGN+Wj>m_wDO);5&;4aU=UM(`%813J{qhb@lWzPvtn z1JypfIw*lXXO>92=lcpN4q_O>!4D~v&K{WR+3|>M^ogr&_U_=&fQKA1LM#)#{&yEo z4a$^Qw1)_Ec>B3|W7WH5$9ns2JmUcG!FHob$ja84Q5$q_6~My{VA|W+qZj3qkvfr* zT61jmE0H-Et2TQ;tAa{77v4F4(z+TsJP89asxQzVk$hJ|PJ1;Yo zjiL}Sy$~|Y%{Esz9Kfc&yiA}gVeh_4NVBl+0dC>$CZ1r@H*-4YX{vit^w}=o7mS$$ zg-zuzaul;0B4%ko;t^h@5XO(V1(#dA4guIHqutkFB+G|s#V!_6fPjp&4*H_r{5Xlh zRV?rWiUFGaxxcb!;APVMurP=Y_CvrXXkV2th9eWf{)|8DnG%>-2=^BOMiy-eN%MqEC1$l-x)~T#|#1C=Qe!YKKz$g=S*x&ok$a=ClFXQj(Ks(2ie? z8!-9U7R(M7etszM_nqlQQ}e-tSdceKy##HvE8z!<4Z%-CR1fhD*HVP(XgdRsdI`~S zVVQa$PnCt)$m&ru%Z@_Nz!2VuoQ~ztzlrIG<;x5}wRyrpXp4UybcTzD{kk66*G=k} z<()8I_Yn%Q#Rb1%$Y{nE?)h~ey+5aW1@{Gf#i@Aa@1L;P-s5}4pYOU!anM--pcCG` ztSoR6wo|;CI+HTzs4E-HvMXV6!PL+Kn2x_ho8*kUS{Sn>ph>(q&rm0f?BJg-%6;#1 zdJ6sB)05L@K=@e?Bc0Z|fpe=BY&!!v5a1W#1Kj2`lJJ)99*0ee3)qKQPoQ}4aIT>n zTdopUuvvAanZ6T&pk@zb(cDLd*XMH!Q&UOlzp5Wg(2Wn?dIU6xGq1n@1Ne`jqr~UI z-AQfQe*h-mwQ(OrAYhRAhU|r1p+0TU3KU_NHkh%*c4VhcFj=XByxn`{N{`*fO={OsOJBee+LW%Q67X!}gUA43B!9ci~ z)Ywr9VE26>I}KZC=V8%xz}L*Yz(31q#PfRs?^07b?sV&exU4WMdtHucbiFVW{`?aI zN5WZ#H4I*BudZ9jS&O?a#>PWR+Y-igtVz`rV^qh?MHLEzcq(7lVbYH$@>VM2e@Y%H z(9SatTpQHw7CwAngc?%GEP_wK_{B!GXB$2fNEaz2_E-47v!s9bEhP2k;jE(*UZ+AD zw!DlD40lY(39udHa^PKeNRm=S3(;qoM!^9;)5U!_OS4(|@DS}tK2sJJyY%A`(W@1~ z)@3isd`+b<4d&x`^CYJe-}awEf-R3151E`3B+PV>5WaMF2O50pU_HM3 zB=c|x6TfxXzOBjU+z59U;k>>#W_!*UiH8Qd)}P7f79XUp#DkJfZqbrO+m#U8rh{NHy3J((0m3%nv7!1$lU|x0~i^~&? z#TH&p*mp(0#-+9qhK4DvGc{5-OCKd1dL)*Oak~cGyvZrvF4bI=y=l?Qz2Kn>*(#rM zMHINQ=;jQMi)^xCj%4JSzUZp-VFB zen!AT-R&QbQYe(GZgDnLr~IC5yS_M2hSXxpB{4;*sjxIqL=vEid5tcB95$rHW?gdi zY zjuef-MNU4B1J%h4!R$7zP;9G*oyE5XXub?H*2-4dZ@2#S$QGhLfy1b{96dOB$VET| z+kxQp8rcBnI;WgFydXV^w2h)J;@g|ujjM@XS9xv?(%pksb3{!+@A0Ee>!cSJLL_^? z#fm#q{5zlB{O(Vq6jjDb9CS(%MoyGiyFJ&B}x?2pwdem+9 zD1I}c(8$I+aiMne#eGLmu7m!oV6~~w8M$cw;*M2!D))7RZ21hEic5}VYlValayDFr zj%H^86W_T#37zh6ClguM0%E@e%9oEU`PV= zRsEnZrX<1h{<{j~s5VHIAJ;Dg6g;%sS*bq}>2=Pu-m)@Hq7n7$8cB^8*|rF8 zuWIC=I^RR<{P)=PUqge+K9Ar3ppo%S0L+SN9Mk2EPOrx5%ivmH zMnPN;D^+9mVie6_M|S^WM!(;ETwxt;;9>9!<($Sv*QX!9KDF6~`|ppjJ}Xov#mk7;&5aHmP#YB-=owP3~x_=HXcHM!Al*9|P-L)EnuJSAJghNUjNKvS;k__0)bX+T?igzR)qutNAq_ zC0s9`?f^y63&#Lg7Q95H#EuoA5$ZTx*vp7)LaY)bUc{?g{XYP%aC;>eq|4!*RPtZT zq?d1?1sE791!2M7ES=nnZAGOHfx+-Cc#DSP4SZPgMLPKE)5JMR6ao^jn*>Tr_(zsi zNs2E8=I{T;1OEfSjgaYEL&|w;`v-tPpFnL>$NBM$z8VnyY?HMPr-U`utK!~6OntO1 z)aNfSKqA=&m)J&*=eMjN`h`PluTQy`IGL&N$?1zCny4R&H3-sE9J;xeY;8Q8y%6YI zo{Gl_iSTV=>~I?GL|sA~ZuFyrh}`|OtVJZZeM*2jtn0x8xP(ZF+ilkqz=n#o*L4{5 znVPw@>~efRf~2tL6+p%-i_`iE4~S6PBM$G4-Nq;+RcZ$1VZAG2Dz!$j_A&!GPvho+uq1{rY-BuZXg%jbXF zpjp0+R12hOZ{rbZ*wq~9TO)^P#++NoK@#%S@%rtBT(BEqobCr!M`Z3(jlube9uING ztGBp?X$8p{1*EjeD4gqloYjaC6XQNK(L^TaBx`&pW?G?iTrOtsq_(WHN9tfkVJNkA z5*WaLqsP@-GWC+~7?r|J&q}K#JjauUr1=FMUM<>|jHi^t-z!=MhSN7Gd;ga9AE&6{=di#Q zm?grK5<8OU5V_M7rAd-MAz2LY8V(mIUJ=#T z{;YZu)+@QaT6!LM_~%2?8`PjXx$EMLY#9tmdM;!u!`><5t&7w~pA)#AC9Se&Ls0D> zemD>T0S-*;e;sx;0&0KyWKMKSK*^%|61hdFRyg<#Ml5@J3fn?ot;DH%Fowff0M!)< zQ{j7EgOj3Z$51+#afz+t&5pi7iCd31HGI+IFF1N|DHv7LVu+v-t}r#;H#4lgcw-}W zXc1)(hRikk)f_qbLr~y{C9V$(M9)bI^~;}LhPn9Ho?F|b?p_yDx8ON1vw*goA4!G} z#~0xS*I7CyF#^iR3pkV5Aw|C@V=v7xI>3-2gGB)@Kv;2ht!AM53g?_xRbftu0kopq z{prgwz_A`!2bHg$woDn8fKifAe^2>Y2^azD_@moMZ#ZA$E;7T)fyyfaNy&-@!on`} zkkGp0QLcfPI9c+Fsfm2tv*G~H9#?ZCGG;+_(6#HBdgNjBNIRv*1~|X!?xXS7$=-lA zlfA=^ZtX^QIM2%4p9}`1K$ZJp+#DB+&g*S9ID869bIT%I+f9d~+8-SUkZuviMrL1V z`2BbNtlaR$+;^BxbI9RhNc`;CT?l>zs&fT;_e-MR^3UepJ^)jsf!Do!Z)SzO3h?{! zsh6fEHhlC-fgOMTB3HKdDySU5lkcc+&{@R5b}Y=$I#mV9UfVr58n%4KGo^z|Lg9lu zWmdrn4Wb?!S#-JU$G`2?XOs<0wbp|51Pz0_3zju#iLBAbXt}K z@f??;^F_$TvLb24T)(zHHEvaxT*a2{?C$V!)VZJE?HrW;hhAE&xHsu_@)sR>9XXEn zXz*Q8DAUCxL@=r#$fvzVwrBg--vj>F%D)YfvZB5aQ$uS5b)msMX7v;lFcffG{{RA9 znlN1@j)N44z2ivIBK-;9K&B;)(5zA0s^1w4(dci!^N$!aaR$2wMiO+)qTAD0=Re2~kmzGg!BVhA>$e zH)-dzwKbzRjQw4vRXPTId5P6KTMU#Im!_ey1oiQ}L>Fn*JATZy&34Gtfbbd>J$aI3 zUn{I+1Z-XSrPI6BFqH>7(U0*j1$t85e|`MT?b5RO@EV<@ogj7QJC!1Jv{>dj!|waa z9Cs9eJIC>D)(8L?gPm5`@$o`_qnuH=v$%OWzM={Unu4u=>oSA7F%4fglJj$)kH>`h zZe|kv-9QDz|K%Yh$ZB}VsOi7I%-?i1@?)#NIl){u)zsk(k>R#Rae_nndWAB#n;qg7 z8b7#LfCR#}*+)|ZtIinXi?6mK_0|;r;(w)<7tJNA`$X_*hH6Oi9tnidoRkx&M9 z(oxl3Rgt}GU;m&p$nxT~f3iwJv4E7eN&O2d=s=REEP_fHzPHakeuQ<9{Mb+)V6BmEpF-3q5;!^zt}i_Ke-f`=TwUJ^k}()GeBt*y-c&DqKvi=Pu6e&z>%t z>5f+@B+V`-fXj^Vio1raM%4*c3=AVNOC`2D(8^=}KT)Fscj1$2jHoz#!({{^P(ehq zmg;gaj_1dT0z-fCE1VWUC?U}n2!j}Je@)XM&nbk;>o>R~(#4o+lST}V*kfHO5^mufUl{p0fNH$0)suh5N+B-V@N#icsmd4WC1mkh1`^xO7JrO!#v=@M#20jG3(G z`=vc(bF}15Zlfm!)wL-AT~XAV(=R_SOL>eodOGm!(7qjT&XA zBmSHLIq}v`>V+=BI}d&tWru~JeN}vj!!(&&qoGz6>KJFM(WI@_c68RLX$Q23i3w1i z4pr@>YDUESd5@?oip!rVkmd^q-&zz&lc0a3XYu@XvmznUJdEUg`KrG3&5y6-F5TzN zT;1n##?!B9`M4an+ED=^>ZYX-$DP+&&aQN-W8TP%-Lx5d-UTRSlru8aKd&MXLKrU? zLq9qb*0{gjGjlK;AD)5^X(;e$sfZ3x!DOr4=Jek)=Zs9Jd~Mmk$8o&2?qHyu)?4$a z&{RIm_*wNT#zRG|X=Km}r_+g_VK^*ezgZ4?<)D@cX=v!F;43jf+F2ls>b%ZJHu&&jx%fuVVbW|!G9Pmln`aK?wY?+S?)Q@D;si?8PAy2a+QCqBddVVq0* zJY#VroSEbI%i44l_^!Po#&KWLu|KfHu72Ew*F~EU(w4WW`GPFOinKLw1wfE)Vh(*X zy%<>v$BW?)w)?DSo7bA$IluUQJEN9XLxZMFHvV4yr+4{K7Af4q`XlR0ezaLhN6t|X zzd~UhIeN2h70_oT&HQ&yu|tt|`39{I3fK#~*nK>LZJ}W#3-)Abcmt()MV4-7Y;gg$ zv&m=PN50g^3cBQeG(T@U zh8lIRaKP0H4us(HE@Sc^uWX(o!vvS}EsG-Ml2oG~Uqfghr-e36MVW(DCH7J_seYlZ zd6q$I;Vy@-LlOSHolOf)rt-YJQaReA*HNL_F}*oWACido>Q(L;;<+PN|HOrA6ce1H zpq35-A)vOdE)vK2iTJ`67k3;P4`Kk6Eh#MmU_AelRhCK+_Xz=IF>1$;65iyx*2Ew2 za-$h^lG~g{gNDnw!Y@IO9Xz%OL;6F1WW}KTT&9V>@`Rz*-NnAYqU5?eB?j?2RoJ6s z`d&>7gv{kalX*T>=6=(sjrUw;_B>Qa;_tAX5y}PFIy(j7KT+2JP!dXouFCAN$?3hM zjQ(0&LbgXjDQ6O&pF7NCqOGt(LSDNrsJVcHgWxTU1#FMnpwZIsN|&D;J%(Hg3541G zE6tcB@0c!f(Judu#MmQZha}q8sNY|KqQ9N_;&1)|61n{P|5_j@ho;dij^7=FmjByA z(PrcV*Z`3|5&Q#iDfmCE_^v#gS&-1%^m{ahb3;iWG!am_wRmKmJxed%(t+ArmNhpK zVtq(#FERdl#WoZCc{k5OZZ)4$q3L#Lbylx>W|^V)xU1NN(}_@Py6(hZU9;VhcQ;>2y=hDj`%; z#wxd)nBzQ#-9fxzEDgXLtu7{16&S(Nav@6Y<`>5}9MZil>8zbBHXpBQZ9hPZh1=ip z$;qn_#Vx%P!4QBH)h#3X{;TX!zP-Ej4 z!i^Q`ApW(>E~<+pHjbvi#=mTfjV>K>+#dttM?aK8XM`3IsxzpMra$rd-tsMN-f2Id zz!MXqu~r`*|O9RN#c zMq4GRBj-G}>V>DjRS6i!F^q600KXAKmz+(`K0kL&ie{13x@l*o?jhzqLEV#D+=*By zq_GQqp1vDo*<+HR%Fx*CX=laQx;EIVXuB9cM1z-yGer*3VsRCxNxeuI`^^xApv3C> zipu>*4?cqtqPA%armFZnW)ceWu@`QBt{OmTs;~(KwsiK5%4hS($R&`%5dFnD1CGA3 zAx22tw^Udg+0O%OC0FVslP|*WO76&hOa_}%@Se}fUjggBwM6DT8!0Y0H^lWkB%z+y zfiXR^WR#sd*0vC}s#NGNZ`4RICapeP^iG+rhq+?L6}(n0UUbu6JERKC?%jwQ;+k-D zMwkdv=#R=@=fEL$QbdU;;Ujb`7}rj|K#Eo)j0IRLN)$gnG%JKfWq#Htq9=|!RS0q z`_fU2I+%fn)L;nXdDu^{f_^xUP}^zIKGPtDNDb+m8F?sRy+|j&>0Iuk`+4ao*I}*f zAf5T|io{G3eV{CiA{9p`=ZW37|1IQ}=s}ZxZ%!-}6`~3ycRWL|+Nm?ZX@w_8;z!5R zpdA@IESbdfFrTin-ImkfjF=;_F8`l`90;4^|ktgYgts_}^@z-E7uP%_P6B75&lqes?TV5ZLke?P2D4rw&qN z=4opCwdfWRe7a5CNh#uT{XFO+k_2Tx6#+7R3zUz{q8`Nd()eB`cuAucT_^p1iMl)o z85I`no9~fmDkqjqqPEbKaRL|03Dzzf-*6heZ)Vh8;QjFVi%-FKg?rE@dP(%`;!0pp zIehzhnCWau!9K3Iyqe@j&6pZTkJSksa z3LauR#+BICjM7J#;f9x;zX={jX6n|{K`{~v?jpttGDcvc+shu2xB+cH%i=miHh_!n zDE2;fwQ;TrTqZI-#u?2IEY6>_0tkD*%CHzyX70?4aPAYsf&|56Lr+N%oQS&ZrrEWz zVc&tnawaGeAWmx77D8C6ojQ?*Lh_={0CrvJ6s*t5Sb_g+vGIm|b44S=e}I4;!8+L$ zMSl?{RgQ~>mn09^>iEr_u9Z3K{X8-zzwp8~o(z4G|1?dkCU6|X3@0DG$2(v#p)qig zOA;UgjmeX|%!nkWYPyr%XA>2y;iC5*gh!}CrRNM=tLYU+)fQY zYiZcs(Y%vn1*r)CgN|awioUomgFd2d;}{!3*_KwrND$xuNB04W5NGd8lPHf^+DZf+ z-UX1IEIpB2+vR&Md{^IpEnBRu>*Ip)2uv{Bjv=HD>fs}v)Vtwv&C)Y57) zfX4jFxJPI1qLo(X#?{DOxOGhXCBdDZgz*P$-+)%Jt^kx&a6?eeyrSwn{ zqdBl8Gj0mbKGb7kh8@_wjOy*wOy``BtMsQ;p~Q}gm_s~q0HH}HocPTlRnUhWoPydb zLa4mI{o3_PlcioOWDeCg`*Jr9gjjyHiNY{VaaP8QovB&2mv7mf<6{nPp+1~E_wlf% z-{|8*Lc1}zqCTTO1tgNn6+`1W7GIkcq$3uuKjziJ{MMjGk)q811BMizj%Xk)xWXyr z+6Ym3Nr0UE4vXak71kU96p+G}tSfU;AypoFz1mIsm z-NCH&)6t6?65}JdqX?y#biws5+#uRX@&cGPmA*!R%5Pvz?M;#CzV>*pylol-4sO!%@lLuDdM@)@yV4R6J6pe-G2^y6f0e*}AA*MVnX zql+y5teuax;yffao)}y?pgpg3TLvyEcXf>1Ku39r9-Zx$USaN&!acTCUw0B4;H(fP zA*4*0-E|br#+rT!@wP-KRtR@4pqD}SE4NE`=by|QvHW@UBc6KGL@>7BaBbrk94!kr zB~&nq+sN1e&11wOMQnar6V?F#K(kF75EVkRy)B!?Z;+L?PLN_5U!dE7_?Lil({Gp3 zYAwiG82yajeTeJH4gl&|{gCgANm_0bFo#VMC=Gx=*Ka|ltjL3ThnA+o?aIdfJBtOM z|ETxrjvh%G%!5(@4D`6uW6J((yt~!GH?`IGMw)Io=u4qpYHI~llD)Bt^gzsjUntM` zO61m~_P)cgSjDiRo9uqH8V%!bha^?KL4(8mP5Ok8zoi=;8Wt_>%mz#feq44;+D55xC{1y6 z#Rsp0a4oCgZtZk5b=#RaA!`!=25PU{!E8CZz#j2j@k}WHCMkgeEs+mj-E{-YO$J+k z{tAVah6eS%jc=Vw;kcW@T;V%OejD~+qAHfx#j^OTr_oNUE~$vuziTKeTd&RjBsF_f zf4*h~M87?lr(}*D<(0^v!`QOkD&?urRe)Pi8YOebi^=Y!Mx@bRk{$}D(*e5-rfO!} zsOWY}0O`$a21-`rbrQKu7(Vj}D!M=*2fu&o6ft$Xm ze?A9+c=<2Oee1ihMY!S9bQAu54&YNYY$S%4oY?zhKMzZPW}y^@>nETJ#PzSK^Xs}4U~LR ztEu@?-kgZLS9D?lB$~C^&%Xm{cW-_E0eFL@K6^XV**9e32OP~|vUk9;cBU;uA8&IS->k=s7JGHy|M|hA@GhtL zUPGJ}dGoomQ2H7`V8U1pKOB_Z{9*K5#h0{pW)m4hM9~#nk7O=ffo4Z@v&+oH%5h}X?qnjUHe=q^Or2rje{bO$o-Lxex`;oHg2K9Sf20Db& z)J)9i)UL$u#xQQ0G^>QDDI`jtVN5+4s_B$G60(>F4%B${C~aNF0waVlWdny8*Qg!+ zY-0E18K=xnutru&&mr~c??=Bd?BRuh=V16WHM(>ypHCzJ8+pP*Jz+xOL#im$MF$86E;8lb=ogmY0zwQ(VR9N*7+P3o_n< z`D>hx_&y7L%s1q8J_W3OM8S}qquQ!*!BgmZwd}{@DwQVrQmrE(GCvfWJzX9cn1CB+ z-a=kR+NHVm4jr~PVff&6wFz+IclE4Ya%$<9W$6rOQF~bk>Qp*~e9C4#ug*MDwvO(e ziZrpPeW!RVM@A@7AOKG9DxbZM;qf+?4d*hSZIwpL9etg)OHdZs2KRAQk}4jCuX|U{ z(b-4^kuV(WMaI{2CRPcpuV?gm=3_!&J$+nH*3{6gAb_tvlV+}UKgT(WO^En-UVQpj zTZ|7ukU_2{Mv7G|&3JCzaQA~YgvHtBRLnWQR}c%EG3NgGVz_h;wk>Z6WW3;h^1S(f1pZ@C( zFZ_b`+6%?_Ng37$K=6po{8p$@ruv5aJt4g|552PGij=QV4ks#9btjdT;2IM}h?Guu z4n&x3nEj4LKB`W@Cw@K&=S`T^6S9I3@YNaM1|xL6Wm0AO8liD2VN1J-nAq?4xZIe0 z>Y9JHCw9QaUKS1!e-FlqUXoelzUm`jEG`XfA41@kk7o_re}NjxrNuKs{*D?Kt1;PH zcB8(++n;fefS^F>+>AUZeQ3U(rauNw+BE`hnEbA;1v5!ea@89>-vrZ;ie6_wOc`oO zUU>!jdj!wgnjFxcNAP{025>`x@B4KRXCIb0hAaP&++|a=u%pm`3R*u&*ka0#%#~kmHd* zV=CJc%Qq0<{X@)3XGgvhC?>U;b=9)$8RmB`*_w|BkUG}=KIVp(73*9Si7fH;{eZGG zPoCk4lc6%IKuK7CeCo#qY*^uuVqxF_y*OL`HtcZnBT#%3ajZk6Wokd12UX_(MJxAO zxgUqj!9adH=-+{=-$BC`<&y`z?r9#nrOMna4N?sGz|*R<%vn6=74QjRj4+}ZIYKQ0 zISH#?%~JVplT4?sgTJGJYP_Jj-JKS0z+ppTzJm2cz9)mVRN9dKK}5qtgqHAVeIN`; zWa*66r{K|BdqDN5vTb@{Ut!H+zyVSTXys&tKaMhoOwqWEt@g2sK}hqeM*5=N6^iyH zz%^Tva!}K2?uyv*S~ZNUdTv=Pd*2Ec3H&$&j1(n7*_H*7QO^!%&j{_?&&3N3J-k|l zmqN7+_Uni!NE{|4U0nC0hR4U?KaYe|>7Y+V8#^I$%t`l;t(RU!#@Cw{J10` zy81dMy%-1$exk>zS%J>@*wN=JjS=jr8dkC%iiloj{NQIV%%~Sm4pT2+_S9B?Ebggy zqdFwytWvG7Gj(?rI?&Ksh0mq+O7TadRpsH$FCZBI$hI`_!U+zf0OUqy8VjC~XDBg+ z0~pxwqC!=;6M)rd^TJ3HY<|+n0c>(e>nr2Z1psg!RSma9#ZaCuYzKapa6zl1^uyR`;ifCP%V?2)B%_tXL@HiqmNmB3?$fLP&k}7ifb0$~`x)`LtsZ{#L zOzKg8Z&buSU*$GU!7O$9X6u+xvcjq^DbA}zuHAl5l(hmVq=GZ|U52fdpTuyiI>MV; z*fm`Gs_i+YlBn9=j+>?TLzWaO7gtqEK(z5YPJihSLO}J9`AMn^;vWU~k*P3Fs+p{i ze0TuSSZG~WxqFx_s-zNi#g+i2sh+0F|G?+cDQqOX&aIwmdP zm;joU!ea&|SU*+{NVE&(Qg;sf$E^7N;TW__7@}k&(mr&D#g&EYhtzg_;>02eKw4_P zKlEDr3bH|FS~xlfF`{E?#eDd1h9`G#CeYD;>)wi16Z{9z-Kg*xsgzg}X>%1?VMC6H zmogIh+twxt~p+qBqw^A>1g+%aCQGFzn7^#e0N|&`+ z1>rFb`r=}3DXFOmF*njH0lO36XW^ON97T**K-=`4jQ%p_kNtttt)=}U&Y9%nCocb> zH`Acr;1$FLw2!A+a(@_Th71!2s2b&Btq=~4%l)^rg&Fn}Wl! zucM405RSVofoiQ6O6Xe7drJ$K*U=$@W;HxV;A?CpPjCi=nR%>+PtPpVw zS`(v2ojsS==c)bXy7&8tp#l#2hc~^2ax@ee94$k|vN_#{r}Fal4tfZ)c(bw8Y&{oj zN!iDVRyopeG3V{hdT{R|E^3`|Pwv=KE&wpVsAuo4*_I8u7hMnlj75q|V!p}%9j)7U zqme1}WyP%o?jMinLoJ?tik4}={j zknbF)KEw_wciU9oT{GCVp60p%(8|VRMhTvxeDh3T@8QeFSqkZ)98gVB#EcRLPgS>q zgk(+8*;;fw^I3f9XuP*)-e0Vf;jE;s?_`;TR)J(UI9(9xdFOOaYNrm2Cs zh)~5zzeM3W&0xseW~G8U*i^AievwlTO~v}4D}GXh3j*5NJtoVxQS$<92e=?aWT!+4&~|Itx8Si25@imyWNPE?zBcZvY{QV82Io z(j?L1FK89i4|7qwgAwQtSy=rMYhGI{Gz1TM`udN@aLk3KO-Hu9Ux5j1OnDv8gCo9a z$=b0pz9!L7;nzQ3_tSLC_h4>vqBYbntR9xz$6WjQ#mbyc6S<>)D!?tJMeTzxO5cvj zC}0z|?*#^=3tOX(L7yaSlATor#~hqR=#L+2*mPA3x(K)tp=nR3gbx-GP|=$^+TL>p z0~&U|Y;&(@k`zxadp%1BN_Te1^Q1;BN;kli+jOqmWqilzljTW%B*D=0YWC3k({>D- zelAiMDpg&{lpw5J2l!O?_M~sCl6k~`UJtY&LM0bKxp-;g4qEGECFT*v{AM2z1V z9!LXMDYI}oQLx!MHU2rM+RX;xyEIk3}RjzvCKYdp|raXt%sDE8J7`k_*||9VR1wv+D7;!+jTR#n{I&}M#y z;7Fzni(jj;p89UHYF%9i+~MV;%Lpl^1UM)zZwdygDNWII%+y6!=#!Isp(aA=kB=6BeNI(`>OqlbQhfc(f z0&Afv5%clMO`&}N*Na#RYDxMy={NUl-h{8YXBYn6o7bmniO0nqLOpB)s-+f$V8dO^FD zFCB8baD8ZFb(Bn`==&g-X5Zvv~mr0EWK$3%j(NvFB|d6d11fM2I;CKXQh5zzGXo=QSvvS8 zhRrRy^IDwcOX+J8cQmBHx!14VU@bqdY!TYujY@J;Nra;W^YwO_5?;0p3{ux>4$1lS zxXjF~CJf3@?(<3gngDV?Bv9_o%vaHYPD8pbUGLniNM!l7bm5S-vktzlfNim>F(WP@6SzV%M z5RRImXe7eKLJg z2S2`5O+(#(6XQ!|J0t`3-biX-vo1+R%bUUO{N}gx5oNb_au#TAlexZ2)fg;Mtx()9 zaf)pZcT8-w8GK2k77LEnj%vf-G30dUsM|sc%S~1>uTF7Pnh{CqSf?4I^DlFK{&Nz9 zE5t+;29h2>UrjL91*LigZ{n4X98P0tposD(4dmv&2?hzX%iR+Rj2__OWgQ#Jeb?wM zy^FFNJM+#mWC37ufJ5a-NV9IyQOK*_zOxat!BdjfuEYtFVZiPu)2)5)$dl_8aY_0q z8n)A;lTqsKi@#Gjt=)2Kv0=3S&>sk6IoLti0uOn6po@d%miPp$1}Us;FjR1~3)i96 z^Bh9mP08#xL5_Y}p}Yyt05h#5|MvLeFQiVBXOm7DLiDMoE{zZFo`SnU;(4?rQe0Zi z!?*xpz~*ReWipSGT#koJjA&IFf)OTRJs(#9SKc4(>S%#Q7*0Ym^h={=Q1%txBY8vQ zXkRa{%@#d&`h)-eY8V9P-&~Uo?lmD9yjAx2R{rQB-8vaQSM;nG_Eu}o418zw5VJR- zGUO?kzl}oGaoRTWiq$h40&350%)g4NRSTKMB2XThl?jYxGk<6!)kuB8Nj=VUORcTF zTKj~rPb-)e6h-!@V*$`~$?9l{?AIdm+lO1Ae5J@hxe{?$g_3Ut3JZ||3{(XHuZP}D z1mL0BK{p}g+`=UEJkiIVqr)gRa=ixy^Tjj_#E+pG1kt{LHkW`}hG-wJQTy<4jM4&w zadAKlsDnh_#roPKYa#-6h9_WMLhL$&yCvsGxc)G1B5B$~{1TfGa{iP9i0 zz^1`&%SMfSyB*v^V;RVKd`%$cL-(u``2V}Zk8xV8i`rqc^Sq*Nu#{I`wi!D31%=!eN#b`osjkmQn8;EtUXPY2?u}a^@kQP9 zc7eo`WXak4Va6u6E5y5)X=-Pk+k0_PWpL{Ge2>E+nlop+NFAg>NtcbdT&scgvIhgPxjBKIg{$1Z;?OuofGv;`LSG{7L?9M8 zN$nsh>kE3ggK?RQY;(oJC-=CP?(PuWCBw`=|IGI=Yx<$r>gw**552m&s?Irk1MFPi2|9OU%%GN& zX%rPGV|SFJoP7OQ+;gG*~8jB^Aeg7LlQ7D<_E(2@gY*G+Q@>5ZLG zejl3>YFDY|;wswsXdB40aP}|`A&d5Jd2edSE2T~i151|SKOtx%q~?%zq3pwri*MQP z=Vf-eZE1^m>pfZK!bMSf@A&4N7wh1C!#yhnk_zLD)Ah-d{g zC(@j`AS2EeJ2W|U(h$=_h&lSPT~D%m%|jaazSv~BpJX1`HF&6uFk)2jS1PUq`gO$I zyp-_bn-f6SB0Lo@BXYv$9@rkInZ>b2+Y|W--VT|NAY6^0u$~$V_sP5F)2*_V7;XbM z*)xfii!M@uXk5)$5E8eQ6J-{AJ}Bzznw=Y`2$yAM2{NVqom1vUlF>~F^4{!31AyTs`;^9hy8Mh|EKin`ecg_J< zGXBrUuvwpA^0dx+ED6{!@P@?5!oJp<3g*b4R}ZST#K2&TdPctZLTbM3sQNe2R0 zRg<U(mmkTDfpE;x>X)0fpJ& zyiUgFA?AZI{5-ttTMCicZ*97_bYo1W3Zw||OJ_hw4T)HbmZ$^=5TheedjK5b{$k1j zp)B;Sb~bGUR!YvNSg7VPHTL%KlJq)@tb$J~1sK*Q&igpf^zht%o!sq_iebAK`F$D_ z=_#J8`&il>RZikvaSteaGW#iItn%w>@v)3NoUN_>+70}LHUc~bH<3;Vs51l(MM?7X zueNI80|CE4ZI02Uhe5uLN{xbc4nPfI+$kMlrbj?aPt)y3{V*J)Q?*8TGI#GSSq6gs z@axVv;O7yC#`D@gK*N7Y<^3TX&FPc*7Z3Z=Dvb8VB7!A)FrM;+~r2ll)%i zKQnVPAq+b^-2X>%qmzFc?!$U7&0GACQfao+(=OD+xz9m|{z{4DjKVCJ;Ca1|UQ zU%4N%Cq-xsbAAuaxp}oLM*((mXO#w}E=#Z#G&hcsx1mlb=Ov#2%W_)2x=k9wY27cO zvo#FeT}Xn}2naILH+J|pN5qdPiz@9C`Yc_@H)$s}cO%TXIV5m5%E6B9ZbA#?Nz!7EJ}k! zx10Fp!zK`6j6;Cf*1|5L`pZKI)59Rfy4TBl)Ty=i_Iz+q^$)L{0WU=6}rWyS&81{)2)gmiG5ITw%! zTigFmUrB<~^^hfT8al`?CC<7PEamM$dh1H(wVcIx)Ic&S(>M9Bz&#hv6knY34c+bv z(j|@vRj=Mh?u!RgEf1)TBz%3>VUARaBkzkCKXol^M-tqN@eUUNf@5bxRMaPU}Bwqe|>=9A$*@)BBMad%>de^syFu&GtFdChuT zlI4__)ECF|w0ex~iWFcfdzip?PH+@p5F&Bb!qY$9Sp%1W5Z5ukoG4+!|CDf7W+tRoQ?6(f4ednGh4aJmZ9qjt92V|rJi0a z8=+t>eHZUlD`DM^?C|2W?WY79u_E{#LYah+2z)yvjOpc$+d8j^Uhs|^VbpW(bKq+6 z?A%KeY4jG#{J0T;??Shui`=hB7FH=1h>j#VoLLY=o*D%s}2V$N4%uP3AT|fz>rKKu2-XW8=z<1 zkCyCiXN~zXjKh)8860^wV==<$5XKWNk?1L-uZCfNf9mtO@O;K*3WDqovl6hs8BZQT zC(SwwnCl##+GaZLyd9}uxY8gBj-bscl=XV-=NzCAcjoP6yc^-uE%OY|CX}*O`m|gO z+X8qv0_!z@7$8o{7!_aF-N!x0DSN6TeFp@`;z$>1(KYnjWDv`46RPazI55OSo<<$7 z_l21ZpXdr)JL(3V2K8!XY4d@e$KWwh>dr=Z)2&1vspLYo6)2dO;7Ik-h^T0-U71(v zmi$<22nuWaI&ZAK4;v{xgb91LYEen}2(+~o39khmmjMWD`DbfaF!+CcOa$JWHey~5 zj1?{shTCz1ODtLZIdw82-tu%|{{iBsKNrOVA?%M%f)-V>TM|bhnHZ3v*}lSEq0iMi z=_o2($DP(VWEEBc%5Ov+x?6mFmYPCEsO@UX1)50Ny(s)H>Px@)? zMy_MoSY$0w)-b#cLGeiYYtnQE{a7@xa{G+$Us;&IRO`g8 z>R2k$5I0Y9AdCe>_Y?H z?nV=PdyZ(OFjKFC5cND`N7Z4_o%p^jPCHD)u7WKv{B60g>PC#P{a*?HO9oDe6g)9P zVH9)7$*4}mRB;j6#)P6qkleae6pLwB;)K7`Yk?yCj*Xo^9%|G69*#vDsBs9NpvMT~ zH`VPc3qe|6Htx?6DNM$mRn?!16Kzr-HXY|!3z_Km{q9=7UO5p;^^s`wI#Mc}GB8-9 zP0=rFieK#B(vbD6*(Xd;o2Ezs&U^o(zgVFF@%oYfh{{sahl;LVKG;>U)hfx&aTfmF-(zjh*wISk}fSrjk@w(5QVF=yd(~5ns>pVKVp@YKiCWBlnTP z!h%2;x=sC=T%yxdZwkq(n^#NbxmITx0yu{6cZ|l-mr{pY>y93aYrvi@{8P2uxfIXv z?xa_i`%J3qZ{22;U8axODZ;{_qwWe{<#}|M<5+N!E7DxR-_iNZyUgZ@vKN{yzEUyM z3FwDTq7nb~u3#S&iP-}^X{u-bbvC!4X=g-P+r7Rv44*kV-+W~DjI47PX>|Q}e>40N z4jRI}9m`IoGN(_di7uH(kYEQ2IX+yRyU91QBobPxE>_YZF{zUMR|W3z^VGb&s-Nxg z*&oSS5)fQ|Sx$uHq(nh8W&;tpZ(ILu~syNHsFRR={9PCXo@q-3Dud zJ#VLkRlPO`HeDQ>7?;Y<*5oCbpdshPl-AezxYon%okLaJ{Xt*mqibhFgI6e| zrBv&ay6Ev>#y$N9u$AtrU;aBOcVbm>iU(J5v{YTGkSvFI)fkW3;G`dIQ5buChusHI z9nTj*6)+#V8F?hdph@XKinjU+FBV?V1=#n6(Im&VvRC{yq$xa4wA7?MqMPNilNl(k z3rQ48v7lBaa2;=kU0Xa;l)&)m0L*z5&Kbb(4aZdtJ&F*9%DhwfUU>GTWu$OS|tPIBjr#% zkC0{*NaE&iT-Mg>XAl4a_mcpcC^cCg|^I5f;uA~u?V%GNqMcYAPciT2Hku5(fMn_RYp@6wf;S<&5A?Y(q6 zESauZmtMFmtdg)|4utTzElz(Fom2TusynM2_@tNXAehJC_qt zA+F)MJ**4fd%Q*p+x?T8t(I8_uVySH-=;CIjH_MXnxUV#P9liutcxs!zB+6Xu4Qe9 zdlun|qj&p$EN5-5Jqk@-+aQd7GN}ULB&F+m1=H1~OMkcsdj48a6keRB3cXjy3{z?KICv_M{M3?UF2i+pI2NbirNP$&*;s2 z-fgj(mm5POL{7)^Kur9)bS^Z54qdYou-{UvtwqpDMsX zL8+Zr(j5?h83;6FyR77jut;_h+Cj(XfdX|t_!0PWoRhw|=T{zRMlz%T5{QG=E4dAr zH87A`{rQY4NKk^8FP+c8G6V3S#WxyQ1idkLmzxgUj_o4!J$+>%H#FMk&Et-PcBQ=9 zxi;WoS)nmrmJimehd-YXFC(`jxZz0VaU_#V zP8eJIk=frp1{{`|&!YDHOpIL4d-#PylE4;N_j>@bQjr2_n!1*5CN)l3J)t=-l>$Qz zwv;Am!)h>AP{24}FL>xWVjd-NzTkJ4wc#0IzAEAt#!{XvwJ-`~K%w&~*Bpgz_%qZ0 zGeU;6{Ri+Qo8Y)K05kc*I+>yP{#pNsju>_}E!5s;!`KUT|7v6tm0vZuhb}mgi@wb~ z#gtGbqvZSb&FEfU>ZGS*Ev)j%j8Y}J$crn1pSb>-Z<2$OGt!Sm9j{Q3wJ@C^jCl=c zQ#q7&?)OCA*ex1)?(0%iI6xx!-sCWazy(L0`ev4R@Os7Uv4uIWT8Y?p{WwC!qPogF z$H**A)PDxOnlHW5=k9~^sJ~>2X16dk4_OR_EaU4O)af|i=CkqMBo(Udxk#Ah3_0U( z;nfAk8mB-;COmj2cOI$Z_q|5Vi32AYekCz)vdLk$BVv z-gKRvbjh(Oh7xhTE%DgpnTy+`uzD~J+S{hO=yFX?Avvh{$G564JuXW)ieK%ql7zUa zJrG0VU@F6x_z7iBq5zi3^*Odq;tC-^aL+`~qVy!B{6e2$bnJqt(0GmH>LLmFKiX^gC#YnApqewW19tJ&raEQ-T|Fs$+vU}lvFp*k!st>_p{^rqneo)$`)RCrBy2cw z89D$h2~sX5g7BSDvH2>i+o+8Nq%{L3Zj;{C-U{8AtkD)4xanc3q{i8FVoe~ zk6F{FiU4sKMLZ2mWoZO-b1eFTM#C6G8Z8sqy~m6$R6z<7ME(MfBgS&10uyo@`;C^k zmJoJ8%PP9W^XPPAyNGNbj%4@#&(iTAY-6^$tS&Q&fmC52-@H$H4(IfOc(H~;elfm2 zFiO^a=PbH}()#6$)d=9Q5uj+t&D7Z%3+>`0Z9xnLG=*}A zKwbDDmvd6p_&#ez?LdDWCsz#%BA63&$l>|SK46r=oGD@%t}>hz0bQ@}aS0$t|Dl_i zMmJqVxJ=^!dt(zU z^EYDxzHvNKv2Cs4-Vfz1Z|`!VOZu4g6q_aKhw(6izyT3MyhnwTX5*=FZ@3_DbjwMS6xH`c1qaRuo)ngUX9e+TCd%LL<9T#AW`6V z&Tvs{MmC+CqYrCsc1=7kj}ZQx9~BL zz$<|h>MiDXDVP(V^n+C~q%lI8qiLoF^#ovuYOdVv=6gK}EEGWCVCCJXPS>6#DR_KPkulg&@?g=74tM~~yaS%(>I z1|xYdVxdZ)ao?V#T-$4bH}*8Czy7vHiF*C;JVec2*u+JbAyC%NTf!(@%p81dr}(OD z6&{C~!y{%8_CrBCN&|;fh_1iNLrs8{Azc_z#5WHoL)yL?v1+}SJ0;Ia-R2}Us<|Z6 zf9yX}C3pV;nAk4b{gj@G{~XAg8qNbeu_N44+%J5xi(I5sNbSDLv1vk*X!$P1KuWRHgxUO( z$DtyIpgIwhh4YpW7GQbw?9NTEu&tcge%)nU>9a9*e7}x%?1m|{$xcJ;tw6^rj;!oz zm$bgq^z%$6iwZs=NIXD?pMrpTKc_{gw>N^p6opu&wFads7#fa^V2n|#t5n*RW9ebKYO=)JQ% z6*HSkkAY{sq)B!1;7+mDk?S#n=%IZvQca0tq?Pzo7Aaw0)w0k_zRAq*^ao3&k_xaT zGV@48x|At^=W2}uj0HFiw!Q@hSP}j5%WyDv^AH^~^8EeSDb9(Q++2^=lw4S;)`rom_9pyH{R+=aE7J;HRjrg6@CEo z;VD*=h8#3gAeSM@o{>ygc=py?D1N+{Z{D#J9rfpEdNENYL zTRD^^!PHG!*g1Wg)N{KVVr@M#m4B*JjNEmbYq^hd&!LnVG6j}|Y;_+b4Cbn1 z=Lutts5wPVQG`mQ8J3hbhYM|h6tGdmu)zR9j14VY6hcb6Mc00 z0*K|ePG_$Vpgq;6;-h+f3TgshyID@m9-t;n&Q9I?K78&m)-bqeD^>x17#Qk@%6ErB zk4e^&qAqmGqKN>rhXV&wGDKD`b$YtCQ3jX2Ute}z2~dl3$wTk(`jAcZx(zG4f=eE= zx94Uu?L9~J72lOcvjNZ{NYTlZk0xoq48b(ZpAq9zUD(XmWZcV(n3p~IdIyS+z~BIA zIih82@5Ul13v)!~J81Kf+E2IR8+-fzBAaXkvNC;d`kahmbRTsJto&D7?)js||2c@I z%)iwvak{9+oh1AW-2Cm!dlmSvl{ZGr9+ml>w~tyV-us{R;fq&3MLogONxm7lD^t`o zP0ZRA{k9yzgAwpCzAAID_9CrQ7IJtzp>1&qBp9}Lh;EAp0rL1~td0yg9wO}7ZbN%m zc?@3TU0rr-tB0kN5wSb0#j2$B4G}j7SA_azB7C#gewf-*T>Kxjo#RgKzHD)2G%u2u zIT?q@6(dY)>`#z37${2h%6n!ansxjJ zM@(EY2fm-W#F((~NQEkz!+55oyipveQw>A-y1ZJ|mk}bI*Inf+sX`a`O`7<1*DC7i zHC&N6PO9Wj5w5K>4!JPIqcy<+i@^-$9=Z-z`BUZk1nQ)r{(#rWyFzlPCXQKVazahpxq%^IOr4(9QoIfb00c-6*|XOFNbTo5H#@ zXk~-$A>pO%r*1?uTOY8I^AGzQg~FL-BIX3 z!zyqFMat_)*MjBpXu#RN!uEx#$g`lnr3HE3j%8%9Gf?ii3|E8!UiaWeFWQ zpnoMm>JFtRMTB44sew5aNW-Wgh3;a1!(F^Ww120xp6*^|x56i>^VU(HgRK)t^oK(q zs$ZC|>=+AXcJLx-j)Wcf)wwXT%T~k%BoU%i2rD1Vtu5lIsG_aJt}ihP9rcy!&$*!p z9dLd;k)-2{q7p-M6gM7fG>T_`hAOJT2mUU*gB696{hEpr54XUCo_>^OQirep3Kh~P zXbIU|^K$sB6jM0UtbP5LjCu%83`JNidO4z9i3)HE-ja#kMvMfyOm=%tfM2;gZ?KZw zqn+w7NL?pJN)`ODaY~711rO=!%C(;!j5WSMX77YgSPEg5s$uVip^3WnLlY3dq1X?w z^G49ll2*Y>^$ydYMO&9C?t+>%byP{5q5#Wt!K)x++bzf>W|26^=wBgAgFu(ZRceC^>jLMT=dZP~j^}AIgI#Pj+Byo}r&gqbr2H4tp-I!e*2C(x(u z!SGD8c3e3tSG+g8lgwlTvS0v$jP&Hlpo_^XO{MrNuWQnaenG54K-h`Oc#z{cS6M2N zfg{O`nMCAz3g&b)df0a)Ws#c~$pA|dH)c6qRpR`;LJGEb(YfW^bQ-JXgF~ov2axuN zr|iyy8_M$_MY7oQ0X4v40ma&+cFvV3Dt5_>j@3z`$PKEENOW?v`(*a02b zvAZH$4lE+>FGiHh@-ytn=owQ^%@Cno60p5KP#9p#w9#DrsL}@ENr=dmBc3OEia@A0 zK~6PRQB`G>GfMdeKFtI2!Cl>z{-`JUJV`(20v?6;kLmu$?4G?3I+}Qsn76r|h?!6vZjEGHyL%pKI>M_y* zcD`&HXeg)WbufYg+TJwPaBvJthmVeSKI1S_)x7acj=+t|3hynPw2Sa#HtAov!hf$u+!=m6KRCE^jqU~)d?BFpIVz%!#GTy~^xlj*Bh85ZzPF^6-z(_`S7klh z6_f_9h{VTxe~lyx6Zh-hWMTPq1xyFkpB~wure6`|luaZBU%DPS2vr@%g*WSmONrYA z?hRQ+ZYQ8wT1urSg0v0F-F<$>S{eqAx<*+km(qo+kx8g&BWirTlPs<^($Txj6(ZNN zKrw!(;U=Eq%P5V7<^pkzdaprjqLXmm(9uaO5o_Q8R#b$eQUHN&0mzW9T=@nRK2+Xf z5sOfmjYxc5Xv@AR^GO( zE~tIXHSi7;Ql4c8pp|rs%Me_j8eX<5dJ$PAJ>gd zQGwqBaeuU4gbQqdhCkZqr!qxK);&7on;^Uy{z&|C^4X2(QHuaU??`1@@98@ATNITj zHI@b@J+~pG0QngJ**h@odI7fny701_C;+5hb$arYU$EkP!><`0QR3a1Sojo6v8J|} zG~R_E%V5`X?WR~x#e~wJL_{LO&h%RosfOCAW%H;r44AU#F-Iz!zp^tMeImmetoxkL zAC0&nF9*y9&)}~UYQKOAKJW)bWDw}JEBd;tuttFXM6u2htws3yuUBDXacBf{bW3!2 z!G@p|oc$qC5lIwjdO`(QTGnVFf^y0SoH*vUu+RA2e4J%09xLFt zTrtv|lkghe&+B8(hggz7hTCxORYs$5BEtu3(kBS?ER*vs#!TSP?*^3N5aOELu? z+;N&Sei^^%*HkmiTdK}Ysz=zuN{$|amURh91=7(^zCu_*xrj#lo_?F#Z^KicINqft zoCjV`qsD-=06#}B6*#D60j-f+DYDsx!tO2ot^?GHo@3wk;R%OfZyelK03-IXyy`UyMd79pW?lmQ|6&JTO#X_b{*#|4*Q!cm2}{! ziL#G0tg|3^-x^c{u>1eIebj@sL^QmX5-Rpy*K@Zj@`gO896X-XT{i}c(*FW;F1E_N ze0ZY^1_aV`N4VXIuTers!J_|rhdh0U_M_tZefPiH)&V@KMw#89{XY{XcLNV!2{3ph zu%@r)HR7(6^_9hjul;3bLy_Gqs58oM{JEC?RL83^fN`OZ&jAaz)5TO{sOFc z{1zG&M~I@l!thJ9a&h8By*%4viop}Tk|z;?T=5RyWSsh)nl1J1E0LRMcDF@?>avRs zAvrzMvh&+Cu;^F5r_F(sbB{iRZ-9ve0$|*tAOug95wZQiyJ-qj#D)`*r@`;IzGA@! zVmyCDyvLppVD-EiGZ6u5gzX3nawL@EL25G&ok2tV`4Uv|uxO;AGJ+_pBotCM8*0^2 zedhVJJ*&Hj3mV!!9{X&kCq9MFgqMC!nwpCk`;t=bCb>&BE}}$v*;SBM^_|#$h=ybU zwF+xsrFEKS%f_|eZ8s3H^g;1au=2Ju8AVA;S%Jc&(Q<+*F z5-nQ#iphlY(L9$LpNH7gl9dl>F@HFAVeG^eoPy3+ju+YfWX0lpe!;4FfaT7{*E_PU zsT|}%EvrR3Cn7D`4Dga90F%U!db`VAoo;t8v#6oP#Z6{TIYo_pkLO(v>+b^+vi$@2 zH(mK2F}EF@)5!|Z8+9P)$JGhxvL`^Q^JQA-?2Y!_ijRsh*vYe7Wnlei9zupFs&$@I zrP#C3l|H#lYlpzm*X(5`Y9GhLFi-l^n62Q#O$7k!@B;(S)+g4KgEY|Puh8(cT<_)n z0oMKKn~GO&>pjK^_AuZ>(0}Zy$=!JV>LE4UVovin;f+s%+2Tu4arM(wOGse24R|c`HJi%^ zkQ$a8W$kelPyoobq_?s#X$kFG?9Hs?3*b^^N`AUCN z>b=iIYeqSp+q|BQvkKx=NSwF~6C(ifVFqXL9)X3ZL@_R4V7xd77*zc9+#GK$3m;tk zpns=?oc{dY&mkXJ!qJ_3V08J4`MZF|&4HUQgc}d`kFGY|RIJ*yz)Jh7Bs)LF^Q6Gn zSsbn^(=D8&7rjSAqe+`;pA~pwcl7+SeAMbVWpuKZ*%RlqDaBm zMfTNm{|O?mLk|LF8i?MKj2q#GE%{r10PTt;3Z;5qAsbdFZdetO3MX@60ieYPC4vFpmd%8?^NU&=|br&ILw zTR+d+ZN4@5A7F1lTIdv_?;a^}VT%f`J%XC51nYZc z$-(9mAyxczZQk)k0bvR%Yd$Z&uVaMPC;BeRf#``1_aAPtqMp%^-vi~sJ@rHx#KtyPv^t-sF6B69P8&89j+(qYH4S(ygX%FEH>qzz%FTEErrG#3YJ%TW;dKbNZ z$x)Rcr)_bDJNG)hwKw3oW)Yw_zaL$whTSw1=)gntv)(O>kjm8W z1rTL80-dul%5JB$wK1al+>`?5?UMQNVV67&3MCL?m-)O*Y4QPp3@!{4N5i?d5aXE)x-aTjO&SSsDFo(hPCW>b`;D@}2zdi(QMC|KqC= z%%<~e9Atswl}GSV>ka^x7iQ#Y#5;QemrD6!?HeM?7w~F9W2Szl_%G-}&tw=fn`BSl zhHvoV6+xC+c=;w@VE|x^fNMPmz*3xf2ci{wm+s#8on`uw@xE>w3~P`T_(9*ii=huA zDmKnSYnTJjDX1?qI6~fsj8@x$2m|CkB8j8WdlN7(4H{~kULz~lrnlL+B!$f0a}V9w z%N9QcP!*t*9Zyor90$P^)k^1Xb1;RrSR~krj4a$IQf%x$>s!r6|!f<0nUW zI3U5WlS{M1?P6_z#4ocm(jzNJUi=jFY>@-=vo@1&qkb|uaR^jDeL1%T-Oc!=>tx6# z@8flCpX!2_QqrwY^|&&%#B)uFu?HQApnx2aJn<_?UgWKJbA~J$H5d+z-^kJih2& zJ2!sd?nI3|P5ZMK3l##PbdJ1)(c;K4Le!~tKMYxQ^q>9Lw=a=YaLa;m(yOoArXM!c zw^~A(V{eNJhmHOm$f+lu|b7PDdEfDA#l^-&CxT7836ked#%4ge}5j(bmj$ZH{%OV z!NV^i7Lxz^o~|Wma~0&xss3O+=@tmkI|MR{N=UGvLrOmY&_{V$v8#T~iXP8|mbj5k z#s!pTC^hL{7z)U+&T-`Gjg#Dl#WaVk` zfUpP+%~VD4J=w`ra;SQomMjyt4CF)GRSI7bx|ym-yP}UT73HiZg@dB&k<{t6aZ)yu zP^?h%BT+^xxoH&XNa8{~`#*q`+sgPiwHw=Rx&S?bV*YOL!<-t}fb&u(4OmPPZioVG z9X?K_gM3=Tc~Hlqfb{Q}9b*Icj*0UJoq%tUr$2|H3{%9u1c-^FWNG;9%8vw`qKX+R zJ7^%lFcoxE@T3r;V0}8QB8Z`&@eCOWr?lHd#CYU43~Z{M{FlVsVStDwMq?Z-NW)|( z%3Zwc1ZD>t z3RWKaoWB?=oFfeQI;Yir%r#*_O%4(-y$QPf<*o#lj(X;cCiV3gQ_oMS?Bj2R6+aCl zkCe7pZkOn z0pV4D4~`cgnzy$x7?;BIG)q8;-;L{8Q66uD)tGKhE&?1y&O9auLkdgbg0wf=`3)gMYdj5^ zG&-BsFqIU!fdW)?hzcrqRP1uOHKW2l0H2~SjWh&wy}II(>SYQ&XyP5Y0$mpMp?1%s z0e(JPK9<5rcg(G@OMb4zr5J!~_wU_D05y(~K(qPu>iY&lDskCx$oKoy2S@?p7zlRZ z$o_MaKL~@uYb?@{`tddiB!+-vpb)QVe|M=?SI_< z1H2ON36qtIWw#;-%zqPf%&tJOi^AC1pHMBNtX|~z5YeD@V;LYtH|=Oq$5AsMw0X;Si$^>HY8fu8=1Nk0O`;< z-Kyp7M%dQCugBdO!?&GBywN5B$`y3{YoBsQH8#nBFne-A&f6e-9`P~m1%a8 zu-j&yO&ftwWMijV-GatqS5o5W9;uq>HWRGXVcpC9se(+0oajDHUB|6M=nh%6V={B* zWvXBtHYveD(?xe39mNTa*NRFF<%fr4N$6TO7|6XV#jqYNg9_OG-dUP~aolOs>ePj) zK#0fhM}qf~XL(H-1`bZJEtfLw-yjacSJtt)>JBwz|?xyR(U1|_y^i%gqIcXMSTdN zyPY-vNc{nXq7u4{;87*T<0y;#!n)5yC2mXjlenFEcs%ux>u(nx-E1p7F^u?y;AT9ebEKno&(DcJTNw+$6bl|xf>Ox%dg z8$onD>@t~Af@@N)0ENRwIj!?Y1tJ2OUdxy4$3W05CklqeELS&=HJF>i!L{4UYP?-k zrQU+HW94wC66we8--o#>U$!=z^j3Va16SuW?!Y7=Fl>}l>3vKQwY-cHoGsAuno3fS zSB(+>idDp91x}e+ajAAXB_J=cPxuaIet4xhu^)t6ii#3ag8J=HYoX7W6r%s`V&|Uh z2YbZKIo!+dC=*|8OBo8M#2r?gDLDF{va`?ifw`*?aN_E*V~+kUx@brN(3SSq_Ij%# zBrM7`XrNmuCr&iv0EYl~l_m(Y4~arfw5%V0gIncp^E}4-yNXU(Q(R*s!qtf;TKl`mT5tG_8>-?lq9wpAw%FiN{dY||QV6nm2{|L@m<6LbbB%#VU@3^ZE75&URlIx@R?*+T-$A$Lw8=!)-IUPo}tN!i{m)(0zRevV9U z;re*_ySffwq*8J&n0bbMn4(9*wFoqa?xH6W#-S5`N`7ACL;t})d~*L{)bh^KT<9{Y zkBuyu0!uaiV`~ex8q+}c*jWMVi%z`r9w^Zg;U6G<^$sVve@}~P;=rB|KPYki*?}-R z1Um-_?bJ>869a*+U?^=b+r$l|Zj}iap*@QvC1!9GD&V*qzvFV1U0z-M>{~&Ww~qIn zSfQLtF*H`ccF~r7a}2kRd1Lr1;C!*?*qb$&90_U&q1lsfsZga)JsmW&*a0$uzN()| zmUrodskiX*#qLSX)rHcuv-O_d@8)F!G%#{G4~PVUZn(T@a>$DqdO4ILc(ApxfCc-`yyw zlOff+l|@MI-vVDpZ%l`O&howpI@K^S<(5$6$`h~(e){8AN~5Qz*gXdMlf@Qx`M1e@ zTNtfoe}BJ@QaS)J#qJ>GI9c~QeZ8|QDaC586frPD$!Qx4j}2JZKokl`vx5#8!2 zr`*+?E&rT@`>E)q!}2?aTfnRJ#VG`jgJ$w;Pq!(jV7|5G-Ttrf2(a2`%G+(1b_gNm z_f262sGESxm^C;BjCi53AZmOA#M>U$C2K1pb`y-R->CC1vsL=)f6jTyh~o;M>PC&B zC$iZl`@dQeh$h__17(!;IzK%B0k$t_Ncr3qde_)B16h@;o{d7TVEzFpAUPGo69-_* z`tg1$)fNcY=XL4?ujtiABO34sC%M&rLE}=%Ao_E>g?5j2ap_w0jl&Mg$lmg!B*4jq zu1AAQT$`Pgm)*y4h|BNr zl@7qIpIzu*x*$ATyEF^VNRKroD~|HQoq>IH2B%8C)5vmZI4)Arc7a9|5HbC2TAEj* zAtqDjZEfMP@rs9om!}gk!`RyVp+)Xj*scj@(TVC&&9qcW8^y3O^PuffYYhT?JSpSjteocCOdJ=og-H=x2UgPViQB7 zi4l98UUGq|R*XKZ845qx4Q0rIE0OG=y`UFzoPD0>1kLHsxmghjXGJnu0x-X*=GV_K z#4&)%tiadZ@kkPiJ7%!Ey!(C_a(V!}dH_3Ny8WRM@TZ*ql13*>d69fs{9pTHDs41B z&3bYIGC;G`yK{d*mYDFfulL|okOJ>Y^cJVjKyC1dEE`n~i5YNhej}X%)MB?&PI77E z7P6RvlmaRbaxTg$2KAFF+6Jzf+ew6*t%RUk_?QXzg<7AI+-zhHelk`A;TUZ@E@~1p zh@nA<#anv2j*J5=g_x_?ZX@t!~B%zzwVYekZ7)z%f8hXH+Wg`f+m7B zOGJwC$Yb@+h?Q*z05Fa)6R03Cml&5TQG--1{*=jgoyG2z9(BiJfV{HCC^Q%mq)-=r z7L8{M1dPPyejg}cMmMn2-tskey*5It!*}hp31YD3o_WFNS|mv}1si%}B7Ke^n3u`O z1dKx%zR={WYx-eu>i!SrzA`9|=-+a1cN^T@-CctdB)Ge4aQEO6Jb0Mk1b1hE5OjhB zhr!()^7y}fRlDD|_S<$>-P^aTtGcTD_U)gYbKqU@3TwlSGG#nc+J`yw@v6IX?zFKD z%c)pD4UwY3 zYR^ai%!MQFUGE=WS#J$<*<8)@jRVU?9Y!q=R;kIt-D8yLewr4O3FhAU4$c@)DW=BI zO2Yo}L>$a9ZySZaKGDTLxD?<1lE-u6jj%!88_dO+UC3YDN#Xt}0ee|UYGtO{-y97kv`H%?%M{rIj@-C-;(o`tqGLMjEyN|bly*@WuQWx zn{n1}KJk?E3#QSQU-kVxUAv)E(fZtgvAo{8hRXKexO@kKE#>~D}tA+If90vu83ZLJrZ_$T)&i&mjiBRE`K<_9jt6#;yKyb+I#ij8j+kc6ZiBM&bQ)e_CMdIKf2zmvUkDzSPPPV@@jbJ{w?F^uhX@keL6bV)=5VsPh{U@r>@Qp`dhLxG%N&N4;Fq1| zB~1p5XWjkmNUosbuNeOTlB(E=tH;k_VO6v;e&c<)qDEyuUE}Lqlim0U96Y;yAQ@VN zZx19HNt&G(Gu&B~05Rtu>*|*>#VQ2yTL_Psj{7NHk|G7+H+Y3{dY!ds6nx3`_2GZ{ zBT?2o%1oZ1cUzu6KRU~JbR$MTvpNI9Y`ihAI-7KKEk@MWx+lM?Wky8|(6sjxtnJC} z7vF)Y(TLb+e;!-qOVQe(ix}$R4S8e}rb{5{WPUj}kHKeN)Lf2Yqcxel>Vgp*auC_{ zO_`Hqk3j5yFfU(nZGuUq@0uT%z4-X!f!(q2ktXkMFnqo6By~Yv3ihX{E%JJU61?rB zVj)*7Gjeo-ydFdBKsdJLtbT;3(wv9)9jX@{s?3Eev>w@%+MVY#txub7Swi2PP8NhpDBtOp_erY%{&d$0HGFxoMQ;?!yhH`j#D_)LtRyh@*UH@%gl9kxyBQs z^Si;oarrQJyeGuwN>FIZr;{9O(Wr_FHNqk>E1FG%;zJ+8rv}ub#Oz z6V_>YTli#Y5U>y|iIlSZm8eDdmy|F+s*vn`@BwSi{9{F#sqo_@-xalQ zT3(;|M0yH5rOc>7hJH_ZnDDVgdb?J@EC9-8S_fVD8NYm^pDw4}qfh}ajCi%@Oo6LM zn{mLsSO17?aho&wjG#TD;4}~7mg{sUeV5tvpw<0r4H1TFDF_W z1SEiA`bJ}G{DI}b0t6C7;26X^O$;ZP=g_qeBVbUO;VlHL-b~)(l!tNwMyw5OELWvoM2HVe#jg{Sn{78SAJMvbY{U`^=9c>01np2D=$s zn|RG%OF6kZjRM0Rbr5wg)Z2Z+%4a@Re8s|Q#h2lNEe#ChS!<5~oQN~LY&DjeKn*uY zSN%o_VQBJZLVUs0pD-M%t8TIC?BNb{KTObzU-BsV06p$UBjEw30l9|w!9s&J&FVQj zqOBoL1z2`(e=DKy`Xh*=aIOx#jMGoE zMIX%{x-_5+4{z?>?o2|DJWWI(#&KhGP&g_GXF?XG7%doh3ddYvaH1@BzomV0=# z{iCW&st(AM1K>P9P8f=(V78lk^CJKzT|W6kLvji9>m!^-_ixAja2CleZ)D2QLOfAX zQxi9)82TMH-$J|fn2cHum;4$gBTF>V0|p6PU?+#(I*NBpWs$o;2G~p|c!67QzDcAa zA04#L)w$xrH$rqwhVjf~r`^ascTa1ZzTfpLv!bD4BAj_kRAKMe%AFW2yhdfo7AAK#KF{rvHyjSc;`nWC|it>=<1kXzncs z@Rtwf8_IgGIFA?=>??q$L=zR~DCC{k!6IOsD?2+2Res~<`&JH7`L!x+(qHNc!uy!9 z2sNS4*sz%G*g`@aN&8i$`a%HVkuZILj(3yS{Lt`B14Z-#4J1uTeD;wGAmh$W#s3uG zmHvGhf18K?kIw??>Rqg(;s?{c^$eQxiX7%Ww4Dgb{0-c%4=FpzYb$MjquH#r8!2Rz zvJ0zbS8r*-{<|I@MTBdfcig2W4;2=FbU_NDISM&Tf+8RVs zdYY^3#cb&l9@!$nTYUl5u|rx@CqqSsC(uP1K1?BWw4;2FOIkWj8*OO#l45kj-AEXf zjq>RPOudr+I;~MBrcAm;tTI?xYlpyJz&iNqN!EJW&#<47Xe13m@b%kyBMxmaocM9A za+xit@Z*#A$`o+Ki%u8sQ=gDeo=6owvzQaoGvV*k9{m(AA(=22G+mI(x+J-!SJSIa@HPgf)|G1^y1teO0aee`dixm) zU%v14SHeDnQBc#n)yTH4R`+6_WuHkIDr~wbDYa~y>oB{KEPq{8j5h55ko^zf5O90E zSZ~_%|Il3yV`HJ1xv$`IjH6{w7;lxz)*yGSMER!nJ*s;Sxx2l|gk4FBU0kR#T`-^b zI9j@X#gn(tWlPQ=6KIrSk1EB03%>YyGY0ygSu&4BO|~qlA4m`Xr((@-gJJuU5M@bs zH5w z50If>_MNopJ)=>@KtNU#;Pz~xI99)Z{H?F#8#Byrm-24$A|Q9rwXGD>;r>t*In#6! zk-YY|$2zqRW>wN}Brk$Se^r;IkMjfq!gm6z9VbQHO!ufD5vvUtY7MNJ=bZo9gbpZ7 zxyC_d1RTFbF#;@Rh4JJ`;Ee7@=QcBjT};123I49r@KJph9pJ_WDMp{K`1RR(;uh+b z3+rGs(J7X%ox2DLLsLwwq}KDf=KONkv``xVUOw4WCLja|*k@&1aBHmei**G`v|GD6 zeGmKjR>$duP}i?L=XN*Zg7~Le*VoT!ibu8rZklxE?i1q5XX*9ilX@gu>pT;j?_>oJc`0gKI$}5Z1o$-w&l8R#*A$OCp zy{HfaF;8$OR8{8(|HUS-oF-At0%(ct(*F@{5F|3F3@;svS{#IaLG0%9Cjc?BT0&^B zR_281s$4B_Eu5A)>_Y{IU(TTA5T!J(N`~WILc;{r$XaS=T|r-k$+IhRDNZZGt+no| zptreHCakG(nX-$AG9f`ybQ6+&#GptFQ`BNX3c{~7k33~7F`&tUJCuUo)y3%oEVE(! zMg&-Mz8zQ?oeD)O8r&=_GFGx{61q%OGb`ZCfL(2WPdgO|BCA&Gaxva$ z^kb%~np5*d!NSBRDm$%yfqY860=mRWL=I^k@E=i=!4PEE$gA7qmAaOzhb5S*@$ZhM zZSpo1hUCaqXgdXP<1Y7EMszyvLl%Mqeo;4=(Da*3HI-R0s^8?LxPL zpqj9bbqO0QiS*3vF_sYn@H^J+KFG=e!hbh4X-rj1+;v>1i^2zaR|oUpe)lF7zt+An z%l7}(u0Zwui~EO4T~?i_cP{F!REHej{M16?K@=Wyz@o=3pr1HOSp750$RWi4=F-o2(mOHFFjW|%rnPGQ*SvxD*S$JlCB5~ zPZ=39ERlM%o~JGXf84mMG(>o_1r+%rCQW+6Cev!r!iqLOu^_MzEXE>gQPc1koY~&S z@J`Z|UEl`n05p{g!^@KV&GQ)fP?}5U#Dssv;QS~fuvb_>Hswixx3bdgBXhBmbVquHx$H$AT%u7KY{(S1@g7UBtmwaMIR{ z^X)SStQONi@_g^BzE*d_e$KZm7n3WCIkkYO=zZ+uMjKFcZvzRB3!$N=M4u+T6!Xl8bMPNZpF3l{V}jtlAkvdIh}n`M#3=A_<#GCptK$IBl3_$a2b zj{}B<8^%o&=wd5FGAd4Ir;qYBYU%d;s)o!2J0&2Q0eje+VMlQ{H|1$vg`iutkw{*b z-8@=Q@u+02Fw&(HEFJihQ=Z) z8{KBp@#qS5r3)vFZc`o4pQ^e|;y*W@D|AVX2vNNoh4c$JYH}9qmdVB}N}D#(Q`&+@PutNVnK@e+8A-$xKN$9grr3T%bU@lD zpIFw2aRayiQuqrxDX4<@i*18X-k-~LuINSu6?oxAynTX-D)U0K0_aZ#vQ2O6v%331OH z<+6rFOvKv?&xhR9c@**cq2U3wV=YW-t8-fn<`IH~_22ybyOZt2a9q;ohKoQp)tQNA z(EAz~z8T@-`F+T|<19PHSga|Gr1`Ti6rI3@fyC(g$u@kZp_lgVZj|4+{fx->_(1#f z&c#%Eszmq;qKqR^F>Y^hfZ58$WI*1a%F$?&8PJCA zyBvI35K`pSMa#g257qV|QP-57S~-$b*|3l3uzup;Z5;mQMsnlA*Lrpn>jcJs03k=N zHk3N>>4JBs=we?t=|i~`;?p@vaoDNelOjtJ4S+Hmq13Lp=PmaaHm(d?iWT(={;V@AOF5Rmj^W)~;&?PsfjH(rbsa9`Ub740Vctzc)tewE#jGCg z=?XS$6K}owGbgxOwE4ibwf!t1%4FfnrW4+rWRmUEPm6V2bKlAZ*VRcj`_(sS)RsCC zVzCNR_{FO#1Lwuq#+an*Vo5)HdMxT`f<1JAIyAw{(`;-X;dIX_k|-L9Y`kWty!O&MKQz4)`m+?6kQSfNh>LCVJqY+w zZw-xjs=|${ArTS(?7xdKc%zQBEv@6G!qEmLYK`C21%@QP$x5b*KSa?Hr)hsbyP3o=Uyyy-WTm$E}- zyLU`$q`m7eiVs##CD)KzIS|sM3U9I9oWTZG{QmAtjQdT6{}Y5#d-3Byyf4CvypO;u zk9M}<8|#b=e^(^an&|ND@Cq!u$A-a%wXP%S_39lMuJYnEWMDZ)ZWklsah5$)KyqLX zH7+k*>^@`bNtlANLX`S;aX(gwlB`Hl_8z?KDIKJ18s_R#2$B-CST05yBNo&`Vux2 zRIhyDMxb`AFt=#kiCk+n9eD7EVtC`Oy>L%p(PYSwL!|_6-c7n0t%5U-_Xa}XQK!^U_cl{p2h-Rghl!fXlkJ`pdiyNN?sF}1yeLq zD1~>MHjXP)GKm8Vs z+LhAz7%4u#Sg*JwHkMi(AK6rvmx>a1TuwP{b)r3y@j3mR=IPZ;fc8kOjqe@&T)eBA5F^|?9FD)_bW7vCkfV;_b`#8r@GCzeRNlt8an z6!B$Pv_T$M+1+^ba)6bcq;nX0VGgLswrTBd>Ms`YCk1CW*wFZ@x-`aurO(W^E=7}j zLsy3zy|gfeeVh74d#{)HXK%)v*x3))sd45IV!;S94aloU1W4TIeuy;=@rCDenZt>C zs951Bh2-f&-?n7iu3!DdIoS`?n4{PN2QN%Je-lG9D`4fW+go8iDl`g^2Hfl@ovMsF zu^YX?;kUErdwlxzm-hSm*UnVKvDWsS9Q&vCFd_DMenkos@-lqUFCeE;TNI=j)ce)| zAlh$$2N{NUtjIK)vH7aST>Uv>WEhl4zWu&E#;kXGb|to>EjU$w;aH@Dlk&WDw(fWvK4-z7XncM|ZhXD2^#oS5kSY{w~LpdikVT zxkQ)68Hxajn;RPKW8+fo7Ep%UA0rR2w1S*wEt`55aOC_CfQ877unEt9{N1L5&b*F< zFqY4DKloB5%GE!G?rrLMbs^>CGH~ zj%Ap4-(wET2V=lV5xaNsSJ^lK9#O^(-{zR2OY;L%<^nFFIVj9(qR*IuyC z9$pDZ(r!v7yUATKR>q&@pzu`lycN0~Bs%#PZaw)5BaeFI1WGp+?3fWy>vK*4BuiX7 za&Pj-qtlQ>w#H+t?28x}7OcVounL;z0^jFxsKy1NT@&FuFZZ`-rf1r?31U^M* zGcVzrc;D^V2-_qwiusDW)CA&}!oThPG=)=Y`&X28EJnnwR>bB8pGFG|KBku))cvAnqnf3W2h$@C5CX*12JIl zE%l!#KU;DLN(pVna=zvM_{*Ibsl@4fGrR?mAup=Kcrj_xfVmReTCg`<9narJhpq5v z`(}+X&*<5S%p1XM5`NL`)dys~5v#zLr=voh{JL_|A}#+H=)a&l+%@_^fl}AECG2C> zcjI8z4*1uWtrP=-R@Toad?I*&Dw~+F0PDw)I*sh3o%c>G>G_;$=1I~S3VfDuz!6b2 zU~n)1M=b>~Y1H|=e)$4d7Xs#{(H-B(`S6GO@~k~2T~O>7&zsU3{BZ|QEHWyio%Z*D z`|oyis|eI=nH#M8@Pwwe_VAEZf36}FrhAvLyoERhNXOU(CUrdsbQc{X%6y(GIqiJZ zU?N@nWc8Ja8VVuo&??!Q_C3vlO*6*o)p_`U(jU++a%u0^a_5e0!DMv3Ky86}t_Ydp z`7!#v?_yBP<2V%+b-IFXmn;^&21)TTXPJCZF(oLk%Xc3i`?5y;v---R#&ox`DL%J_ z)ov2pRKW(y*kZPj$q$Z(XbvD2-6%Mv4g8 z$0OL&T)+{d#y>#jyFo*MyxYrdp-<5{MRh&o)pE25Awlz8Rh0)rf%D(pFdZJvPjNNQ z-UB>~&}6^eFk_yFU!6O$-NZ&naHdP21L?t{pps*XV*duHb}v`1vGqH}jag7~*bEIM zMYdZ|-jm5isvzJ#ami06z^E6!QwzD0wPi9-9M;*Z%VPuQqnpKey}C#4a5%g4?#@7^ zrXy{8(6#;_o~%H>=gsO(l#CL<;-3k&e*im1&bNZptlb}oU&TA9VH8|1{O~Rez^ep) zQRCQ{S-y+saf*1+(8rpuu+1Ys=y=L6-`;W@U+fnD1W`R5IHi0`}HRXfqdh|2zXRn}k zeXF#qkmWPc50dcEW$HvqrxkJr8@6{c#l@>+;gu*L2UNn7jOJ11bk z9K5csOz|i)F3MsweUK9H8)EIp$BIovagN=maPP11p??5>DOr|y;Nc+{kF3pY$)G4O zk02rJ`51h?Nr?mQ+8sb1_ALaX&?{&~`%2TOeu{%%dg|eRjtn=w)0qAuhM)jn5;F1t z9u!TjXdB&tB@CbsXTeLsL?K+psc2d`%(`wwxnunPFl_>-uMp&aj)XkwoX~vV>zOVu zk&|Aq*-vQ5A^iSKFaH5NFnGQ{8Y9h=Y_6XNS)3l4#ttQ0Nqvcxz;;8S7n#b7)SL&db{lVv2Gwe8_`*w55i-R*!}+!Kt@*(WGH z-Iw{i}Nain@U=&&~pF-mZ1&$)DNx(s~zUr+h1KCcOTGyXXq2 zjr%1kCQRF#puH5+8Il3CQB-VjlyL=>mzD`$BkSq1?QuuCNIh}heFP=srx{4(u#v?! zV7}=qEt^BE+%q7*%ncV~k7Lq4bVj^`Md^5l6}~R|k|kY06zvun(YL?m162@uLf+(y3CA3~v)fZh(G zuSBn$`NTIs0>>NRgFR?rN}03Sfs)c{!cCTRZyxSn9OEpmxoH&t>YZG#GiLzj9r+6$ z*69Q+nHhQ~Nd`n)Ye2Dw5vbx;%`2g;Ea8kW`~LvH0z&+yC@p(KO5MrxMD`a!5B3+V)=3Vyq3=CCNy{#h6TJvzwwzCt>U4 zjX-BXbXll)y_`xdva7T+vGPh&AXgOId+Y_ltPPV8>uG}<50YmihpuBp5u^))?oYqC zx8X|kKJ?R>y@y=6nQlZ2_fX(NG;+Xi@33sHS8gV{^SXHnG#JlsaM<4*;voyLabI;+^UpOv74p#o5in$0 zqA|bWJ#eP<6^Kaw8Z*+V&4$gY?b{v=8YFG8V9b?a2yK28&~%`+qQDOCGEtCrKzX|q z=fW4;vtl*OFhLJ*ty`thq&Xg+LZbN-zP^Yv6Rvf{`qcILbfpPB-d0^2{z=>_vJ(~c zGzcZyKna)qYMUbu{w?TtW*eW8@Oq2K;NvVytcdiyq#%IMs@AAG@zP#Hf2VResgEQhj1#bH>J7E&?FF9lCzqE;^9aN_H?b$Iy9$*&Tg4#b$ ze`xnjI_E1+elK3(OpLMCH5#l3O_2@=lzM(SUFcfJg#u7hKgT!))C(fJ8fhS3yU7oZ z{l?9r2D$|v4C*4PWg^??qIv0AeSnNkX-aMGcSxwd6Opdww8rB-yTkjgE->}foss%{ zQkMLXc(Va~pb%bQuHJsvD-K7YAY=I2@;NN8sRl4qp!WDHbXtFsoxx@QFkEl8Go5_w)%_i^V3Yq;;PJeT zEq5zB)QeR|10G-!>)Ff4mnNZfYo#;_OzD0Ynn9$l^eJ!&G3n`Z-h6&5dI}&Jbhl1D z9fEQ#eVZO;ohy7CP(z6$NkVr$&~{w@6fK}A>J{Ob6YDT?6%dZVg{2uZRXa*#yHU#Kbv2oE?!OA1c#Q4 zvl9$(=B$gED}Ai`i6=X|u|hg7Pj`bdv=6B4zt^=8Qs?^B&}G$lKXEho>)65wVziiu z^w^qK)gm@jYjF`mj!dfP3&Au*OR875nsOM`iAQ*8$f?gIkEzFMn?hpE^+Zod%KVjz zU&^R2R7Tt2{qmNplrSaT+^Slcd)wi58yxY znk?k?55SFptK0#K{PWA3c)njvQv}v-arcD^EIl(HPTTH0#?=DHq80zFS2%%bJL$o z+ci{}+3df61x~~6O@Dh3)GHyKzMGSAweK)4$2?lNK-vurby*C5x&dG zZv<@n35;8TWqo&rMI)=@!zhHR?5`V;pb#`X7%CWDKQQ&qLvV$V2|NzxOTW1F&JJ|j zcy^}hHulD2o3o-V;zjSX`NqKMPJ|%|l(kzA-=t&o-$X5>1#{9vxk-cXqE=wM)T5bn`<}h9RGol} z^MH1K)LSWjh9n8k@-TQ~Y%H@n(SX88{VX(PBj=)X`0X>lp>F}^T&DwQp}u@2@xEPi zLD$(|LDu`GoljPjV>Qqz=A|mS09E&z2Bi2aPxe*p&CUnjL^|YNr*+nnv0B$d<27=P z$+67$_}a|68TW#I&WQA{*}k#2ZR2}$jU$!97ny}ks(ye{oljKuFTChhzM$+BJXy8HT$fVH#!;s&z~yla1gg(LOH z%eXk%uuRlwq3&%ol{xE&-NWc4GBS~MW7J@i6u5oa#8;B{s$#bih^HZgn>Tk{kNejh$|T+8xPPz$C% zgX_Il;6jws?t+?0NwH`mo7k~|Rzn!iubV(<5c)D~xVC1mN84CwA||2x+&U(V@q7K1l&t$ zms;sN4_#e6^}`y19jt;Ki8~ZH79HSdZx9VrXj~Xu> zv$y3mJpNo#M*rCFHim(cy<5vmDWirgA~bG*{QghN9hzLgmP*_9znosd&6uH)ZwT=V!TlG&RER<(y26k6e({x(T1DS9T0L3 zA>L-xc`3X<3~Tv|7cabzY9SC;k@2D4?5q=3moZ6WgPocK^xR);kMZZ_XIePDR-dyP zOmm`ScDfag&c(SK=;0;N(S#`AeNH`Z9w`T=`uOd?c);9}TktY_wdjU)tkq7OKGm}{M=*7!%t%@cd;9}LU7CL>11XO1?Z zDLWE)P7yVyRS*qnL%i0QhI2I?cDJn7MP|* zw(|SrC8YkLsQ_uB88*mfui>vvQP7!`y4FnvYORv&o)Di zmDSq;HuMY-W$By!6#+lFa>tV3h6Y<8Rsv_@mfk!uwXfR>ffup~q1e5b9Uq_IXdA~R zi*+WSV~^N5mO}&F7Di~d$@TWOcCAHf4Bf|%uC+H%^4}0JeDH>GDou)v14p-2mv=EJ zdtS z0u}`|5{V5<(jf`;LoJxp;>0*<&BK5qXIj# z*P+ey6cVr!NQ+3C8O>0BN9Kd2-*YOLemd^`jL3@mOG92#v1?z7Ir`gix{N}+(Ttna zmJv9FQP08O&H)6psMqn@EZ+WO`xkZCFgMnZPmMvZ1`;7PMUr|N&s^}uH|G?m%adFn zM1Zxh+ZI)&6rG%RdXdm2Q#*ZQc+WtAqZ588wv-$$V^)40Ju}?LzxKN@^mdx4b_v+k z1cthGRJ51hk*R+^Z z>FvrT+SyQPNW8WEdGHhBgSUJ}H;`p;tq51?wii)_?}x)V>zqw1T@eS`#@o=Ez8gTz z{sgyp=$GJG2#;vFDu3%%S9|bC7UEifV+~^+#EaOl|BJ!RlC495oskBJYI9(D3_*-T zS#Gqt`|w?2iXFbN()NvPUIDY9h**Lr$ogTBA4m{nj-x|}bg=UY)+Ouh?;TvMWg@@O z(sJhQkU3ZUvZ!Xg^a{6$qJj;aJ^sSPviVQ9Urk{+OY;X6#HD=1&toIouGdNs^n9UD z^Zx)8W9!^*nq<+Ow0!3;K6D5nOTLx3u;!Erald)HR1OXWp&X46LcP~Jv8@r2zwr8h2z!xZBS1SJF z#Jj1~bZ9Mw6( zMaZc1I|S)p79TiJKR3y_bF)(_y)=HLoD+L(AKW30EzBFi6PyWiJN7x*D#rV9ZyzK% ziaBwhtnH^wf@9IYdgGq)nd%#_0+LNN6s99Jd-(NQ+7Pep$AF~=Y&_^VR&$*pty>Zp z)fhe%uoFWYFwj-Ng>Qcac;z;PM;EZ6KBNSlTYj z9$tb}xzd}c29K=fv$Ii$Q60w;>&E`f{U_HRt@ykKRnw|W;t?HRWs>yc))!d`@Lui| z9ZD6d93{qeSn_aPrWC)a$6K@O{L|f5o^&U^&*K)x**j`6`{qR;Ok}dy)f;Jw^4rLHp zE`Qm9{r#H}Jw1$-KFWxM1tRK=Z{`G;>Y&PsDVM5>G!>JyJIWsoPl_)>#`-#)d_MzT#f?Z$Gm4EdK3F*79 z@iFQjiEpfF1NG8<&fL~+C)+J7_&hPrM}bIL#CrA;=w_DK(vFp);s7e7=iZht6YC8RUP6X9=?%)KNORsaE15R{OX<)->20zP!f|9 zy%J*j{gG8ZFmR8YN#C}v5tCcL^|1D0yT6(4P4$iOZhAY^`F}d*_>YSq2x&a#=U46s z9_=r!A?o5qSjksXs~|+q{iAckxI?*d~A))*f8Q*JuH_=dj`|M^s@v~tyFlW zs6L6#b7b?dA-9K}AY-iMa!DRnbS=(7hTNhJ#P@^m)o!73@PEU2hD84K8U zlg}-6HGV^>37XQPn&@-JWT~GbhNo2{y^bPobTpy;4om>4sd zq959JnsVjs-0a`Xo*&a6V^bW1BCq{|f4Ci#OE=7~$GG0dOh3@aQurD5+^*bqo@vp_ zzrO(!MN&=)Q-1Oa?5UyO|M{ti5tvsx+$0V;OxnFMVrse1*?EwO^dWr68-90EpFPn7 z#P2gjck~D&*Y?5q3w=&=hf^tgjHOQWf8903-t^b;Wm#LaenTP13F={t=vYB1#RS>S zx3UDO8RpePH|Dvx8O}|nCzckiRJUT{7p-J$E4g4w^9W%|4qUj&@YC)Y!KKzaN#cgx zw$awUAZupWSx}iF6dUye{pm)@!bM|1F%=TYJH#HdD8l{#3bWdv@JN1Mle!A#7HHZK z`tvJA%=h}8BEMUxTC7~4BiO{UA!toz;f7JD0)$O>bKP=7y8a;nUxTgNdC^RmBfD8o zTI3yzZ?fA%*X`2ji@tOIDPF}-;K>d{3#_Z7(x_g~KIqANWl%OK;pHbNg@9?~ay!DQ z`vVRyJuF3)V|^B%Tm&bnYk_{GNrzowptF|@1wMZU6K&i7IwnW6pv;zXLLR}9>2fsj zd%2~M0C_e9$=jI#2Bl5CB~CAHlrdPVYk|(K&m4n2rYLBgnV=491|qf{c_~Z9=~lqa zYot?$fUT3_wn7meSWsB6f!9ro*mL65c1Q5H-=w6nZ?C|Ttrcd)FF>lGE{U~8R&Smu z`8XQ!8yB+swUBE|4FbtD96pxjyKsD_wJIB9S|e7tx*QN&9EY-~-Q2wZ}%?&6j)g~7JYnlc&rA(ji4P`@}=j_rmGGRYZAEix$^3af$`}F=s2J4*JbjWnsDzX>MtSBe}Ipsz~7R8 zJ}80+wql%;M5Gy07yy9^^NZaihXpp+%bO)T)*D`|CY_%2COS5Q1HBj>5=E*Hue{Kk z=@f{Bq$*)pvTlMvQqM&{5!XJf$7rGhCUMLUhSy+jeLTQ{lsMZG$ZwKOfT~Z46wYUz zFtUSahs3gRt$2Gz|cWBW5oAZ1Y&(gvr~zc`>%VlhS>#>mlL3jqUN3n$8&x4nZ7= zS*4pnp2>6Y)yqM7mt+d5cXelU2t8aZ73#E0#R-vIjun$W;f}z`h_mP?x6QD0jTKoi zfJ1bBCj;!qzOGQi28EeR#U;h~6o=1-5B&rD774*Hv!1d%CGm4R{bKn1UQXN&W8?sR zJVDX*@xFn{Q(PyVi!A3NchH$5dDBZjeu+BPU$O?YKW<|1QRyNE zKP^})0PInw5FEcE8BXZo@=|@3RGJjLIY$P@_WsnazU$ds-F(F-8t9X74~Xx$AvsrG zR}C3kw97fp4r#ZJI@-})49{rezhgwcA$YlTz;GwwT9d=k5F};=@q=nO=-`&2hg`^{ z@8Cvrw2X$|hOZq94OoHId1@aHk6cD~W>(^)lqWANCCQlhI7=ttFgo!od7piT26e8m z1UUvH+i6D1DxQS~zJTlqGOBhn1=DJGqT@P-8RsNz1+Xn>^X=EWLqA5N;xmzvos|)M z#Y*K&{^^G2(5HL+$ko#ZQ#+&ierpc=13K;*ZP`kMR6H_*jtWB7p5Dp7Yq zUfCa$eTt`YeW|Xc_T=-ZaZW1A07EDxsKo~{P%xk@3@dx|F$Oh7QW3eS5fZz?H%zhO z0n1MCt0=NhJY$hAg(vg+t&uP+@^@!Wkq;HL>uGVoEK6&Dr6aeeP^53fW zV^4ly3sF1`FX)RqUc_%m@Vbne!{F;G)IsPh6SPYk6f!oDl{DE(k>hc|i6p1Ps9TU& z6Upiv$L(G`Hr*E?pk77-t7nlm_3-AwaqlG{E8}I*qkH2O9j*B4AD~`{g8}k~s&?lo zhXtKDceaq>4Av^saqwVrCY2D;4z8ykc*Iif#ViDor3@p_oD5R)P z&@;zOg6rk3)IHFI(GRcy)sv<`S=oTawI9drcC)?#=az8CwKZVykB94MHPfw2>EDWu zOgY-NE2N7D&Ii-_oR zMI9QXbf3gRjp$SJ0FwUAi0Gv%iS`F63tv)|ong5FnobNp(fs~I^x6KdFb!w@=89|_ z-t0r#w_ACy1I^TcSCoiAXE_#1T9}BI>vG3 zCGDSaH-Pc`qnPXXcW$FXn~rq5)c8{bQtu8DMdxqa-aa43R^S6S0KFNbkp1w`Mw@Od zAB{wadubvebV^qS?al0}J#mKDP+^%{*?@fP5nLnE2?kl;KFqw%tO1MV02!XEA-%2C zMF%w{D)jjD0qt-gR^1+R6yJ97z_=&jbX%%^hA;LCnLyZJ@;MC36u+=0@gh^ndIDRy zH^)erj*?P=kE}Eny*B?2gcNO0aoUov#{?84zCDu#Nv!uV{V%V70aD#n!!NI37^}9H zaLD+pjK_vn@EZV&2FWi2g1a~4zO+wgCmjRKJWw4JwN#GfsWh$@B0Xm{#$IK>cx>jA6JhrFbNxMJ&jiP zMXgLVi0Sqc>D4sD1h9*pKA=sWfjL26{2*_&+GF0YsImsu4a3m_YPZWZ7qL(802r zoB6V9mA8aCiTWFGV8_AItJ#4SlddJF+^8k`vJH8Sny=PR`RAxjQkX{EpEI%r@|One z4|CY(sY5_O?ih$vPdf|1v!|%&wcZyI1Lfza`;Nr9lDVooI7N5N`xFkJ)DVLGc1WNyoV*f66!OASB0eROQvL4-Js z=emfnPB1AcPHvv6tj4L2mk!eJS03D%2lfR@LRs z4O_`?zhzF#M78W~I~X|f=ut|XlkPSnMI{Nbk?HPq@j_-oh|x4M{#^wR)e5|SB9y(Cdsng7b!A?2&W{{4pYs5bzJC9{yxTkECvItJH z)BV1`clJ0jd|HydT?2=}Tg7tRY=6|TOM3Zv6K^MtZ`NW!Vr7^%p=*-n(m(|HFF;yK z>YI1;LfzQz#JdviN>laqdjjL&1h||Y04NPe7ZX7?5=|cZG{F%GRDOb$TkU4 zBu=W3Pu`np^jmE9};wR)zS+I8`%nu-`*9vEc?KTgPEDlbdM4d_hGP}2Q?oxh6SIPs{rLrb$D~2=n4gblW$pC2@MUHRCRFehG zMyU%L>g7ckBA!CpGJ3G5I|Ea#b|{=~gXepl_#Shg0J=(L(Thk0)3TNtgxmWl6?vs;)cw0*;bqxlE@wusFw~ zgi^-T5dfS{Yd~Ckrj6hvKLrL|^}8@zQ)GGWR;m?wM%&L7j^EFRRj@=LgY2D*5p)11 zPzB82P=Nl;{Wi&fBCvG)Tdylctg+0UV6gpB_S{OAOpbn1MC7Eu0{0l*&a2qjO=Fg2}tY5`!d(>hUFtzl55$ko-n%#OsE!Z zK4(fTtImCjz~WW=9)jWD*)R0iUxc~O0;0LUK(p9I;zV@K@VO;XWp_VCI45b|^_|6O z`MRfcHW*7cG`>5^M^PfwDeXH<=%J&EDhmP&jB4;|L>5^PcPOs>1@#atell1Xt*wn^ za)|Smeu3uK(OHS5urrn_vlP`HzZ)dTHbQGaNR_}{N=)xFmz~+tatDV)vql`~1P>?Y zgk_&Up7dIU(|A4imAzcUOq`VtuTsxW0uDq9eV%WpQan^8THmT!U5{BUqg*hFY(q7# z5@^Z{q1`h>weZOvC(dFpcuoV=GjTHo>;Fu0U^tK0D0MOY6jdjfrH9xO(lZ-nkoukXxcF7Is?0*FD?AHZ6-h+;`s1iXQkh6Z097QMyC3 zYoAE8iD07C+wHv$$`w1o`8lI@ncRKzBco3ABqAYw4;4dLpW~G1^#d_mYxT*tmlmC| zpTECpZAY52QmvdM9u356jCXy-!hRZvl3LQG&VHNlYE%ama^a=lKi4G5*ieC9GVjb3 z5d?9-1^h@ivTwphX)%YIw!*gX!TP+dbMNd>x-(tB&2vtOG}trkumb!cjlm{|ExL7g zY_(ziJj~DmBYq8+9d?l-N8473V?Zmj6Cly|D;D6{TR|?3U#VV1UhJI?Eu%H20Y6vj z(Zo`1*fKiroI zm^pGp$-v7_?hbbT>J)GDRfhI8Cg3rLvbUjhe`iU?G2_)gr!BUv<+WrT;oX{ZCD^|a zR!R!$$@+Bt15YG$X2y-X{h1{v#cXiXQ<#FgkmdW=AsJr|Yb#w-XF8ks!nA zOx@t$*XVn1n@VDyJ+&g8H2Cn1LGom=+MzVF@_IfxD~WnK=zaDH6>deZmntnt3UI}f zv-KEqb=^jO*hZ@+Ac{oeI&)ncX2=j#wM!?-U4e7?95Z@x?$s97u5I@p@Qqa5C|ZlP%P-mYZ7d?fZpqJTUXE&w;i zM-)-=iwySOTb`BOSUZ5d?9UL3vKtFo20m>+*Hau%LvQcLaqx7&75r+rN!EaxIoHfp zjPrh>{l~G(!5S&2} zg}J}a7(K-BNqn4x6iK9?<6x^K@PEMEDH!)P^RKO8J3r2lO~@G8pvVSvXav{~GhDON znRr|Ra=L#`4mY{H2(!U~h!X^TokaV-?{(MCy^cW{c6?%o%_uo{bYlY6C7~T8)P-Bu z7-ka{*t_$N7_eRMU4Or|tnTtx&aPQZp=S&!7qDep%5K%Lx{(Ss}y3W3OLy+O5g$|RO|y3N%80e4i^c=*BsyA)j2 z+_k>u3P3Hxe#{Izb^Zw6{R&$&dP!xY-d;D0S83)jTbs+^WxF3N-nb~Kk5H99ruq5& z_uM^lL(Z&sa2`w7vT9iuVeVTG-T`2dU3LKXLH8+ff7I-S~e#!(ID6`#w8LH+A-RG5_xTt6Tr?Pi>wa zZB6$-oDoM?t%hnx5Ferc{40jM{D?W7skemFU!2b0*-p#2HjDi99Da?oO**=n!z>CZ z$3P!u34CIf6#DvNr2Z?S3q+T5N;EA^1B|;DBmH6s>F}A?ff#oeZ{q+c zy@#_cC{z{lOZQF!8@mUuGa9aT_;<%Xjnxw`yiY&gcIDQ3TRz2D>Lx22xi26$&o!~B zNvIfgDM&}9ZcR`}1wH7WEqia)0|+@=?r5zDQ+z@*id&+oEtT#a2?E_loOgtt!^Wb3 z3!E73;l|CE^<}yA9s=0J6F$yro+sp4{R>>H?|2X2$UL~;@GO}|8Am7XO9R=lpoqE!H_^YHIDL|FQXC27?v ziCdhny$CV7TBVuMawEs9g1h4`>|`2tht8nmc?nm&s5%79DHq2g-w~8HrB-=$HE?ib ziV2%aU5CYBfcRuOd5E0I^gkg3|6q}|YYY~$Tu?25w5$^@sjPELu#ITRVOL!odU@il zz|4OqV!^OzHic#TbN&kP#dxU`#Wzo8b`gauolBZ}_`D)n;9OI|6$_X2I!Tm3BC;Ab zJw4m1+fgzUY3k=TynuxxBH1!NafG_e+-);5&CuUb*e1@8Q!lkI(Ao4AJv4}J#X<3l z1`p%{Uw+8-EZGNaB7H70R1gV}%DZqGVw(mR(wcw3hMj+GPgYh|(t`d1&~1Fe85@6h zG*F6*?zlP$=jp|lf+$b!M_+vZrvsbh>+lC=FAc`y^<$-n7R0;%vRxW}1U2h(RO#!y zB;0mJs)ra^qu0Hq=bNXOoZz$H8Gb~yPs+zi{ycv7vY#D%Bm@Vdl)8i!2-rSYk{uOx zGLX3aadHnnc;Myh)Fs?zkf&F-Qlq%9e|&m+l>hR7+CP>U7tWHL(6aAH_5Q1+CA|HQ zZLsz5V@{<`ciyxHck+cDgT48#B(0c=k4;yg3Neao`adsJ3zla8xV~t(A&K=(4 z0mL{~vX4`+%4*NN<8+%y8dQ)@80r;3>%)n?+(+J3OaoEYO=L2M zdYJE*6b3aXMoyy25>acrR7GXCre&@5+e2$&P>aC;W9j&AZcxNl^9Ng4fEDhK%b0=~ zzsR_)<5aSrM*~X=GCD*}Jw{K%Kira|WE--Mzv--ph1|EpR-jPX#9)-v-o4*Umt>O7 zt#EneD0Wgj*RctX+s?X%e^+%6GLfJh8;J+8AfzlF;hFvgh?){H#;lAm0xP!N^mooF zCvqAlW_Bw4>I+#bMo=lfvBTrW`Y^g6#zCPD>cmc$iOxYKLsj($WS`;VkdN}1M|IQu z<_QW<&avgVhIU04v>)ph(P&Ud$YG!o}V8@+Po{j=xvOoFq}rmD|@0+sDacUeLP3(Tti) z>)R=JTf0iS^2AGU2X>VnVS2Ibj;cv)ZjX9U%%*rv$jPbp;L9Ti_bIja;kx$>A#@Vh zKAs_{RIim!OHvgzSCm!5Q-o!;Y@~BRi8Ye?Ire`?yWwvbQ5|tuYhY7I?HCc&wN@lVu3BhqvO=aTkFUL}6S9=M8pL^CjiRQB=)6ng+4D*=&DUy)X=(om|cj1BF=<%RuYnjAj_phSATi&q_c|N0+eo9>~(Z zrwLu#J#9(o{hhweXJ-#h!@|B$u3F?*6Q`LqDc-qv+$T1g3s=#%ydaa2_}M#TooIf> z9yM4+rC|Cf{k*#V{Mf-2nC#X}k~*&U26qU++Wu6qJ#nX->o=nF(eMzRh+QX>R)`j27p?~QsLP@4&NyeFAb{R2pPhECr zbl*quf+E+L)W%N{I3}jq`|$mbkOf7^iUbR_O0gZ~Kj4GlHiWp-wuKx+#GA8y>Hk0b z=1nyt1mPodp!`=KpEj47#-# z;?tN?HnR?mbm*=&S^r$2pB7e7 z6gWuZutvb>Nj?M1Hl*3>t#R%5ETc%l6n*cPp6fNA*w)@#90)pqdjCB#Lpq6MFE46Tn>umG~!~a?ak*Avd^Ly_u(;) z^;XO|-{?-G)xjt^PS%R}W}V*P0?7F`*MQ|RW(4Zy%Ps{%jv(G?-Rx~_33ZP{Qzvm% zb^4pfNWCK*MO(g;B}*VZ4tw`UhWEKYEVN$bnRYW4hipD$;iQB#IVrT_h;J@&l;GTg z7zYLCh|5gLh>mQjck89M~5=zY{W{6h|l4sYj4PM^dgc*t4a3NHn7J4so{njhs&n0FqMulHV&cX6^ zSbdzv8E(w@tZEtRz#ih_`CNefkuSlY^{@syewx5cI(vQSU-N{ap6lsR1m=qY$=D3A z=_+g}I=GUMxaqXVI8ZQBR-OFXNY>jC8ovGCeJiBcl05GCm<|jCsd|z1&+2G|eL*J5bxll>7U$NI{j?p5+eA zm{H6g1T~WQ^8KRm_jsJOw0EP>&A~5%y#22nhieWNPE#LmIgqDO=hqx#@N^}cd073jO8HY|J=qa zVwyB(`L(KxAMz77HQr8BekIN{biq0cwZyA;IlBJv|CuqX%1U%H7=nt&yj8lj0M=?Q zE8utBLp9q>@DR}41k)cT!Ju;~>lNP|Qgl%JA`3c2uFppEZGAE!**#Uia}>dlR-n2I z2l0fmOBgYnrQR;dh@9>7KA&-QM@f1*7G#}iN#_!Q5G`2BL0Q?=h&rYs<*fA|<%e)l zFriBf`;9#0tY~dXeq^woykI`MLYwD%^XiXuYPXnj8#n9A7!JK?{Ox2I8|tklfg_R; zh554fhe6oJMBLjo>6sF{)>!o zBWReHE+2DNS#-mJc@w#u(&&4iOLR3spQU6q{q1;WV!DWvxygg;aQNn+Iv0-XC5XgA zN{iBN>eoThtaPHATYo}r1TD9>Ihcy=sc6n*(^E9>x_;dm*si1WM#nn z{f4PJuHem496)CVr58tX@L`P%+iF+S6N5&PBI)}WM~K5*eg@*>Aj9aU)m}F*N!qnd z`%)V3L%sHuasMGtLveiw_tCyZtKC(L@Z%wKQmHoEL$%GuoWfn6;P3rxiKS1hUz932*ReS4RImRgNW zhnU9oEO%(cJE6a&t=mBOUzWQ4A=KUba}nBK%uqTBB7O$I6ifq@h;mzh%0d3b7a$N` zlV!*`roMupUTeACubBP-pCQmHk29^A#p`$?1NlUvY@ZzqyIKPC!MY}r`jPS0ayN6(Q-X&d_hSW%!1J>~ zfuJ=(4uK4RnRZ{KMKckw^kuNIl9_}xIoGSVDXVHpCe6>QZ*;{ZBvLvMX6sATdsD&w zzLHoAM107n+UUN9E=SOT$|^dvAR_rdi&V0dc(ZVB*89K~!*--xx2SSC{{TA#0GO3| zmUr4t)4A)ca?BEnBNZFQFth=r0y#Hupp3N)>QPTPRl} zp9T2<%(6PKdxQ#-#)bFIUi${deKH*PM0?x$0+7yfk6GdY-=dmlQYGL%o%p^HJ}VJo6@!~`8LO{%#i_uMBnMy!o8v`9 z4{JuL7*+sFjL$ViQ3eX-WMO4vf@J7|Q>+Ilg*KQ<0e+D3m5ga_FfZDxz*d1rz_&RP~izk1~q2Omu2t9v6^ZoY`x6mS!=|DY{SWRRnAO z!L&hG>@sl3A0wZ~fnRkprRFOZ9(DBbw|>sU-+k=?$2am8Uigg~$cXoJjbYQ26srr- zp=-8S@sg6vk%%qk@fgstB{uw)VOPbip4l~Wp~)|H%Jx2gcCq&{g#w3Or-B2VN7*g{ zRt&Y?+3DFziAur%$y9V^XWE}5JotLFFZ%N}i3h3waO zzmF;gpw+I+@2NxcGV)eGO_YtMesR2h*@mOivHszQV#dsYO%=D+aaQR&NgK@XaL^TU zqh_wl&6Xl$hcty}zksqL4d6H6-+WnuC@fTCDD8<6ycBO6O&~KQcTu|E(&Cl;K6(Dc zh=)-caO-dm)=vX0gt`}6H?@TB4Y!n<7`$vXm^)Ea0rnlTN=Sd==uo4uw`~zve0k6| zo?W^^s>xUR0&$!}#KF|WE#bT&q7Y!hhVb=R0m$TK>*PG(o+=ZVh1p(IaKZQgjU}{F zctjjA>`i+vE1kR$8sfLXqa4SR00pjgiud@kO>u)eCuSLt{f|$>o`jzW91yvgC-=WGRqc3U%iL0Im|tAtYI*)X8fQa&9)$|GgWNOxOA3i&U2D}Ot>O!BP* zb1fLt6Ij0NxKLajTsxcon4Uz2CMkiJ5%5=VJ=(W=zh*=eMFWW(;wuCMqO3!z*(kGW z@+{=!U1ICMhxYiIP$?t6v!93}>z+-+n8&{iA&>>OJ@)qNLPhTGE5i@e zPyPi2n7=`ZY<~iyG6%l!CZe51BN+R@Wv>2KXIJ41!jvRb< zf)7ABxebg&!SQQ>1>op{scoDa;YIG_2C&IdG1F>5q-w?wz|C6fpLfppQysjLod32y z^91YP%SKD8vfgsb{+6%_uFCm;U4svjXy5Yq-ioK3^S$nU^Y28ae?jtlnJCOg@#U>_ zgOH3Ce%6!BjQOUlig3hOjRy1jvS%i4p(Ol7uZ?Hs*9N})e>vd%fXKT-K22TbybNlk zi8W~WSO33U`S*f{Wpf!w`aMfj%76v5v=&u~bj3qVD=J*4$>z${Z3T#T%Y>9+G0NjY zUe}L$?`d?c3!%)nuzMw{KEN@-|LyC4+ny5X-XO^HNgqzj>j4*lftOXOFo%`Q85V_o zCdp-@JpPf0UfrT2YW1SxdBOCR-YP%YS!1Fs6QX_d3HkF>B*Sls3ZoU-3e;l(zF1(2 z=nQ!5%J_{0O34n&ZtnXLL|ctgdt$vhQ10mB=KYLE@b+S+z(bC4t1O}74fqA%6M~6j zw}>9%4e_YR1y`e;1w9Ca+Cb`olGWYDM-^Qq;58J4x}#9x$~tv73Qos1V%cYx>9T!_ zs-#dQpslH>1WG9eI11*KXqOqxcAJ%U-3^p9YNJ8d5Dv6g|MY&E28_G%$_C(DP2}{T z+#nkm2wgq3!hdmRH;O=w6^yIpmqi?^RmYnEy6`<`U7YXyZtKT(SncG+qETp%i1SO5c7eaUkUpu!%BJ?!$nlhOcpcXZR&+uNwa9s0H5=;6 zrN@Tg`(J==C!fE#!2*Fe;WT-5Ty-4=(*sd;*&>bD_1+a8gL97!D4Z3%X!8oKT+Fz! zoVYOePP=qUti9av1`Xbr`|N0_ zc-nky-=|;BRt0&G(lEkH(J6VNz0vadABXaR%%|4XJiiQ^*8{wEwhtf{;VYRwG&uxG(WA+VkMFz7l@Lz1iAm13AA z6s=Ke$CsWLFWE7;BxjYLP^A@7Uc!0?&lu-OKg^9MhDKd(G>`*m3G9dr28eaN-*Dxt z?z2hrs?DBBhtCiq%gDXVDdoq)-DZGCIQQ9@PThHF@MsI-~U29v$Jk|5u6MWCH0idvD3;+k-I z_stBx1`j)NAf;c%-lGji3@gJ^7}b7ka(4O3_yv;Mn9hin)q|l?F!O+&zSvcJ5(a*I zh|K3x|5537z0WRg@g$;{IZ!$8Sc*O9qJKk+Z491EM}3sz$6Tw{J&)5Q@pZ<^dj%yu z(E9)fb8SNrRJRSxv^S>(WJ`j?nngzjwk>56tsOyKPvfhULSPyN+biL6K~Zul$>uyha~ zSia;LO*wfbGg4iIJphw`Zs%$EG}!VzrmUCO+X<}%Rs?9D(+aIch&aPS7Wcg|0|FA( z?G1SXE6nC$#CHI>B{5W6X^z9T?~p9Y^~wYF0p1*Uf7c7IFU0TK68jj3hXrZ7q0S0w zb0FKEf>S6IbFC-f`=CaP=PZiy(d~KYIOM9bM2li08gz(^@(?W4{>%5bJcX^~ldKzG zPCw-mx(G3nwVeB5on=VU>Y{zah!cuovXVYxlySQRlLh?#J8BY^v5gJPPrGpsZegLco8akWU zdr=%5f(m!-6L?c17*xcDLtc#REg@l}K3hr`N1@B^cPRO2Ji#eB6QLXSt3(XQ7BS-x z&nx6qqU@KP3}iTlv9iwg3mMHtUF95YeAw`Llcs8KbDu?eSDrr)HdY&+^^6768N~Z{ zGuMI%Ct6o&I@%7;PST9dgxBsl!Bq+Ph&UV*{3AB7zi@-^dux)LoAMM?(wE-aC&JvUH2@=N(i)$k31fF ztI(SU=@tWSWMLabw^xUExcUMiUSrgU*URpw!j3F5^zhC^sfyDI6ppoFWwsFXGbO~k zd{zYVGy78~U@5!cc{NPE4e|qvgjz2mhS?yfGEc&^{`oiIr&!4J50j$9gV&#>_I~w7 zagT&Pd!QqX($%9HI-iEPn=l`A0R{ZK*Q`0S-J1Xbdiy{j2goR)0W0*Jbz~6Dud;&C z+ajz0CQO-M&2^~!B~lV>t6LU#w{egM`9{nOS;Nyrgc_9j%z<80FOhVTDk6A$e5B4u zg(jpbkdPq1^gX6-n1QarX>ZCxl7s~N*4OA$)l<3~pe z{R{L#Ax&GGQBf)uX8(;GKkB__d`#n^Y%5s^NK0dGZ*1a)GkolMr)PMH!YR6%O^NA4 zHr0pGhC(>srG6@&K7Q!eA2c$8QdAln#NVOV8_@FKYyI`G@PCbQa8)fTiR+I3ln_5X z^BhJ(77RgiZb1CKBEnBOFxr&P9_L|r+;#Db_UD+x9quB8(NSCK0GCRZjT^YCgEB1q zjN=@IzEfSJ9aP5#l!}A|^2BFD-fgSu<9cl=aA(Hdi9=1b+t`Lti>5Oo8O?IaQ*$%E0cyQt_*@QkHK1di#fP_M*}axi(G6AJWy%j!x&;p zV>x-IeBVdBsfC@;9S{jD%q!wk=@zXgOlQ`(1I)Qp5H=sZhW~sMF=GPs&GgO*@YPfBmc$Z3{U5ii~CO3;)sMeRqj@fr&B`$66QB zKdld9V-umw%5q<9e>az17{;YOL^|)xEY#j|emlZ4bt$+`5=8>Cb=eN>aKMS!532U^ zzivZ7^VmFpxQ9SO_654WP98wV07>y7r>@s{mHL*GpD$A)e()%WaXZ_TW5C$k+kliF5teJhxYgoJ~73^(XV!5R-A-EOB?)AQZRLUprHGdkLF zgFh*hB?UVIW&(UAt%emdKTxo2 z-P5%ag1@*Nrpjc3(&;_XTp*g;2P2*EEiW!IY5JN9TS zR{iR=pFi{i36OA%>a2E^qI)fp3ZErNWF*c8Tw>@1ToRIzz@+md@FZh4%m3*&!DuO; zysR=SCrcDFqsrvZeR>zh8ZMBKR$am<%P!ODYXzPW`HE3^2jWCP1CZ$(Xy^1d;=~p^ zhCj87euAT6T5Hoz#+9^7mo9iG^Z4EAWSmPg8-O2g@L}`XGZoHidNcgl*f^Y@%Gw(7 zxzFU~%`BIQ_;Jb4j1q6cW!LaIvLTA#I?wh6%;yu6FBW#WK*qgetcc`&HjJPW6zfDl zww0zvR)gN-VnlNTE4l$X9mjyg z*OqH!iVthv{E*EHI!{`|I=F0oqv{M&G3hasgJu=rDg2Yj9*E%7i_PW zIJhZZE<1r;XrQZczZi)=VLG0H-Tb=p%UJFEE zDJ0q?WfN^62=%)~F&&F+KqFaagw@W;T5p$5Lr)fzq5bxAz+^P1rGGg>OTL}i?ljT9 z3`(zs3l;0hYlfP>j19Q6uA209X~M5wM_0^_!@s7m;K@X>*ed!8#Rm$4t~1EWeM&wi zz+prT^L*+*xyrvQUHz%v0(EN?`(W*M4d)fWb^Pmg+RMKB-%Su&<`M;KnBI*fo9|#8 zs{l$W7=})5l8*C!q(Gb#c5*g{mM4Y=a>}I|O=2M{_$$GZ<;GXht?pY>R9I2yxVHVr z(USLp)E*h4%WU&)$}Whjvgwl~4Qp1ioz2@KCUXw|QoM3jbMFZALUb zCpOX38HKL1zIoEm_?4h*kjr;}ga zjqfhl8L*N5a@%*sc|bg)-_R9Jb~yO0Y$+*PFuO^?2)7K$rucJBLCvBN!l;R*P0xaT zEO;nF3tcx0Uqxp{D88E0x{zuE-b=CTI)b&<)4#y${vc_BYe$xNvFvC8BlE}fmXku` z8^-dvkdW^_H~U!0RNJds63hRSimBEu@5)z{8nx3_k+e)8dI%VJDC zEItjjY`DxSDYqJDO3G16z7aK2xX2mR-UR5^g236qe5}vG4}DbR$FO+yThgeAw18=J zd1OR!x{!sMEg<(wTv)Q+du^?ZCmIm@Au#1|272bX5(w!A<=Gn#0UUA(AJ%*`9Yeo? zt~R~XhJ*~S>p_+Ol0tDW{(i-IknKvBwMWps_ZNU6t=L*d_Uq^Lt@g)RUsF|a{cE1h zGGkcMqxlCVSTBHLl}~U-l`NBJuRP+9_d$1ddmXsC0DVo&d@Hoa$r zHiTB>3G=bTRE)m8ygShUiRapX{ibl}z`Y*j(HC1ABY&Oe{#<+T$4?8I(r5l)QwkQX zHI7zx7i!g13qU%et*EshaX;=H$k60`-lHZGf1L@(;8DtnlKum+d)S}p^RF8Z5C8^K zb>l**wxdy#P%G!%^*kUQM)Kzwb^Wgn1-)O)uLj`cBDSb*=}RYf`T@5gvhb{I+1XI< zOt5OKiKDN>Vtqb2H_9UoFDxORP+b)$_wBGqGJt}FL)k5>8i){uqlmQB{$ey7?F~ii z`7rhFvYz;7Oz?RP+ulCg_07ahNE04+Xq68$d!V~kcy+m&3CldAJG+4=FqUv0-6iHrrv&MoZ~rugG&j8+VoHDezPN%Bs0#V)c$iW2o} z!%i+U1OjS}z!s_K$0Zp6Ht5*<(E4in{VxD{HQYlingrfRD(JFA>Kks4?h)emHuXn7ZIBeU?}|Jl`Jvt$&8|@E1VI=lvHT@lTTa zK3vmdsAIrm-Z6yl5R&6V+b^G$*PX~ttX#fLh|_G&^*jNFgxmoio5RrwgYQCj?|F$l zsjGC?HQ`zG(c*a%yCzQ2#G#G%2=s zK7vb?g3^l-=jD~ehUrJNBfj)frFgkh`42M`M1Ya`AQIces(A9IaRGk%LI*Cp-ylRonGTdJ+ISmENe+L4EQceW8Kt)U z!<{PcJ%E_7S_op;D~Yqi{&RH*3@}J{Le@AQIVC`!G5uMkYpxJNtdJ@|KZBZSu^3#4 z?_HqAs;N|khw37vske<+H2$O#5jPoSkL6_??#Gw_B7xtXn*N$Ui8y4X%>oUSa?y@8LyQ@odL5RQVqW-S z8pIJN)WfumE-iR;odI(k2OP{FC;AKE>w5!J0ANTUl4-dAsIO39r;vKoYkHVmO;%QD zD@R9VZw$19#*kisP8Kse0+u&F_09btxp|BGlp>rL3g;0S3a#xBhrNM1^Y%HN%hP#@ zd2=suWH65WwLX~uAlvNru{w?P-=I;X{7oWgb zg_+kd|8>rfoxDfn7R`Di!`f*qsFATCmD;`SyP+P-S0mp%w11rq_KfsuWY`GCx|8~&(kCT^S-HK(-8`15~v;o-DXSN-6sGa{%0hS z9rgp-TIc`lGXIagfe@1InJ2?FUO0X`!B^v0U)Fe=zkpEiwc|aEq~!L2{rxXX|L3&- zwHqjQfy`$(+Lp15mVBcJcK3f91g4oBu!9lH^qBUa2>#dl*2!1DPjgcSv3S(!R#%dc zKkcSxkfBSZ))lThUIPE?*=tj>?2@9{&dc-%GpNt?#waQY;YU=}k&mM1NZc1FOv$|3 zyPe?;-}>+@$tB?T15qet1`x$=Gs(}bZp?k&OOO8RfMiax~OWKbw=8j6yPsVMjR zwRYxo1kC$!R`a2NEpycV9>h%f9pD56cJYw!4VM4Lc{%LcWN<`!mIT zuO`?)VO1}c?c6M%FKmwCLPG3qBh9T+`ijE18vQ$+pd<}a<14V!^+|m8yA>bm73L2^ zJ{TV`>Qj#bZYKj4rd$8rq2t$U+td_wA{N5fCOZaQRh!A_?#(D^S%T7|agni`;nU3&i6$3BGcz+0)%>5h#&Qf+~>}fm7gZ>}V-U29& zuk8~Z+}+*XEx5aD0wlP*ySr;}7@Xi52<|Syg9U;OJ`mgn`R}~%_kDYJ>+as&s@v64 zQ{CtEneOV-r=RC1%BLDp5q{@};=BM97?_K$qvv66IYJNf+9D(KTiqysq&g&+v@5QI zOB}71Q_P$%DgAjp9&2VSqLcNG)LC_6I4$yMl*?)^-`LZ+8mZKLWmop{=%^>jf-E7e_3iQghr*EFtFNF^9nv}PpF$K zrB{5Bi97A;oZW`*AY&0#S&GZh03+4LH%E|-ZmBGe^~ewXC!-6kNv)V{f)bkJ>H zhFfIfyRVAQ{N3b4w3oA39s5cB>ywmM~ZTyGsc^wp%b;OVpZk+dNQqZpp@ z*FS(!)dIme1D=JALjS?p48s)B%|i{xQi~wq0GI1 zO@dob|HBR_@qK;1@e_2Se?Pu?<~3qC;!N#};xjV$;3}vg(-qN^N9uS^_k+vskzxpAwP!6M3Aj9$$qnOGduut}ABPt|2Rn zi5#6*2n7aTFF`Q{Wj zg+SNaPuy)iA`6oTnRzF5lc1Rmjw`iM25UHCCrKjUC#-LBm4X9zKPGw@?W`>@o4SQ! z9-6zW3`Kh5!4{0Rzt3y5xZ*mFgv%Q4zO6UNL{Ay15|oqPvS@)NHGesVF^i{iiWooL zfRMay-i-!^Nd6qOw4ZTAt|2>LMU5YC26jc-LIUAp|s`Kl3uz!tdSBiUcmM9Vg)+!7jVH z^zleVo%j5FM}gShx-Lr=gyhDa7gvTdK{ax{IOHHdKM8H`J&xR6qL0ia?K0pS=O&^F zWj>E;N0EwjMt#gtvk5oY!+02y^m^la?l_Hmcn!@K3cOU2UdFmR+aF;HpPoWxr1urrD zrVYF9MVdP|LUA^1kT^Gzq|;-lmCt)y*X5Wl~$JEHxQYD+5F0>*v;o9gfUWR*FB+##J$3RnI&mW(}mA$AQH?JLU!V)b|q=McX zxk|i?d6eMZmS2J)kbJ?XEcMqp3Z*rk9830)oU|>&W#lyc>uv?Z$Vn!dzCkjrHM*kn zddIvEC~0lHF*+QY2tgwHTvJ)sq6{Gi2rm7k&M$-CNkL5_X2)k+917+!%X$@lF8;)_ zda<%-(Lg;hWp_eDdFc%FYBH@y4!H1F>Yzj9eQV)ko27UQfdADc3=D z%vwu0WiFmPguYE=AD;xQ+4ljFp_74FbP;OWmtclk02!Fs``(q~Fvw9de7eL`bQZ?g zhmY){liOz-{&8N0=W`LbS2KO;BBZkkssAeG&;E8u(oToiK3%irp?i&)5ZU1nB66BH zaA$}H)5w{JcqQBE%H|Q+fsJ`BQ72}|IaqW2{=7F?Bgs(l};m3Ga;VwSjgq41#%@5Z~w)?6; z08-!IDnmphbREZq+nq`-W#)Vtpf?yuKvysz`WiBp>bd)3!FsxBHA9M&Z23oPU~Ft~ zir>UzR@QtXl^E@ND!oRFq2qU$AslWpt95v zl>{6UdFj3UD|@v6AW0|qni=pD9tVE5>k$k`6?~ce=I-I>y@n7cw3#qbZKUBkU|3ED zRRv1@IS+azekP6Jooh9LA*@~vWJlcS?XF%Ti~j8 z&0``~elf}<6d4T$1aV!1vuqT=FaZnOs#KZL#u1pYku})g?TN$T*K9+Jl;99j+5I@n zCxoZBM&vzks#v2h@$l7g`7r{~NsUClyj1!`jwv0rt{DJS_^6|Pa97J9ugyG3FP@rK zq7E9MendZlSb@JUiuL$b%YRB3m#sKntdAeGS}<#TLO}-!Y+DoLE>yQokV&ea(I!-= zFpiDG!uP-wwS8DmwQ=y(G{{w}8cs zH*RPPv+&CAn8n|yf+(QRCDszuQ{D!{SW<;-yKmPiuqir8aZ(XAbrmA`q?iw*JRT`xF5VH$gsA*h zcB6x4Z=-rKM+W#!u&k(hDQM+{*N<yUx|Kq~#mQ6|~v&BUt+MjbtO4X$xdqg*x) zS3`@Bm@waPuE*V_X*0Zko!;sSSMH>v3of{C#3^06w5II}gV(4LP_&R_i|E9TuKZAk zP(3MJo<^3_0Nrqv=i3ONzagDdLD>tdx~WuSxGjP*dmP zV>wvQA}loMRH9jBAcT>QL}H0UA}8@ZbJ~2S^ia2B)@b>L`SM={3|pwkj(0 zOvXf9xxYhyboVnHSt8Wppx)N{y_9>wk`3<&KF+<@_$tbZj}1iHtW>z)g@CcxGh ziVZxq;FzwYxM-?+M=NP#VUL48URdEl#fdoKU!})iiizh#oov_G;8TxnG=>T54@Ri4 z806S$Z{xW20CleN0`^sN9Exu^gZ5>}qLHg|J8f>3b*>&Z<8d`=;h>CQ9?CGyag!N> z4raUC`bwO&iMOG7F^@a}(p(F$LTr&FJNnqAdM{$f_Q%06o=P=5^a=~dsa~xbGwVIE z-rK<4iC+MY{LNn@OpVa7IfE2Oqf_RGTn|sbm<}%jGM@8HiN>Q-#UM*k)z(p%wPcXyPQa6rH@QTU-eiVy?Knb(qus{|QMo)J&f zdL+&5#BK}DtsmW}0op`sSZ-qgEmRzCm>32bZkasD(G-c1`+7N2?hzl(DyWmjNlj;+ zqVC-FGZKH&%DUaJ;P1~#1V@w;JIlhW39YfnLT)8TNRp9c)^Dtd`KwVGOG2H-i8Kc@b+#vD6c6!7ui%n8DnVTUHa&e_Y#+xl9%? zRRIpa90fZXrj)bue|6snRl?V(6-n)q69^sI)5>vbIi2kn(xW<*yM$3r7_w%eqekwU zbd4_8%*~9H-JR@$)%Mikln+bCwIeXm|DA;QYIP1rK-HOdX zh7#^7ziCSU_S`m%w|ZAkIRbb6rWchK^i7>8_)VDO;wrzI=Trk=*qI^`S5K+*U&Z+n z|AzR#N+#iVw;#id)9-w_pH`6or6GAy7MzA1Sb7!q7?>!5#y{Oe0PHA)axsB_keymF zU%n%h;MR^}fBNMd8Ejz?aQ3c##H;{Fg1?a4gA=v;LE#FBkVfqqco=AReQUZX_y^$l zV#Zp#@{w--Fx4bDMWJ5^d%}ncBLGI|9Zg$vvtfl}kx%E9ngIZ|+bk_cK6%|fYk`a~Iy$;-4p<~oG z5Y$!%2CCqRa~~iA+BXpiBsP8t4SvTp(|VTd(~f|B#o0$WW# zd#~-a<{Cykhx8?dg|o~x74I#}{aC<2F|gVe-Jnk*w{szJY9>YjuJbhs)z`l6ymOSg zC#6Bh9Q@nrM991R05$gg=2QHHC7*y|veDEjV1DtZ-TZ@_UWF!U|8a_#c zNfrQIGE#*KsIa7YJ(()Tr>Yvvmru+#9u!ek>P~rSowV)MCVu@k+En=&=wbeMdO>fG z+Y%eY7!wL8$M^Y+3y%|2Y{Z=>@7})%{m^YGvmJVVNZJczUQ*ua29}0!~C>^O`Wc?RsqwRj~?8?ffMoG z3J{AcTrv=TZAacbzFUWepIX;TvLO1Gn4}jACec-aNaS5?Rj%~g>_59c7GHU&e{heQ z=(7gyEudc;UWW0T55E0fPeB_*lspP`LIT)M1B%nkN;MHY^m;D91=NF=%gD8B&SOWq zDvCusr0E?@V7DmCsriev{g+kZ`@O6A#6^!!-M44f)wZFf(diC!a}M{^4M8cajhFU; z?#nc+9clMVHVMo}BWtA8Xxw6Wumq4@F4qcvh?!Dg0lCqi>$mS#Tm`sz>lrubWEdw6 zRBA$LjxtrLC1c*@YYbqz1IV6yN0z#GO1q+=V6U;mD>2f>wMBy!MrvhqfPWxV$P%u> zCx8b*6K46qZCymH&V;*+*+dcF0r|2n3B^$P)7Bet6Z@7fIF8;12WbZrFMd$%Yl5q3 z#QI^OvCrp;)w>~_Mi(4hJ(K}a9yi#qzv4eR{r)5p4JyHiT_T{-r|hmawPJ}T zTI_wAkggWt2K;p~%U7bQB!R-jA^jfrk(0a{ftGqGL^2WYGUbqRqX1$?U z5U84{q^bqtIQFG~KDn`Sz|Ak~P%U`4yrNoXKovEgm>-Aj^GzW^nz<;D6lJeX`NE`U zeztzVR=k57-QFSYGtsHV2sbEOyiDvlE3=cfO^+w<>+x*pshlAP;g-XWWtcoj!QKS+ zJP)_z<6X`;Jo9V+zMo?~cF;3+a3r!$`E>%ShtvK=vqp@d_8CSDwP5Dkr+)x(t>WFc zi5hu$`h&i4XM5y=wi&52a825!TXhh#?Mx*nekK>8-^zpwdOMi(7$?1`mCe;6n0UYP z+T{~@?*RdOzdE&|GtMB66c$<5e{+R9O`XW=H*{FAM7G_*J=zOBcj6YMSC^WGvGw1i z{Fp_@1+R2yfJ1Tq{TUoGQaR_gH~V4y(oEw(H3Y$jDaf$^D~|YIe7fPA@dmmI*LU2} z=}AfDjLV|*t1fV`n#cehoy@a^WNZ3v2oIhnhylWmp??}++Q>Nu_P&PLR^1){#~cyD zHx){9`X>B;oJae{``m$jL?$r^LwCowd9OztQ~y;<)!k8eo2R&1Ozw_2`rSM5|L3e& zpE9a+iS5dIA7wf<74c()pfuKOye{?E#waRzb^B?JAqKFsccau){i-l z{!sIOk7L7&jrLasR-wc-?&9Z+E@C|T_d%ma+aB@tj2H0%h*#VlX3MMln&eExw_45H zV+gsMmXwdH7pKI7R|B^8c6w&{K*vS6#t;bJZDf;R@@u_$N{?-zCgl)d+^FWt8vw+@o~mNp`}9zlP9%3m(>Ck$8o}r#`9TeL6^w%)X8&$tv-85o@ME z;?fk>NrV^Ef5eM$dft_b?H8`{4M7*CBFSmSb$=KF@GYH#$KUHxM&T3MfskV|8m4M} z(yt!7KL9-W>ySg2;jj;!8K2)e-I?w#PH@!2XjUBkmG$7;l0G&xp@C?D)(dHHHaG6! zA;%ar%4-GRI5=SX>1V>>=;F8dZ?`?%q)PlnEZ}x`=QGC~zH0}>fqNMW;3}?rJ4VKh zJvy+`9cw_nX_X)XL>v*PZ2TcYGFY+r(=e8acg(n_QF+DOK4Pir#z@TXv=zCA(Os2! zy3X+~57l2EKB1>N#}NM{DzWRPks^+Z(NBh-~5XaVgW8mG0k z!2KF@^mA))=}Mj#1=ma9VWb9O;ma|+sVEI7@$AL2nS|`mg|HuwluA75(sPGVz}}ez zWU=(meeeKA9I#1l&(e1HebJ3ScInOSqW}E}z#Jg)vt+}BQG=I*7dh5Dw*u|Ke_LCSs)W=ht-qJvZ9b8EL1PtoGK1y^TAv!sMtNy zJ8<7`=1JCg?}K3X;7EiZhDf~I`lBaAsQufm-J83eYc$p@&mE1;+|{XqCd<>%#ykc$ zT&vk@`8XQ3Ebha7K%mtCy^+9DVd*Mu#`Cvc*X7Ful{~HSXB{yfN42oQzA2gIA5D!O z0gjkM0oMrv>5GsE0UkhmE&xvNga2Yx0Wj}xxM-ELqhh21^ zsVQjzv!*%31wIDPCCdhzAo9nbs)Luk2~7m?$22V(CG9)1=6v)DEnMO6w0;ekD$vQ(-!lHu9L($M%*9OJ`!vq}6;?bo z>V7PNh7s+fcir7|aLHs4DggqT0{;vmjOC?Q;6vV#U2s`|cQg~ZCK`Dd>)HDopxtT!qAMlig`kH;CUW3#O2G6Wf3pukxba)_ zI((SRZkT5sIJT}}8OgmiRl+k)SFSHOa8O<)R}Uv_kxuz;x>T#64~JMW=!(;z#W?OA zsdpVJL@W6EP8^jdNk3t>DlQ+Ab2p|_o}5`V3O369uwS9KkkhYv5tp{J;o$5BB&KC? z2_vJ_)mRuqk)c_(eUl(3drGWVt$Pl69$V(=2{E$3_UxjwTS#;$M!1dA{ndfyjiC+kIKn47iRk))Pl;6bit}sl;wcV7Pe#!J7SobF4Da z%{!)36FWTdh$K2!`&3ppUfjsL$B0WWOms4mD=(cuuy0@Sn7>IRmCtA>ZFV6)|+CG;o^JWU-zQA7&QWB_yj!bKP z0#}&J7@G_upBfv6(swdhl<7v^GR<7bBD#np`@_0)CD*OVNEeZ^9!mh-L+Pi%M^uCF zh>tY|;Tn6DjI)^mo@UNOu4))pZjD-~E1H$?-|I`X4BYM*Jjz34O_z!J6XeAAw`&ar zJ%K~J#HG#B!7jMcqs6e%A7tm~j=8s_Tvq)WF@walI#AJp9n5N8@pHIs6rA&^YM&F4 z(kNeMIo~47DJ|<(wLj5UR`@;)nHB7;cwTU$U6_`mAk@*e;A16)uY$w8+KWy2)Je9I zm495y+@>RbtETyhTy{yv*G#N2f-R^NYh(|PAF&)FTt9R=!wPI1r%^B#9wpQ~SByjx zxu5D`H&a!BD#9BN2zAJCr2Or38+PzLji1xUMDQ0w%aH)X+dH}`K-|nK) zikPyN%q+sNx*>>~#BAoTvvd};ir~1hN1B-f5R}{65WgVnMJpf$2?u1)ionj#U!cosTx7^6?lw7evSW z>)j~BRsmLPY2!3JSXnOpIPSwvBut=eE+WL)`!woS0wrGNPAF1wjuxWcQIhEBYtq#Z zb%b>MxUw3Y{>+y%a3^{HD}vDl`Ad)?!x317H9uSQ%lcw>xj;TOzVVkCaMor}d&CW$ zE1pqT2X@?0_HV=nvA76oWNK7^B97BvE4QK8+GO73nsO9orJf~KpLMYbi^b91-*wa| zGSft#SGVoq(cyg9^@nSyoIN)!ipIs@x%pG%V}AJxd3%Ae<{7Ju<4`|T`8cxb90w@~ z`|7KXI(!S(k`f`)BpMf*wnWv#lnvM39pX&GsqA0n@?0jF{U}elpeNjGk*W1Ht;Z(X zL^x2(?vGxPZ{R#dG#;jFMsUiia1|Td&Cm@O6-kpFA-mP>qexvl_V@6bL zjz4Ss=AUJ;U;#nxpMz4RrD&#=xZY!Z6^B*_RoaUT_pYk%u$(v(?VUT%3uDBlot1w0Ft{<5v7~l$m z{m`r)w2K9T3b(XDl&9#FACN}a1323M^!7M^b9o4M{iZ) zn%klqV6)InFjmC?$O^tqUn8lfCo~ zgz}L%>cI>UTP#NY?vT)r@BQ5^&*-tJqj5u*oefGUgQb2ZZx1qRII9hsc5`DTbH1Z2VE|w|sNILdz)}+s`lR9n5pLBR zm#SuhnzVhD!|D&-IU31ndA4d*jr=*41EoP}ikWT1zKI6!@-8riaDPhQbEBzfXMh^U z3TjC6{RfaT98ZSwYC>cGuIt+lH3+@&TTp~THRmx3-v_wFmXDtm4L{p6q9Dsv!w1c- z0aSE{tL?R}1f`|grqO~!z{0bdS0@nU?256y;m{px*()Zi)M@~uL10LZYewoL&!#|npn4dy2Li^ zvy(*QtkrWJ)i-Q~I65c$Mh`$_Exs^a0ZM4jOGaF0nXPQ=t6-I0Z4LNPkOQg59wvH*rQN>5(a)4M0iMJF@LwzKKTWb=o1baZO6Xl^v zC~%sY$>+_}5Z=wpQd`{fJar1#_YVM?!D*Bkxd1{F#q}#QXE;a(VKNTC9fZ)shVXM# zUVT8P(Im+Gg`&BtHu#lgOkbZCV3$22SLYQ&v))p`tN5og>$95BTU+slDg;}ceokxG$7~W;{)OS46hv$zoKobS^(r@y`V2mXcy2yKx{@LlV+&V;@A!SEycW=9;uhWLdYfx<58c5^0Xx zI3PU)%;Yykd$zO{rL*u(ah8ka(g-+aPL05zrrm~cfBDS@`V!yE^BGZaC}`vqNLvng z91bwMPG5geXwBFG2}yMy-N*~|X|wGH6R&QDqs zqap^0PKatCHnPRR!23Pl51o5e7Wcb;Z*sk{L@g6+8Xavdm=W4IyBV%FxI4O14i>(d zVT0dYM#j|G>3qGOD{&8mMlkqIB4i>;dUui-ULpz4G5-N%E#mW8`PdC8FdG>jHrg1D zd83fOh6WlE@Td@mZ_jJAjB@nkEVCl6xC+T!8WWqn{LI0UXl3*MJlgYlX*-swC@Tjn zfzFd31|LXrc6%MqkhOoNAn)&iAB{Fhq(i1-@`z1KxU%ji&O50JA?zPeQ$*<1F zV4>oV&UjF0k@>gH$T~^8(Wx6EW;w11vp`9;3(cCMa7-jmcGDQXMccAj7z!vTej-^Y zRAOVBK`;Iy(LR^~D~X)k&uCZTC}3Yrg5QIQky9-@pJ|ynX#(lxx)N)MX~&<>OQ=;m ze4fNa*F`QrAa@e^ZDJ3eo5|TWi6${pgW66E%ZP!KJXOuSUc_Qw98PZyXpBLsezoK7 zKdCgb<;K@fyA6+lG;k3uRSyc$R3oeCe%u{eSY$tPy-2xjOdenfJAa0Qbbe=*{nn}n zb1@N)O-0i+SCyW4neYd05pRz zKKA*1ztJy~9dHt3d01#8b$CG5(6`UNKOTprh7P%n7Kkex-aI&Pbm)qmkf}T*oaw$=k@Q8>mWC^!@dgeaqc~d6z%SpIeI3R%XEXD9u-b4vybC6 z<_Cu_pwR-*<9F#wAj_NQ_czmvu`aZ&oyXY;l%YD3Fw?_1W`OLE)|Ftxv;O*f(@#i$ zo{#I_O*$EcCmY_}M==j0CM#Ns`=xmoy49hPUzK8`YL*4frVnk6ph z#ZA}Jsi94FpV8?6+K$P_JXn@he42*>JdG<3NuEn+?eTgAyBWWH6onNR^oD;MPF=kB z0vMBwRU0XCe{R3>8?r;J-0%>9zGx#19})l9q-Tr5abrgeSGyV<^yfR3)%eVQv{B9F zUB$<#jY7pwl>HS(KYE&f+P5o*fw`@MWu(EgWVhKH?s2o#{J`D3H@OB&WjF4J-wO)^ z8@>|wQGB#PNx3Ig!stXw0YlXt)+WAK-eGen#+C)?P-;yu@<@pDldR7A5G}X$MX?{WK zIuz4PnZt-#T59-@8%IirhtEXu~}~tiF9%6_PpHBTm6Pn z;`DqQB{oPib|18Vae^#DthZ2NW_KSWPaT2Z-(y^nOXI-=0%?P0lf>@GLb61`Q zyBjR1n_OFM=fsF&)#(dE6LT-Sy1(Q?WbdalvHx79E)zHKzSu63MNm0e1heky#V$*p zLhV5NVY?7|jql;63?+`2*}0_(@ZWfTi6Buod~=++ZK~ui>AQT{Q>k112hh(^DYFIB zpS9)}k3n?-*-w3TW4wE{{H+ki6~{VWuGx|F@f&%qKJIYB08Ofco3!G^!^=Lr5nL^K zXh8TNFnYxBb*|Z9kss+8J`u%knW6v_NL>-iPEaE)*BKrtb_t)X`wWgp^C|f9eBj6D zfYh2rt=KC{P9u_YYk+PM#2=%d4f^x z($87S+1gWhoK{}_Hj1A=P;3u(sSl=Uc7z4|?#7(RgZqws7jS%wwIi7u^87mTIDbUd zAIkl9`y6{&{8KXM-TY-Yx!EXaJDB(6v`RBnqDvzLy>wzK=YLxQuHY%;sVa5kam-I~ zVJ{|(69;T1nPW~TCh`TPo{QD69`E{yBn3*6Ca!r2Wf7SKh z_xw+%6FWY~TEpaf!~*}Tc~|t6g_3pDZ7ZiQpt+F2H#d-^+k4mlvh)?E?)BS^|9kNc z%HLPdbQTb6=8a$c<^TH9WFGHMlLzG~$)U)(hCG2NktxM*fUhL7sTo}VuPgrlc{>h; zpLm64FTVmc|5rEbe<(Wbc@;u9!j2m5<2MB3WD8}N-u8DUezxo9ODSQ5};kUuUwG*cpphG7Vgl~~d;qD%h9tZ_PNo!+>(O_cP;qn$CJSstd zcxSe2VK?t?58UIQO_M`tNAIDrTvZ42?W2f94=o1G7(@nM5VjE0lqIL+0QW}o68cS` z7kkDBQ??t)5~iy@blOHh%`Y}^x~j7=W?#$e&hpja-D_U=PZv~vym?>^=^Qet{_Xpn zXqL6x_L=AE$C`XG%h13G7_a*T2Z40^^0QTldxwb3E8IY7f$b2|%+wn3N$D8U&)e)P z2AW67N;oaYlIu45H;)&DeASG%lyf=HjKJVkE~ z(uWm%rPm0i#zK4Op4Du|2~_)B_V{MIx8otl6`{_58^7b+|Hh<;Bs|TmmFr-U$BQ!w zVZZ59Ndfx**y2A@d6(bK-XwX6r=Y9UGl=HGtD?Kh0U3RuR1nSmlz(G$DOAbUvOhefpMs($+Q_+iQ9zHBCne*h!cB}R>mueL~jA;^5Bk1Zu_ zMoMbtTWY#4!lUa->vxickbwPXy*d$uHGeN>rq26S&uuN;y!KtG#*(nxZ2;Z(+l-S3 zTZ>bF<;x4tk|I~}fO{8aTVS+Mmv6=15XbSYEm6xeaoSQ7u~Mysil>BZGj%Cn(e;BDKr_ola*dCnJ|B&CyZ&d$ zHKocrxFub?%)h3vB*TIZL@OXGY&5D?D`#|}rKP74@L)kejYrr2&WpN1cso&tqrkk3 za7CGfkFoA}7O?AN|6O{tvKMZEkR7b6LX>y%G>A&_b1&_XDap?uH#9v3IiccVwznLK z){s~?AB_fFg-f2CQYG85iK%@dhQ+@}eut5G%&$UAAO&`9v}J_F)`N~DV4m{>tOe9h z0eAW=RZ$n9dkf5s&GSKGfxVI4+eBiNb&AR^kV$8!QyH74IHg3_GV9WuW$!sGjNIP* zc^>I69GZTLkheU!;pc(ikldiTyb2|RZ{{DWXup;|x1=-M@3TN`iMC#EpF&C2MG;-h zvwV+LF_q?!)-Ps-zyt(82o!I@o45to9Wk!E%G$0bzhBK3kYUrm=cCOLtDb2s9P@7*Z7 zK-iys@ZsGwW(t?4{o~!tyLY$kC*zf(hnMPa1>SKC4ZQ0_AeBu zCP!b7f(H(4ullgw+c2brjj(&+iIBA4l5E5$Gmx^+k#{y3$NlQ=hfhMJUz-J`E-6ab z&Udr0P2nO+zQ0%}>YWNkdNygkqc!T_O}}_&8E=t|4YV^wUc~iZM?D#(cxE3ve^Ei=E?#4u~$|jM`LBt}LH}M;>2waTR`# ze4uN%2!iZsnF1GrxF&~`&PbmIHxO1IiagF2Nj=P=*dNqojPDxm%g3mIKYP$_g&Ci^ zwS&vXi6oeKBptyBM`$cQlUzV@yF0sF2r73UCHnC?Zd2~hjpiEKed`Xk#M5C|DfQYM zK?kwJu7epyO1l7@qS5Vj=H>@YZGI9vrGw>dPNrBV*C-?bqDAZ7%4<_$X#lUw-$Pab zN)*xOp>+`jsrLs!tpPoT+sxFaL$|XWe^rE$ix3ItuV=p ziss$dj}|pbY$R#@%8g8v<$$TupgH>pP?+VaUAbH6_Vpl9Xx(U?mtL;M^n5rcQwrN& zLfzh%b9Y$^N?ZWHy-Qk*U)@PsB8Ow+UOclPvT>;@{6b9W-SRt*VZXtKmKtvsy6uMD|Ec|LCUxMhR4i0 z7=QEYT`+G(>^N4KP?Fc4|KmUsfho-Vv?QNo>XkVRjOwS^pJ-@87RyI-!dF7keeb6} zfAK2OQN0my5 zc4^;^Cg4Vbx20UG7anA42vpwMYbLz~;oHZ{smtq^7fk44ko{Ux#m1>yoFfEi;cMF0 zjr*Q`$k${Dw8#&e1(K!GFZ_D;yl7sh9I&Cb55V&-yK>(~>$d)ZO>Hh1%&RcY{E-5H zc#5zbIif>^fG6$4_`|Kx*-;bWg2e03b@G0_GYYAW9mm$tLaJ$k-x8*@6`N{ZiAS;> zPs@0d5-pRR5{qishOZY}Q|Vc;5XKKo6s0+28tT;@(fpZ|CdQ#7d=i<%!R8{Szn0ro zej&igJH$e(qq`BQnB*=i0d7|FCQMDXIoc=bS_`XoJTuyRaw@5FMjEzs1bC~HxBtQk zF6WVab#-XC(X1po2Srmin%Q}nP@iCH_{J?!<~zGJ>}get^XCj6I`Urx@$mbk;uxmv zQ322bwD7T|?A%i^->)~Meve9rHG5ty(3>Gh(_U>icQwPvW_~!Xdzjb1C~Df|EW;`H z%n-Yj=kAMt{!yS1W`H!$u67w|$g>wvLQqyR!#qc-FK zD59hyS^M+f5yh+2`bjI^Yu>L@1>rpCz10C0(o%t~O-|}W$y5ahRA2wTU4fVoGJGh10| z9r0_Pi-f=}W?rZj$4+^{JTJS_`7@MpXe^5x6RQbyLfjD|`v=gn#vhykP6pe=j}7S- zNa`~cbN(U=$OFiAWH1$K1iM{rO0B!xW+Ehl6x71$zVySre-AG)Zr(EX4Oz#?Y&MwvTTBQ`IzQXHuRHjSFxpF_B|6kr1iKSF=85wrG=grn7y1;)d{ZF#B|-K$X_q zr~Zgq4fTA}LBU(TpZ_t|)vJFP=fM5Ry=Jp-P5YQCRB%1()2I~D3j@77>BREv>>uQ=W56JB&QR<_ORxv6*NX2=-o!Q%P;N`gRbf+Iv zLPWC}MoQBoBl`~F3I3LuahMxwy&3t+xU%lQq)@oJXs^%ZD({j85a$INw}oFhl6a|^ zm^F$wY_|}c=Po25l?bk7+X;5>!kmt?Z@q?3o-k4|+5B2O z6sFLfgKf8i@8$|zoBKdK=Q-F5fw;$)lt-M=lH0AiPU$g0v=EUH^f*3`k62FLuSU#j zq`D^YP}qw-`*=2Z7LZ!A*?+2>2hx4Sl|rVV%q@+_G_osWLJy$~oo`h3FRn?H-VFt| z@bG_6{Tw=$ZVOXw8j+rK8W3hm51LE#9BoY%LI{?^19#DB907S&LLA z?$YXDDeWg&_!7eVVDL35EEv6Bo6F$#enKv~;*r9lmzJWUzo;`Mc8>VBeJXL#k0DXF z!8BAO^nU=P!>f;xMgu7BG8V`~ODL_?O4PzZs6gjRPN9#P_IewYZp5fYTru#)a>6h; z%n8c(hB`2FVSq&dz{WR_;G_x@Ngj2>Am;{RLCbs<><)x7LTu|456sXMu`5iBrnKE) zIb?r8f!(xc2s4T(K?5w}{?qtpY1hS>AvU2@yA#`6SRwD+_-!WNIv(epaBgs}E^dCP zM;lmD&!bD#SP`>>(JbG)&MG5vFpR6$5aIUDMAtbs%87_RpOs=n;{Yv+@~n`s;Efc> z?J+VxmJpZ$7A*KAWU>~EFEKe35kF=;jQS?^#)VSyZ0M&&0q(nBcWFV7-&l~5No9;A zy`T>Ah%6Z7g!?b3dy|%+;&y#=#7LjtJEK=i31^Hkr3;i%5-0$kwy$#MX7G53oDq+_ zig>Y7;G?(is@%gE1o1M_#EEREk7&#&6ZKxTli#tgHSIU zzeK*jwV@&<%ka@@1I#~D|AuuXVu|iSlUiB0!V_v&V5ltL+@lZl zyL5+ojT@e6e~BR?fgev^F&Oa=w#LimQB0cr**-d4e1lkp{q1`A2asMod?yJR2e>@(IpuPta?%(CBiB0_uzuwkF4rdN-uBJJDWK?JR z@#kT1pBT$ScJnmhvsU>{6AKERz|)%oVy#a?-%plYRGF7855$47iI<_sqV(2;=^7Nc(ij|8b4-+%uMsLnBpeCu zK$)aP@Nn(JJLWuP9{avymfvvQ!YjmFEd!ptoFI-DLFWtuB0jF6*Ah@K3>cluptOGh zbI|AIP&;3$wL$%mJF0Y#fgiI?8ZCT2`*k-*JZ`azEuWZu^AcdEZm=KFGz`3|CMu`w z%Zj;H#vOuV^=)#+5@K(WdNQ>^tX7XD{dW{b6_Bi(DVu8ejxQuq zZfKV*Cc=`z;S`GzR&C%TDOTzF%b}i#O69iHR=VOcI^Tu&C%CHRHTO~kW>V87aI(0Dx`WUz_xh9>WmJ5o3O@o?90SFl0iUZ_FwfW@L zzBguuq+_t2T;#iKvD;d{(APcpEqN}zy3R8QE!B2#QTW~%0=ku3(-9Q#_JgIId36Uy z)~dv=&8tnR?!n_DE-tRs#Ua<*^=2$wuHPm&Rxp0kpSy;~&QU4shz)hZ4>SxIUTEJQ z?;gcS@>V7N((uRC5c*B~K``y;rvhoZ$irW=sJfyg)sEtJJUK-6=BN8%99JPl?Y2Bj z1)#MEL~Y9->o#*SGzO7~D$};KC?UqP#CotmIB3^UC8SaZyExnIqA~+Ta7-2wMT0Eu z(fK8O(47g7f-%|kepn$4VT6Cy7HJ`u%%68A~fn|4^kU8b8m^b?#lyP@z^K?X+Pdm~6xq!P_tq z&FNW&p(Be54eiio8e|#l$au*F=t`(09I+&a7%D5BTh=?UfqaY|MZ=EEIL;AAtwu); z=Xhoo{Us=X>dicbo+7^NzAM`euhdw-ly^dS6Qh$fX>4Qe^G*`u_1#E)2v3Ma9_$3- zkI0{lSj~>Pog5gRhZ)VL?OX$Y1~D~wc(X(W62k4PjWS}U-4ie$1zIms+yL=s9*;jl zp-x>bYm$OTGoy~oBv4sx=|hRXF8}hsEZq|pS92LAX4jsO5NrhjzD*x+gG{sKdECAe zcM3YE^1d0Rs3-&!FJDIBY0CBVQ42fV1(v64HJ~Kp2<4}`yI*}WYN7*Xk~)B_v)z;X zPBeHh;J!TZCfYiDRJG3&Y$Bp01Ml`iq_g!tWy&p060^w`34B*Bc8v_Urhgh&Q`z6F z$Jk$_WyAV(dz!e<&dQISS{jU0`6}cRu7t1L?`qr;zk5_y+_XuBi!PoAF)tMhd2XgJ zV>LPmSjrZg+@ih{)8jZbk)1qOgO|ZqWB!K3j7cONnP=Y}jd-lD_IznNe8*E6#QJpS zo=F+Krm!Xmx58V1u}aUpkKe{(fUbXT?^IG8fDnxlzFO3~B2fT=?an;%AM6s9E@$w2 ze7|ZqaFZ98{KVFvk4>L*DjVt~F5UUyKS98=`0jU;1XqJs2$UqwQOxh++1P%YCmX0l zf`LKZlf zwBSA2lbgM{1y)7!(&l}IiJv+kqq zZ>nRFZRr)hQOQ=}IZxmbcQ2Nl<}$qfLTC;2Hy-8PtDuSHYtq`v<=0-MdBV5ji{g@8 z&99F`H|?R7nwe)eFBX4OzeuV%3L>psgtgO$L@pETN~Ws4dp^t`OFI3}o4B2tzvA4~ z3Um1nLzB?>9U{|wx8}0snIu$6q#CLuQvNXXuWg_T!WX2 zjT%_S_L{f`F-<;)s&z174R5~ZN@83@J#z(NjRc0kts9D1(h|-yX}053=LQ55qm*&} z0|4QEef$StmuqO0P3%< z|Hjr^hqV=S-QvOB-Q6kfZbgbii?p~yDFi3DyVK&XMT)xyhe8QbtWY3WkW$~~`$5xnZ$5XPsw?6MIVDFwMd z*WGtU%h7ip2c4e|fw%Q*hpKYG4( zrLlv1O^b|bpyb2ibjmf@0ng_9wOmYr0X3uDwVd$1MU2Gy#8$x{%bN5tQ0Q{7_8A^7 z+qhmivChh|S;}Y$M~mf5%BadKM{sE^R;gJe61Q45XmZrqGW!lXMUPJ}S(n!4Bc5!t zXIMVI;Y9dVNSMsK(gp4=S&$pFgxW$8BETN(@xg7gr_Y^eE~3|87kU*}Pwe`-oyO-V zvx{r|I!ww%$vXyFK{tqX%K@%tYy zS==nP4$iRDj@Js6YzQWAy=3dn)Wg^6fy;M%I-2$d){Amvc#h5gseZ9uX3d&@va3%JJ6@B{kX+`xxmRMb zuz()W z#834=k)_qdK;r3(Ycr+m&bbV*2Lkgv->=Mc$qcOeX7R71OVljjrS#iaj|mdAFlnbs z_?k%faxRa9a?&u{$YSt;9d_UF15B{0N=k+U1q{#=2R>q2CmAtN@PCEAN(ns{Ml6NJ zk4fj$)30$^N(4Xz4HlX>8@#m_N#|F^KsFA1(5n_D23dQjVHes789X9-=bd3I9!7Nz z1-55FzeshAbTvrQLc%W^ErhU;1HD==VXp;`H2XUs1CM(}j`J=m;*9dYxa;cd$azFp z{Exx$o*pA(ittpW+d&gsu)qyQjSPzOWIR;J2`V-w*YX|3kY->;u8l1ZR~QJr30^kDc$eih;Be7}tqF#d5G zTqq%_V2@k4E6}zhZqeO$z5F7$|Hc-%@?O>@V4Kn1R2|?RGLeYklNFf}=)NWmX#>Z2 zhNwz}5qo?SkU&k2=K0-TQBhd(v4SAv`eg9yW4u}_F) zr|&Z3F@L~3wyjtsF8`I%=6V&WRN0yEf$1h!dSX%lQOuuskBRkzAt_Im7WoSPkw@hc52;v+N?qsu#eeXWi*%g zk%XqQKbUH^5sJVbnMI3soJ+QGk|ghB)nZ~*O8yOQvPm$&LObaS7VKC+LQeXzSxvWp zo$$AzKS#!D$VWA{#4h|KVIk1=XH9jIU}I29M_^4~i$PR`Nr!CLT1C~uMiVSJuyykYN8@R;rZh$lTEQOUAO#{%9(YOHi$!%S6nQzudjvApkBqS`R^v`9E&QYkgCqU+yu zC9-QIxxix^)5DGT#cZmEe|^@&5^k5591+2x|K>)9kj+gg#q<}vqv-5heeRZ~21KjNqR3&Mnw`-D*%t^PaB!PT#7!zl+a0qo~?5p4}9b+?+%=$vbRrrhXy>$11ppJ=AW8 zW2*Uki=AWFLz48c`O^1E3F%9*RjE{@-`F`=zqfuxKrt^yOTeg%_#m;YQjnm(vH^vIn` z-M;KKLCuY%$kK2LM%FWa08oPE_D47t_YuWnfxKB)6>RG?#%8x%EClrNAAo5#bA*gr zQ&8KIgQ^`t)|jP(vYZ3H#5&E75>Z9!(?^h+ll3N`mAdY*cSoSsH}@typeVnjwY_bk zXNEG^qyDrWI{cJC=0qMA|4~oWi54b+_WBQm4pG3k_IFB*{*yJY$(&QlBlT|I`$+<; z+o%0*T0OY|!_+FwQaodRbth5$-xbCQ7hg6DNcy9qKm*EU zn)SeRsF+e72vIgAt5+&1+iLE|)0RpS>3buzHy4j1?Jfa_tubW&H*;v+Yel>i0l9{N zy(a3xD&SDg>G#49`Rp=O+Zr)D|A7@3hj~f!Nr&Q16V&l>%XEE^XMhEHJ)9Ao6T{e> z+&~$2q@fp*IXh&T*j9jEFr71lF)4aWJfgf$#wMH*^ZIr9&@O-fxQ)(~7s$oG5Iv_p?QZv`x? zG?f-L%h%;@9w>*f=O|lgOy||2uPEWR4PWr<-(DCezhE&D>{+?HRMZ!z9RjVSFs3?1s=>R zo8+uu+AXK};v{3mqe(?_@hs!O)i-KE`(l<*Aq@%ep=7xCQik|YSK{X*0RnUJG#9e$ zWRTq<6^Tb}OAT6BeKdRH&$EX#Sa4|n+8deO2-z%hA`V$fVq7*(zF49JiFKeY`7x&` z)m~$SopK5(+O%$A2S)p!sLDm8#ZK%veymC28tSV$74xb+W0TgLQ83WEO_|CT(e+_h! zF=;m#jyusZ1$yKa%V$?fe9vcvNh4fDNz~#mdAtPplNq^S?Ey3WH~^MHc&9<14lu$} zU$7HbJPm&wrFhpA@2_%g>9PM9=e$M@50GQ~fYhv)_6^%>pPjR%(J@DIwJk2@$&+Ka z3{?<+F{YAJ;9V-Rma&|NDc0kaZ0nDPDR6WN3Mmx0l7}zB>CV-kNy7J=dKFxs+1}pW zi8dmz*7|`&9}jxiZTP87Z|SwMTfkW(4w{p+E|tm6=gsB^aN`oB7ryFwE6=;*y)$YN z2l0A_g6s)Xk>D`Yw8WI+j#o{gayjsid0huDIek6}{O&(TWZkE~lX6e1tS_)1u7naoq$5a+k6-eS}vFERqo@OqZ&;*X$BKb~$rS zw$4-Go}?2>VaUTGsJ~ttXGP6q9VJf(yUFa&@6;W%ssNIHpxx^!+5j*WWH1TYaKpvv zB(np}ZLHH`uHQ3I#wU@>1g#pd56SgD+6XDA*V@m2r5ML@{dHp)LT4D`j@e5}S<7wg zlJC3YrhN?*ecZq0*%19C@t#j#zEg#s zJR*|@)FS8viDyXenWpcBQ^^RqM3PP@Rrj(XMY63gu>`iPG|Oh{M$KoW5kQ+y^6nj2 zx&==xmyZ0QhoLtp;)7b({L@HXjNNT zDm9O}!c2DA<$b2T>WxB>H%>4M_wZdE!(&>#4>S;wombwX2;o6{Qs_YVv#|1cs4W}= zoey$zz#KWSA1`x1%5O&IIzx#497^%(v*AF4tSQ=R8X2@&=;*>mFr*cfwmXs8 zX7=xf%>B zfE5S8lb{GRj#r30J6AQ)*eW0Uo}##`zp!0iBK>q|=-A;^x*K6($EJG&H{E41WgW=< z8WrJsMmJQ``UH%PaEo}O9?1&+HwF!|g(y(EUYI6{4wghzEv>7Uj(ty~pf90Ik(1da zPqlA92?LbQhvSF)CyxR8x1BdlIZXacCG!;K%%bX0KS+;5Ik|n>@^`O>Uquwe{JiaT zb30M{5bRuZz{PW#S{s2V%lG?E2+K6_$oT@WKK^P#ct5;_$%KmqmI8O0Ag5pQsY*$l z4;vYs$~_M0807y+mJJvwx9aC;8)njnyxOq|u*U#d#Ogk5Qf^~6^a$NEmlpSjC(rf>p6zEl z@ee0ao|)eZWZ$1k!Y<%c@KE$nhN0B7VA%E4KLE#RY?^H2HDvc*`2Gb~@t`O>25Dy{ zt21+Hae9``TtYmEGLfu2jt?LF*oYT(ht5m$NE_!$rv_4q8%P211e=ubP_y*sF!kp$ zpmVbr{tlxf(4q}{f*cit5n(h0L-9Gmx_ns38XQ3tyv@*ow|XD4cKl4R&T7cu3-B!X zly5-4mRh{K%L2Q`tBxbN&26-L1(VUlAPhX$L@5@|uV?=J9 z+aU;O8K@ZKC&twv7Z>rT@F1JO(En=iMA<8@V*7=78olD}P$CaRf+AEk6!6@7k6=tj z3=IUh9bA-8-9~(HL5$Lq2!qtDSD)WW1?_S!jA+z9%GTu#ekcUrRw%r@5QF7S z`gw5Zvf2>B*D(EmwlVK8KwM)n??-+Q;Q9l}?gVl0pu3Cz02N54mj^}e9pwEItoL0z zJRoyxypIY2pTM>sW((9GvljuFLv0@?@Xbxe+eGFirk&|6QlCbh{42kwF}({d5_l6{ zKfg#Px=Tc-IF26vJ;6D0SDD(d2yQ(mz-5Z3AP1iP1k4#is5|SX!RANNxY^rQ-61p`=AkXOIP8(Q0w}4hbK1^ zc|egc$q6qgji+4xE|t(L0+LSHY5ot!?)*Owqkwl?Rmd_qmZWp5l3QBk0FBj3oPnZl z466gJ_c8|~4MARUU}>&K35xt{&oB1K?S-jFQSgv&x+i(Xv6qu!r7WP~53mRom zag7~K=(xwJ5KL0lIGT&TLuelVI$3jEK7*?iUs(0eA5nhaWcx2sl)*_)Ry~~W)G$q) z!d46y>C6`iWvqYex`eoyk7mbCyxRMYQ&}jJ=YjhUL2L_1IZbl?DmBHp>Y==k;u3OO#PS9K3CP^lsXs$g5UzVCHPxQZZBc^)s zCFno){697#1VXg;JQNwSB@exNVPHM)!~F-yn3ic|`Je9@dHOU)=f0ljRM6AP95jO~ zI8;sdKtscpDKe$^FnCeu6zmTJ(G#yPt#c~7r=^&9Ij6QOY=PeCoV-nd~O`qJy8y|e`t`htXi z5-9A;?&eS-&M(E6|FMZ7)5y>B}JopX7LzBmvnl zg^%1!5)BB1gvqmiV)XH_l1NXLs6wABv^tEPCiLA@EE2x}zfAMYTp&e+tbGxIBl>15 zzBK)R*|?CYqRu}IU~ZY>J{UYJbjtDnHXIWjRDJPMN!TiV@g5xeeqvtPt%k~ojd1?N z<>6ZJSE;q=1V81<0x!NQeQ^h1lPAGXKg~8Qy>`8$CBvX+CBgwP8 z5m#W2RWaA1ar)!+aD5O8$$eybq^IDT&Bi;6UNE;;B9a8#KYW=#88C#@5dq82?C%q+);Q_RXYfw((K+ zAqqWEru+D$K*QZX{n~PfsjE6#Em_h-HJ0P^-O%-qm6$b0>0wckvFG7^@{TgO&;I$3 zJ0G%DHHau)<<2|(j@t|D;zsUpG?wQLH|*buWZxx0YgrjX&TR0?f3XDV@{2Ev2e`h|51uAqTIVOFC-rM>pd+GrWC_z}VWPpi5s(-yVkbq{ z8v%!3j!AFG?H4|Bd5C&9|HS8zZ$R+c--~0E#KNLYFe_F@`mA3OWJ9K3h|QRduHsyv zdkj@fNOQ#5B5gsH=$cnamC9dJUb>kSv0Vs2h#ZG9_1IE*julDag6QouBgx^)IxCXY ze7ykvwzWA#M6xUS4*gJTQD|acsDbH-cIwgIv@V+N43W zYQ9ZJl(e$TZ=a;cLv@jiC+)_kJZlKp{bfZxK^!UqzEi;xzc!m^sg*!l*iNT#5l__u zITGnp9$vs+U9Gt*3PD%=%Re|Igr7N({XP+S!qSKh8v)Tquw?0JwOgU28~90#`47S3 zs99A|FYeLLnG$t-p<#)aarpk>yZ-Pa>ORR!{vQ!X+wi0`bChfhwSMIt$tKxo|DU9a zT_`j3K+&vkAF^;l1RuSw1R$`(9}#e-rCAqpjUKcH0Nq_ z&16m>T;NMuh2km7#D2KpBG~tt#|X__^u35{9=U)1Dx@7Qjd$-0C3V3I9dAN=8%)H`H(@ZGqD2r{Q?QOUt?! z7|rB{0LQ_Y64&zfRdYPDp|av0O~79CdseU%O8)J*lYmnBI>WTd)rQ@ioWHXmCze)_ zy1RryhJlTU?W|r#l!>kR$99fjd*G^g3y-SOF6*&{2kVN7XD+V#(vF`tx^SK6a{GiQ z6hBbvX43s1pvWtQD!+tI6UjK*UxaS&rb8}WReaU!D0SCZZz*0eH6T}gMv5M>VyCn& z!8B3Q9aL1_t=6!^X!wW}i2uYN?Wbt)guRjF;7UZ(V@???lK}n&z~p2EFtioY_X%@M zlsHSwIVfN}AEqZ+b?%39A38RuomONGCDuix`_@m8rrBW==niG z;@L@ICxd@`#Xw)E+LfFnyfcP1{bT>RokzGEIau=jc7qq)&l|8A?>Dx;rx8x z+DuXpBNq4%RNxmm11e{wc)H5p_mSZ`ljy%~*fhZ0VMN-ox3PSI0+3M$Pphq~hn($3 zG7l`g=mUqF`s?lJw5Gn$4V9`#cJGXL(_yI5gH=K=Wkh(}S|qZsX?Kj#NE=9# zZ-gRDPA*XxE?t=EF6|fjcM{iIW~D~o9|V1n=RjWx+XsvLg4jh4WG{XU#>h%^U7K6( zC*&nlZ(e*wXe5~3S*_7oH=y|Kijbc%e9ZqX>p74!+I$rm6eQ{NR?1`g>%O1-QR?Tl z{bl1tzJg${p8Se;8S*kH_%WGAZ{Ubk$hq9%S@a|i1?dBKD{)q#oJ3?Tj1jHKAFM|+ zGI@+(8%9PIS|UZCJy1|aC4aO-%5d*a{=tuCt-^cFM~HeqdyNBToAtNA>hfsmmqc~v ze6l6(6D5DcQSDc+-or|#>W)K?oPsQ!bn~?rU*=4twv38evqoDRiqnH|sGz@h$y_ZK zWQBd$%4@^O@(NB03`^J;KK0`BxxHGlI#a}{*lcNd{@K`&98+z+`^2Kpy5rIj;5Cm# zXc4(eR*Wcvkuy6j$^mPXCx#vXP{7VNVDj=e(6%LC)`y$n$4B(S{jRd=wDd{8xgN!y zvtzG(ylBcjV_k`ZaU?WO#x}c+$F_uUT7`HuhdT>CA&1dRzj$(eugZ*dQ7=h8s@J{n|i}6 z?3nCRvotM~+UoG2kS@>zZphjLLf$V@zW5^fB(99-)5(YJUKq)1?I#_uh{lL{ z7T;9aoBLTpZ8}aLY{}6r)%u)F!T>{*48C(W>LpKQyc9&b+el5=uTtYvb--^XySGSh z=b8ruR?UlqD%fNZyNu%fG?SotM$uiOw(`B)(*0;HJsGpIe!%69D?@Fn8xXDF>e%|6 znky}r!VQVOs{p0Y5^zT7xlqBu*hUY^iF{>Ha~ypVa<9&&K(D$HvvWt(S?2wFjK+Yw z)Aw0mHfOml{J1rS8_dfu+kx|l-VrUl|c9&Bxa30;8B>O zjAb4lKA$^@9f{51l{7z{_XDM-g2B>kG1rT6zkx?$!B#jTQeV4A$Gd;0<&VQ+=ee5Z zclPLUl>k9a7ajWh?e>xly&{VLvuaYBV-`cS*3n+~kQNo^vwXrPl@9bM#@OOL;}=LA-qbUb)+1wc|_@N1QK`mZC%bb`DW*_ zJnySC)X{P$4xC`1D?R>!fFG^Sf|Xm`<@WhX)DA*_##N%hMv@u0r_SE>5-2d_?R_+Icke^15dI5tHpv< z0S5hna5@nm30F+-csixMFU72G&fy#F0e<0-oGuwa0or`eAg<3J=qo}fP?$kWtVK$e7H4| zM&TU$>e24>=4P79_>1gC__3kmlCaKmk!2Y)#*fIte_Uti@IvtHcU(v!Zv%CUpO)+> zoQhE)3@7;A52SE0hYQyI;Hp8H2!(6zTY}ohi+Tl3w8DUR*ts2YA`_B(&vzo6sCpQT zya4^Syg2pzk8^U8_ueFHo_prx;H(fqdj~v8vt$Bf9xs$*CrSm{nOT4AN+YdK_SvN9 zr0>8#l_la6r(7luxwrem-5|68h#wbXh}%aO`7(W)0^n#Lq6zx~g~&SKQOoL`)vNFj zdFTprTZuIVT3uWOtF?O^O99ET0gU*ke}G|6EkgOi9Le?gqlweBv^f`MnF8-z zrQ5)k5cnogL>O>-duhh)IRI@v8Aq1|tmyR02`coiHT(m(Py8`KBtV3=G2GHv0ppPImC{t=AIl4~0|JhRoAW)WACcc>T zr>S?-fYxVOn^~&d>2lbjDWKu0+`ZGHn@q^=5yPATJ>-XckV78f&Q^6R`(n(A<{AaT zx5eNMMAER}gHM$V-!Bm7ohNpASNP0} z{7~M+FaQ4S+-SwUlK~Q#@?oM1kTxzPQLa(b`Ox?E-CFlSkF_hiTChO7+o6YN4(VU@XV zS2D4{{YYZjMcQ`r-LHVF8Q1AE@w3dHT)sRz{`JB|geq1i>zve!Iy*O=8k1YpypL%_ z@;iXH|5iD5&&^>fwb}fm5H-GB4*3U6K_wXljt=q%hA=b`35wTjtODQIirf|(e%m~l z0q@y^_W}6cNL6~1$)bF*o3ZaAnUPTa<5|S_2=Tgc{E~Z|L46Or&ng+s7Y_fuwx&Gb zO`+(y8iwocgZGi-otw$(e%y}%k<)@WXhhh1&iL4|La?Zns~x$wkyZRJ{(5T!@gB&< z6KF@0hAfhZy|Z5`rBKkE-v$?hh2pqNtF;VLofD?@cwA3@Gv9a$orFLU zC{$8$MY?GP+xm%KER*!ej zZ&=Ob7b37Hc@^d0&@Y@>J8T2tcq4KeLOLF*o$F*U3x9-ubH<2WfuL*VOp zD@(N$Z?>kgL48|)!1ph}PUb!T*7X8o+(9++Sy7H{+2XJlf(iMg^Py6QGsjAOGc-%`T}e>Z=lMR<{hM zQoU1Jg|`6|WctRWx+kV7kdZ9!+2Wu4K9Qk6G>hQweX=HZLWABI&}HoQ{3 zRWEi$wSa4r@@B+Y;V7eq*Kks71KJodRD_!v1VU=c>eAx6!QqmYpPA^cn!8vzx@SWf zed*ewq|=u{=-xX?yaFMDq45GmI`3HdU4t4G2nsibiYJ`1lY6IXXsgnNy zc*W;y{~xkMW>_a@#sTA8OFwca0@<)q$BMb|*vq+Dhvgclqx zW+wHYiM$jenTQVwztE6)(Ne5!kAx??UW0JgOYe6Ug2ur249;T@mVpq&+#1^YuWk{& z-!ojk_zyniD4h7$pA%2SOvnDa~@#p5aL@vG{49*JU zF8Iu`uB0L4_r%5E00#KUKE!zQ9{?ki=4m^0`T^lT{Iv=qXnO$|`UDO}BMwRkhvHuP zerroU`T45tf+TUbG3cbkLphA;eWA?W1cBkWIHBQUQt_*2amm>i@jJNL*=}eM;sxZt zE(r0z?5nYVfQ@N9udo~d=L*R3%iUxUK}WFe7SBIG_y6h}F$Bb5bX;jy7XTc*?)2}Y z1CawFVfPw5J<$4rr%SPNGnS3}CRZi}w+4&2mACv`JdV1G3s>^aVBn;NVu^^H3q^jv`k0U#5Bd zs{jt@R}pA@?>!c~Mizel82!iA%f5rKf%1uKyuSaWy###IUPcJ11_&?*X9d=3Ag>

f5NxdxR)JV`V_q&Ht? zd&SQzpXOX?92_7N!iim7N2d{fvxEV3@wLec+ zYj?2Lv;V%|btAB;487o|Rj1Ssi9sVq#F&*?z`#@n-#|GyMrto%=rYznfJvtKjkVi$ zQTfimblUJd4S+M06?lNR{=G zAp#StztE09ci}45vk%dnAq0=O!6v#$ z^cWFpOV7?8TmN%MT+t=pV}R8|9Poz5xp1^lc%)RS2Z)d^$3>F*`C7=4O{7c)ZBOEh zP~RB5X(mKX{q)h!8|_Wp?A+x=*^Hq6Fz%qtLO95J;5_Lw%_~dgaZ37P2!jr^)D$p= z$tHO=5gL8frSv`HVjKqS7CWrGeGIUlea9anC{m(QeK{FD;?(DR2H4J!1piqOld<8UYr9;A`UJ+wCr5gZN#;>+b;aM~NDr(>_A`p~`?R zaV%NS$hRPv=r^7ASyyLSgc#(?Qg>-hVrX?_QYRT~ZYbtg%kanR`>`fq!V*BXd#uI; z7gOJ+YWrqln7D~lqREmdQtxI$GJUOy7TSi4mb~S-|0SO$cgC%2(qr-R2e|rgQ8SLv z?5h0-Nj{0b0-7gs^TEW9x%5n#iluckFQ70{6Uef zieEzLP(~d$4T*%xDThf?;Pa}Q%Qebdv{BiNiAn%Cg7Z6P$}8T`Y*5Pw<$BG^O5RHl zn6MI2LR+dUuQi|M{0fQy?X3N{hc{Do;~OD;_!H-1Qx@1N|7n*9mAxP;A$)3!tz12z z!L4nXx_{7+?nSOOXV52>(qOKB>j)*;*1}R$qWW!GMs`N8QzF&jc3}}v0cidDO1wLb z%*JmU7NU%Ar7rP>r-hw`IULC;=Vg zRXXXxz8J}XNc9Db9auuv=8t5i7d@hY)gOKn*}-OAS32+bhF?m+oUA6q5vwV zJFfnlvgBb-XE}v2o~ud4e`d=#&S6CI5zKmTEBACSbh;g2@I*i)0}N4_K8W`7o(S)J{(nnv`H<)p@Lytz0MU!4b#b&Wt_QmJ2m@X4z3FqxK-!Yh$0dLPpsjU`a}W)dvzG3dBQj!-TovTdkVa?GbmbP2wJUZNzjwX*Kd?+!glLXDe~blKYxA;NbdIk4Ud zBNJiWzX6_(W1YUJdfvUn-k)Ctn`S9nxXf6Us4Rg?c-ks}?k`Fu!(Fd1`IBdqjW$5R zt)7&R#@9p87ej!Q+F^=P%VT*c3m!+*o{5j7V?ks=^!pSf7~VDodi0mkO_I%GtvGiP z8H2TIye`S0?!R!fVG~yH752?8p_&t)6sK`+0UPgcFo)F_8GB28@w2cQ=78-npkLu5 z@mk|t;}9(d)4i4Z%=eR4FS3l6U=v;4;o;>& zKRZ&HiDLex@Z-k*e>q1BRhowX;mil;wh12484eaGy_z$Yy$DNrkACwqV}u@E*#P%H zf#H3eQ2C&vOhhj+zJeQGxF7G+<)1q+eEjV#$BzdAbtK8k-%s0XSi|QVZzfVtA;W?ATMw65ZF=#@p192fPr4l{IVwRS z@4_>5)b~=*?bOVXf?s(SZ<#LS?hDU%8$cuF%dpiD3n5a}j)?ot%-363F0t&<2A}yG z>1=sl6(p#&%XQy2PK|^0w(my>n-?;2_^XEV!-yyX>ASKi;4?XA^k*ESV}d+-tJ=4; z^jcJ_fB5kQ#CQ}wS!mI`5cY}`*xLlC7E2uca&r7#O`zs~I66x&QT|AEOR0B=vxpjg z8!ASF87kLImkQnGx*Uw9(w#0Jbmhg8XuKZRRQk=3#rE#f^7}SsX4=)6$4!R%pdkV7 z00y2Fbme}BSJ!4SFc@s_lV}q+}xNH##ia#ewv?wsZMbc|4Wcb<^?sOnDIoq9QiJaDRE-- zHgIePmnSMH`8jzX&o=)JswoqD_asqRI$Bhq&ZeNV+xHtZYmA~mV{~N6w>nV2Agmjy zFN_L5)kAhU`?|e}t@T->CDDcOz*Zm>1lRq4KK^_RSBf9uwSx}+O|&k zu;8$ko1M2zv%U%Cf~WwT=F4N+VQ6~K&RUwKr;tM74N}4McXHc>l=MS1ya_weEpN-xU-*c-y(>{sEMa@-ayI~&=^$g}< zjAi9Wla`DSmvrgvNC8pW9Oi;d0j_N>u?ODQ*W#eQ7)ipn;UeHSjO7-_1lk=;$k+D3 zBVl`&o6d=CVcZtOdL7|+JBCVWn`b($US+C1F)f@qO>bQBD32uWr-KE*&&9F+eg#@D zjQQ$zDhP-o4DaJZX7R!7EcXDbdVXU7x4XV?hq>`m+vnLoUx3Z zdVrl<2ww?Z1Dh{AG-+MG@;VV*?nX5_0l&OmGy4#c*4Og$@O4Zz7b5?t9e~;LJr!@4 zL}TNZZ+xw`#AwSzV4si4CVfTIM7^FJnjlmv1sW0 z2L81YAZG##*?Tlvix0ss^4AG?M0EJeR6nu4u@h|o%hp6^ychabB~`wHiP~xg{$u&& zVzYe#*W!J}oZsYnG`HAc7{~gv)eJl5PhgZ5yQ@}0E=#X(jvikeXoBH?qb?JomV19t zhow;}jO9_Rpe}7oe*AoKy7`9Il()zA;JFFuXj3+2<=Y}2KK62fMezxmKC{&pTr>w_ zG9hqdVh2Tg^?wzWC>@Yq! z$@Alk+@+P^%Q`Tz(DX#1bo#TY zXQ18R9QH7dIOGeVmdPGef_FkiDc4bXg$qPs?Pk%d%yR5++Dl-xk`osb4O|tGeXqe) z8z;|JL99zdkDni{y@y2o(F5eo{ET-8*yMTX?ko^IJJ&&m^7DhPXCnSjFN2X9=02W_ z-mi2$22_o?qpV}yYS#rLsXi{3L>O>~sCR{aAC&?CE?|^o;E1$q)j;K?FuiZ5FP)Mh zw9Q;8{{U7F6f0Yg%T`;Lc6sCeY)c;6o*Y@yuaFzIFhB~>#qSfAGB5WZCzucLaD2)X ze(#yR6=SqscO}OD>guGVqgf{hN0$Jjbm9S}HG1|_S5O0I8);@Iy-LyazG`9)ISY;X zDwb~N;V)3q=qL;mb|hRfH5AID=rV5E{T$nk%w>lBnD~U`6D1aCRr;J&AGM-by7`AB zaBx%gkGHR?%NB_}g3x_dnc^X7w98idoC3pUo<|}#RMKRwLs|6MB1GzBjwUh_ zxyV!g{161U>Dc45l$Q{e{m&m60q{W}a2;D^bHpDPIL+Ag%I4@j@$bvl=~klUk1tPV2c!zSGBX z)NdFGRhvbyx^c?crA0`S=%oqe7Xkfn3vLFVI5xiPOOeMH(?&Nw(Z3{-X}0@SMe9_| zEOg-(Z*3GS&s4bPZ5z-pqPRp#`n;bf;FvmBYtQLZN!qpUi>O#6o`0a5disqV@{(`M zIbxXrnY0|KKSlxDN!Obfn))X7Ukd&K6sn#48M3GyZDXk(pFR3)0vQWPw)&iYD;8IQ zQh$f63AixkUHRvheEho0Mh#dCGV;o*q|N3zAN@v-K?7Nd8vU(@BhN<~&;9rPtwlg} zXKGSMe*a*M4@#{OL=tm86kWVVxA#8+rui2SR+MGT_Uo1QTP=Qxi<~p`p?n&GC0Y{Y z<>48+g%s!wA!^5t7cYW`D5myjEJ`gg&vn${(p9;Dy9bp_f&P6k=YsP1?A0yHb?n z)DFPHlyTm%rBg6&6mJ{2H^e^!m7AJDyhud-5p5tvA)F4C3T=Xw|3_nJHF0#%FHfMB z$!_B=1@l7{XliOP2Hx$^hzaoD)VEHZ)9EowAsGQ(i;ZhL4so0` z)_S%3Vpe_HG2!81Ah%iEgI_>)KXO(ss{`sZ^_PqB1tD^OwEcQ4~wf zTrT&XnP{73242Vsn^^%iuI1uIbH(@~52bpc3P0W<|GkBsgi`|;79lcMH8am^qO2e! z-c$(y>AA@_%Cpev&#s!0?vIpgB6Yf*A#ypxqA<&8?gouy23A;7S{COLEXg-a=^p_1 zWo->akoMThd+tfvPpmsY4eDy_e4v`%dSuv%;6iOk4%oJyCg+eEIJoG=9yNuPf78MO zV{8BI!toV+j1k=+EEU)8^%1{FO5n<&zqc_q^x3icO}rwLT2oLAms2>rO1MpWs1cRU zEEwb_5dA^@`$Q}l+tyze&v@PB;RcERTg4>`{`=s%V3klUT1-7XT9oNNT*>@0TKa0K z8*p-yOUFog-m+*d($7ya2qGKs9Z-<0_e`P9Ldu_r|{ zH23ad{4NOMhho^`Ie?ddm7w5t%!oQqG8fq}+WE{kxh6hzk5I(^Zpt`g9vsn`{ld#5=RwrDh>l9YoKFQVSdZ+Suk zM^1Nct#;znh|iH4#xEs4^H8%X{e<_e=b1zTZ1+2@k$(Mp1c=*|LMt~A5d=jgdQ0w# zhH|@`fo?FwT%#?M{HKx>-^1q@(E^gKh(hn&WqTBXM!?kgD!J;pi~Q?Ydfo`!ZWS3lmz%vxzZ zE+Ush^(bAb3HqLDE2$$SLl=dV;JQm7r)hJ;QGsb~QRKu~yatE3f|+$qtFLEnJHScX zFi8|6@A0jct+zL)%KkzTkW=r`X-XG@F`T+?^yUThzvaDbbPuT_Lu)GNctcX&VKS{L zy^K?0eBPEqsB)d`+zA*mUcJc`3aHGFeGIkyDs~83i~`Jw4Y)Ny8j53zqcM^3Tj-); zeveZ1I%CpcdaLVW|M~%ii#ALiF|(7p?O!RTG<@opKVI&)IeqJxvcv&Aiu=oRF6E;m z;cqoZ+#)W;G?>6Rbie)q0xgXWVya%fG<8{4QEaUvDXk|S*$paBP%_+7!HPhzqP;eG z!H{muqu|}^u|a(S4#m?*M2-$^=*f0I3dM^{a1T&iiUkNB+(S>^_xpb5oN>qfFc4W<0bj4j1>8LQ~&-FDIM?0s2pu|AhZtl5L@x z1WLy}dOiy(*QEb^#C3XFE{jRy)5FqRV@1y>|G>Ca|He{bO>YsR%2~a|=f9~NjE+8a zEofzULJYTg3hKb{O~BH*(lhbh`Hp$^mKhira~Sg~<>nBXf)Zxu|Hiz{GvNH(t+=5? z^d^Z^$?MA{AOH(r27nfbxmqtL4>HDB!)V3GD|1q+}95z1o8nI4N@wt?Bx1h!sMU?{PcX zT2pNb@`cLYFi{V{PbHM>EwLsX;u=(FVYH4&v)+JnvD4Rz?hDK>L^v;2gg<&pk^~y+ zP3mJdUsAKDtzgkDpB!Qnwrbu7qVYRP-G6u#zir`5)-D~$U$pd*yMMnK>Uu6+HCp#B zi!#69-B166)L<;exvDaPM#g#aYEAG`+`?U`YY$xY=VeHVPn1~z5D_DZ)=Uvz^_cZ4?|+oF8!%$%GsU7 zBKW3LpFK-Vv0gE?{+@1U2wbNcT24ig(D2QEebankj`Bizp_;l<2>TsbkqV^6n0F#+ zfEf5O8=6F|m^_uAip43@3|{%@P%2P(o~4r3n9B!`F8B0LHhY+7TeTMdOiK8e>gJ^^ zrZ9mrCqe0T)$o0u50DH_r<#*?xvdU}M8*9Q{EP;c$6&k&^Od@Ab=3MGG4|UCO%I9P ze|j+3-lEajWUvG6ZZW>-{$$APmm;+G$SKKyIlxpV?9n0ri8d0=8V^D9{L<|A^yYq(vPdUEbNEAg(- zYJcLKA^7#nT@U72mP4|;yKlln6wQ9!k84qukwjdcvDuj`GRy4R9gHr_G_O5BKBPM+=#5bNvG zW=IXY${VD#dLSI0U-JiXir4JEd$FIAWU&H=Es#?fZ9Ux;C*N=c&A<>cMAp|@F1ABP zh>NKqHiYYJ+(o}f>c+b>0zdU(dj_#Qnfdxc7B_;gNNaP83-3o*EF%A$Lt=gSeOtbpCh$XLTh~UE0RT1IRn|-LkJb zS}^l>3S&?}oGMXV1$D`z=69SSOjV+w0o$NJvB7~LsZ3def-7Xc)gUF8$?v z7_`?hO<-@H?rPOXK%5ky7a*U^Z|+a+vWE@-Jk`p!PhcBQ7x=%&8Nj=lT9Xn9uaOG}|mVi)S zLmY7FgZ$d*J9q0Z#xA-VCa-)<&GIggFaMsue+~(G78(C+M6(rQKeaewpGJ%hbY?zm zjQUA#Sm+%h&S}f|c({eso}E$7oFgv&`wd6YU?~U}+90u;{x;HV(@A5=YWslhexI*> zKH8GV+|C?o#12=0VvcFk#ZKF&f>Akh1mM@XY{M z9qx-{J0~SbkeBwK!`u%K+v+lRope`eBLb!iO*=Bk`ngBc7Rz@I3>V28dD|Z~Q{(2( z#7X6gr0lA`?ws6&vbH&AZV7SrDsG~QF`~;B7|Ve9!Z^%`*--z~5=hbUv(VW;OUT8Y)i*IBPHZ=~*ksKjF!QHQUx8PcH zpq}_7)ljvA=u9xWt(q)G4RW<5csfZrOQhndN@3yr;EKH`!NtLa74l1zXl6fCK17~i zdEaVZPadK;lj$+9;7w^~_u-AVfBK-U(-ll4!Gg^5-uefbBD_GYmMZBx;tQOXUtvoB zb%_zHv!1`~{9fD-6f1E$9JsOP| zK9$)~4gjzHa^?`mxJcXS@^I{UF|7)ewcedOi+veFq_%NAkkK3YVG}7Lg?Go0bS)>n zbt7AUV#$NegJ;{s z#d(G-vt_NHAnjY;mY}05TOIaGV%57b-DALbh+-lwc%0A@1DlZQCD*xX(R&fq;A=;) zj-kavU;*iC5-JBSVc{fZEqG~gugJ#fwfr{lk@HIg8Cn7E89 z``rYSTmNOk%|J^)H1hhasjEy_r0bRm(wH?$TKQMS+ERRs!OqZVqe!)pWkJ1K$hm*@ zeD2v4PG4@s)TH(s%};Bm-8%5HPi0r9w-b~e*vbx5GOOE#TJZ$66dndqKDI8;ObOad zcUybDzI}BN!k3W!dxHuNLe>N;(iWF}RR@m!jwGB2p{{mU4YSd+yY}A!e09m_|J0;; zC#dKO){R(sujO1u45$oC_MdpLtvL`*U>`-A9A$5P7m4`hSa!?6AEu#9g1MecO^A1j zblHVx1Q%93>>#k{69YNdr8>gyo`^Xv^jpj52J(vnv&mLFnF=EPZmyML5H-@_@Zz{cq$MW7PL#f*yYBp<0qu|VXM^nu zoDgODoSr-Xe$t%c&iCHHAprGZ9Xe;zCtM>!v*}zjB-df{(R}f8B%F}zfsgD!Javo= z;;a0%BK6*@GK3&&Re=MYc{Gcm$@>1$`BiQBr~|iZYOHXbLI!g{8ssIpw4&UQR&R*- zK#p}H4tL^!*RM3Zh{%T^<)5E_26JblT*Ms3qHI2sX@H4ECN>Um9U%lS(Umu~XKfJRghN7BUCnukouPKWwZT67Uxn%?wm%bHu!|DJxNUw1K{E?_w!@^X^0x}p34DRVK;at6N7{s=y%tB4GlC(NG2e_$MYL`)+HClo8z|lDc zFrEQ9^y60Cs1~1|!rC8H8`RfQ;uRbsB+Tb~t3YrgaS=hxit!A3_{3hM?{ymtT}Oe? zSl`j4MV?`HamxImIsyLK?;@vQ(SQTZuM^zn!&fCe~!Nt0O#f>S5amG*_cE9OF0%;vu5TqQr)Q7HEcM zU0KB<lIi1lGotJndzI{4+qY9X!#|$%@ zh4Bq#c;qEKtntzE+^cBsb#FG8@a`?Ky{Y zC8r&RvSN@KKh4vUN8XR_!vVujx0_#oFN~CCH$x)a8#_#`h)i$-al*S%5|_}rk%D{MwYYoW{w*Ka54mDeznzS^7YY`O|4l&uOj zN)aCZTg%sOY@9?=A@Qx%`jLIgYqim}x`}8A?LpHqa=@r`HowI)ti#X)W{>IA%{Ol; zgTfUXn6NJrJFHOq1Ckc7D@ljaIRW;EIL6sjf8=Ho#=e1Bt&u5vrTaLq0*8r+ln7`8O--#XmgXR_V z+*#D=&{M|SM52n*ec=yYz$Ip(iqMn57pHYPEV#=NOQ1RX@Bgwz6=7yz7U9Q-GtG#L z8Y&!GJ+>|@vW2B&D@|O?42tFXwY3JLQZiDIJ=GqQp>$LzaDPO=LzTv%xg~jHjh?#( zgr=@DN87U;^XK&5%o7HhxVV({*D4WyMpQ5>ns_S_+9dL|zg6Y-7 z(rW$!h`E=u-nIE}x_|o0Sy)fD0H`COn$E(SoI;#SA+X>HQDNytOC7-(#mwY!3z>A( z?emUyiCQQY9ECl_=3nl+^7Cn@OW8b7| zdz1v>nK$9&hn3ME0UpITMIH_Us)ks*j9w6;vQJ5b`hYjuMj8ZpbaRDA@7@QTR-ggC zOtCGbKik1G0=vBVVbo8*Jsj?eTe>rRamm=FQc(Dxql%lFioU$xgc37}V64_iZGyt( zu+R?&h7{kf3hdlGSdM5cZ#6jdr=|Xu6V5u>AVLN1wlIGGJVIhS%qYfcfjY%ndeFm5 zd{k7ZJE!pJA`_eBHy{@t7vMrvQ1q}>%zT77Nx$tB58q{=0YT9b%wp0@Jp}2A|8-h9 zdqpkjNlSq4hM7AtZeJux!Ja8`8) zQ(k`mJS!#^2Ft-bc@zL+#DGbz``q+`F`ee!OM%!RZ&Md+XY~8LIp>PO^H<>@RK_h2 zbjUJ{M;1_um2KRfx=5?DG?MTa@MW;!2K<_09<_KuJJ+tN9<>FrQxVJ2}u%e)x^LG|xdxOv{fgwaH~7I4N<} zN6sYD^bLuqO>PvziuCSmLRO9|7W?nB@JXWs5YhtNZ`S;PQ&bUtxdGi6G)~bzgHEKs z1_?|_Kpp1q8x8L#8M0`xE6*Qwyni!zM?QD$-+6hsLc+X6`9jU}4rJ;74?NA)eVtunyA=rSSQ1{Et&Tpn7q^d*g__g`!`~Re4 zz8>{-M;uuCgl=xy6_5I~1mvn!+MLlj;dh%96i=$8p2`B#g6}5fuaL{o>1*>>vqI|# z{sDFE%BL34`@M_l?G7Rc+lGw$RDi1@t=Y)PO4N>&qP!xJN|GG-Ohq!t(-y?&KQ%kh z9gGA8nEjrheJj`C=!t?11JzI(?OdgAQzq>>4^|{f5IQP3CQ-6(;7f@WDCJ-qgDkBd zk8U!uUJ(C{zT-BW7;i3B+W2VBE4x~>)f!E+=V^$gQeZy|p;FzZSf$OMZb!~gyjmsDVBVdefoaKbKSV2T zk;(eruvzy6s{EWyzC3xJK$-8fV^^0eS>s?*m>(5xY>b(NqbICeB1e;nL`qvrB4Ofy zPh3|+6jvr@VdmM(`kBD4s&58TLNBnu?qEnKAYhf|*>PZZIF?#QHRiW6vAX9Q_m&q$ zs>|1dXTt1~Pu*2#iS5B*>ZWTacnwP5We(07nKqoP`PN}i1$=72#mQ*thN?R)j*FFz z!HT9ESwh$hlh+&1j>pp}{?N)5>3OIM$XY%Nq;TW{oY8&vKwacI<-D+f68xa+- z=?iJ4d)!H&&!cQSRZ_TnQf~2sfI++uMn-sQsfs8N@Z(jEbV*j&Yu>TRVyH#9ETsN zeXs`Qxng?O{G2gOh;U&mPp^XTrv3t+xy-hc&QN(`LV#j!jsY#tGFkOG&{+lPF(czR z{y^&X(!-U_U7Km}_Cq!uEd2NeG242ZAzl^hWY502iZx-Y0jEg``-fze;?wd4u-;x| zTTxi_EKv8#dAsGMMPJc9!?R;PT)YQ10i<5Vz#j7gK8*h{MDdzrbT)pbjMjttNktD8 zJ+Yz#i$*api<9RPW$J3alYh|tzA3K%t=%guJCxT&J7B?SZu4*01ic!61$R2=t;t>atJXo(&FB?WKxVO7$S{?YXHA)ggED(Q6T5FQsqkT8M( zyeiFt&Ix}g=i|fKadTtGgb2l6MDE57Y3J_837oAQ-V)M{7v@<@y9d@j>cvxGGB$~P zI*Xj#d&F`E^P)r6qq%@%k{|pp5P;_R*M*AGV&{EQ>D`m%m(Qbiujq`$gfQ8gug4JT z0!s+`hVq*x5hsCpKY>90%Z>G8@v&1{#?W!vd4c&e6C!+cIFYi|0+l}&3=6l6t{>HX zEPQS*fM5fRANss}V5oku_cizL#?!53Pfgjbb7~WN=dr6^(CIEPGPH&UMt6qY`1!W- z#_cpya&srK(NZjxYKqovH7Qa~P5MpMB0KicO716{*DLe%tihXWV!YMLN2nZ! z2v{P!Y3UpYU>1u&@-L2gkkgp|Yjpe&vo!B~{+iUZ`52McwDP%W#nQ%=ewp)Z-n9qt z+gyAQuC+Ju7qE^D{Ldn0PcujNcIsLKOM;G2TOgF4jDg#Xjgzu{VrL5Lz@ZS~X@pr)Q)xg=;uSMSoGb|cMvg?Ow=2qjg5oEP(MeRWO zQtM{BcyaB_ptwv}8J2H-sU{VU5oe7F->63m3y?z-+T#+KGl4lQ5-WC&iORzR1GaBW-e7zU0Y~=#Rva-X&m*&ic-?Is9O?Ela}Y zv|0vP#Z@Xa0GO-G4Py13oB8{)_!n0<=O3wsxc>=}C0vhk-Xk+{O_rr4rKEdMG5$2< z9JD7XP|hS8-{SE_A_L;$#P~at{!syzf~24r>0_S#x*h#2O~p6Y*DkJUzB6z$n9RsB z836TA%wWD5Wsj1pS;qwvVi))~Gpanm&YTx$i;1-18FZ40-q#SCrPISp znKzvmgRQ*=cS+qPYp#(Dxf>}ndC<|)P{LN2gjMGxq+y&G&ACbXBONPafKR_~w(^mn z=dkIR?58BdJ)y%Cu)R~gnUl+DguZqzPVi3Vehh=cmU@sK#fu{Tb=A+U!|3Dd&1I;m zJj&4HFzQkaLM=&z(ANZg64dpM-cKc#v612(TJ7M}de-yY+8zB;PNWpQzan5%qTJ6c zLqMq+&sTHYbM*Q6gB?w15Jqn(A8nbeyw_jA3WjBr89s`Q{oB!=dV@H-?VVX&A~Ft) z7^!V%v^sZZT0^8qRd>mlYN)nR?%9oE;!4(}ekP z4c}u1*dv@dNI}F(S8QBeCzV@9muIKDnEYX@uu`M}>l^yCi=W3^--#z4T9+w_+(XjD zrYG&=#DW4y;4PD= zQ4*urZ;+NCQX^uY@t zoRPbRinc3ud*YT{i0@FOyZvSOG zg#}T3b=w)s#6&8OWM^WLYx=kl1iO705t1_pQuva_(oRADHSsD+b?`sbW#(+rhJzIkkj>gglPWcBM;-l2rfmtIeW&nBSKx=+lV**MbY zVYS#-qm>6lm%uDQ6B*`4@1HAhR*(k%uONo^^KMVY<`*e)p9r6u6iqi?PpaMv;2sF2 z20M;2@}i{0Vh*JFK}{^Duyn&zQXH_C5}6oG{IJwF)45s6Q?J|Lrp;8Zq&#CbFKxF3 z7&REowFdgEhMIUPsOhU#_y~QSrysUK9ro+%q=>GdzNfni5CRx)H6`?nqBw zEF`)dV~c*b#s2NIkC8V3zCt6a05ZGF87s21{uyO(w;!ydvzGg`sH+pM&9#iS z&L^9}&{H#l(>m3AgY^sPj0Cp;`)hT6i`y+i`749~Q#2ed^jYIra@^nJN$IG$TPlf; z2p8s%8nG@hf)YuYqn%rwYhUw$(8#kxswn_zRxr(53nyB?vO{>sOKq{qLH<<=J!);z z1iuZ}gz2Af9!ZMI=VHAOcj4U@{nTmcT=D`6=Haa)e-SS}34o2KKN zF6#MM`k@YgM*sLaNg-U1LxRdch<&)&7n0|+P9tDUc;UEh%K_BUh5eI)7vpkS}MpCz+@Xjtbi^w+eR z@nNz!>Rxydcs*1HMiljM&Fs}4|i9I{GQ$l=uGxq z&iWDd@fXS^cT?gVfh+!SO)(C6aulVRieF`0&Q=<@*9P=IlU7pB8W$i`4NfJw-yKob zSFp&;Y4!nrvmDJav9FV&YwS9Gw~BYe_1sZner|ll`y~?k@X{F{Ly9(TjX;T~$)|7~ z)0CtUhbjL?l8~~n@RDCnitL^XKPpvQqeKJ+IUNg_y?jb@alYcn&ilPlcq>bs_(Dl_ zLGL8M^%oC-)F;|}HnPdAbF^=pn4#A)o$Fh~R>5ZYD6{!p)+dG??#B)GikrbO6BA=| zT4y0{T9oWoyL@~Nvy@{6oIeZkCZ#W@$Q&Lw2R_za96=PAypZZ8?VQwDX`NI^a0Ly? z9c7BF7Xjw9e9LJ)8Z=BUN0u!m_-JKXI3FEi-(y{Rj@HBstWgaiv7uAhB3lQM5X!Ti zWWl+oYLc@YpY^y79kS7oy{PL}udDOxqhg2ZKbJp4QHBA8jlCCZUV|^F8)=qA{j-8T z()Kc|NR3M#)rpP@xgOT^qkkYSF-{U^d63d}?xHV1eQGJX&6SPsmU`km8BXcxCo<3$ z8JgM3rxS+xHv}EoKAMucFfuycOum2Ybp1TOfp;}f+#TQ5*4J;c2TLkDiYZxh9LQ{q#nqSxxbOlJe=TImI%~N5O1T|q3dp~7icSLK;e6=Cj(4L_) zc972x;Md30g5Qr|YxCXr4~Gj)4!-*ifVlXlagD=^Qmq+=R;Yx7WWMTFERR3f&cBVz zq#yrAlp;_n1Rk=aT^SlAP)ypaQf0l$$@oxS;JkwM2d;LJpc6QDkwB+U$Fcr3O=h_x zpzbVx93iAob{x3)c~9yrUPqcQ*9NM<({Yozuc>msRfv==>}TN$8WbmBOW;d9mj_oi zA-v<>Lvo0UFdr{0bQEp}v_>v60Q)c>Tx|L^*I}X*!F@(5g&LVw(vaOurj#0*-sK-$ z#s-a+thKV5HmS_z-?CO)+|KetKCQXtcpkdAJjZ^vc}kpAc_DZQf|)GmFJd<%g(1Sw zn0ifVyke+NRee9d(HTwNCnksJw|?rPr-zFV)gR6P_qI%0!IEp(wu;0N>9f>D4-Q z2&%9Rpd$MV815xs8Wd4E`#+NoewE6BGyotTw#Od-pd280-p61lZ|UaB4@ZFIc}telE9& zXozTF&yrUwTk)3k{bYw%*(4e-z645|RXd&pWr>^ye2K=pRi1xlF*Cq@;Hioxd?c)Cavkd8ZH9rjxQ#6 z;e>pe_R;cA8lJ17KxPVB-EHOIhyA!W^TOG}{F8RnNfZrXn!eEr@iShyOG=79L z0$fqR9puL6Ia5^+=7I2_6(ak*XHW0%%z2Zo{7g*cUVGi=neTQ8nX`1Lcz5s51E(rF z4JS&b0+3UysZ9E(Fn1jd?C$ycA{6B0StEf_;$6^O;9^n|?VX4#Gtux+<(>reJ&%r3 z5m?A{8?;t$i7Ys5Nxoq{j9V7|OkcdRY`vYVreA4da9D6<*2E(>GCt|=;>Fq!n07US z$%e@{a&F$<4PB7_>LW(FVC|2n_ZfO0z&{idra#o5@5Huig%h9RJ>fWGvZYF; zr+B})9CPp&@I1mAK>1O-9N5T%)(lIiR{>~zw2|7HT`i#cdV*GkS)u?`bXZMd{Dh0m zCmxojwqpy3ejL|S(R7W@&J1HotES7tKC&gC*QN^A|Fff-vPPBdFF-KmK}Nf`nI4-B z=S5*q51#gOB(%KKFiO8O*4Wx2<5|4*1^b0Tscy9;TXkYCCuuCjOm1c<+SVXg{+({Y z4MT(p5~SmoEgwitPjRSrv|K;@I(N^;`|@GuYx*Ab&j7!n1MzB}S;EJi+V%MJ0XS79 z#AHV(m~A-bY>m3?$t8~UleewGHikoqb$-@;GLOVhgp0gwmZ|C2ru{6{0~umQzH?bY z^;`v$u(DNnz{jYF8A6uJ0{x-7mdyP4!%W5>=>D6Du7~N<+{wRlC3sRTCTJ!l@AI0OLfw;E7QlQ zCS`9YeN9AQi@zK@ZIW`6v!36`2HmLQ_%X+?^a{!fqK9bZkO2;nd;UApxz*uoJ^~H= zP44!I+3TUfmmDZM+sMN1N8Jr=q*QBsv`YPkmK(h&Y*lO_o-$oIPF~yFID3$^jEHOM zg7>p2hTUr^jJEwKYG$t=fy4fGD7hQ?`l9n^1zwF>y6`H&SNb~dMTQuulF5DnL>zKK zZUnDW-@Vd(f4Co4fQiHZTgqoZh+5&5LZ(&K&xIh8dWL{2sF)8p7=T{7R|%?-1?2YX<~RZ$2_Dyl(V+PAANJaIh>3XP#Dcb?6W->cX7a_ zTGgI+7Ox&IPf<8q87=)~cK-gVPsNxqrWteS2BPz;c_2h{1|7Ir&C9*34b+(c++ zp!(rNv^#Ul`eSs15NB-ahLpRT&jAW)ZD$ZJ%n&dW6^>(|Y`ITr;j4KJO;VCB7Y@eh zf7s<)lv45D4>%s7AornTfqzAQsiKaAo)pm$|04`+{tZ6UtS3L z@7`|&XfPNPp_ZqF*5JkKp_yTl;eMtCBFcx=cSlfIe_wFxWYL< zFJi*17P##XAzWpDb{h@*m0myr&`_g6rNF4%$PGc)^nq?_A#W%#8_TU=i?ug|D;&BY z>MUo&;Ig5~@SL#IU6&)O$i0-%DDhj|_1K}_3~~EK4m-b>mb5GJ?~8;H+s{sx=0^(8 zrjQmd*>4Ww5dx#9g4OO}Zwmd+1`Q0MmMhRuZx_NmCKKr8${+%*sx6FR>hz{ngZvb$ zVA3$pJSnNCDfnSK?$H^~%3LLl+nxxQavyA)N8nxIkD9UEEGB9`%C3sM*XnQb4rH67{LISoLg!6v7kSrd*j1K#7x({6fY^h>l^z#gY z@(YloiK7{RHsFDBBMKA0QqYDuZjJ|rc)|FLRN%?tlj};J+-$MLr9jNQ^ z{8uy)C5qU0Vvhw|NR&|^hraWBXPPMOTuptduOw_6ZD*lfEE?GK-|wvkUnPIScJMeb zj-YoKIp9t-73|TBVP~bg^}AelFj-90>pKy&bnN%^gyl<&$w*ADx(1_Xk{Ne(mpuz$ zs}cq!0r&Zzqr^E!1U{Tan@AGk0#p`2A)3uD#oeX>0(ab~lLrb%1XM@T1uO5X4vh8z?4-4oVU1AW2tKlL7~`?p?Cab)Bm@cH_Y@w|-4eRrB+ z+pxsTp5C0wQZPkxCKk%!u=y8RIY%)+`S6CCc!kqV>5e-Hl*%%9z1h&BSWXUK;T72{ z!7w4mPck&%ymhd&Z&r0N6q|H$Crg^m2OL^~yC6=V=etc(?ATQ|Sa4$r)}?*8{fX_l zt|4mwxLH3_znkML`Ui@i$4o?3Dn=kUinL0n#mcibmdQGy*vvKO$zJ8xH|BM3`F)W# zY>?UI%Ph@LgDTHi=24<{k*)HqTf+^9CBOwo>E$@1$_$E2tm}U8Dk|v{dWN2=)y!w5 zjf23J5C_J0jwF+~4A8Jd(*QxU5eSdSaTwFe3PYcXrTS4BX@vm?;5f2jQQKIpL`-bQ zhVQ3<#cm3gmK!q3^nLWw`*MuYVRHCTuQ>|K1@p~^sBjTl-yD1Ou^!@XA)My|h6gaF zl{8lG8*7r`GGQ!d1)!*`hn~_}q*3cUw|}(gKzxFu*A@SZvc$3Dv+D`!;77|PSI^7Q zy5s;Vx(2f!TMRnJ=ar@8`^b4eCV?SB`})D6g_d~D5AVB1#HWvr6*ck4U+~uwBd!EN zI=vG#4>khMY>p3hvOnmt9xV+w0g4G4x&pe{QW9s`?UDu&SG|X-oehE6gWovWe6M0r z^2(>2K?(ui8CPmY)NvWn}x&o{gFXdmid%TNg}6`Pz~<-d2+b3LC%y% zHrv#69~U~L*^P-Y3U4I@$BpUhDj$Z#s0SZ+;iYy4z#EWh?F4;&>MZh6R%!QpzMa3h z=#YcaFac#@Kl77SHVyqd&^+B#vDE>0NAFJJKE_J@ZisG~WRL+06fNpH!+N*7R#c4h zj^@7k8IoMlT@+8MsU-(y=KR^y68PM8eNRjZ-w4r<)IBJeN*DZ4u=H~D)ghpSX@zm2 zY9lo1U02qH`4(`B$+b(sz6;}bgU zfaP4A`B~s2&Au?gy$MJk_>Oj=05WML34hou7+ctQRt3(H2+ZOe3P$TgiCF_$m8t!q z6T}=qvbM#)PF+o+!PDF`*A!$-&wgW}g*h4rwxq2-Vx3YlM&ua`8KzP3#KrCkeJ<|c z0JDs{8cS?hCpcpP5ws)8O$%s$68=C*x(>D_R2Z^?Jv@VrTq`pAS~|jmG~S}MU9MbB zEQBORWHMni4jBq{jU|aM*$`pA;JRGCFgm{J+m4Qu?D`A9)|s%7P<^UWEV6qq97Bk= z>zy+FyqQ73JPD`>IXT@!`}J!QZ~i5L(Y>Y9nyd5!!m!-7T3cKbZNA36W9d1&+F9&I zluN)Olc)HmDFSpbSwFF^s9IP<(J^w_iTU)50>)nww zt*@{3tV-iRr>e*lsTG2@aX$7~Pbck{Vvy&DzkoZ*sNO9(Gg2mueOqdlHF->qu5M~O zCVJ_Z)(!{!KY%KRUmv_96)7|*UQ5Vi+0Qc#rM)>@6DQef)iE0G;^i;3#0LM|^Mp{y zU$4C(aJ{+gxo@vS6$_SLnNFSiY`l|@%;0l1$Uv^wL&)1~(4O$IR{k~N#K7g{2%d%L z+x8v_91AIF3a?$ycg(cG0R8GmI;-6Xt`A9LFMQTXzd?68UW*%I%rr|Wiebs9dzb7x zgVyP&dbqJX;@vi55b`ex0~b+#GpT-5^NPQy66v%5LR1r6Po)rY%%r|hO@@A?5JIsf z`5o3V@ z%j3sSgi+T3L6=YcSs(NuN{`k@Y;=k4+*R3I-P}apSRrUi}b_hYNVjl+7I&3DeAv%v@%XdXRkTTEc2)ky zu2 zuk{|potkwB*5#51wl3pZ_f(ejoL9m8x3~fl&zEy9LK)WL-@Y;OY32oAg1PRq z%OOJjxy~zL>gFlW(+ks}@X4l+ke8KwGt^|(gpdTEmRGnmI!XYSzsf}xSvWJ*gBfRB(-4<&3l0!>;np#_aWHI32<`s40xO31bhaJoqvyUg|X)UB$+HTYgLOBRQ1#9z%nPBEN}M7|v3Sa{@;jC(*!=r1;eM`c z)iJ$paSE;IIoympp}s0M1t2U7T66UrgXU-!TBE`9nghxh+MXqpP+Ei@+G$$fDe-=g ztLp;zS{Rffw%wbk4&n_VbV-mQLhlxWa<5i(by$$6JA`3epF8leWt^Nvf+cqE{sJ(N zSnv>!?2vor<`@yYl^=)gJPTW1$9W@Af+p>rU=j^E1&jSh;j=hwb%Lu+FN2FE^cdFF zNzx9@l003=F8~{0p?&%O%|Pp<*mb>)M_b?^R?Tp}?&rzy;FHb3uHWC|^y^c!Kyx!M9cu(l-0Vnf zY@Gbo;1Y&xx&>KqtB;Z4%u=m6KN<1y@-hfy3S%v>w@4%9z=21p_~1&mkSg74hZ}zrw=nG=k_N$Ot!m2Lp9Z#jDHbrIrR2z)|7Bw(mM0Y zwTg!=(F?9Ml)(*`$XpB2=`@V*GsfOA-Q{3DD(pW36*{=>qvo)9f^BTYzy@Jp1~CzA zkOe)v!#y{Rh&F#5p#ARSrz?o7q#ZCVaNG^2yj|==W(`&78yn*fS8|6n>i|rAzI<68 zno42*N`Q*Z2+rg3=H$hI;KCfQjKR_5zc%h0&CA^@nCP?b2)#!x%L4pcn1uD*$x5`L zRp=j{r1@u5&h~TnTQ+5uz8N$iTuN21+$}sE(NSq!+`FXR1FCX4S8$_EgJ7&Pch>{f zjIbGcdD#LD22x~E8kG1YLw@(C*GkD#4~__ncfs7hPQ4Cm;=-GVRT+q9s>oL(SW{*t zHr;Ot?^DHCXE`;$~a-Dzh5 z&9nZ29g4g?u^6*}?S<{lG(41*73fQjGZ382*~%R<0{b>R=?TJ%mZyz!xM?4MJXmpC zFUBh5PC!3P5`%$i(w`4LLCg|d0KcV{Z+i;2d%Hdzu&`a$r2h8}P41+7dg=qaXLAHSENmGH<+N-h94sGDspc0hyAU)qL z@lC_7kQ&VSNkKu>ob+yC7T<5?(T+M2=!2yV zpx842o`W}w`F>z&?8WCVs$x(}E6IlP+=F2f?uwNcUx0JQd8jYCIjP>5#ImrFE0;ak zNxcWVqoz6oTB4DZMfbp#R|rA6SDe+)Q315_qBl>cjlv;98p$+RRP{fl-~0t+pX_#d z@GT1P_Qy*Hbx)B=IwAs+Ap-@_s$tK#AY@86FcDZ(GWMk?+}EgzHfr-9pyCqe540O9 z9wJMTrTp=|?Xzf1dI7b>nEnGVNq7Tqsl;9qK1XVe%cpt^Y}Wv zri;~T+ z)K_c;g3sd;cQfe7;7CVBr}We!zARO>pg49&s*&(wft3E!??4})0yIO^5Iz_-Wd2(L%yDp{Eoap<}0_1MyCN1)-Bgt)hb<_G1*00D9+ zOU^}likjk@?)0y&3uiCXRil@VQWhgKSWMY&5tQ;8q7As`b3Ox_wS~f7xpp);v1I zjGV6(<(RF`_D+4qHWVtE1Sv2Gr_#N78S44CfHMeXQ!gJ=I&2uYhazVI{0r!gK<6up zw?0zz>~4*Y&?UxtvKCQO7jKnXK*Eu1ZV*ETuIl?7f9vnB=-I=+X_RD|PZ=4&zRWI` z?8beQJQW9*RfCfn#%~A4XbVeF&1kxT$)pRo-OY!In9F*4Ly0bIUC*s1%RGJ6Z zsGLJ8eiLWd=z#-cKO}D`8GEyG@GM-Ul6Ry2^!mo~xyCRGh2FGuZfu+jiI1?xLVJJO z3{F=tSv*MGO6zUt@Hl*&l;;11Rcf$is{ z`+Qer5~t~=>YHx!D!s$mkEu^zD$dUpR3bM2euSY_%l&iKQ490?nVWJ-<=z{W1Y_B5 z6hac=#~>S9#VR92h}h&Ej_djma=3Vy?9rhNA!q3I0cQo$Aa9j)L)v05&CViipGqFB zi(G$W(2dK->E2m>#%aiPFI47=Ib1LVm0b|KYZExP_oP%=nBp%O(W9ihAf&-S)*pBuif)6}%Bs!l#CGyZzjx*$S2;wi-snQNm z{p@l$xK39?BL-Q>(QuU$HNIn}wmxi!1u8tX{8BYUGW&g~ZF?a>8Z@yW`18-4Wwqwq z9U${U%4TkZ4KP#=gp<*0RUVHj&~3Zvq|bVY)}zQK6LGPj}xWvRAt_qD^MEqEQ_ z@3;HpQ|w)crW)V-mB%}JgffscOb;2oF7=Kz8@Fy*m`f5MeD{@{+x#fd@QQiai6JQ8 z&FvR0hMwZA-e-B`9?eobIT|Lwf$ie|BJ8cA+HRx1&EW17g1Z%`xVsd0cPmod9g4ea zu;Rtt9fB3t;t-@XE$;SA-tV0?v*u`$ldK%&B=`T`d;j)z$&}!SnxwF~f6r(A1KlF+ z1GJ%(orSqkf8mS$vFueaS<@m9LqYuqp!1uK;gQntx-$n_!)ypDnJzaILd`X}n}yyF zcH`5)bLtB7P&>zzlzg#%HOJoHtZ2LnBNStb+?2!9mn{&Ml*7Z0wWajjeDqMVR?Go!qy^XV9{}d7`Vd=^P^H#?8El7SOm3pFbHUrRNlX_6 z-SY=K+zv>Y`Ua~g$SOGf5OOndjmRoDpwNVbxQ~uDw1|2VJ>P5OpQbY#NcvW@iE^|&tMZzA9Iz5$TfT0$9~EpXCdw*c5W-59JOds8)mAH_I> zvNKdo6z^SrGS@rY8@I9*@W{`_3!T_l9ZXSKN;MVB%`9R0I_?;+6ltN1!DaUyP8I8p zFTeHA4HM`7mjH{^_k!}9C?oK-DAQaarc3-j(z^9k67jrhH<_iu`~8#5B|aTa1@GEL}FUV;(r} z4{oMUWA5u;K-b<=b4}C#`ho+T{9386!n%xn)u*GxY~9IB?lF>{V-Oa7m>xxpp^CKu zMP<%+t@NS}f@mlv9dPq+BRri&N@KC$P!-&bhWy3haBo&+Lb*O($EOQ<43lfcYMbKv zdf~?{W;vC?TbrGGXf}^W919k_(b+`l760i^`tx34R+Vk6$rL`b6sp6ZDMD+ zB8CM*G!&?@#XTj*ZZcJW;%ER*-Zx+~l_v`1quDuK`FFOeM7>GA&~Rv&;*>fvt*C1N zcxElSH{MM`LZ!qOw~B5StxLyG^v}(c)kWB<)9sLYw3PVc#R^&_tN;BFn`#BAMc_b? zHL3>L+@s#(&=7q#`2hNI9oviircPsdqbF8(rk{?l4fjac6&S_Ax`E5Qd${jujBJvE zNAcjN-RPMrN5q?~XLhaLMS0Wgjy;2nGuYDy{e@>?$r$evzbbAucE?wz6MWdbq za9L4c66^Y6Ss=m}P2!wXvKGjDqVPn@98JwnRW$lYat$EW+n=o1xjKKT{``gqJzYZ?& zo>PD)^`v{FVGBUI>LuTu3?J)CUc||)GX4ORR*LkC+nuu*nK|Z`mL4~Ql8OVj4^^pW zl1zNUTbLYc3SKr|V)cJcA`feg(=nz>dJHi!pV@CS@rDoYEDm2HnId&oJh2&B((vqX z;eR0ttdT{fYD>D{5T|Gp{iekG?jkY&@K&g@I-jNHPTt+}G~DH$4|~Wns64g6jF@!U zR8iH;dQ-9I=VYPkDi$?fCJ|u@1D`Yrz7?|Ul8n{eWhK3#WKE_%qfH!)Vw?YoK)&(X zmrdlk6PKB&WSB1f%xPeS1K$K#cpqi{O`$&EQAKZ(MWhEV%pKY@448o%{?Si%mMW=W&2C#81u- z66n)oy%5AC=L6nr&qV$Q=z@HrY8eXCIuGT`#9AB@tE5(B1e>sS;ObuO4ft@8vgh4Q z{41z*4{|5NrY;Iq;lY?>&8iHS7Nk>KIS%ID#7QJ*a7xq8Rbe@+6Rds)9s~S9$9Wt~ z@=uHel4yf$dRx{)dD8MJOu&={TK}<$ClwxD&KBNhQOHHYA0N-eoNPf`T_y#URA66s zBeKWLcR6dD*)S>-D%)?hwRIj6=COFT8-T}rVB;=-1{*Chd56R0uN1{Vt`y$DkxpV8IDvRHXm|IDL(I_k* zlx?5aD_dW9^)My^Z}|gd;}3bk2tfN*-M?NT(Oh_3k8X9hctATA^jY&bnh&p*tx65f z_^D0Qr#P6(X)9YQ{suvKVxbUC((mmd!uj45?%4JFMT$go4o` zW(cH}8WbS3qe)V_rxh2;)^Cz3woB%sUwI0I9t~ zKFWhXM+z+l2={V|F?odtY9NAZ?OT1gwA|%B*`A5qbo!R0g_Q1J%DsMrC&9tDn3qwkDCIj#R(WZP&+UTg6tt74%{{9vHB~CY=zm>{$N$eoTgrp1^QBEq=RL$Pr>RV`wWHd6P~`(} z4vF-Q!)xp?D((Yaaeu*jo24^1bp(Q1j=-+V1V9S~M{;G_9_tez0y8sAJmRV}GCqB_S&6q#@= zg-ct?XXBuj9VGVCOUen=ey1eKI;6Kp%kKGCvF!9{$SIko%F!t(exMqN>Tp=NKT!4; zFqEM8S*A9jicTD>UQT#Wc+VI{4k{=hq zDB9!bJ6|xiS3U>6=gy1W&5V-9n(qW~iE zN3@Ns@n{E%Jfg8c?ouUQuPNIukW)7Yk&0mz^c0cP=;qnlhO_t}LdAM~Z%d%Wq~_sa zcqNgX9FNAd878czE&yQJF7jWca_(ix6*U5dJt(3)1+9*?1C=rvmoxYzzTx%>d0=%d z{#hJUu~ny=&2{cfwfoqp!IF9SiA7<3Wroz8UVEKzE@d5iF2J(d;|{`))kyNQ0-9*8 z5@g{4WzAWI#!iMCo!CrS+*Si7DZ6UB8{pX?6aJ1v$p-?TJmp96Br{6QuHw+MerS$C zjaxyO>S|$A_HtLdUW@Hfa_S0mCWx2!gOMOqV%t2Y?@JyyYGmT9vaY04{&1;mm`{+r#*q-J;iLmpFTnG4-rRq-E zj{6pPu`y9p(AIb2i5y*-jUC>98e#Zw{ri2ld<)~6-T$O7tZ~{)O0|_jUC-zW%E?2AZ&y36YC5 zx5$5RvKRO)n`q8hYNpR5rA8%qwF4)(e?&^8)cjoa5ihBS;E!<{6Vr5QSkQe)1ZmRB)OMYpxPtmCVPK2sTmF~KoKREf91U|1YY)cDEHG094YH9 zi)aB)c$%Lt{bueJM{sa-m5)6YTxle8PqXfZTI4sT84Ho@8`DPs#-T;V;Kjs(e9sbLNQ?iGlIK<->fEut^1Yo%5J{hd9U$b+cg0VR9l(-`k+=REi zdO=i;ueI{~f-};+;4YF!qvB9O=(FPoO{Fu+o7#HZ`fMKgTdR7fjs?cYV$u;4a=llR zDFrgTT1lkW=kN_pw1buYyWrp7NVh_m8rc7SUxCkvO1((jHgYtg4J$$36_YpLHgF7< zXo*j5E#v8~nu_yl-_KdSNlyGaR=oJpem1-D;RBrWcJaRm=B$g9N2)FKv35tx^I0pd z@YpZUNG2Mb?0n~+gSm8LRY%nJ)Is0HaxBMgeE+4w&#mk7N)k60LkGtXb6`%!jlhY08!TKFjH*&!-o!ZQAE#P<6=ZbG zN_e*Z4d(R4J#NFnRw+_THNT6POS`oSB$~353O`yip!NTk9cuOw@HD$p#N^LYtbm*} zC^D^?Z5VN%+FB$II%bcQb{G?0EW?$jd(8zOpn#G-YJQR(33uV2d<5Cbe!CyHUbm** zf|z;W1{Am`!q4>SVResqX$Xo!{va+4GwI|?renbnj-N7})nmvHQ!7W*Nm%+~3~;YT zqs{NF7y`kUOEjL5a1%LTNgO(?b_ko4_c-{g2D^V1QzG6Xoc~3iUL#88e*p1c+pY0b z(;;1iTf9nKI%P9t?r!r8!ybVg0dZjP`vzkDXrs&=hJxiCrcbp7sOY^*ZS&vl-dQp} zqTvS9w#3$<31Y8i*oiFt%ndZ+BM67;K``-&&#uC+o9u^IwQIq%1q;`-;{y%}I=vdq zD&Y8&>@AgtyQpz46r*_L^s@VvZr7+iPBje^F`24~t~=a!R7#;2OV#_H z8uoQkCckXvCC9rS&mAaD*}?C8N{-!1a(HJ=zVg<&D*sNbzlna>JcIJ^=&2F>*zr@) z2#gDC!@nN*eZbsQ+?tK;opwQ5g89zpVY&LIWHTykvIquIp`#hx*s1Z?n=sY}dVx9( zIW2`Ku@E;&Ol--rj-J0_+v)o*ijrp#o0NLaQxVynn225+* z6|6-5m8Kf*Bo$)6&Pnv)FCiKw@p@vg%qX0x4jcquL2N_v0(;=EROauynz@GpB1QZ* z@!nry^;$ih1$T`O(eh^FY`+M=;!n>YfT+{;5H9+-jJK;eNN`nGw}oVn{rONY{Li&U zV?rkTkV5HtLSla=yeRoy(ktcu+N~>yBdp)b6N6U#LIa5z&aRgiCkJF-b*U7SCzI#T z_`F_1mXtL*eqf{(e$0@-MOU_X9V-1Z#-Q^#X?Sq=yMUd62fSBRgS&N2OCC)L<{qi~ zI$9fnmS^wFK59A5Paa%Fzs5cn5E*S(?DP4lB^H*OWz)z$0W_JZ+UwekO51-na?$Cd zlx#TeD6<=Y8ZrF!wVBlIAP3&*=z)_pUa7@_tb3se7faoqGQvzF^D2{h%gKBW6ZKq8 z6j*Dl%V?-5#v~D>AxkjLK9)4K;fgDw->L@B?t1T^r}#~T(v6lLx5!f;h!=|6rFOB! zQWH-65>$FBBzCaFs_<>%pf83RN7DURt?y(fsh=VhD}~7pf3|CSJA*R+7uci?h z$Sv~|jPY$#3|J;qTGfik@hl#|5(^3lK}Z7+R+5=<5Lq{{-`bGZ!xxy*g><#Cb{3fZ z3Td{fnYc)>aT>q5N{u>7si#^LcPrD7X~#Ka5(+iR*f>}A&C!7K>|^EjK*K)K&F>X| z)U4?4u1PICnj6Ws{J^4j1-%=7w#k2{fqr{*aeLkG)>Th=0~6v2Bz{h>JAnjRW;)Q1 zx=4}5eUn`^Uq%{;EBJ7356n*j*_Es5^RHXFveCy0TX6>15^RAfG+_yW#vl|=!~`|w zo3Ju54Oo~jo%q~) z3$DWWvDAONANBpBW1|~1zOXw#JlnGn;~x56#6R#ggB7JjjB;1pm3WVDhci+@v^HT;pC0bK8T+ z@7y#FbB|Q!H*dL?(eXmV9J1Ae0L5q1H*P9FAJxW#+n_%_ZOH& z+y(E9n35Fxpi#?$h@ujWR7DnWwm{{YcB(KbN` zYS;h!byKm)y`@<2&7%ot%}p3=;Q_{D*?X5s*q+Qq_L(Xb3sw0dRi!QE((~pPYoIA_ zDC%((2i^$VyoI&W-_BE;ygx$w=ozM32!)<`Py5{A!ktBspOfz*i-s+LZHGxwnp^ki2Dl4oMa8s+3l zW1!yjcsJaYWOr11-ecZ>6q$1-NP`PKpzWu?ws!uAIj1mI_OlE0iQ31i@?vSNLs(6}EI&8DpJ;a(@1qY2wA4boWQFmae^=PL7S$6w43UuJz@p9f=B5FJK4 zdq)|nC{}jl7(5rg4+?y7)S6Oun+vWqnn)w3_|=AMl}Ej$^M`j&XpokgaLd7KX~07R z_1%Pd2}}9Um);U#u7#Tqrr&%4L}6Gx5~Um>Z&Dr<`|8)Xd`!39;Sz(BQ$X**;rCP* zKVaue^fw5zAPrasK~kM_2hZPw-B;A+?$+9( zS{gRYaL6TLXK%PliPT}8yzy$)>R9}4DhvM{m?N5+rz8{rQ>y16|i zHrep#iPnp;zws0LsULdcs@7xuqY}Mjb-F2wslgEYhXh-61M-sPytO)rn#i+mCwJ4% z$%lMR0PZSJAl3IjfDrS;gdidH2~<#4lnzYsSB-4W15S_wC0)5TWwkc$E>3ZKNa|E~ zmw{+w*W*+6ny1^HQXBMxgv5{cnZS)H~vPt=5mdl=rh6wMW!qC`=L0tY2 z^UeH4N z2MQaQ_FFfI1?VI#JKz~MT3-ehBO#+(d^)1Ks@|a!NJN0^lKOL;>wI{9ljx8Ey-3@d z9nxE_cmL+O5B4dmiQd<}pzRZTocOyD<04=ed%T{ArJ+T<{`ls$tpXP|G_M(1ok{YR zER}GG-kHefBvoY|dNev&i^I82U~Vw5F_fS?PuA^(pTC=!F5jfwm%Q}I-R8)ivM}=3 z$4aPd)Nh*BeeWJNBpSoCue~WAIl529?*vPZln~=x6A!cXTbM-PNVYu8>G55_d+fd5 z_I*P4&C1G(d_HYOgI*MmoV=I6N979q2Z$r0?55vMRfY_RKgK^;k1ftZmMP$xIG!11 zAFoL_9@Qw%gOcX%mDCtDS5dgkVW*dnyIc+21M!Vzf)-LN?Q>DGM;s9yr`Xf&#Hb?b zzHFw~Esr?~zp+#Lz2CFvo{ubY|KEPQtnf$t@lstU>%@Vmd;?!K1H^OhFw5ks&q1|~ zW|w5(V?{s3ro`X7L(Eo<0!z+TEkdY>KIg7^YbqF@5S>zw#JR5e$Z8$EzDXW|UytDz zbYvzFAed#TwWZR}D7A@{yR>|$63%W{{do9iam!Y`vR%EvJNuKyGBg*n&(QC>!mdqDd-n7ueu(L_0oUes4S%9l1v;5ZfZb zv%e=W6(L4Ki6S=jFsWv!d~AwLKgGW3tUJlc!M&HAF54lz0LcOC^0QrteO5QwS|h*w znlU@7Nfo%Fx6>2-^S5#CK1|r4)2HWo`b_daT%K|cg1xQR387GRHi?1nj{EW%%3$Zi zvD(vT`2WN12n^9)GW1qQ)*V4)3&AYJbHh}gC%M?zYc2G*NJh~l*s6M+{CF8B7_9GE z=p=+lsl*h&6{*D)rTmHP=8JN7fSHH^kVBcVdg* zboF{lpwSU{OzJv6AVO5o2~S4T(@9#6a0-f!-P~TGJvl%6%VALZS?OUo^K8yEWg_vz zK;6QWLH|`%y1i&P8hM2(#@mgBPX$;~sl|UPzMWe~jkwZeQWhtq37!r|pM;Cy)dWwr zr?vPgMv>poy#SqM2K&!s4NTy^5eGLQ5frb51U*Y#^TL|l6*p>L-{Lq~ZMB)kg*lQM ziBwcwy!%?v&N?ab)x77(2z?veEh^4!2WxJ!urOvot3NqiHgHkkRy|6mMW{`;+mA99 zV+4&i_>@w_RM=G72dJExCM~>=Rd3>`PcvxV)R-~@_VXBYw>h}^OrJ5)OFB7R+aV~w ziDJKcB5Dt`f1AYlrJw+HDA&rodUIrJMILyO^AcS*R{>;Avk^Jpxp`P;e)^Z0_?atM z>{9R!w|y15jMXhjw7g}2A%~dkHew+=y7zh0gqPk(^w|o3?c}3==6hDIz!l7U`N|=% zzDIUDJq_;PS2KQOR0tI3=7^H5IOZCmx8v1^Hdb=gj36xk2k7|3%F2p%HxlsjKeZLg zmEpJ0NAA{TF}u+}D$eO^?^P8yDJ0HmN8x8{s`QycLt{K!HMn8#ZJeB-FMHF}&CV*+x5 z>>k{@;uN?{A*t9iCk-HB@h5>Gsu+!J6-FzH4*}%OzjS&s6x%K(4^9#4*|$xM8s6L_ z%hY!ZMZcP8C(8*w~r*a={FV$ zjzjz){Sd&{NB#{vVbX>dJxNGI@v<?-2Mnd*=KAzM zEAK@Hp}~J=aoPf!$y9K>-v&#zFS%VG(!cZA-q{lv{yzBsy!W}z&Dlro?ZKRzV}<3) zh0F&5U1$4?1R+m+F>+Nm1_XlejfrCRy2sKovLMYF!jtlw9?OW9i@P^)0 zPIFuqX6$q3i;^0YCfIMxaL1vbqt%YF%)0!Hi#6nhR1{!COD3b>`8M9p&Yl6vG=^4D znUKgX_N0;OAA(~r#p=2;b-Q4m;;Q;9DbGQd2|f1Z1!#s`3s{fKd9jK@-ER| z{8J`z)j40E%??-Hu!}MkN*pxYp*iI)(J6(lCT&&{31q(`Np9s+LKWmo1l*4O(_u-U zPXG?eMk~2g`KUeIz#~YhJ8eoiho5;eJtPMrHs(;v@>seNv) z9e+Wn(5Hoy&}~8Gs9z0eX`mQARTyc1G086%xn?2n=WE_iN6Yym&*=Ulb0BYbZ_&n! zeGGgNjta&S_tIB{x#m9>VRc+BVyKhXX`&5J*8wK-S*OHbwX}1HjRC{;!O~((bPg1Y zz_^G40AXlViT*dx!Wq9AO8X&MwZ%BIU(1)3{pGGci@ftP%d&dweI>6U8q@D4dP2g{ ztpQHM$PnFjjwHKs{x@Jfp?4A`GoZ+AdHZ$a(6bEr9bheH4svZA5ID=qN(gPK?0o^s zQ{ps;r-rB?CStxxyrP?tM2SpKj|96F4Ll9jz!HeC`-wl4s+idSFqFc|)2%^#bn5v4 z$;RLDD98%QHgJsc?shC_Wj4`AOe*TIDOz{`ch-w?ddPB=4%7}d<8#;GN7w(8f&h(Q8?VU2!94y4`A`o}5JUJT; z2*cglB1mmaXlfC)+P%dtp@D7LQT~Kh$8~%6=kId-gKKU|u0%A9`5|pRXv`oqv6VOi zhrO+B)*bwjq)PJAl%zzYtK>I`vZxDg;t%<^K4czREU^NI;y>ky~wcG39#02jP&Bsboz;j|>i;h;PxKX9+GOIioUz0vv zElqU4NmjvkbfS=ino!pHgdh|s51@cU07_lJRem~r@f$b2Qi$mdH+j|z+|M+P{R-x! z&o{?I3U+gj#rF9ih++p^f&uh;Qzeb79dmc|?L}SftuDJK;7De7)R$j75!T^3Z?8vR zW)g9=2o+ zQkjzXoYPdYF?hET@v1L=IYv?pQ*y;O*HGzr3L1D16=JxnIr2W3c`vI@lx53F5xqC^s89%L;}?go->OiL za@>6W5sJ%}MVwKo!b~fmjo#QUQUK8 zm`i4#I#z7U6P&jqRV~^iH$ejn&caL+4UB^tBeuVn5oKEMrcesG@)~mYD*v~Ry6`MS z7w3ykLGMp`&#fm!@mmd*=-@;DF^Ka{Zl|Y50FAtRn0-@vtQ#JD5#uJt!;UHlr?vfV z3S)SH_+T?O8kPyuL&zL&CdAbH$J4Bk8keR>?7#p45^A}<#>4CjY)PAPPxdO4i?dNi zz3B07XrA7=?@u`0ytwYu67)0j4_D7bc;DZ~ZoJ|_RUqoBQcYky#_ioqK}ko;#|Yad3MVhvK+wSikWQ`fIs%(r+$m?Zu6bQm8~xdY(2_z%FNqZ;D6Z(P3&Hrkv- z9$FXkyoz4_CJHb)8xXX9;S#P1z+`b$qI1(v=Fyyt6+~cLUq_AtXrR=cnt7yKW21T{ zKyqD1l?$4|27Hp|8T?e5*tCC!cQCPFs~TqoLEf!Z{jHcmeA?8 zeEX;3duSb=njkpJ(?;h1syeA^-G4yJ5GXL#2uY5uE_s$`qk(In1aY+p{svl2Ls*{Ej5EIur#gqc2JU39j%ObqPIlV2e=+)v+Lq zzyB#ZJs(T#LD(Z1)>cRsRq|93XeMxJCWuM58M=Bz(-5r%3zY@uez$f1IxPa5;!1>8 zhy0=oY{G_CKns!)hAR-Z{Nyz3mJgZs1lxW!ty_jX>U1<2uQorEbYsR7?;&CFLbmS4 z(+m92DEa2d^%vY+;>3C<>{OS?y?17F^^^7cRz~MO;P!RAaclPm{yK|x4GU^~o$zwh z&bdBZ0p|`#n7~yy>jqc`6v>;}mrd0qfqblD-!`jY6F*-Kdd#I^&p=5D>fjucG0|iSZ}h z8_5sj1R<#M6FUW)q8B24Dm(Oke@Ov5bE;@h9q;n+nTR-*yi49wNp%c1Dv}Ggkz=oO zT*8zN?t~v)4N5B%U#u3K%$eJq*Xx3BO4_9uNrkf`iWSggqY}nvsE-=>~H54Tt?kb+GYX*Yw|qZ?hjy z;dDY01bI^dIkdn+Y_(5cC_?E1-hq}<%$hb1tm`h0vS}Gd9F+Y_#y>yoX%lIG@bix= zzzGMVokdvZL(_w%B7t%?e0Pv{$RZV`jJjCvyL*Dv8jc_!#{+papkUH5$zuRVRP5c3 z5Ry#Ms~(fc9ES&wqO{!C4X>a4?iqiSBR}v&!CRfMD-Ac~S(J7MD1LEKnJ|_yrntlON+9pEU34}A!r03`VqBYKpzyU zj#Qr|oL4hko$`=C2)7sBwBJO)S5f*AxgmA;X!#T^h>YJISfHPP+(n#J@R_3P(}9dM zeL>H&&0x#Yt=rYqzRekW#=7T(AeDD(i&|Tmsqkdl{fokM2~(rsWp5&8ziJMsOIvFQ z32X6?yuc2Q*=i}?vXL01DvICqHD>CxFFMKR3|DQvj{bt95BMV{iswAw*iz$eDj$g? zSa3{94x60-CGByFHDmM3j=Or9VX0#znQG;{%m)VMN}ZXh8lj*wMZ0T4x}l@pYcQQ5 zn$+?I39nK0CN))C_FBDb1;|f;&ePW$6zu+1I=_mT)o}fbsJX_vglmjQ5W;} z#h=L~HII4+CObg=6;4okY`A7&b{rF>$|9rg;GBRayG#LM>(HXotvjx&LI{tr0{ZBs zN{SHG`Ixr7BnS25jsnIeC!@nrbw0(bgl29~za5nD}=zhf=S9i=PG5$ZFZx2lN_x^Uz{Lis? z4l3xfSR0sro?zA(7V5s00CZPwxp(4QC4I*19z{nXeyaQ867&J*AtK9OVmMYqJQPA` z928~V@iqA}qPPQ@L+sslw$3`upL}C(P6k<45dCh=ceed$DH0 z2XU1MN%D0A1&8+D*F2J;c8~qUKMpsA?X@*HIM1_m@m|R;eHN%IEEb$pCOwP(eGt}P zs)Hcg=guuSskD3M2Er*K z8#xLm7+qY!WjMJDn7N#Zm(z-KflK9$gweBO@~GDnBb0-#P+jE*x)B3SatOlvY%o38 zMrK0FXPneak@%Y2!r5?(Q-Elvg`oL#gSOT)oGh1m_H@b0DA^eoT z=t`E#qWwPCQGO#si0{B}IzaHNF!ps-m%eABjRK1eThYLO05dMf*c!zaC+JOdpxvPy z7Q}S7rQzc*(o22wY$PE356Du28NP0}zS-t}>hOU?X%2^`VP<@#Y2}VPG&VD5#LKDJ z9BP>A^T^@i5_}gcjbdG?IeKHyJid>=pTy_65Zd=4xQXCyM4HL2L<@?K>-6=CsuB~G z{i^TROdr4)+69*F+|_|xRRE+Y;Sg>7)Efpk>hX}tz2FNN`@%j{zc2e>SV zwj3gUpp&d!X~jyDm8@MRtvMg_)B&{4xGLhRQx{H+gR!iv5d^~i@ju^N{rl~f+6mjY zpZSZ@O(&87?JGZ$f}nk7-F@T9BN;2ILZO@V_k{jnZcJsv^({x?8$q z!q@A}e2TaHfdv|P&k(%tA3cjgMEq6o?3+B9*HS&}uKQ_{w>W2xKb8Wy+fg$090XZd z_!yf{`6J^vioBZ_PEv)1^3~i8U-Wa-8WI;{T&4)#@d2hWwTNaWPa4N`QuC;WE?Q1| zMbVub$_C1=`ryH-FI?8&*rk}pv%-R&o47(BdO%2=!M8JNfQG3$Ei=3pB{yQ1c=-6=yvA>*bVGX$)cfW^b&8ZOgs$pImNQnPfKLO^zr71R{j;q&mdpMk7FmW)rcv+Do%0k|8Mw`D$Jm4mjRes5vId`G>CF*GOOr>fT$VHb>1*Y8cpybW)3k-(eM2? z{9X(z66J`k#Vkf>1{H6KYa$t--*2RK^Ckw%k&&&e9EuF1-mtx5A=m@SRqwfmmn+4% z7mrXyAyHWQo>48aycnG;Lr-97*9h##F@sl&6!iusbSLA!&*3oGKxmj5e5&O-Y|lzg z)G9Z_Q~$|RyUZ)_v~m|@iO@h{K~^2@5>9tG6wHf~T=_EM!mU|T!eK;=um~GN{s&-V zw9#^dpA;U>LfY(u6xTNhU|LzRS>=m&;ToBV+Q79YYJ)t)Y;a*azfW-r`GRs^_s3jF za2ilK{KheM(rnfU$>N?NIW}W`$KZb^Uo7aJZltKD7YJ!;J+nhJ7tW+`YRFVARuM0*&^76w z=Y2L_*90EbA|&600AF7$nGiY+1oN3e!7ce3Fhf1vh^S3yAh9@QeWc24MSe1{tNQ#H?TJ<-416>}8ut>ZeuWpfG$T{e(Q7+BjUr&~@`yl|t> zr{lO(!^51W?45(AtWA**-`)<%{;gzHmr|Q(;2JaMj|^^~a^nDmtMebK!g3_DECBT% zU)QkLuxdv!DbWukZSndn-PLPh271M`kKI-}AHT(=Y(tw)dSBiKOYLyc%vdwOdzw-{ z@?lJi`*9&#Ha2PS-HkZg8aZz`dcJm{@*v}(PD~e**wO4KgfsXw+O{!;ny`!npN+7t z-3f%#8E|8(3{(y6XQP$}d4AI3kG{n)bKCqyc~i0X9p85mRoapCAs6s!aB%LvUbv4# zRV^ZYBmN6clO6vF%E3$d4{WU<)44I!`G6UAb@m?sjQRie0g?Wv56CBTJ($gUXfGB1 z^w!ePpA7H%3#@q#jC2XOAn%>k+&Vdst*n=HN*3P;0ewX)KX(eT1gmZ@<>&VWSkhkW zX-?7AnJJUwt=%ViN8^VeGczu3{JH64sg9K+c(dTNActsvoC@~`=qcWSPZI-!!c1Md zq*!P8D+&Q6${jBP1(=rcs1KiKe8srslRj=$jL6!97RYCKkamRk{N-hS_IwcXJ5o!a z*H+oAIGPiIsQ7+A`Dr7~6^s$gW171!(`=E_K|zO=7NOaBZ=s0xqn=E(&!0<0HFngB zY&6P3pBcIH5`r)*(x%tpKv^(WzmR<$Mx|3Z>U4R8zB zAu&Ms#pD_c{HaG4jCU*E^+w8~Lud{}8||9tY5rzBtT_}PfwD0u_$R}M-dnWxb|Sb9 zKhAZ%i2HKT2?On4_f3?d5VgLs?KZ@qyTC+g<1bl=`x7ZKbl*i`Br|WD6SLN&Y-@99~ z62?8-rEU=6ER0{}DR#nOm-kd1DnWc|Rf!(4s73~ZL9+0aemyxp>7BeQp8~GtBm>Al zA&cN{E5Bd8+9A@~dD?BE1{><@P_h{cxrc{9TEg|AaZ=D1VHk=CCKvv>w*n)Ar9z3` zSqsa&ro$xhTMoMSt@cLBN!r0){13zrW6>pmfY8C=c3y>PkXiFk7b4cQ*4Y^Z(O5?$ z^+-DAQ$JI26n~wF_OkUS_Z(EBnE*H(yx5(vq3qi1(fY>3rkO+sM5=6hH`AndzX|0K z2~mDoY0JbysvXfHY?HtiiiRe=WH+~$0Jn5Gln^e%XNViN0?1~j62L4*06NgPisRU=cNu4Vo@IsB$b{J zVs<5h!)>xE=5h`q|50d(4S-)5~r+5tR(D&8_l@8j&3BD(k;k1)}SIVTO z8@;<5@A;V@A2ioe+vOxZyBE^J1t%-#dlCJ>jIxYUH>y-ejlh6%kyR|5vM1{F;$FGN zOI@?Z$s1(DA~j!W-qXMQwvRb99w#l6=)J!iEUC>3Cz?M)C)4d-gLDLa7=noz8~5mi zsR+;%YGA5Z#m@ONka9`p8<)jKPDN2}*uqCMv;O%Gt%%_JtJ{|&)ur`<%n$?oE>i+p zr%nz$;o>0QZ>6W0!c6)U)Wr>$?7)B+sXxBa>|UP3epNzDr+x0q^*ILBqSzB&kku ztg@gr)TH7vb-3;7ETKOLK>Jt9VLs6}A(;dfxl|rq^?1FH?S*0>QQTug*1{JpK=dN6 zMS$juRYR(JkPy&=a8(iQVUk;-)(W0;1q}QTU}P=ksezkePyW(fvsfN|pEl_1OwY}J zg6?%YOXMa}nDF7MQK&}ru;@OBJ2#?s!tYYF#>+pNYJZ)`svgO*WD9hmi9?KnWJui%s!)F{DV1*T)YmSAu&O3?==_c; z;&H%Qwp?-{8D4VM zQ^jQyYN-2y2oI!aKK7#el6%lM%88$)7**K17vDej(fibzr6kjYMdhSPU-pPhDewb2 z-(MJsRxbE?cd)3>3H;<6zd)tbf=4xdxwN`%jul`e2PG}Q z?l~^}UtAaMsuiFi_a2+>fiDdEo-hPR!7<69IkYbv;6}Ci(oT*DcU;%s^K7*ayEFtP0fZ%{snUZPNo8i<6+U3cMcp+8o3oz z*#F|QRd&A6{H8vW7nPovpx<4j^6ujA3q)X!yv7d()>|;H-tp%?WnF{_#{0! zZNy)IT+T*sbJi5&-xu}&%o}j1!)#?g(qN=W7$;}HsZe0h@V%}0(7KV71D-g~BKV68 z9Iqpuriez8(M(M&##9i~mhQ6V8(k^5j3R#8mOl(Jp>%tCi4q`srKXsu5RCcqWwLQA zD#sxL3g=qq;P9aKmGZmGS%+SJZUFl*!8v@Aa8#T%`wB#70=mIO1G)%{abhPRjfce-?w>?tu5pGT(Y!T0T zR3b%(* zy!6AzNd{8RTt7EG?p_WJQHl(-d|FRIHoU)qvBXa91-2a6CiU_2&yZ<&Yc-#sgS`d7 zm-<(~VXweqwf<|Z9oz@&Kg1a2e^`DWhv zS=z;brKBFO3Z??o+=XNMPj>#Ql=z9~$@&UIgi!mC4I%XhJ&hs*+^Ng!b3%AnYbMuE zvk910Yd;_eQ?-JRfG zf_qDmLXqO`($W%&Lx7+KitBgt+yBna>^^TYdHpBkYMcUu-E7TuE?@GHp$Webwd zejXVutK^S~ZERzVc>gxPFPI=CP<;42RYmeF)Cx|_-0cz@L1owSjDU(J#?h5Z|5okU zic++swXgvpd}snuNlv~+`Y*WZ#BQC2rH@3;CrZ9qak~?WgnKyOb(gP1Dsiwr82E0Ifl$I>@%$jx_D{=q#~Ba%_C-=r zV8gEdXN}|DPI0I1nD+L|_?QiDfbr)xb2&3Oa&2MA?7{^ z7!She46!V7e$IyQM;W;&*GZ^*0V!Mnu0$E2RYo5*0GH(S4e{d$k=uklc2oxm4b|9D znoUbCr^+`l8Og6^IRLX{*zF*VFFFYutXIGvh;BxOydG{~_32QFAg6vG`(t>+M@FQG zje|7Rubh@42O%-PN6h?;NYmYb3yKJA6hCfp2mkxh zc{=AO>>ZQ2UBDuFcRHLeJr8YlSfN4B_=Cx}@j!rb_QmsZT>D7ZGU~+wW<5}B$w>V5 z#-k+7jxqP*m0@2CFT3^1(fH)pxu{d?3r#6rZ6l%=XT>9P^2cftk|=-bb#-9goAJ&A zF>airjLibTfCTC8!45&FX zlk9HpDr(Aoe$`@Ch7kXS9}rh3SUpy{tmdcL-{X{1gHSc3(B{{ z1Q2v~B{XJs-K$w`<)(wxaE3wdyhSG$N70&14ngvLrp4l$D-iS9Y0)7IX@&+qV(T3{ zwiE=a+C%%c5XO)9D^LZ&y*v}LTfVC__c+@8dA{I7*)EcyqZ8Bw$_cdP)-?_cy0`t~ zWEMRZmTD2O6)cTM67m@V6Ue^aT;v(f8GY{f2v2)~H$ql&Q%Iqcjy%omNq%n9mAnq? zwBopUK1)~f8aqm!r~6{jD{*4(b^ha1^Hmy4+C$!2e}NoJhB+iqonWwh1Vgi;$Nmsf zzcztPgVJTR;Y2p7nZ=kz#sO|TG)-gG62E!sNiV5Hea^@+i}ywdD%qI@nR5RYSupS1 z2u$-3o9gDAxE`A3Ff+V?XvHtQrV38;9eEIZ&;%BV8JJAbHDSyG6OzQ*Q!kzTi{B|4_elKZ`FnPOpu1MC$0n!NF5|@@Hj?wy@BOO4NWW7u zo6LL53M?dTERiR>Q>drq>xFLYYTfd}(K7FMPoTBEt}hi_wrT+x{m@;yxuWen5~AS4 zq14mQBrN8^@CfvOQZJbNz&zi;9rkkwj0GTnIbey?%b zk5_T6H}T3%y9HmppU+N`qahpd#sdSw=7uiIEBX?>;xo)2*p?VfeeUn-TI$;(TYmsj zmJlAUf^NmlU(`LYI-2NlvzA>5DdazN6ux3R1M%}Ru=8(_+H^SST3tX;b@*ZF;lEJo zGEV>3cNQX}uV;3oGQCi}v1;F+Zxgr7ww>jYZw|WcWBe-GAN!ML8XWai9({8nzozYt z&f{K;k$Gc$>S6Z(u9N`-0%G1arUW9d=On6+$1EQ6r~luf8>QvOqX; zJ}&2wAow6l9D_&<7-XsE$)*QM4G2B^+uybG9?VSK%kl@5>0OWaD*y7OSk?l}OGc~- zuo3zgu=07qPVd7ZgMlzrgh%frnxUlS+ipQuvBg)glFh611)4G&O3XtSLkM9hQA@lU_(;Ns19`>Az*tv9V3;}P|w zDk6_MjqersD*OwVP~_|FBK3u+-lsTJ2o*_Qp?mnMkNs*E$E~+h4R|ipan9TDE~-LY zG*79)-(=M?b_5<+H(e3czxUMR#ee^qx;7tRXoPWqcq^z6l&A5$KNOeLhF4tm8_{C3 z_wdsAw*16Fe$2?Nxa1iXt!kEY^K^|Wp2*17?k6z3!mZsOyEf@qme28V#88lPaWcmO zG|Fe*nU}a;!QniG5$h>+B(Pce>k&}l{>~lRxaT~b!?Ij|)lJivCQ8}wWe&zYn|~q+ z6|fr*GV}34kbk{&3NyMj-H|gG>FKrOQjoVayjqrIiS4c`l@@@@*= z8EvZVkkgzkzO&BeVEdCuiWi&`3Jk(PDk`GCU7hUP{!hg{2h-DSSllNYGKKxs~Z zNr|g*a-aGp#tL+PHNWSdc4LF&evz)2L$yI?Ydg~s?rn(OyP@v)sxWc0z@ezrG&nhv zm(Dh?sxGcoBAU}~XBFCqSy9d+YyK8E)apXr`ZTc-=2lz1)IjEbp*sU{jKmKdY0{G~ zmKYJoqk)|YIccMhhKfW(7``HKFCyZg-1&BTP75B7gEOh98Q&t8$vz)4iRvw(g8@{) z{x)ScXuYm*{`7TNhu|ksfv`Iu`2k!^;d;8{>+q`bCnGRq5myN#TIx>FzF}nLAZgd% z@vA01;s-yCfSo7Pvd0(uB2U+@Vdir#)0KXC;j{Ba*$im$iT^{BV(YXumPQ( zteCg-{InqkEL(5p9Yc?Ovq(543O*7Bs36BqQ%tI;A@{tm=kOw0|0;wY#C84?E;hbr znrvo|C+>Bw8cpRnEt1TcYkMxB>uEXQ{hi9N#hzx}0%v-w zAMq4-e9tIg%JA%GhL{r*E@fk<`2OtyX z%aI>-*EGqrB>Utb5C>()7A%Jx6?s5V9v($O5Nx;V7+2+z7Pf;gEzc*$D_f37nbFuD zST;oQ>1_6w8PK)=hc;13<4Me8`NV3t^af#dK594dAA+~Ul%uiN<52UF<)1Fr2jELb zX*Fzm>sVQ-4zJOVV-YT-*_}Si|K6c+?U`-4Uo5nGL-|V80XsA6x93T+gg8v6As8uf zar;}N-1<8=J;RUxh8D+^-vz~eAHbbbLSqwpupTx+5PG;xt-s85`k6H}iRe@NR_%;G zPS@O(By>o+p55gi`32`q-C{TYPhw+2^^Cq^JSO)TM*CZlMpv9QQ!G`u$X1Ft;TLt% z8!}jSx+iwTQ|(lp1X6 zVG&BDpKudAVQN;}^)GcjpP^Rdo zQ*Uc-g$p+!E9>EjZ(5j&J;NVtY2f*KQn)8BMx6iQQQ&3KcT%pM@ohiL4G^dn{w8rU znM*(25<>@@=PPx4&XwX_Ki_62#o-%zdZFd~lL^p;4rM!K#vo}`j&M}2!BMn%utBLX z?f>$UWG7J(b|~SyU~$Ax|HYu-^l18=v4-4M9G!fNT42+M+SKtMe7u+;MOb3u?a|Ua zr&WXHe}gAQtI30PTo|`IK7{r)p=?elfN{5=2;XaRk7^p$?y7-<2~=ktdN23n^&cQT z`;P<9=LkYTt7b*|?{}Kgv+qqQKY>2&4HQ754E~0CqB%4fKR7&%ox~qSqkcI^AAdwY zUtG`Kr=661C%YVK?JH5k@s$O4?8oF|j0g2EvY}}?z3uf(kKmC|$JvF?>LEP=Iwte5 zn}qDb2e%)+BEwhxaSmIG^OrN!mCRn3H|L>{&HjCt=|BYO9h;VNcf;EGk>^_-O7!k1 zcZW{-XiY+&&bu#K*QDi4#>jO2bc7_FO#Rd_2 zT)Febt1R|HqVreYM-h^;Se{5AEgXj|s{yvv{AOlkKPGu>ly#nvqXg<2M2Hl`hW_gB z?#^7bSsOx9mM8bA@qUi1#ey$zR-%iRhU8VR_X;!l~u#RoLTbxc4`CO7ilewW__*# zcS~``JB1qoT~*+Yp~|RH5BlAnni}c9?r6t!nW?K%!b%kh`!PaCw}c5%Q$vYx3{B|g zkH-AgEUQ%o_2v2xyEZO0oGD&~v}K_{@|O=yXb=SYpwki2x&~y^1ZKag@Jsn_Bn6w% zz{8$hsVERZ?L%z3{&AR@ez)7^6|vh;U{@F)&Fw6OJu;Fn2*2b-^C9p` z(H-~|YXxL(UL!c7;p2iac?QLC^f}`41Ou70wz&C3=~$5>D^n$IPj3fVvGOpbdo=z& z=g+#VI&MB%qvKnm8w!SSIMe`j^I0^tMNf%n=(UOIY&QqBaK1tkD1R7)sonZ!NbE(< zOREVnI%nSJ8C-f6_IeV=u7iDT zyL8JJO(T0!YQ9@~fyjCVn)Lqw7xMfqHU=m>(cNFEJQRoH3p3V1iReP*H(=f_lF*#& z+mx!oz9nyQ{2&9~T*&4E30%mF^;Witz(p}ci62c?KU(J_tP4udCN^p?a06c*MQ!Kkw}eJ>k!s)j~Y zls#Vr+CPtq?tu!jM{AM~bPRFN|7;SG7e< zh4C_fAw|f5BM-iFq{i^KB=h`HWOm%RsW<9Ry zcAp{(P-%`Y6MP<5w8hw5&v{O}U1`IHLRDGlhEq-G^M@O4p15TFc2{8=Z5kNqSRZWX zciTpzl11eSwNL^>#D$tMv+ev9VcEGC+Lg`Z(#KGpaa~+lhZ#0iS zPzt#Ka*zWI=OLJGR2luGvaPUcV#zP~h+iH1Ukp;_at{bf$yq|ZdFG=+@~+S>iQFqX)T*B2`?vb74zmpEK&wY(%dnHr%P7@|b6{Abu?vQTiV&~wot5u_ycfWmVlA@-NGu^+1U371N zGUyN-&gkDqK-O9O(0YZU{^WFxe)w>ZdZCm6u6B~rNQ0)*8NAVK0C>uN zg+%Xj*ND#Sx&#_+p2zV?2~@lPl_lPYuj}@BeSbMa>LAkn^H~Rcp4`{DjxOncVbt*pKG7J8;pI&Obv3i2)hi$Ls*z zQTnUXdU;Ks{!eu*l<$ccSNBi&TL!wMpeknZ?X6sG)}ki! zd#@X#H62jDfhJsxx;m((J|BB3+@q+#_rtsCLn$WDmm z(^(d|9bZWCLRH)}_M$f^nGVR4N?`~T-61QPoDUO z0k{c>sRbxT1UfU}!?dT&xWAunh&7Spr@VGbHG-#KWJULOv)}XstZzd+x9{-{dx%ZW zyYZRJC$C)(IA&=K6*$d=;79Qrpx;{6SJ8%p6)Nx?y8{+?-Hf2#KRX0?(Y_R?so!dS zOmymXv*-p2{?t()MM<>P7PT)T=->Cq82!GmsOI5hijwH-oV zXt|I4z1tX7nwd=a*}E(d>{jLId^owV$h}#?(XJ64;Qh&p%waH&_SL=w`{CFSy)g-h zqGs0OKAh}zfV_c!U1aGX5D=Dgagd!lZvK&xr~-*@Fx*NR%7lbrC`2jmKZNT{`-Ln2 z&j+*ZGuQd-nr0$U_!KV|ZZ{PjUiH5d5)0*md9LB$MU61%g)Xo++LXncjgG?lpk6-( zY^6URrC6BDFye{lpG6XSE>)DxF_^Nx{P(;3rE73teCee`Vc*GsHcBW5;19vXcsO*_yi zhsXZd3JW2?IZ=rfsp7Y(^s2E#8%aR8}luEgWxR)y7k}@6~v?-8BBXW@r z&{cidI^k5WcZ0X-Ae)rCHWsk18~N|odzytuw9=qzP8TypeQH3=g?bBnOxt{z&gm#E z=o?a02WVU=agnEuoPFiam9hvbwQ~>?j+u@I!)J{=snL1`?*>bYNrvYo&`mPgGV*cDUe8d3=oDb>|UL_9B`OGt=g}qw1t42K5O#DrTE#q&t4^dynhJIZB5p zbD!08R*I@0MqfJNu5zC0S~SQH4dt0Hj~9N!ERo#iDT^CK!bA;z4T@(KZ3@GzP-yCH zEOS@~xmYRIW$Fi+Gnjqh#ul$Z)&_A9$@iH*0DVZ#awgX>WB**hR&3XIjBv86ei5`- zZau-c(-ktoc`uHxA{@M`Iing^BwT2!uWDBDJ0y72+rZ}F$NGXLs-QNeyG!@eD#4Kt@ ztbVkhL);1X%v)z+kpDiuoxvB#oAp-kqPH=ZSI?KKm7?KjU?nmsukP*;^E~0=X=gCC zidr>SL7^mQb)(PnEyI~qr|r108ZosGWo@ zU_ZdGLcNynRL}P2@F)HQ^uOKgw4k;C8r1)P9;ZcvQNo>)RqC8Vn$EsDK6}(mn|@f; zD6QaEtH>y>wKpz@Ko@PP@znAp(J&({0taT3#94Lx21Qf3F`_Fn5zEH0qm?Ew=vJ%X>+E?@R5sCdPLZ^Yo zdSPKx!R`BAUv`P%twB?FB_ne3%!Xz}CrR%wj(Nv;YF3Y)NIz)SB;i+!*3(y3?Vl|A z#*!uymm{=i8GI(Qg%@$nuigKKugV?cA4tx>K$46fTeAXGpI8Mgehm4Ffd^?-q;7*p7--IC)GXLH9{^aS zypn9Ra#epnyO^x9i}-xGK}J6i-^ue3tncd{=A*s?s;q4B z?jPy<#c9qxC$?IEH^Z(y@S6s+>Z?>oDVTxf-uChyMJ6z0R@7oqGVEa&f0efJ2Cw)Q zdP#IYl)7a|VYA$4N{Z=N6U*M)pi+pef-5mhWpsy{roY!={pE6=hhLfxXhudKMVI16 zWFzVII%7FXTwidiM~?*3Dc4sF^ou9z&%YYgqnbh4x;%#{(z_ZC@?FBg*Je;z3>Db#PNqTZTmT}v1|eDNY=`}?ah*vzh*VVyk=N7R-CqT5gnM2}EI%%0a% zPId))CxM>x_r?b5BY&MgK>tJzkd4fMW8xQHbk5_f4%5MBg*N@nz3!AZ&yz{5hn47v zO$^PS_NfjhATn>OuVUX%$p<0QfGw?{IRoR-D7NEE1Uqeq;Jpi4$h+eQ>&*iCnuElb z`yNtD7WIcN2i?KG235|^r`?-fB*>TMPx&!&jUK%cZtqh0;7yjnWmB^(w3?r>3)Rds zE3U>h;!iS_40DDeySK787fv90G+wI^)v-|?g(Xz;E~2{qJSPuh^gPK4=l-v^o082a zg*q4q7=fR&eU4zmDvq9QijA|x2L+^pJ@3W?f?-=9%RGZVH4-FB>efbdfKY$qe%B&KH|0Siaet z6Pv!>{1xl%+uQ6k-z2SshxMBw1Za4!;xRuQ5#P9f1vjSn_d@TB(}Rtogl_srX%PI5!^hYPl>r1tTQRJ1 z;wwqLMc#3?-4i%EzeT`%KT47$){kpaAwFLIbcE{OqvwP8IJUKUa1zB_@@k<~C{dFj4C8m>0#i|968>>_5&d>hC7Mfo?&H`fp)&e0`kNn= z=vPy4KoG1uzrt%ylw6euR#UHW_)TS^u`i+D4O_NtUELQMc#w#IzfejpJp07!uiZGS zR}((}A0WWeTeIswfUE=7V2|DZd91<;{tiAoIGhzcvWMf93|dKUK%r2KhyER#&^hQc znRLwD7GLr6pTBc{0!JtY66#429|%$Vze8*#sJ%5P?OMge(A~~js)Nz&iBx`Ovbs4_ z42_u!=~r7Gz35ac@x`Y8yE=N@RiH03HV2 zOqIdS8pO&Wz!y@~;G}==&4*n7Pi?@s=qA%Xr2f?#nT$`z z9vpC%*ZnxQa%iWC$XF8F*uA5LqRk~|!bAfnam_h%$${)Q{sXCQmz*(D%>$mE-CpeOeebA*{}h3e~K3>%3>1n|$2vL-{feL{N07 zgck10<_PAilRO?aRqj>Tp@t|=j zI7JD$@g*$!oxnI_(wk?J{{iSUHOJnBsZvO*-ueg{zSN?(C3KBY8I@9b!PGG48qOeh zNdEaCPu_Ph3}Aw{+=oZGKOS0=0?oki7qiLw2yna_P@Y=_NS%gUj;k3LqdT`S+H$w` z^Gm{f#4P$5*9oU9Z}Vjq;wDZTSnDjgy=WS3W~L~9r6FM}M=XcyY%t5R&Xd^g7Y3ix zvC`eH&Xab5l?XO%j`Lt!4>UvfW%nysOC$jkipOrRw;QQPOOGdzt1DkDU*~MLns$u9P)shBS-)YY*y>!%P_^#u%`u5N5Q;}l{?Tilx1wYUqrb5*b;3>w z^u_6zS6qQsiHJR+i=w0+2bvA^VKufNi@cF&l}3wAt)#L}(dK=LB}H_0 z7!h`#qM-^jjm(gU=R}y#?>N~6wM5ZkcUH{wM&Ogtz7c7b!eO~PRqWi8cS44|Aee3LZ=s&W4z|U)`uu;gg zBYp6+>`$ni9SeoLnjTjV?C=?{JHyAZkj}SS1!yv#=Iar)j!Vz_kC8p)B3B zamKQb>vrIqh-uZulu{TlL|E5_*37uEnmOLnFI-#`+8C7|$dn)V_4qFt@}IRw4{HQ= z>?TG##_CFL4mWPQ!cX?Q{^6Bm&{J$0@N)`7mlkyfKZ}IyYTg(Od+L@`ePV|zfXoAD z`Ik?yZDX6d8LnW@QuRVo6*W02%*^Fx%#G>i?bAiT->uA```u#361Bx(i|KKEH|Ykc zhzIHO!QKCzp;lq}7U8bXWO#ocEg6S~D)RQYU@a2w1afu_8zFI|<2ChsE zZ2((CRkTD{774tCi0*O!{s*XjufNl^SwtfOV>-=S-& z@wa~WjM*lBNItOB$B}KQJsB{p|9FSz*jTyP?C_niav-bp29iytOE`~SM zZLBOWL+8O{yiUgp42YCaM3AVIe;fRKjau{GMQ3|?&mq+jsX=xR+kIkR#e3#Zdnnm^ zME4GFLh>9#Cw;R%K93U=zms^1Mf!MgNjjA5l=Z8s#Sn0K(edZf~P+LgJc z36ugIOVYqJpuqrRF0ztzYqt+1p=s)-NtY}L;Wh&D@NpTuDafAa(Ehc^MS`;kw1+Hd z2LY--p1t#uKgNWXo!<<|8uP^EBkETY)I~rR1D4pNpENq{rtd`==6CgU=hZYbQ$OPh6s7J`?dtXXT)+!fzqd2~ zj``;T$zI1c%mcM8)tLC0)Lrc`!H58c^g^<7-(!)fa+`uL-3EsfB)h!Nq0*l2_h9dw zA(~c8yqe%~f-v5^PzSLQ+7~JY2KPZW-<%E7+QbLX+nDqHBS>%R;ta9tVL@suAAMXA z*Fzo5XkvWLx23mN1%xtyP&2Egd5hbb*2wmU?LiXGJcm)4MKiIvYCQaI%o{EK&_%fC^DKLh-0|A7A<8rprGMU+{7wUFF*U1sXKlMV^=IGP8`YO8Vw&L4OADsLA82oDo^_wjh% z+*x`9-p9}0z$!`)E(bE1F%g_t0I#^vA*q#nvC!$;!h36O55oyq#nlrp4d7_{GYzGx zqqHUvA*#%?8$GO`Wt<^e?thT7`zAK-rHa`FQY1Jr=?~4gx_hqxBsi)(u~kUw*7Y+e z>dm|L_QSDEwn+g+2nzn%gYcca_uw?z+EkKV-P;xtWQcNEIE@e{GWCr8)A@HhFcc_D z&l=x7^=qN%djOwEujsJG9SterZx=iw_X_j4`DG36%Z)HdNdANt4LPeO3{W9$`IF!S zLRZN7oiDTeoml_BH2^wYLrJ4FNU%UQJ^X|c_r zirqrc>D`eiH^mVONJnt_e~QGuuJAf;R0{XEYNYgtQ3S~w59ku1ZY#$ZER%AVfUOtF zCtk&14tJlmH_mNB#}9l>3?E27nsvvK{`%?IVwkr8V%0|7YmvFJa;+XgGrf2uOoS#3 zQUZ3bDIGG!pU!jy*Xl>a5HNMicX1qT?U}mDSfFBv0EgUm_QSx{5Qf$gdyPY3!t0`f zb|d3J+-{{-gt#1lgoNp|I}&oj7rpGr@&^vYiI-)eyqT(}*Jmmz?J8+wuS;M|Rxk*$ z^Tg!u1G-&r@~Zl(e3=uyZ2yv%Dus6*Hx8#@Rtoz5umfv(fkmSI=5l8DPt{U#gS{K@ z0)RhDdwu~EtB`G7!{@#e$|zCL^>ub_Y%sl$`8aXqFd85ODSUDQS=oEmKQ;)uSDy~# z5M*eLws>7+{>;;KFeSRxrY;m-8~9DAkW~ZB|{dy z|G&SS`0Hpq$dt<1Degwi>X+ub`MCQwkkS?4E z>mJzn-mZGu>*c=NW5e0DN9-4j&+x#IOZnJ`>*_beFhPUY^YVrL-`HJgj%{9c@t_S6 z{Y^-gy8Ysg!8W*Lr@m`Q(p@>$_M>(J4#zZgi-el&D9-t{tRPMfayf#hA&%UQ+0;)U&1_rm%#jrDRyy}1s)Mm zW{EArPWFpBO^JTbrgi|i{_Jg$)hLWXB~rVF%d#lQIatk|URya}=u{DU9%KK^H|*;@ zVYR|XF^@F0Jk0*xxI&(lD~6fhaKto`RE_naBgyE?#sb3<;GAI&Pfv-*qL&s2-hP^v z5SG?U%uAGN5o%dec|2=6L!paa$>fp|)9d-}bD^Akxwn11UjwI_f`se)GOM=N6T+wk zr_|7y&Qk8Q%Bd>OO~13%d(nu_XZ!}qD_-`b*i`Re3>7H@f^~3$lo?Nm%Fo&XF-i_e zMC5crduH^gd)w@hgmdL(zIavS&}i8eQnPZ(FGE-T zt~laKQ$RtPUDs9xqL}R|0`UabI@(;0cM_DlE_!Nm%mLS&Y5&bOhW+Wj=IOLN*$tn3 zaliZj)PEdZ=Mmv@rg;AWCOJ*TNbDMiMh6tZcDPy{VIHNCmq#x@hH3AwpYF^gS2z4N zyJ#`n$=5N{P(6O4SueWt=9bsd(e*EPvlNU-kwn>&f-c;IKn&pB4(CrR4iRfTLAz`J z0U9iWHX6Ijw5rG9<^r)84>DQD#eAnE55Cy2yVWBiU0rp!uLw}UexB=oYjwzvBO0b{ zj?*3)p8W9=dAq~?v@MRID#w}VdpWB+`GpacN8exseGBg8eF~bVp=p#kB z4CIMJGqgj$jcR72752BAg1nW0j3=TB#U0pneuEqw&|OCKX^aUDUL+dp-d~xbY>R5V zZ1M?r0C(w4YW+N#OxdtG*b1)83(Cwt`)n^ftDAz-IF1A?y-R7&a8^B7m9TO#oDM_t6))sYb!l)l`2Bf4NReC<`bV7v z=y9_C6@Nfz>zIqc|96nGsYO1&p8kC`_L}R#lKID%TEd4t6ulKS6pEt)L;W8l1STC) zBZUZEulgm`-kkt5`z1rRF>xA~rWi{NB?r2K%C0Gfb}tXkObLqTa3=h3{{;^7Mz8^s zv&P^wMJ>ck>X3gcD$mF*PSSS(XNV%%LU&5FP3b19pIAT-!ZpeDcomh&7Nx?_7Tqin zeZvLFFyJx>>+3~-A6@^wOS1y@QwvlzzeNbpYDM>$OjH+9;fcN6+F;{OS)8^n$IR$= zm2}sgAg)}x4jO_M>IA=v#6a6py&1;&`Y+%r^tl5+TQ1p`?{-Z8>w*Jh<#5yLnn`No zRCqRtebqQcA6RY&I^!seq)qVtRSy)hgi8zw(R`eB(LNR8lSc?P&<1ogV4ZO@HI+n& z-*~!vSt`_foyTD$NDLwWjYc+IiiF(pI)7Jr^V~A)IH*z+)`3_RL?|xbTdG)7!7+QU zO9ha#*xz^>7u7@|Wx&p-e^jlY-rEngQG)%ap?(UC$;dGyN{q4}ho{_v0HUSwUn6=O zplQKI*Se7DjLuB=V5=Xj76wAT^?Bsjz-0o9kfjz!V$pW@Pm&u8B1&i;W_ziFVWALF z+^_qRk{9MX4LlNkKqwB)Ys)hTM>Vw^b0X`AUC{3 z;WW1q-8TG%PMmwI5n#+2CS$uab4kw^uB{VMWVy}GD&;TW%w@flc$9*>Uy%Bitz(!7 z@(D@j-5wad_J4p>FH`Dk-$k^&(B|Sp!s+_=_#iB=?7TvRD#`et+_eG-gQSnu!qbS(5C0Ogf{hNJY~{19I&4AAsb4-N)E_tI(&G@dr!Ik^dE;d-uS3!19*3 zqG*~x#T8#qWIyFu?@}X%`^3SY%P|p>WQjKf6EVH}mtCPifl+x=-qOMvN%x-Z>P!HS z5!n5SFZ{)h8CisP3zTA_`}tr=*Ws5@{H~uuU|5omIWJH4M_7lU5H)9@P!t!1?e42ot_a~}QAyswKD@_NIwqdK&G*wd z5f{=PL?m~80!%I)zwfBQ9@ZAQXw=2>P=bZwoq+J*CkX2;+5KMWJ0d&Id!S<=lrpZXdhyI;+j5dr{?5lt7@+!d~*0X8e%x*@&F_Kx?C&JP)TZjY@OIl zY@^KGR5ME30oN)%am;PTSqK0}6U|mVP6s*(=zc+NcxM#e{h29{ za_L_IDj{eO_J?v95?e7d_8E=>)hPw`{)=HP zdKYY4ZH?2w{^O31`P)UxUtYaQ(|Dt`yw~0nsYLTd=R#*&qLz2U>G_`vtjlNL@0~ZX zwv=p;%pSuUM}4=VAA!&x*qO7S+Y!oalgnYB+IL$M9cca$)PocC`VSbe!y0)6{es{PLY08FWQnWS4u zn14VV#ir^C-5C4UY!puJ>?L{w!+^>-QRb5jPeKOZz`wKeB+hTM|5yj!KrAn)-QV92}N= zUh_()d~q2HvUq%g8Z`E+lZ%*ZT#tezy-1MPcI)eo5j-5c8mQLWXgBRTkx|AB4l;#H z!6z?=jDDGHrq;VD3iRP0$!o|3bYn)6Iq*@glvkpJNzXc;wzABbOm91aJN!7((XySZ zgV_~v8aXS#C4LJ`J>eH5ugUj@NXQ%eJv$2R&{a`tvdNDNfvr2jxNdipHNj*{wg3wj%IN5=z2Xs5;2#;#Js9#f6AnQWua9 z172U7`qX&(+5#C|@oua7OP&C8SyEm?dbgUgdqwN8l$*OZ4M7coL#8@{A6xSBa9RlZ z7jY}UCM0Vr<6Z_KN|QTeIkXHV11IkX%L3fsL~k}Zlv4Whk}p2`%d-u_g8MB$phtp#og@D%51m1 z8{F_Q!cacx6ici6 z3MSARni87-HNj18?`@0+BQteTf-(@MoqNw;S$x|A^T}Q=_$wNlJM1^tyw@A+>KGOq38^7vrrp?Ka3-5GKsSa^%t#{`q8>70V zzTf8`r1%&sbP(TWrdHMGKfJYgn`W z(t0$jyWO!nO5!8qbJg3+=MVID4!C@R?9}07htqE|q2o?^5YTeu47%Vxd6|eeq`4-= z;CNHIuR-&e(Lic$MBSz@5>E~AQ53Mc2p4RkTF(nKCeG;jliQj*#xM4^BK-Y3P+iWO$$fQ+g=gCy)& zn(iJYVOI_Jbo{`9sclp?yu|cro9*Rm@x;e(J6~k5P8UrOJWosjK>R<3Y-{t`SM^<> zD}L!;Imtkwiej*@03jW3BI*0S`2K>!)E}QMc%)D1Z9$RsuMC!|fss9e4@H}b_$_@L z0bT;~N~7nEdiXIbpu2~HvUaDAIEfQYIy;J-=Xulm`lZ#mErD>q=U1K_{{h~$Fw_oD z^#t%vbG=!FhQD>*{wu^ol&0qEL!mxSOn$Sj)Cv^_xKqVZP-xM(b5gg{K=JyWbI#$j zXq65fRQuAPjy+7^$?tWJwa-g(ppsnYV);PhAHlWP-bLjQzhhI{{|gU6@V<42bCs*- z3q=q@1D6|Xt;M@I&Ie&z1co?_)O)M--L1zoKkNf*% zIW#g#)3BwxzL@j;X3T6rhDfpGOLi9Mn&uVB?VL4~qQpC4#Guj(yljjGPDC zX^|}lR9oo0VhGhE%YP35i6|_WiuaB;JhFsVn|1LpI^t>)(4@bg(=Rm(!6y2**PZo* zCl_J9$21Q_*lR++8O4zvu<^Vc4JvzIAbdSsuoo-8m%KxwyWah=R{~z2 zY)cKTxNpu=lqwk#-^|AdCI#_@7JmF3M16Q*Nbh_tN{!o$iiC=Me%OiXTh2ICm<*wL z>-ll8z~++|C!7!JRbBMSE@-9VJbU0pL_>mO2V^OD>K~tYsFWGg=ev}_h1qkTr{65W ze$1VM>S7*K(=_LvoHSoia&au-W>!W^rk24uga#B`Kgb|z-my zH*DjnlvbVI=bpL2ZRhYW9O7Mek@mUIrsh!Py=J$R{TL(`9#zHc#M^IzYwLm=iV>_M zL|r!>$k8<)H^0*xoUqim&^tijE7M@fF(pMxy#6aDI{>Gkt^@CaONJ_Q(*~vIs|XL0 z+Yam}s}Hfr(X7(km7#K6FJ|P#dFn7SVc|wT5ij!nFeKL9jn1d;ImcdJjlh$o(`Wt4 zY_gfC;$1oC+lVBf8@P-Fv%HEKIW(COt#xvyPS{rN`}{92St6M1j6Tba^$Ec9-VuBn zP9^;Fc1B5(Rj(Si0woE&X)gD?v!HO^aispcgkHN@G0WpVXgCqgp>#XV5y$y|X8yUN zo644Qjwz;4KA96)eHph^NdEv_IwE}O@2zA*b3EQ--V_0WrCWh);k+abd0_SuFvGwf z=^YaYuJNt3r)B5Q82X2;{>`mfg$ZhF|? zqlpz40C$7QzFCGi@1$~q!4(W~xFToNAI}4i;iu%7tVT#P=a)4S6I(nJCC&%|2edPK z9-SG|T5tH@=YWe3AW!%83<86I-oDu(^8nNH`VI)#IkPYb`O{Y$NgrkJjKh%{du#cu zs!AzO*9PTlh56@4x_?MqtgP7F&*3wFcK-nNk`Ye*J#ob+E~eyu^cU0pOP*d1n znQyemfm{2VbGhv1t&X$Kcj(kO!v=6)WE^1#fxsW+)Lnq<0!?e1zl<^V(0V;zTicF% zF$|eoyUG6X-DxDP-+eMp@`G}dL`lG)ZQbCR#?-SHomLTqe?UFUhvw~TsCIPozZfjH zugOvbEjhekF&=nx*v~rWH=1tEIR!b(vP3m*?}f*kaIP44=hxc?+~xjJ(+_IW9>tHk zYCG-0Tm6SQe}Wf0jCcEV=~sgb!83HMnl+n8m7Ncx+ZiJDZGM>!AxdIi$-|rh84!Dy zj!XoTUNNr&IXS|LgUHV~k3LV11y1k_Ky(Z7h?QZp1)7W7l#w*zUtMCHSm*iZepsMg zn2-E0UzCt)s*Mx$>lH&KbQZ=-C#C^Fp-4RB)zED%{vBgfz5Ly45tJxP`9Dl*zyP#6 z#^TD=4I+uphbNcYf1fxt1U_)?JbmzXK)T;t+Xv}>fy8}r!LS^MWEiS~u%7n;ZN>TJ zzy*8WbBMZ{!vXoS4%Yp#HxXh~z==A*^@DgXki{3IgnetDF`}=YzStr~bZv4{md}jaK!V`j>G7Lxm`!?*uj!1cI!+}0^6F6s zzFbz41=pJKawx{u>*Gg^W;zi)F7UZYb`(307@1fH2jH_51n@lN62|-G-u*hxHdwTL z>kJ2(ASlqgVPlVF;BR-(Ok2zBxF0L=%RH|kz)zqCYUH(naL$N}lFzRh#wo)AKb{5S z)6)jFZ62P#Ox$40K+4@-4zNbiTeN+A;+oo3#b%}vJ~7CyImH^oK_ip)FdF=@sH z$Q|6i7I0)M#x;&~&7mYZ-mn)2(_ydM3>{{w^_iipTknY>kxkH@eBuQp8%F`iOTXl$BCw(xP>WF<54> zUevjIsp|x~2eJ4C%EJ9HzW&+2yMOxinKV4J67!ijq4E99ngk!7r+!adD)8;cZlT&prI%6QKyfP3|_GW0;6B!70aQJH`W{2z3Vi^6Y5FpFNayuWS*v&PMR* zI{KNT4+&Ggcl6#Ik2T0&=|RF3^bTA&5~#+Pv*Y>_Fj~jcBzeOcvIm~H@?jj$MxW4; zHR^8|1T98^$+_PQ^P7xTH*R*G;SI+zKbt-NzRr% zl5>g)lo9^`4js-;f1wbFoq5Ix<7QdI)?7lE4vn&6`$gLm8IZR78V#Vf%Y3;Hoe z>-OJT;ps8sTvOW>JupP@)dC9MH@@!~ez1?YLStWQB{c}Xx3?6W!`K}p*Ebv#-Y{bJ zfy>TJ>T5ZFlqJiAoKa$oD$qW`o~O15xBCuq{{RHs@G)=p+EBb0QG#iqBH})|;hX?- z(9Lp!@wf=kiI~g6UL4@0=mXAih*Hx=Yrqh7;kAQz{nqDN76yN|P2Pxnw5>ka1L2@2=0Hzf;7aD>=ZQzmdS<9D{g^8)K`>-= zA$FMHq8Zl(UvEZmIiTBEX6fh(?7-AN z4&2|YD0;+s)Q61PyiWx;?7bMw3Hgr{gt;KqiW;d}=Maka&wbPV-xzOue< z4jA>Kb}>doykn6`k7DhCke9TWf)^CTBDyAlt-M={{{Stf&TjQ}g3G9O8oTbp0=I|L z=P%emP%&^xp;z<7#xqQ9;vPF7?|99FB_+q&@Fh7mE;=qc%s9KDbtWMk=kpJY^YN3@;tWSP{FuF($a+=Q6mIEzF7>v2M&8 zZaEjH=HjpCBSX=V*~rdmM1$*qjQ}pRtJ9VCy+(t6ly+95;z#G#AqAOll2-ng4c{$# z4Xaa+X5iF;<2Xed*#7{Nlt}*oqnWu3>mT8tu73>ubNFZLnlB=%6$^>u#_)AOPiOC6 z>0sC+Zi#Q(6f6G#G(o{uP!m|@&j3JA=dMBr5g8r&Ttk{ilmp`}3<`Sk{3ecd&JNiRrOtZ!-S4 z04?PH5xnch9vXqb^d7Of@nSVH^ieQ-Do7LpM5`CbdR0V|&E7@i1rKJpM94&1qBs-RNJR&6*0pfPDH zH2J{n3Q6#E#|aI^HHr{)6uYAW9!&vs1L3La=<2^PdEpNs8qje zk^VQ^5l?Wb`ek=$otp0wuFRdG?g@jMS+@e;k$!PiUT_ryv@y=HT}15tt|&lm3LQRL zz2IM3nhVv+${>)7cjbOExbG3&3>4o9ik>~ z&*{T{b7ef%I{yG?3F7H>2Mf@fR)E3zO%K(M0m$3yk~=+dQ#5U7jMJC6zc=ZeUc#q~ zfC<^gH5{m>u?uvTSq@)Zm54oiH}QjzxJK*M^}-w~!8~{Gf&t-7pT0RjZRq;r4v|Sm z#tt5qCCy-Y^7?0N6a@{U`NhlxQTI3W&e%M0h^PxWI`-woq`Bd9m(E|hB+9b#X6%wl z=3&k94hiY&`e#w>65`_fa}UccSJ?HQy1-OyS&Jte;!~v#VD-u+CmLKsvpzL|5-|nG zjS6@l_ZdQW31t5OxD;-x^Emw6jaw45$VgGyF(@mO9dS}y&3X35;hHplxbVdCU-yb0 zj{g9*BQSID^WU~KB|QHCz9q-h@81?Ge?GXtpydAmywizDb^GKH!Nqa&gHB}M`@p&r zZ}*AQd2jp6cVS`e=MV=tU$;5ZsV^Sw-x$h7?ShF^;$Q&4P8$7j;2Os9_r~x%HJ^Nh z$I?F69<}9*_r!lM=Y#Se&#ocJ^ZdAfBK`8v?(4tb0GZNOpIva`Y&+yV`0!(UAloT` z+)6E;KU{2Ius$%5s0`a~@1fQV)*K7RrufBH={(#H1cS)*%8B&uOdz?fWiG?Z#u4A? zIKyU{HU{aEV5Mc7!gz2mx9yPew`V2cg1&UZC1+xKeBz#88uUJ-Tnf2GI*`V8^S$wn zdW7Y9-PzP(Bj*T)kyzemgGRk@b|OZa#c6{Ury7+DApZ9m+4Vncr?1=g%6k33Y^Sf= z_P|B3N3Kpf&ezJnf9d62y(kFNd3BFjOL;Ys#H4(c99Tuyhbl?dA65-O4Fz|6^*wW4 z&^vd}KG@g*4)$YqsXoqbPU2g5@s|yJK5=-h;K(-KmmAnv)7!jQXnJ6uBUi5Z;}peH zDv-XZP3sYr0KkS&x(mjPBR51z*u=l43DOB&05TW9!jBK7-nWHEJgZ2vtq;=)6s}8D z^-j6gEEYpg%Od-Hn1Oddh#aN$KCWCNk-j(;OBp!B!Awjw;3f3Iv$*}g`t-Q9*$l%+ zMxLGN^ZH;P?NP$M+~ZO%a^oFkN<@BBqbtC!T6G^{d|^!QE!lb*t>lnTYrntt1@#V_ zq5fQz{`S$xhNw5fW{6~K3b99?Yqj2z-RVICeu@~Er`|~gpkc2=#zpN65D_;ZPQ@IS zJam|L)SQ-cE^jbzO;%g)UzQ7ifs&x$s&`5-oLT3Ln?XZRT}zLX33vEnYW(ZW!HmL& zOy_$)rXrdJ4udk-pGY5+Mq8>>*x?vKapt~J}j<-xI_q`88!|Cmca{h5{*b&0jcvKwR zL&81m1FENZ{7Tufp}%B)aUj0q#$2S(v3bK@>~VS%iFx(wAC~dkL2ZG_$asu`3QWrp zrw*|}E!v3H6`D>L0nE9?!_#1YwwEf^fIh!_`)5PG-#>>lpoHdd`{0fk-!fdXX+ZfH z6Swu>cg_GI(xP!p`@V89qb^pVj)U6@VMyNMK&I8a)XoNQHdt}tLhwJ=QwMYAqp7ivsMp*Z!;L^U}i z!8(rAo{jA=-ImVaPx#9PyixK@|s${7d}c1#jCTZyL<4wlsKSUtm^7)_JMZ@x#RAvw;%zKM$5Ny!W; z1^`cskijmTuQkDqQtnvmBow1v+}>KiPjzu)bRyRsN|r6cLPT%N_P{t=?xFtxai$W( zv+d&{lx}tzrCkAj{{ZVWdWal2Nd=$N7TtiBLH+Pb0zD2|t;IY(OOzx%usZrgCVpAo zFpf8~?U4F^;Kqdi06FM~H+e7*1zP+t4#yYntHCgId(>Pc;Qk%qvsmX7^qeF0&ENxq zagJy^JALqQ0sME9X%D724+%9f5bgE<09fYlP_YC`Q?5xH;;%G#EGXDUj4}I?M>5T*tNIL5n znN6x669{^pOX|Ak19{K^l|P`eVTTKNa@*U>?~Tn4HU9FxzOxusHva(DRxhRB^~IJ= zY5Fd+s;FXV`QI3rjmJ}0g#DAaaz1NFi&z#qex zyD7LG(*h@bWVp*{u-jI)of(OKkTlSpO_k(RBRW$6Nc6z^99Q`IXYgJ>`vIq5LleWC zZx^@GF%!L7Dt!q&t;Ub0wG+Z%o|E4UBUE5xiZS#gI524X-m&LBBX_DjRdG3lUg?*? z{gZC!0YQCnf_1&h0=ZY%4zia#k)V)jM0H1UVX02p0Fb0+_!yCBLQHGr>BcV9a*6Av zqcCzKa_r7WE)5{r2@nnl!{1l{(pxNf8P+=R5~6PK@@XF0ICf_)_1YoXv)R_*5U* zDSEbW$=%k++&Pm|l;rgew1yv=4}cZWJf2hNKX(8dm0q7=7gqvnXb)HQIkCuwd6<{( zF&YZ=>E9&7JaFqxuh&D@(*;(9=^k+cxSUQn1NHR9shm+?n*3)TSGIkU-g1#zMNbcm z<@oZ${BD>P5nDXeF|n;W&Gh-jXS4|WrhmY|d-cLoREy<@;Ywn@DqQhqEtDEiM@xu& z%`g=^PZ|FJGY3Sdm_qFqX0zA`B(+n+7e`2Tv!Z>t&{{4o8%Bw#u3s1(Is{+W6#!Nu z3jDY|98~Q1z_@cEx$nGghE<1Q=hqQsF`ERl0K`4>0m}#8hwGX)h*NM=^vkpIy-%;E zcO(tHakw}H@orZtDL3#qiAUQohOt>2PES?=LL-p&Gx)FRkNst!5bX8KVqCDP(D?iu z4_2TKuVLdWbvJD#;CQFk5v~Eb2WhA_q1buDYfxVE$_|uw_Qe7267r9k;~Za9;Jo|m z+F>EP4%>mOb!Ul-vQnbNS=@)y6rti8=GPh{%X4>!Dzy@P8~WnSVevp7u|0gx;@IFApIjlJp0)-l z0!|D&oeK|P(=W!0T6l}6#yTkKgXw>!J0Pin^KigxYA@hu@CLYp^}~7yqsWI+8k@eE zZ%D6a6m0{rdDgIfAr+Qe^e_R<1KSK(-X)ldifpqcF(`km@xz<{05AZPzvRRO0|r;= zn<*8=#)nCLcZ(wOJz58Uf&5W7UUEv5V-7LyJ>1~sw+kf?i)n})8xqLJnyM4KtsRID;^XZD{ka!G>_%Idw;@K3d zZUY=mg*1BN5W1KdMV zz^0<-IG|ljK_5!YSc>`^hlcL$maWuTZJv1F*90sHU4JGDG*lIylN4|XP56x8c>qJW zOynOp7Y&q0np|x`IIIU$=}yM|B<1#hgmtAW8jac~C<^OQ-`*ESwgtVBb8{9=Gq zIL0n0ayOjY%kcmVn#w_4cZ`OIpE*O{1~0BKPLnrz2p6ne;Z*w4dtg9GgeDF_<68d! z44^MUOk=_|OryQ<`N0|BcverVgRTPJIl%<`vCo9{#I12ia{2LvNh9YWl?(-S-=+Z% zhrDJYM@hU*M9n#y`(l?Y(O+%vCmBG~<%I~=;MAw{tPSSI#9`Eou7$kY&1)WUPz<~n z&~fV|SG$6LW=nxK*MvOr>In!OWmpG+GiV6|vlW3$G#urr(Mb^LW7sMhZ z{Y-8!sz>+NIVk!G_;UARa-kVzr`n%5Ld)0W8$AL%gS(CZ;)>UoqNkS@Rj%I`K2N@X zKjELjc>e(G65wxCiN{ZdD-204n>QOfZt%{`hlF4+*S8>JJN+SqjgQ0%-99|ywZ_G7 zj)jGN3vV%vU1}#^UiPlEW z&k4pjA>y2UCRNwFKJf@J1b&!;T`%Xy8~a<$^N5&04JSEEN$+Tzuun9S;nu zt)4j62;5#p&Ik{m`@s+DbCv;MIyHCaCOuG602iWq5*+1USsUWb>wJ4)DiINT5E19S z?+TnjIh@>=!^4d@76i?oMKw3PTj~i0;of@sVah@ix^GPy>T{Z>FK!w5^27XOxUTgz zAwOI}=W|*EAB-hbf&=O~{{VjhH~#=BIHV6O4gxL-;*8Jx_%hiG5l5iJhR!&ZdmlfC z4mA`aqHF^;lfnaKqBvH#!J&d6-4h0AIhZ_f!B!kN045wj{c=J^2&MX%0UN+4&Mh08 zV*Kwlhe*w!JKBae zCv5s+V%(yyfq}ea<&BCgF2R?Ln1~=<_6M!W!__Fyqk(MgR@c`F<{t-x0y4*LPd|yR zQ|@qHN$`F1ac`eBSK~)mbHr;y))DE0LBM!;-=-zGGBd7E*W4VVb`P!Z*UR2VoXC_e zh+Hlyl&21MTtJrTrvNR7u5@gey0uR~mPJ9jvA?ze@9cirKfwL7(xW#<{O@ z{&)k|;rn0~m*D-fczuuC7#lai{V)l@lIZLH;D*xK_{Ul#Tn_y2&N{IRbaU~a!~90G zlPCwDJ$qr!Uh(>4G;d$>$5Bt=)(BVPMEhpT_#NZ*DRdjv`#&>X%E- zzL-1%0p#|=n+pKEepxVDOy7T|cwm8~$P5Q;r_9rii&}r#jR3QzJqZN{efQ@N2gP~5 zsfq~`X*qr{+){LgdT$Q_4U*e{19@Hf#WIsscYJzfjXDLNObQAVv#s+4F_}1^yz*w^ zSVI23_#YP7nbRbeO%&Jtz_$bdJNWd%ND}RYo~MFg#>buIqkYMXDWAuTSi`ozOgdr1 zdC5EzY3Blvmq^PYKs>X}Aca2ItZo39H9TNX!7Ra(CB&N)IzJN$wWf$Xlji_^LKR%_k2}$dKL$0t>cxI;VZhW_Wu~3wg zI9ZCkXAHQNzvai@2*fgtAsFy|I+j9s00aBoyP8OCE%ZW1m>v-)wB5Mb7K`(p-3LcQ=Ilvxf)C7UB}-9?jZ`gSY~}>O5eF+)glh{$JXEfjwIn?}dh))X(k3~Zo2WuoN6LS&ws;o@pkyli$)#b*}^994FC() z@BUz36b}%%!M>}%LuUZ<>4=KL>9C$~ea62L$WE~?(FyVX92Mf=w|ieVyp6(UIeViKp zVrKkD=L_OLIF+@lrw*brqp6g0KDm8YvSNhc?&qREIUR%NBf4^%GA^D>^aR67?VKoG_(-CZZ<(vWK#SlWGo6d7r3{uZR;Kllya9+vt_*R+dLjZIB zA3x#p9G}NLEAh=kpVOP5{{Rf5uU3p`k({VA{vSW#^Zp+{;q(3<2K}~w!eU>x&-i@Q z;y^0mFwmRt*Zh$i?tX7b^_yiRcd_h3v*p6m&Rho%i*?4`h;f?vQq_UBAXfiW(7 zuqFp*!#@lGO5ZiOt73aUgbSEnZu8%6L%+5lbjMMXE{$nPCkHz?!ODQpCP#NY%=a_g z&vQM@_cPqZxg3`Q^re~GIhdpM>m9d9K@oRR^u_(m0HLpB%0V4IdC2l)c``hi9!!rW zN0TGTk>tpM0QYbTl_!7(1=Qc15zrvx z#P{LHZ6Z(8)8{l%rrb&r*p~S3-xUaHPBM%>mCJuJuADRkg){WPH9vvG-+kt}L#NIF zMcKnGUd9CA+?*T4yy=XfFRkr~H#x;#u=YLok{sS9uogArct)^h(l4J((KS5M;3$GP zn$8nJotEEE=o+=wP^tV`oFQ;E^1qQuoFKY(VwEf*zhQ7e>8q2!?wY>ZsEtIs|=wn58I= z<-m%)c0J5qtJPcak+2A;YJc3GTyRd!y>J2u^>Mg^(|D?JRUBslw!2G*A}BZec9bIq zIcAU4shXPs-!qzjOIzEOl02 zJ>l54{tcl5Cms30R*KL{a@;$dIA%U>Xf|zAURTc=b|(ICVia>Es?>`6s^JUuMWEO7R&WD0g;os%SjjX630DF*(t`UKm_&9>_!OJ^n_X zY0)*$>-bzOMTN#D$90{~AAFDG=kyqwXnsQ^e=p^T_I&U-5WVGh5MF!2#tc#(DkUkdXDL@rmey$B_G)PO>=$1(FwDxjllz zpxRgXW6n4`f1j>)x538}g@V_qoUR6F{eRvwaTf~CUuUy~p>8N2Bj|U5Lx}TJm_mK< zw7CQ6K@U9M4BU4^dO$_>qt-hpO_$-vIMjy6AHN05)hggp4paiFGk5gFuFG{)(c@e5 zlu^k+Dky9CVSTu;R^E_+cakK2>VBzek*yD14T(*x^_S5wDl5k~IoL-lH>R)5uJ z{Z<@`yls%=PPfJX0DYhJSUBNQJHfn_ZM}bxmm0)ADZ-XzYlGYk;vw8{rx-Jo``}Of zM+4UaFX0D;JYg1)@V6OYJRtg+RIZoyvvTf9zqS!#x3#~3CTs3YN%(TkvzDB>yc_;~ z43U4kvAHoWJN@1>jUiXYGnk+$UtT^jPyjqN?}b#J&=0ooDsJ>d#*=5N2j3+?DfA)l zoZKD2TmS_n*k``-09X$cZ#QMJbU&^QIsqFPBr07du+1$1ZS5)f;guA-$h6q`WYyB7 zkp{qKt;TOT=%zp7KYV^JA+S61=)`mItvxi~qcd6yiZp)DA74y)4M=aU`Q!cIuvdwY z6LZr%RuRestAlJGMj)xn7671)N`I`F!w-R%KwL{ca6lF#V@$%K0}T*=-V;4U61{F< zQ3Yy&x8`B>KrYSi0ra+c_WuBQ-Al`m@ASx)4@zXLg35D(8d`;48~WjftNo0Y^%omB z2{Rc>OReWvi##c0xTd-T^kDLVUHoAN0|Dmap&O%bjG!t*TK;&6PD9k@_`1sCa=hRC z!n5w;;!S4u&0wLSkci>}faqtYBKiSQFQoL!MF6JaAY5x1j;EcTKUu`O!I1{M-xzFL zd*JD?3wy^A3N|=~UJi2oae>JV{A4Xf8zO1y@{V$9e3|En?oLdKTk?;;T|%tJZXw(&6))v@!`d zI>W(XvbQ;G&Hc%cbAB?eE-9-|zFQRaxG7g1V}TDl!wSWuG;?uxTWR&clT>wtHK`FS z!Q!V$=5_0c4U?{Oa0aWHfF__J;V~dvaLc?RdBGMIpQ9ZtE|TKCO}??YaSP4>nWM%6 zEmbnjZ_QqH-yU*Arc;QV{c}Yl&7OJtrZH(fiIOUQa=Um1=O{M1WxKIODjXP=04sMU zFWiQw+q?#sfPYT8&VQr(0dlavOshsGrdMeEVy%Mum-EA^;L{)4N9~DUa6e4tb?{=| zTqpVfVt8gDYQFfFoZy4*U(W*Id=v7`5<`=ln>@G^{ID5yv z=WBFv5U46di_YxuNjted5& zy!Jk}0o(DP!e{W9i-Y*cKW_qd{9=d&ajdF zKnWVyRrGMA64*wH_X;@raP8>mXhG&Lo-lJ7vn|4q9F zYIM(Aq3A9)^!$i!?~GJ4;gc!;46s}cPpaT#z;vH z+piZ{SUiE5BC%4{I6XVgHZY=#$SI?F#JRm=x3?}MyxrHU`vHsWvFqCEPD zAFgivi5DD_U!O^Wk*;v?{aeOV))E?_#lL@MAAXb+@NZwN#LU895RbI`;-_49FJ}Tf zs9en4hp6p#Z=tD^kpL5jdSgN^oF+kbqB*LFI8iJ2#+_BP@quwBEb8GOA;uwkI3^@; zE-r%ELyhGKCzzdo@WE~^&Clv{m*LAg&R>AN)(!svInH0)3!D45HT7;S{_EBxSOL*` zueaL}(VS!|ySZ2hLEr_u$yLI$l8QX$(buTba(N6S+h~s^SCzto@GT{~S#t4HkZ&)` z0kdfbeadm*RVg^RA4W7sZO=XIT;%Cu3EI{0$T5wbOR$)xfq<;e9-w^UBhro%rs@s# zz-k7OD6k@rGvgvA32lRy75XuzRANvd4%Y&5s0iTF31maKzuvz8{U&)Gx63%ytmQ|dYi(CNL)ph>y zvW5X!X+E9fQ$!wuO>Z?lAvMqMi1-1AM)>tGxM~vtesB=(ine)}{sz1i`tbFU-D@g7 zFp+E}i>Hqc3iBlKFH_eQ69Y7psq5zqt#l!N*?n~oO{bZcDb+$=GggTpRvX;?GFae; z9CG64vV}R}lyRbzvUTX?`A|0%qyYnmwhhoAK`u@_GIYn&9<`u4VP&K)H*oyhELwJ% zV`g!h=C2%>$hd*ogjQRSm_BLF5Rx9k;I9aX-n)5nEC#(ti!dlBJl}ecPVn4k(>k`cHsfCdDdgSP_bC$2p9PfSWk_`+9CGqo}XC=gqte$&&= zAp~00Wy2McLw)h?Q9Kv7T)itj7VSti95vsY~7Kq;}##E83ziS*7Ex`?SW2roHd>?+#Hjfoa9yS z1ie^Z>l4p}*?ac|--`2PSoW*Pm?S=MN3Pwxeh#)D@2vtFC# zeKA97E+9Pr045622m+$>-oBXA%0o%SK>72hB z?@tTR>jGsXNTLpRt1^u=>jSt`yarWl0nUUVv|cA7LL?cRMx#?g2HdrtVkzyidLg#v zA1!X24FyWg#`Df@Q2C0GeDj(FsDu-tbp+t$6|P3K+rPm|O>aJ!3|uKNLdYGs^FSw2 z{kzH-z^dDqp6F-i_OCt0aH1@ogO`CjvU`NRxgm`r1A zRJ{xbfp+)2g=sRxLr1PXoSz0YD^xW~mh-s@VOUHa-+sHTBGSigdA<=Nc1R>{n zzz>{AhO>B_wkq*>`s6Uo-G6MO-UKHfT-CHuJWs+MUMGGy$MONZa$u*z-#fs#l4r1( zv^6nj1;|GOA#xrtqO8HK%t-WlU?DpE0ny)Bh-`Y`jjN1oWy^WO1I{@hd14Yi%s&9Q z5#C6#xaHN!&1LSe$&DR(GPZ>Wy*MOPLf-^IV%MKj#weu)ft>R=iqj>JbhvN-mNU1$+^u)r|LDa}f@te8R<0`05RJm;-vKP~MnUs7G#22K;^?k$EInRH@lEyPd6G>ZN#=L+%cnPnj1`PpG#a}pL41m?c?DO=+JP7#-O(avCL|o5eD30UT zSz;1&{{Sc9G-;Gv(Nda$zeLSz5MUiQ9v^HGQQ}v8IBd~LZtuL93aTs?04PZU@`&}X zt|15-Q=C8-l3>wYo9!|=fMIMh`Qt1o)JdBkgU<2C9#o$JuCsdEX{|V5 zd*$(X&B~s`DU$XM@6pM<82)dKoX|dp7UX4QngRIq%e_=vgxmRjaYhleqRw8n=bnZ| zHN%qUoVOqh-+I@?NY93F8JfNpv_DG_l~#L zPYBk7!4RQccaEwAV)+&43sWy~?tK05goH>F07L%(hX!GNeg6QfLw5cgzohJrUr+g| zaLN76jme#7FYi7wSr%_Z&rogaj4Pxy7Eof|EANi8DtLV_(-!CFGA#UHw?%is!GK|f z8yaI^*K?-~YLtlz(In{evql_BbV}`KEp2z}tQrFABD=3T`lnlQYTVdZejvWzgU{#k zamj%IN$F$tQ(EH^aOW`q6cE!k=ieMSy*8(ZtgWnY0HGRl@;xA-4;W%L4IBD#d7(Q# z{&};sFVkp4c$Y9d*V3_95(WrQGafKJr z&6n4KZa^AXvi#zMf&e`}*v)}Md3q?3E-A_h%g^bYG1n2j@4m1;O&-zKJ=#p> z^8Q%aP7gup>x+7~Zy4x6qnCfC5Tb&oSlgC`t;BMOMXf%&=LT~(v(EEn$Oyi3Z3%}r z_Wg47+-nQG1z8w%qrZ#@l#A7WOgO?qwoiR#*%CbUj}U@hA6#oF6y$ru2DjYF8tA?+ z?~L8u%FEx*Kbg>N*RL6&Drc#xp}-G?3gAmu0YzJd}i>VcZxKJ ztVJOnSer!eD#0*Ab(KAym?DPP4;daX*V%nAB6#c0cr=n?nC(v*Yx!f}QChwulD6~= z)BJGjFkY+eKU{uu6cS8+0k#4ACO*ux}_QzLu zBYQnCCN{;(b_#cjIiL+i#A5m>oBOx$OMyT2tynhITRT_2A8{4)l%TO11vMg-ZAi)l zST{#=2t?}!H@X;mU2YCBN06WVXiJgS7F-#DlsweaO3^{l)GXpRrf{{S);8G-@u*^cf7 z^(*9!X5BWX_$n~5yH!`MYZ`SzJ`Hov?#0)T&=!Q(ISHT|CeTh?eGGOY5ngsL zJ`5{hp#dR;yy+W@pj!-~!+%oa)=F`;3G=_EQgOQakFG8qQ*;pY@9UhuNb1SoI&dMb zHjWVG#_-P32LwiVvk7{H>L*`(Hr*uhdu~erOThBwgrHZy8L)JBnl*#VI^q2Aca5P1 zj>P5iV?S0fTMmoC&KXlFLsa>24D|t>UufgFno(~r53V&E)7h71%1%rTtRqc$;PhP7Ni8J@uED`7!9Z)OJTGH>_EMf6Le0n3MZKbANW^47Go}E?F5w)YQ%4 z>>#-eySB_4&3Z^08Pv_nqtt&)Qq77+wf4rz5|@Rro_@J)Q4k5DwDSFPLeinRFNfdb zHK`ElSRU2IJY258179sp@&Ezu{j>hV_QzWwRaduVNuj*v9Z$%w!&A7J3^ zi}-H<0;)v6wiX&ATHXCIros>(?SzYlZ?E{s;Gjy3nKzYwE(>Emk&p21w2|b)(xFr-@^~X>^hVQNhT(i``+2ne0X~^lYxj2Tj zke_>+57lX3_~BV+M{fP_Z*9HK{g@)FzE^m&#-|qJ7)cg)#K;H;dKi47s%V!tWKkbh zAyX%xulJg;is)W(zgb+kYYbOko@F5oZ0iy^6NX?g$m8Mm&0z@#72oBJZzEgh4U3h- zZ2hreQ)yff0I*`0^ItpRWJjb+D9}s!FF+wr^7ZAtVr_BkZSJ^Hv?h2oD05AIm3@b z_VoR501h&&f8GicQx|JdxQnO*Oyl!$^;EQS{{XCTAv6ye6y-4r6OHqShR*YkOoVXO z1mN?Qc^n=wP)vJLVmGYZ#+QOyhlkPqwV07A;GVJc@81|fHs-1*I(+3XH=4{IDT8mU zmc@Kv$l2Sh3IV64Gs0Y%rFg+;4!tvwM+;JWdgh#;OnojMh-HgFbiA|Qm0li=%Dg(P z!ulU(;MZDragPD&%mdyV@gHXmq|QTu-c6DEVgw#uGU!X{%rptNin&@%dARI>vzx4~ zk>~2q0zS?xLT$utCRxUhsAh8)dOQG4D0N~1 zg)>JRGS!1`t>zao+R4gV~O`h+jLV{I^ z)EBR=0pJQ2PJEqJR2%;n?Ss3!yHliCa4)oIp;)1~6c13`-Mx6Q(jqNRfgpuo!AgKq z+zHy??!TM=y7&3cnul3y=K0L|p1sd!2j4&G793Agau{xl6JJo#q>G)-VX zvYL*0t9oFgBg4#7&!%x&ju8|Z9_RM$EH?v3FYNq9ExY1tmU?#sRmVYI(#iT{~O}}elE$zr0eyZ;4+Iwj_GwezE5PLcO1Pw^{ z-Qe7tE)9o!C{{!^VGv`Z$ z*IFX~2epA)%@Ovauq6%WD?3m1rgo9YNScRnL%8mMmJ)aJrJV*qr4N&@zH1<{`nx8R zLcW$(!ZXwT1}gm_51jiG7=1^G?u>#368Y!3TX`PWn%}O6yqh|HzNUD;RcDxX)=kLp zer$kDfb@3bCgYh6Kq6JveQ0YU?-T?EQzGn6CuwZDcOgL1J0| z0mi%kh*V$9JG$5P2tq7rN>jf45&g34d_9=O%|#gK#RHsDS{;#>me4UwMZ%R`5Rr!_ zgUF&D(V7YMmF3R@vW$T;N3~v50o#q3JN1qJ1K7m1;NCJ9 zTf;qmMCz#fQj{F?w4-4+wh(N~{M-4oC?niZ`9YBVA91h6_p3Rt!XJLu14$VM=4Y|j zv3-g1yXIWQK^?UcY~M;PMTjslo?GK`!^`WXVBU@t04atxiot;x+zrKge?L9N%I1Se zSFg_Kx5J7(FQ)}<&mL@ZUB*iCNw4{S3>${nWn`!!@3ooNnkZ@p#{<>Bc}S(8r|i{c zmB%R_GjVY8o1==O_u+Ar$`SgcKqgEa%z(gQW&t?Cms=33OsK54iZiW@T9xA{n zToVU3g88&fU`d;G?lJAy03fT~&^>|ReWTQZ<+hZHz>Jk&^McP8pB2I+kj3TnD-flD z#{lTuY;2EcAWxL7Wc`JGF*pC3F;Rkfh>as4j#`)i&il8Dn10^vlfpv12@2JmmAj&Mp&XMfSaJkWz9Pi5<7>*;h&E{tf6>WWyGlJ;1u0AQu zwI4Z4OI*>FIJ}B}Mn0a!fSBZ)bbU5NeCD6TVhB-o*Z%;XiE2qs1DOYJJZFUG5A%H} zDqX+=aJ_YY|C^mzeG=ev->3F#ct`yzT~&URrT1^I02%1S-y;v+A!oy(oKma!6jB@l ztUx*uR|dI)?-ACjDItef^pwAFJ`ZH(Y^ne#rTa9xl-ckz+t_v-`R@9LFN;^_9>3^xDKztV{g=NQqB9W4rPM+ z>0L-SA7F4xY@JE^gL5J>u~eWIB{D1(W6tgJ#f~r*`A55pl#guu(vB-T=UjNd#{80D z1nt3Y6i4-XD6(%{$66+ON3V?yUD`F=&DAAZzeK_-;W|j=!6)wXWD-3Cc$k(dX~I-z z!-%?i<#OoVtK#@q%^>QbAXx4hp~;Cz#IAG8j7;QDovL&(-G5ZHx{6e{6d#N zGS95Os-v{6Moug)WU|`FQ|5&EdDh5(=#pnL0~kvFtn&Av=U+cW=_*PQvYFx$C&uXd zzYiFQSF4(N+QQlqF!V26UX!KHo3XN>#e3C%wVq=29;6y?u+M4R*rjtrn<*N>LP4a$ zKU(p3aENodg6cqE5A6GF9B+U8)L4=7ws9%g{2JDy?h-72&Q5xyaqcSnrp|EiUb@1s z8kjxLAVb#s>NGv4ZF}ZSbaXmCxz4spFm0%}vdRMCvoNy`)8}v^_HjVRPV^qPW}F(2 zmH15k?tk=q`kGHKJlCFs1S*^a`we~}gmo~pwl${m6r@C@_>s|Q{ z`cotK5G~kB+CHHxAYEF{{^E+h?DT%4I3C?;#SBeYeRFrNs4bAtmZ!duPj~2v#PQQWG^U8A)A<7J< z(Qy(G)jm7lQ%}71wlK4&TqKbjNKq2qWa}}5%Myg-^!BuLYe;sRATSN=0!|55=ZJWy zTFaP`#FAj^@29`ca;_90L%#2DG(C=JU>%)Fc|=~L2kAAMiD6i!Z(&#&f3_ZSLot{= zAw0ShK|2uhxHhe|n~Rjza<6^G+S_qihpZOwth*F@os|zV6AWbAs4gTTm26JjD=6+o z%O+v;HTk!J13rIbJf0I;$*ma`CLWv{my@ph^EQ6*T}VLxdm|`OQ1I4Vflto35tc8v zRL?bB7}yN{D_(6X>&L3Cu5F;S>^<4LT2p(cQRgv zvPIZkRlaT7#)N$3<3T@*oF|MpyB_@Fz7G+I*qFypyjL5@Wf7LH(LNnie=?!Mzk2PJ zm>t_f!zwHxB+4dp`QT7=jT!^KKu6JNaMSQ|FcoQ2SS#8SGdD0fhUvl|bru88;NopR zwQIhSvTy^g`C$UhREWg;-40H+M7A#z54IH}y*_f{!e31XM38#{i}aa$aHR;^9||H< zAn2kz$N}$16cv(GcErHG9c-S(DkrY^e2PHMu2s>3mM*etisk)-B#26Cp^Tws*Q$=YD+SuPAv55{yd|?SMhc*C~~EmwnVGB-)hk+%AXg_F^PJfIxYlAjuO((pIAfq(nmY z9(XI5Wm%RHhqt$d!mb}|?F1l&4t8n>PV`qF0q5SLooSn7`KD@1!HLk+B46^61ulQ4 zOcUS8ASoNld3$a_N-gCZ9jnd-E@P_?7kJp@%Jf}KGoASP2pDq`6#4sXzEx~BS^pYu zK<>dH8UWExw$s2?`TWP?&68_?RFYQ}&Vb!3G$k1(uVvE2>d}wmJf<8Y9(mL{fW&p$ z%SQ_Gcfwh_qh-?HpNt6-DgA^u`><-DEzjF#A*b9PZ|27}su*bi$DX>}hJG0%RfD(v z@75xM1gC3rUL0@1rteAS2t*=%LsJN}l~enABdWwC1)1|9{nL|2$s)hn&MzWz$N%x1 zL}3&bc6{9Xi9tuju&FHXoA`o-_ow~kATmf&T%qnsR0sFKgc~?%vAxczKcB$QsffE2XRuEmGC?D=I6c5 zu}E!WtZ(&LcO1b2hdt=#t6SGzE8 zfD(_tkE~!Fam6RFKN3cR(Y2*`BDi#`N%Z)fPZ^W?pl!ULQJVG7p;{j8YLxEF9pl9IN!!dcA{1`&g|}68NwgQ!0qUxd8)_ypZ{t~FEU1Gk zOgQlQXKR}F-lS=(Yiy3={6QhiB*%sQW8i~>e7Z1n;9Q6cO8FqsJ2mj>+N?{dbe1a= zY@-hRw;Uv_poq3OWn8Abh^R^NZRyJFX{m|un*A!!i%%hcPhmnVOCE{; zc){_99-Egd+b&H%3wnlcC1slNrlq1n2CcSfxbY&YyE;>W=AZox8p^O~5s$XWsC~FV zS}UvD+5>V_%TNbfHUmO1S|Vwg{GaRfFisxqPZdyG;Q#-pcc12~pYsP4Wcae^&~x=o zUg-d61r}y*p`?|%;RngyS#djoGFpEMcljl&XEZy#K8O;Pft@%3BqsT?$e=WF0&JVP zb_lL{NA$mTP4Qp!o)x!I-K)w)Xis9wvDxK!y)_51E!>B);d5-nkQpf-QpHJHS8ga# zfABDaLfO?|+AmE6S(Hf{7{Em^I1lymn(va_uoO-5w1jxX{92BA;VC47b{sIoW7q)15`Qn} z7?bT7bS;n;rQQpaK;nvhtU9ItEO}*c+LMPSRivX$xwik(DFpJpGqdN(N!IJfqbGpl zd#gfNfl}*X_?UsQa4S%VEYN8P7a7M zz00|90ECsI47r$8;Kr^tft$99l19J&2QY65sj8xFiwEgR+=`V55i6Jq(O8`LUkq^bu@9YuEwaZF%OY?3M5dxcu(^SG-g{QM=TSe5 zj5Tk)c$dCN1q2NoM1kZOMjlpVe8uGNwx7I$X1+(xp2fZ6V$sg7S?=E0#L+K=*~ZR9 zL_p1FYJcf+xyU{^86=u^&W}?ZZ%^<0=G2q&DfssIjCD~3VTqOnugC>gW zwIZHOZ(hvAyo()gW7}qNfYOMlh;*}SXBeIoU0B|t4p<2Kh@Y4$Ewb4eyIMO90&ZI;tTOg83w9o%#`YSoub#2$!e@#La%R~ zt;9;TnW9KNl84Qxn!eKo11GmxDiuw6G5WbLOwraR>0Y>o_bKxwebpTUULP z#EmFHk4ed?Z_QhIUM?gIth;U)ao%_Qys$Z<&YTUg{Zcn78`{YGwM7lIn6Y-)bM{U*5d=TT+i$_KX z&M<39M-@1wpn3+3@isqm40|yP+5uPwEu&1;qN6@h{!u;leK>{`9;+-C-UHTovmJ)fH5~#)|MggqDTlF5jgi%ugKYbTw9Kq9Bq@ ziv}aD=AmI(a6#$yHf0lHnOF$8ENfieGFr_af`p$XU&jcSvMkfWHlm`oHeGA>Qsgv0_jDze=^dfD(vqp(R1Ym*I9y z;(7_VTKA_kZR^|qhDN`!GSfq-+H@;Tsh$Nz2}alpFZ#+2jyOsdA!H3?v`gvw0 zDzICq*L`2U-Oj><+2|C~Z;N1y`t@?N2V23v{IqTN&Vye{G_^Y%USn%d{8Hy)46lBm zT|txIUh`~v2S{n&4pK3y%ys6gi8-c}=K55ca&Nm1!E!jiKX+K0HiS#lmz5c`-VQzz ze5Bl7$3C_G<&5)heMS&F>dh^z_RXwt9nS!66WaG#>Cx&2>!&kq?vd#B|&6DMQV(1TV^naD7E2m6hXq4|69c^j7T7a0b^g=$869!313aSpK^pw$m{7L>Xk z{wgh__8~B=K+S4A!aW=;-Q8LaMc^_^Ypn;NLOQl(Pa{2hl(9ToEzc#;F|Wc3%4}Ra zbl{V4^jLl@2IEjrH#3x;q;`FtlMHd(Db9|KKoJe*E7|BfTXkAj~?rX-UFvv zpHIlc{VUn8E52cU{nUs3iOcrABo9FhTAA?0MJ}O)cf{v!-IES|OCk>a)JmL;tDEl~ z-lGq`ol*LPO&N#f2c($7d%KwCRfgpyP0BH{nMI2~x>3H}Q#5>BhN~XHYU=u)Xo_6& z-WJU+K&og`ljHAh?t@1|{5(IOFqQ7JSc1Be*-ii9oLj>>9`@{1;YBKi_jamR&HPaj zfMeKd=6TD?pw5pT`j;qL9hrj9-$>EhhX46CP7-}S#Ot(}Uxq2j=X&fFD{fc2oGX~L zI4oxIKi&@h)nge?X3d*$TIZ)`YPm<4X8zoQ znY)^z{iTS7b>H#IE6S-XIaBtOv& zCdV2#9!`^V z>?L{%H*K^+gKfj|DH2efd z@9>`Y17At0ko*Fl5v$wj6R1K+C#M;HvWy?VG~RZLxEibVA^(e{6D2)((6iut02R+Z zws=9-ORq9z%D^sX^qJq~o8em#g2C?dDb>ur3>&i>b7pT|Ca4!XfR|_V9^wf|{bbjg z7#LnHArB&(5XlW8%(wwHeh@r~FXS~pEkQ8_4~0BahJGzJ~9U`pT&q;`!rOFeXqVqYc^KqFva{! z+WjlcLtIcFM1i~>`1?#@w{&lFW*X1@Bn_H@9oj`41-wj3Wc$~8Z)2K8DB6ij0bV-5 zE<{*tEq!K3p+6zv3$65unu959>bQ(n^)3PX&LY?N4Nfd2WU(2qKKAx-8*@)UY|B~{ zHBdCnJi^kY|COi>x4w?@uJBGVNeQ2DgYc*tH|1U1hA@34lKKUi8RAh>;;~sQIo#FQ zfEr5&KKY`~B9CsjH>(VDX-ehzJ`GEfmNGIc2ul0N*V6Bg0lEwxr3_;~-)Tgc?KUb) z;6?nY$}&FtVrgVU6xc5akNy-7`+zsCqfv#7#%McHUfgeh@kD%PkMv~f1*&&=9GR2E z)4h73$#B9_9_3i^q3&?-K7ZIUP~NMWT@uG)<3#}<3N>fzAwEfw)T>-btN+nJrYjnh zmL>3;{Ww_R_G3{1Dd9hXb<<$grGXik5L(@ucSl71p5ldq#4v#UEz~|{uOOn@h~8$z z)AM?gRZoasw1e+{gSESgZyYtqhVrt zUUNlLWixNKgo&vfuII{E zGt2|&`A$qT_$1SWT;Kx5B>vtU`*<*nI#3Wo%4QGdrnPuch_bKZmFG1;9bdo~oU?*2 zQeNI6NonJAc}0GF!;rYRnHW{~^mMBcexTw!4sC8oimHHre3j;1r}+RmvM*&DW>9H> zldH3|x${b1j-+3hnk!%1AE;F7GvWYkj|GAU0}0Bx15OC%@W*WDdv>)7r*ddmFo{8s zkE?;OkHhw11^767nBOzI53CEJKJB>#sSOG~IegU@+56qVg8G>mQq@magPkLmavQxR z{9<14U7ZkH=K+>_%&#IDpqA-XyK^RpkC%%enVk$wi-=^oZab6Vz-|({x=(48ybG1OAXN(lMV$M|GQR#0L;gNgLBhpG9*KFT0WWfw$dx*mw z$irA;onXNzsSa+TWRD)l>(sOJUeeg3kI@iCP=bYUx>a%mK=l}l5R6x8F?@!M^IfiEEm+1%3Ohn6$3-M5Z#qQHi&S1SFMb|3qb9iX`2M%F zu&$ZWSWT_E!?uOj`w}`h`_SG-(NI}X-5ZiLt4bdC?V;1{d=`Sw&8EDYyVhDPydyC} z@Fr`ljcjCGWNch_Fv5y@vmQsWF9DzM>!0k4L1F1&sT?@QDM&7Vsp1l5k7rMSoTo*P z!i8sEJr;<+9&ed^aM-wE$@0h@9xM>P|M+8|o9T`&mRVMfS(13& zPfCxGJE86*u^TYN~ zI2w|y`|f22j(Xjb7xf?0+#|ZpSYgdBAIjVVZb0=5gGp&9CZKd(e6pyf{c!|M!L*Qd z!?$k4Q|S0K3~!2u`tg^2Enm*7(V!bmgtCPSKiNUqh6=$bh@Lm>fvi2+u`_wF^dLwabdRusyV}~QGQpSfk!Q9MRW|@X7$Y74u{aH ze7znlthL5NT#^=CXUw8KbgA+^MS-SB7fT_jxa3|6`5^t!M#BmOxJ&$||Dd~pYskdR zQmm+Udrh`IhZ2m)JPKQ|TWp8%%1$wKyY|R!x0#WDxJWiFrw8lI!@1eZEgO}BvwYGe z7u-Y7(1w<}86EtnF1qy_)mk%-`uqT{9wN9(Qsnhp{}A3})Ei6Q5ab9VVoi<<9TZ)yBq3TD=%FP{FL`i|LMqtD}yp z=J|;$4;^eI7JFP!iGN;&C9T8MOFI=(Om;_A;i=YL!FOQIFNR;Xbi#=|an!3%K(NAG zTRq*gljGdN+x{qnQsSRa-VWUnd%~2jJAhAKMCAuIdp%E0-&#`Pp1TgL61dMkMTDKQ zea2l)o{xh|hIa9j^>S)n-JwU`RSH>BYZ{g?!V?<`0=9`STLxG<`Jr(=uN?1ZSFLyB zB}6mkKib{11`D5Lh2W<64Bk7$w8=LY#Qo@P<9F)Fq)~kZND^9K#`i?u(=5Wk_$z+& zU{ix7Ar;E4LoS-pv={f`7%}-`(N8aBO+7;GELMET4;2L&MEP?4bp)nh*fJX@@F|zX z#{6xm+e`G}H@*SF(^O`2nwSrtck-XorhG4<>ctNDn-o!xxBF$K}JN zB)*$ErK`hZ*emNP&WHsL&SrYRjT6Ck8r}NjMSc~j7mFGELi!hH>AOlF!7|hjEXlzA zKkle}r=?GNa$&dE6Mp7dT^`|^saBrP`Hj&Fu@AQ9`zFsK*YBa{Ohn7qS15uEr3=nM z>|3n9PU4Wx@s0RIv%83!>j^xC@HQrz^Z0|bk85}+QLi9+Bi(e}`tA3bgKp-#?w?Er zMrh}eL^mlPjc;t#v<}A5ZW%LKiWTcQ9fozV zTT?9m>0th;w3BG4#-NZ-MfDEnZ&-jDFArI7u0_*=+lLP&y%q`d?i@YmtZhd||2FC7 z2x!r-pfbgqxCGPbh}Z?<&rd$@GdL*q=;YEcS%aADW=s0=3c4{MH_x}flaAZlsO>dpi5`oPFQ;ulV}ep?}%WOe*mt z7L8zE@0mDGvv>J0P2bZhu4j9&be%5den;49tzwm)rxMf4y`o3A( zp?w@ncrOo*-Nox)3Q18jE^u>Q^6|Mbf`EIGhhR{iF zY3ON{n{@$9HY@}B`JWWPr*jLRnfR^`*Wbcczd7{|HidyeD|?HWk(S2L0^to7a1)N9 z&5rG>*If_VV?SGPns!0=K)4rck6T-WOqHi@V^kk_^v|*e-SgVpa5g&jB>(cbQy}t zXj(8Mcu1i*aW^81xCi5NOBl-nnL%e!_k#IP$W+_PZ3u75=~ldaQJgRZ&k{=r+x~;Y zQINudQ+^PX;rPPFjxIrkli%CAHp&jTsAypu^SXt1yHGxW`z60iY~tS}j{BEweWX>B z_rv5l9xyqz)0aVsM5S_e-)*~G2mAD1Qi?tlSS->@jci%`;X}S%0*6TL>itI2=c_dXtPSn9im*6Q!!4ngSl%SGFu=yG?*Uvf01v*rA26me zWnR(_)Oq%Pb@CdHsSmeHQBM%mz^IrBD(GR`zle>EkMfHA(Ug>s*{4RylfI7DQ$`Wn zK}cHHUxb0vyG*THk_?kBf< z-4+5dP@Jh<36EENeR1HB^*+a75zjljEG_+0tnKwzMb!sNTjhab2J4cA+T>H5T3k7< zu*X$({68^#$Cy7We~0||8%F}gftglbC?e0kY7)~GafW)mXK_aL z>6C@=flIe3%p}!Yu?ZS*jUmsmZ->PX8ZiAK#;3`-5^>wPx;i%Sjtj` zXy_2-x$KBkEJtxAW@`Dr4S&?+o7nwlZS)Pq;5CUS%}EJmGA!7$g!DT*D{}RaO|yTs ztKPkvuU98Mq9HvTWWd{I;8;!0^FH?LemEuSYMNU9dfLIblr(*{G~6@$U6VmDFKew? zq<+-%(lKuIQ|C(Ug7NuEN|><Ly6@uk$2o% zIJFXYDLPY_jlOLd?&9tQ;vdyp)yEfgr?9@8oe0#LM>VtEJ_bM`q+R+ZeogE&ihlW>&51G8aVKdy+KSihU+2;%lq{SjO{Pi9KMV@aQKBRO-eZvj{-zh ztLI$eC3ds*P|*;|qxOSHdzaPz!pm~H$D8&fhyq(5i%yr0`sai|uR*?^x7|JpJpKu| z+BF1y!?r0q+=zXEprIG9_m6eNG$`jwH{SZQ9pvzSpg89wz@)yTU!>DhLFAvG#~Dmt zFzDj*b+-B7TD&LF7azf^JW2ud1PXCf1)#r>+sjEukvHa`)Zh1bXCo7fPXM~t2pYA} z0{MS)=PmhcAU~uS*d5tT`T^GTkcGD~kic!Qc9y8ap5Dd_JoZK4)Mc&ax$5DVg^Qp+ zwik)0yblY6!>I-2971Em0}qnczI2VIcDOqK$UsF)YqVF2s;Y6ZAxP-cPamu#w;g z-aGI3lQ`h@o>&Jg=>c7Cx#?rzl#dQtOBVeB~Z69K>pAU$RG@*i9yvS!x? z4XPt&QL7)xNk-kFrxtWuS|X2$$$WD?-1kPD;3O~P%>~U2KmqD-Am25pl6jU>(t;5^ zM!IHb)|T|ezvwI{=6Rnb5F}j(46)VEjQ%;nf`y_8m-T933su!MW>;DH}>3r5TMH`WGYB{zm;^QBh3E3$h&nSD*g@Doh!=Lze zdBG6tK*4s(s8jNquj30EM#D=gjIm?iQ0aV0d$d=Y7#O|2lY6H7%3~1a{%>4}b1#oX zrI6p?jm>VKO%z1#AaYyWCw7GT*Kby`;b+=J7SPj6BMR2$$Zmk>Rl|JV#jM18#q*)TIM-rWZXb#zPs_!@wE9jTTWw0eT~*1n2Y15(!Ua6J6E zwu=WuU6T%h*M=w2e93cun*R?A1;T0W1TOirXfEHfy+c%apqP^X5%(P{+ZVpYphMfA zs?M~#alXxIm@A^}cJKYg{k%i-$JysGV^nH@QT?RbEN_(kmx$fpA{{1ob2>Hvos-6Au1o}8K|iTj zuIMRr)N=KMC-t;X6|vK(itXw+Wcoq{bE}c}&%~Gssg~!g37XrS<^i7nlCAdM7$F?r=_<|7t71p@n>v8`0y&X(s2@@uGa|Ji_{Jqv3 zHUOI!$t>C&`SZ81`oS=UlzEpIBM0_IGxd>J2y)KLlym4`EyB#%3__11(&ztG&I}ROkV}6cuM!U-akEUhPT?k)fmUeepfX6(O#` z&<`B=a;$?gn(#jMBAL`5glB*)k3n|jYw0G-_^J-ZUI#rd0hIBz29#79G*#>TWFI`z$#G0$Z3rmf(g3K5AVJDL;}}05ob@>V>re ze_X+0(586yk~4Y?ub_c?n|q20VI8QihU4wLd(w#H&{Dqh)A^`bV~)q~%+ZLmyciVz z+YpWJm3c8#yZxquM1?A0PyQX?xnPQPq;vZ#z440m-{RW;0F@f{rzrnjUYw2Yd2@4P zsRd6%PdEWe0X;)4BR)8kTHt=(m;1|}DXosN^_oEg?O;%aaAVn@ zf9W{UjF9**MWjvC)F5j#wnZp_!0&2x3iuEHDCM`B?PJL#t}p%ZG6oqiItWk>vleGE z>=%r7uF&7mnE+|!RvB^Wzv-Oj;fd~8T)`685ubnp4c(}pbaz=Ovk*};Z;=Os+k<`L z$|irj?i^!4%C6PGAd>i*e{)AgzCs;63Dqw3)o&|D2b}u$r*v#HG;1b>UPkE%Xg8RQ zrx3a|v|)UKgMQ|%k^?l{-155Vaqck7@3~Q(E&PA%pocj_$CDX=vM?`sm9$cQNpCrd zy203p(omj37IhuZ|)@tkV}Wn85TJZPAY&jc4sR)apavKD2s^q}%NkRJML zxSsNQbx36Upu)Za_V`U|ZyJ4l~S zbXUZ3N6Cp&G*Q+XN+tgRE_mmv{fM~+zK!@@#m^AGL~L3rEPiN@_@!te!uifWSAdX6 zyP4jn=eLV)MsAvib;U*I?#GS(KcSp`Cz^I+i{mg!o9YuvCW_Fl1H5XzdHh*s3})P5 z6Cg_Iekl?^3nx;gon?}~>a)R_VQ@PKJIwQtfa^+?(>2l^fh&v%GNV8fw7$I=(rt_G z_dNAV2IY*l{1~OQb(X>2--VjSm&y+ndtU3HByT@(okikrG)OoN*X*qP`81}%^;I;> zY(>K)qjblt7p(DxvS?nydcDRAB7zIhpEY_4%9y&>o|BcvYzdE(Zfl90^BcNAHm$`>9<1ChiM)Ji!ZsAD^B}vJ+o0W@IjG)oQ$FbWXg$C@$(SH}?q&~(;ZUqy zsh-kyXyCt#%l%3_YpCCdYj>=a1sPWC7Cp%;&1W%K+HovZ`__+8Yf*3*>|>IJVO^)m za`z`3Hk>&9(i9~O0H@IKRH;8xspsJ@;|_R**hGOOQINrpa^s>t%0YvK6f#4Z0xEJj zv9H-Pcyz55kzr(~JIxq&5j&fqO9vO96iR5*0L*?FIm7iNBPzAT^JV_8>wsN5b+3&E z@I?&t9|dK(#K!tiXiHbbaojzi+5@ulzJBC%E0wPn6Q~R+rS?6<~UqwsiL>ixa|BQ=?!5Ji4RFDpy!qly&M5x%`RM@kt>k& z&7}#s9nyP=EO{xH_+dNNrI}qU4~*|r+0L5bW&}G062ktF@l&8 zkMEYnDYi*sxJV53cdn?>-}W<$QsQCNyn zt30iufhMf+Yyasrj7)#-C1Tsdc<$C3mfmd5d=oip?O7%6@s$xFFN%|#@kbvwT~RAc zlsJ^tGQziXGTZ{^t~Z1{Lfy!z)Z(>#ZTRXz6cMG!tH6sQEi=+P^IA~F0R~IG+|aXv zPn_Z~9G79ADsGu8XvpYK)ptwKlEyX>wft}8erkkLg{4)$A;_}^5ezi;Z>bL}AaB%3 z>I+Jpz8m0;IDw+gglmg^ZTc}CqE}C+C3&y`8C=&Ijy+${wtgqy#NVE=ziUJ7498&` zEsBO%W0mfH+srrYuC3*nN1g8e-w*R1!ZFl;hAo1Qe$O!t8ay?mRx#8U*&^MaXi8Ys ztogFkCv+*)uaih%I~nj-g;PePibPNf`}FIL%%lpf@`v3tlRhQ2|s@tv=6OF?pd$YNWa# z_+fPbEIEGOX(4ku`;Sg~6N#m7g8sV{@hLi!W_eB_`-9>~Vt%#du9ut5??o~k<845U zg>Qwue|TDoa#-9=XZVU=Z+S$SU6oI`^xiy9Gw9h{jB-VSdA%`#L`_?#H^2 z)-^00Ug$yee7e9&bC5zvBQe(EQsR4Qb+7_kSw<1_&*o<#?T?L+zz#iayeDYBy4tez za73BvGAfUP`(e`@MU;`47gGGp$xSKT49QmuHT}l)xZBK;aY81b1^+FcagbfvuW~XBGzhGw0eq(XXr>_Y3Z&egve?Z-2l}>?Eans~Bp(PI z%5;($;cSR2Aj2CSt`}$63o!rKc~R&amSQW<5w)qur0t>!K9L4I zIFYV-p{zsN zudTBWA1axPG>8rkz#Y-z*|M~UOH&2oZLwo7I!i5|7wrmxFLx}*AMeA21O)N5q*0m0u`hDHuUGK&7h+F7Rt@ZJ z?Fo7mm-4*()zW@bD5}=0tzvCqaKsG)$Q^X|{>kH8<9w91c@B^iQ(<)ugub=&F;6J|+zZvq1M2h)&!F)EBhXPLW8 zVfFGNP(xKhpz8f`=&ABp6~+zh15NG~m{Z3S>}T>1YN&F?zqRTNZ2^!T;Lt*aYpth5 z@1^J`(E7U(N)y*oywm4)`b2?4JE^A#SHm4IOQm|UQSx*R@SiZtd=`qa!C@t>eknm_ zrmd*ht2yoHFwu@L_nUl5dPE}xf=G(;$rj14IR0FRHtk`HFv@-F#?x>VWn~Ksf$$Ee%+u;#VWNLnqF_(QMRp`DG2I7xKpH9fVNn0r#KV>1gFpz zhZZUBP>L1T00DxB;Ql@N{m;E~=bmThlRVguGLxA-dw)LfwbpATd&7$F=r$|x&fKv& z?`=mw`L+wPQl4^D?8awtWij*y>>KTyb49 z_2V4y=y&v)>l?#6R8_QA(R=N?O@i-d30@(Qi5^b|aei{N-79^YYlGND$rIRsu%HG# zjr(&^8iIt}B{%$NqR;Ek3 zI&2Q;sDY26>~u{QPGf6s@obQn{3{)MAs>MQ3mIZ?yDUrKjN> z+Kr1}=JI-9NvI%d;u(KBSn-;7XR((>k;Wy%NN2`0^-lWp#-uFA5Z_l~AdCjPXcis8 zF_iJp7R0t4nu#q!^cIsMS3X(}VbxhUFSS-Y)p+;LPN7BL1_GZcywCmH`v2)G2qn(O z`wx)+zq$WSvaLSK9q@~Z%UhRH(695*G5t&_{US2-s}udT59URHVcOh>wb+#7XDRRq z_T=c*d0meG=;bkuuA{EV_!gT7%T=7wuHml%h^$Pe+iCs**Z3+6od*HWROOLqc z@!~<%KS4SvHmPYR@_k8Ue5e?2lfZN~OpSz6@@D42*OKGV^9|dqBFyfsRr&SfPjT4U zot@^wqR1K)7pl@5;Wvbe`rv}+$je^hDvvg5BR65}pHdk)OM07ZA@5x_8JKbPAj0%# z6iM=$Kv`o8hA z$Noy>M*(lf2?1sH`d?Q(imwIrS*71wOzE?Tz_oWM*3cyl`3!&$8Nk@VPbJ zsxWMq1_gNCzL=(UB8f;h8O042trNY9;8@vQTqYrtKcF#2CKl=G`8tLBa;qBT$%V9J zNh~gg$14dlg?JKQ3{{SIE)cw?Z50@@ZDoeKw(4;2VRbs4^wh;p3>vPX)}KpwzLglW zpOY}P7C4wEV1f}U>eSTs!}r1z)6RP@9h~oN`vl7npXZCebYpR6P-kq=9!bPoHU16B zA)DTM06N|tz7O#wytPfNDbSBkOymC0jtM|IwdxwQ@U~O1(kOHSEkbG!$EQY3Zf&3S z?m~M$ z`iV5HqHNdzWhB80{i^7wF@(z2N5JM=v0~KE11!#_P%Q|8=LdB({ncEo4f~h zyDH7;aFBd?bm_!%I`IVfM*D^_j@dnuw1RsI=pa_TUw8R{swG!ytV`HQ9qC8Ax zY#%`v&Qt4u@2X2(Xk%&4ZY>ws;zw*G-PT3lW_B3Un6t@TVhK<_lqsYpX}V+XY30~= zgH!w)yjad6yr(+LbufnLkByNexk+^`gPcBiGIW1?vc4(!GNt9b-=pM$IMd9MX=VnQ zv`+Vv40V+Hk~F|3DDek*obJOZ#00{6CH{Oe05o4g=Rw*thjBEqAdRxIAjG{je6tdU zJrAdV(yIIbBz^UUUFAUDCgPy}qP3AWlb z&0ZiR4Kr|~aeTH$gQKA47p8MToSMre#ljEtU$NxHsY zwbv{wGDBR9w<~A+_W;s=Xjd^BqzOk4NYZoLeT;sBZ~BHn(iWe;1KIeLS?6F1rbHDe zeLhL=^L*DR!(vjt29YBFTB%vzE>DuybcTi{(17m*GNRl~IJ#!3U zLf8xHg4XkK0<0RFm*m>rwkjS&gYWTRl-VF`rKMMQ>qqV>r)%`D_&_^c;@18Tb>Op4 zQVQ1@wi@t?yKa28!>@P9`a1utM<+1}m+6bavNYXVxRkDvjccA>vv*g`>-~(-X(}RT z&sw;Iw-RWBnXLj8GTVoQ`}0vRj5;4>`m7q7C73522Ri15(^#`Y0D$hu(DU^Fqa6Gn z*t47|${Sy=Ug7%vtkzlDADefhx4f+ZZ8zOqxP(r^*srW?+$nC7eEU6t zF9q)Li03PetCzdVxz5#c&#wCU)V0$*zJ9=}`N@4d5 zguLo8`{x<7Ss%_@?Lb%_e4Eps7jcGZ|4Ss|v&~T6Sb*2Ge81rAPs^A`MRaB5aeCVf>K{+OUpbjtG>ev5DIFAH8%tba*2J(wqi<~k95(IY2Q(e_e;FU549`S* z5A$2j$NuSQMy9R5%#wW&6|Zk*E92$r)?4_8tpF}!uJCv0*ecsb4ywdvw5udB+Xd>< zSxfh43pik&N@B8$7Cb>B2Q%II9!ASDfT2H@s#`=_EM3xr1kI2ZqY6GmWPsHHY4Z(m zA#O=H=Vl9E&3pGi%FV#HJlPQ%KRVkZF?Tbnc@=hbH_7-rc4nap6EoBRqraoF zi|oa`xaJeTsOQ5j&Y}q}om%n(*98UzZlx{ge5K`^6PO#!_FHliUlm=>QQHFVy&|6y zlT%pfb+)`iJ=bh(W4aBGFYrOYrXOD=pzBpR*;aa*qllT6r`OIo7o6X&C zugZuoI!S)*dKB)!98%EsvA zSlTKJJs=D|jzuWjOWJ80R%=euhj7IDe~sKr2Y599d0fblH>z@> zmnr~r7qjR!>Wa$y?nM(c32zdjq-CJI9?4*PuJwS8w!SFyB`A>PJhT(*2}V^!;S&WG z)|d`;O-PU7o_oQu4gDW2MRT~{$hkjwJM*_roz-{~q?S<^-b5RiGPuD4!a7#Bv6Q57 zT4}~Qrn$GSyEVctdBDmnuL|N1bu#R%1MG;OEaXVSE1CbW42;xK9*WQq>x1}IQtaY! zsXk?6<3!fI`po_GYWPH9G@JyJaZLylITF<$rl&N#5Yq0y;>V)=&Ez0{Qu6I5jd&84(-aYT=UWK3%!h(8W-sEV!=f)G6VI zQ@xO!_v&&Ap<12P`hnZ3Ha?jjvNmLb)_vq{U zv|3OHY8;H!m{=NZ44?n?Z@w44eyWAC%=t1 zVFA00nDEeqDZy$Lv-Gxcbl1~fa}Kh-$2*z#b{izqcCCPcmFXA}mpy5tZ8k@j7(iz2 zad*M&6Y;!1nx>pVyyINuU-qe|?*DIuaK-@sqbs ziOFxMQGFME1l%tymaj<@CxQFGfiOrrZ$}#&6?$gF`U~TMXhoNvv*#m89Lj z)#6D##EYRi8CjWliXCTGQKc>L3W3r;v&V>PXu70 z57A$~{UzhNKNadFm4yELRJ7ajl5^N%oWvDeAX-JWf^y<94cm04WoEQx1 zOysPbMhathb}qWOjp|;(JSWNt#^{p)vq*v{xA8iq-F4Eg#AhvX>+{6DxNp!=EL+gG zpBpT_G{)7@a(8HLUP&+Y+Y#*N|uJ_ z)Ps1v;}>bz1-YE?6^J;vX}J)9Ke+M!3>gUJs>-& z#62jk$pfPo6n%RP>h2{S)6QH-(UGAHI2r3MSaC{-ptGNdOuQNyoj3^Hs#0R7^}qbTzbMdL#{5cm;XUOw&B|6knB2LB{^c`{+il9D!qRrH zTRGs&AFM`d_xu3gHNzhmp~e!bye($_GM)>4)6xOpR=b*?=D|6+um=mWkh^PXIX^*A z6~D&EOe~tPUwd`!>{yI$^jqU*Z*Ln^N@ZJp$a4Mo(OQqGRYCMyiLF6rOBZQVuf8t_EYHB0KD8c(d$0OyCXnc?K=P@8fY&6K0Wu_Q~( zG-Js}N0}y$Daq?7ei-oWZ3Vjhjlq|$iHc1z{yEaen7g}o-^U)SgDpOX{-mWB?4rx8 z){HB}MIk8J4a2jYaCo)e&!&}b-L=ZLuO|yWuK)eN?-h##R%cmQpMI5}+{QtNcnVXn zsEZ2j+6xJhZy$YD*8KKjV2HI-cF6WhP(1@%iKS+DkcL>T2}3Z1G(<+Ylx(u3pc+ak zuCv$Ka%{j0k^X?U%j9;^-AZWu>7BR_H2g(D1Jfo8^j4)b?HN zzhE@kKV$?2F)CMKDfyJUz;)o_cmuGinbmwXEPn3wMx<#-lF9r*ru)&>--Mt(!Jj;I zYY@Bi)Ym%xa0ugqUJ-Wuf(9Zg8OLIgiEW9J?Qb7McfMtAXVR>islbaPc4B{Y`u;Fv zj(S*V<5#ZSw7>Qj-=RK;=4d+t4!D${f8>Q z?7`nS#=Mv^3#QE*l8u^c86)jqR_k(?Gxgibzill!(oTWrD$NL!W63;4<{V@)DLH`u0y5YQ9PqY#SitcTp<}Q zC!FCF+VPsiP8Z|yOcd>0^IZYdGABddK8{8@#N$y$eyH!VNi^c(-k6w%sqOPdouTGl zNsenCgdN5Vk#{OkY%M)B>_B!Gku^Ga=YY|aSXRx)M>ZdkX~~tnIdfcsR{^7=6%0r$ znmZD*gvLHp7;gDY4yD^xZ`)hT=Z=hyE!Jg7%dNo_i}BYod#w}F`pC~kMHqykGwz@3 z-i~+wTXrE(n^1S>t|nUevSQT4hS;?ZZyP!+)I%t!aW!1=mi8%&$v7bak%)=bWVW1x z!KWu?!^xNEgkj%?EeV{c(SoOX=N*BM(A}(s*^B-Y12Yzk`GahxnDHJY_y;?n|E0mz z(Hc)0u;jq+d`K-157iMYdcY|0p)mi>E}`zTCA!*~IT|UD{h}fZDm%O9>0SLyoOb** zTl|ji4I&kwDfM}dBBb!A=&+}PZ$XES0jXHY@?3ks@JCV7V5`5Y@w-i94xQKwmL#76`tfOHD%mqT6L%$gjk4PvtF*@NVm-Bar%V7Snx0b2USB^0lifdqR z5yi9M|Jd^LqT=sEohX(&?D_%R7z=#>_gTqU1Gx#-%~E*G`p>*Z&U+yXzB~J?h=&Cy z_xC%GWsmv67P$;Lrp;1>6SVn_5$c?^ifvp+dafADw5I#f12K@p?m>njyQegv zey%%Y%=Y^qwC7*!VsV8wJLU9wRMM?I9PM)Q9pVhYpVWtw38ewKo=0@Jdei*GpL1l; z*;*9gRNr^h0-@+Unu(b*K6qK$G1yotal7!1jI$JIVR^Sng)smsZIaeqWA2=(_OE^K zHWU&RDl7)Ru|==R(7GAjydyA2kzmC33A$%59Co|XQm@o}r3>>?z5tZR`9H*YANYiW zQl^0yY?(Q%BSeeAVnK0lJO9^36H{@z1H~fq_MXn=L~`&{IGbkujh9M(Sf!zte=&QNITu^?SZD;N)8FBzL@3|X7p4g;Joht-%U9v2v@Ztxmj>gm1O z%Lfe|deQzfR`v)RdTR727K@M)VGKFF2m_1^Uca5(ulqiZ6-$Kr*u7O)^=>>P7t_uY zn&a&mQcB}80r^@eAv(6Y)haZh1#^jA0h$>7{XNqBm*TxlG5}W|H;UaKO6h^d@Styy z;;NGIQMpRKVOW7f#6&Mw-tZcGjPr3DSCvRmDGl04FTg@PU$y0x+tAIr-k(xLhRvMC z^GW48niKB$WtSPs0r^sK*L+T};R6EWy0*>lB#_c%g7U!KZ{z->?6}poc`UzTmZsnO z@<`U;4&01fC4B$2?={_?1+12r>G7wXe$h{lgX7?>J6{PF#<(`Qx8JUo(!+K+a{JpgJz$M))~-<8l$)aq)WM)BCxPNv|xe7XPx3u!5m z-l8w9Tlx5?eyiWK8-7t=7Fj za!vaDSdeq%G(<{pd6jKG=GeEMZ^V@|uaqw3!hDlvR0aw}b`1~PKd4bwBbg3=>v`RG zzaKCj=#6N@*927?2b)kb2Fq=_-Dx|C8&y9GZrCS#UWG>R^#~ps^Dax<@PtB~{%1}V zd`w74FeKCdjNU%57>$)1ufuZw{uVRd?&=p(Z70MSTq6CYZke_pdRHv6k3({5{#{7- zFmu+zZu=FgOcq0>?t@AKZWWJ3sIM{@eo^=hw3t~0vM`5&`gt66Z9q(luSlx9eMY=f z4NkoCD6J`w(gm!vPS!k)WZbllRZrx8y+hT&ivEo>M$cl3NT5pSUl z50=RI+fu{#?PUUj!Lz&S`lj!FeC))^fH)W9pa6yVzs0T^4yU`yX^ISS=};0CK-@Pw z^T=1I+Hy7=@Y$x2$!tG6kAup>H$ODYu>C0W`}BOI>-~I;5Q-F3x?Ug%ZJ$Gc>R0W< zw9x)V-}0-w;T?8=B@g@=ZD{dazIFP=GZ0LhGJGWMn@A)a#v4Va2g}9+;<4b#vZ#P| z8FH(!KhGVJg%xg_P}d9pI4(bs+#3 zMazhbUg3|lWO8CKT4sM)iWOkZDaOl%7t|jDoeiZNYQBzPT80P-X+yZXCHaRR8e6Q9 zSh4JO3D3Ps0gSOYn+{SNJ?46d%YGU1*rW9I5NY-bbpNvztUKG}k774}1#nttdu3P+ zZ2R7g$aV)#>)!6nlC{x3afCPofJ=gLC)95e5o^|{Cno-z&-IAIRo`4-N<|9|b_ThQ zH&Z%4HM&#d*1#^u zDExyJC%9|nsVHE<`#~+9ic2eL*lwHp+Wh|GbKR%7#?HTbLUhf8T_zcqa&@IfXiy>d zfx$cy!GeSzezGK!OTYN@X5`z3#;)wDB$n%CZ%`K<{yBF)R7^exXSNkzdo_N?Sz_iC zco)ZGauz2M_rY5AV%%>YgDMm%SZA%l*9jFum%dwfCfwgE%%o0U)~nqOQ3Shk?=}N)76_(TFp|pOZ`QVrf<4c@8u=}8 z+#MLb^%n*S^zr=(R+L0{k`WX4{j!(?1ePaLD{mv+f}QfkxLTiw4jw=leLiNZ*q8VT z@v~0w0f?Q?L|Ad~nMm3^1Ak?&f4DKx0z2Q*B;sWO&wHV9#%rS4;FI$7=hi@xnsps{ zmO|Q;dEQEPDl0h5Tzugo7tg(rj>6m{N)y*&oUfTvSnAQX@_R}rZhz(LO&(nZU@6*U zoQSyca&>Hl$(d>Tw0}J>W@khj0K@zNbAFnZla{fq&Mx{lN*rVp?7);VkKBXlpD8*m& zD3DR`tysMcO_Nu}G$%dON9{4;9$x-gs`k8n)bC$me9#8-o=cD3#T(JlZLnsU21oM7 zO~VNjYDNp+(zUZzKFV;sGUy|+jA;0_`?RmnQU-|QsR&WZPFGL_HGM}9p(6I~?-0x6 z=!2MNW<@p=gbp0Xyu6k>1<|`Rqj`G4K>GdW*hnTX+GwhnXU8Meop(JXjy zV^VG;Q#(|Khq zO#63WwW6MO%89yAs4y8lJ5h?_8Gc+xaT-CVJ{+Il_cQA}J!1g-19eLV5W=c8C;JFnjtrxiDr=;A?~mLs~!HA5uLzN|s7?iVOvIl^TK zK9cfu-OEHuiNIa?<`EjdhscXLA{!SWz+cmcB(P}dmor)j0f|qbwWImq?!Ufm)L6_n4-XU6UhappywU@hoO^Z5aqXB-B5?SzqPEL9kAK<%_5uC;q%U@U;VD#mKGgxh*qL67P#|Ks$rw;)|(t(3+h9KQf3YT9P z8-ENIVg3)GqOTx2i2MB{cVK?*#gRlB+3Z)JDu=aLIS^WLSyHl~@F0(aoVBMra&Ov` zeT7z|VqB5smTf3=M~`vENVVW(rmdkM)0PM-|%55*r(bdJJEaaI0H?fQFh!s8N`{q=)k6Y)s|;!#W) z(;xK7M z$a=TlFHilu?9|t6y}j6BNE}rii17WOE}vAvrXu}n4<1kYtFWkF%sWL78bV$w8&Zjp z#LhUl_o)Xs&tG=7+!@XcmR$A0442+)d+Uu|3NKS-NlIJ}VyWa>WX-U-F%w((_c3(p z`KW$yOY6&?#!iJWJ4BMi^D7_^0T?(WEXyU6D+DA|q)( z^^VT#4i^2}J~LhIM4EGIfQj`PNiKd_&(*+HH%3;r+EBY5w%P#(5+P5gR7A{&6U<-qg7nobrmyWdcS)i4CN6YRT)xgotbuLK78kMG&cV6VxyUGu>F{Y|R6{w&ft2>D~-zo6tHu?^4JyP1S$1n@vDL1Zha% zlZ8XRrZ!ryuAls}Q`(S6F|?U0C66h9tu4BT>r@C*;m>Ee@#`U{Vz8PmM)rcik+P$#U;8%1`utt? zNq^rWAauE2*Y;17&Z;6y5tP2M@tIgZ<VYh~!KD1F+;&P#nbXj5+X>VP?j6eP2KX zax!z2OkHXDBUfWctVJY}Y73_`+Y1JAOcD5PG4Gy63NPSrzxg-_{4pgnI6E5_w2AOb zI?MPy=HXNL)|+Gd7RAZ!UwL3DZV`QgF!j6fwTmoQ2QIlQTGqJkBWMVnYxw;d5&Y`K z)-e>dfKWN=n;D(XR_LH?hCJFOclDfM+y9qSx@& zA5xEw2J3j(UQ1osm49{Jj%2eaudCm`=HZ4&VYf7A8(+66)AJs-rz(WqUf zH7NcI-%9}GO`u1@&cjyLub+s_C~s9wykcN=y=TpRWJy zdwb4kcuus6vLI4g;MsMH+>0IiS)b?YL|!|0{lzX%wzK8MVRnA2Gaq_5pPA5OED3WzQZy+C84zlMk}eCy0B$_x(QU#z3#p`@&w2Yl5@1Ev_;SW4bT z?DXm~ar7!-Ok1M05w>qo4I)Sr`mO%}X70=6B@+`eFv2JI;cvraKaAXNZ6p@G9}V_( zii@va|367xq?9-BW+N>YxyopSSL)35S+eHMYED(TD)vT^B8*MaX??9*>_iIJxZro9Tdu>H&7SUt zIB8(x6V@J3wkvGC*OY;Wli=zB`hy@lzAaNZfKajBAVxz+izycQ*-N$@qr@2dNGCxAz93|icE)r z9(6ZKo7GgAzLXc*STBGE8k&#%d+3WNhP_j?#5w1sdqBxY(BG*rYM6_T^0?GIHjQpf z44sO45SS^`A_eqIOWfZ~L~#u~YFF zZ@sT~anLlLl;;}(-zhWMx1P>jFP-;D7Z1Z`2=fyhDM?(hh zG`DXf@=a6#c+|Q(o!~Ve+-!6PM8|$=p2z2ONrD%4+ED*mGjWiCCPeh@A!?1E0|BA9TegtC|0}4hJb4ST zCH;=&E;T4&pw|BTzHT`p>1-(3SNW#O0+B+`T-girJVpH#vBgoBvAgcfo!&!d9=1qs zH`4rAx*mA|g+%vT9V++_Y@`}@LtormB2vD-I?EKgy>F1nP#=PeoQ*``J}=h-P+&Tl z7bm;B$y7fYu{sm~-5Ppj4!LM!QJI5-VR22i9WH7r<09uYf&M zffQy$d9d~J&~&?<@=o(}I~Mw(&(l$1>fIbiepPq&b&Gi|k#Db3g?s}GT5d?5mlg~0 ztN=8d2=UXjW+)`rc*25);-h|~FnUW;{w+)cM}Ku^F5SvIi)dzZbk~=I*#AB(8~f<* z^bnux-+pKNvpQ8ldx(lPihuGO$vDZUEO!4v| z3x&RK-epwlZbS=y8-eRzMCK+t{%W4NbvQ6w`QwdX0`72(UB$sUiSr(8yAP?fE8yb7 zd|FG@*$F}G17v^{t9I}9#mUT9x7Znd5b)Slt2Un!4BbdGsVml-nefN1kJsK5_;_3nD zS%6!#4GMgreIYqbUXBQstZWF^*vLt~$g7^&MlMiORpAxh-WO-nhTdTR!cHP}(wp3z zzb}6`vTHpCIF3dtfA@BC)4jp?4yrwxkG_mLdO7FYukMv=0|~#u3VcqA@n<6f>`e;F zMP0-^MY0#Y60tIJz-%0B4%tK#dSV6{8mpV+Z0>YE()H= z9}{mkMTLxk4g4x$=iL$Ni3$_*!BFL2o%>^Vj&TCYOoF99#q~1L305sHzlhuDI6Y-o zhv;Y%e4qJnw#Gv9$>em6n`^Y#SI#Z}LLYR1n;`^9A`PFF+qj}v`SUD(dI;t&aky_v zuCzM(PM)xLR#@)uWkySFSE;bSXI8U`B_hk{g)Z7X+j12h6<5TY?mb9IKVy2`=M&7i z>y9Aezb?9(Yq*`jnO{Ijrza~jF?21N!PfpB2Ga?qu`0CSTIa=(=a9+#EuuVrt8XbK zHbN;ceN`-n5+~>%+mi~u-#FCcwUNe87bACNjCD@r+h?OhwjN|JeX;hsAI_gyJHd%Q zMkfeI#u5p*AB^)xnCZCSw5}XHm1FUA`IWGp2JG7j@pM%#*}mv1r&Li6sXWVlvo3jb z>kMkz1+G3_7o~e)`myJOuSh|h5-a5Wt8W?sf1uE|9-j>gvpC$+Mw=$E;wB7sKvezq z+1}n!ScD;|teijaH5m@kM~U2p1ekBsabhrCT?^C{+gEO#n~GA(_^X?KLzL9U}k zBugAavpk>3CiyOI7KN*X^~rAFFp9+O;N>a2{Ce<-BXi^QG%p4Jvzs-eN6ku9q(G)d zNQ;PVdu_q#M4jBnfbQ+Xrl4l>opls-`x#7SLg!y}cQ&#UIKZ_&Kx$NFE<2hQ!P_bP zivTfED*eYDsQuWWc0~2&p&|GKvHzT5;v^z3?sEiV7ewiYZfh`lhe+FPZD#<7kQa_G zUQmCFD7MtMR!YTA(!Sj=G>FroEG`#PbG8O$iY?yNy;*v(-gQP4Rc98keKRWg^T?>Z zOG?G?0zchRQE510E#~R0C5c;RSDsfdAI4Z z1IHmXpW?g!5c-{^`Ml{UzlyL>7-Lj!9Pel-29%JHI8rY4ITh6C9jtm>l5`Mu9ohCo z;*rpa*vXCj8N%5zmyMkbf1lAy)J0GwcGd_ zudJ{an^}68ks_5dXQph{_6;$#9JX|^Te=%cLQ&wNE{-VO0}rH$Q2${mox1F25BsUz zQ==oe&CDU|=DRHHtzRZ>T`nz|8}Dvqerr2;W=Sqlv+4=gF(SQSBhU;)W=jHDAVe9O z@>{|*ZdQXbCo69@>EsyOHV&#L-QySYAYP=Crmw+yS3{v&hEmqBj-7v7?|3;Jwmt{F z#UL{#j(zB!(Ts9Qtd5%jLpc8@x{8>cLo0Cl!u^xyZg+YKyxSw* z)G_%IyEHPeq~ADhTQ7&JI!Ct%mBVPo>q_KSB4pCxtaP5s`sX7=`XoK_MR50aW!dpy zAQ1Xo_#leXpwoYh+iVpr&**cy$&rGx1o^b?&9WuduE-UrbznP5*}BHRlke(?|P zK}3`sw41tT49O;I*`Kq8$%b9@JSE|R?%J}-inzJF$uV0l+4!#9E?F#@3@pQnSq{x+ zG210f;Wn3BA7bKI6uCrBL3cMgTk2FG8@fTdn`lTqJHy4mIEoH@m2D*d1i+TxA%dfh zNO(EmH%-fUlJ5}x+tal-sN05z3&V)XTUOXeTtO>x-aic#9w+#w0JgWJV5!VS(*GvC5#RBAwb{ zVwqIF7D4EC?1mIjdl~{04zN{IYd;W{2V)eN{(>lt^odYsb47@dZ3=f$8jU|2>=sj!AGmNH3jhkNJ)qS5_5&BsF<+hCmn?r;AH z$7^PrDVp1JJG&-89B$fTzlQvx^ocPh{`PmWGWe0FNW9eD-ir2!5clcOa_cA~1b`_P zw3d>{zbz6j8P{Na@|tUG_ji9Cb?ByC(B?NK+SrGYn6Q#Xq31~eses|5qxcZwHF@;R zoUa7m@mX>qEA6<%d{%|*AeWJThjaPUVf31ZHOZcG2tRDgv5GcSl_gHv8pdpk^{4s_ zQ_IXyHihsfoD{b}5a6O=p^hgl)%?5!+0A51vz3K;=R;t$sWfTIvfLhU02ewpR^9(z z;Kry~u!wlwq&6`=lTuhwhi8)p247|p-?;@-oz2F-QGHuSBr*6oKFX2ce$`wub1It~~#ALTlDVscZNIM3J9@Jh*3LZ|WLWK?|(xNzoAw^vKq z&=-$7E&w^fb!8#S1M)DUYD>CY1CnkcW(^%xkbf1gVEwO6=l6f0f6Vg|DH<7c44$o% zXz2M?y;WPvbT%8HN$^H~PLHZ722b*Ed0dYnpOhY43_4i~7K93Wc2eaZec_Bl?4V0Ba+qGMFU%Yie{L&ho>H0Gm8^e7%&OBSk4|D!MA8n zrfVV?q@*5}@<%c&@~w-heQ=v6{O6wPWn+maZhKyhrEs0~we!hw-~;-{YyOL!t~G*6 zYt5;uZ8O^qRQmd%o(PWXYJZHE^hy*Wa)O^r-Q|RB+`s=$NQof}|*{ z|Fk?;{c{$@NEiBIaZO8uMmy&1SKQXJ&Vt6rb#BS>P#sf15T}zVlM?VNjbEpCF0-`= zUc&{bR~yd@8zLB{GC!HYAHpnjwl@SP(2MB2Vi+K_w1BxA=Y@EiIjchKHStVL`NfUV zi7#MVIW6QeA<#J~-oy_dh|YcEsfYc?DGhX70(Z_*kEgWL#KU~YpU$wM5nLIR&CCxc zQ(hV4WR?u=mQpm`+gIIdKR}7Okt3=4d8Qs=>n%CxJ|b21ThX{M?@r$;)VPpTyM{xp zK8Y}qCV=714!GDcC5G+#9{=C)B7H7+I!@wi7w$s3+EvvPAwnHNKF5`c%HDJNx z;_+axPXlJvV@m1MLp`S$(yfR$5vf8wZ@Dgz(@*6|?m~l|luK&yJTLwP>qn9at)T#) zx;z2~=KC2g89$b2<|PIyJ3#Qus@ERGbhY@ROBKd%3(S>gCC!dvfa_k*LKf7%$e8F+ zlze};JD`r|4?>P}88@Ij#X7+z%Cr&xD2^ZwCsE74sDqiM{{l-Ggi8K~ zK(?VHkX)CF$FB>4JGRgUrZM<5f7NHKHtHEvm5gM~kX`3bITmlCKxm1U^~&N=RAdR1 zg|a`K@tQ3Tw%JgKbfC%i&3=sWdLV({(s!MUh3+~oFlsTG0l4TT@0_g1O1y@cux(9S zEMFHS(}^ZiaPzq$E!Hj)pK9!#kZz%cPNH&ktF;^Svu-{4%N%;9ZZ6Mg!J26`_auLYNa21V{cvg+ zr`c0;_eY|ETmc%O1%S(pl)v^O^vdqFeR?}_5w|kksjvW0ZGkPvi+6m7I#AG&+I4VN zFUE;%Y`tf4y1HE*wi-t!%8pc+@P&gZS$oljj7e`T(Xp3`RR^S+-8(R0 z%M$xvgPnc))HJ_14_WCyt@}36Az`C7w+}!)Edf6fDy6BhcP?YNPSK6*_+RGuGzR8u zJh>Ef8b2)Ez5D8~aTc<`RFBgq-9IT(*L9|V+Vj7MAy+-dd~cut5;E7%)5J11^AfaD z9Itjz45fz}0#sMT==oT%k7nRPjouZyrA|D;)7_H}*2mNx%#g3wT-Y+U< zP^zVSc`CZYSS;k6LtPMsf{G?m!jPS03q>8jE!48W0ljb*u#4m2M9WzX$p8?h6Q}Zy z47;fjIwB*=(=GV;AHdh~=XUEiY8_vk5rd?9I0o1Re7vi&0J0MN@)oehg(eYUv-q5l zL~dkqFl5)>Wp41{3z!3NMt-|<$syD2hsJ$+vE)*);-iP~3*>gH{C(5#OWR8V=IDEU zQ#aJV-IFSpO2NmLQv-;RD*-05ItCd$>joI%~1di*4 zh-4D#&aNg8>CuYS=g3vivynQn`UPJ^`IOD`e?`XbrCdO0tfdiH1mF?p-vJ~40o0nr zvQ0)ZQQWv!`ys6jJz*^W^AdWuLv;3>oLK&cK11Z8W+EAGeba!| z->h_{!``37d2^D>^XhYmdL=v&-wJ!8q{N!|Z3B4lzG^xrvdeyq)L2R1q?}pfnFydB zB>EVxZ@GdM?hg$g9i8S0d-)AP_xgp3rKx9B|6EDaNb>7UKmWlGE~^eRo2Y5x6q9kl zXeTIt9aRy5YlC}8`@6)upOy%;<}?x-bu+bS9a&nX#HxO znoiX_+^3dQSPDU~I(ZwaVtHk&zmLy&3~@ezPK3H&IViN6VV0>)Ib|*{eP^37R)2v& z7l>WH`R;-2Ruo`rJ?4}nP}ALb1z(o^N;aP!E29855BBL>GS6VxLMnah5|}QRbS+dz z&eO|8XdST1eNjCfEX#fRj}@cUba%4dG}4yLsb_q;-Dx+#FT+ONR7hJ&&A6Ru>4TI3 zxd~Idf%Z<$hg!`)LUfYw#ME_f9!O+>%JXzVMnr1$_h%LZd4j5Y=OfSvsXu<tFkU2|gT56G^TCCzHJR<~5)O{nfuZJDJWt^GM7<5NOiQ&k-#zpZg$RnBH%W z&0IMgenyA~8+k8<3B)EwHja$7l&kgatr^z`o%D$9Qtb@ex+z?z3kp}@bgSSzwz9gw z$>9>@6(mE}6xNpF%i-`Ki=(iA6#o6y(ytnkoXTw>D_$hT?@`1UO+o?6SUGh1jw6Gi zTm7Ubs(+=q(1hLO{%6MCPiebtjVSDizvrPVwPhS zPU@t;&QaW9+tV?l|1Yl2DyYpiTHC?hEw~jeuEDjqOQ95pBE^EcdkJ1VSg}$lUZl8N z2~b+3H~|6;T3o+Bd!PI>J7+n}JDF$R^{nf@?s?V?gX-1v46x;@Ga{QQM}*F?uWQjr zRlfZ>pSu^wd}{E}oTqCyxQAI{CE|h+^tMK|3+?sfp|fMpaI;r&F#JPeX!;0$V;b^$PXUrH!KoeP)6 z^9ql9n%WmCz$H6+&&yW@65EitAYval$4|#xtZ*O)Lo1hY^zdoFamI_D=K}M&artGZ zkL^3G&`kmo&QFq?dBXyV}^==kvg-Zs8XTNJtTJ3;AeK7hubdlH}`vkzj4A zrb1eT!_$>8|Er7GuR=^SI)=M@BbH=uMZ@c90D*S}M)B<%#2CCHWc;Cx?UJ#1wq_2$nJ3g_VDbu`GVyZKmGccKE+iMt$m6eU?OW(C}ue;K6R5Mh8OC?)`fm)mLxP z|B>LRJxr8W(lRk1>URg}&C8htAPoOHL*tysA$B!-PdOww=Eni(1bl8Fkzd!Hv*h{e zZw>3Gx-Ty_$g7o-X^Q(ScRaT#KBdmwY{&-l8o{KzTeGl8ss%F=yh0us_d*LPnPV|a zuJkLk8_pGf!W;_v4ljqdfNCMV-$%E|x{iIcUHJ7r_1RP;O$oAu3mJj8_0@f!oP`$& zyjYOqkbjA8mov->g@(gK`&>o;0j4{I<8P-dB##aC0iJ1Ea-=JMB^hB_T1#aDwo$wc77FLDNa+A+|7G z@=lm&Rvy&s+ZquFyICaTxX+uY%r&ZfDu1LzWdTM4+U;@Nt?1(v;4N>?@_QrqV#HEc z1$@7guW>rKLZ%8!X5(~y3mRrZhcBQ%sDa=UNM22=t=RIx-ZYF{6Z10){Er0pwxI@p zY|j`#y7^yBOwZ#@8E+up8NMY|u9oV2JlxGM3Es=$k4u*ntgwN80GD*~1YG2PF4}lS zMU8~6;+38$46~U33-7h_gJ5iI1@|a*q~45iM!9j~*2)kZf8c54spnAt)NlEYPB(0M z3eDt@p^voB;`#o6PiO56eVu?F0(tq~Rzxp9niXSMAMk#F_7_4-?A%x7x z4X2VL`Z5x3*H=R{1N=cw1h+x5Q7_~4_WH|vm&hkDF^E?w;#f;w-HydOXeekswR*n$ zVr?lMQEXd|-d1!Rc5&dCOL{IM3-hVM{}KQhk4?KIAySUi$F-NIc$k37u=5zA(xsWB(T^q`TV!a)M1bI#MC6CcK zl~c5%-y4SxXDK6F$2fu)6Vu-m78grT@`m=pp@mZo_b3q)4|dorm#v5&2#QrX-vRV+bsNO&3;-cOsaN?##Ost06{cW+|{jHY#MBzPL zmFn##Duw5P%Wea@BjwJ%88Ec-I*f0LX2&OPuI#Zj$#zSM`8QUJ77)Ce@tyo8ZCE!I z4$1y=1CBohWxpTDh);)!X!$l6q9Jr%Gk=zZNR&X2TLM8gaUtIJHNyfV$s72|5B?w2 z*)+%B88jlGkE{3p0U{eXqjKw~2pM+gKT_)v6xyOOD_oFjR9f){BO!B)eEWWuKAwOm z1-_kv>{@~w`zUF~mK%6Olj&)g%q029``KR1V~0bb`kK$76o${$sH&(|1LIEb7cr>y6$AD>1Ul)&59?6EURv-)2)-M61U zV=VjLIYNo&sza9OiC!6=7|W2eD1Z?7F;=<bFFl3FU^*A$GQ2gFz^8jf}Q+`=3MR!#qh|pPYzhp4f(H8h=O^(1O`BXuOSSre>9= zS++AR53N$&VmegGTto~Zfz?3_E~?(@EG&IBIpWG-FR^w3B^Wx7!ipk;t{Hj|R}0I@ zIdUs z_fHiY7q-PfjAK%2Lml zlmh<(YWT0mlX(KJoD5ou-|wPlo+ta3+UTgy#HaT)V_^QGyX@=yM!`AokPo)wSMP^9 zMa^Y|=i0Kc2;o>q+@^iT@asJlJDI;cYTMn85Zd|ahf|zQlE~~<+Hh_`p0E9mc6$JT zZ^M3J6BftIJt}t!M5*=(@9lYspwD>TCJfn4lb_JJ^GXFE7&$&h_S-)V9%&%jC2iJE zIv>qu@lF_u1&Jvfl|EaAbcWfppgIxRTIf-9f0zd)zn^-fiYW+Wejby7lt{b(b znk6`sh>6+VFZnUl-a;YWol)M+_sgc7rB+f%G9AgO?EG`JojY~C1XP|U_TDB<_;;}=EBg6xN#<%O0Z?gs ziO2i>?G>EV2$iSHFT1p6`9}E5&LS@6qz_`5v|ujczmU7E@9tgsfCO=!?VN1d?;(C= zGYWgfO259pNQX6S7Ew@noctQ4CzKDK+R8RPw`m|yo0rMH87`S3bU7R z-ypzcr-H`Eh210~5d}UxzhwPSW5f*qg>6Ssce}}jgXx)9G9K>6)-|Gs@5s|dp6}FK zQK4tjFguRnF%}jbP9amP%1PvV`7{yMfotAPCXxoB4x$TjnVZ4ErR*_J?-wKqKb8l| z8#bgbCrMxPs9tY)XW8wAY-f~kQFVG&b06G?*vf|wh`tM%EeW}v_Q>}L8u=|)jix~w z+G+g>kd6RO6Hu<{%sU?q{HX;9r3Y9(E1nk7PT<^NB$8OxbMH<1}EA2Rwm|L7ljcO9#LQ{A!53k0*!LgSHFQ7pk+bDFQEF> zN_`^3VcR<*lAAm^8Y^Q&4nt4aPu{6GSU5}Af;*lOc@*m|{5RfQ7J2(mLhTvRjvbfN zzx5SM!%Er=Qd>XbnI49FaX&=L+1{_nE=_PDAa!2EJ-WT#Iz%7e z%q0Sz7lXRJn8X$`l8T&r7+X_e%o(Po~-f@@pOJrESNpn;S*e^E6V(HtE-?^6>);cem@ zFr8T}mUbF&e<@N2&_uT=#ABfE4!(311Y&qMjS<(#cS_Wav70q@g~#=E$ld&Ou=w?W zI3f1bb6bZqHZ{-+QO-ZVAv*PeKn4yx-3mZVZ`AT~ zJMm5Dj%|EbFNkeiTgl8|AFnD2e~fQK>sz4?nQDlfDGlR}BT8Yewd$JI#Qw8Jw^3=;@nF2XR2 zL9w{eIfV1;o9v(7>gt@olLMLn8;x1>LOIs zFPKmqmkH%RQ(ipfpBQ?94LBGt8$!d|-utLlveBfN@Xx-pIBtN@MFNs11S9UA+;2_u zZf^JBjD@BIN^ycJ4`xQpFwoDWKEFg+5`xBXY87{8XNGgnMllv7jNM66vWFBG(tO^h z_*Ltq-a~iT@O5dhL*Lnu!{M!RP_ONQjan{R;Ul^oP2vLK;k)sLD;O57M?^l$zBCtQ zTkYTQCO!J00;5lER`Pd%xdErf*5`Ao#99n~3tkv8nz6b6|+w@^O3ok7HObo4i(K9sqJeQ$aT_KFj+(kyz=toe00*OvtH{avh z@40`vE1({!^_=fdfjN$6RiRHpBWOns7scNnInNz21I}n-C_ilrO7BLtpL`>z5 zzlPh+eRriea6)MNS(l zZe|`EaU(jV2`{Rj?_88d=^l1+BAOqzO*F@5H*t+Ycn@1nB{!pf=pjyX(bE~WJqpMd z<-s~E6ViiwHI>6rawHprtl1-*eOkUgzOUYkq6ER*HvIk7KDUt}AGTLm?z;RpX3m|D zW9KyE{IDveTM>t8<%^vq6!rMchGXjt=l8qcwUjyxPO%E(%jL-7O}{-EQCAx3Vt_)D z4)bqq3|X<`4QfLMy4Vu07B%oYwL6YKNaj(ei9;U{^}pf&0V;~(d%YSPh@E3fi-WI` zjEZMLmk9!C$)W4k{g(aPC30Tp8-A%2W+hL}K{j!VW|eSXR`&zuOAxJ_(h)tJlyl6rIGonf!#D!@1bLo{DW_HU0zKayP99 znEeq-;hBhEKqNix;IQOY#1_k(Z*Znu5cOC#%d+{sFFb9eeI2FxVouwkf_sN>eMHS= zWA)cC;F~z=h4sUWyyX7?V7mkMP0%L>A)Vhq(j{cl06vQy)t+Vifg`an^ZS%CE93Bitx?5lzfxA!l<2{O4m18FHDLeLH_~R)^!Ef zU{J~{|EsMO*x>5Z?%WJqQ~D9{Wt_I2H$Gj8>JJ%;U5g|9`W|X{Gg(#!N=(>6OLi>T zp=j(Qdi!z#3CCeFsaR5-X61ZiZ5!$oMcR<=?J z-c~FOxa)C~e@M*HiEQv<9Nm9V{f`T(bKqDiI9#4$9KV zni^V(xUq%fcvh$Jf8tS4yyf$yKEpSGATUMChKS2=MISdnDLM(y9f&~pC({Zs0O7>V z77h_>17+lsjc%nnXc8PaR6g>Iq0gVEn(kf|a`LOWcZvCkU%^boDRKr0QoKjvN71UT z1sFz8bPSpM-u-RFVeS(cN!IX9*Ch4A&}Fpc!dlZo1El30r?kTpwltS~H(l>{G^Gew z>`}dnp26pf_y&}mMGv+k7;<1^0{^tOmxcMVlEiH9>yX1q$En)#D_rlCOJ^J_%&4M; z!|{iQ;ndS3zu?_SIOaHpHuN{3$h((!_o9c`vP)l~&()qnsb5ER8?N$O)B|vD&mG%+ z7!%rw*AKceQp_hbURfm8IOMd#4I)&yJ%L)1C%TG)wYD?LdZh-TflCI%dfbwW!jeC{ zh0kj^Z%5yw*87~>CNvNz=Fh-v7WVEer-OdH`z>|)p?rFqJ;=Am=KFx_S&Tco`?yJ= z58vMAHl+Mr{`!i2=6-6{2v*_Ykf%^c=)b`F`E5b#FQc)}?fxrHTb^o3 z$UJlY*A0IpnQjN9)V1J)frpFQE54+vSqzguyve@B^F>s2Yj zN<^r>1`Ym^JQUV2o$qlZ=MBvG1RC9nE#;F7ls{V5l-tiPQm`cRgL9d;1_H{hmxGOdX5Vvn^I4?yZy<16O8Le{?|#aq&v{Oj1LCFvZu$dq)6A+z6?zQDAP zpN{2!67K!iLBEgwvd1vQCXq+31?}b(V$hyJrBdpA2x0Z$=w#TBN=o8h#jurTZ zgi(rP&lx*Q;awi-UQ0o@F-DXy>x}&6!LUw)gs9)AFC6ZOIB^oBOp1gt3C{O=>Kb}RAO zd2@?zQ6_szPN!id&`~{?CcjRm4o@#-m+M)>_VaFf4 z5sg@w#i#N1)*hCk8UJ1*E|Sw*T3qYV*-tp8<0a6?gquzCS)#5uS(VTAe3~nwrk!{9 zySOsr3e1!|nSb7X?RgHaCT9sG3bBLqqTk;{k$@>yaiL}FHWbX~#3e=wmM^3*Gt&q& z2a){?q>2`ygE>^b42OsYdQ`fQDWBBr;uzuz#$LQfkOt;Se4~7=U!JA-a2?*9$PHw; z|Ka7hOo%e~37r>y4b!jpwQc!@cy=ISqYn#ls>f97lNvfu^0+vL^UEA!7TDo6x1aO2 zWytFFGWfJ*=P8Cm@Q>PpL8b`A%5&EMFrkewRfqYbX5HX?>>@Kecs%TvH zSTzYW*&UR?wRo?bsR$OMH@+>H{X&g-6Nl0wfuO;L?YD`oynn8@ z<#WB3Q&^=tXi!B+$0X7bvJT*E@=5ADtiH3=oc!y_VcVGTbYEVoK|G2il63vHyJ%O?=;JsONM$hNluEt5B4* zTFbv;6)9QVP2d5%hck1JofXe&exP?nr_1~k4pe1gDqn!@ULwex(bQvNi3(>bN|J~K zQ${wcF~o66%^dQP^`u8SXQGJX_@Nhtazvrqny(jvY;k(Jq_8YOC5ktYyjA?8FiuRY zBe&J}BS>Z=Gb6bB-o5RSi3a$0#BKDjDj++ez?GYKUUS2zgIByF68Ix)*yM6x9l}AB zUexH`#91q$PVXnQ)IhO=6TsSovJp&5T*-`J84xcKo^Zc%?6l42>?oJn9{5CWC0s^Y z1#VWYYY?9Ph!?hXUUv9De%2A$9j?un42u|0_0cWID0G+MZ_Ei{YdkmP?=nPA`uFLi z+7~&OuPyhe0^eY2FPaoGZUZ{nca@*3-92>e#A$}*v_Sd8Uyq~0#v#fjOHfdToNsZq zCqw*Ph#loFC(pHiZ5-=3*1*(11E_7)Z|5SIB~byJOwi>RhKp3im#!Vfz|=~3{d->O zeAS$*$=%~l7Xo79?FpEm2AsmDEa+w+FN+JLC>7$A5pWArUD>S0;qSS(i-i&XJ?umu zBw=`WIoRwz1ki6DMU*8A7q}vVepeu%-sF{yz?JA)I4IZT^<>m{d$W7{8gUkYF>M2XkINkhrx_A-f4_zChxYX8I2J*5_D1M+0IkYI z;)no{j5ZjeF#bjh>=HTzl#yDcY;^4p zUew#79UwLCJFg&T%Ge~b&Q1iFkhMj>?QCoiRZpT9qHvFPKfIHA)f$iAv^~wOF8znT z@ocNpc28f#{*k}3lWW)bq5W2MY!Z#$p zQ7tdg_4xLkIWd%33#}BLije@7pj&BLS2OVVMJYs>k*!=LHdwXGja_C@l!njKkrrQd zRHd|94xYUoN+YJrr1>!qvUPLU(#ePR;>Je-C>HkM{}FOQsbf4K_Nt2j^tR$6enYcv z^*9^n*ul~BVT#=!rYkS>dvjI1;{eWgXSvhUtmUZ4|KOmQvOfMhQs-ksxCqw2ovI2D z!+SRW$qVqXC;hpW0H=4B-YF+1#o6@DP`qZJf1y$oyZDEsQQd(XxZA!R?yOFsciPA^ z@Vi`Vy{c-RfI&+zC!bvuzFE;2w%N7)b^eL-8fx6fssRF?me&Vlf9}yrSbK-b?DPYL ze>L3)hM!}`7^L^fwqr4yA%a(6MsCta{Gs<=gmETnYhsGpJAw;Pq*?We8^qgmKCDm3 zgkKB?#4UNQcNQ)>SM0FN7%goudVVL}Zh z?o4d}b(M5FfBtzl*g|7wu&r1`acMA!1w^FbYrHAC}|9eIytsp8u-5$mS#^FqhrFcjJZbh?>H?&Sjg zLjh3H%7>z;J8`^Q4oe&r90nxga9gRb9`*+TeQpB;KQlVCqARas(y1_ z(q*jo^Qz)>(V+XFjNHdNM|ta;p?KG3=O`;6S?#?4zl zM-_hwQHPN&E3-k7wTPadvD6y#4hoAVY=q#V-W!qMtY3f1{Tol?_8?X)j-JkZYZp_4 z7MLKG=n13ioYR;3+A#X3^RfAVpk6A~#cuDfw1U8oq%}F&#`C9A>b$#NvGw6ge&Ic* z3*-Rm4&TH_`*%3?KYt!s>3CQS+0bxI6I+5>ZHq)#7?$zXt&*rcD% z#VkVX{S0RtUXwVv^h*M$e7afhI?FodhcRs37^q#5*(rlp&&Mh4~E) zKYe518=46%I%13^ozobLXSwt5yg!B+c&8tUchI#)Kv#I0Li4{I`~WmL+YEY!nGUioQFhoux(*lxZ!q%;$%{V`6MHnl_%^yLTabf;5noAvi7C55 z&(3R3;{BAc9r0hndDwWtO_t^J@TK1~Uj(zZxsS1%7zOx`15=l%a&#GJh05`SdLEsF}kMc~3 z5@_z>oK#i;I}I=F;RhWn8k`V(3?dNRo+nnz2+? zKKr#7Eq;8u4f+HsL#v5mUv?htB82*ZHW0xv8aTmu{O!r)!Zra zkrP`I+&nIclFlC9cf5Bn`z`S>kD|qOt0K z015ViyUl>TFKrh%d*i2&eMuLUw6dp`#`p^RejQE1X(Q$E=H=X@#L|Yog3q>k%Q5DPDTXhnbh;$)QwEBKRd`Hq?XWXJ0q$<( zUwVE%_(vCd0&7-jHl;Hjd*MBo@QBXq0q?u78!B!cX7abLB+aa6mhrk$H3#4h8zk2% z;fCC=&Bp<&KO3{vI>VvlI%Kw5hx*qeWptG1{{bfIwPrxK<)t6vO45UC6*&`5Ue>D$ zuJXlLeOf^#le~_V1h1RdPG5{C*OB~5qF(|I(G4c+o+Ox;p=wWf78h_6sDS zc&=7%B2@Wx!`g1AYVq#NmGNqZUvdn#^u~dgGn!+3sR)i68(_1loaHV6$CuZ>2CCuS zyNxk%IT+mm!AUCGP?YKY4^Sdp&Jxrhth9oEE@aPiq&=%R^SwAB_--=rD3OBVCdm8c z1U)kMvbu=>sRjE7CgL<1hb;ICSY#zcC+|b>{i2@PAA7fzrJca$A$p44dhOXssg}6c zTTxTIX;nGQe9n zUYq@^4wS-*ne?DA;&%5>*;4{i%q4Sx@yIoWUj!PBQpdfJ3HPZ+bz72p8Q}LvE->r? z1Ogf`U+b!R%s=f_WU35F1)r+fI9Bz+Fu{XCAHx3u?l+VLm~vvpuwpx*?7<@;`{=Pv zI)wORueVbrZ1cYw{@u=@08d#HQeFi!$Sl^ z;}mC83xYY!S4C0V=rgKpgK@juyJ;nRWjM<{5rC6Ue^GD8H5o1Ob`t{O1QBF1eSY%c zA)ti=`iPJar`~o6@egNq>IY;W;us#j5Ak$mS=TeudN-)QGzn*DWVAFPRn$sKs+Kop z=14ly(5KqpE~oq+?z=o0z9#hub>@U8gx*GU5fP(3-aE9H!rA{%4&xDnOSmn1jEM4k z=`{EFSbaZD3ID=0uaDB}nsL&5BH}tEqgUu+6H#xGo%D937c^lWT`RAjsYVvbGLX2D zX5FCcyxxzC#(j1LHqV@R@2-KtDOFH7R{O!zbx{l}oo$Vb?s3Po!X`1-tMhnnZW{p3CME*v{x^u{{~xl9cQ2beCK1xgog0VAudNv^kF9tP!0j zypnK$c(?Ly8846xZ~hXX`p!W&&cGzBnQD*SkqG~Q5Nsz1NSCsYl9L+x;Jd+#mrarA z>T$IRbR(>Zkk2>E?jS8p4DS`;6qzR-h2SOv34Fuy%t#L+z;A$3dm_xFmLBakAn(VE zce#Fx{fnefe_93GsvHHrkKZx-gj+*D=M!jYEZVJonA@=mKbwpXhT3e>vBt-q%=knp z>$eM&MFX#AJO_6|?xq)+B8i(jqYbxw@0|s4?%ilW7z>d|iLSSo)27`zk!dQF%e#YA zc$2vu?g62JaqL7(3X-I?%M#)LY-h^*EDP-4j&HI?p!=;TaN$qUf1du(7#L%OiN`;X zdyvPY^TGzmU%V+>rE$H;eL&C0Z`hFzB0jg6IHQpko?+iL zKSuk>eM30cE7d!iMFf0ipQZ}-r*(A~)@|7%P9c0@s`6i9IyGOimLE595R zl=&aP(!t=madE%aj3z+D0wLKzQBmNz#@c023qO+(5AKVwvNyu3Oh8YqC zBYNCgh;U9*VnSFny^G0Q7a2GNp1rlEiK@|9JjO`XL$*4zY}YljKb70h|Aqr*Iq*Bv z)-B0iQ}_=quD^G{|L8CBlr4@u9%S?uMkf(qc7zZT0WTWs$CV@rL-PM`)m1#*k zPy9TBdbbXioqH4sVn4;U&H~>q_w_j9`&^BB_#-p%!*wj8S7bz_zT)0HGGf0(6>bzL zr}AyQtg!B^?eAtHx3R>)011(9^$KdHP?r;*F zIG$zbyVkDQ;iVw%gt11-!~3n_=Mj#)yL;PW)0}|9SGvBZaAtP&Ymb!UkMTIhW0+pV zzL{BkK1WFNu)YomJ$kwkoj#{zyR^hn%vG|>M@U2voX~EWR3@-pSz-{q1k6S&tu5D% zz+hkGIR|XQ1b{~`2Z?&6N8-Bp&edBt1=Hp%v@+TBYjbuf%j-FIu6lpaO$6WCNctS6J*1zY3}A zj;${e<&-da%aVkZn-8)2o%p7*l#k)^`)%PBR@T!h^ZI3vQ6?=W*nFW2+k!3WIFt46 z;79Kv$a)65i+V9HkV$;@{qo{TG7~zRIQ;j!D~4wyq<@}#wa^gMSJ{i$LD0J)l_~^v zD#e(vSZerLSbJ~*;OsD)9L;Z#KikMDxkURo`}2EccqU*zL}~z9H!txF*zs# z)Xvffwf0te6EY?o+-YW8IHIO_<7*DJx|=Gz9g>i`8W%*TxI=z03fV$+xhnre-w={{ z5`)8}stlM&bhnex;vk_fRZ(3R$l%ctO+@tW+{V}6JqB@o-+g-YFfPxw8H(Nsqm3y;edIdfS9G_OD8dLAzMB*$wqU8@@sB3x$ z%T+hw-95FwqZN1jM@(FBu-;!k}-wh{6k7<6Q<#po_T*afeJe*Eppj`Xn zvTgNrt{-Y#7zy+U-KIV`cwEgS(`7xixDUT@KMm|0`T*NdXtySoy}w>0wBD%?btC4g zB*=~FP4kI^&X*QLLN5|m)t`ias-DM9%x}^D#gP>Cx^t>7zi?ZX$euR47-=h-Vfg&> zf+?b!BMNpIvGP&|pXkA%N*sYMwXot{uKg!c=P2MxIIF#CkRL5t;f_L1|8xHHjFHin z?tbkoOeZTjj{Sq&jg3x}XG#OEE#EgEnT^9WR2G@V06%!j6QIbe>cw@C&Q(J0kOOWX#BpY-ErAPIBte$v8P&Pa zB40Y3eSP1*N?A|But%3+q3@2~bp9b{gVa~vdy=`&;A>y!6e=$|bT}H%f#fdiO^Gf_ zSmI&-OziwLtw;u!LY?4|rv5R1qWgZhZ!@F`FRG}*(fa4G)zn0P-_36O-daA>D8$ch zgZpY=Ua^tYr!Jv-9T_@%eIHfE`g>eL;gty;>0T;hFE_EwRupX7Sw?XFM&wKA zPCNkVxLf4A!ATzJJPZZt;q$na&H_i;xf}mSi*Q8cf$%eI0vn;5LjW zk>0)%ttD|rKx+zKoqN7@S+oPez)pXUOR=)XgH?N7oYCSD6WL$oD1%f!Zq@g#O3%amooex(xaHVZQAW z1lHC*L_PiqW7!K(f$h4la2sMTd*(U2&$n^e7d|rLZe{|eLw?@KLRq}o$r=_zvpMQn zYeM1)##V?cpsX17d`lo!%h@X$D0Y1mE_{S_R)8i@;`wh6Io9+Ih$<*rs|uQKDXtEl zDyKb_*eSpj59+^Qc@^KY^GexmGVwnEonlF(4%4i|n-OIAmJ#_&%#zLqvDmplh!K=I z5%7Y1|K^r>o`3Wdjk7KjeKK{-Zj-j>-d_&<*#!3~n1JH0H{6GnyWqOuM-{V9X}a|7<=qtMP9fF$>U8=S>t@5Sg(_1Ih}4wqOl>*{vlLa6`DRMhL&oK9FOOO5XC z(2An-I1hdE&tzn$3XseH0OV4>Vz;9iM=^?6!yi~k5}}cQ^r`0ic=|0d^~!C;M@d)C znY4-7Q+jUU|eZ$W5_Qv`X>{;xGGof z>|f*=$nj)~e!?%Y?$UXG=s48%H3o{Mq+M-Dd+YFL^h&{6GS&thX0qMKMDlmTT^K#Mix6+Y(-gb>a0T~6RPyUzXSY*5&C5~# z#NScqQ3psSTLPkjg>88nPNMn5-!{O8XUJK<8pdFl-5yDMQyA-MPci+6ppsi3kT=8C z^X&#Q9ISs0!+qGVF+=bfYmS|p1-6PVdS8@S^7RK;|GJw|n9pxmt|AEAR-*7Cg45|{ zcMCt+rE6ZnXfGksvlqv)yBBU}sZK7tJv%4S^WJ@|#b_hn!@Z|5#?D?5J?!5TZJZaq z3Py#kd$wYH{1E~Mj(_UIN;w6!hdkxDE!oe9DRx}uY$C0TUs3HRKQ+5P90^MixulBI;^!h;Q&(}(>lt}UFAnT|# z9xuA|n?z#uNt(k#)~y?FjhVDQVfNFP<=;cLK9jwbClscRn?eT$7HC%dh9j%t>Hvnx z{{TQ6ssLf6c=BR!Zck${T|xWRQqBHAl==zw%m$N4)q2DLo7Ijh|8CpbCiIIxi$GA? zxfDwXH0ZXoj>>bY>XVgQ#BI4O)kii3P=^5~!PFD8j&dGY5ycvY3(r^aR+eAkU8H## zGlJEZ{@x9_b6oz8X8kR5k@PaBCFJk@br)>Bz*?7-=U}H<(pDSZ_T;@2l;^hE57F*n zX!5e=>P4MOBg|^JUYe(4Z2Ln`e8Wl%I4I;-XfXu%5x?sc5{3nLyLXUghG>`fiGNTS z|2KGjTQ#H)vm^XMPQx4^(#aOkuSRj99d=63ib-$9RDh$L&akztCz2#m0NeE6#ilZppg5`$+)7~I+(hF3N<7d57Z9mROx9JjSv;v zjt>S*Wp5}JRh-AGHVlQ@wJbS-Khv&{suAYf=C*UbQm#%OV{F^v0vT>lP490}y4!y? z5~-0ZV56Li5N^V<7r=_5<0KVgZH)}$sb35l-BHr%1W_ZClQ{@&fYR|QBa>$DZf4GK z8>?Mke#{SkQ8}!{$Y<6+gf^WefW{2`oVr(~E$z z2AjF_MoL19K|B)Oy z6?Z(x4nJ39&>cr+a*2_L`6k+Rn#tZIzq%$jM!f0rA|5-91O{l4FzzR?ee&(W8RD{* zdTIe~s$+bzVy{1}9TD>75IdYO{VZOOxaeq<8srp8AZ1W{C*;@O%-U`<{L})_3zoYu zHLTpXC(&y(m*+cjH`En(NAUTFpV1j=OpDHaSWVHt&|_MbdCY7ty1$AtGRgSbr5WJI zH!oC=Wo7@Hf|{l4uaGrYcLwV4>E~J!oV=R;7w+>|YWaV^5VKwju&i65Tas;iISv{G zY+c06$qEHDTJA$WY@6|<-IKi-^H0qld7QgYv!`p1t&^s8#_$FI4x50(*_ z0(Y}e94+!4-`o>iCLf2-#)*>s?qZe7bUO}=$rU7XRHX}2|HQR@nwJTkMOrGL4bFu~ zMuW1~_lypT^MSrS^ub(V_UOR$$e6ya8mJQITbLWnRF~AQcaD_>+MQ zy6WpPIh24Cqu*g;CY>#^u9uOa+$nXuR|z8Q5kiaRr45+R=be)Guc9kz)+Pp$UX5_H z@32LQEqy92f7*{GXl0zk`gRI|ynQcqT;Ur%G=D@~dX-k9$A39<_lVB}cC{Xkj~CQh zi47C4));-ie0wxFY*9o0CTvfd3{L{JF zW+O0BKVW1X{={E*}ttix*0ai*|A&z@+5isDYok1?2&1ltc+P3)R1 z*0cNTyjf!^0H%wS{Ln}WlUgnTUMCRrH9sa-s`Yi@1<;SZKDq&mz4aak&^djkKmabL zrTSYzm4Xe_V+8w4)iSulZ9xda+yqk*zFzwLpWK^anXbEoie%dakQt?4LZ7^s9=89G z2uKyE`^$Hg5ufntmM2s*yNg8!Npc$#=i?4B>dZkHzI_N?-~nhas_~cPAO0#JU-p=m z#-(k&w0k$U^iEFXXN|_IE@c<5Q)fzQ^>%Fsk3M1Cr0i9a8LJ*=9@=VCbRH2N#q~8@ zT%&%SVvdYH;lxPTOKuH*xOs@Uz2C_xRAcP7rQ}a)s8xt>s_V%W%?Mxm(n|`eDo&9p_jaEOtI7qRx^~LrYiY2q(hZ-qhB6#1f z6NoCD@%GC(!jw;^SMPv{wQKX8GVj7M#wrIAqj>MF{c^#vp%LwXK>-iXjvmc##!RqY zQyPMRR{sDlA}Cd@o_@GQ))3-PT;i8goJzXT^XCS$jb{(E{+ZEt=O}4zc+wcWVJqu{ zPTH-Q4$(bw@loNzS@M9t>l$Rc^Toks%Y}8+>wjG4Y?saLF?de(!-mV%>mGS@dKk4)SpFipI{+~bT^GX+ZMg#;%lxl9CT|D5#+zlTyGzi9X z*q?OkCJ2dFo)w>5AcC)#669n;H&~$6eL3Co*NhPAdFtd(PuB+CwZuH@STCww(D}uh z4hhB)Pa!5LTCE-A2-M|FLKZ4i$F>miS0An_oIGHosh;dq4tsdT4W~Z2NOaxz!~<9_ z(DV2YW_v#Ya6cR;+bjkg{{X3vIuCWrwjY!4it!$g_Rk8vJNLuK97tk1ha4tR!259s z?6jCaBLY897&kY`!rymqJK=rbt_fUt%8~)#D=P53#&84MCv&;WR)^6uyvGwZAaxlr zvZ!-bW|OC<7#bdZFem>2C({9QBL0}iKTt%fGT6zmGR^KfXeji$uc+-na7#4#skkCZ#C!Lg7Y6Z z8O1DLe2+=*80(<=Rv~CUt`%+lSdmir!N{@ACMC&niuU?sQ|`w90GsCy`}_(VSI#Ol z-&`3EFE5OO`tpvC$`}h{&dh_e;*H~hI>yE;A1KD~%0qzXkgoC(j?-78cxy*cT+p@2 zaj}I!9DJZxS2$Qz@GsGX3<>c-QymNC*cP{%14F4IU=j-YFT|fsb}a( z1i*U%?%_Ep86$r9D=paP2(E`?`ddY}LJlfxENJ#-rGvD6>={+S3g-;kE>|h43ofj+Aab9s0c|9z{ z5_{V}d?rscUvGv%O@!1wNz2-x;cmIV3#bfa(6e zZ)RxULl#bhoVurIC+mRy{4k4r;?@PhR{sDGoYnC^mnwt=UOsSCB8az)wje^_6!Ki< z@SYon3>KPZ)NzKvHub`QY{a@{`PM=Xy7QVlp7=1lwS*>lC!&TR&@|Iu z#{i|N2bIQvhz@ad)F>`MYEW3g9KCXUPzHYeW3m)= z9I#VM<(jiqt#J5A*h#;a2Mv^EehoJ?!7_XXGgSGw&O(ozoWOK_Hxj|HbhrLt zKp#olGdc#u7Fwi<5}SVMrNo^WawLnc2RJ(;FrC8?wxT|z zUF9%IW&AqH5pfN^_*R{bogbW2W$vcRPg$C)pj-x~C~1bBZsP$quNW&XfxkBk@9l*5 ziczX@lpQX=pi>Gs{AYu&QZvpt@_q4>qxs$-`psfLlRYeaP6N*K(Zu+#oN$g6>r0P3 zGr=(AL)^I*8u1uE`eHnNndF%8moLs4s3&X@d0guPAN-<%}4XAF~! z0EvePSSn!}j!V5BPqrfr*a61G=f7Nf(Ks(TXG z&Iec^p1DZ#e}jY_s27>y8i%p`9VA%?*k?Ulw~sJ=!m34HKK zBv`n9T;LX%QuCES_&TP z@js!3pdOYz;>Sna!brS;epqQakVo%}1oQ+w_m=DYfXG1303WM^x^6%1joG5ZZ1u*V z;R2$y-Q?)SlaIRF!R*F3N0py$7lY-8$ktAcAvy8zaxXB-3A{>L}7JX@&x+-I#Nmf$N(ucid(PTv?XB;xmi6+86KI6gOsqT7s*_@*oP zWf_Dd3$v_1Ak%c$q2o112x|<3FLMP8+tWF&mjvUvkoCA!(8WAmU`d7*TOg4??neQQ zfcBX!)Ip9uGn%Lmf7cUuDKG1Qeo(mk;1g41zphRUh@Y-e+Xu^7aC~BC24B8EAy@Ry zJO|$>nR&_r5#}&TU^;=&Tz?T76Dv{lE=i*taK#Wurt(UK`r(&P2b>c0B`yj^_xfcS z38L>RVRYaci(qBB7lUp_TzK9I1iY^DG6e2t6As2;hi?msYwhs+U?ffL>k&)~u;&Q( zOeBh*J~59BQ(a<7J5BSJ=)R|Ti<)qC{Ba3`+G`%c3rQw0<1IIi&CI>Jf!Uqja=7@* z9Yz9RfF{@9DU2jL=O%Csu5sH(L6oJPt@pr+2>Ni+(1TBThye0)f}O+;E{z??xikxX zO!K!Ma5o8;yZivot_(O|R&8YJ_V~dhotPeGr@lNP7RP>`xM#}JJHkra9N*gF(EI`D z*S=APgl9Our~&9;&cLl%l`3sloF8n@p;*d_6+Uy2t!L8(4)w}!69yZfiIP1YpfQ7NvThRUa`XAvX#-{jgBkYqa?@v#rI`aosxu-7KG}Y%lX==~y zfP$*3M4mBlH(FmzGJJt!Pd;&N4naF|g)SV}rPvNHHw3Gdz@LRArpw`$1*G3O1gv~z zzIo{9Xkl3E*AeXe<*m%@+RGYDI9KVG;eIlO)&S-9&*m^+3<1r2V4vxiw|+9!FUR5l z7zeAIB4?t&@CGB&A0Pa`CWQ%ZDTwiX(66K8*EF%%TzNn`-ZTIWdSM$FR9_u?;&z6@ zah#^RQequ&j)C8dO|i;%ii8deS>;8`ad=kf5@FN}>4Vo-jbW9ILzzBu0+`xN0tV); zLPU=`=Nbe(!rTgtsKckYBlWG7aeAaEoPF?e#|U%x z%ZU5B{c`8{9{7GC>;AEUxYh*pBy9WUl0@!v_s$}G-F~`W~hZ79Rd*>xVef40nm#}7S?f-F$+w(EF&nphHz0xYV{%-%$2+(XojCsVsgOUYs4Ec=V~Q|Gab{0; zVp^_-t#9^~IG-%Tu?~z1g(HZgN0p4;>W^F%3P%t~J)0&J0Y|*uB=pIPW7OYlmf|X% zY4^nlFiOYO#tc!*msqhwOXN5F@tUwC7EsyojKYcG!Ok5WoecdpU||YfBK`484%$!m zf((o5;Urbze|#@>cFIj>w-PUU68^X_Q5Nx;0lip+zP#s=LN(> zxEA{0{SZjLM!EBjkml46GyA;W%;r0R!`YEon}>E|N}>bL^5v2^M&ajwOqK{~3upbn zR-W2^fA853@&5pEsO&zr&)XU60ZGOQU;r*q>;;-VK5>(_?Bcqk zt?`LJb|z@&H?X*dX!*^d`LGF4J3QpqQ=j<3$Z2$D%j^%1a!Wfr65!N`B{7RgrP!XG z;;oDuXr9QD)uodC$Vv&z?{-y zq))ax0F#rZTr}y{9Hib%23BWd2@A%xj+Mr2S&7}r)+x}OE4&^Ua)u%r*PF-hkWi;2 z=N~1(nOL{*b2=kSgBDQ08ev@^sz%(NO5y1cJc}}M;i8R;467zY6Oz#cyb zBj@dr^Y+O3`(%9mvU%U&mp#}M{{W#hnPDI^SI!{YH0^(E5K328Ok_Cqlp?FF6C31* zpZS9m>m6ajZ@%E&e;5)w>4P?$b)U3YS*6Al?duNTZIxf6U^W%z)xi_t#sf;c>R}b# z#`0AQ>w~T_^SnL}7-a9`2{PCtyS(*Bejj{GRDB#{O+<3(a%$_s;}%%VGy?tbhVtU_ z1lh#iD!#)OpCp*T2mJbC0pEd7K$wY_#`36%%)k~d*Q^$*{u3(=n)YO56CjgTWkY$n z7ro%m6OH3dFB1akpHe+;S=&4_4ig^>ZV?oY#!Ql%ESH;KCJcq;isBvVmH>S+;L&+H z=7=jeKTH;j92wIMd2RuXF77R{?2JXuyd2zW4RDe$>6o0-^vi_XdXNM z_bflDgfQ-N##)l~Yg6{dRM75%TgFSrf z9yA`9fGR#F0Zx6~VM-6$Il#NP+%gh=YlMO1>jeidyZM23I=9&3+H;66rp|*6YclTUCP(SD~S%X1M-aH zyk3Kv*n#Q3G3h3U(EzBp(`D|AkMa=U(+t9rsTHO}%!H+6WyQfbjU zzQ3k(kUU`283vN|^XDrV(7@0@f1WbJ#1*;cAjVGla^{+yWS$1FKvIQy=d7Wu0d6kG z=RH8Kd1BkF$`f1++Y55&0d#F#D(&7J74*7C_$^AR{bd5fgl4 zgC@6}fvPo@c;D9}q7j6{KXo|s`53NefxJ*B*@zpq3%{X(!TiPrM+X>EqhU1>?SL3w zCR^{(F$9DQ#t2H#<&@{p$f8>!K5$J^H5>kz8}bA#o%}svP&FpCjIiLpKb|~9p!1LK ztQwT`j#$}lWD%S11GZ?czP`APx`Pr#lN9 z7C7Ih!`>`o`#dYIb=Lx@}te?j6i39KCu-?a&tfKeuEG3 zm;my|>gq`_vFwcZT(t~4l*LC-)?J^zX`{&-a?~Jqj=mIY`Z_n%Fv7<1@0z8)x!eB$ zuof6L+eswjylEsiOgll&O10}>?+rQc8vg)z0?TZ3_r%R>!TIk9o*WbP$b|t^x%bBI zQ-}TV0Z#z`0DSlY(SG2o2u<0NxvqAz;LZVwgiU z!o&AJ-e}Bxt`vs zaUl*DasfuUhkr5(H!w zA0=ziie7L$REOEe_2xV2V0Mof28(YVm|%kulHucl#N#z$9OUrRf@81?r#PZQqF3vG zOrF}nyyB@KeQ?(O__UCAdB&h9#9+m3=MV!_6+SRZmT+09FoI3l-d7Xf z0#~5L(Dx99kDN(uctwt55nTM@rIoKm^~GUIT^9w+WCd`rge)@AY6Z=f5|#e|S#Hnx z@sUAtU-gi@fZ;ybCUH+cwsT=@93M=w1426eF*Th4AN7JXr7QmcFo5k^4;dPf!i>xA zgjtrl#QHMhZ6)g_x)W&wj1<}RIM9m_HB4Lr44MO}Yc$3rD`o-!CfS96>iJsUF>1KG<5(QB^Rw^v4uNI5>-5BpBznEEoBe5!?QK@m;^4d?l~>_r&{u9{6;N`1i>wu0NM0??0bh8T5-7 znyJP>*WWjcu$P(ZJ#dLQZ#}*@#(skj@&%Y15sC??P8feYwx91Aj%%&)hmrs$6BIgp z;20kFS)ipH2Jn59H#iLG5MW#h{W95hA692FDu;8Ngz7?;oRq!!9ADA1RnQV|iJM$gH(sfCsk;@oI~#vIKC~ z@0S3D5f=0G%7L>~_A$|+bdhsY3yaC|#}(VythX=C_<{t;(dO?KY-hGS526^8hwWr` zr>;WWKyZW^a}J$eC1iSiaSn#PaTh}NTmktG;Orl9aX}mLk1;+lImUBYg?Yfb-_@F4 z{;aN!6U&01TZR*6{tGY(&iuwfOZLlAcPZvlWL-pTZ{qySgw#WAO@D85`h+Q14uQox%H9=O&#!$~+U^+p=>!P|tS z@F(!=#!Z0Qub45THd@}g#6@b?jK2Q>zySwf!&-iN#(UG~2sri0&Sex2VdKIw*;@SG z7wBUk6G8YP#G3LIJ|$BmPMtCjeU3Y-(U1F#APm>za+%ncf5N{A}5@j8*dnhLV9C4Urgf_&fS{FyQD$p*qQ-$2bj!%%7&lz@JFp*Q_24FeK;q!Yu(}`>7tfzT@$=7yoB^VxR3zC&i6^}hJ<(0oK&a+Q5%R1LHmomYBWYsq)#jDHe!Tk z1yk#+TLcjC6ebPBd;=55f_V-O5GE~9;8(witSjD8%NojFYG%whV0gH2dtv@cTunz2 z;Pf%nlPoSsF(A-!#wx;>x1S-LY^I9S{ z`dpkEVe}m}TP#864Ce~lKrKPY>ZbX{`6lJ6<)wV)_+{~FF-6#v&=!xDjz1N|1Ohu{ z`P@J)Re07YjaWy7DN}{>X^Q(eyDKuj( zgy(!>0FLLG|OE-S3T0P`)){dyW<1dFS@W$GqBpnECtzv233}0I~kig2G#ynIV67%^OC7Bf?eBhMTTH)!eM`Omg&1;tr zj45MHrVoI`TsTJ%QaK4QfE;AkIIEU#X7ExRpW6e6>fC0yE&EdfbB5nJZ)ne7A{)h4 zOD1Wg?-qpOcm4iYe^AhCV9!iIFx2xOPVD&08mvCw+ucUG6X#YEAxR2}-p<3Zl*4d6 zYPV-;s`jhiZUXzEL-JpyBIbjWV5b7TG3Oo7j@q=f6?wxk~n26-`Mqcm$4)TCWypBG=o zczxgQb9*r$rvSjZt-6>Rk8UwrNb#k>Ch6j^WO8%skjR?}&wn@}kE&s)!lpE1u0uOM zOg7&}Dnqv%>RlR}4df(KSpz`Biptxy)o>b8k5~824QS(e@I8d*AT&wKk@v(SA5$N9 zg0*M2j5H>pp+57R31W*(M0Cs2kOPsoEvO|pVTM!%#pdGgBfJhUyze(DGDmkND{tR` zK?~0E@AA07ti|MW?~8$m4c55jn2q*39e0BYE0a9)h%~h9 z-`9sLRYlEhz+=n?{qO0595Z?x^{z~1MLFDYy^~M1q+Opt*GtlIa zo{i$)v4E9X&DH`oUtCZVh~V0Q^=2R&z2o@D7b5t;OD;Jpz!RLkwDakTmdg9#4|;mx zC^I<}6I8jzV!=7a?vyIwQ&Lw5Dvsn-lV%b}NOdV7! z2akU9m-2r01Yi%E{#XfnkIM=9&6gvUJEr6H$xy<3L$CLi(kSvTj=9Yl*0w3m2Lgw- z{ry}cTxAU6VsslJ-<&<|NJi?n(bf_UoDN8V*mlLIUfRhxm)CftrC&N?Nh`pM$*%@; znYWg>eC*a#s&bRMbMfow_|JBGzW^6D^PawMH=37b2oFp3&YswRl$SQ|J^AkZE%$_X zf@gp0=<+{&XB)RpGi8&8g!f~oa?lCVtkO(OF8Mp)gH++XHwe|BW{{3YwVE8~S_@q5 zzp0zj*Q_Eu@OZ??tb)^Bbs^eKVhx4pD-c)Eku};f@>PIp*1{Z|-9So#K@e-lK7KP! zc}NmX-4gfd$WuUCkdvw#5aozk+W!Fa2Vv+o|7zE=6uP|Db?qUTiw75KtLQZGxlZbf?xDAV6IGIs) z*ESFjjs16w$TOLSV{?WI4W3f1mTio25=SZdBpY_Hw(7{tt;%I z*704SoMEn-j!lr4R|24l)tr9V5W}>bWO)mOeGs0xB_>dBJwoQn>SJ+;OED5o68`{x z#L6Gl$^7dy^-JnAzn~x5Q=8!c06p=K5LjrgbiK8NrCP5T+5+vFkoin=3g;6;&+fnz z85H4}!dSE$zCE(_EMgZzZcK1!b~I_41B_?_YV2?q%$;-l;R=Qpzn%HcqJSv~;@{{T!EFzKi1o*%fMrVnL(*Yv@Z zkB0u4rjfzR_RUWMF3*XK0-8G?7^6u|HCo>wO_X4a0~;ko>uq6URaXB1P^2ZirOh5p zZ&~%=$IM_J=jDLfark5nY6oS=BXM&zyY$5yz#H$Jj$GkAJY}iXH z>M##<99&|h3T8|ke+b(#Ysx2^vGym&+at#|ao8$B`5SvtdX9z5X{;o~n? z3!HjPMY_Ci1<4ZXgDw$c2O2<5tSwFI)bw z1PzUUtW5|ZIpTg;KmvR`{W-wqO7Fk6R}dUfXQudaV7INcD)kA|>NFFweXVr?K?Hq-+v=6QALZ8WcINFlaTCOqd>_Id_6&EtYc&QAD~t zw@jLN7`7_%)aXX%{{TP+>R#s=qTPXRK-T!mU12UH&SC7yyJ4jE!fS}QoI{ytup_nR zBcSMSw%<&0(5w4qy3cpO7B3x`ielhuV{QTIni~DGj%4)1Va>|bqX5Cg0EcHgxZcB> z{{T!NmTY`Kp13DV+xP=-lY`C}1n`Hu-_sIu<~R9e!*vtMToCGcy@wWH7I)F-2TC<> z9=8xq^*McRKF!l_+ab{lXHU}*HoADqN$G$rT;IO_m_j#@_3!63p*1M|@PbP+^#1_4 zvhT(*Tn)#~iWdB*p0O9HLkG}w=g*u@aHJk=anFs+IFT2Q?%Y!nh2bCXE(b`r#L9J> z-y?mzVryg$&t5Rels=-#yr7JVKb+wVRVDL~9`0@vDa$fIi$-wugd;^uVd8x-4JV+h zl$rAG{jwU`S$U}FvoE$DZjdMN;pxHCInNUWF;?dm4=f=}diBH8LaqQ)qx zOf97<&wL1Tal=9AewfLE39&dv@4mB4#u6hX;Po>5t)Rb58x%Y${KilN;7{aWV-IpY z^kO0(56v)lHzD8Wiv4(YeX!5vD<5Nn0=hWafLf% z5#n#_fFst;^-p{drR5X$#8(YGvRT5C3G;*LQ3tQD81F%qp2~@=f$%(qFU-F6?;u1W z#;5iLV(sUw6@^wGo9lp1vTbq6hV61(V{kqSV5b#^QbRG-Uq%t5Fkf-!4M-j22yN#h zP`;RHLfT9x6+_ufgm?@FpOU{^Q;TADa0s5Fuke_dML|xL_0A4c9ee-g959;!^|x5;@;TsGUe-*f!XKZUzT3r4V6~&N^s2p z0)U)M)6+$I5XOb3yi%h5i$vbB_l;%h9M==*UOhz}vnB*fI26*(#}zU^UX z+V+MZe!gy$1*?G(%pTJPVR1rBhTi)4$&;bVGxEZLndv#j!($;9<^1GOuNVM~o~6;q z0SE>!boz|2%LbAjK5=}dUG5JA;lebbSIx-`R50_5kpNOpjPqfWoM$?i?zd5=Zh`vP&$EIiv5Zok%5q_Oy!$uwl zu1H&p!PmDq#}Yds=j)oIH9W+>nVSg<<9grIG!*BnmTNH*EkJx=3o^mO)?7#(;2GwG zBb=Cp#7FWnz+u`)y~szr)7OuTO^Tf)Th{q8+tQ;FNG9x=2Lt0b<>K`YcQI5^IP>|> zuAy#G;p0i;{9tHxq0&*s&%G}peyriw27{0A+~9_nhsF+)0Fq-=(!3AUab~o6U#4)> z^e5zGWCY@u^Dz59H7C;=>a*R#i}IFXzPND` za35A%6hn~);)VKm^Uvm=rW}3n{R|VaesZeuI@kART;ovb;|ZpWA&z2Z1nLmiiM#LC z2AU|!^xXxYd@Yaw5uYFLDhMvT{qm|IY)WY3&c1RK1lFSM@;)-~kt%pRet+3e@EjHJ zuPAYbc#Q?)c?^YzSWlFU-oI=}^9HxK7(kA)+(*VyEm^M_Z*0VBy(Tb0OC~kz zkZy6-S_MW4`~H}b@kMqX*n&pH(UR{YhMsYtl42r4=H!0NV?+#~U7nbIhMc)%Hgke{ zv4w_tW)bbC*`AZv911Ei-YMuu$&QA#PYhpD4driB+X?M-C!7;0PzPW4BGmRbkBr(o z(}92=EXe+msg0m)2tA(_a z_sztH*ukP`RKrKnJilx`M!hL6r=uV%IpM{g5WBDZ$P7hIZ@t3op$(oc9wyJjwsymy z1qfF~LjC^uDx$Rk5c>f7;v}}dIR42rVyXQ0%{O$K)B4lvou3cgKM*z>fPI$v#2x{v z!yEyGjtvf8a3}u&inxT$9<2e3#uZq7ss3z3NhLZ$YXsRDws5jYy#X+ z*(+bO6>4X7Ii*FMOo~1rN?r3kD=46~V=N1aKCJNF35$UX0rARmpsECzu4sMH$ zZN)U&{@A40JZAfR<0}f|yPVK2Q@p5%k{;M6!H!@UrQ-)^M~RxxW!*evIXN-5bNS%~ zXrae5_RA7X4AG*3o;@&Y(IO=H&s=R&=LOq_uhaF%-tP}b(-{G3YTyJ6Q|tc#G0xE_ z!I2oW!({HQz_%^p-ln}DYzD5;ImCrg^vDBAlTobE<;c(pG}r|8!=Z4rm(j&ug;nti zdf;iAAI!G@0Jjx1EEWsT9@%7=uhlLubwOo#pGO#$5Tj4iH|~4OXhgsptl7PDH*zDv zf?(@x11QZm{sWf={{T(RP8|ENxw*mq8=SxJ-H&mua5I6%Y}RB~UKxr6q8FKuiV3$Q z+WX^Y^mDnrV0GdEYt9Q-*`EZ!Re%F?tA9?grg@fOXRsd_Ue)tIwYcPj@aN+>fCJ^m zJYA`!jsX=`aM?cJeByvGDi!&~CD7ws51cZ7oIW~n42AT;L!j@@0vDT!o}78_H`NjY z!SBV*AOe`fr%K>@V4?2CxaH39+8ci?3o&w8fb{1TIkx8BPtHiVEqTQi*_S{agED9U zaTe8n3`2rNqlq<%W%G)CIQ>Br&mNd&f}!yqJ@bx>shoQ2HFSp;jCUvO&8Wom!V2TO zH;N1ABO?zJURU(TE`kS<=f%a1%Z8+z7wV-ph1`&^_hf@|-R$ojYAIM1f>FV|TA0FaKhcZ10x^S6IYJEBHy3b!YpY+l(z zgYBG~;H@d##Cb6&zHGsN0VmU+t{qEOJ-sKsIDSnpjBzkNvh>IW40%5+-6#`D#zc5R zbH);0P+T7~D+;*Kkxx`vQts{MXFb-KkZhD>IPyYZGc`$hf zBi>TkHIlp6(=-5ZX)pseFn}~Y++fgrur?W@QRm@{ew+pQ*6+s{sZCE?kkU%KVyN{A z*4<6=V~gsI`#y$EM*!c~8!|S<8I%IWZ)^VmF@h7|=MGrhxF9rL<4-|BIlcU0RI(c^ z#psAfigq@}FFo|Ji>%*^^r@TN6;D_E&FfokFPzoj+20pLA?wBvK-ePWc^`gu;~G^> zIG(AIoM3Z8O(qAxmq|Fwm(iR|0{F>@5K(R>GXrky_u<8!pb_oQ<%Q#2Waj`%u5TEF zQwEWWF1Q$0vCG>XLGBYaOj2PUa6JB?Z7LZh%!8I@61ZGXO{O1`%IAHT-axrOkB=P#;a4Mj0jbzCn z9r@k>3r5%c2QVk}!4W}>(VxM&2|hB4hy{9o!*iGZIKidOOTavswNcTd$@$Gq!-b=j z*R}%zisx_q%iK`y3qIJq2&%gWe^2eCf(v?5zsGn1>XB?RyaM{)(;%L2yKBVt`(y?Z zcjNxzgGtHf9*!M(z;ArGG>Ld_BLImTIKoE+VhZ{w<^QGjN$;m_qfQ^ z+&f~#Bhkxs!Mc#V7E-l9<0SFPG%Z!t7i_Mt}J6h%Ec)o%Wu`MHY{@7h;eY`b;ggFGe zap+MLTg24Oz)EL)?-#4pAJ;bcJR)PXBfxR*Ujf!HkVXah#oDEj-bGg88^L=MgbbQ0 zgfO_-#p26~m_5B~1!M@nT-=_D$@7ZvL9d(%7(i6{$ySZ88ekPPdB2)ke--D+s8CxhhrNum1pyCC+0t zmw03&ooS0 zU6{&k{t0kG=zC*U!xP&GD|{7lY~rP#ucivStG(iVIl$^L2ekdM%6E^y{Ky>wocR54 zO2da)Z3%bB6a*7dF{;SVOUmGOSeqU&gFBHG+2@SiE+4SCtZEf$h8iHyrxVTs5j_)) z^S*G{LPZIw?;LNkcMpf-0iz8Yrw6AT<$Jn^exE#jvZ&R_p1GR-(`m z>pie#vLUD68k8h7Td%eP%@iBH?i_f*6$R(lgX^5VVo25B+`)<;3cNeR&MHiro7bE~ zs-O%@=M`XT0k`(Swwt1nna3lD@aHZUW|8>8%{12Xw|eUuXq!4N3{31vlmsZiU<-7b zAJbWaBb;v zAh9LUKf`mE{y@R=)092KG{>LF#N8SXo^JiH2~8D5mVS6kw_S%Ht@zHt1Jv0%w0HGp z_hy-=`%1_n_eitBj-^(os(Hm+kP+t%)X*H7_4WJa??!6~?6@8pImCp3>&|$^))bg} z2hLa~dBF(id%`6s9_*QJgcp%rSB-sg9ZO2`9b<61^WtvYjWGkSITkhPg6X8;xqYF|T^0?;ilfOGR<)(-yOh%zHo{f^}uo$uT0=+<9LQLma(=1D|GLyx_ph;`6lpLxd7K&z@VUP zR(>5bfUtYU2Ra<#d8k_V#M%WTcyf*Eahhm2IS2k=^m8hrbw0R77LdFj7&4P$P3GS& z0z@NE4~$4W`1Zswe63&%cL>ReMtER^*MV*{hWiNlLD182z`5D{r1ow%;r#$A}YZ8D$b02^0PhK44 zyO6r%A6ZYX4}tpMv5@t{RCV4&0*-DjX#F_$z@PpyEV3J~PBF)S$4d9FX@wkXa5u5< z0yKCT;y2$Vn(@_*sU79BZN48I{{TA9Ssw@606w5UY^#9VTq=ACt8rm5RjJ}P->g+K zzoKhdtUB2s_R85OYcNP#$=BNwqg(~NuCO?dZ`UMOg&ntkJYcNE0E=HvOh-BpCM}ZC z4U_AVX;ep<{{V88o8>=DRhD(vTH^?CC?5Ov$ES@z=JivYvv+sxf{Ky6Vt#Ma4!RuI z38VN`I>$lTY6%2{?*X(B59gMw{=kpdHRcWa%f7hrmOwjsE>fwfG_M#GoW+L#P4|X$ zU;+1BI%pPtJuy%+Cc9l9gAF1Lf(JbByk$;?G|uK*gp;Y?JLeX8GhMhYrOJZSr@5qa ze%P@?CI!PUql!UOYae_+iKg}RtS6KMMdr5^h^)MUsnqAZEfXPQ_+bh|WYwb5B5O(VK^MzlKL|%7K20>JA`MKA9W!$KAd|}O&9B&AH za4FUY^WFioc_%p-XMU5(m|X|QvHKFO0uxSRUot5W;3jdja`01OYW;eDCgPwx!P z{Ym{ihmk(mY`$+FZ2tfcUsmGZ{E-zVEkibNq0U{N%&naJ>GsKQ0RI4kBGY7oJA2XZ zJnG1WfxpV1Pweo;I6UK_4t}bH@;yAQ9XsId4eOkXsS5Oe+=9V5B$p{OB-c0oWlib# z#yis{2aD#jCt|pcC?l^r##pz+-ZHx5tU^8c%37B%Q!9{Ly=jH2Yy>5Djk9-FbLld| z)IN@Lnn<3xrQN~=T$~mh?-Br`*9nMbrn$$iSoP;O09M(?6c*qfx}Lc5<5^PxFOITj z;nO70qICOWfKkAyjgGhs zu{H3;$mpOyEZ-Puk>EM_!WpJ&3{av*rPe@z>Uq|1{6DK7wtr?PA_jKO-++Le8a%Hb zaQgaSu9FSaTih?s2tTv2@Y&}GfxAHFy+AkYnxv?+?Z&r{#dKG2vPr2Z{qeHbg}&1g1;a?g<2Erz$L8d2>zolshPhuc!rl8~fyqF^DkoU#HNuu)PR6L2Mk)Y} z;t z<;mHMviNqq`(Umt7JWK>aZimQeA?e^1jHIS&vs0i>Tym%_bvq$_+plQse&%2oCd1X zqxvtiJ8AvrE)D*Q&=$X=fgK-&{%LaJgwXfb_-2Qu4PX3{u8(KiBiDQ*p0j*q_2V{b zpc|tM+g|WZ)1)KXfH*;PUeK4{*ZU2+`wTM9{Vn{E^zIcK;R+s&ZUHzwuAXa1ZC@f?5|oapW+=kv;Bf6wyRnsU+8IV@2ULfVBJX358xzxU)gcFm*FiQ`Z7< zK>2U3u^}O9{I!<~0`%ac)VgoP!8Vn`5!SIpB0BAdDnu*K{Kipjgv+Pco6XX}#nuQP zuJYOwWK1O!bc=%R*c{@WddzEW^L3S0DQ7&Qz+2xOxTeXsmg18~Bj{gTP`BB0XRRsb zc6i2aHG%Qo2DLoW;@$=h%Eam!#3m=Pvjx%=34#$tya?ls5QC|k*&BE>asVXa;r>{I zlBvQu21QUwci(uWk-Evn+FJ7#PO;82QwUS%J5W!xLcO zsrAo@=3kPGF=e6r2Pp_}FD!Wu1lB?e2#&x|YyiN~CQETYi#-dQE-zbgm!@j&`w6N4Hr)W)&Y(>LeN zL?<~Qdtd}PdHfRhuFPylE#r^P&RBZn zkx-nybyVB$vo0Fk-QBgg28ZHKOIx(K7PsQ=PN8`4V#T3Fin}|-AwbXu2=366?{Dwl zI(zSP&sz81{F7uQEBR#dzVpsJGxI!Cm(#m8WA2vzoKHw!O&FoTr*$t!Nuq=}WyRJ} zfT){GJHwf?k?19JtSyJ zlIl$3T9;vjq6(sm9W_s~3Kon6B=gydxkMp;z)c}y*_;L;*n$!CRN`6* z_GlnVl{1!oOY}AUom|e%bHburjZ)!&Pv)sf!$hy$3UAKi=_Ada$X|2I7wk8gp?jsN zqT#ooAbF=+-0o^Hrn+a|d!$(yTJ^-w*|Nwuawcls=Hwolz&`FJqT*?kwGuir5cph7 z3WHdQIY4<$?tU7GJT4g)H3hFS5ZtisBn5)*`Rs+%to*v_9CusW)(}Tb`w-)hs?kx} zU2EfzM=c_q>w!vixdbW%7SHwW#VG0-ZQ$rBaY2HV7oXJCIFoZ*&nQS7Uz@<}`p-Fd zS}OrFu)lituwfdn3KVDx-5U5=w1ke{0tZ=+!rBk;Zu(k55FuV%G3w2RDeVxRG;Y5g zh@1|N?~sio+K}rPabwp{xevx=G|!{aybV!b`sicfT2&KYZFstJ-*@e?`{JdQ5v@~# zR&x*E9`|EL{YdOymbFD()>5X|m%v(pfsYcc6?e8i+i^G;6GeWs*+>2hIREh`!EGC@ z)7rD<%<^hHiqllR*^X#(ldR<-^)_vZtXaP5G9TQ<^%vl1xR}+FMoXFP(X!nI0y{H~ zOefRjA%gV5lwa4el;8mt6pe^g`^;W^ zDA0}V=HC1n)q8|}msV4$OSC{E^a3HE|49=E-jkm;aHbL9ks6U^BC{y^ZSqI8qjAJ* z+)Z&Y1=GHIHOVf%pDCktFq}NwqNd-~S-9n_SD)pMW!2n@F3@mYB0VeVMte(2enmXA ziSx3_kQF5Gf7fR#tCZ5_F|L+PCa;P0kGb7HThjU z0LP+y+jMe(YxF!Fa{ce=&xI3f+VxJtvEt`mRunx~xdZDl=N5p+HHE)=HrPD*X}8Xa z9&DW9O_t+ z=E$HYvr~p4UOS+q6&V6Fmy;hZ+g6|+TccZ{8i%eIAC(|o%O?-a1i4eG2ziHFGJ9_} zvI8Y9^XdUCZPrx5xaqYH5tL|OI+iJgB_Q-%iY{Wx^DV>A1I)M@`O!H@;h(p2LaW-KRa;Pd|BoJLd3a?=0#6js}i7&&xo=x1ISAwOLH7m&;{{TcbCZ$fpd zUL|U5fN@xz-kLp)yc=k}heIm>)JH4W8}7yYuugcwp&#}ssb92TMOW-~iFJe|yKfM*(-JL4PD_@*)5@ z(>naeXDS52^5eA(Xs7g9L`&{XQy8rq(%Xpk2>2BoWfi~a8-3@uyksAS$;2Isx7XpW z)}@b**a4jI+hJ251hW}v_c-5aDKGhA_Ob<(-1OmhApAH0Qz8AJwG1qY6$cOpc=p&m zc1Xk9%mq;GnOw*cNXM`g0;IMwpA=e&aMB2a?QC5BXdjwmS>)Nftif{W(G4R-_WR_k zrs;OW+6$V>7?Gv#i7x*D` zR&L3>qmk$>m7%t>s4vT>1X9`N$Ut&q`qf}ZD{V6wN5h`8lAskQFE`5^6+aC;m3^v5 zOEZfhN%L@7|0DxRgfw7NZBK6-Z?iz9NfBR9)w)J{<}i7o-a^ipt3DA#sDjAFYbim& z5N{mO$Ra6s0ScxaLjQK@=Eyu7;#GANM`PughAM)4sp1Yxa4MCwlXpG z+fFvA6erQ216@m_q7Bx>gUICIQhwwFn`p>X**+UraMq2?g6%w?TIwxgK+F9}{G5qV za2kQRt#T%}?u@oazzSFa6W{jVi~k_2d{!qJSnHpMiWu z%{RyDi+pBtI8Uh9aE)Dkz7d9#4#;wN&p0e8R`#_WoSo-G)H-hTmoC1G9?hT|Nt$jV z6vK!xFoDHD^EO@v6qd97ZDhX>0W1q0x|RE>u=pdI5-^J-l({h~`vu()C&Uh$g&24nMcOmRR^V)E z;Se*ng4hEUVoVs(l49-WhSHA6w=!PJE=~|j?IN-($A(3q6STh}sNXI+)JU#3qaDkK zfZ9`QlD(e&n?0Km+=y@D(wa`aR}PIEp;SX?Tj^bMnstDh5z~$pkRydQ z=Z=_C9)+>&6~`{woLpV^vR!$&BHk%Wnfa#HXg%&Yh#4hmT^~Y-+3aYy_mbCp?U9z) zuY!|R7X_iQ@XW0$xQKzwUH2g|ts{nE=}iNLkWyj9&h~Qwl-4 z!bIVAsLFVgXcw>YqZ=elqLz{?gq08V<$%<7`w0fUptof6Nk}@@INpuIE`{v8|tGZ z`N9abE5PIk*`ZVli;8bGyfMW){2=@pA-<26HULAZ0Epm9ojxK$uF^k;v*n$!BF@>MYhy4^OVQMA$h@@5{;F5;Gs>LtZyDz@oM zNp*BPLeOfy0rw3g^mKH!4u;eUm)HEZwjZdqM~Cs5tnonRShJ;G()X8p=9w#fO#~g( zSUS#o*cuhr#d|t&Lbi#A3td?~K!uXi`;ml7D%B4mJhj;^IPZT4lKIi#3Up(rEGN8~ zklVaC1nleFGd>-Veez15F{{kQ|MgMgW{8B5Fwse9i1LJ@+Gz8M(sS+mN`uY$``;9^ zzR%M4t$|fa?^w34#*csl9hrWVb^8M(rj7v715Ho+-mzm5#;5>?7Esiv!#4uytf#A` zQp_1cgA!Kf-p}rySOU3QotQH@zx_iox;bKg|9azGRfx6BtAUBf4idQfMa_tPwq8iy zkwTPTf7FGJg<$Z;7seSfryn7$@op8x6KQ6;9X_;oY<}%|8P~=TBUzGkp7Li-hyYSP zWxPOw)|MN7j56m1TDm)OWqs?F@UWu|-HYCFydtAA*gQR@8%Ht0M7xB(5Kd6tarMhw zM1=eM5sbu32^rf%4e%H6-`tP-pg$9?y71lkIeJ}V6zB~cG ziJ&^C_X}h5MBnGqC{v8y5Rt%eXI z`Y#5a@ggSjCT$)_CvpC?Kt1n{W;QYrtlSHCNw^=t;stUb%^Ym+Y*q9s5~U9qE(PpS z`nyohu#BlnxjB1;eGzSsQ?#y7-9*1)i|jp3Rh`tU)c|ll);_P@Y37R$VtGPo%BM|3 zw&^*CFLru=DCB!%Rx9)nR*hLUWVxI|k+>poUFnHg$dFWLko5B8dvlmHF2xt=S-z%G zN4~$-Xeh%~onnS-sbu!t@ozAw+zz3W3+0T&$x3T0i|!kV4H+6~K&X3ui}$E8(w&VK z5W}>eCa1@a9>l~QnGK+k8jGqe1hB4pLSFCoD5Kfy%gAcxoxuCiaQZ?TbH$7ESXS)b z?pSB5Q5Iw*-i!S^p?A$&ygmSO%NFfCOJt($*k*|=tg;_h*QXxUF`qG_zxaZG$LRYx zq2c`naH{8L0`PMA-X&DlJ>hO&nIBI4Vq~!@gS~y z4-3UHI<{j7tyG`bF+#n%p8_7L{>t`^&Zw ziHx>EoC#dbKB4)#Vgd@jC|yG)Ef+w{*ZU%8hxQM_5{FFCYc&_bAD zh+5~A0Ll-b(vCa51U7HU{`bUoA6fVky<#$<6BNK;Ho0%Jcb*sfP3j;tfU%M%;0*o$Wc>Uxq$!$6(Yi z8AE5s!{Bglfd6Wug@KXT$G8S-`)Fwjl7Ti7>4^zGnt`t0g+ltsXOm7b`wkKLE$bm+Fv*RZl+uLxShoJ z%_qp0WMh-NAlhX>!#jQ}E9s}367YHm@9_Q9+@nOx5<1e4zW^I%l$S3aZ= z`w;Zt#}u)_4%;QdAPLHr^9H8(WJnt76b*&)P-oh(PLM=!w{K;9aG?$NU%;e#{I`dA zP)Yzse3*%H0&j)r>vaq{y*_VPI!>QMtpF}+cM%^dz!A9xHL3_sCrz~jxs3aD)bqPe zNjr_F%CQCrn{G63PHOPHV(DttP$sINQ#e@SzPTIa7?^Bo!&cMs%HTb`?r>C`6@K$T zHFSplrvpT@l}y-?9S<{>W~?i?k5-=?>o^Jv{c00&3em|Zknj@dcyv9rocRfJWF*xi z*^un?p0?YuAnY z$JM(ghObn=heANBqd7<}WN*Vhysy|x(ESKW;-7L_5>tB3ES48|ZjQa|GEM##@i3E; zs*u`a6M=lDv%UY*!?-P7^Q$j}8qO{!A$I|mnHO#-7UnpFW|`3mUI_WEneB-Qi`CE9vYKsQ=YC(}1Lq#KTT$8ve>(K*N%8Z1jgymx`xGsEXh1^FrIVO&rtb z2m+!&X})h?)OP&M0Gu+fMW9^`pB1Sm2)`k_U5-~Rsu5m&0UfEKoPT8)ZnPP}Y{itG z;BV}jL-DHLFcMgf_J^^MWm{)r(TufxB zi_r-)emIv&D;*>RQ=GU|jpgK;()oNKl7-6@r7ib2JreVJZU>AANg7=i7d|Y)mtlO@ z?rkbS7PX%7f=iRq1k;{h;60lJP?vMdG5lR)@jH$jB|(^4=x1!Z=1A*S$V3 zD@?L}J#(R8>>%Y3tG1b3L6!Dq4H^xUqamWtzl_gw(zQ#7PlJ;+)I7R}_1$Rx0%$Bh z=P5V?lRU9s->CDkqvLn%>=F(ny5-R^lQwI7vtmReuOhC>{j&R21oSDu zw~r?_QSo7CAd+Ln|G_IW!mr%J1{pWYorJZO3-hE zmf+s{mUY{1w(}pFu0Ovw`JH|8>YfI8-aZpv|1n>Th`9Rmv@61}<$MYqauJADuPZQi z$t*gT3E-%#@NL4KKu@NIai`hIU^5da2!}+~d3QK!S4|o{JOy4kt*4{?vU%dMYim#z zlG@_2s*w=|VH#t=JI#0SH|_)&_)Fb`+>mq}AqEZY@SQh!c@MNqL637I|bOO4a zR3@(h@NB@kwT_%Z#}l;cmmtz|)DL>ozN5rHAMi72R7%8hA3cy3qacTQ`n4dF5?YL( zpLtW#QigQZikpz(j*_brk3h?w@lJ1`kD0vGuR)bCxizUkfk&;_MUqeX9a{+aF>OKg zh5NfF#B}YqqlMU^50(K&xFno4-ZAf8g7ioW!(dVB#6YeB@->XIspSB84F|cm72o=3 zQ3!TQ)B5fc{17FF>&15?C%HpI>?0N=K&(lK#lVVF)cY)BX!k7O_Pf zuTzKR1nXRjeC>R3BL^TZNO`op4AxU_1lafG711ie)`a$pR{s12g#Oc>@SLpMNaECK zwwdT*kYE10pl9ce6x)0(@ildzc9l%%wC7z zy3dwcLDg8@|GaI>)j{dWg(iIh+>gZl+=VB1H+e@FXim=Oqq$do2r=HF!U*+%i+;n2 z>=A=F{_~O4%4r{e^{ur*podCKb_UDl^$Ah%C zDs0CrLXFQ{>QBZ#*GyRA$*gQjL>f6oK5G|VDb{KU>*e~c+Sd``nDmxjx^8Q%v)gCA zo>-o((TaO$J`K1bCcLoBJdRxhjpGXLBLQ<_j!78)NJXEz4N_Tu-+3rPq3B=0A8M}< zZQY~r#cunzM5JWl>W$wY4qToSf7=PcnBvoR83VTP^o8Lq9H>b)!59g*H$#E$jg5^B z<@%zj!G{293dOf~In%oy_aNIErKiT}L%E~Jm8Ya&!Q8ut`dz~NP5q6#!PccA+_`kI z?}7Dcr|LaKC;57H6og9yi@{6<69<=KPgC-#{xHDXRiA462bbw38y+UZ8)N5V;0+w|(510qk?R5FyY8Jgvnw%jC=Sg0UBJs@_{!#z=}$zw=Su`E z{u*$I(!7>DKcsc7{{XU~?|}+bdhaF6Xfa#a1yhiN%giIThtIZ8-J_#kvN(^A&%w~U zpKLLKbW1denj+J?lMlBDVSzfX{(6@OEE!k2*ZquQB*qe^IBvH+sbTLM1h-1Hwi z1^b0``7eOZ@|=wEf&TfQO@ndwPl;yW9}w-O=m*eEFN7uYYd=>gSJdf)t#p(FS}KQb z;bmU;4Un*|gny!+=F{yn*-1_wlb+00(-N5UFW{86xODLM0jakS(V0P7&SY9$Z~5hB z_P`DQl%8~nYwG>Ir!OGM?_OQ?WVWvhXyAcy;v#d z*B~g;mlKN-O?fr`B+~vi8gg{(aV=?>f96%mgAykw1k?du+#D7Ig==T>aBA^%8t$0`DNFvwRQ> zjD7eEc$i(@YZt|m+_D;|kzbK|k&f5raD1n8p7$4UgF|zbZ7F7a5m-=nhwBb6z~Oi9 zCq%TXa7CEUYaOlq?W%2DNPT>6Xf~jiE=Pf-E zVfZL#F~a7p@Bz|$Re!O~Bac)i6spd@fRF>;=ajaFwtVF^#9*c7n!)a9t~b|*=Rd)p>mv};UNMu3KIeK0K(#%}j@A_N zMa`Y;!9rEvVA@C68i{Uq66;vQWwg%Nq)_5AVO8^XQ@NlD%M7n6k|?~TWAAAqJSe7# z-K^`C6r7TneDq_MONU}~{gCRq1Dv?y&i1P3g4UTyj$_hQakdW2nF2=Pj0*m2SXj}3 zwI~~b$HJ5k1$JzJP;!L1_WNCY;Pc)puwXne1T>WJ;Am* z8eXJ_uiPJruKxnAO9kX=Gohg}^m4B^p4$d2*T0|KTIJou%h`3g;iHq=ty%>(bIC{= z?O1Yjpf{0rtZ%RJrPMkX;8L`P0SqUPY)w&>6S|B=nFb8726Yj*st^q6a#X>?JE}h_TXR{F7i7$!+|=v`ZpQ2=e$hQ`keRH(>6#po(FnT#$dR)xjU-KJfnKP{dnoq)%6*DEu<#3szpBlr4k~izs zkahs@*~ldsOfQ|X;rI@IVbQ?|_5`IDK~kR6XL5*QW$p(1;h14f;om5Em8Z*iBEtU+ zyi4tb83VG??G-fQcwHw-mE}?jPW;L_~Uc-nmY4ECOE1 zm+tkBO|kN&p%tU;z2J834ir2Td02Xg-nv|IO(Vey`gXtrJT9l}N3dL=o!e2mm8s4P zH6k|xTx~d*Ql@jh!UTA4@u#lcon)Bq1y;^R0pdHXEbJA>|jc)Y&NY@13CtIgaOf4Mw;1q9s7@MD$&h)d2@OU+J zVxBd)FkA7vhJDJAwR|iPC89iM*S910*WU)Zo+4s?Pkiy)MsC15*%-tdKrlSGpK?Gm zYmdojYnAW&g|(^vVf1k)iqog{P)+JDpzitg1XWmiTlO01f2}cfOAXJBu>73v$=VQ;?kD zwT=*+W0+=$0x>s#@;p44XE|uHoIfp!XW#)`WWmzjM>&SMfb%N#ohyjZM5{Dv4rJ*h z*(QpwQ>Q=!kmzL7!8HmPcafeju9iRBc&6pIl_zQl>!34ke1mpP7F@x(2jLXh~c5yFc;;&#Rk+>}@X9tOVETTRNq;`vnx*ONG& zIu1y{qh&QMgvKF|JG%O^Of9Z=c+BH|zep%=Dj#E$^lss`IG!UpV`&mk;Kd5m)U5lK zx%|FgHZm>XemHNFpWD?PWlysUt?V|eX7`mW;1###M>kP49=6^h#b`Q7%c1&d%l;uk zIJ4&`6o-HqZHa-5k@^r~wnTFh8zeC)w~*N7+WXCO>sRfex1*j@e;!YouE#Esgy5*P z=2rS8U!LauP_)+29U&A)EtAr#EG;u_fBUyP6;15O1N}DiPCr}zf1D+Er8W{Wmx%jA z`!1(oXao$1R(~1wB_4Na?Uh1OAxak-EZGx(Ydsu?V0YCm2hTppZsT&OmA~p&ssOkk zO9}@nnKDzk`n3J0aC2fcPqmxt*=?v7*%|?_S^OhTf1Q@ku%OCUFMkrLbsdH^iC)K( z=|=86vr~ydW{g=x6NBh4`T7G0_1Dz9Dvfi99i5=PXx((S(zN6*exU7;VtC$pToZ;i zV%3uV%s@`j>3z>kS!P0KHla^8uLQ<0kUO=Z=<nt~*GCRF?cZHRF7UP;a1ea4P&sOk`5(OE{lr`7C}cwcj2e z)mUJ?+D=OA{!j^X%s4b`!Kv!!vui=2u!&d5`kvBM)$G*y<+qQb)~2}rt)UfP>T~lw zpDc;ph)Zb?N)i+pJP^vOe9gq5ad^B->=%R~gi;o@p94s4t**|ZXjS7KS@=d^4I8rz zQ>gJ+K``>E^+LzVRd#^WC=HnD$aB$YW zBoq14_QZQVy&YWp|LWD4*0P^S%H3 z>i_+UTwS&T&oP#x&s_hQ`R8T0Szfui=>7$4<7UHC8D<_wXPcLkm(uL5z)N{u(w$s{ z1KQS9Ux}xB_6wnWU$Uo>+ zE#duC(2ujf8#KfZV@3(g-F&i8mL>7nG(wsdJDJVt=S9Ua+3@MNP3zE%P<;&~te*W@ zOZ)P)$=8c?5|q{QAZF3qkI}Aq9>w60af41T2ChZJQRfibe3s4{x^8#B#GAd$sl(6d zN?(G8(7;UrjAzT%S=1KKRm*?4m5D92+_0mT&Y*v zd)pg+t8_EPPm@sW1gly$XI>@lt>adv z*Mj$^bbkTpAb9#50T0tm>c`!9kY8Gu2fG(|?uo)!n^{eMb|6OLk~4vHGAUf;7kW-U zx=Wujqq8#f)ael!VhmqgL5S(85E|{GCB_3NQG(KKp7}l$8Em;fpU1779S>C znUj3DOk_Pw4Y&+B8%OyI$V$bi*&D)g+Mvw?z7KIecMVI$DlqEwN|bH=j29crhu0fc zMU`WS5jY)bxX z>bHAKF8_>48{H{QdlSI9M=XO}D|DxMDfz?o6MNwNw}xR44wqvihDp%1>M;B(_FZ_1 z8YjDs7peLdBW&+ubhz)djlbYZ{=|)KlT`Nc|HmhmRcrs%q+w*QoDrTK{uLsYalicd zGVX6S&|=I{3a`JLtD1;G0Sp8X{2a%zW_RM($oIqa4TqyY4zT-ra@bAa?!x6}CDyWc z`w03qEbnUy@gFRxUv`CFa}FDg;WMA;dx@`2tNAZkqD}>#rY8InKiJ;>?DFZykicB) zRt0W~VN(x#4b-zx_JQZA{?NQVCbO+8ryQ?(f2-EiCb<)xw^%{Pc)OI~HGLLK*j`(% z-=)l|UsaQ^iY}TK4M)KA^qpU0ZMrlq zlkqa{=*Er z4|z6NG|)*zI{`x#nRN-C*enfoe}m@ARUtG~|1T3`6q8Z&u>&TYbz4 zFb;PJov+Q)7Q2%JRG_X*2Vzp)|J!dIMD{%kkaZvTc|SMUN*TWbcSL-Co@iqW7TGd2 zkrE&-iAozb_!LpMdnaJL{Mzjp*b5Oyel3Onux*iuocsQCosgJe8xM>YM|$)5LBuPB z%|V=u_G5jyfWlh^DX(sge9@!N1@kBIHQ|so^tNfO*9GNZvQ`xVSKjiv77)udu`=T( z+Z>v=8X~WfEA6UjCQfYPtA-%M-qg)Jd$;r3F}5OyE*NbSQfe0iqi6L-lfufR(;4IP zNzH>f0>@h|9K1ELi)k#dzGDw?iS4F;mji5n4Pg`i09WK4v;u7vFtE)tQ|%ULY=}19 zTdW-i8|CmOe5~5**N-XoBTFb zLSFuXg%#33v|TlbGGIFfyi4B@T6Y4ltSz2ZT?RA;k1^|RTigS>;>@+32Qw4N~R0e;5g+d zr0R?UC;V_kAi--jyCrd_c#}I4H|pn|~dnn9nS#G$R6fi0D$nx6MH2g?#9F?h?Cx3cv}>vB*~gg0fXbuN^Sc4I!~@N?mbR>Tb5s1&XP@ew*+Dst+x`wg`-q2h&W~w+RWYw6WjMJhHduq&0 zTrS6&>&NYSVjvYbXgLmra5QP}>iwgI#u~-ZA_97+#{q4G@0Bh_-wf$(HBGxZ$3%Zk z1CB`lNy^hivbd$3cb!)-*L-m=)=3I{Fqha?#Ei%2^&nhisj_8t$2|a2q^vLPx*9{h zN_IQ6MVh;rwhiMJ%_(*XCXd5DZMU^CZRyc9_Rc8%&^RvD+V3c+T?Z%g41tHvn2}a8 zNn$qdQkR@XlPF@!y15dXfB&Gd2FL>=p72H=3jP8x*pRqQ|D9gK9mGFS#Ytkmz$~G+ zIe+gywPFtvL1ob`Gt&?7A^qV`P?3qko&M*FO_XI&eV*amXp(+Bi-y~$cm z4XfK)s=hn=$z(Mf``oaLQah3zbmN3?(b^c_s4 z`_fVAI-t?w8!M6U1X)Xh%TT*b^`PY@D!V)J+n(XEcDU}-Olx>-kx$R38d@p70JE)D zh5DQ&eZ;j+q63yXuN7??EB%V}OYjg$oME6i%k3zvG1ljP*x?2Pm>=l2`bOb)*bGtv zZ(gDPP}JBG-gA41_n0=dEeEDcixG=*Y4W-597$OMZb=GFn}YZxd_Ef&x4a>YGJL|a zzHb}YjDC0R(^lQD7cO8v=V^ZlQe-mHo);PUI^IR?5&J#U6vnL|<}nF_<&0q_X@2q= zqH?W}L^*wcgoYoc=`L|SbW-~Bz<5i>gc0QoXh1Hu@%-+zefL1KQY zTQ{snpHXTo)gdSi-7c)VkgxE3FMa*N{+HODsPB*FJY#fFlU_8Kwi&vx`YFe7Vab<0 zgSG^PiD}CHq<++Vz(Re9Mu^~cEScfLelih-@-oi;N7_-U6cX#_!7NcyGw|RO)6)2} zX7d=SHY9`rAg28o@+IjurBvU?bUFcp-%cz)YvB7Mu2`icHM}ThAFb7WN?tPJ79BMo zW&PTp+%@F7U(`&~W%zlha0`Nc&Md90%cakn3HS=|@eSr;leCY2-D*qg5dc>{zH|j~ z8A0&anH3~Gl5pPNyO(vI1K;&VmqTN)FF8Ofo5--#U&=sbb|M)d49h zQI_kMd1U9lPU4lq?bh4T&);o(Db){Xy(!ElB-G1t-9X=~tZ9{%wa%Gbyi9a_xDSkN z0koMO;?7Um)et7mF7H~`bH~u5j-7&>D8m;M{u2=Lt%j`kz3t=F=6z*ihib&bwp8Hd z9ULKH^kU`YIrl7&ekc{<{0PHr+TQPK!wukAOWMYanc`sQ?$dma>HM)P`G<#BZM_)9 zSx2`904cCL@}eJzbJEexHdX(Jmi3%4MeL)wGq(?qUX|FdflB2NV+HuceC3=rt5?{^ z^C?BgtPtfO{&F@+v*ZAe+|Ry?f@N?Cp{IgMc&3)>_Xr=|N+J^x6%76iPx@_q=mKUI z2D`WTxaMP5sutxsr3F>q%O9`5f78hr3x!n+JnRp$?_8n#!MI2r=F#~mAO<*0i)ZgO zJE|XSzJ*By3uFhO*rml%bJo+~H^bH>5o0c0YNWF!W7&1f9{1#gb1nltyfN(9Sq>%sM@n*Ny|S#V*(4{mw`zU0F-#7T*po0?$%okY(69IM5|$whk2JO3$uC#ZY6J zQ6I0rPE%=hwJxb4wTRyI?nb460zF{oQ+g{cQ>b7yIsKU4uD_+vAwpI4u5(!u23rw5?0xXuJHUM}kuae9r`W1=`SGAOYkl8h zDyzqgtIr*uf!9et5p|#S zz1EEC;+HA4^EYFM^9c2RSKnCZnXP&I)a1T2$%^wtEij=T2W-JCl;X=?i*9xuJ}#tH zrj@40my|xn4M7p6O*yz49mD$K9&pf17filfoGaHs0~y`2rP>&9e=2Zudn68<8@V3O z(TSecAKK`&8LkA;tXB+>wKc6#3b|qqy!r^uotg4OVL_|xpl6s@?%&ipEPa$QP6?A8 z?Edk%E9FTc&kVQn6VrY70%|O+y<6yQb(=3&1SoNCQ^Temvr1%Ei%9=M6AvwUfZYNY z2gz}NKl%HdnN1=xcbnCmMy$G6!0yZ`BD^!+hW=ezde|#k2=ZeZS2}S%=zwOa8X-e3 z0hzT}TWo}e;djJ?PG^O>;J6Y z?U#?)4whs5lfe}O=pAdLuXy%2%eNmzU*Wcrg7YyMXtKe{8ilMMUhBLubpc816k)A& zU@9=sT!zJB$tB9R5>Ke=^=+e$g?YQ(S!_K zAC7JqB&~ZWorRCo>W~_PhR8=RHY^sbt-Vb*`Eobm@Z-j9eE*f(htf|rzqjF2U1+K1 zJuNwz2&@GZ1zbC|?2{FUQe7TkaX3knA#kj(*(3?56p|T5(x*@(+P)0Qm5mtlukR#WP!s(5vQ&50O0s{=) z&D4=9ThyeeMc>(4fHzDQowU@@!tNWsn#3Kp%h5le0n@U#XjQl8fCCwyHkU+ovR9)4 z-Ow0F0o(Pk$6OrF5f$7apK>~!#LfIf6x^}o@gWFWrkgbFB6_9AyZ+5)DEC{kDEeJJ zazsgT;dOkBk5o8f5Ow{(?eG^c^NhD|dqFGnLUb4$fby@L@Z|NsLcTKtHlYC|#mleO zr783*5?Z8fW2Ztqn|P)aN9cr3C^9RlYwQ)VC~#Uq{E{lolIn#HpM~XPbmvTZKQl$5 z2FE8eMV@$pmmttbhzbjKdJ+s!swEnu(3dQ4^7FxZj~-1K<$ekwm1WN>G}6_j-?wk) zQW!!4=an9|?F}1nT14{474XANLk`6@P1J=>am%%x8{G@O6MlA`Np!0fu-|D6J@jV9 ziPoBXFRpqISWTEF3Z zi*OwH7eHiz8|d*tCc|Wt;L1fQ^XSW;?+w+me3#IGx_NAV6lF~(C!^=S z_zso0d7;qVPw}k2Dsj=!R6#s74FK#i0vz?{le_FLvvtlcySrEzYfO)P1*62qAN<_r zCkEf1o5Df>aJxMM5a8`k)BwPZHJ;1Dzl_2GH_E@p`~S22bR3%gPu3V0iJ7vVV}{{g zNBqW9@tK4GqO}0%^N&S}Ks9|esRtGu$#w*TwkDBU_y6kbx`LX}wrC*q4goe*2T4!x@hT6Jl?>R>z zyP;L)PbPf^h=7!Eml$7ECwOxTDdHZUvk<>?z^c6!YaK^m8Q_7juv-zNBmF?r zY<2O&_YIoNQjJ$y%=av?QZeDUIe+$B)MP|{X#zR#CDf$|RaGTIWzRKXQgLam*+PHR z>WZXmeNNW@wT$LXIpE7B-!?{(c`DGayz?KvBvG$E%V%Cbyx_PLVEFhO%?1kB#5J}u zGu!LLwZP9%SREB=XRDq`!$v=YhiCIH3}>NpBxTmg?4N>tAA7c?6UYes)dP@jk5t%^ zTT$F|^xg?HPiWADGovh5N+KU-Boh8O(8$ql8sq7BLF%)@$G02e7vl#94(Fw7LS9}% zTw!($Fm-#Bp*L*DBHaEYeNK7$gJLaqr>K9#Zf8t@-@b*6BXm2xl6-KZeAu0n!~GFU z5RD&Jw1T-d1sm5&Wh(M%--9JEkH~Z^{Jh3Ee2HQckRAzbK~;VE8eaR3mgYVlKK8t-Xj@b4^Tv*p-vDf*KsKpFF<&YTKB!8Wf{^> zB)OkvO%~m{a){=waJ*2IH_!WduR!cAOol{{1y-nh3MPey6r3+s%p-Y92k1)R3i2*j z5;l4J0J|S434By;1qX=(bzQibomAq{`_4hWgu9Sr#DMOkAM%!=M7Rqcu2UB;814+V z;2-s7`uQ*_2KZ-}w`nwQYSdoG&BfU(%c=LBs~$?ryXq+>??;+c#+P1Ah(xt zND;JZO1`;F_=x5mXj_WVlRqf9aSj8ZpvAW8Atg10DKnBsZG_UCM*ff2hD2CpXw{7R zgYEydF(3vw0#{QDP5gJaVwra5dtSoO_2mZ9mPjb%??Kc$aX8x*MM+#(e|380*UJ)r!anp zDd8HUd|P>rE%$Rsc4K*&Xy8knvM<`_kHzBSE&jZ_gFziJ&ZNTxFRC9Ag1&%JOO^7h zfn%@?vpYxlxIJV>L=)-2>)_WXhx1}l?E2UU-iy-i5c9YfoFcOc^_5rK%Fq)DC#4&A zi_7Ig<5TjEaG@XXh0RfX!#d9CtM&ffx^ZUFI6v>Y-d-mwn7l|?gmj4w{RVw%x8WVu zJ!;0o!iRmp?k_lIiFXLEv^P3)J*t$8^X@L7E>Q$ST6oW>Wz4NGkGOU^ST2hZ*5dUE z*nMzJSYIe|^&iCFJ7mCkDEI$)`V8VG-W$<7pSCV1p-pSO=1qn#DXGCvvsR7INvQ%HQ zh10!Mq!6PvD;#~a?K>oa9XcYN44WkQ@M0y!cw->@V>x&I3CE_d!+pxtpOPZa^yw`A zL8fB?ftMs@6{)oosB*Y_>@yZ<7L;G-V@E10w!0B~9V5KQHGGUR)U{HFl`Dw5ERc4o zf&(0;M72X8o1){JhkNvSai^yR=kJaN5_GU!0RYSGddw!~buNwG@@2tQlEZiBFff{a zJH`AN^rb;{%P*&f^fZmj9GAFmliZwP@7F)_wXl$QYwNhn8=S!?$GT_R;4ot*|$G zVd@EKr!E-wV6O9Q{15{Ts3giuG!S{E)92}=()?D9Dqz}taoGMgEs;T5Jb;AbWJ`7q z?C)0AUPuR3Uqf48vQ4=(pBpA`NLna_8)7+rO($icqs_H$vK83&%Bp1wqqWTFExElA zaboMX0(iM&-zCnKb;W!j3G&ECPn`@MRb^YTv6DP!Q*=vy?XC^uA`ltW^UBAw(|NYbt5LZ;{{ z9VtX1=FfFunD{0;M#w}{@+n;=?whz9AGEKMSb+zXE;F?xmVn<$M_;F~)7DIYvK>mz zn!90^b>H$u%cf+J?7TqD91cnB_m*wV_G+?hLUVAXnEhH(ncWtF`ir(9{1$jLoSICg zS4cfZ6L(_OFjeyHe5X4ceT{YGN^R~4lWPOQ#maC9PwBOsiok2{xQ!T)T4zmL61P=q zMFd8ig0-s)7djT`614MNkCtWb07sNH;N3Dz88Edsc?%1y%6zSNQ}3kB>IM*QNg20}O92>!7}zx1Je5S6QaiS_hGGu0zklO^If zsqpj3jLo7(gi-{_u+dUck>9_6>*gvo-5N&>J6|=)6L@FKs~iY@Q>LaTT=2;E2QJm# z**6L0u438lA3PYkF{`$6U+&zAR@Qs{S`xB@d2o~n#0@(Fa0t?%t5t06@^i02jiMsvo6L*e2k(vVdVaunet8q6Xj{% z48F^!b`033#5ybAv5wlBo9LP(fEwc7Zp8qsZ@C+l`>p3^ymJdV632jY1QoEnxhyH z1H`B*TDwNCd#Hl-jlk`5-|%yzg=8Dw58XdD2)gmqYHvW>IN9&)iR^SxQ$d2aOm!hr z5=qr>$L$A_UL`(weVQ&WEmJI0=9}hb3S*FGTQWqBmBHYf+`7DIO^i_S4mQSmOL4az zk!HY>!zx!q{@hk%^E^&J+|YELBSB(K+wnH>9)H_3#ZsMM;kdLg*Hv1RlM=ZX43S!E z5u2yb#J`OT;~_l$KAhf9QB>K(T)h87TNt2)AEjA7q literal 0 HcmV?d00001 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FlywooF745/README.md b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF745/README.md index a491a15a10a64c..6c4817547a3bb3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/FlywooF745/README.md +++ b/libraries/AP_HAL_ChibiOS/hwdef/FlywooF745/README.md @@ -31,7 +31,13 @@ The Flywoo GOKU GN 745 AIO is a flight controller produced by [Flywoo](https://f ## Pinout -![GOKU GN 745 40A AIO](GOKUGN745AIO_Pinout.png "GOKU GN 745 40A AIO") +This board currently has two versions produced, with different pinouts. This is the original v1.0 board. + +![GOKU GN 745 40A AIO v1.0](GOKUGN745AIO_v1.0_Pinout.png "GOKU GN 745 40A AIO v1.0") + +The newer v1.2 board is shown below. Unfortunately, due to the reduced number of pads, some features, such as motors 5-8, are no longer available. + +![GOKU GN 745 40A AIO v1.2](GOKUGN745AIO_v1.2_Pinout.jpg "GOKU GN 745 40A AIO v1.2") ## UART Mapping From b65313303f96aea4613fd6b1390bc1c64dabfddd Mon Sep 17 00:00:00 2001 From: David Buzz Date: Mon, 8 Jan 2024 10:46:07 +1000 Subject: [PATCH 0448/1335] AP_HAL_ESP32: analog warning fix --- libraries/AP_HAL_ESP32/AnalogIn.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ESP32/AnalogIn.cpp b/libraries/AP_HAL_ESP32/AnalogIn.cpp index 0cb88f3e17384c..6ae04bc489591e 100644 --- a/libraries/AP_HAL_ESP32/AnalogIn.cpp +++ b/libraries/AP_HAL_ESP32/AnalogIn.cpp @@ -70,7 +70,7 @@ const AnalogIn::pin_info AnalogIn::pin_config[] = HAL_ESP32_ADC_PINS; #define DEFAULT_VREF 1100 //Use adc2_vref_to_gpio() to obtain a better estimate #define NO_OF_SAMPLES 256 //Multisampling -static const adc_atten_t atten = ADC_ATTEN_DB_11; +static const adc_atten_t atten = ADC_ATTEN_DB_12; //ardupin is the ardupilot assigned number, starting from 1-8(max) // 'pin' and _pin is a macro like 'ADC1_GPIO35_CHANNEL' from board config .h From 511659e6ee71b50ce183e8459250dcbed73b64f5 Mon Sep 17 00:00:00 2001 From: JanMaciuk <38810823+JanMaciuk@users.noreply.github.com> Date: Tue, 2 Jan 2024 23:49:18 +0100 Subject: [PATCH 0449/1335] Copter: Throw mode check altitude within params --- ArduCopter/Parameters.cpp | 14 ++++++++++++++ ArduCopter/Parameters.h | 4 ++++ ArduCopter/mode_throw.cpp | 17 +++++++++++++++-- 3 files changed, 33 insertions(+), 2 deletions(-) diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index f56ef3b0205554..e3b949b7c322f5 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -696,6 +696,20 @@ const AP_Param::Info Copter::var_info[] = { // @Values: 0:Stopped,1:Running // @User: Standard GSCALAR(throw_motor_start, "THROW_MOT_START", (float)ModeThrow::PreThrowMotorState::STOPPED), + + // @Param: THROW_ALT_MIN + // @DisplayName: Throw mode minimum altitude + // @Description: Minimum altitude above which Throw mode will detect a throw or a drop - 0 to disable the check + // @Units: m + // @User: Advanced + GSCALAR(throw_altitude_min, "THROW_ALT_MIN", 0), + + // @Param: THROW_ALT_MAX + // @DisplayName: Throw mode maximum altitude + // @Description: Maximum altitude under which Throw mode will detect a throw or a drop - 0 to disable the check + // @Units: m + // @User: Advanced + GSCALAR(throw_altitude_max, "THROW_ALT_MAX", 0), #endif #if OSD_ENABLED || OSD_PARAM_ENABLED diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index e59bf2238788b6..3d8b62b96d936c 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -383,6 +383,8 @@ class Parameters { // 254,255: reserved k_param_vehicle = 257, // vehicle common block of parameters + k_param_throw_altitude_min, + k_param_throw_altitude_max, // the k_param_* space is 9-bits in size // 511: reserved @@ -463,6 +465,8 @@ class Parameters { #if MODE_THROW_ENABLED == ENABLED AP_Enum throw_motor_start; + AP_Int16 throw_altitude_min; // minimum altitude in m above which a throw can be detected + AP_Int16 throw_altitude_max; // maximum altitude in m below which a throw can be detected #endif AP_Int16 rc_speed; // speed of fast RC Channels in Hz diff --git a/ArduCopter/mode_throw.cpp b/ArduCopter/mode_throw.cpp index c9ff702e3fd887..a2f71ff42f24d4 100644 --- a/ArduCopter/mode_throw.cpp +++ b/ArduCopter/mode_throw.cpp @@ -272,8 +272,21 @@ bool ModeThrow::throw_detected() // Check if the accel length is < 1.0g indicating that any throw action is complete and the copter has been released bool no_throw_action = copter.ins.get_accel().length() < 1.0f * GRAVITY_MSS; - // High velocity or free-fall combined with increasing height indicate a possible air-drop or throw release - bool possible_throw_detected = (free_falling || high_speed) && changing_height && no_throw_action; + // fetch the altitude above home + float altitude_above_home; // Use altitude above home if it is set, otherwise relative to EKF origin + if (ahrs.home_is_set()) { + ahrs.get_relative_position_D_home(altitude_above_home); + altitude_above_home = -altitude_above_home; // altitude above home is returned as negative + } else { + altitude_above_home = inertial_nav.get_position_z_up_cm() * 0.01f; // centimeters to meters + } + + // Check that the altitude is within user defined limits + const bool height_within_params = (g.throw_altitude_min == 0 || altitude_above_home > g.throw_altitude_min) && (g.throw_altitude_max == 0 || (altitude_above_home < g.throw_altitude_max)); + + // High velocity or free-fall combined with increasing height indicate a possible air-drop or throw release + bool possible_throw_detected = (free_falling || high_speed) && changing_height && no_throw_action && height_within_params; + // Record time and vertical velocity when we detect the possible throw if (possible_throw_detected && ((AP_HAL::millis() - free_fall_start_ms) > 500)) { From eb10b8196466f4b53e8d018cb6c4cb37804d1992 Mon Sep 17 00:00:00 2001 From: Bob Long Date: Tue, 9 Jan 2024 16:49:46 +1100 Subject: [PATCH 0450/1335] Tools: uploader.py: set write_timeout This is needed to prevent Windows from hanging when trying to write to "Standard Serial over Bluetooth" ports. --- Tools/scripts/uploader.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/scripts/uploader.py b/Tools/scripts/uploader.py index a4872f2844ff70..b926b26c232795 100755 --- a/Tools/scripts/uploader.py +++ b/Tools/scripts/uploader.py @@ -275,7 +275,7 @@ def __init__(self, self.force_erase = force_erase # open the port, keep the default timeout short so we can poll quickly - self.port = serial.Serial(portname, baudrate_bootloader, timeout=2.0) + self.port = serial.Serial(portname, baudrate_bootloader, timeout=2.0, write_timeout=2.0) self.baudrate_bootloader = baudrate_bootloader if baudrate_bootloader_flash is not None: self.baudrate_bootloader_flash = baudrate_bootloader_flash From d2400ad39b0d19fded3dffba935dcba510db9e6a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 12 Jul 2023 21:08:10 +1000 Subject: [PATCH 0451/1335] AP_OpticalFlow: correct names of variables in HereFlow OF driver my guess is that the heavy maths was moved out of the timer function --- libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp | 12 +++++++----- libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h | 2 +- 2 files changed, 8 insertions(+), 6 deletions(-) diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp index e7a94704420d00..123b3408c3abd3 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.cpp @@ -53,8 +53,8 @@ void AP_OpticalFlow_HereFlow::handle_measurement(AP_DroneCAN *ap_dronecan, const if (_ap_dronecan == ap_dronecan && _node_id == transfer.source_node_id) { WITH_SEMAPHORE(_driver->_sem); _driver->new_data = true; - _driver->flowRate = Vector2f(msg.flow_integral[0], msg.flow_integral[1]); - _driver->bodyRate = Vector2f(msg.rate_gyro_integral[0], msg.rate_gyro_integral[1]); + _driver->flow_integral = Vector2f(msg.flow_integral[0], msg.flow_integral[1]); + _driver->rate_gyro_integral = Vector2f(msg.rate_gyro_integral[0], msg.rate_gyro_integral[1]); _driver->integral_time = msg.integration_interval; _driver->surface_quality = msg.quality; } @@ -79,9 +79,11 @@ void AP_OpticalFlow_HereFlow::_push_state(void) float flowScaleFactorY = 1.0f + 0.001f * flowScaler.y; float integralToRate = 1.0f / integral_time; //Convert to Raw Flow measurement to Flow Rate measurement - state.flowRate = Vector2f(flowRate.x * flowScaleFactorX, - flowRate.y * flowScaleFactorY) * integralToRate; - state.bodyRate = bodyRate * integralToRate; + state.flowRate = Vector2f{ + flow_integral.x * flowScaleFactorX, + flow_integral.y * flowScaleFactorY + } * integralToRate; + state.bodyRate = rate_gyro_integral * integralToRate; state.surface_quality = surface_quality; _applyYaw(state.flowRate); _applyYaw(state.bodyRate); diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h index 8b61a87bf7cd91..afc75841631a07 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_HereFlow.h @@ -21,7 +21,7 @@ class AP_OpticalFlow_HereFlow : public OpticalFlow_backend { private: - Vector2f flowRate, bodyRate; + Vector2f flow_integral, rate_gyro_integral; uint8_t surface_quality; float integral_time; bool new_data; From 6038a4d8c73cc8dfa674bb003a35d11ba8c120e7 Mon Sep 17 00:00:00 2001 From: Mirko Denecke Date: Tue, 9 Jan 2024 18:47:54 +0100 Subject: [PATCH 0452/1335] AR_Motors: fix prearm for omni outputs --- libraries/AR_Motors/AP_MotorsUGV.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AR_Motors/AP_MotorsUGV.cpp b/libraries/AR_Motors/AP_MotorsUGV.cpp index c9e351b2be03af..90b8ef99157125 100644 --- a/libraries/AR_Motors/AP_MotorsUGV.cpp +++ b/libraries/AR_Motors/AP_MotorsUGV.cpp @@ -494,7 +494,8 @@ bool AP_MotorsUGV::pre_arm_check(bool report) const !have_throttle && !SRV_Channels::function_assigned(SRV_Channel::k_steering) && !SRV_Channels::function_assigned(SRV_Channel::k_scripting1) && - !has_sail()) { + !has_sail() && + !is_omni()) { if (report) { GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "PreArm: no motor, sail or scripting outputs defined"); } From fa5e58d652e7dfc06188d0d6d8c2feefdf30bb42 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 29 Dec 2023 16:10:52 +0900 Subject: [PATCH 0453/1335] AP_Mount: switch to RC_TARGETING on RC input --- libraries/AP_Mount/AP_Mount_Backend.cpp | 41 +++++++++++++++++++ libraries/AP_Mount/AP_Mount_Backend.h | 11 +++++ libraries/AP_Mount/AP_Mount_Gremsy.cpp | 3 ++ libraries/AP_Mount/AP_Mount_SToRM32.cpp | 3 ++ .../AP_Mount/AP_Mount_SToRM32_serial.cpp | 3 ++ libraries/AP_Mount/AP_Mount_Scripting.cpp | 3 ++ libraries/AP_Mount/AP_Mount_Servo.cpp | 3 ++ libraries/AP_Mount/AP_Mount_Siyi.cpp | 3 ++ libraries/AP_Mount/AP_Mount_SoloGimbal.cpp | 3 ++ libraries/AP_Mount/AP_Mount_Viewpro.cpp | 3 ++ libraries/AP_Mount/AP_Mount_Xacti.cpp | 3 ++ 11 files changed, 79 insertions(+) diff --git a/libraries/AP_Mount/AP_Mount_Backend.cpp b/libraries/AP_Mount/AP_Mount_Backend.cpp index 8545d75b90bf23..7e1f28d3d5df16 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.cpp +++ b/libraries/AP_Mount/AP_Mount_Backend.cpp @@ -570,6 +570,47 @@ void AP_Mount_Backend::calculate_poi() } #endif +// change to RC_TARGETING mode if rc inputs have changed by more than the dead zone +// should be called on every update +void AP_Mount_Backend::set_rctargeting_on_rcinput_change() +{ + // exit immediately if no RC input + if (!rc().has_valid_input()) { + return; + } + + const RC_Channel *roll_ch = rc().find_channel_for_option(_instance == 0 ? RC_Channel::AUX_FUNC::MOUNT1_ROLL : RC_Channel::AUX_FUNC::MOUNT2_ROLL); + const RC_Channel *pitch_ch = rc().find_channel_for_option(_instance == 0 ? RC_Channel::AUX_FUNC::MOUNT1_PITCH : RC_Channel::AUX_FUNC::MOUNT2_PITCH); + const RC_Channel *yaw_ch = rc().find_channel_for_option(_instance == 0 ? RC_Channel::AUX_FUNC::MOUNT1_YAW : RC_Channel::AUX_FUNC::MOUNT2_YAW); + + // get rc input + const int16_t roll_in = (roll_ch == nullptr) ? 0 : roll_ch->get_radio_in(); + const int16_t pitch_in = (pitch_ch == nullptr) ? 0 : pitch_ch->get_radio_in(); + const int16_t yaw_in = (yaw_ch == nullptr) ? 0 : yaw_ch->get_radio_in(); + + // if not in RC_TARGETING or RETRACT modes then check for RC change + if (get_mode() != MAV_MOUNT_MODE_RC_TARGETING && get_mode() != MAV_MOUNT_MODE_RETRACT) { + // get dead zones + const int16_t roll_dz = (roll_ch == nullptr) ? 10 : MAX(roll_ch->get_dead_zone(), 10); + const int16_t pitch_dz = (pitch_ch == nullptr) ? 10 : MAX(pitch_ch->get_dead_zone(), 10); + const int16_t yaw_dz = (yaw_ch == nullptr) ? 10 : MAX(yaw_ch->get_dead_zone(), 10); + + // check if RC input has changed by more than the dead zone + if ((abs(last_rc_input.roll_in - roll_in) > roll_dz) || + (abs(last_rc_input.pitch_in - pitch_in) > pitch_dz) || + (abs(last_rc_input.yaw_in - yaw_in) > yaw_dz)) { + set_mode(MAV_MOUNT_MODE_RC_TARGETING); + } + } + + // if in RC_TARGETING or RETRACT mode then store last RC input + if (get_mode() == MAV_MOUNT_MODE_RC_TARGETING || get_mode() == MAV_MOUNT_MODE_RETRACT) { + last_rc_input.roll_in = roll_in; + last_rc_input.pitch_in = pitch_in; + last_rc_input.yaw_in = yaw_in; + } +} + // get pilot input (in the range -1 to +1) received through RC void AP_Mount_Backend::get_rc_input(float& roll_in, float& pitch_in, float& yaw_in) const { diff --git a/libraries/AP_Mount/AP_Mount_Backend.h b/libraries/AP_Mount/AP_Mount_Backend.h index b88ddf42bf760c..d2f97273608b5b 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.h +++ b/libraries/AP_Mount/AP_Mount_Backend.h @@ -240,6 +240,10 @@ class AP_Mount_Backend void calculate_poi(); #endif + // change to RC_TARGETTING mode if rc inputs have changed by more than the dead zone + // should be called on every update + void set_rctargeting_on_rcinput_change(); + // get pilot input (in the range -1 to +1) received through RC void get_rc_input(float& roll_in, float& pitch_in, float& yaw_in) const; @@ -308,6 +312,13 @@ class AP_Mount_Backend uint32_t _last_warning_ms; // system time of last warning sent to GCS + // structure holding the last RC inputs + struct { + int16_t roll_in; + int16_t pitch_in; + int16_t yaw_in; + } last_rc_input; + // structure holding mavlink sysid and compid of controller of this gimbal // see MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE and GIMBAL_MANAGER_STATUS struct { diff --git a/libraries/AP_Mount/AP_Mount_Gremsy.cpp b/libraries/AP_Mount/AP_Mount_Gremsy.cpp index b9bf372a680646..6efe6b7ec4b39e 100644 --- a/libraries/AP_Mount/AP_Mount_Gremsy.cpp +++ b/libraries/AP_Mount/AP_Mount_Gremsy.cpp @@ -20,6 +20,9 @@ void AP_Mount_Gremsy::update() return; } + // change to RC_TARGETING mode if RC input has changed + set_rctargeting_on_rcinput_change(); + // update based on mount mode switch (get_mode()) { diff --git a/libraries/AP_Mount/AP_Mount_SToRM32.cpp b/libraries/AP_Mount/AP_Mount_SToRM32.cpp index 1c1e5da3eadc1e..de3c8035c989a9 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32.cpp +++ b/libraries/AP_Mount/AP_Mount_SToRM32.cpp @@ -18,6 +18,9 @@ void AP_Mount_SToRM32::update() return; } + // change to RC_TARGETING mode if RC input has changed + set_rctargeting_on_rcinput_change(); + // flag to trigger sending target angles to gimbal bool resend_now = false; diff --git a/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp b/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp index 518b698ef69e76..928a40a297496b 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp +++ b/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp @@ -29,6 +29,9 @@ void AP_Mount_SToRM32_serial::update() read_incoming(); // read the incoming messages from the gimbal + // change to RC_TARGETING mode if RC input has changed + set_rctargeting_on_rcinput_change(); + // flag to trigger sending target angles to gimbal bool resend_now = false; diff --git a/libraries/AP_Mount/AP_Mount_Scripting.cpp b/libraries/AP_Mount/AP_Mount_Scripting.cpp index 9eb738503919bc..c2b93304e67ee5 100644 --- a/libraries/AP_Mount/AP_Mount_Scripting.cpp +++ b/libraries/AP_Mount/AP_Mount_Scripting.cpp @@ -15,6 +15,9 @@ extern const AP_HAL::HAL& hal; // update mount position - should be called periodically void AP_Mount_Scripting::update() { + // change to RC_TARGETING mode if RC input has changed + set_rctargeting_on_rcinput_change(); + // update based on mount mode switch (get_mode()) { // move mount to a "retracted" position. To-Do: remove support and replace with a relaxed mode? diff --git a/libraries/AP_Mount/AP_Mount_Servo.cpp b/libraries/AP_Mount/AP_Mount_Servo.cpp index 196b79edff0a89..8c59eb6abfd28e 100644 --- a/libraries/AP_Mount/AP_Mount_Servo.cpp +++ b/libraries/AP_Mount/AP_Mount_Servo.cpp @@ -27,6 +27,9 @@ void AP_Mount_Servo::init() // update mount position - should be called periodically void AP_Mount_Servo::update() { + // change to RC_TARGETING mode if RC input has changed + set_rctargeting_on_rcinput_change(); + auto mount_mode = get_mode(); switch (mount_mode) { // move mount to a "retracted position" or to a position where a fourth servo can retract the entire mount into the fuselage diff --git a/libraries/AP_Mount/AP_Mount_Siyi.cpp b/libraries/AP_Mount/AP_Mount_Siyi.cpp index 5cc1330bfb7670..2854a28c7466c5 100644 --- a/libraries/AP_Mount/AP_Mount_Siyi.cpp +++ b/libraries/AP_Mount/AP_Mount_Siyi.cpp @@ -103,6 +103,9 @@ void AP_Mount_Siyi::update() // run zoom control update_zoom_control(); + // change to RC_TARGETING mode if RC input has changed + set_rctargeting_on_rcinput_change(); + // Get the target angles or rates first depending on the current mount mode switch (get_mode()) { case MAV_MOUNT_MODE_RETRACT: { diff --git a/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp b/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp index 907b09a0d4574c..6dbf8cdbd3b260 100644 --- a/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp +++ b/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp @@ -31,6 +31,9 @@ void AP_Mount_SoloGimbal::update() return; } + // change to RC_TARGETING mode if RC input has changed + set_rctargeting_on_rcinput_change(); + // update based on mount mode switch(get_mode()) { // move mount to a "retracted" position. we do not implement a separate servo based retract mechanism diff --git a/libraries/AP_Mount/AP_Mount_Viewpro.cpp b/libraries/AP_Mount/AP_Mount_Viewpro.cpp index 07608d689bfff1..a1180f85e3e58e 100644 --- a/libraries/AP_Mount/AP_Mount_Viewpro.cpp +++ b/libraries/AP_Mount/AP_Mount_Viewpro.cpp @@ -76,6 +76,9 @@ void AP_Mount_Viewpro::update() // send vehicle attitude and position send_m_ahrs(); + // change to RC_TARGETING mode if RC input has changed + set_rctargeting_on_rcinput_change(); + // if tracking is active we do not send new targets to the gimbal if (_last_tracking_status == TrackingStatus::SEARCHING || _last_tracking_status == TrackingStatus::TRACKING) { return; diff --git a/libraries/AP_Mount/AP_Mount_Xacti.cpp b/libraries/AP_Mount/AP_Mount_Xacti.cpp index 9f210993d4350d..adc752fd46947c 100644 --- a/libraries/AP_Mount/AP_Mount_Xacti.cpp +++ b/libraries/AP_Mount/AP_Mount_Xacti.cpp @@ -110,6 +110,9 @@ void AP_Mount_Xacti::update() return; } + // change to RC_TARGETING mode if RC input has changed + set_rctargeting_on_rcinput_change(); + // update based on mount mode switch (get_mode()) { // move mount to a "retracted" position. To-Do: remove support and replace with a relaxed mode? From 416a41e75646cc464380cb5cd6f7d6dfb5f7cb25 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Mon, 8 Jan 2024 21:05:43 +0000 Subject: [PATCH 0454/1335] AP_HAL_ChibiOS: Only test SPI clock if SPI is enabled --- libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp b/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp index e362804b91a966..eb741e1ae7c520 100644 --- a/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp +++ b/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp @@ -227,7 +227,7 @@ static void main_loop() hal.serial(0)->begin(SERIAL0_BAUD); -#ifdef HAL_SPI_CHECK_CLOCK_FREQ +#if (HAL_USE_SPI == TRUE) && defined(HAL_SPI_CHECK_CLOCK_FREQ) // optional test of SPI clock frequencies ChibiOS::SPIDevice::test_clock_freq(); #endif From 8bfd8f2403e3a7f8247737c6b592ec134028990d Mon Sep 17 00:00:00 2001 From: Ferruccio Vicari Date: Tue, 5 Dec 2023 07:07:10 +0000 Subject: [PATCH 0455/1335] AP_Scripting: script for idle control (gas helicopters) allows manual and/or automatic engine rpm control during ground idling fix for conversion to float rename fix --- .../applets/Heli_idle_control.lua | 212 ++++++++++++++++++ .../AP_Scripting/applets/Heli_idle_control.md | 17 ++ 2 files changed, 229 insertions(+) create mode 100644 libraries/AP_Scripting/applets/Heli_idle_control.lua create mode 100644 libraries/AP_Scripting/applets/Heli_idle_control.md diff --git a/libraries/AP_Scripting/applets/Heli_idle_control.lua b/libraries/AP_Scripting/applets/Heli_idle_control.lua new file mode 100644 index 00000000000000..16e7de0a0056bf --- /dev/null +++ b/libraries/AP_Scripting/applets/Heli_idle_control.lua @@ -0,0 +1,212 @@ +-- idle_control.lua: a closed loop control throttle control while on ground idle (trad-heli) + +local PARAM_TABLE_KEY = 73 +local PARAM_TABLE_PREFIX = 'IDLE_' +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 30), 'could not add param table') + +function bind_add_param(name, idx, default_value) + assert(param:add_param(PARAM_TABLE_KEY, idx, name, default_value), string.format('could not add param %s', name)) + return Parameter(PARAM_TABLE_PREFIX .. name) +end + +-- parameters for idle control + +IDLE_GAIN_I = bind_add_param('GAIN_I', 1, 0.05) +IDLE_GAIN_P = bind_add_param('GAIN_P', 2, 0.25) +IDLE_GAIN_MAX = bind_add_param('GAIN_MAX', 3, 1) +IDLE_MAX = bind_add_param('MAX', 4, 17) +IDLE_RANGE = bind_add_param('RANGE', 5, 300) +IDLE_SETPOINT = bind_add_param('SETPOINT', 6, 600) +IDLE_RPM_ENABLE = bind_add_param('RPM_ENABLE', 7, 0) + +-- internal variables + +local thr_out = nil +local idle_control_active = false +local idle_control_active_last = false +local last_scaled_output = nil +local idle_default = nil +local ramp_up_complete = false +local idle_adjusted = false +local last_idc_time = nil +local time_now = nil +local pv = nil +local thr_ctl = nil +local thr_out_last = nil +local pot_input = rc:find_channel_for_option(301) +local switch_rsc = rc:find_channel_for_option(32) +local rsc_output = SRV_Channels:find_channel(31) +local SERVO_MAX = Parameter('SERVO' .. (rsc_output+1) .. '_MAX') +local SERVO_MIN = Parameter('SERVO' .. (rsc_output+1) .. '_MIN') +local SERVO_REV = Parameter('SERVO' .. (rsc_output+1) .. '_REVERSED') +local servo_range = SERVO_MAX:get() - SERVO_MIN:get() +local H_RSC_IDLE = Parameter('H_RSC_IDLE') +local H_RSC_RUNUP_TIME = Parameter('H_RSC_RUNUP_TIME') + +-- map function + +function map(x, in_min, in_max, out_min, out_max) + return out_min + (x - in_min)*(out_max - out_min)/(in_max - in_min) +end + +-- constrain function + +local function constrain(v, vmin, vmax) + if v < vmin then + v = vmin + end + if v > vmax then + v = vmax + end + return v +end + +-- PI controller function +local function PI_controller(kP,kI,iMax,min,max) + + local self = {} + + local _kP = kP + local _kI = kI + local _iMax = iMax + local _min = min + local _max = max + local _last_t = nil + local _I = 0 + local _total = 0 + local _counter = 0 + + function self.update(target, current) + local now = millis() + if not _last_t then + _last_t = now + end + local dt = (now - _last_t):tofloat()*0.001 + _last_t = now + local err = target - current + _counter = _counter + 1 + local P = _kP:get() * err + if ((_total < _max and _total > _min) or (_total >= _max and err < 0) or (_total <= _min and err > 0)) then + _I = _I + _kI:get() * err * dt + end + if _iMax:get() > 0 then + _I = constrain(_I, -_iMax:get(), iMax:get()) + end + local ret = P + _I + _total = ret + return ret + end + + function self.reset(integrator) + _I = integrator + end + + return self +end + +local thr_PI = PI_controller(IDLE_GAIN_P, IDLE_GAIN_I, IDLE_GAIN_MAX, 0, 1) + +-- main update function + +function update() + + local armed = arming:is_armed() + + -- aux potentiometer for manual adjusting of idle + + local pot_pos = pot_input:norm_input() + local thr_man = map(pot_pos,-1,1,0,1) + + if armed == false then + idle_default = H_RSC_IDLE:get() + idle_control_active = false + ramp_up_complete = false + idle_adjusted = false + thr_PI.reset(0) + else + if switch_rsc:get_aux_switch_pos() == 0 and vehicle:get_likely_flying() == false then + if H_RSC_IDLE:get()~= idle_default then + H_RSC_IDLE:set(idle_default) + gcs:send_text(5, "H_RSC_IDLE set to:".. tostring(H_RSC_IDLE:get())) + end + if IDLE_RPM_ENABLE:get() == 0 then + ramp_up_complete = false + idle_adjusted = false + thr_out = H_RSC_IDLE:get() + thr_man*(IDLE_MAX:get() - H_RSC_IDLE:get()) + else + if thr_man == 0 then + idle_control_active = false + if idle_control_active_last ~= idle_control_active then + gcs:send_text(5, "idle control: OFF") + end + thr_out = H_RSC_IDLE:get() + thr_ctl = 0 + thr_PI.reset(0) + else + local rpm_current = RPM:get_rpm((IDLE_RPM_ENABLE:get())-1) + ramp_up_complete = false + idle_adjusted = false + if rpm_current < (IDLE_SETPOINT:get() - IDLE_RANGE:get()) then + thr_out = H_RSC_IDLE:get() + thr_man*(IDLE_MAX:get() - H_RSC_IDLE:get()) + thr_out_last = thr_out + elseif rpm_current > (IDLE_SETPOINT:get() + IDLE_RANGE:get()) then + thr_out = H_RSC_IDLE:get() + thr_out_last = thr_out + else + -- throttle output set from the PI controller + pv = rpm_current/(IDLE_SETPOINT:get()) + thr_ctl = thr_PI.update(1, pv) + thr_ctl = constrain(thr_ctl,0,1) + thr_out = H_RSC_IDLE:get() + thr_ctl*(IDLE_MAX:get() - H_RSC_IDLE:get()) + if thr_out_last == nil then + thr_out_last = 0 + end + thr_out = constrain(thr_out, thr_out_last-0.05, thr_out_last+0.05) + thr_out_last = thr_out + idle_control_active = true + end + if idle_control_active_last ~= idle_control_active then + gcs:send_text(5, "idle control: ON") + end + end + end + last_idc_time = millis() + last_scaled_output = thr_out/100 + if SERVO_REV:get() == 0 then + SRV_Channels:set_output_pwm_chan_timeout(rsc_output, math.floor((last_scaled_output*servo_range)+SERVO_MIN:get()), 150) + else + SRV_Channels:set_output_pwm_chan_timeout(rsc_output, math.floor(SERVO_MAX:get()-(last_scaled_output*servo_range)), 150) + end + else + -- motor interlock disabled, armed state, flight + idle_control_active = false + if idle_control_active_last ~= idle_control_active then + gcs:send_text(5, "idle control: deactivated") + end + if ramp_up_complete ~= true then + time_now = millis() + if ((time_now-last_idc_time):tofloat()*0.001) < H_RSC_RUNUP_TIME:get() then + if idle_adjusted ~= true then + H_RSC_IDLE:set(last_scaled_output*100) + idle_adjusted = true + gcs:send_text(5, "H_RSC_IDLE updated for ramp up:".. tostring(H_RSC_IDLE:get())) + end + else + if H_RSC_IDLE:get()~= idle_default then + H_RSC_IDLE:set(idle_default) + gcs:send_text(5, "H_RSC_IDLE default restored:".. tostring(H_RSC_IDLE:get())) + end + ramp_up_complete = true + end + end + end + -- update notify variable + idle_control_active_last = idle_control_active + end + + return update, 100 -- 10Hz rate +end + +gcs:send_text(5, "idle_control_running") + +return update() diff --git a/libraries/AP_Scripting/applets/Heli_idle_control.md b/libraries/AP_Scripting/applets/Heli_idle_control.md new file mode 100644 index 00000000000000..39fb88684e0207 --- /dev/null +++ b/libraries/AP_Scripting/applets/Heli_idle_control.md @@ -0,0 +1,17 @@ +# Idle Control + +Allows manual or automatic rpm control for heli while on ground idle condition + +# Parameters + +IDLE_GAIN_I = integrative gain of the controller +IDLE_GAIN_P = proportional gain of the controller +IDLE_GAIN_MAX = IMAX for integrative +IDLE_MAX = maximum throttle position, shall be set low enough to prevent clutch engagement/slipping or lower than first point of throttle curve +IDLE_RANGE = rpm range of operation for the idle control +IDLE_SETPOINT = desired rpm setpoint +IDLE_RPM_ENABLE = 0 for manual throttle control // 1 for RPM1 targeting // 2 for RPM2 targeting + +# How To Use + +set RCx_OPTION to 301 to enable idle control from an auxiliary potentiometer From 2ba3ac0a9e82b86189481d751ae34c056c892514 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 10 Jan 2024 07:36:47 +1100 Subject: [PATCH 0456/1335] AP_Networking: fixed a lockup bug in network ports we need to not hold the write semaphore when calling network socket calls. This fixes a critical error where network sockets block due to low level PPP issues while main thread is going mavlink sends --- .../AP_Networking/AP_Networking_port.cpp | 48 ++++++++++++------- 1 file changed, 32 insertions(+), 16 deletions(-) diff --git a/libraries/AP_Networking/AP_Networking_port.cpp b/libraries/AP_Networking/AP_Networking_port.cpp index b68c01c0c045d8..1074d896351c07 100644 --- a/libraries/AP_Networking/AP_Networking_port.cpp +++ b/libraries/AP_Networking/AP_Networking_port.cpp @@ -319,10 +319,14 @@ bool AP_Networking::Port::send_receive(void) { bool active = false; - WITH_SEMAPHORE(sem); + uint32_t space; + // handle incoming packets - const auto space = readbuffer->space(); + { + WITH_SEMAPHORE(sem); + space = readbuffer->space(); + } if (space > 0) { const uint32_t n = MIN(300U, space); uint8_t buf[n]; @@ -334,6 +338,7 @@ bool AP_Networking::Port::send_receive(void) return false; } if (ret > 0) { + WITH_SEMAPHORE(sem); readbuffer->write(buf, ret); active = true; have_received = true; @@ -342,22 +347,33 @@ bool AP_Networking::Port::send_receive(void) if (connected) { // handle outgoing packets - uint32_t available = writebuffer->available(); - available = MIN(300U, available); + uint32_t available; + + { + WITH_SEMAPHORE(sem); + available = writebuffer->available(); + available = MIN(300U, available); #if HAL_GCS_ENABLED - if (packetise) { - available = mavlink_packetise(*writebuffer, available); - } + if (packetise) { + available = mavlink_packetise(*writebuffer, available); + } #endif - if (available > 0) { - uint8_t buf[available]; - auto n = writebuffer->peekbytes(buf, available); - if (n > 0) { - const auto ret = sock->send(buf, n); - if (ret > 0) { - writebuffer->advance(ret); - active = true; - } + if (available == 0) { + return active; + } + } + uint8_t buf[available]; + uint32_t n; + { + WITH_SEMAPHORE(sem); + n = writebuffer->peekbytes(buf, available); + } + if (n > 0) { + const auto ret = sock->send(buf, n); + if (ret > 0) { + WITH_SEMAPHORE(sem); + writebuffer->advance(ret); + active = true; } } } else { From 77fbe1dcfbb8e205d6a6ca7349256edc7e344b36 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 10 Jan 2024 07:37:31 +1100 Subject: [PATCH 0457/1335] AP_DroneCAN: don't hold semaphore during CAN send this mirrors the changes in the networking code, and ensures we don't hold a semaphore that may be held by the main thread when we are doing CAN sends --- libraries/AP_DroneCAN/AP_DroneCAN_serial.cpp | 37 +++++++++++--------- 1 file changed, 20 insertions(+), 17 deletions(-) diff --git a/libraries/AP_DroneCAN/AP_DroneCAN_serial.cpp b/libraries/AP_DroneCAN/AP_DroneCAN_serial.cpp index 6856c539f2e9cf..f0bbd72884d1ad 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN_serial.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN_serial.cpp @@ -74,26 +74,29 @@ void AP_DroneCAN_Serial::update(void) if (p.writebuffer == nullptr || p.node <= 0 || p.idx < 0) { continue; } - WITH_SEMAPHORE(p.sem); - uint32_t avail; - const bool send_keepalive = now_ms - p.last_send_ms > 500; - const auto *ptr = p.writebuffer->readptr(avail); - if (!send_keepalive && (ptr == nullptr || avail <= 0)) { - continue; - } uavcan_tunnel_Targetted pkt {}; - auto n = MIN(avail, sizeof(pkt.buffer.data)); - pkt.target_node = p.node; - pkt.protocol.protocol = UAVCAN_TUNNEL_PROTOCOL_UNDEFINED; - pkt.buffer.len = n; - pkt.baudrate = p.baudrate; - pkt.serial_id = p.idx; - pkt.options = UAVCAN_TUNNEL_TARGETTED_OPTION_LOCK_PORT; - if (ptr != nullptr) { - memcpy(pkt.buffer.data, ptr, n); + uint32_t n = 0; + { + WITH_SEMAPHORE(p.sem); + uint32_t avail; + const bool send_keepalive = now_ms - p.last_send_ms > 500; + const auto *ptr = p.writebuffer->readptr(avail); + if (!send_keepalive && (ptr == nullptr || avail <= 0)) { + continue; + } + n = MIN(avail, sizeof(pkt.buffer.data)); + pkt.target_node = p.node; + pkt.protocol.protocol = UAVCAN_TUNNEL_PROTOCOL_UNDEFINED; + pkt.buffer.len = n; + pkt.baudrate = p.baudrate; + pkt.serial_id = p.idx; + pkt.options = UAVCAN_TUNNEL_TARGETTED_OPTION_LOCK_PORT; + if (ptr != nullptr) { + memcpy(pkt.buffer.data, ptr, n); + } } - if (targetted->broadcast(pkt)) { + WITH_SEMAPHORE(p.sem); p.writebuffer->advance(n); p.last_send_ms = now_ms; } From 7e5e55a97b660c8d62615d8d6560afad194d296e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 10 Jan 2024 09:05:32 +1100 Subject: [PATCH 0458/1335] autotest: fix for flapping multicast log download test we had two ports outputting to 14550 which could cause the test to be very slow --- Tools/autotest/vehicle_test_suite.py | 39 ++++++++++++++++++++-------- 1 file changed, 28 insertions(+), 11 deletions(-) diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index be0cecc95fee4b..5b7e4f54b7ecdc 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -4274,7 +4274,7 @@ def TestLogDownloadMAVProxyNetwork(self, upload_logs=False): self.set_parameters({ "NET_ENABLED": 1, "LOG_DISARMED": 1, - "LOG_DARM_RATEMAX": 2, # make small logs + "LOG_DARM_RATEMAX": 1, # make small logs # UDP client "NET_P1_TYPE": 1, "NET_P1_PROTOCOL": 2, @@ -4317,11 +4317,14 @@ def TestLogDownloadMAVProxyNetwork(self, upload_logs=False): self.progress("Downloading log with %s %s" % (name, e)) filename = "MAVProxy-downloaded-net-log-%s.BIN" % name - mavproxy = self.start_mavproxy(master=e) + mavproxy = self.start_mavproxy(master=e, options=['--source-system=123']) self.mavproxy_load_module(mavproxy, 'log') self.wait_heartbeat() mavproxy.send("log list\n") mavproxy.expect("numLogs") + # ensure the full list of logs has come out + for i in range(5): + self.wait_heartbeat() mavproxy.send("log download latest %s\n" % filename) mavproxy.expect("Finished downloading", timeout=120) self.mavproxy_unload_module(mavproxy, 'log') @@ -4331,7 +4334,7 @@ def TestLogDownloadMAVProxyNetwork(self, upload_logs=False): # multicast UDP client "NET_P1_TYPE": 1, "NET_P1_PROTOCOL": 2, - "NET_P1_PORT": 14550, + "NET_P1_PORT": 16005, "NET_P1_IP0": 239, "NET_P1_IP1": 255, "NET_P1_IP2": 145, @@ -4339,24 +4342,30 @@ def TestLogDownloadMAVProxyNetwork(self, upload_logs=False): # Broadcast UDP client "NET_P2_TYPE": 1, "NET_P2_PROTOCOL": 2, - "NET_P2_PORT": 16005, + "NET_P2_PORT": 16006, "NET_P2_IP0": 255, "NET_P2_IP1": 255, "NET_P2_IP2": 255, "NET_P2_IP3": 255, + "NET_P3_TYPE": -1, + "NET_P4_TYPE": -1, + "LOG_DISARMED": 0, }) self.reboot_sitl() - endpoints = [('UDPMulticast', 'mcast:') , - ('UDPBroadcast', ':16005')] + endpoints = [('UDPMulticast', 'mcast:16005') , + ('UDPBroadcast', ':16006')] for name, e in endpoints: self.progress("Downloading log with %s %s" % (name, e)) filename = "MAVProxy-downloaded-net-log-%s.BIN" % name - mavproxy = self.start_mavproxy(master=e) + mavproxy = self.start_mavproxy(master=e, options=['--source-system=123']) self.mavproxy_load_module(mavproxy, 'log') self.wait_heartbeat() mavproxy.send("log list\n") mavproxy.expect("numLogs") + # ensure the full list of logs has come out + for i in range(5): + self.wait_heartbeat() mavproxy.send("log download latest %s\n" % filename) mavproxy.expect("Finished downloading", timeout=120) self.mavproxy_unload_module(mavproxy, 'log') @@ -4387,8 +4396,9 @@ def TestLogDownloadMAVProxyCAN(self, upload_logs=False): self.mavproxy_load_module(mavproxy, 'log') mavproxy.send("log list\n") mavproxy.expect("numLogs") - self.wait_heartbeat() - self.wait_heartbeat() + # ensure the full list of logs has come out + for i in range(5): + self.wait_heartbeat() mavproxy.send("set shownoise 0\n") mavproxy.send("log download latest %s\n" % filename) mavproxy.expect("Finished downloading", timeout=120) @@ -8435,7 +8445,7 @@ def run_one_test_attempt(self, test, interact=False, attempt=1, suppress_stdout= def defaults_filepath(self): return None - def start_mavproxy(self, sitl_rcin_port=None, master=None): + def start_mavproxy(self, sitl_rcin_port=None, master=None, options=None): self.start_mavproxy_count += 1 if self.mavproxy is not None: return self.mavproxy @@ -8453,11 +8463,18 @@ def start_mavproxy(self, sitl_rcin_port=None, master=None): if master is None: master = 'tcp:127.0.0.1:%u' % self.adjust_ardupilot_port(5762) + if options is None: + options = self.mavproxy_options() + else: + op = self.mavproxy_options().copy() + op.extend(options) + options = op + mavproxy = util.start_MAVProxy_SITL( self.vehicleinfo_key(), master=master, logfile=self.mavproxy_logfile, - options=self.mavproxy_options(), + options=options, pexpect_timeout=pexpect_timeout, sitl_rcin_port=sitl_rcin_port, ) From 462eb46c8b885efc9181068d13ff4b6ef60e81fe Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Sat, 30 Dec 2023 13:30:08 +0100 Subject: [PATCH 0459/1335] AP_Mount.cpp: send gimbal_manager_status msg when control changes Co-authored-by: Randy Mackay By default we are sending this message at 0.2 Hz. This is totally fine as no more rate is needed, but whenever control changes it is interesting to notify as soon as possible, so the rest of the mavlink network understands the change in control as soon as possible --- libraries/AP_Mount/AP_Mount_Backend.cpp | 8 ++++++++ libraries/AP_Mount/AP_Mount_Backend.h | 6 +++++- 2 files changed, 13 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Mount/AP_Mount_Backend.cpp b/libraries/AP_Mount/AP_Mount_Backend.cpp index 7e1f28d3d5df16..b6080a6f22545b 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.cpp +++ b/libraries/AP_Mount/AP_Mount_Backend.cpp @@ -358,6 +358,9 @@ MAV_RESULT AP_Mount_Backend::handle_command_do_gimbal_manager_configure(const ma return MAV_RESULT_FAILED; } + // backup the current values so we can detect a change + mavlink_control_id_t prev_control_id = mavlink_control_id; + // convert negative packet1 and packet2 values int16_t new_sysid = packet.param1; switch (new_sysid) { @@ -382,6 +385,11 @@ MAV_RESULT AP_Mount_Backend::handle_command_do_gimbal_manager_configure(const ma break; } + // send gimbal_manager_status if control has changed + if (prev_control_id != mavlink_control_id) { + gcs().send_message(MSG_GIMBAL_MANAGER_STATUS); + } + return MAV_RESULT_ACCEPTED; } diff --git a/libraries/AP_Mount/AP_Mount_Backend.h b/libraries/AP_Mount/AP_Mount_Backend.h index d2f97273608b5b..f75ea29da5289f 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.h +++ b/libraries/AP_Mount/AP_Mount_Backend.h @@ -321,9 +321,13 @@ class AP_Mount_Backend // structure holding mavlink sysid and compid of controller of this gimbal // see MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE and GIMBAL_MANAGER_STATUS - struct { + struct mavlink_control_id_t { uint8_t sysid; uint8_t compid; + + // equality operators + bool operator==(const mavlink_control_id_t &rhs) const { return (sysid == rhs.sysid && compid == rhs.compid); } + bool operator!=(const mavlink_control_id_t &rhs) const { return !(*this == rhs); } } mavlink_control_id; }; From 3b99a3ac269df8fd2091c300c275c49ffe28f005 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Mon, 1 Jan 2024 14:23:00 +0000 Subject: [PATCH 0460/1335] AP_Relay: add function_valid helper and only pre-arm enabled relays --- libraries/AP_Relay/AP_Relay.cpp | 25 +++++++++++++++++++++---- libraries/AP_Relay/AP_Relay.h | 3 +++ 2 files changed, 24 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Relay/AP_Relay.cpp b/libraries/AP_Relay/AP_Relay.cpp index e16d0248c20fe8..89f9a747547c21 100644 --- a/libraries/AP_Relay/AP_Relay.cpp +++ b/libraries/AP_Relay/AP_Relay.cpp @@ -313,6 +313,12 @@ void AP_Relay::set_defaults() { } } +// Return true is function is valid +bool AP_Relay::function_valid(AP_Relay_Params::FUNCTION function) const +{ + return (function > AP_Relay_Params::FUNCTION::NONE) && (function < AP_Relay_Params::FUNCTION::NUM_FUNCTIONS); +} + void AP_Relay::init() { set_defaults(); @@ -328,7 +334,7 @@ void AP_Relay::init() } const AP_Relay_Params::FUNCTION function = _params[instance].function; - if (function <= AP_Relay_Params::FUNCTION::NONE || function >= AP_Relay_Params::FUNCTION::NUM_FUNCTIONS) { + if (!function_valid(function)) { // invalid function, skip it continue; } @@ -350,7 +356,7 @@ void AP_Relay::init() } void AP_Relay::set(const AP_Relay_Params::FUNCTION function, const bool value) { - if (function <= AP_Relay_Params::FUNCTION::NONE && function >= AP_Relay_Params::FUNCTION::NUM_FUNCTIONS) { + if (!function_valid(function)) { // invalid function return; } @@ -416,8 +422,19 @@ void AP_Relay::toggle(uint8_t instance) bool AP_Relay::arming_checks(size_t buflen, char *buffer) const { for (uint8_t i=0; ivalid_pin(pin)) { + if (!function_valid(_params[i].function)) { + // Relay disabled + continue; + } + + const int16_t pin = _params[i].pin.get(); + if (pin == -1) { + // Pin disabled, may want to pre-arm this in the future as function enabled with invalid pin + // User should set function to none to disable + continue; + } + if (!hal.gpio->valid_pin(pin)) { + // Check GPIO pin is valid char param_name_buf[14]; hal.util->snprintf(param_name_buf, ARRAY_SIZE(param_name_buf), "RELAY%u_PIN", unsigned(i+1)); uint8_t servo_ch; diff --git a/libraries/AP_Relay/AP_Relay.h b/libraries/AP_Relay/AP_Relay.h index d53bdb408c080b..3ad445cf0321fa 100644 --- a/libraries/AP_Relay/AP_Relay.h +++ b/libraries/AP_Relay/AP_Relay.h @@ -71,6 +71,9 @@ class AP_Relay { AP_Relay_Params _params[AP_RELAY_NUM_RELAYS]; + // Return true is function is valid + bool function_valid(AP_Relay_Params::FUNCTION function) const; + void set(uint8_t instance, bool value); void set_defaults(); From f6ed18f3f698211bd8d379b3f231e9d6170b7390 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Mon, 1 Jan 2024 20:54:24 +0000 Subject: [PATCH 0461/1335] AP_Relay: support virtual DroneCAN pins using hardpoint msg --- libraries/AP_Relay/AP_Relay.cpp | 151 +++++++++++++++++++++++-- libraries/AP_Relay/AP_Relay.h | 52 +++++++++ libraries/AP_Relay/AP_Relay_Params.cpp | 16 +++ libraries/AP_Relay/AP_Relay_Params.h | 20 ++++ libraries/AP_Relay/AP_Relay_config.h | 2 + 5 files changed, 234 insertions(+), 7 deletions(-) diff --git a/libraries/AP_Relay/AP_Relay.cpp b/libraries/AP_Relay/AP_Relay.cpp index 89f9a747547c21..0630cce2fc9a03 100644 --- a/libraries/AP_Relay/AP_Relay.cpp +++ b/libraries/AP_Relay/AP_Relay.cpp @@ -24,6 +24,11 @@ #include #endif +#if AP_RELAY_DRONECAN_ENABLED +#include +#include +#endif + #if CONFIG_HAL_BOARD == HAL_BOARD_SITL #define RELAY1_PIN_DEFAULT 13 @@ -327,7 +332,7 @@ void AP_Relay::init() // setup the actual default values of all the pins for (uint8_t instance = 0; instance < ARRAY_SIZE(_params); instance++) { - const int8_t pin = _params[instance].pin; + const int16_t pin = _params[instance].pin; if (pin == -1) { // no valid pin to set it on, skip it continue; @@ -352,6 +357,12 @@ void AP_Relay::init() // this will need revisiting when we support inversion set_pin_by_instance(instance, false); } + + // Make sure any DroneCAN pin is enabled for streaming +#if AP_RELAY_DRONECAN_ENABLED + dronecan.enable_pin(pin); +#endif + } } @@ -374,7 +385,7 @@ void AP_Relay::set(const AP_Relay_Params::FUNCTION function, const bool value) { // this is an internal helper, instance must have already been validated to be in range void AP_Relay::set_pin_by_instance(uint8_t instance, bool value) { - const int8_t pin = _params[instance].pin; + const int16_t pin = _params[instance].pin; if (pin == -1) { // no valid pin to set it on, skip it return; @@ -386,11 +397,10 @@ void AP_Relay::set_pin_by_instance(uint8_t instance, bool value) } #endif - hal.gpio->pinMode(pin, HAL_GPIO_OUTPUT); - const bool initial_value = (bool)hal.gpio->read(pin); + const bool initial_value = get_pin(pin); if (initial_value != value) { - hal.gpio->write(pin, value); + set_pin(pin, value); AP::logger().Write("RELY", "TimeUS,Instance,State", "s#-", "F--", "QBB", AP_HAL::micros64(), instance, @@ -433,7 +443,14 @@ bool AP_Relay::arming_checks(size_t buflen, char *buffer) const // User should set function to none to disable continue; } - if (!hal.gpio->valid_pin(pin)) { + +#if AP_RELAY_DRONECAN_ENABLED + const bool DroneCAN_pin = dronecan.valid_pin(pin); +#else + const bool DroneCAN_pin = false; +#endif + + if (!DroneCAN_pin && !hal.gpio->valid_pin(pin)) { // Check GPIO pin is valid char param_name_buf[14]; hal.util->snprintf(param_name_buf, ARRAY_SIZE(param_name_buf), "RELAY%u_PIN", unsigned(i+1)); @@ -456,16 +473,50 @@ bool AP_Relay::get(uint8_t instance) const return false; } - const int8_t pin = _params[instance].pin.get(); + return get_pin(_params[instance].pin.get()); +} +// Get relay state from pin number +bool AP_Relay::get_pin(const int16_t pin) const +{ if (pin < 0) { // invalid pin return false; } +#if AP_RELAY_DRONECAN_ENABLED + if (dronecan.valid_pin(pin)) { + // Virtual DroneCAN pin + return dronecan.get_pin(pin); + } +#endif + + // Real GPIO pin + hal.gpio->pinMode(pin, HAL_GPIO_OUTPUT); return (bool)hal.gpio->read(pin); } +// Set relay state from pin number +void AP_Relay::set_pin(const int16_t pin, const bool value) +{ + if (pin < 0) { + // invalid pin + return; + } + +#if AP_RELAY_DRONECAN_ENABLED + if (dronecan.valid_pin(pin)) { + // Virtual DroneCAN pin + dronecan.set_pin(pin, value); + return; + } +#endif + + // Real GPIO pin + hal.gpio->pinMode(pin, HAL_GPIO_OUTPUT); + hal.gpio->write(pin, value); +} + // see if the relay is enabled bool AP_Relay::enabled(uint8_t instance) const { @@ -484,6 +535,92 @@ bool AP_Relay::enabled(AP_Relay_Params::FUNCTION function) const return false; } +#if AP_RELAY_DRONECAN_ENABLED +// Return true if pin number is a virtual DroneCAN pin +bool AP_Relay::DroneCAN::valid_pin(int16_t pin) const +{ + switch(pin) { + case (int16_t)AP_Relay_Params::VIRTUAL_PINS::DroneCAN_0 ... (int16_t)AP_Relay_Params::VIRTUAL_PINS::DroneCAN_15: + return true; + default: + return false; + } +} + +// Enable streaming of pin number +void AP_Relay::DroneCAN::enable_pin(int16_t pin) +{ + if (!valid_pin(pin)) { + return; + } + + const uint8_t index = hardpoint_index(pin); + state[index].enabled = true; +} + +// Get the hardpoint index of given pin number +uint8_t AP_Relay::DroneCAN::hardpoint_index(const int16_t pin) const +{ + return pin - (int16_t)AP_Relay_Params::VIRTUAL_PINS::DroneCAN_0; +} + +// Set DroneCAN relay state from pin number +void AP_Relay::DroneCAN::set_pin(const int16_t pin, const bool value) +{ + const uint8_t index = hardpoint_index(pin); + + // Set pin and ensure enabled for streaming + state[index].enabled = true; + state[index].value = value; + + // Broadcast msg on all channels + // Just a single send, rely on streaming to fill in any lost packet + + uavcan_equipment_hardpoint_Command msg {}; + msg.hardpoint_id = index; + msg.command = state[index].value; + + uint8_t can_num_drivers = AP::can().get_num_drivers(); + for (uint8_t i = 0; i < can_num_drivers; i++) { + auto *ap_dronecan = AP_DroneCAN::get_dronecan(i); + if (ap_dronecan != nullptr) { + ap_dronecan->relay_hardpoint.broadcast(msg); + } + } + +} + +// Get relay state from pin number, this relies on a cached value, assume remote pin is in sync +bool AP_Relay::DroneCAN::get_pin(const int16_t pin) const +{ + const uint8_t index = hardpoint_index(pin); + return state[index].value; +} + +// Populate message and update index with the sent command +// This will allow the caller to cycle through each enabled pin +bool AP_Relay::DroneCAN::populate_next_command(uint8_t &index, uavcan_equipment_hardpoint_Command &msg) const +{ + // Find the next enabled index + for (uint8_t i = 0; i < ARRAY_SIZE(state); i++) { + // Look for next index, wrapping back to 0 as needed + const uint8_t new_index = (index + 1 + i) % ARRAY_SIZE(state); + if (!state[new_index].enabled) { + // This index is not being used + continue; + } + + // Update command and index then return + msg.hardpoint_id = new_index; + msg.command = state[new_index].value; + index = new_index; + return true; + } + + return false; +} +#endif // AP_RELAY_DRONECAN_ENABLED + #if AP_MAVLINK_MSG_RELAY_STATUS_ENABLED // this method may only return false if there is no space in the // supplied link for the message. diff --git a/libraries/AP_Relay/AP_Relay.h b/libraries/AP_Relay/AP_Relay.h index 3ad445cf0321fa..9d9055cdbe1842 100644 --- a/libraries/AP_Relay/AP_Relay.h +++ b/libraries/AP_Relay/AP_Relay.h @@ -25,9 +25,17 @@ #error There must be at least one relay instance if using AP_Relay #endif +#if AP_RELAY_DRONECAN_ENABLED +#include +#endif + /// @class AP_Relay /// @brief Class to manage the ArduPilot relay class AP_Relay { +#if AP_RELAY_DRONECAN_ENABLED + // Allow DroneCAN to directly access private DroneCAN state + friend class AP_DroneCAN; +#endif public: AP_Relay(); @@ -80,6 +88,50 @@ class AP_Relay { void convert_params(); void set_pin_by_instance(uint8_t instance, bool value); + + // Set relay state from pin number + void set_pin(const int16_t pin, const bool value); + + // Get relay state from pin number + bool get_pin(const int16_t pin) const; + +#if HAL_ENABLE_DRONECAN_DRIVERS + // Virtual DroneCAN pins + class DroneCAN { + public: + // Return true if pin number is a virtual DroneCAN pin + bool valid_pin(int16_t pin) const; + + // Enable streaming of pin number + void enable_pin(int16_t pin); + + // Populate message and update index with the sent command + bool populate_next_command(uint8_t &index, uavcan_equipment_hardpoint_Command &msg) const; + + // Set DroneCAN relay state from pin number + void set_pin(const int16_t pin, const bool value); + + // Get relay state from pin number + bool get_pin(const int16_t pin) const; + + private: + + // Get the hardpoint index of given pin number + uint8_t hardpoint_index(const int16_t pin) const; + + // Send DroneCAN hardpoint message for given index on all interfaces + void send_index(const uint8_t index); + + static constexpr uint8_t num_pins = (int16_t)AP_Relay_Params::VIRTUAL_PINS::DroneCAN_15 - (int16_t)AP_Relay_Params::VIRTUAL_PINS::DroneCAN_0; + + struct { + bool value; + bool enabled; + } state[num_pins]; + + } dronecan; +#endif // HAL_ENABLE_DRONECAN_DRIVERS + }; namespace AP { diff --git a/libraries/AP_Relay/AP_Relay_Params.cpp b/libraries/AP_Relay/AP_Relay_Params.cpp index c6734fb9b93501..5fc7f92d52776e 100644 --- a/libraries/AP_Relay/AP_Relay_Params.cpp +++ b/libraries/AP_Relay/AP_Relay_Params.cpp @@ -23,6 +23,22 @@ const AP_Param::GroupInfo AP_Relay_Params::var_info[] = { // @DisplayName: Relay pin // @Description: Digital pin number for relay control. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot. // @Values: -1:Disabled,49:BB Blue GP0 pin 4,50:AUXOUT1,51:AUXOUT2,52:AUXOUT3,53:AUXOUT4,54:AUXOUT5,55:AUXOUT6,57:BB Blue GP0 pin 3,113:BB Blue GP0 pin 6,116:BB Blue GP0 pin 5,62:BBBMini Pin P8.13,101:MainOut1,102:MainOut2,103:MainOut3,104:MainOut4,105:MainOut5,106:MainOut6,107:MainOut7,108:MainOut8 + // @Values: 1000: DroneCAN Hardpoint ID 0 + // @Values: 1001: DroneCAN Hardpoint ID 1 + // @Values: 1002: DroneCAN Hardpoint ID 2 + // @Values: 1003: DroneCAN Hardpoint ID 3 + // @Values: 1004: DroneCAN Hardpoint ID 4 + // @Values: 1005: DroneCAN Hardpoint ID 5 + // @Values: 1006: DroneCAN Hardpoint ID 6 + // @Values: 1007: DroneCAN Hardpoint ID 7 + // @Values: 1008: DroneCAN Hardpoint ID 8 + // @Values: 1009: DroneCAN Hardpoint ID 9 + // @Values: 1010: DroneCAN Hardpoint ID 10 + // @Values: 1011: DroneCAN Hardpoint ID 11 + // @Values: 1012: DroneCAN Hardpoint ID 12 + // @Values: 1013: DroneCAN Hardpoint ID 13 + // @Values: 1014: DroneCAN Hardpoint ID 14 + // @Values: 1015: DroneCAN Hardpoint ID 15 // @User: Standard AP_GROUPINFO("PIN", 2, AP_Relay_Params, pin, -1), diff --git a/libraries/AP_Relay/AP_Relay_Params.h b/libraries/AP_Relay/AP_Relay_Params.h index c5c783677143e0..8e34318e2910dd 100644 --- a/libraries/AP_Relay/AP_Relay_Params.h +++ b/libraries/AP_Relay/AP_Relay_Params.h @@ -32,6 +32,26 @@ class AP_Relay_Params { NUM_FUNCTIONS // must be the last entry }; + // Pins that do not go via GPIO + enum class VIRTUAL_PINS { + DroneCAN_0 = 1000, + DroneCAN_1 = 1001, + DroneCAN_2 = 1002, + DroneCAN_3 = 1003, + DroneCAN_4 = 1004, + DroneCAN_5 = 1005, + DroneCAN_6 = 1006, + DroneCAN_7 = 1007, + DroneCAN_8 = 1008, + DroneCAN_9 = 1009, + DroneCAN_10 = 1010, + DroneCAN_11 = 1011, + DroneCAN_12 = 1012, + DroneCAN_13 = 1013, + DroneCAN_14 = 1014, + DroneCAN_15 = 1015, + }; + AP_Enum function; // relay function AP_Int16 pin; // gpio pin number AP_Enum default_state; // default state diff --git a/libraries/AP_Relay/AP_Relay_config.h b/libraries/AP_Relay/AP_Relay_config.h index efc3b918f4e297..946be54dfe1460 100644 --- a/libraries/AP_Relay/AP_Relay_config.h +++ b/libraries/AP_Relay/AP_Relay_config.h @@ -5,3 +5,5 @@ #ifndef AP_RELAY_ENABLED #define AP_RELAY_ENABLED 1 #endif + +#define AP_RELAY_DRONECAN_ENABLED AP_RELAY_ENABLED && HAL_ENABLE_DRONECAN_DRIVERS && !defined(HAL_BUILD_AP_PERIPH) From 69e076605e7391cca576581d7ebcdd6343915e08 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Mon, 1 Jan 2024 20:55:03 +0000 Subject: [PATCH 0462/1335] AP_DroneCAN: support streaming relay hardpoint command --- libraries/AP_DroneCAN/AP_DroneCAN.cpp | 52 +++++++++++++++++++++++++++ libraries/AP_DroneCAN/AP_DroneCAN.h | 16 +++++++++ 2 files changed, 68 insertions(+) diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.cpp b/libraries/AP_DroneCAN/AP_DroneCAN.cpp index 9f34e7f93b10ef..cc6242e8daf661 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN.cpp @@ -55,6 +55,10 @@ #include "AP_DroneCAN_serial.h" #endif +#if AP_RELAY_DRONECAN_ENABLED +#include +#endif + extern const AP_HAL::HAL& hal; // setup default pool size @@ -153,6 +157,16 @@ const AP_Param::GroupInfo AP_DroneCAN::var_info[] = { // @User: Advanced AP_GROUPINFO("ESC_RV", 9, AP_DroneCAN, _esc_rv, 0), +#if AP_RELAY_DRONECAN_ENABLED + // @Param: RLY_RT + // @DisplayName: DroneCAN relay output rate + // @Description: Maximum transmit rate for relay outputs, note that this rate is per message each message does 1 relay, so if with more relays will take longer to update at the same rate, a extra message will be sent when a relay changes state + // @Range: 0 200 + // @Units: Hz + // @User: Advanced + AP_GROUPINFO("RLY_RT", 23, AP_DroneCAN, _relay.rate_hz, 0), +#endif + #if AP_DRONECAN_SERIAL_ENABLED /* due to the parameter tree depth limitation we can't use a sub-table for the serial parameters @@ -252,6 +266,8 @@ const AP_Param::GroupInfo AP_DroneCAN::var_info[] = { #endif #endif // AP_DRONECAN_SERIAL_ENABLED + // RLY_RT is index 23 but has to be above SER_EN so its not hidden + AP_GROUPEND }; @@ -434,6 +450,11 @@ void AP_DroneCAN::init(uint8_t driver_index, bool enable_filters) xacti_gnss_status.set_priority(CANARD_TRANSFER_PRIORITY_LOW); #endif +#if AP_RELAY_DRONECAN_ENABLED + relay_hardpoint.set_timeout_ms(20); + relay_hardpoint.set_priority(CANARD_TRANSFER_PRIORITY_LOW); +#endif + param_save_client.set_timeout_ms(20); param_save_client.set_priority(CANARD_TRANSFER_PRIORITY_LOW); @@ -532,6 +553,10 @@ void AP_DroneCAN::loop(void) #if AP_DRONECAN_SERIAL_ENABLED serial.update(); #endif + +#if AP_RELAY_DRONECAN_ENABLED + relay_hardpoint_send(); +#endif } } @@ -1212,6 +1237,33 @@ void AP_DroneCAN::safety_state_send() } } +// Send relay outputs with hardpoint msg +#if AP_RELAY_DRONECAN_ENABLED +void AP_DroneCAN::relay_hardpoint_send() +{ + const uint32_t now = AP_HAL::millis(); + if ((_relay.rate_hz == 0) || ((now - _relay.last_send_ms) < uint32_t(1000 / _relay.rate_hz))) { + // Rate limit per user config + return; + } + _relay.last_send_ms = now; + + AP_Relay *relay = AP::relay(); + if (relay == nullptr) { + return; + } + + uavcan_equipment_hardpoint_Command msg {}; + + // Relay will populate the next command to send and update the last index + // This will cycle through each relay in turn + if (relay->dronecan.populate_next_command(_relay.last_index, msg)) { + relay_hardpoint.broadcast(msg); + } + +} +#endif // AP_RELAY_DRONECAN_ENABLED + /* handle Button message */ diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.h b/libraries/AP_DroneCAN/AP_DroneCAN.h index 61f0528bc95ff5..8b37c2528b89b9 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.h +++ b/libraries/AP_DroneCAN/AP_DroneCAN.h @@ -35,6 +35,7 @@ #include #include #include +#include #ifndef DRONECAN_SRV_NUMBER #define DRONECAN_SRV_NUMBER NUM_SERVO_CHANNELS @@ -165,6 +166,12 @@ class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { Canard::Publisher xacti_gimbal_control_data{canard_iface}; Canard::Publisher xacti_gnss_status{canard_iface}; +#if AP_RELAY_DRONECAN_ENABLED + // Hardpoint for relay + // Needs to be public so relay can edge trigger as well as streaming + Canard::Publisher relay_hardpoint{canard_iface}; +#endif + private: void loop(void); @@ -272,6 +279,15 @@ class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { uint32_t _last_notify_state_ms; uavcan_protocol_NodeStatus node_status_msg; +#if AP_RELAY_DRONECAN_ENABLED + void relay_hardpoint_send(); + struct { + AP_Int16 rate_hz; + uint32_t last_send_ms; + uint8_t last_index; + } _relay; +#endif + CanardInterface canard_iface; #if AP_DRONECAN_SERIAL_ENABLED From c8a63a1de4416b241297a392fa6fe8fe779ba12f Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 2 Jan 2024 21:26:03 +0000 Subject: [PATCH 0463/1335] AP_DroneCAN: remove duplicate rgb_led set_timeout_ms and set_priority --- libraries/AP_DroneCAN/AP_DroneCAN.cpp | 3 --- 1 file changed, 3 deletions(-) diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.cpp b/libraries/AP_DroneCAN/AP_DroneCAN.cpp index cc6242e8daf661..5667f5a54af4f5 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN.cpp @@ -470,9 +470,6 @@ void AP_DroneCAN::init(uint8_t driver_index, bool enable_filters) can_stats.set_priority(CANARD_TRANSFER_PRIORITY_LOWEST); can_stats.set_timeout_ms(3000); - rgb_led.set_timeout_ms(20); - rgb_led.set_priority(CANARD_TRANSFER_PRIORITY_LOW); - node_info_server.set_timeout_ms(20); // setup node status From ccb4d688032326ce7f5781fff092bae83f31966b Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Mon, 1 Jan 2024 21:07:42 +0000 Subject: [PATCH 0464/1335] AP_Relay: add support for DroneCAN HardPoint functions --- libraries/AP_Relay/AP_Relay_Params.cpp | 16 ++++++++++++++++ libraries/AP_Relay/AP_Relay_Params.h | 16 ++++++++++++++++ 2 files changed, 32 insertions(+) diff --git a/libraries/AP_Relay/AP_Relay_Params.cpp b/libraries/AP_Relay/AP_Relay_Params.cpp index 5fc7f92d52776e..99abbcb77e6bb3 100644 --- a/libraries/AP_Relay/AP_Relay_Params.cpp +++ b/libraries/AP_Relay/AP_Relay_Params.cpp @@ -15,6 +15,22 @@ const AP_Param::GroupInfo AP_Relay_Params::var_info[] = { // @Values{Rover}: 7:Bushed motor reverse 3 omni motor 3 // @Values{Rover}: 8:Bushed motor reverse 4 omni motor 4 // @Values{Plane}: 9:ICE Starter + // @Values{AP_Periph}: 10: DroneCAN Hardpoint ID 0 + // @Values{AP_Periph}: 11: DroneCAN Hardpoint ID 1 + // @Values{AP_Periph}: 12: DroneCAN Hardpoint ID 2 + // @Values{AP_Periph}: 13: DroneCAN Hardpoint ID 3 + // @Values{AP_Periph}: 14: DroneCAN Hardpoint ID 4 + // @Values{AP_Periph}: 15: DroneCAN Hardpoint ID 5 + // @Values{AP_Periph}: 16: DroneCAN Hardpoint ID 6 + // @Values{AP_Periph}: 17: DroneCAN Hardpoint ID 7 + // @Values{AP_Periph}: 18: DroneCAN Hardpoint ID 8 + // @Values{AP_Periph}: 19: DroneCAN Hardpoint ID 9 + // @Values{AP_Periph}: 20: DroneCAN Hardpoint ID 10 + // @Values{AP_Periph}: 21: DroneCAN Hardpoint ID 11 + // @Values{AP_Periph}: 22: DroneCAN Hardpoint ID 12 + // @Values{AP_Periph}: 23: DroneCAN Hardpoint ID 13 + // @Values{AP_Periph}: 24: DroneCAN Hardpoint ID 14 + // @Values{AP_Periph}: 25: DroneCAN Hardpoint ID 15 // @User: Standard AP_GROUPINFO_FLAGS("FUNCTION", 1, AP_Relay_Params, function, (float)FUNCTION::NONE, AP_PARAM_FLAG_ENABLE), diff --git a/libraries/AP_Relay/AP_Relay_Params.h b/libraries/AP_Relay/AP_Relay_Params.h index 8e34318e2910dd..c8c9f7ab98b615 100644 --- a/libraries/AP_Relay/AP_Relay_Params.h +++ b/libraries/AP_Relay/AP_Relay_Params.h @@ -29,6 +29,22 @@ class AP_Relay_Params { BRUSHED_REVERSE_3 = 7, BRUSHED_REVERSE_4 = 8, ICE_STARTER = 9, + DroneCAN_HARDPOINT_0 = 10, + DroneCAN_HARDPOINT_1 = 11, + DroneCAN_HARDPOINT_2 = 12, + DroneCAN_HARDPOINT_3 = 13, + DroneCAN_HARDPOINT_4 = 14, + DroneCAN_HARDPOINT_5 = 15, + DroneCAN_HARDPOINT_6 = 16, + DroneCAN_HARDPOINT_7 = 17, + DroneCAN_HARDPOINT_8 = 18, + DroneCAN_HARDPOINT_9 = 19, + DroneCAN_HARDPOINT_10 = 20, + DroneCAN_HARDPOINT_11 = 21, + DroneCAN_HARDPOINT_12 = 22, + DroneCAN_HARDPOINT_13 = 23, + DroneCAN_HARDPOINT_14 = 24, + DroneCAN_HARDPOINT_15 = 25, NUM_FUNCTIONS // must be the last entry }; From 7eac47b06c20b5895035eb5d3d2de0c356591ea6 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Mon, 1 Jan 2024 21:55:22 +0000 Subject: [PATCH 0465/1335] AP_Relay: allow to build on periph --- libraries/AP_Relay/AP_Relay.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/libraries/AP_Relay/AP_Relay.cpp b/libraries/AP_Relay/AP_Relay.cpp index 0630cce2fc9a03..7225c6c3d30e03 100644 --- a/libraries/AP_Relay/AP_Relay.cpp +++ b/libraries/AP_Relay/AP_Relay.cpp @@ -198,6 +198,8 @@ AP_Relay::AP_Relay(void) void AP_Relay::convert_params() { // PARAMETER_CONVERSION - Added: Dec-2023 +#ifndef HAL_BUILD_AP_PERIPH + // Dont need this conversion on periph as relay support is more recent // Before converting local params we must find any relays being used by index from external libs int8_t relay_index; @@ -300,6 +302,7 @@ void AP_Relay::convert_params() _params[i].default_state.set_and_save(default_state); } } +#endif // HAL_BUILD_AP_PERIPH } void AP_Relay::set_defaults() { @@ -401,10 +404,12 @@ void AP_Relay::set_pin_by_instance(uint8_t instance, bool value) if (initial_value != value) { set_pin(pin, value); +#if HAL_LOGGING_ENABLED AP::logger().Write("RELY", "TimeUS,Instance,State", "s#-", "F--", "QBB", AP_HAL::micros64(), instance, value); +#endif } } From a5f2076d21f717800868efae76a4b075172dcbc7 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Mon, 1 Jan 2024 21:56:28 +0000 Subject: [PATCH 0466/1335] Tools: AP_Periph: add support for relay via incoming hardpoint command --- Tools/AP_Periph/AP_Periph.cpp | 4 ++++ Tools/AP_Periph/AP_Periph.h | 16 ++++++++++++++ Tools/AP_Periph/Parameters.cpp | 6 ++++++ Tools/AP_Periph/Parameters.h | 1 + Tools/AP_Periph/can.cpp | 12 +++++++++++ Tools/AP_Periph/relay.cpp | 38 ++++++++++++++++++++++++++++++++++ Tools/AP_Periph/wscript | 1 + 7 files changed, 78 insertions(+) create mode 100644 Tools/AP_Periph/relay.cpp diff --git a/Tools/AP_Periph/AP_Periph.cpp b/Tools/AP_Periph/AP_Periph.cpp index 85672d9d62f636..78cc920c1df8b3 100644 --- a/Tools/AP_Periph/AP_Periph.cpp +++ b/Tools/AP_Periph/AP_Periph.cpp @@ -285,6 +285,10 @@ void AP_Periph_FW::init() notify.init(); #endif +#ifdef HAL_PERIPH_ENABLE_RELAY + relay.init(); +#endif + #if AP_SCRIPTING_ENABLED scripting.init(); #endif diff --git a/Tools/AP_Periph/AP_Periph.h b/Tools/AP_Periph/AP_Periph.h index a025883ad7347c..488f05cc0c025c 100644 --- a/Tools/AP_Periph/AP_Periph.h +++ b/Tools/AP_Periph/AP_Periph.h @@ -41,6 +41,16 @@ #include #endif +#ifdef HAL_PERIPH_ENABLE_RELAY +#ifdef HAL_PERIPH_ENABLE_PWM_HARDPOINT + #error "Relay and PWM_HARDPOINT both use hardpoint message" +#endif +#include +#if !AP_RELAY_ENABLED + #error "HAL_PERIPH_ENABLE_RELAY requires AP_RELAY_ENABLED" +#endif +#endif + #include #if HAL_NMEA_OUTPUT_ENABLED && !(HAL_GCS_ENABLED && defined(HAL_PERIPH_ENABLE_GPS)) // Needs SerialManager + (AHRS or GPS) @@ -383,6 +393,11 @@ class AP_Periph_FW { #if HAL_GCS_ENABLED GCS_Periph _gcs; #endif + +#ifdef HAL_PERIPH_ENABLE_RELAY + AP_Relay relay; +#endif + // setup the var_info table AP_Param param_loader{var_info}; @@ -482,6 +497,7 @@ class AP_Periph_FW { void handle_beep_command(CanardInstance* canard_instance, CanardRxTransfer* transfer); void handle_lightscommand(CanardInstance* canard_instance, CanardRxTransfer* transfer); void handle_notify_state(CanardInstance* canard_instance, CanardRxTransfer* transfer); + void handle_hardpoint_command(CanardInstance* canard_instance, CanardRxTransfer* transfer); void process1HzTasks(uint64_t timestamp_usec); void processTx(void); diff --git a/Tools/AP_Periph/Parameters.cpp b/Tools/AP_Periph/Parameters.cpp index 2faf850167d598..d425ad6c7c2525 100644 --- a/Tools/AP_Periph/Parameters.cpp +++ b/Tools/AP_Periph/Parameters.cpp @@ -644,6 +644,12 @@ const AP_Param::Info AP_Periph_FW::var_info[] = { GOBJECT(rtc, "RTC", AP_RTC), #endif +#ifdef HAL_PERIPH_ENABLE_RELAY + // @Group: RELAY + // @Path: ../libraries/AP_Relay/AP_Relay.cpp + GOBJECT(relay, "RELAY", AP_Relay), +#endif + AP_VAREND }; diff --git a/Tools/AP_Periph/Parameters.h b/Tools/AP_Periph/Parameters.h index 9ff079217a22ec..884f1c4e64baa0 100644 --- a/Tools/AP_Periph/Parameters.h +++ b/Tools/AP_Periph/Parameters.h @@ -89,6 +89,7 @@ class Parameters { k_param_can_terminate1, k_param_can_terminate2, k_param_serial_options, + k_param_relay, }; AP_Int16 format_version; diff --git a/Tools/AP_Periph/can.cpp b/Tools/AP_Periph/can.cpp index dc3aa334ed0c5e..9000ab4e33431a 100644 --- a/Tools/AP_Periph/can.cpp +++ b/Tools/AP_Periph/can.cpp @@ -848,6 +848,13 @@ void AP_Periph_FW::onTransferReceived(CanardInstance* canard_instance, handle_notify_state(canard_instance, transfer); break; #endif + +#ifdef HAL_PERIPH_ENABLE_RELAY + case UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_ID: + handle_hardpoint_command(canard_instance, transfer); + break; +#endif + } } @@ -956,6 +963,11 @@ bool AP_Periph_FW::shouldAcceptTransfer(const CanardInstance* canard_instance, case ARDUPILOT_INDICATION_NOTIFYSTATE_ID: *out_data_type_signature = ARDUPILOT_INDICATION_NOTIFYSTATE_SIGNATURE; return true; +#endif +#ifdef HAL_PERIPH_ENABLE_RELAY + case UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_ID: + *out_data_type_signature = UAVCAN_EQUIPMENT_HARDPOINT_COMMAND_SIGNATURE; + return true; #endif default: break; diff --git a/Tools/AP_Periph/relay.cpp b/Tools/AP_Periph/relay.cpp new file mode 100644 index 00000000000000..925211c2003fce --- /dev/null +++ b/Tools/AP_Periph/relay.cpp @@ -0,0 +1,38 @@ +#include "AP_Periph.h" + +#ifdef HAL_PERIPH_ENABLE_RELAY + +#include + +void AP_Periph_FW::handle_hardpoint_command(CanardInstance* canard_instance, CanardRxTransfer* transfer) +{ + uavcan_equipment_hardpoint_Command cmd {}; + if (uavcan_equipment_hardpoint_Command_decode(transfer, &cmd)) { + // Failed to decode + return; + } + + // Command must be 0 or 1, other values may be supported in the future + // rejecting them now ensures no change in behaviour + if ((cmd.command != 0) && (cmd.command != 1)) { + return; + } + + // Translate hardpoint ID to relay function + AP_Relay_Params::FUNCTION fun; + switch (cmd.hardpoint_id) { + case 0 ... 15: + // 0 to 15 are continuous + fun = AP_Relay_Params::FUNCTION(cmd.hardpoint_id + (uint8_t)AP_Relay_Params::FUNCTION::DroneCAN_HARDPOINT_0); + break; + + default: + // ID not supported + return; + } + + // Set relay + relay.set(fun, cmd.command); + +} +#endif diff --git a/Tools/AP_Periph/wscript b/Tools/AP_Periph/wscript index da728bdcf4e282..a3b92b0150a111 100644 --- a/Tools/AP_Periph/wscript +++ b/Tools/AP_Periph/wscript @@ -81,6 +81,7 @@ def build(bld): 'AP_RobotisServo', 'AP_FETtecOneWire', 'GCS_MAVLink', + 'AP_Relay' ] bld.ap_stlib( From 0467ccc1fdc4e08fa58749dc5bc3d32b927d22c7 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 14 Dec 2023 14:56:12 +0000 Subject: [PATCH 0467/1335] RC_Channel: add Ghost and DroneCAN to list of enabled protocols --- libraries/RC_Channel/RC_Channels_VarInfo.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/RC_Channel/RC_Channels_VarInfo.h b/libraries/RC_Channel/RC_Channels_VarInfo.h index 8302be931d6a52..a824cc1ececc34 100644 --- a/libraries/RC_Channel/RC_Channels_VarInfo.h +++ b/libraries/RC_Channel/RC_Channels_VarInfo.h @@ -101,7 +101,7 @@ const AP_Param::GroupInfo RC_Channels::var_info[] = { // @DisplayName: RC protocols enabled // @Description: Bitmask of enabled RC protocols. Allows narrowing the protocol detection to only specific types of RC receivers which can avoid issues with incorrect detection. Set to 1 to enable all protocols. // @User: Advanced - // @Bitmask: 0:All,1:PPM,2:IBUS,3:SBUS,4:SBUS_NI,5:DSM,6:SUMD,7:SRXL,8:SRXL2,9:CRSF,10:ST24,11:FPORT,12:FPORT2,13:FastSBUS + // @Bitmask: 0:All,1:PPM,2:IBUS,3:SBUS,4:SBUS_NI,5:DSM,6:SUMD,7:SRXL,8:SRXL2,9:CRSF,10:ST24,11:FPORT,12:FPORT2,13:FastSBUS,14:DroneCAN,15:Ghost AP_GROUPINFO("_PROTOCOLS", 34, RC_CHANNELS_SUBCLASS, _protocols, 1), // @Param: _FS_TIMEOUT From 19c6b0b8aea8332e9f49fb1533375adf2d32d1eb Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Wed, 13 Dec 2023 08:47:51 +0000 Subject: [PATCH 0468/1335] AP_RCProtocol: IRC Ghost protocol --- libraries/AP_RCProtocol/AP_RCProtocol.cpp | 12 + libraries/AP_RCProtocol/AP_RCProtocol.h | 6 + .../AP_RCProtocol/AP_RCProtocol_GHST.cpp | 434 ++++++++++++++++++ libraries/AP_RCProtocol/AP_RCProtocol_GHST.h | 198 ++++++++ .../AP_RCProtocol/AP_RCProtocol_config.h | 4 + 5 files changed, 654 insertions(+) create mode 100644 libraries/AP_RCProtocol/AP_RCProtocol_GHST.cpp create mode 100644 libraries/AP_RCProtocol/AP_RCProtocol_GHST.h diff --git a/libraries/AP_RCProtocol/AP_RCProtocol.cpp b/libraries/AP_RCProtocol/AP_RCProtocol.cpp index 9c8ef679a1643b..9d9174e89f3489 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol.cpp @@ -33,6 +33,7 @@ #include "AP_RCProtocol_FPort.h" #include "AP_RCProtocol_FPort2.h" #include "AP_RCProtocol_DroneCAN.h" +#include "AP_RCProtocol_GHST.h" #include #include @@ -82,6 +83,9 @@ void AP_RCProtocol::init() #if AP_RCPROTOCOL_DRONECAN_ENABLED backend[AP_RCProtocol::DRONECAN] = new AP_RCProtocol_DroneCAN(*this); #endif +#if AP_RCPROTOCOL_GHST_ENABLED + backend[AP_RCProtocol::GHST] = new AP_RCProtocol_GHST(*this); +#endif } AP_RCProtocol::~AP_RCProtocol() @@ -303,6 +307,10 @@ static const AP_RCProtocol::SerialConfig serial_configs[] { // CRSFv3 can negotiate higher rates which are sticky on soft reboot { 2000000, 0, 1, false }, #endif +#if AP_RCPROTOCOL_GHST_ENABLED + // Ghost: + { 420000, 0, 1, false }, +#endif }; static_assert(ARRAY_SIZE(serial_configs) > 1, "must have at least one serial config"); @@ -504,6 +512,10 @@ const char *AP_RCProtocol::protocol_name_from_protocol(rcprotocol_t protocol) #if AP_RCPROTOCOL_DRONECAN_ENABLED case DRONECAN: return "DroneCAN"; +#endif +#if AP_RCPROTOCOL_GHST_ENABLED + case GHST: + return "GHST"; #endif case NONE: break; diff --git a/libraries/AP_RCProtocol/AP_RCProtocol.h b/libraries/AP_RCProtocol/AP_RCProtocol.h index eeacb6fa0a0b62..8889fdce89ee49 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol.h @@ -69,6 +69,9 @@ class AP_RCProtocol { #endif #if AP_RCPROTOCOL_DRONECAN_ENABLED DRONECAN = 13, +#endif +#if AP_RCPROTOCOL_GHST_ENABLED + GHST = 14, #endif NONE //last enum always is None }; @@ -129,6 +132,9 @@ class AP_RCProtocol { #endif #if AP_RCPROTOCOL_CRSF_ENABLED case CRSF: +#endif +#if AP_RCPROTOCOL_GHST_ENABLED + case GHST: #endif return true; #if AP_RCPROTOCOL_IBUS_ENABLED diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_GHST.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_GHST.cpp new file mode 100644 index 00000000000000..1f2fa06950c887 --- /dev/null +++ b/libraries/AP_RCProtocol/AP_RCProtocol_GHST.cpp @@ -0,0 +1,434 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ +/* + GHST protocol decoder based on betaflight implementation + Code by Andy Piper + */ + +#include "AP_RCProtocol_config.h" + +#if AP_RCPROTOCOL_GHST_ENABLED + +#include "AP_RCProtocol.h" +#include "AP_RCProtocol_GHST.h" +#include +#include +#include +#include +#include +#include + +/* + * GHST protocol + * + * GHST protocol uses a single wire half duplex uart connection. + * + * 420000 baud + * not inverted + * 8 Bit + * 1 Stop bit + * Big endian + * Max frame size is 14 bytes + * + * Every frame has the structure: + * + * + * Device address: (uint8_t) + * Frame length: length in bytes including Type (uint8_t) + * Type: (uint8_t) + * CRC: (uint8_t) + * + */ + +extern const AP_HAL::HAL& hal; + +//#define GHST_DEBUG +//#define GHST_DEBUG_CHARS +#ifdef GHST_DEBUG +# define debug(fmt, args...) hal.console->printf("GHST: " fmt "\n", ##args) +static const char* get_frame_type(uint8_t byte, uint8_t subtype = 0) +{ + switch(byte) { + case AP_RCProtocol_GHST::GHST_UL_RC_CHANS_HS4_5TO8: + case AP_RCProtocol_GHST::GHST_UL_RC_CHANS_HS4_12_5TO8: + return "RC5_8"; + case AP_RCProtocol_GHST::GHST_UL_RC_CHANS_HS4_9TO12: + case AP_RCProtocol_GHST::GHST_UL_RC_CHANS_HS4_12_9TO12: + return "RC9_12"; + case AP_RCProtocol_GHST::GHST_UL_RC_CHANS_HS4_13TO16: + case AP_RCProtocol_GHST::GHST_UL_RC_CHANS_HS4_12_13TO16: + return "RC13_16"; + case AP_RCProtocol_GHST::GHST_UL_RC_CHANS_RSSI: + case AP_RCProtocol_GHST::GHST_UL_RC_CHANS_12_RSSI: + return "RSSI"; + case AP_RCProtocol_GHST::GHST_UL_RC_VTX_CTRL: + return "VTX_CTRL"; + case AP_RCProtocol_GHST::GHST_UL_VTX_SETUP: + return "VTX_SETUP"; + } + return "UNKNOWN"; +} +#else +# define debug(fmt, args...) do {} while(0) +#endif + +#define GHST_MAX_FRAME_TIME_US 500U // 14 bytes @ 420k = ~450us +#define GHST_FRAME_TIMEOUT_US 10000U // 10ms to account for scheduling delays +#define GHST_INTER_FRAME_TIME_US 2000U // At fastest, frames are sent by the transmitter every 2 ms, 500 Hz +#define GHST_HEADER_TYPE_LEN (GHST_HEADER_LEN + 1) // header length including type + +const uint16_t AP_RCProtocol_GHST::RF_MODE_RATES[RFMode::RF_MODE_MAX_MODES] = { + 55, 160, 250, 19, 250, 500, 150, 250, +}; + +AP_RCProtocol_GHST* AP_RCProtocol_GHST::_singleton; + +AP_RCProtocol_GHST::AP_RCProtocol_GHST(AP_RCProtocol &_frontend) : AP_RCProtocol_Backend(_frontend) +{ +#if !APM_BUILD_TYPE(APM_BUILD_UNKNOWN) + if (_singleton != nullptr) { + AP_HAL::panic("Duplicate GHST handler"); + } + + _singleton = this; +#else + if (_singleton == nullptr) { + _singleton = this; + } +#endif +} + +AP_RCProtocol_GHST::~AP_RCProtocol_GHST() { + _singleton = nullptr; +} + +// get the protocol string +const char* AP_RCProtocol_GHST::get_protocol_string() const { + return "GHST"; +} + +// return the link rate as defined by the LinkStatistics +uint16_t AP_RCProtocol_GHST::get_link_rate() const { + return RF_MODE_RATES[_link_status.rf_mode - GHST_RF_MODE_NORMAL]; +} + +void AP_RCProtocol_GHST::_process_byte(uint32_t timestamp_us, uint8_t byte) +{ + //debug("process_byte(0x%x)", byte); + // we took too long decoding, start again - the RX will only send complete frames so this is unlikely to fail, + // however thread scheduling can introduce longer delays even when the data has been received + if (_frame_ofs > 0 && (timestamp_us - _start_frame_time_us) > GHST_FRAME_TIMEOUT_US) { + _frame_ofs = 0; + } + + // overflow check + if (_frame_ofs >= GHST_FRAMELEN_MAX) { + _frame_ofs = 0; + } + + // start of a new frame + if (_frame_ofs == 0) { + _start_frame_time_us = timestamp_us; + } + + add_to_buffer(_frame_ofs++, byte); + + // need a header to get the length + if (_frame_ofs < GHST_HEADER_TYPE_LEN) { + return; + } + + // parse the length + if (_frame_ofs == GHST_HEADER_TYPE_LEN) { + _frame_crc = crc8_dvb_s2(0, _frame.type); + // check for garbage frame + if (_frame.length > GHST_FRAME_PAYLOAD_MAX) { + _frame_ofs = 0; + } + return; + } + + // update crc + if (_frame_ofs < _frame.length + GHST_HEADER_LEN) { + _frame_crc = crc8_dvb_s2(_frame_crc, byte); + } + + // overflow check + if (_frame_ofs > _frame.length + GHST_HEADER_LEN) { + _frame_ofs = 0; + return; + } + + // decode whatever we got and expect + if (_frame_ofs == _frame.length + GHST_HEADER_LEN) { + log_data(AP_RCProtocol::GHST, timestamp_us, (const uint8_t*)&_frame, _frame_ofs - GHST_HEADER_LEN); + + // we consumed the partial frame, reset + _frame_ofs = 0; + + // bad CRC (payload start is +1 from frame start, so need to subtract that from frame length to get index) + if (_frame_crc != _frame.payload[_frame.length - 2]) { + return; + } + + _last_frame_time_us = _last_rx_frame_time_us = timestamp_us; + // decode here + if (decode_ghost_packet()) { + _last_tx_frame_time_us = timestamp_us; // we have received a frame from the transmitter + add_input(MAX_CHANNELS, _channels, false, _link_status.rssi, _link_status.link_quality); + } + } +} + +void AP_RCProtocol_GHST::update(void) +{ +} + +// write out a frame of any type +bool AP_RCProtocol_GHST::write_frame(Frame* frame) +{ + AP_HAL::UARTDriver *uart = get_current_UART(); + + if (!uart) { + return false; + } + + // check that we haven't been too slow in responding to the new UART data. If we respond too late then we will + // corrupt the next incoming control frame. incoming packets at max 126bits @500Hz @420k baud gives total budget of 2ms + // per packet of which we need 300us to receive a packet. outgoing packets are 126bits which require 300us to send + // leaving at most 1.4ms of delay that can be tolerated + uint64_t tend = uart->receive_time_constraint_us(1); + uint64_t now = AP_HAL::micros64(); + uint64_t tdelay = now - tend; + if (tdelay > 1000) { + // we've been too slow in responding + return false; + } + + // calculate crc + uint8_t crc = crc8_dvb_s2(0, frame->type); + for (uint8_t i = 0; i < frame->length - 2; i++) { + crc = crc8_dvb_s2(crc, frame->payload[i]); + } + frame->payload[frame->length - 2] = crc; + + uart->write((uint8_t*)frame, frame->length + 2); + uart->flush(); + +#ifdef GHST_DEBUG + hal.console->printf("GHST: writing %s:", get_frame_type(frame->type, frame->payload[0])); + for (uint8_t i = 0; i < frame->length + 2; i++) { + uint8_t val = ((uint8_t*)frame)[i]; +#ifdef GHST_DEBUG_CHARS + if (val >= 32 && val <= 126) { + hal.console->printf(" 0x%x '%c'", val, (char)val); + } else { +#endif + hal.console->printf(" 0x%x", val); +#ifdef GHST_DEBUG_CHARS + } +#endif + } + hal.console->printf("\n"); +#endif + return true; +} + +bool AP_RCProtocol_GHST::decode_ghost_packet() +{ +#ifdef GHST_DEBUG + hal.console->printf("GHST: received %s:", get_frame_type(_frame.type)); + uint8_t* fptr = (uint8_t*)&_frame; + for (uint8_t i = 0; i < _frame.length + 2; i++) { +#ifdef GHST_DEBUG_CHARS + if (fptr[i] >= 32 && fptr[i] <= 126) { + hal.console->printf(" 0x%x '%c'", fptr[i], (char)fptr[i]); + } else { +#endif + hal.console->printf(" 0x%x", fptr[i]); +#ifdef GHST_DEBUG_CHARS + } +#endif + } + hal.console->printf("\n"); +#endif + + const RadioFrame* radio_frame = (const RadioFrame*)(&_frame.payload); + const Channels12Bit_4Chan* channels = &(radio_frame->channels); + const uint8_t* lowres_channels = radio_frame->lowres_channels; + + // Scaling from Betaflight + // Scaling 12bit channels (8bit channels in brackets) + // OpenTx RC PWM (BF) + // min -1024 0( 0) 988us + // ctr 0 2048(128) 1500us + // max 1024 4096(256) 2012us + // + + // Scaling legacy (nearly 10bit) + // derived from original SBus scaling, with slight correction for offset + // now symmetrical around OpenTx 0 value + // scaling is: + // OpenTx RC PWM (BF) + // min -1024 172( 22) 988us + // ctr 0 992(124) 1500us + // max 1024 1811(226) 2012us + +#define CHANNEL_RESCALE(x) (((5 * x) >> 2) - 430) +#define CHANNEL_SCALE(x) (int32_t(x) / 4 + 988) +#define CHANNEL_SCALE_LEGACY(x) CHANNEL_SCALE(CHANNEL_RESCALE(x)) + + // legacy scaling + if (_frame.type >= GHST_UL_RC_CHANS_HS4_5TO8 && _frame.type <= GHST_UL_RC_CHANS_RSSI) { + _channels[0] = CHANNEL_SCALE_LEGACY(channels->ch0); + _channels[1] = CHANNEL_SCALE_LEGACY(channels->ch1); + _channels[2] = CHANNEL_SCALE_LEGACY(channels->ch2); + _channels[3] = CHANNEL_SCALE_LEGACY(channels->ch3); + } else { + _channels[0] = CHANNEL_SCALE(channels->ch0); + _channels[1] = CHANNEL_SCALE(channels->ch1); + _channels[2] = CHANNEL_SCALE(channels->ch2); + _channels[3] = CHANNEL_SCALE(channels->ch3); + } + +#define CHANNEL_LR_RESCALE(x) (5 * x - 108) +#define CHANNEL_LR_SCALE(x) (int32_t(x) * 2 + 988) +#define CHANNEL_LR_SCALE_LEGACY(x) (CHANNEL_LR_RESCALE(x) + 988) + + switch (_frame.type) { + case GHST_UL_RC_CHANS_HS4_5TO8: + case GHST_UL_RC_CHANS_HS4_9TO12: + case GHST_UL_RC_CHANS_HS4_13TO16: { + uint8_t offset = (_frame.type - GHST_UL_RC_CHANS_HS4_5TO8 + 1) * 4; + _channels[offset++] = CHANNEL_LR_SCALE_LEGACY(lowres_channels[0]); + _channels[offset++] = CHANNEL_LR_SCALE_LEGACY(lowres_channels[1]); + _channels[offset++] = CHANNEL_LR_SCALE_LEGACY(lowres_channels[2]); + _channels[offset++] = CHANNEL_LR_SCALE_LEGACY(lowres_channels[3]); + break; + } + case GHST_UL_RC_CHANS_HS4_12_5TO8: + case GHST_UL_RC_CHANS_HS4_12_9TO12: + case GHST_UL_RC_CHANS_HS4_12_13TO16: { + uint8_t offset = (_frame.type - GHST_UL_RC_CHANS_HS4_12_5TO8 + 1) * 4; + _channels[offset++] = CHANNEL_LR_SCALE(lowres_channels[0]); + _channels[offset++] = CHANNEL_LR_SCALE(lowres_channels[1]); + _channels[offset++] = CHANNEL_LR_SCALE(lowres_channels[2]); + _channels[offset++] = CHANNEL_LR_SCALE(lowres_channels[3]); + break; + } + case GHST_UL_RC_CHANS_RSSI: + case GHST_UL_RC_CHANS_12_RSSI: + process_link_stats_frame((uint8_t*)&_frame.payload); + break; + + default: + break; + } + +#if AP_GHST_TELEM_ENABLED + if (AP_GHST_Telem::process_frame(FrameType(_frame.type), (uint8_t*)&_frame.payload)) { + process_telemetry(); + } +#endif + + return true; +} + +// send out telemetry +bool AP_RCProtocol_GHST::process_telemetry(bool check_constraint) +{ + + AP_HAL::UARTDriver *uart = get_current_UART(); + if (!uart) { + return false; + } + + if (!telem_available) { +#if AP_GHST_TELEM_ENABLED && !APM_BUILD_TYPE(APM_BUILD_iofirmware) + if (AP_GHST_Telem::get_telem_data(&_telemetry_frame, is_tx_active())) { + telem_available = true; + } else { + return false; + } +#else + return false; +#endif + } + if (!write_frame(&_telemetry_frame)) { + return false; + } + + // get fresh telem_data in the next call + telem_available = false; + + return true; +} + +// process link statistics to get RSSI +void AP_RCProtocol_GHST::process_link_stats_frame(const void* data) +{ + const LinkStatisticsFrame* link = (const LinkStatisticsFrame*)data; + + uint8_t rssi_dbm; + rssi_dbm = link->rssi_dbm; + _link_status.link_quality = link->link_quality; + if (_use_lq_for_rssi) { + _link_status.rssi = derive_scaled_lq_value(link->link_quality); + } else{ + // AP rssi: -1 for unknown, 0 for no link, 255 for maximum link + if (rssi_dbm < 50) { + _link_status.rssi = 255; + } else if (rssi_dbm > 120) { + _link_status.rssi = 0; + } else { + // this is an approximation recommended by Remo from TBS + _link_status.rssi = int16_t(roundf((1.0f - (rssi_dbm - 50.0f) / 70.0f) * 255.0f)); + } + } + + _link_status.rf_mode = link->protocol; +} + +bool AP_RCProtocol_GHST::is_telemetry_supported() const +{ + return _link_status.rf_mode == AP_RCProtocol_GHST::GHST_RF_MODE_NORMAL + || _link_status.rf_mode == AP_RCProtocol_GHST::GHST_RF_MODE_RACE + || _link_status.rf_mode == AP_RCProtocol_GHST::GHST_RF_MODE_LR + || _link_status.rf_mode == AP_RCProtocol_GHST::GHST_RF_MODE_RACE250; +} + +// process a byte provided by a uart +void AP_RCProtocol_GHST::process_byte(uint8_t byte, uint32_t baudrate) +{ + // reject RC data if we have been configured for standalone mode + if (baudrate != GHST_BAUDRATE) { + return; + } + _process_byte(AP_HAL::micros(), byte); +} + +//returns uplink link quality on 0-255 scale +int16_t AP_RCProtocol_GHST::derive_scaled_lq_value(uint8_t uplink_lq) +{ + return int16_t(roundf(constrain_float(uplink_lq*2.5f,0,255))); +} + +namespace AP { + AP_RCProtocol_GHST* ghost() { + return AP_RCProtocol_GHST::get_singleton(); + } +}; + +#endif // AP_RCPROTOCOL_GHST_ENABLED diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_GHST.h b/libraries/AP_RCProtocol/AP_RCProtocol_GHST.h new file mode 100644 index 00000000000000..e710a70fa99cab --- /dev/null +++ b/libraries/AP_RCProtocol/AP_RCProtocol_GHST.h @@ -0,0 +1,198 @@ +/* + * This file is free software: you can redistribute it and/or modify it + * under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + * See the GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program. If not, see . + */ +#pragma once + +#include "AP_RCProtocol_config.h" + +#if AP_RCPROTOCOL_GHST_ENABLED + +#include "AP_RCProtocol.h" +#include +#include +#include "SoftSerial.h" + +#define GHST_MAX_CHANNELS 16U // Maximum number of channels from GHST datastream +#define GHST_FRAMELEN_MAX 14U // maximum possible framelength +#define GHST_HEADER_LEN 2U // header length +#define GHST_FRAME_PAYLOAD_MAX (GHST_FRAMELEN_MAX - GHST_HEADER_LEN) // maximum size of the frame length field in a packet +#define GHST_BAUDRATE 420000U +#define GHST_TX_TIMEOUT 500000U // the period after which the transmitter is considered disconnected (matches copters failsafe) +#define GHST_RX_TIMEOUT 150000U // the period after which the receiver is considered disconnected (>ping frequency) + +class AP_RCProtocol_GHST : public AP_RCProtocol_Backend { +public: + AP_RCProtocol_GHST(AP_RCProtocol &_frontend); + virtual ~AP_RCProtocol_GHST(); + void process_byte(uint8_t byte, uint32_t baudrate) override; + void update(void) override; + + // is the receiver active, used to detect power loss and baudrate changes + bool is_rx_active() const override { + return AP_HAL::micros() < _last_rx_frame_time_us + GHST_RX_TIMEOUT; + } + + // is the transmitter active, used to adjust telemetry data + bool is_tx_active() const { + // this is the same as the Copter failsafe timeout + return AP_HAL::micros() < _last_tx_frame_time_us + GHST_TX_TIMEOUT; + } + + // get singleton instance + static AP_RCProtocol_GHST* get_singleton() { + return _singleton; + } + + enum FrameType { + GHST_UL_RC_CHANS_HS4_5TO8 = 0x10, // Control packet with 4 primary channels + CH5-8 + GHST_UL_RC_CHANS_HS4_9TO12 = 0x11, // Control packet with 4 primary channels + CH9-12 + GHST_UL_RC_CHANS_HS4_13TO16 = 0x12, // Control packet with 4 primary channels + CH13-16 + GHST_UL_RC_CHANS_RSSI = 0x13, // Control packet with RSSI and LQ data + GHST_UL_RC_VTX_CTRL = 0x14, // Goggle/FC channel changing + // -> 0x1F reserved + GHST_UL_VTX_SETUP = 0x20, // vTx Setup w/o 4 primary channels (GECO Only) + GHST_UL_MSP_REQ = 0x21, // MSP frame, Request + GHST_UL_MSP_WRITE = 0x22, // MSP frame, Write + + GHST_DL_PACK_STAT = 0x23, // Battery Status + GHST_DL_GPS_PRIMARY = 0x25, // Primary GPS Data + GHST_DL_GPS_SECONDARY = 0x26, // Secondary GPS Data + GHST_DL_MAGBARO = 0x27, // Magnetometer, Barometer (and Vario) Data + GHST_DL_MSP_RESP = 0x28, // MSP Response + + GHST_UL_RC_CHANS_HS4_12_5TO8 = 0x30, // Control packet with 4 primary channels + CH5-8 + GHST_UL_RC_CHANS_HS4_12_9TO12 = 0x31, // Control packet with 4 primary channels + CH9-12 + GHST_UL_RC_CHANS_HS4_12_13TO16 = 0x32, // Control packet with 4 primary channels + CH13-16 + GHST_UL_RC_CHANS_12_RSSI = 0x33, // Control packet with RSSI and LQ data + // 0x30 -> 0x3f - raw 12 bit packets + }; + + enum DeviceAddress { + GHST_ADDRESS_FLIGHT_CONTROLLER = 0x82, + GHST_ADDRESS_GOGGLES = 0x83, + GHST_ADDRESS_GHST_RECEIVER = 0x89, + }; + + struct Frame { + uint8_t device_address; + uint8_t length; + uint8_t type; + uint8_t payload[GHST_FRAME_PAYLOAD_MAX - 1]; // type is already accounted for + } PACKED; + + struct Channels12Bit_4Chan { +#if __BYTE_ORDER != __LITTLE_ENDIAN +#error "Only supported on little-endian architectures" +#endif + uint32_t ch0 : 12; + uint32_t ch1 : 12; + uint32_t ch2 : 12; + uint32_t ch3 : 12; + } PACKED; + + struct RadioFrame { +#if __BYTE_ORDER != __LITTLE_ENDIAN +#error "Only supported on little-endian architectures" +#endif + Channels12Bit_4Chan channels; // high-res channels + uint8_t lowres_channels[4]; // low-res channels + } PACKED; + + struct LinkStatisticsFrame { +#if __BYTE_ORDER != __LITTLE_ENDIAN +#error "Only supported on little-endian architectures" +#endif + Channels12Bit_4Chan channels; + uint8_t link_quality; // ( 0 - 100) + uint8_t rssi_dbm; // ( dBm * -1 ) + uint8_t protocol : 5; + uint8_t telemetry : 1; + uint8_t alt_scale : 1; + uint8_t reserved : 1; + int8_t tx_power; + } PACKED; + + enum RFMode { + GHST_RF_MODE_NORMAL = 5, // 55Hz + GHST_RF_MODE_RACE = 6, // 160Hz + GHST_RF_MODE_PURERACE = 7, // 250Hz + GHST_RF_MODE_LR = 8, // 19Hz + GHST_RF_MODE_RACE250 = 10, // 250Hz + GHST_RF_MODE_RACE500 = 11, // 500Hz + GHTS_RF_MODE_SOLID150 = 12, // 150Hz + GHST_RF_MODE_SOLID250 = 13, // 250Hz + RF_MODE_MAX_MODES, + RF_MODE_UNKNOWN, + }; + + struct LinkStatus { + int16_t rssi = -1; + int16_t link_quality = -1; + uint8_t rf_mode; + }; + + bool is_telemetry_supported() const; + + // this will be used by AP_GHST_Telem to access link status data + // from within AP_RCProtocol_GHST thread so no need for cross-thread synch + const volatile LinkStatus& get_link_status() const { + return _link_status; + } + + // return the link rate as defined by the LinkStatistics + uint16_t get_link_rate() const; + + // return the protocol string + const char* get_protocol_string() const; + +private: + struct Frame _frame; + struct Frame _telemetry_frame; + uint8_t _frame_ofs; + uint8_t _frame_crc; + + const uint8_t MAX_CHANNELS = MIN((uint8_t)GHST_MAX_CHANNELS, (uint8_t)MAX_RCIN_CHANNELS); + + static AP_RCProtocol_GHST* _singleton; + + void _process_byte(uint32_t timestamp_us, uint8_t byte); + bool decode_ghost_packet(); + bool process_telemetry(bool check_constraint = true); + void process_link_stats_frame(const void* data); + bool write_frame(Frame* frame); + AP_HAL::UARTDriver* get_current_UART() { return get_available_UART(); } + + uint16_t _channels[GHST_MAX_CHANNELS]; /* buffer for extracted RC channel data as pulsewidth in microseconds */ + + void add_to_buffer(uint8_t index, uint8_t b) { ((uint8_t*)&_frame)[index] = b; } + + uint32_t _last_frame_time_us; + uint32_t _last_tx_frame_time_us; + uint32_t _last_uart_start_time_ms; + uint32_t _last_rx_frame_time_us; + uint32_t _start_frame_time_us; + bool telem_available; + bool _use_lq_for_rssi; + int16_t derive_scaled_lq_value(uint8_t uplink_lq); + + volatile struct LinkStatus _link_status; + + static const uint16_t RF_MODE_RATES[RFMode::RF_MODE_MAX_MODES]; +}; + +namespace AP { + AP_RCProtocol_GHST* ghost(); +}; + +#endif // AP_RCPROTOCOL_GHST_ENABLED diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_config.h b/libraries/AP_RCProtocol/AP_RCProtocol_config.h index 5619c5373c0819..d6bef7d61bb01b 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_config.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol_config.h @@ -61,3 +61,7 @@ #ifndef AP_RCPROTOCOL_FASTSBUS_ENABLED #define AP_RCPROTOCOL_FASTSBUS_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED && AP_RCPROTOCOL_SBUS_ENABLED #endif + +#ifndef AP_RCPROTOCOL_GHST_ENABLED +#define AP_RCPROTOCOL_GHST_ENABLED AP_RCPROTOCOL_BACKEND_DEFAULT_ENABLED +#endif From 0da6989c8e00ca6b1eabf1e2783fedf064017688 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Wed, 13 Dec 2023 11:14:40 +0000 Subject: [PATCH 0469/1335] AP_RCTelemetry: IRC Ghost protocol --- libraries/AP_RCTelemetry/AP_GHST_Telem.cpp | 386 ++++++++++++++++++ libraries/AP_RCTelemetry/AP_GHST_Telem.h | 166 ++++++++ .../AP_RCTelemetry/AP_RCTelemetry_config.h | 4 + 3 files changed, 556 insertions(+) create mode 100644 libraries/AP_RCTelemetry/AP_GHST_Telem.cpp create mode 100644 libraries/AP_RCTelemetry/AP_GHST_Telem.h diff --git a/libraries/AP_RCTelemetry/AP_GHST_Telem.cpp b/libraries/AP_RCTelemetry/AP_GHST_Telem.cpp new file mode 100644 index 00000000000000..72e2d2a09e7e00 --- /dev/null +++ b/libraries/AP_RCTelemetry/AP_GHST_Telem.cpp @@ -0,0 +1,386 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . +*/ + +#include "AP_RCTelemetry_config.h" + +#if AP_GHST_TELEM_ENABLED + +#include "AP_GHST_Telem.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +//#define GHST_DEBUG +#ifdef GHST_DEBUG +# define debug(fmt, args...) hal.console->printf("GHST: " fmt "\n", ##args) +#else +# define debug(fmt, args...) do {} while(0) +#endif + +extern const AP_HAL::HAL& hal; + +AP_GHST_Telem *AP_GHST_Telem::singleton; + +AP_GHST_Telem::AP_GHST_Telem() : AP_RCTelemetry(0) +{ + singleton = this; +} + +AP_GHST_Telem::~AP_GHST_Telem(void) +{ + singleton = nullptr; +} + +bool AP_GHST_Telem::init(void) +{ + // sanity check that we are using a UART for RC input + if (!AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_RCIN, 0)) { + return false; + } + + return AP_RCTelemetry::init(); +} + +/* + setup ready for passthrough telem + */ +void AP_GHST_Telem::setup_wfq_scheduler(void) +{ + // initialize packet weights for the WFQ scheduler + // priority[i] = 1/_scheduler.packet_weight[i] + // rate[i] = LinkRate * ( priority[i] / (sum(priority[1-n])) ) + + // CSRF telemetry rate is 150Hz (4ms) max, so these rates must fit + add_scheduler_entry(50, 120); // Attitude and compass 8Hz + add_scheduler_entry(200, 1000); // VTX parameters 1Hz + add_scheduler_entry(1300, 500); // battery 2Hz + add_scheduler_entry(550, 280); // GPS 3Hz + add_scheduler_entry(550, 280); // GPS2 3Hz +} + +void AP_GHST_Telem::update_custom_telemetry_rates(AP_RCProtocol_GHST::RFMode rf_mode) +{ + if (is_high_speed_telemetry(rf_mode)) { + // standard telemetry for high data rates + set_scheduler_entry(BATTERY, 1000, 1000); // 1Hz + set_scheduler_entry(ATTITUDE, 1000, 1000); // 1Hz + // custom telemetry for high data rates + set_scheduler_entry(GPS, 550, 500); // 2.0Hz + set_scheduler_entry(GPS2, 550, 500); // 2.0Hz + } else { + // standard telemetry for low data rates + set_scheduler_entry(BATTERY, 1000, 2000); // 0.5Hz + set_scheduler_entry(ATTITUDE, 1000, 3000); // 0.33Hz + // GHST custom telemetry for low data rates + set_scheduler_entry(GPS, 550, 1000); // 1.0Hz + set_scheduler_entry(GPS2, 550, 1000); // 1.0Hz + } +} + +bool AP_GHST_Telem::process_rf_mode_changes() +{ + const AP_RCProtocol_GHST::RFMode current_rf_mode = get_rf_mode(); + uint32_t now = AP_HAL::millis(); + + AP_RCProtocol_GHST* ghost = AP::ghost(); + AP_HAL::UARTDriver* uart = nullptr; + if (ghost != nullptr) { + uart = ghost->get_UART(); + } + if (uart == nullptr) { + return true; + } + // not ready yet + if (!uart->is_initialized()) { + return false; + } +#if !defined (STM32H7) + // warn the user if their setup is sub-optimal, H7 does not need DMA on serial port + if (_telem_bootstrap_msg_pending && !uart->is_dma_enabled()) { + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "%s: running on non-DMA serial port", get_protocol_string()); + } +#endif + // note if option was set to show LQ in place of RSSI + bool current_lq_as_rssi_active = rc().option_is_enabled(RC_Channels::Option::USE_CRSF_LQ_AS_RSSI); + if(_telem_bootstrap_msg_pending || _noted_lq_as_rssi_active != current_lq_as_rssi_active){ + _noted_lq_as_rssi_active = current_lq_as_rssi_active; + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s: RSSI now displays %s", get_protocol_string(), current_lq_as_rssi_active ? " as LQ" : "normally"); + } + _telem_bootstrap_msg_pending = false; + + const bool is_high_speed = is_high_speed_telemetry(current_rf_mode); + if ((now - _telem_last_report_ms > 5000)) { + // report an RF mode change or a change in telemetry rate if we haven't done so in the last 5s + if (!rc().option_is_enabled(RC_Channels::Option::SUPPRESS_CRSF_MESSAGE) && (_rf_mode != current_rf_mode)) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s: Link rate %dHz, Telemetry %s", + get_protocol_string(), ghost->get_link_rate(), _enable_telemetry ? "ON" : "OFF"); + } + // tune the scheduler based on telemetry speed high/low transitions + if (_telem_is_high_speed != is_high_speed) { + update_custom_telemetry_rates(current_rf_mode); + } + _telem_is_high_speed = is_high_speed; + _rf_mode = current_rf_mode; + _telem_last_avg_rate = _scheduler.avg_packet_rate; + if (_telem_last_report_ms == 0) { // only want to show bootstrap messages once + _telem_bootstrap_msg_pending = true; + } + _telem_last_report_ms = now; + } + return true; +} + +AP_RCProtocol_GHST::RFMode AP_GHST_Telem::get_rf_mode() const +{ + AP_RCProtocol_GHST* ghost = AP::ghost(); + if (ghost == nullptr) { + return AP_RCProtocol_GHST::RFMode::RF_MODE_UNKNOWN; + } + + return static_cast(ghost->get_link_status().rf_mode); +} + +bool AP_GHST_Telem::is_high_speed_telemetry(const AP_RCProtocol_GHST::RFMode rf_mode) const +{ + return rf_mode == AP_RCProtocol_GHST::RFMode::GHST_RF_MODE_RACE || rf_mode == AP_RCProtocol_GHST::RFMode::GHST_RF_MODE_RACE250; +} + +uint16_t AP_GHST_Telem::get_telemetry_rate() const +{ + return get_avg_packet_rate(); +} + +// WFQ scheduler +bool AP_GHST_Telem::is_packet_ready(uint8_t idx, bool queue_empty) +{ + return _enable_telemetry; +} + +// WFQ scheduler +void AP_GHST_Telem::process_packet(uint8_t idx) +{ + // send packet + switch (idx) { + case ATTITUDE: + calc_attitude(); + break; + case BATTERY: // BATTERY + calc_battery(); + break; + case GPS: // GPS + calc_gps(); + break; + case GPS2: // GPS secondary info + calc_gps2(); + break; + default: + break; + } +} + +// Process a frame from the GHST protocol decoder +bool AP_GHST_Telem::_process_frame(AP_RCProtocol_GHST::FrameType frame_type, void* data) { + switch (frame_type) { + // this means we are connected to an RC receiver and can send telemetry + case AP_RCProtocol_GHST::GHST_UL_RC_CHANS_RSSI: { + process_rf_mode_changes(); + _enable_telemetry = AP::ghost()->is_telemetry_supported(); + break; + } + default: + break; + } + return true; +} + +// process any changed settings and schedule for transmission +void AP_GHST_Telem::update() +{ +} + +void AP_GHST_Telem::process_pending_requests() +{ + _pending_request.frame_type = 0; +} + +// prepare battery data +void AP_GHST_Telem::calc_battery() +{ + debug("BATTERY"); + const AP_BattMonitor &_battery = AP::battery(); + + _telem.battery.voltage = htole16(uint16_t(roundf(_battery.voltage(0) * 100.0f))); + + float current; + if (!_battery.current_amps(current, 0)) { + current = 0; + } + _telem.battery.current = htole16(uint16_t(roundf(current * 100.0f))); + + float used_mah; + if (!_battery.consumed_mah(used_mah, 0)) { + used_mah = 0; + } + + _telem.battery.consumed = htole16(uint16_t(roundf(used_mah * 100.0f)));; + _telem.battery.rx_voltage = htole16(uint16_t(roundf(hal.analogin->board_voltage() * 10))); + + _telem_size = sizeof(BatteryFrame); + _telem_type = AP_RCProtocol_GHST::GHST_DL_PACK_STAT; + + _telem_pending = true; +} + +// prepare gps data +void AP_GHST_Telem::calc_gps() +{ + debug("GPS"); + const Location &loc = AP::gps().location(0); // use the first gps instance (same as in send_mavlink_gps_raw) + + _telem.gps.latitude = htole32(loc.lat); + _telem.gps.longitude = htole32(loc.lng); + _telem.gps.altitude = htole16(constrain_int16(loc.alt / 100, 0, 5000) + 1000); + + _telem_size = sizeof(AP_GHST_Telem::GPSFrame); + _telem_type = AP_RCProtocol_GHST::GHST_DL_GPS_PRIMARY; + + _telem_pending = true; +} + +void AP_GHST_Telem::calc_gps2() +{ + debug("GPS2"); + _telem.gps2.groundspeed = htole16(roundf(AP::gps().ground_speed() * 100000 / 3600)); + _telem.gps2.gps_heading = htole16(roundf(AP::gps().ground_course() * 100.0f)); + _telem.gps2.satellites = AP::gps().num_sats(); + + AP_AHRS &_ahrs = AP::ahrs(); + WITH_SEMAPHORE(_ahrs.get_semaphore()); + Location loc; + + if (_ahrs.get_location(loc) && _ahrs.home_is_set()) { + const Location &home_loc = _ahrs.get_home(); + _telem.gps2.home_dist = home_loc.get_distance(loc) / 10; // 10m + _telem.gps2.home_heading = loc.get_bearing_to(home_loc) / 10; // deci-degrees + } else { + _telem.gps2.home_dist = 0; + _telem.gps2.home_heading = 0; + } + + AP_GPS::GPS_Status status = AP::gps().status(); + _telem.gps2.flags = status >= AP_GPS::GPS_OK_FIX_2D ? 0x1 : 0; + + _telem_size = sizeof(AP_GHST_Telem::GPSSecondaryFrame); + _telem_type = AP_RCProtocol_GHST::GHST_DL_GPS_SECONDARY; + + _telem_pending = true; +} + +// prepare attitude data +void AP_GHST_Telem::calc_attitude() +{ + debug("MAGBARO"); + AP_AHRS &_ahrs = AP::ahrs(); + WITH_SEMAPHORE(_ahrs.get_semaphore()); + + float heading = AP::compass().calculate_heading(_ahrs.get_rotation_body_to_ned()); + _telem.sensor.compass_heading = htole16(degrees(wrap_PI(heading))); + + float alt = AP::baro().get_altitude(); + _telem.sensor.baro_alt = htole16(roundf(alt)); + _telem.sensor.vario = 0; + _telem.sensor.flags = 3; + _telem_size = sizeof(AP_GHST_Telem::SensorFrame); + _telem_type = AP_RCProtocol_GHST::GHST_DL_MAGBARO; + + _telem_pending = true; +} + +/* + fetch GHST frame data + if is_tx_active is true then this will be a request for telemetry after receiving an RC frame + */ +bool AP_GHST_Telem::_get_telem_data(AP_RCProtocol_GHST::Frame* data, bool is_tx_active) +{ + memset(&_telem, 0, sizeof(TelemetryPayload)); + _is_tx_active = is_tx_active; + + run_wfq_scheduler(); + if (!_telem_pending) { + return false; + } + memcpy(data->payload, &_telem, _telem_size); + data->device_address = AP_RCProtocol_GHST::GHST_ADDRESS_GHST_RECEIVER; + data->length = _telem_size + 2; + data->type = _telem_type; + + _telem_pending = false; + return true; +} + +/* + fetch data for an external transport, such as GHST + */ +bool AP_GHST_Telem::process_frame(AP_RCProtocol_GHST::FrameType frame_type, void* data) +{ + if (!get_singleton()) { + return false; + } + return singleton->_process_frame(frame_type, data); +} + +/* + fetch data for an external transport, such as GHST + */ +bool AP_GHST_Telem::get_telem_data(AP_RCProtocol_GHST::Frame* data, bool is_tx_active) +{ + if (!get_singleton()) { + return false; + } + return singleton->_get_telem_data(data, is_tx_active); +} + +AP_GHST_Telem *AP_GHST_Telem::get_singleton(void) { + if (!singleton && !hal.util->get_soft_armed()) { + // if telem data is requested when we are disarmed and don't + // yet have a AP_GHST_Telem object then try to allocate one + new AP_GHST_Telem(); + // initialize the passthrough scheduler + if (singleton) { + singleton->init(); + } + } + return singleton; +} + +namespace AP { + AP_GHST_Telem *ghost_telem() { + return AP_GHST_Telem::get_singleton(); + } +}; + +#endif // AP_GHST_TELEM_ENABLED diff --git a/libraries/AP_RCTelemetry/AP_GHST_Telem.h b/libraries/AP_RCTelemetry/AP_GHST_Telem.h new file mode 100644 index 00000000000000..768470d9976bdb --- /dev/null +++ b/libraries/AP_RCTelemetry/AP_GHST_Telem.h @@ -0,0 +1,166 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . +*/ +#pragma once + +#include "AP_RCTelemetry_config.h" + +#if AP_GHST_TELEM_ENABLED + +#include +#include "AP_RCTelemetry.h" +#include + +class AP_GHST_Telem : public AP_RCTelemetry { +public: + AP_GHST_Telem(); + ~AP_GHST_Telem() override; + + /* Do not allow copies */ + CLASS_NO_COPY(AP_GHST_Telem); + + // init - perform required initialisation + virtual bool init() override; + + static AP_GHST_Telem *get_singleton(void); + + // Broadcast frame definitions courtesy of TBS + struct PACKED GPSFrame { + uint32_t latitude; // ( degree * 1e7 ) + uint32_t longitude; // (degree * 1e7 ) + int16_t altitude; // ( meter ) + }; + + struct PACKED GPSSecondaryFrame { + uint16_t groundspeed; // ( cm/s ) + uint16_t gps_heading; // ( degree * 10 ) + uint8_t satellites; // in use ( counter ) + uint16_t home_dist; // ( m / 10 ) + uint16_t home_heading; // ( degree * 10 ) + uint8_t flags; // GPS_FLAGS_FIX 0x01, GPS_FLAGS_FIX_HOME 0x2 + }; + + struct PACKED BatteryFrame { + uint16_t voltage; // ( mV / 10 ) + uint16_t current; // ( mA / 10 ) + uint16_t consumed; // ( mAh / 10 ) + uint8_t rx_voltage; // ( mV / 100 ) + uint8_t spare[3]; + }; + + struct PACKED VTXFrame { +#if __BYTE_ORDER != __LITTLE_ENDIAN +#error "Only supported on little-endian architectures" +#endif + uint8_t flags; + uint16_t frequency; // frequency in Mhz + uint16_t power; // power in mw, 0 == off + uint8_t band : 4; // A, B, E, AirWave, Race + uint8_t channel : 4; // 1x-8x + uint8_t spare[3]; + }; + + struct PACKED SensorFrame { + uint16_t compass_heading; // ( deg * 10 ) + int16_t baro_alt; // ( m ) + int16_t vario; // ( m/s * 100 ) + uint8_t spare[3]; + uint8_t flags; // MISC_FLAGS_MAGHEAD 0x01, MISC_FLAGS_BAROALT 0x02, MISC_FLAGS_VARIO 0x04 + }; + + union PACKED TelemetryPayload { + GPSFrame gps; + GPSSecondaryFrame gps2; + BatteryFrame battery; + VTXFrame vtx; + SensorFrame sensor; + }; + + // get the protocol string + const char* get_protocol_string() const { return AP::ghost()->get_protocol_string(); } + + // Process a frame from the CRSF protocol decoder + static bool process_frame(AP_RCProtocol_GHST::FrameType frame_type, void* data); + // process any changed settings and schedule for transmission + void update(); + // get next telemetry data for external consumers of SPort data + static bool get_telem_data(AP_RCProtocol_GHST::Frame* frame, bool is_tx_active); + +private: + + enum SensorType { + ATTITUDE, + VTX_PARAMETERS, + BATTERY, + GPS, + GPS2, + NUM_SENSORS + }; + + // passthrough WFQ scheduler + bool is_packet_ready(uint8_t idx, bool queue_empty) override; + void process_packet(uint8_t idx) override; + void setup_custom_telemetry(); + void update_custom_telemetry_rates(const AP_RCProtocol_GHST::RFMode rf_mode); + + void calc_battery(); + void calc_gps(); + void calc_gps2(); + void calc_attitude(); + void process_pending_requests(); + bool process_rf_mode_changes(); + AP_RCProtocol_GHST::RFMode get_rf_mode() const; + uint16_t get_telemetry_rate() const; + bool is_high_speed_telemetry(const AP_RCProtocol_GHST::RFMode rf_mode) const; + + // setup ready for passthrough operation + void setup_wfq_scheduler(void) override; + + // get next telemetry data for external consumers + bool _get_telem_data(AP_RCProtocol_GHST::Frame* data, bool is_tx_active); + bool _process_frame(AP_RCProtocol_GHST::FrameType frame_type, void* data); + + TelemetryPayload _telem; + uint8_t _telem_size; + uint8_t _telem_type; + + AP_RCProtocol_GHST::RFMode _rf_mode; + bool _enable_telemetry; + + // reporting telemetry rate + uint32_t _telem_last_report_ms; + uint16_t _telem_last_avg_rate; + // do we need to report the initial state + bool _telem_bootstrap_msg_pending; + + bool _telem_is_high_speed; + bool _telem_pending; + // used to limit telemetry when in a failsafe condition + bool _is_tx_active; + + struct { + uint8_t destination = 0; + uint8_t frame_type; + } _pending_request; + + bool _noted_lq_as_rssi_active; + + static AP_GHST_Telem *singleton; +}; + +namespace AP { + AP_GHST_Telem *ghost_telem(); +}; + +#endif // AP_GHST_TELEM_ENABLED diff --git a/libraries/AP_RCTelemetry/AP_RCTelemetry_config.h b/libraries/AP_RCTelemetry/AP_RCTelemetry_config.h index 8cfb33467db44a..9dab308187a796 100644 --- a/libraries/AP_RCTelemetry/AP_RCTelemetry_config.h +++ b/libraries/AP_RCTelemetry/AP_RCTelemetry_config.h @@ -16,3 +16,7 @@ #ifndef HAL_SPEKTRUM_TELEM_ENABLED #define HAL_SPEKTRUM_TELEM_ENABLED 1 #endif + +#ifndef AP_GHST_TELEM_ENABLED +#define AP_GHST_TELEM_ENABLED AP_RCPROTOCOL_GHST_ENABLED +#endif From 0df36a8d8136270910b066d85a6eabe68167fc4e Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Tue, 2 Jan 2024 18:20:46 +0000 Subject: [PATCH 0470/1335] AP_RCProtocol: bootstrap Ghost to correct baudrate --- libraries/AP_RCProtocol/AP_RCProtocol.cpp | 6 +----- .../AP_RCProtocol/AP_RCProtocol_GHST.cpp | 21 ++++++++++++++++++- libraries/AP_RCProtocol/AP_RCProtocol_GHST.h | 1 + 3 files changed, 22 insertions(+), 6 deletions(-) diff --git a/libraries/AP_RCProtocol/AP_RCProtocol.cpp b/libraries/AP_RCProtocol/AP_RCProtocol.cpp index 9d9174e89f3489..d2d11cfb304bf4 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol.cpp @@ -301,16 +301,12 @@ static const AP_RCProtocol::SerialConfig serial_configs[] { // FastSBUS: { 200000, 2, 2, true }, #endif -#if AP_RCPROTOCOL_CRSF_ENABLED +#if AP_RCPROTOCOL_CRSF_ENABLED || AP_RCPROTOCOL_GHST_ENABLED // CrossFire: { 416666, 0, 1, false }, // CRSFv3 can negotiate higher rates which are sticky on soft reboot { 2000000, 0, 1, false }, #endif -#if AP_RCPROTOCOL_GHST_ENABLED - // Ghost: - { 420000, 0, 1, false }, -#endif }; static_assert(ARRAY_SIZE(serial_configs) > 1, "must have at least one serial config"); diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_GHST.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_GHST.cpp index 1f2fa06950c887..195e56bfb91641 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_GHST.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_GHST.cpp @@ -21,6 +21,8 @@ #if AP_RCPROTOCOL_GHST_ENABLED +#define CRSF_BAUDRATE 416666U + #include "AP_RCProtocol.h" #include "AP_RCProtocol_GHST.h" #include @@ -413,12 +415,29 @@ bool AP_RCProtocol_GHST::is_telemetry_supported() const void AP_RCProtocol_GHST::process_byte(uint8_t byte, uint32_t baudrate) { // reject RC data if we have been configured for standalone mode - if (baudrate != GHST_BAUDRATE) { + if (baudrate != CRSF_BAUDRATE && baudrate != GHST_BAUDRATE) { return; } _process_byte(AP_HAL::micros(), byte); } +// change the bootstrap baud rate to ELRS standard if configured +void AP_RCProtocol_GHST::process_handshake(uint32_t baudrate) +{ + AP_HAL::UARTDriver *uart = get_current_UART(); + + // only change the baudrate if we are bootstrapping CRSF + if (uart == nullptr + || baudrate != CRSF_BAUDRATE + || baudrate == GHST_BAUDRATE + || uart->get_baud_rate() == GHST_BAUDRATE + || (get_rc_protocols_mask() & ((1U<<(uint8_t(AP_RCProtocol::GHST)+1))+1)) == 0) { + return; + } + + uart->begin(GHST_BAUDRATE); +} + //returns uplink link quality on 0-255 scale int16_t AP_RCProtocol_GHST::derive_scaled_lq_value(uint8_t uplink_lq) { diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_GHST.h b/libraries/AP_RCProtocol/AP_RCProtocol_GHST.h index e710a70fa99cab..248fb3f1790d35 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_GHST.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol_GHST.h @@ -36,6 +36,7 @@ class AP_RCProtocol_GHST : public AP_RCProtocol_Backend { AP_RCProtocol_GHST(AP_RCProtocol &_frontend); virtual ~AP_RCProtocol_GHST(); void process_byte(uint8_t byte, uint32_t baudrate) override; + void process_handshake(uint32_t baudrate) override; void update(void) override; // is the receiver active, used to detect power loss and baudrate changes From 3caf336b0ff84f745b85bc21a002db3ac0a9a70c Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 4 Jan 2024 20:46:35 +0000 Subject: [PATCH 0471/1335] AP_HAL_ChibiOS: switch BetaFPV-F405, BeastF7 and BeastF7v2 to minimize_fpv --- libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/hwdef.dat | 2 ++ libraries/AP_HAL_ChibiOS/hwdef/BeastF7/hwdef.dat | 5 +---- libraries/AP_HAL_ChibiOS/hwdef/BeastF7v2/hwdef.dat | 9 +-------- 3 files changed, 4 insertions(+), 12 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/hwdef.dat index 11006490e13e1e..5e27c96a75d303 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/BETAFPV-F405/hwdef.dat @@ -142,3 +142,5 @@ define HAL_FRAME_TYPE_DEFAULT 12 # This is a whoop AIO board, not really suitable for anything other than copter AUTOBUILD_TARGETS Copter + +include ../include/minimize_fpv_osd.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BeastF7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/BeastF7/hwdef.dat index 496e7563d11855..d1c3153292349b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/BeastF7/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/BeastF7/hwdef.dat @@ -137,9 +137,6 @@ ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin define STM32_PWM_USE_ADVANCED TRUE # save some flash -include ../include/save_some_flash.inc - -# only include ublox GPS driver -include ../include/minimal_GPS.inc +include ../include/minimize_fpv_osd.inc define DEFAULT_NTF_LED_TYPES 257 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/BeastF7v2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/BeastF7v2/hwdef.dat index 174747369a40ae..e1c82946b5ed06 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/BeastF7v2/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/BeastF7v2/hwdef.dat @@ -61,13 +61,6 @@ IMU BMI270 SPI:bmi270 ROTATION_ROLL_180_YAW_225 define HAL_BARO_ALLOW_INIT_NO_BARO 1 # save some flash -include ../include/save_some_flash.inc -define AP_GRIPPER_ENABLED 0 -define HAL_PARACHUTE_ENABLED 0 -define HAL_SPRAYER_ENABLED 0 -define AP_BATTERY_SMBUS_ENABLED 0 - -# only include ublox GPS driver -include ../include/minimal_GPS.inc +include ../include/minimize_fpv_osd.inc define DEFAULT_NTF_LED_TYPES 257 From 3c9c4a58b8f7e83f5bedb5ae533fe6e9c85dd605 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Thu, 4 Jan 2024 20:47:41 +0000 Subject: [PATCH 0472/1335] scripts: add Ghost protocol to build_options.py --- Tools/scripts/build_options.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Tools/scripts/build_options.py b/Tools/scripts/build_options.py index 01bb18cfad60ea..dd632f33d0f7c7 100644 --- a/Tools/scripts/build_options.py +++ b/Tools/scripts/build_options.py @@ -72,6 +72,7 @@ def __init__(self, Feature('Telemetry', 'FrSky D', 'AP_FRSKY_D_TELEM_ENABLED', 'Enable FrSkyD Telemetry', 0, 'FrSky'), Feature('Telemetry', 'FrSky SPort', 'AP_FRSKY_SPORT_TELEM_ENABLED', 'Enable FrSkySPort Telemetry', 0, 'FrSky'), # noqa Feature('Telemetry', 'FrSky SPort PassThrough', 'AP_FRSKY_SPORT_PASSTHROUGH_ENABLED', 'Enable FrSkySPort PassThrough Telemetry', 0, 'FrSky SPort,FrSky'), # noqa + Feature('Telemetry', 'GHST', 'HAL_GHST_TELEM_ENABLED', 'Enable Ghost Telemetry', 0, None), # noqa Feature('Notify', 'PLAY_TUNE', 'AP_NOTIFY_MAVLINK_PLAY_TUNE_SUPPORT_ENABLED', 'Enable MAVLink Play Tune', 0, None), # noqa Feature('Notify', 'TONEALARM', 'AP_NOTIFY_TONEALARM_ENABLED', 'Enable ToneAlarm on PWM', 0, None), # noqa @@ -203,6 +204,7 @@ def __init__(self, Feature('RC', 'RC_SRXL2', 'AP_RCPROTOCOL_SRXL2_ENABLED', "Enable SRXL2 RC Protocol", 0, "RC_Protocol"), # NOQA: E501 Feature('RC', 'RC_ST24', 'AP_RCPROTOCOL_ST24_ENABLED', "Enable ST24 Protocol", 0, "RC_Protocol"), # NOQA: E501 Feature('RC', 'RC_SUMD', 'AP_RCPROTOCOL_SUMD_ENABLED', "Enable SUMD RC Protocol", 0, "RC_Protocol"), # NOQA: E501 + Feature('RC', 'RC_GHST', 'AP_RCPROTOCOL_GHST_ENABLED', "Enable Ghost RC Protocol", 0, "RC_Protocol"), # NOQA: E501 Feature('Rangefinder', 'RANGEFINDER', 'AP_RANGEFINDER_ENABLED', "Enable Rangefinders", 0, None), # NOQA: E501 Feature('Rangefinder', 'RANGEFINDER_ANALOG', 'AP_RANGEFINDER_ANALOG_ENABLED', "Enable Rangefinder - Analog", 0, "RANGEFINDER"), # NOQA: E501 From 709656c49dd7fc8ad41dd71bfb65621f9551ec01 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 9 Jan 2024 17:30:56 +1100 Subject: [PATCH 0473/1335] AP_Arming: remove entire airspeed_checks if AP_AIRSPEED_ENABLED is off saves bytes and removes some redundant code which is obscured when the ifdefs are inside the body --- libraries/AP_Arming/AP_Arming.cpp | 6 ++---- libraries/AP_Arming/AP_Arming.h | 2 -- 2 files changed, 2 insertions(+), 6 deletions(-) diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index 1153490b7a9996..ff6362b68849d4 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -303,9 +303,9 @@ bool AP_Arming::barometer_checks(bool report) return true; } +#if AP_AIRSPEED_ENABLED bool AP_Arming::airspeed_checks(bool report) { -#if AP_AIRSPEED_ENABLED if (check_enabled(ARMING_CHECK_AIRSPEED)) { const AP_Airspeed *airspeed = AP_Airspeed::get_singleton(); if (airspeed == nullptr) { @@ -319,10 +319,10 @@ bool AP_Arming::airspeed_checks(bool report) } } } -#endif return true; } +#endif // AP_AIRSPEED_ENABLED #if HAL_LOGGING_ENABLED bool AP_Arming::logging_checks(bool report) @@ -1199,8 +1199,6 @@ bool AP_Arming::proximity_checks(bool report) const return false; } return true; - - return true; } #endif // HAL_PROXIMITY_ENABLED diff --git a/libraries/AP_Arming/AP_Arming.h b/libraries/AP_Arming/AP_Arming.h index 7569227da85110..8f46bd47e9d77a 100644 --- a/libraries/AP_Arming/AP_Arming.h +++ b/libraries/AP_Arming/AP_Arming.h @@ -236,8 +236,6 @@ class AP_Arming { bool fettec_checks(bool display_failure) const; - bool kdecan_checks(bool display_failure) const; - #if HAL_PROXIMITY_ENABLED virtual bool proximity_checks(bool report) const; #endif From 0690e3c9fa1e65a545f092b09dff4fb82c94c548 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 9 Jan 2024 17:30:56 +1100 Subject: [PATCH 0474/1335] ArduPlane: remove entire airspeed_checks if AP_AIRSPEED_ENABLED is off saves bytes and removes some redundant code which is obscured when the ifdefs are inside the body --- ArduPlane/AP_Arming.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduPlane/AP_Arming.cpp b/ArduPlane/AP_Arming.cpp index b4e868b2ff288c..2905175fdeb151 100644 --- a/ArduPlane/AP_Arming.cpp +++ b/ArduPlane/AP_Arming.cpp @@ -66,8 +66,10 @@ bool AP_Arming_Plane::pre_arm_checks(bool display_failure) // call parent class checks bool ret = AP_Arming::pre_arm_checks(display_failure); +#if AP_AIRSPEED_ENABLED // Check airspeed sensor ret &= AP_Arming::airspeed_checks(display_failure); +#endif if (plane.g.fs_timeout_long < plane.g.fs_timeout_short && plane.g.fs_action_short != FS_ACTION_SHORT_DISABLED) { check_failed(display_failure, "FS_LONG_TIMEOUT < FS_SHORT_TIMEOUT"); From dfd22aba3223df474a4d64669cd6e04029e32bb0 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 5 Jan 2024 12:09:29 +0900 Subject: [PATCH 0475/1335] AP_BattMonitor: support logging state-of-health percentage Only DroneCAN backend implements this feature for now --- libraries/AP_BattMonitor/AP_BattMonitor.cpp | 9 +++++++++ libraries/AP_BattMonitor/AP_BattMonitor.h | 5 +++++ .../AP_BattMonitor/AP_BattMonitor_Backend.cpp | 10 ++++++++++ .../AP_BattMonitor/AP_BattMonitor_Backend.h | 3 +++ .../AP_BattMonitor_DroneCAN.cpp | 20 ++++++++++++++++--- .../AP_BattMonitor/AP_BattMonitor_DroneCAN.h | 2 +- .../AP_BattMonitor/AP_BattMonitor_Logging.cpp | 6 +++++- libraries/AP_BattMonitor/LogStructure.h | 4 +++- 8 files changed, 53 insertions(+), 6 deletions(-) diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.cpp b/libraries/AP_BattMonitor/AP_BattMonitor.cpp index 35819b8d2efc0f..bf04aeb514aac4 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor.cpp @@ -1056,6 +1056,15 @@ uint32_t AP_BattMonitor::get_mavlink_fault_bitmask(const uint8_t instance) const return drivers[instance]->get_mavlink_fault_bitmask(); } +// return true if state of health (as a percentage) can be provided and fills in soh_pct argument +bool AP_BattMonitor::get_state_of_health_pct(uint8_t instance, uint8_t &soh_pct) const +{ + if (instance >= _num_instances || drivers[instance] == nullptr) { + return false; + } + return drivers[instance]->get_state_of_health_pct(soh_pct); +} + // Enable/Disable (Turn on/off) MPPT power to all backends who are MPPTs void AP_BattMonitor::MPPT_set_powered_state_to_all(const bool power_on) { diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.h b/libraries/AP_BattMonitor/AP_BattMonitor.h index 2df3fd5210830d..e9e10b7ef06edb 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor.h @@ -154,6 +154,8 @@ class AP_BattMonitor bool powerOffNotified; // only send powering off notification once uint32_t time_remaining; // remaining battery time bool has_time_remaining; // time_remaining is only valid if this is true + uint8_t state_of_health_pct; // state of health (SOH) in percent + bool has_state_of_health_pct; // state_of_health_pct is only valid if this is true uint8_t instance; // instance number of this backend const struct AP_Param::GroupInfo *var_info; }; @@ -274,6 +276,9 @@ class AP_BattMonitor // Returns mavlink fault state uint32_t get_mavlink_fault_bitmask(const uint8_t instance) const; + // return true if state of health (as a percentage) can be provided and fills in soh_pct argument + bool get_state_of_health_pct(uint8_t instance, uint8_t &soh_pct) const; + static const struct AP_Param::GroupInfo var_info[]; #if AP_BATTERY_SCRIPTING_ENABLED diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp index 1aef15a6efda3b..842c6ac907852e 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp @@ -107,6 +107,16 @@ void AP_BattMonitor_Backend::update_resistance_estimate() _state.voltage_resting_estimate = _state.voltage + _state.current_amps * _state.resistance; } +// return true if state of health can be provided and fills in soh_pct argument +bool AP_BattMonitor_Backend::get_state_of_health_pct(uint8_t &soh_pct) const +{ + if (!_state.has_state_of_health_pct) { + return false; + } + soh_pct = _state.state_of_health_pct; + return true; +} + float AP_BattMonitor_Backend::voltage_resting_estimate() const { // resting voltage should always be greater than or equal to the raw voltage diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Backend.h b/libraries/AP_BattMonitor/AP_BattMonitor_Backend.h index 8cc972e7e8a5e9..907d8712c11748 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Backend.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Backend.h @@ -58,6 +58,9 @@ class AP_BattMonitor_Backend // return true if cycle count can be provided and fills in cycles argument virtual bool get_cycle_count(uint16_t &cycles) const { return false; } + // return true if state of health (as a percentage) can be provided and fills in soh_pct argument + bool get_state_of_health_pct(uint8_t &soh_pct) const; + /// get voltage with sag removed (based on battery current draw and resistance) /// this will always be greater than or equal to the raw voltage float voltage_resting_estimate() const; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp index 123287c89a92ce..3c7d35fd9e5b9a 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.cpp @@ -114,14 +114,20 @@ AP_BattMonitor_DroneCAN* AP_BattMonitor_DroneCAN::get_dronecan_backend(AP_DroneC void AP_BattMonitor_DroneCAN::handle_battery_info(const uavcan_equipment_power_BatteryInfo &msg) { - update_interim_state(msg.voltage, msg.current, msg.temperature, msg.state_of_charge_pct); + update_interim_state(msg.voltage, msg.current, msg.temperature, msg.state_of_charge_pct, msg.state_of_health_pct); WITH_SEMAPHORE(_sem_battmon); _remaining_capacity_wh = msg.remaining_capacity_wh; _full_charge_capacity_wh = msg.full_charge_capacity_wh; + + // consume state of health + if (msg.state_of_health_pct != UAVCAN_EQUIPMENT_POWER_BATTERYINFO_STATE_OF_HEALTH_UNKNOWN) { + _interim_state.state_of_health_pct = msg.state_of_health_pct; + _interim_state.has_state_of_health_pct = true; + } } -void AP_BattMonitor_DroneCAN::update_interim_state(const float voltage, const float current, const float temperature_K, const uint8_t soc) +void AP_BattMonitor_DroneCAN::update_interim_state(const float voltage, const float current, const float temperature_K, const uint8_t soc, uint8_t soh_pct) { WITH_SEMAPHORE(_sem_battmon); @@ -145,6 +151,12 @@ void AP_BattMonitor_DroneCAN::update_interim_state(const float voltage, const fl update_consumed(_interim_state, dt_us); } + // state of health + if (soh_pct != UAVCAN_EQUIPMENT_POWER_BATTERYINFO_STATE_OF_HEALTH_UNKNOWN) { + _interim_state.state_of_health_pct = soh_pct; + _interim_state.has_state_of_health_pct = true; + } + // record time _interim_state.last_time_micros = tnow; _interim_state.healthy = true; @@ -185,7 +197,7 @@ void AP_BattMonitor_DroneCAN::handle_mppt_stream(const mppt_Stream &msg) // convert C to Kelvin const float temperature_K = isnan(msg.temperature) ? 0 : C_TO_KELVIN(msg.temperature); - update_interim_state(voltage, current, temperature_K, soc); + update_interim_state(voltage, current, temperature_K, soc, UAVCAN_EQUIPMENT_POWER_BATTERYINFO_STATE_OF_HEALTH_UNKNOWN); if (!_mppt.is_detected) { // this is the first time the mppt message has been received @@ -283,6 +295,8 @@ void AP_BattMonitor_DroneCAN::read() _state.time_remaining = _interim_state.time_remaining; _state.has_time_remaining = _interim_state.has_time_remaining; _state.is_powering_off = _interim_state.is_powering_off; + _state.state_of_health_pct = _interim_state.state_of_health_pct; + _state.has_state_of_health_pct = _interim_state.has_state_of_health_pct; memcpy(_state.cell_voltages.cells, _interim_state.cell_voltages.cells, sizeof(_state.cell_voltages)); _has_temperature = (AP_HAL::millis() - _state.temperature_time) <= AP_BATT_MONITOR_TIMEOUT; diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h index 819ade73164817..a25ef9667855c8 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_DroneCAN.h @@ -61,7 +61,7 @@ class AP_BattMonitor_DroneCAN : public AP_BattMonitor_Backend private: void handle_battery_info(const uavcan_equipment_power_BatteryInfo &msg); void handle_battery_info_aux(const ardupilot_equipment_power_BatteryInfoAux &msg); - void update_interim_state(const float voltage, const float current, const float temperature_K, const uint8_t soc); + void update_interim_state(const float voltage, const float current, const float temperature_K, const uint8_t soc, uint8_t soh_pct); static bool match_battery_id(uint8_t instance, uint8_t battery_id); diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Logging.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Logging.cpp index f5595d321aca32..4f3433d87added 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Logging.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Logging.cpp @@ -16,6 +16,9 @@ void AP_BattMonitor_Backend::Log_Write_BAT(const uint8_t instance, const uint64_ temperature_cd = temperature * 100.0; } + uint8_t soh_pct = 0; + IGNORE_RETURN(get_state_of_health_pct(soh_pct)); + const struct log_BAT pkt{ LOG_PACKET_HEADER_INIT(LOG_BAT_MSG), time_us : time_us, @@ -28,7 +31,8 @@ void AP_BattMonitor_Backend::Log_Write_BAT(const uint8_t instance, const uint64_ temperature : temperature_cd, resistance : _state.resistance, rem_percent : percent, - health : _state.healthy + health : _state.healthy, + state_of_health_pct : soh_pct }; AP::logger().WriteBlock(&pkt, sizeof(pkt)); } diff --git a/libraries/AP_BattMonitor/LogStructure.h b/libraries/AP_BattMonitor/LogStructure.h index fdc97512ef0065..5d0bb2cf130432 100644 --- a/libraries/AP_BattMonitor/LogStructure.h +++ b/libraries/AP_BattMonitor/LogStructure.h @@ -19,6 +19,7 @@ // @Field: Res: estimated battery resistance // @Field: RemPct: remaining percentage // @Field: H: health +// @Field: SH: state of health percentage. 0 if unknown struct PACKED log_BAT { LOG_PACKET_HEADER; uint64_t time_us; @@ -32,6 +33,7 @@ struct PACKED log_BAT { float resistance; uint8_t rem_percent; uint8_t health; + uint8_t state_of_health_pct; }; // @LoggerMessage: BCL @@ -61,6 +63,6 @@ struct PACKED log_BCL { #define LOG_STRUCTURE_FROM_BATTMONITOR \ { LOG_BAT_MSG, sizeof(log_BAT), \ - "BAT", "QBfffffcfBB", "TimeUS,Inst,Volt,VoltR,Curr,CurrTot,EnrgTot,Temp,Res,RemPct,H", "s#vvAaXOw%-", "F-000C0?000" , true }, \ + "BAT", "QBfffffcfBBB", "TimeUS,Inst,Volt,VoltR,Curr,CurrTot,EnrgTot,Temp,Res,RemPct,H,SH", "s#vvAaXOw%-%", "F-000C0?0000" , true }, \ { LOG_BCL_MSG, sizeof(log_BCL), \ "BCL", "QBfHHHHHHHHHHHH", "TimeUS,Instance,Volt,V1,V2,V3,V4,V5,V6,V7,V8,V9,V10,V11,V12", "s#vvvvvvvvvvvvv", "F-0CCCCCCCCCCCC" , true }, From a66dc31fbc57b0cc698d9d6b86f9bdc227d13e4a Mon Sep 17 00:00:00 2001 From: Rhys Mainwaring Date: Wed, 10 Jan 2024 11:28:03 +0000 Subject: [PATCH 0476/1335] AP_Networking: update lwipopts for macOS Signed-off-by: Rhys Mainwaring --- libraries/AP_Networking/config/lwipopts.h | 17 +++++++++++++++++ 1 file changed, 17 insertions(+) diff --git a/libraries/AP_Networking/config/lwipopts.h b/libraries/AP_Networking/config/lwipopts.h index d3ff36a44cb1c2..8da2750f279731 100644 --- a/libraries/AP_Networking/config/lwipopts.h +++ b/libraries/AP_Networking/config/lwipopts.h @@ -36,6 +36,23 @@ extern "C" { #endif +/* macOS specific */ +#if defined(__APPLE__) +/* lwip/contrib/ports/unix/port/netif/sio.c */ +#include + +/* lwip/src/apps/http/makefsdata/makefsdata.c */ +#define GETCWD(path, len) getcwd(path, len) +#define GETCWD_SUCCEEDED(ret) (ret != NULL) +#define CHDIR(path) chdir(path) +#define CHDIR_SUCCEEDED(ret) (ret == 0) + +/* lwip/src/netif/ppp/fsm.c */ +/* lwip/src/netif/ppp/pppos.c */ +/* lwip/src/netif/ppp/vj.c */ +#pragma GCC diagnostic ignored "-Wimplicit-fallthrough" +#endif + #ifdef LWIP_OPTTEST_FILE #include "lwipopts_test.h" #else /* LWIP_OPTTEST_FILE */ From ad3cf2633834f1565f508891cbd7d2566d36a899 Mon Sep 17 00:00:00 2001 From: Rhys Mainwaring Date: Tue, 9 Jan 2024 09:59:26 +0000 Subject: [PATCH 0477/1335] AP_Networking: enable networking on macOS Signed-off-by: Rhys Mainwaring --- libraries/AP_Networking/AP_Networking_Config.h | 4 ++-- libraries/AP_Networking/wscript | 6 +++--- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AP_Networking/AP_Networking_Config.h b/libraries/AP_Networking/AP_Networking_Config.h index b54a8e399f7831..e815b87b5a7c80 100644 --- a/libraries/AP_Networking/AP_Networking_Config.h +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -7,8 +7,8 @@ #ifndef AP_NETWORKING_ENABLED -#if defined(__APPLE__) || defined(__clang__) -// MacOS can't build lwip, and clang fails on linux +#if !defined(__APPLE__) && defined(__clang__) +// clang fails on linux #define AP_NETWORKING_ENABLED 0 #else #define AP_NETWORKING_ENABLED ((CONFIG_HAL_BOARD == HAL_BOARD_LINUX) || (CONFIG_HAL_BOARD == HAL_BOARD_SITL)) diff --git a/libraries/AP_Networking/wscript b/libraries/AP_Networking/wscript index 97554622a79f80..454a350ba24c15 100644 --- a/libraries/AP_Networking/wscript +++ b/libraries/AP_Networking/wscript @@ -8,9 +8,9 @@ def configure(cfg): if not cfg.env.BOARD_CLASS in ['SITL', 'LINUX', 'ChibiOS']: return - # networking doesn't build on MacOSX or clang - if platform.system() == 'Darwin' or 'clang++' in cfg.env.COMPILER_CXX: - return + # networking doesn't build with clang unless using macOS + if platform.system() != 'Darwin' and 'clang++' in cfg.env.COMPILER_CXX: + return extra_src = [ 'modules/lwip/src/core/*c', From 37fccc118fe544ecfce81c4ddc1ae042018679fe Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 10 Jan 2024 14:18:56 +1100 Subject: [PATCH 0478/1335] AP_ADSB: add missing includes --- libraries/AP_ADSB/AP_ADSB.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_ADSB/AP_ADSB.cpp b/libraries/AP_ADSB/AP_ADSB.cpp index a36a1849b2e090..53ba4291dc0cec 100644 --- a/libraries/AP_ADSB/AP_ADSB.cpp +++ b/libraries/AP_ADSB/AP_ADSB.cpp @@ -37,7 +37,7 @@ #include #include #include - +#include #define VEHICLE_TIMEOUT_MS 5000 // if no updates in this time, drop it from the list #define ADSB_SQUAWK_OCTAL_DEFAULT 1200 From 964b683b83faec80d6d95fbf03492178b7d6df04 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 10 Jan 2024 14:18:56 +1100 Subject: [PATCH 0479/1335] GCS_MAVLink: add missing includes --- libraries/GCS_MAVLink/GCS_Common.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 9981cb5e594368..913e9fe47b2b40 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -65,6 +65,7 @@ #include #include #include +#include #include "MissionItemProtocol_Waypoints.h" #include "MissionItemProtocol_Rally.h" From a2182f7c4be783420e369fd574448f418b148088 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 10 Jan 2024 16:11:28 +1100 Subject: [PATCH 0480/1335] AP_ESC_Telem: add missing include --- libraries/AP_ESC_Telem/AP_ESC_Telem.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp index d2b7e31b1488c5..5fbaba7ae6dc5a 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp @@ -23,6 +23,8 @@ #include #include +#include + //#define ESC_TELEM_DEBUG #define ESC_RPM_CHECK_TIMEOUT_US 210000UL // timeout for motor running validity From 2332ea7942a1a9404f3769ba5f25f8ce1bc1a053 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 10 Jan 2024 16:16:14 +1100 Subject: [PATCH 0481/1335] AP_Mount: add missing include --- libraries/AP_Mount/AP_Mount.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_Mount/AP_Mount.cpp b/libraries/AP_Mount/AP_Mount.cpp index 9c79d79205d50f..4bb18ad3608b58 100644 --- a/libraries/AP_Mount/AP_Mount.cpp +++ b/libraries/AP_Mount/AP_Mount.cpp @@ -18,6 +18,7 @@ #include #include #include +#include const AP_Param::GroupInfo AP_Mount::var_info[] = { From 8ccf51b0edb9d40a6affe7d924edaa5793b0ef18 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 10 Jan 2024 16:46:04 +1100 Subject: [PATCH 0482/1335] AP_EFI: add missing include for is_equal --- libraries/AP_EFI/AP_EFI.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_EFI/AP_EFI.cpp b/libraries/AP_EFI/AP_EFI.cpp index 3cc4d648ffd68d..79bffff77a9577 100644 --- a/libraries/AP_EFI/AP_EFI.cpp +++ b/libraries/AP_EFI/AP_EFI.cpp @@ -28,6 +28,7 @@ #include #include +#include #if HAL_MAX_CAN_PROTOCOL_DRIVERS #include From 85fc178769367e3237d786526e062eb78b4b229f Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 11 Jan 2024 15:47:39 +1100 Subject: [PATCH 0483/1335] AP_Bootloader: correct placement of AP_BOOTLOADER_ALWAYS_ERASE this moves it outside of defined(BOOTLOADER_DEV_LIST) --- Tools/AP_Bootloader/support.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Tools/AP_Bootloader/support.cpp b/Tools/AP_Bootloader/support.cpp index ddf1041da48e37..c9f37b2b60e2e4 100644 --- a/Tools/AP_Bootloader/support.cpp +++ b/Tools/AP_Bootloader/support.cpp @@ -22,6 +22,10 @@ // optional uprintf() code for debug // #define BOOTLOADER_DEBUG SD1 +#ifndef AP_BOOTLOADER_ALWAYS_ERASE +#define AP_BOOTLOADER_ALWAYS_ERASE 0 +#endif + #if defined(BOOTLOADER_DEV_LIST) static BaseChannel *uarts[] = { BOOTLOADER_DEV_LIST }; #if HAL_USE_SERIAL == TRUE @@ -34,10 +38,6 @@ static uint8_t last_uart; #define BOOTLOADER_BAUDRATE 115200 #endif -#ifndef AP_BOOTLOADER_ALWAYS_ERASE -#define AP_BOOTLOADER_ALWAYS_ERASE 0 -#endif - // #pragma GCC optimize("O0") static bool cin_data(uint8_t *data, uint8_t len, unsigned timeout_ms) From d26d9585ad5749c04f1061d5a672e110796d2554 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 11 Jan 2024 16:07:13 +1100 Subject: [PATCH 0484/1335] AP_Bootloader: gate call check_good_firmware on AP_CHECK_FIRMWARE_ENABLED this method doesn't exist if that defines doesn't --- Tools/AP_Bootloader/AP_Bootloader.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Tools/AP_Bootloader/AP_Bootloader.cpp b/Tools/AP_Bootloader/AP_Bootloader.cpp index f42271208073ba..7e4b80cad15a4b 100644 --- a/Tools/AP_Bootloader/AP_Bootloader.cpp +++ b/Tools/AP_Bootloader/AP_Bootloader.cpp @@ -109,6 +109,7 @@ int main(void) try_boot = false; timeout = 0; } +#if AP_CHECK_FIRMWARE_ENABLED const auto ok = check_good_firmware(); if (ok != check_fw_result_t::CHECK_FW_OK) { // bad firmware CRC, don't try and boot @@ -116,6 +117,7 @@ int main(void) try_boot = false; led_set(LED_BAD_FW); } +#endif // AP_CHECK_FIRMWARE_ENABLED #ifndef BOOTLOADER_DEV_LIST else if (timeout != 0) { // fast boot for good firmware From 59108e9524a8467db61ac95a58477c4798e2ec13 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 12 Jan 2024 09:40:46 +1100 Subject: [PATCH 0485/1335] Tools: added Alia xplane parameters --- .../Frame_params/QuadPlanes/XPlane-Alia.parm | 130 ++++++++++++++++++ 1 file changed, 130 insertions(+) create mode 100644 Tools/Frame_params/QuadPlanes/XPlane-Alia.parm diff --git a/Tools/Frame_params/QuadPlanes/XPlane-Alia.parm b/Tools/Frame_params/QuadPlanes/XPlane-Alia.parm new file mode 100644 index 00000000000000..b9e54aae830ea2 --- /dev/null +++ b/Tools/Frame_params/QuadPlanes/XPlane-Alia.parm @@ -0,0 +1,130 @@ +STAB_PITCH_DOWN,4 +TKOFF_TDRAG_ELEV,30 +TKOFF_TDRAG_SPD1,20 +TKOFF_ROTATE_SPD,30 +USE_REV_THRUST,1075 +WP_RADIUS,400 +WP_LOITER_RAD,1000 +RTL_RADIUS,500 +ARSPD_FBW_MIN,30 +ARSPD_FBW_MAX,65 +TERRAIN_FOLLOW,1 +THR_MIN,-25 +THR_SLEWRATE,30 +TRIM_THROTTLE,60 +GROUND_STEER_ALT,10 +TRIM_ARSPD_CM,5200 +SCALING_SPEED,60 +TRIM_PITCH_CD,400 +ALT_HOLD_RTL,25000 +FLAP_1_PERCNT,50 +FLAP_1_SPEED,30 +RTL_AUTOLAND,2 +RELAY1_FUNCTION,1 +Q_ENABLE,1 +Q_M_THST_EXPO,0 +Q_M_SPIN_MIN,0.25 +Q_M_THST_HOVER,0.66 +Q_ANGLE_MAX,1500 +Q_TRANSITION_MS,10000 +Q_P_POSZ_P,0.5 +Q_P_VELZ_P,2.5 +Q_P_POSXY_P,0.1 +Q_P_VELXY_P,0.2 +Q_P_VELXY_I,0.1 +Q_P_VELXY_D,0.059 +Q_VELZ_MAX,500 +Q_WP_SPEED,1500 +Q_WP_SPEED_DN,500 +Q_WP_ACCEL,200 +Q_ASSIST_SPEED,25 +Q_LAND_SPEED,100 +Q_LAND_FINAL_ALT,25 +Q_FRAME_TYPE,3 +Q_VFWD_GAIN,0.3 +Q_RTL_ALT,50 +Q_TRANS_DECEL,0.69 +Q_LOIT_SPEED,1200 +Q_LOIT_ACC_MAX,150 +Q_LOIT_BRK_DELAY,3 +Q_A_SLEW_YAW,2000 +Q_A_ACCEL_Y_MAX,2500 +Q_A_ACCEL_R_MAX,6000 +Q_A_ACCEL_P_MAX,9000 +Q_A_ANG_RLL_P,0.5 +Q_A_ANG_PIT_P,0.25 +Q_A_ANG_YAW_P,0.5 +Q_A_RATE_R_MAX,35 +Q_A_RATE_P_MAX,35 +Q_A_RATE_Y_MAX,35 +Q_A_RAT_RLL_P,0.7835410833358765 +Q_A_RAT_RLL_I,0.7835410833358765 +Q_A_RAT_RLL_D,0.05042541027069092 +Q_A_RAT_RLL_FLTT,10 +Q_A_RAT_PIT_P,1.0936822891235352 +Q_A_RAT_PIT_I,1.0936822891235352 +Q_A_RAT_PIT_D,0.03247206285595894 +Q_A_RAT_PIT_FLTT,10 +Q_A_RAT_YAW_P,2.0000014305114746 +Q_A_RAT_YAW_I,0.20000013709068298 +Q_A_RAT_YAW_D,0.03000001423060894 +Q_A_RAT_YAW_FLTT,10 +Q_A_RAT_YAW_FLTE,2 +Q_A_RAT_YAW_FLTD,10 +RLL2SRV_TCONST,1 +RLL2SRV_RMAX,75 +RLL_RATE_P,0.6642029881477356 +RLL_RATE_I,0.6642029881477356 +RLL_RATE_D,0.019881000742316246 +RLL_RATE_FF,1.2974460124969482 +RLL_RATE_FLTT,0.7957746982574463 +RLL_RATE_FLTD,10 +PTCH2SRV_TCONST,0.75 +PTCH2SRV_RMAX_UP,75 +PTCH2SRV_RMAX_DN,75 +PTCH_RATE_P,0.6644459962844849 +PTCH_RATE_I,0.5014650225639343 +PTCH_RATE_D,0.017854999750852585 +PTCH_RATE_FF,0.5014650225639343 +PTCH_RATE_FLTT,2.122066020965576 +PTCH_RATE_FLTD,10 +SCHED_LOOP_RATE,100 +NAVL1_PERIOD,20 +TECS_CLMB_MAX,15 +TECS_TIME_CONST,8 +TECS_THR_DAMP,2 +TECS_SINK_MAX,15 +TECS_LAND_ARSPD,40 +SIM_OH_RELAY_MSK,-1 +SIM_MAG1_OFS_X,5 +SIM_MAG1_OFS_Y,13 +SIM_MAG1_OFS_Z,-18 +SIM_MAG2_OFS_X,5 +SIM_MAG2_OFS_Y,13 +SIM_MAG2_OFS_Z,-18 +SIM_MAG3_OFS_X,5 +SIM_MAG3_OFS_Y,13 +SIM_MAG3_OFS_Z,-18 +EK3_ENABLE,0 +SERVO1_MIN,1000 +SERVO1_MAX,1700 +SERVO1_TRIM,1374 +SERVO2_MIN,1000 +SERVO2_MAX,2000 +SERVO2_TRIM,1516 +SERVO3_MIN,500 +SERVO3_MAX,2000 +SERVO3_TRIM,982 +SERVO4_MIN,1000 +SERVO4_MAX,2000 +SERVO5_MIN,1500 +SERVO5_FUNCTION,33 +SERVO6_MIN,1000 +SERVO6_FUNCTION,34 +SERVO9_MIN,1300 +SERVO9_MAX,2000 +SERVO9_TRIM,1601 +SERVO9_FUNCTION,4 +SERVO_AUTO_TRIM,1 +LGR_ENABLE,1 +LAND_FLAP_PERCNT,100 From 1748711b99c12b6c4683dcd05f9f73c7a3c7223b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 10:12:16 +1100 Subject: [PATCH 0486/1335] Tools: size_compare_branches.py: restart failed threads --- Tools/scripts/size_compare_branches.py | 33 +++++++++++++------------- 1 file changed, 17 insertions(+), 16 deletions(-) diff --git a/Tools/scripts/size_compare_branches.py b/Tools/scripts/size_compare_branches.py index 9749569d87bb2a..750fb0afc1fd31 100755 --- a/Tools/scripts/size_compare_branches.py +++ b/Tools/scripts/size_compare_branches.py @@ -416,7 +416,7 @@ def parallel_thread_main(self, thread_number): break jobs = None if self.jobs is not None: - jobs = int(self.jobs / self.num_threads_remaining) + jobs = int(self.jobs / self.n_threads) if jobs <= 0: jobs = 1 try: @@ -436,27 +436,29 @@ def check_result_queue(self): self.failure_exceptions.append(result) def run_build_tasks_in_parallel(self, tasks): - n_threads = self.parallel_copies - if len(tasks) < n_threads: - n_threads = len(tasks) - self.num_threads_remaining = n_threads + self.n_threads = self.parallel_copies # shared list for the threads: self.parallel_tasks = copy.copy(tasks) # make this an argument instead?! threads = [] self.thread_exit_result_queue = Queue.Queue() - for i in range(0, n_threads): - t = threading.Thread( - target=self.parallel_thread_main, - name=f'task-builder-{i}', - args=[i], - ) - t.start() - threads.append(t) tstart = time.time() self.failure_exceptions = [] - while len(threads): + thread_number = 0 + while len(self.parallel_tasks) or len(threads): + if len(tasks) < self.n_threads: + self.n_threads = len(tasks) + while len(threads) < self.n_threads: + self.progress(f"Starting thread {thread_number}") + t = threading.Thread( + target=self.parallel_thread_main, + name=f'task-builder-{thread_number}', + args=[thread_number], + ) + t.start() + threads.append(t) + thread_number += 1 self.check_result_queue() @@ -466,10 +468,9 @@ def run_build_tasks_in_parallel(self, tasks): if thread.is_alive(): new_threads.append(thread) threads = new_threads - self.num_threads_remaining = len(threads) self.progress( f"remaining-tasks={len(self.parallel_tasks)} " + - f"remaining-threads={len(threads)} failed-threads={len(self.failure_exceptions)} elapsed={int(time.time() - tstart)}s") # noqa + f"failed-threads={len(self.failure_exceptions)} elapsed={int(time.time() - tstart)}s") # noqa # write out a progress CSV: task_results = [] From 34bc01ec7131c4932a2e16130632caa78b6619a0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 10:22:47 +1100 Subject: [PATCH 0487/1335] Tools: size_compare_branches.py: upon process failure write out a file containing diagnostics --- Tools/scripts/size_compare_branches.py | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/Tools/scripts/size_compare_branches.py b/Tools/scripts/size_compare_branches.py index 750fb0afc1fd31..c20a5b70bb11a2 100755 --- a/Tools/scripts/size_compare_branches.py +++ b/Tools/scripts/size_compare_branches.py @@ -267,6 +267,12 @@ def run_program(self, prefix, cmd_list, show_output=True, env=None, show_output_ print(output) self.progress("Process failed (%s)" % str(returncode)) + try: + path = pathlib.Path(self.tmpdir, f"process-failure-{int(time.time())}") + path.write_text(output) + self.progress("Wrote process failure file (%s)" % path) + except Exception: + self.progress("Writing process failure file failed") raise subprocess.CalledProcessError( returncode, cmd_list) return output From 5fdcd876ee5b6e084b30bb36eccdbac283ac3fa8 Mon Sep 17 00:00:00 2001 From: Davide_Lentini <74407457+DavideLentini@users.noreply.github.com> Date: Thu, 11 Jan 2024 14:44:36 +0100 Subject: [PATCH 0488/1335] AP_HAL_ChibiOS: Update defaults.parm of luminousbee5 board --- libraries/AP_HAL_ChibiOS/hwdef/luminousbee5/defaults.parm | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/luminousbee5/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/luminousbee5/defaults.parm index 7b5f96dbdf3501..1d59bcecee582e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/luminousbee5/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/luminousbee5/defaults.parm @@ -48,6 +48,7 @@ BATT_VOLT_MULT,3.28 BATT_VOLT_PIN,14 BRD_SAFETYENABLE,0 BRD_SAFETYOPTION,0 +BRD_SAFETY_DEFLT,0 CAN_D1_PROTOCOL,0 CAN_D2_PROTOCOL,0 COMPASS_AUTODEC,1 @@ -79,6 +80,7 @@ FRSKY_UPLINK_ID,-1 FS_OPTIONS,20 FS_THR_ENABLE,0 FS_VIBE_ENABLE,0 +FENCE_ENABLE,1 GND_EFFECT_COMP,0 GPS_AUTO_SWITCH,0 GPS_GNSS_MODE,0 @@ -101,9 +103,9 @@ INS_HNTC2_MODE,0 INS_HNTC2_OPTS,0 INS_HNTC2_REF,0 INS_HNTCH_ATT,40 -INS_HNTCH_BW,10 +INS_HNTCH_BW,8 INS_HNTCH_ENABLE,1 -INS_HNTCH_FREQ,50 +INS_HNTCH_FREQ,40 INS_HNTCH_HMNCS,22 INS_HNTCH_MODE,3 INS_HNTCH_OPTS,22 @@ -180,6 +182,7 @@ SERVO_BLH_POLES,12 SERVO_BLH_TRATE,0 SERVO_DSHOT_ESC,1 SERVO_DSHOT_RATE,2 +SERVO_BLH_RVMASK,3 SHOW_CTRL_MODE,1 SHOW_CTRL_RATE,10 SHOW_GROUP,0 From 54144162305c6a105bb1546da26fb72feb64a915 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 11 Jan 2024 08:22:40 +1100 Subject: [PATCH 0489/1335] lwip: update for PPP bridge support --- modules/lwip | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/modules/lwip b/modules/lwip index 0a0452b2c39bdd..143a6a5cb80239 160000 --- a/modules/lwip +++ b/modules/lwip @@ -1 +1 @@ -Subproject commit 0a0452b2c39bdd91e252aef045c115f88f6ca773 +Subproject commit 143a6a5cb8023921b5dced55c30551ffb752b640 From 39a1fc9dbd37edf02d4787ef26bb8d54894bbf37 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 9 Jan 2024 07:27:31 +1100 Subject: [PATCH 0490/1335] AP_Networking: added option for PPP<->ethernet bridge when NET_OPTIONS is set to enable PPP bridging both an ethernet and a PPP link will be brought up, with IP forwarding making the PPP remote endpoint available on the ethernet LAN --- libraries/AP_Networking/AP_Networking.cpp | 34 +++++++- libraries/AP_Networking/AP_Networking.h | 16 ++++ .../AP_Networking/AP_Networking_Config.h | 14 +++ libraries/AP_Networking/AP_Networking_PPP.cpp | 87 +++++++++++++++++-- libraries/AP_Networking/config/lwipopts.h | 31 +++---- 5 files changed, 154 insertions(+), 28 deletions(-) diff --git a/libraries/AP_Networking/AP_Networking.cpp b/libraries/AP_Networking/AP_Networking.cpp index 87b5147b75f241..dd926a31e541c3 100644 --- a/libraries/AP_Networking/AP_Networking.cpp +++ b/libraries/AP_Networking/AP_Networking.cpp @@ -86,6 +86,20 @@ const AP_Param::GroupInfo AP_Networking::var_info[] = { AP_SUBGROUPINFO(param.test_ipaddr, "TEST_IP", 8, AP_Networking, AP_Networking_IPV4), #endif + // @Param: OPTIONS + // @DisplayName: Networking options + // @Description: Networking options + // @Bitmask: 0:EnablePPP Ethernet gateway + // @RebootRequired: True + // @User: Advanced + AP_GROUPINFO("OPTIONS", 9, AP_Networking, param.options, 0), + +#if AP_NETWORKING_PPP_GATEWAY_ENABLED + // @Group: REMPPP_IP + // @Path: AP_Networking_address.cpp + AP_SUBGROUPINFO(param.remote_ppp_ip, "REMPPP_IP", 10, AP_Networking, AP_Networking_IPV4), +#endif + AP_GROUPEND }; @@ -129,8 +143,19 @@ void AP_Networking::init() } #endif +#if AP_NETWORKING_PPP_GATEWAY_ENABLED + if (option_is_set(OPTION::PPP_ETHERNET_GATEWAY)) { + /* + when we are a PPP/Ethernet gateway we bring up the ethernet first + */ + backend = new AP_Networking_ChibiOS(*this); + backend_PPP = new AP_Networking_PPP(*this); + } +#endif + + #if AP_NETWORKING_BACKEND_PPP - if (AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_PPP, 0)) { + if (backend == nullptr && AP::serialmanager().have_serial(AP_SerialManager::SerialProtocol_PPP, 0)) { backend = new AP_Networking_PPP(*this); } #endif @@ -158,6 +183,13 @@ void AP_Networking::init() return; } +#if AP_NETWORKING_PPP_GATEWAY_ENABLED + if (backend_PPP != nullptr && !backend_PPP->init()) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "NET: backend_PPP init failed"); + backend_PPP = nullptr; + } +#endif + announce_address_changes(); GCS_SEND_TEXT(MAV_SEVERITY_INFO,"NET: Initialized"); diff --git a/libraries/AP_Networking/AP_Networking.h b/libraries/AP_Networking/AP_Networking.h index 63936f025b2c50..c83f0e26da2331 100644 --- a/libraries/AP_Networking/AP_Networking.h +++ b/libraries/AP_Networking/AP_Networking.h @@ -26,6 +26,7 @@ class AP_Networking public: friend class AP_Networking_Backend; friend class AP_Networking_ChibiOS; + friend class AP_Networking_PPP; friend class AP_Vehicle; friend class Networking_Periph; @@ -149,6 +150,13 @@ class AP_Networking static const struct AP_Param::GroupInfo var_info[]; + enum class OPTION { + PPP_ETHERNET_GATEWAY=(1U<<0), + }; + bool option_is_set(OPTION option) const { + return (param.options.get() & int32_t(option)) != 0; + } + private: static AP_Networking *singleton; @@ -172,10 +180,18 @@ class AP_Networking AP_Int32 tests; AP_Networking_IPV4 test_ipaddr{AP_NETWORKING_TEST_IP}; #endif + +#if AP_NETWORKING_PPP_GATEWAY_ENABLED + AP_Networking_IPV4 remote_ppp_ip{AP_NETWORKING_REMOTE_PPP_IP}; +#endif } param; AP_Networking_Backend *backend; +#if AP_NETWORKING_PPP_GATEWAY_ENABLED + AP_Networking_Backend *backend_PPP; +#endif + HAL_Semaphore sem; enum class NetworkPortType { diff --git a/libraries/AP_Networking/AP_Networking_Config.h b/libraries/AP_Networking/AP_Networking_Config.h index e815b87b5a7c80..d9d8532eeff6eb 100644 --- a/libraries/AP_Networking/AP_Networking_Config.h +++ b/libraries/AP_Networking/AP_Networking_Config.h @@ -119,3 +119,17 @@ #ifndef AP_NETWORKING_SENDFILE_BUFSIZE #define AP_NETWORKING_SENDFILE_BUFSIZE (64*512) #endif + +#ifndef AP_NETWORKING_PPP_GATEWAY_ENABLED +#define AP_NETWORKING_PPP_GATEWAY_ENABLED (AP_NETWORKING_BACKEND_CHIBIOS && AP_NETWORKING_BACKEND_PPP) +#endif + +/* + the IP address given to the remote end of the PPP link when running + as a PPP<->ethernet gateway. If this is on the same subnet as the + ethernet interface IP then proxyarp will be used + */ +#ifndef AP_NETWORKING_REMOTE_PPP_IP +#define AP_NETWORKING_REMOTE_PPP_IP "0.0.0.0" +#endif + diff --git a/libraries/AP_Networking/AP_Networking_PPP.cpp b/libraries/AP_Networking/AP_Networking_PPP.cpp index 13929634e79239..18f16f0bdbb56e 100644 --- a/libraries/AP_Networking/AP_Networking_PPP.cpp +++ b/libraries/AP_Networking/AP_Networking_PPP.cpp @@ -57,10 +57,17 @@ void AP_Networking_PPP::ppp_status_callback(struct ppp_pcb_s *pcb, int code, voi switch (code) { case PPPERR_NONE: // got new addresses for the link - driver.activeSettings.ip = ntohl(netif_ip4_addr(pppif)->addr); - driver.activeSettings.gw = ntohl(netif_ip4_gw(pppif)->addr); - driver.activeSettings.nm = ntohl(netif_ip4_netmask(pppif)->addr); - driver.activeSettings.last_change_ms = AP_HAL::millis(); +#if AP_NETWORKING_PPP_GATEWAY_ENABLED + if (driver.frontend.option_is_set(AP_Networking::OPTION::PPP_ETHERNET_GATEWAY)) { + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "PPP: got addresses"); + } else +#endif + { + driver.activeSettings.ip = ntohl(netif_ip4_addr(pppif)->addr); + driver.activeSettings.gw = ntohl(netif_ip4_gw(pppif)->addr); + driver.activeSettings.nm = ntohl(netif_ip4_netmask(pppif)->addr); + driver.activeSettings.last_change_ms = AP_HAL::millis(); + } break; case PPPERR_OPEN: @@ -94,10 +101,13 @@ bool AP_Networking_PPP::init() return false; } - // initialise TCP/IP thread - LWIP_TCPIP_LOCK(); - tcpip_init(NULL, NULL); - LWIP_TCPIP_UNLOCK(); + const bool ethernet_gateway = frontend.option_is_set(AP_Networking::OPTION::PPP_ETHERNET_GATEWAY); + if (!ethernet_gateway) { + // initialise TCP/IP thread + LWIP_TCPIP_LOCK(); + tcpip_init(NULL, NULL); + LWIP_TCPIP_UNLOCK(); + } hal.scheduler->delay(100); @@ -127,9 +137,14 @@ void AP_Networking_PPP::ppp_loop(void) while (!hal.scheduler->is_system_initialized()) { hal.scheduler->delay_microseconds(1000); } + const bool ppp_gateway = frontend.option_is_set(AP_Networking::OPTION::PPP_ETHERNET_GATEWAY); + if (ppp_gateway) { + // wait for the ethernet interface to be up + AP::network().startup_wait(); + } // ensure this thread owns the uart - uart->begin(0); + uart->begin(AP::serialmanager().find_baudrate(AP_SerialManager::SerialProtocol_PPP, 0)); uart->set_unbuffered_writes(true); while (true) { @@ -137,9 +152,63 @@ void AP_Networking_PPP::ppp_loop(void) // connect and set as default route LWIP_TCPIP_LOCK(); + +#if AP_NETWORKING_PPP_GATEWAY_ENABLED + if (ppp_gateway) { + /* + when bridging setup the ppp interface with the same IP + as the ethernet interface, and set the remote IP address + as the local address + 1 + */ + ip4_addr_t our_ip, his_ip; + const uint32_t ip = frontend.get_ip_active(); + uint32_t rem_ip = frontend.param.remote_ppp_ip.get_uint32(); + if (rem_ip == 0) { + // use ethernet IP +1 by default + rem_ip = ip+1; + } + our_ip.addr = htonl(ip); + his_ip.addr = htonl(rem_ip); + ppp_set_ipcp_ouraddr(ppp, &our_ip); + ppp_set_ipcp_hisaddr(ppp, &his_ip); + if (netif_list != nullptr) { + const uint32_t nmask = frontend.get_netmask_param(); + if ((ip & nmask) == (rem_ip & nmask)) { + // remote PPP IP is on the same subnet as the + // local ethernet IP, so enable proxyarp to avoid + // users having to setup routes in all devices + netif_set_proxyarp(netif_list, &his_ip); + } + } + } + + // connect to the remote end ppp_connect(ppp, 0); + if (ppp_gateway) { + extern struct netif *netif_list; + /* + when we are setup as a PPP gateway we want the pppif to be + first in the list so routing works if it is on the same + subnet + */ + if (netif_list != nullptr && + netif_list->next != nullptr && + netif_list->next->next == pppif) { + netif_list->next->next = nullptr; + pppif->next = netif_list; + netif_list = pppif; + } + } else { + netif_set_default(pppif); + } +#else + // normal PPP link, connect to the remote end and set as the + // default route + ppp_connect(ppp, 0); netif_set_default(pppif); +#endif // AP_NETWORKING_PPP_GATEWAY_ENABLED + LWIP_TCPIP_UNLOCK(); need_restart = false; diff --git a/libraries/AP_Networking/config/lwipopts.h b/libraries/AP_Networking/config/lwipopts.h index 8da2750f279731..78ea48e8270271 100644 --- a/libraries/AP_Networking/config/lwipopts.h +++ b/libraries/AP_Networking/config/lwipopts.h @@ -74,7 +74,6 @@ extern "C" #define LWIP_ICMP LWIP_IPV4 #define LWIP_SNMP LWIP_UDP -#define MIB2_STATS LWIP_SNMP #ifdef LWIP_HAVE_MBEDTLS #define LWIP_SNMP_V3 (LWIP_SNMP) #endif @@ -255,6 +254,7 @@ a lot of data that needs to be copied, this should be set high. */ #define LWIP_ARP 1 #define ARP_TABLE_SIZE 10 #define ARP_QUEUEING 1 +#define ARP_PROXYARP_SUPPORT 1 /* ---------- IP options ---------- */ @@ -263,6 +263,12 @@ a lot of data that needs to be copied, this should be set high. */ on a device with only one network interface, define this to 0. */ #define IP_FORWARD 1 +/* + extra header space when forwarding for adding the ethernet header +*/ +#define PBUF_LINK_HLEN 16 + + /* IP reassembly and segmentation.These are orthogonal even * if they both deal with IP fragments */ #define IP_REASSEMBLY 1 @@ -302,22 +308,8 @@ a lot of data that needs to be copied, this should be set high. */ /* ---------- Statistics options ---------- */ -#define LWIP_STATS 1 -#define LWIP_STATS_DISPLAY 1 - -#if LWIP_STATS -#define LINK_STATS 1 -#define IP_STATS 1 -#define ICMP_STATS 1 -#define IGMP_STATS 1 -#define IPFRAG_STATS 1 -#define UDP_STATS 1 -#define TCP_STATS 1 -#define MEM_STATS 1 -#define MEMP_STATS 1 -#define PBUF_STATS 1 -#define SYS_STATS 1 -#endif /* LWIP_STATS */ +#define LWIP_STATS 0 +#define LWIP_STATS_DISPLAY 0 /* ---------- NETBIOS options ---------- */ #define LWIP_NETBIOS_RESPOND_NAME_QUERY 1 @@ -343,7 +335,10 @@ a lot of data that needs to be copied, this should be set high. */ #define MSCHAP_SUPPORT 0 /* Set > 0 for MSCHAP */ #define CBCP_SUPPORT 0 /* Set > 0 for CBCP (NOT FUNCTIONAL!) */ #define CCP_SUPPORT 0 /* Set > 0 for CCP */ -#define VJ_SUPPORT 1 /* Set > 0 for VJ header compression. */ +/* + VJ support disabled due to bugs with IP forwarding + */ +#define VJ_SUPPORT 0 /* Set > 0 for VJ header compression. */ #define MD5_SUPPORT 0 /* Set > 0 for MD5 (see also CHAP) */ #endif /* PPP_SUPPORT */ From 458d8cad4e8ea079d55b00fe1207c8c1bdbe8ebc Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 11 Jan 2024 15:01:43 +1100 Subject: [PATCH 0491/1335] Tools: added Pixhawk6X-PPPGW board --- Tools/AP_Bootloader/board_types.txt | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Tools/AP_Bootloader/board_types.txt b/Tools/AP_Bootloader/board_types.txt index 27bfe00e6a5ad0..4344ef812c6df0 100644 --- a/Tools/AP_Bootloader/board_types.txt +++ b/Tools/AP_Bootloader/board_types.txt @@ -272,6 +272,9 @@ AP_HW_VIMDRONES_MOSAIC_X5 1405 AP_HW_VIMDRONES_MOSAIC_H 1406 AP_HW_VIMDRONES_PERIPH 1407 +AP_HW_PIXHAWK6X_PERIPH 1408 + + # IDs 5000-5099 reserved for Carbonix # IDs 5100-5199 reserved for SYPAQ Systems # IDs 5200-5209 reserved for Airvolute From 44bc523db834c2af909261d2579f106cd0ca368c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 11 Jan 2024 15:02:13 +1100 Subject: [PATCH 0492/1335] AP_Periph: added support for PPP gatewate peripheral --- Tools/AP_Periph/AP_Periph.cpp | 8 ++++---- Tools/AP_Periph/networking.cpp | 20 ++++++++++++++++++++ Tools/AP_Periph/networking.h | 16 ++++++++++++++-- 3 files changed, 38 insertions(+), 6 deletions(-) diff --git a/Tools/AP_Periph/AP_Periph.cpp b/Tools/AP_Periph/AP_Periph.cpp index 78cc920c1df8b3..41bf37b92c9d20 100644 --- a/Tools/AP_Periph/AP_Periph.cpp +++ b/Tools/AP_Periph/AP_Periph.cpp @@ -100,16 +100,16 @@ void AP_Periph_FW::init() can_start(); -#ifdef HAL_PERIPH_ENABLE_NETWORKING - networking_periph.init(); -#endif - #if HAL_GCS_ENABLED stm32_watchdog_pat(); gcs().init(); #endif serial_manager.init(); +#ifdef HAL_PERIPH_ENABLE_NETWORKING + networking_periph.init(); +#endif + #if HAL_GCS_ENABLED gcs().setup_console(); gcs().setup_uarts(); diff --git a/Tools/AP_Periph/networking.cpp b/Tools/AP_Periph/networking.cpp index 8ac256850cd9b9..41fb6ee0426036 100644 --- a/Tools/AP_Periph/networking.cpp +++ b/Tools/AP_Periph/networking.cpp @@ -137,12 +137,32 @@ const AP_Param::GroupInfo Networking_Periph::var_info[] { AP_SUBGROUPINFO(passthru[8], "PASS9_", 19, Networking_Periph, Passthru), #endif +#if AP_NETWORKING_BACKEND_PPP + // @Param: PPP_PORT + // @DisplayName: PPP serial port + // @Description: PPP serial port + // @Range: -1 10 + AP_GROUPINFO("PPP_PORT", 20, Networking_Periph, ppp_port, AP_PERIPH_NET_PPP_PORT_DEFAULT), + + // @Param: PPP_BAUD + // @DisplayName: PPP serial baudrate + // @Description: PPP serial baudrate + // @CopyFieldsFrom: SERIAL1_BAUD + AP_GROUPINFO("PPP_BAUD", 21, Networking_Periph, ppp_baud, AP_PERIPH_NET_PPP_BAUD_DEFAULT), +#endif + AP_GROUPEND }; void Networking_Periph::init(void) { +#if AP_NETWORKING_BACKEND_PPP + if (ppp_port >= 0) { + AP::serialmanager().set_protocol_and_baud(ppp_port, AP_SerialManager::SerialProtocol_PPP, ppp_baud.get()); + } +#endif + networking_lib.init(); #if HAL_PERIPH_NETWORK_NUM_PASSTHRU > 0 diff --git a/Tools/AP_Periph/networking.h b/Tools/AP_Periph/networking.h index 6b7f857fdcde8c..71cdc1754ea3af 100644 --- a/Tools/AP_Periph/networking.h +++ b/Tools/AP_Periph/networking.h @@ -10,6 +10,14 @@ #define HAL_PERIPH_NETWORK_NUM_PASSTHRU 2 #endif +#ifndef AP_PERIPH_NET_PPP_PORT_DEFAULT +#define AP_PERIPH_NET_PPP_PORT_DEFAULT -1 +#endif + +#ifndef AP_PERIPH_NET_PPP_BAUD_DEFAULT +#define AP_PERIPH_NET_PPP_BAUD_DEFAULT 12500000 +#endif + class Networking_Periph { public: Networking_Periph() { @@ -54,7 +62,11 @@ class Networking_Periph { #endif // HAL_PERIPH_NETWORK_NUM_PASSTHRU AP_Networking networking_lib; -}; -#endif // HAL_PERIPH_ENABLE_BATTERY_BALANCE +#if AP_NETWORKING_BACKEND_PPP + AP_Int8 ppp_port; + AP_Int32 ppp_baud; +#endif +}; +#endif // HAL_PERIPH_ENABLE_NETWORKING From 280d7c6d15f9df4179de73ac2d01201e072443b4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 12 Jan 2024 14:23:25 +1100 Subject: [PATCH 0493/1335] hwdef: added CubePilot-PPPGW --- .../hwdef/CubePilot-PPPGW/defaults.parm | 5 +++++ .../hwdef/CubePilot-PPPGW/hwdef-bl.dat | 1 + .../hwdef/CubePilot-PPPGW/hwdef.dat | 21 +++++++++++++++++++ 3 files changed, 27 insertions(+) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/defaults.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/hwdef-bl.dat create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/hwdef.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/defaults.parm new file mode 100644 index 00000000000000..a10bbb4937c85f --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/defaults.parm @@ -0,0 +1,5 @@ +NET_ENABLED 1 + +# enable hw flow control +UART1_RTSCTS 1 + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/hwdef-bl.dat new file mode 100644 index 00000000000000..dbde2799b74f11 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/hwdef-bl.dat @@ -0,0 +1 @@ +include ../CubePilot-CANMod/hwdef-bl.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/hwdef.dat new file mode 100644 index 00000000000000..dfaed04510e9c3 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/hwdef.dat @@ -0,0 +1,21 @@ +include ../CubePilot-CANMod/hwdef.dat + +# we need RTS/CTS for the PPP link +undef PD14 +undef PD13 +undef PE0 +undef PE1 + +# need to use UART8 to get RTS/CTS +PE1 UART8_TX UART8 +PE0 UART8_RX UART8 +PD13 UART8_RTS UART8 +PD14 UART8_CTS UART8 + +SERIAL_ORDER OTG1 UART8 + +define HAL_PERIPH_ENABLE_SERIAL_OPTIONS +define AP_NETWORKING_BACKEND_PPP 1 + +define AP_PERIPH_NET_PPP_PORT_DEFAULT 1 +define AP_PERIPH_NET_PPP_BAUD_DEFAULT 12500000 From ee6478b465b8f354162046feb572e58d6e0752a4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 12 Jan 2024 14:23:48 +1100 Subject: [PATCH 0494/1335] Tools: added CubePilot-PPPGW bootloader --- Tools/bootloaders/CubePilot-PPPGW_bl.bin | Bin 0 -> 31136 bytes 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100755 Tools/bootloaders/CubePilot-PPPGW_bl.bin diff --git a/Tools/bootloaders/CubePilot-PPPGW_bl.bin b/Tools/bootloaders/CubePilot-PPPGW_bl.bin new file mode 100755 index 0000000000000000000000000000000000000000..91f4c3cc91a6b3842fcb15d271b8db7cc55d87c8 GIT binary patch literal 31136 zcmdSBdw5huwl`e+(wE#whXf2sfSv9DfsWWDL83U?=_ETL4Tg)(L2za|pt2Km2%uvS zM>-*B1RaAx#Y9IG9Z|d_fjC6WbR^)>@iN_9oB%3uaBPxz*_{i$lTNbVUv($m-t&Iv zeDCx9^Y!yo@7lGiR;^l9wQAK`tBPoe;A4q?a30Y&BAgw2dhqN+`cK2>**|~(>9=3T zH*O^QXAwR?7(htg^xv1=Juj5!`LXAc|3R5w*89u%#{VIVYc~J)`27<0|Lyw>>3^?l z#{Y-)$NU%Y|8H^q|9iPJlZl@EZqIaQ5k|uf~5E{;yu7cUXG~`3T|0 z%b6QL=_QQb;p!`T%+Wk3H?Bop%GcZTpAFJCuSMk_e`;;LyWjodM; zl|LIUl5e(5UzAw5+jgBRTj3*yyi*s&|Ku$J-xBS0w(DKX@YRN(c!?1IvpgDE2CS@+ zxW$u}yk_Ih-K6k|)%k;7BHNUh#S?#)hI-#2nAgOJK!{%dE$PHlplR-M&;#l2vEbZ9 zgig%!uYMA)?2?PF{MNAZT_w`(Mri%Uu(S1&{1`E9?~AEU75C*6ftMGnqh4PAaFkpa z^%9~qGxE)Y8u?;CCu-#7!y56(QNjM4Ez`|p(EnMo%1%Wa(>-%VTd(16rHRN}RU&Uw z^^GKDrpTae0%DwibY-SEzcCi2IX6ks$fn_$A`vvQD=?vv$dw8se=k4mS*!*3KmkkxDnw)BbuPKs#c<^3u#O)4zvzi(q~0WUv}H%f zvRY{$Owtg&Y$C!X#P#<0GA=c;ou&NLO2^NbGn7K6XPmJSw782^HX|1H*9HK zV&{wrWyHAHzRIDrF19Z&OcJL^%sj=-XVlsTJ!_;zpt|pDfxTYhd}J**;560Qx=w23 z#Q}}{+WXyF*l_O7v$w6tZB!S#*IITkA2(plW*g3%ci%ArIwz#;v;$G&OW6Ir|22TnLV|_w&uV)<6 z_>;mRfJ02jl%?t8siFSdA<`KyMrrKZ^EBs23Rj=JaJuM9_p0{lmH+!&7))7eVwD;Y5EC zAp-Gv2sBU5*s~eWE|jHdgNWaZ`1m_5^HX^LRh-sIM^MoyNwvy@6{Ma`)*N`-N22wv zB+SE!8LumG79t;1cX=`P%ZOa9>ZbLar)B1&%-3$_2F+EZ_lt@Pmvk~09%YEVT4Uk? zLsLuS8uf}!KKbT?K`)=Ys^BvIZz<^W7RgC^tEl(!dLp-~$Xla1K;-+>Bfd0@3Pu2J z!^n`%pWhu3@w=g20Y-jRnb{a2M{p5ly^Ex%elnU1SosAXd&%6F+@UYednislBRY|! z*1H*j%p~$7DovX=I(_It#R_h-N9DzaM($~=$Xxxr&&n>dEz2hI^D0UG*7LT=)Aq*F z_FpfCT5VAc-Wlj$)gL{Yf?0UbraPMoIBQhKVwKlb@bmk;WQNiHws^fbwQRcmH;x0q z=!X7V-wffjt^YsXq!`E}=@=0`qYXZyS1&JlGhXI&+xi#18C|IF(QuDTwYD2B+ul4f z;M{hD|N1v4+K=QhwWiNQ^mdP89MzFI>g9QFa&^oCrk+z6^S77>bS?M>{N$Ish^PDr zA(DPacpn)2E=ZRf`lH{Req~I@37^1*ADkg`q-v2ZFFrTbWfPgliCm>Jb!zgq0wTYp z7Ih!s-tT*ey?;@v$e=G@RJEY&4gGh$$<%9lwreuHv}GA1H0`T5h-?5AZ|J}92AOq4 zECa2M+Tzbnzbd99yq?LJfHj2UCcYY*yFwAJ)6`l;-l%znU%<$kA*bl|W`U+hMm06P z-j9_yCmlUR-ZaX3iRrdv{s52Ki!s)=^*6jh>l_@WHNE-JUTwY z!$y6Ck3&(eb^c7u}N>J{&mAxQ!TuFb3g;CEmlSGI?#M{ zbl<Q9s$t`@+b~+~Z1Q zMp3_Y^KnJUB=XUbXO(9x_ii$6ifHM1z_dyGT7{7$&%(GkJ;E51MH=%!s`+ILQYq$E zf|;fXwu6;l9a%+3&lvtQvo~$JFyo(pC5s@FG|#xPsDI}@z6MBa0do73N{6Kbuy-h* zS*|^>L%C$tzDeX~Mzp{WJbmPh@|ERS6W*9d6`4f&eB|Sv1cdvIUQHlsm}{DE9OLu(_nm@jrW&) zg{ANs&7Xgr)vOUGEGEg!d?IHLzo?|$d{{}-5Xjr*jiK1wVMZ)y3B@hLc+O`skZ*ps zH;c|i&^Fv2QD|sRa6qnHQL7XP*S6exXIdj2ou8T>dZx%5Euib+r^^5{T zW|LcE{wOGKRxf(k{&$J(?_3j`^I>q0NL(Xci@DWPb>o*0q~EvOcEsa&V4g^fyOqzD z?yzAcbTaA8z|M{QoB_|P-efTqEqi9~^J%&PnVFIrkGo4^MHlmb@; z8aqE#PNPrg_qUX^8I?AsL-lhiO`Vgw$EH6y{)MrGz7352Zs_6OTf{Pn$R7vvEhoe+ zotq?@YfkPa2Q8=RVZ+{2PS+4QI#7`pb_(AFq!T8cBtD2Zz7h4x=nj&S2~1`MG3myB ztzh(5_V@~Yi|T)V@Ps(adlXR5lJEexCLo)qiG0^_xbK zOJLGjnPVSB>@BQ*JMR<3@BllY@pUtl5+9Bz4!W|BzQGvh=YrQjLVij;qjUl_ZNJNFZF&m^S)uczlTz& z)pFGFwzOG7P5tRp9#<|IZfT@=UJ`fNZs?!&CP@ay24HJAA#Rqmh4tY~Mr_5=uZb%R zr>5pNSm_78tOF87HNNfJH!Z> zm%=dkK;7%PCn$Vc|71ce3z~`i(8!b}tce)o7o}FL-^iG*C}8A&4iVGjMW|spQ#;8% zxq#G8wzKlT1}E94l*cqq1P9}X7+D_WF=7*kF%vg81o|)oV>y0ca+zUhyBukcckuEp z!}`W(levOxu(Ziuvb=!k18`Pk18qq z9{rZ=Vr1Ruvr39UOk|E#e#0qX_BIS^ux{piE+}6$GV)`i=P|eU+HN?-$PbU|YE=K> z0Bwz~4(;(VXb(Hqo(~m53TAC@V&w7g;%di2g4dv>Y+@TKQNEd6_^XlV3r7B(5_9m0OB~sb@GSbv@QQ#QT5O4|H`IRK z6>ehXy1+E=Da@8djb`a!55o+Zvs^AFJ46rFc;?CF~|7}O`p7J4h_Q8>$*wmBhIB+a`K$QBuepah}LY zrxc-Kq1chX!>04-?2NEoA^Tb{DUUHJUwKJdz+KcoRL052M~Kkpy&rYOL!M1SD1$tU zy8e)zHbYExWzWz;`@+c$Bex|Ec*4L=rGb6RH5-%MMpw9sUlgm zK-)*cv9r)OgNLe4nIUaWRvYwK_Hfa1cuKj}zCua1GNMTm#Lr83`)i`*9S8Uf#e?EN zW%06R!(uYSa3e48Qv|0)GF5N4MRt%GLN${G-Iiji*5on^n+Kd%nVkKn%3683TFH=* zmO;}p9REIb$@>7{Wg$QZ*g|~7K?a-xkw8(zA1CyUmp?v2h{m2EY3zyB^$FW;>{&xD zFRwWQO61eB6b1`jM?6x0bA-5P+W7mrv3Hu6_|&Cj;4y<+3H6zF(QYNhlF>*^dZWIy z0&&&f?qX<8*L8pa-byiXVdmaC#m;1LMtyEs^Hk{y`-#2?{>sQ{)qk-?cy5)#MdrFn zTdWv;GH#IBaAPB@FzYXSnQJ+pp8LjAVT%yilW9h}OXgF;3MW^;VdFh}ZB?!(%aOL8 zxsLVmY@cUk0{SjkR|@F+8Dx0WO~wN;8JcUM!~E#h<2NxGgI?@k2$N-KHViU1ENp}X zVtvNOc@i3#dCax_-UON=>`gGV8pL5QC$geDVd5Z@NM;Xt%JSJ#j}RR2X4DI{BL^XXYlkCVKBmCq=C z+VnW2qBrR`%ZrIupd{&Ok za>wvg{hLQ)pc~-iR}}g!dI|lSDw*&-YSBI$%~RC>Wk!U9akKK#QAyfoL^6XDK35dGZ(c#G$(#avIaZzny3zOy#8VVz?>OaHd8(ol z*aplXlfQX_$Zyjb$?hql1}o3$(alMWQI||=v0FAlH#&N}Ql}W{lfG5LuHq|fu!VMJ4h|~ zOeXYY^7Er#c!h*`a2hW(MIjuZ9~;Brao}*g1@EZOkP-vxGII4OWBOgvrgCQC|D@K< zWnORJlpkwlWNB2NxlsK4$68@ynSd6@ftnRY3r6z5h#6RtWD9D0RK33?I%R#54(+Dz zJ5*YGX|Q(wR44jOY1OCndwYU)&>VNG6#h3s+s!!KPl9ki0Nm6uxW#~LNzq^gqhEuN zSE^TuTNCHpS8E%Go0>A<)%n6WioHb)(JN2=#_Mn9w@nbqZpH+yPBQJQ(Gl7=VMfDP z-%LT@^p7kMH&q`^th2>*{Ga;9fW9%HZ#FwGc^6LokxHSuPL2H7HX;WnDH?R zvv8$VZ?g6go>`b?jg?ids(UH9?D^hnX%)5~`PSc@Rk&U>NXw*Bk!#nR<}bRsKqK!N z!mLlt@PyCE_}SNai{|3%j^NitZm#6eKehuO$R2-AQ2lSIyze$fC#J)OMS1Ri={ehM&qZmk4SMJqDV-rmvpTYOh2RLDD}rzg zfD?bpun>Cy;aR|W9B|?ptvDwLXBXi7*~SLpFz%=s&>7DFAH_&E%y_{YIb)wUV#c2# zM}31e=`%GE0tT-iK)eQVJsI{Jnz{RVF}8(BkV7DG(zS`0Tz#t_YsZduHLRYiAKM;` zmF3eok?4O}ei?KIkyvvFpasXM(9&`Ey$T)7*}Ehf?^0*vream3@r$aEKxGzM#wzV= z)c7K`C`0$-C{1&mRI6;fPtCN5dt7%(WQOYhKuyaPP(G_U5@TKU|0iG@PK8PxRry>g zh{xf8>?47gTt;{;h+}BiLv=iKMT|nZ6M&rR;>FXAN5qv%Qzf_s>3QiAgTT* z)QkkIz8#Ekr-N#=UQAr?SSSg(2OXCjtT5me#6Ish4$qC@5DCn;{1-TU^D`XO>}s(D zSlo#k-%`m8Z4=+~p7yXU+`UGErk)WbeWvR71z^FwZfb6?cea>?oFAxIRYJNo%yUZP zXr$UyO5+f%t^*bpvD$Sfu)i9V&2k8hX+fG_r3$$U`fqb{oJeI^)t`peGc~mRpEWYC zP)eUsnfi>Dbm>GFn{lFxKt&SS`HU^qk>z6cFngp+Cy9O50x~LnS4*1<~3WG`?SJ4k4(8q(I?tOF&FyfK%dw0LmQ}WN%eQ4pP8Vx z;|gel&`Uwt$Z$ATWTiNX7+(}&Z?!{4rBdV48s!$A%1)v9@*m@aD}(VHA?1baZOF0w zr1DJWNo6k|pLY1fZe9t6vv=E-FHIgG~iseqhY$ZTUnl| z5o^R&C99^s(W8`SG8ymU-z4oN+S8`3dUM3tHCw|Qqs_Xr9>Awx@6V*NxS=zINl)o1 z<+w1hpCpF6J&F@M44TK8>4fD^6V$W|Qh^b9EF`tPk1t$bde~)^omMA5F%X_n)Ll3^ z-eHuMlcMhMHM#ggmc~1Tt+sArTjg+UH5{__TPLn^c$9_|CjDLfzdD5-*uFewYql&f zF`I?09PAo@R5=S*?=-;9)f?esA}VcB=lGsV29g`QNZRe_^^TWv^yS4|^fJbtQcX`` z3_BFw%M4U5YggRD!71_ccwZ#T4OFgZ@8Taai7ViTP-~<93WJ`+>bbcQ&g@=^6BTZs zcEI`TFxXcb>zZ-H6@5wWqV|qTCuuQqG?H$M>{P`~wJ{V)qV->c1 z<7F}eUJE=dVyZh!`&!)8QVdzK4bK}*ou%Ze4W3XM6HF_$mlh_%?(JN`4WzB8C$+Zy zYplHu&N~W->>OQUwsl-ksw#@Qxf?Gi)w`huY`d}hkqK=|RcEBniG4@fQYUc~b3Kvd zw361=?z@qLhLC)wIEhuZkdN@hZaVTb>`h+-|3~CX+dH2#J#FF36bm7#hV$nXejl}i zMw|=lCf0CyTe!759A)*^0%b0l;A194`k2Tsz1vGnGQ({zhAwYZD_$(EFFC8@&k#9t zbbI2E`SRHiT~n!k^P#`?tcd>A$qULyokiWc#a}?HvABDCWSdgmhITIHdh$6ki(>u> zzPuwk$-d&w(hyA|gETp<#CHao>TKKmWp6H1G6>Vtt|zG-)C1x?F;6%z$PTMXcI42p zNcG=0D%X(-Js%N@X^w+g(D@T=zZwZ)drtQ{u>E`_gzd}Tf0fn-TU3h{orFD!w&=W0 zgFGLOv-y~qtXFBV5B>;Ht5%hi3f)j zz=2i&ci>EhRyscG#OemRpV}>k=C%$PNZ?`@Ra$Q)u$T)hN<{kh*ocri%d-dk!*qyy zJy+BmoD0c^`{d8IT-b?nVJDg&v=a%AL)H78pQFwX5Ly+z zpU6v~yQ3pJ`2J8xKS4~em=09jqyb)r%(gBjW2RkHEDIN)oUnkdV=u$YLjz2q!&{*l z*nbPv@623FX0E$UGqC+X!hD7>q(m4Ne7*K~SJc&vsYx zs`*Oloke;5o+@Q!)r-oi+g?;|MfmM)Rf+@8H3+vM+<|xLHo8k--5SiHFNS%0s@SuJ zYCxc0LEoj&{@X{ayxq_|rJNTFlM>2Qe_fEqJI3}^WcKgemZEtDe+~EsDr}Fq!i5+i zXIgVW9wvdLrJpqkjjTCd9OwXgn1||oXdX7CpFG}kJdExk!+ac9)O}Ik-uIuJ9@?rG zd$yw{MW$naB<#g53}%m zQ?%LLv2hv^K4{X-)^r#)GD4j5X6K5HyEoDq7UomInJ-SDHDHeFze<=8Amr<&l|xni z4T1jt7n@Fb^ItgyZKgwkf<20Au!1Erg@*VNj!uVK&fpzqva zteHQX8+84`IKO$X_;3S{o&U^-VHCFZv8d z%ig*Yo6N9v$lDgoTUX-NX-^ZmWi02w*)HUvljoiPSG8nC6zCzN$@iOdP5?CyV+=5#ZrX63dxJabMt zE|!v6f{5{l+4k4b9m*|tZ;-9Fi=_#-Ur~6mbk*%eGHbk8T8F2aPU+YwaCooDJ9qmH z{TJW(Y3qiDe#)==hC=-MA79hHUY_|8>>EzZ<0=H|Cv`JRSUM&(7>_mL(;}G#DIuJ$ z^i(qHumr3fx@BiHJ^2%hy7Lp4=f-ZCqFZ$OQ>6;B)O+~X47>z+gFGC&rB18qiC_y{ zpDKqlm*?iX==Z~!v0HLvJr}$2yv}syN%RMINHb6w(#LzhsCCZ+lgE{xU`#Lp(A!PS;f>R zKoqbm+d7(97<*SeGv|y+LQjL6J6FWq&KS2Vx1Kx|nYX3`TuTS!*f zv_@)Icd9~}Lgl%l9Su)oH|!KAW1mMFKJS{apRJ88r+#QV6*FX$Xy`vO%85DKZN!d+ z&dDcL)&FaR2UI)sHM5cOfeL@##-osUIQRpGc61r#v5gFTF)w@cpcGeoQyyD?Zx6>! zJ;~Ld!l->8&N8q!J_qWI1Z#+Vp>l?oB3#*WfbjAB5@O__VJ7ce3KMEO|+MKCv=vx(i__KU( zkL6qaLq6mu(TDZT>|R!mg+DwiA9#nAcfJ$be5c4wt-7QodxF+H4Pk7}I4M*2Zj(hkkWcfJwaU#8N)HEpI)2-T9kpe(E}Z6EKyw4$Jm?yPp>}pinC#F*j)P3rK_C9C%4e zc7^9zTeK(2@r5^5{LcF_tbx$9=N{{GZnEV?xNmCw-m5?Pt@k5XkRu!)dk@v$oU;iv@*F5R*kfQ!=i;B9>=#9A=S*O`!V?4m@Azs$$@E#tM zsP8#5;Xm@O7h{zPZCS2gi|>Jce}ax{g7~FA`_|0d`ME9D*+W`?@=&->ZF;1eVe*H< z{nuC#i{wz|jMv%C2zpa?Z!*g?F$=AP%yu>%aV-sMMq!1_r~0l(<6p87PgZLj>`bcv zYt;`tZBk)ltW@!Ejw9z`CZoRTXP{OX?%8 zXkh~SI1C{iAp(JpfhYt@b0tUj2rufcns%1VD7vg}c6YIR;mfLh$tS?n27TLn%A-=@ zu`(}*$%z*~Xj1)aRO^+T*yFiY{IUdlogCF);zHRnY6+w3gk3VV{C(%zzA*Ohm4;Tn zBtc4YaK-IAnT73@g^uroeXSHt6+he=Emnx_ePPVwqGoo4Xn|+ft4%sz0{`cx=|fJ1 zpBvp#lgIfOPJ1dmH?VU}Ul<2VTV+CLfxY>DR*p;Sy;G~$FLIVzxI-uT1UC#^(HETu zM@K`Q?bJ!iAKk&)yGDhUzaL>{c;ICYFLGZbS0p>bZxok^`tJc3}nJFEnM zbBAiQ43fFmdYF3Fco3W{!l$1weW-Fc`4Q+$$U8o5w6lrn_>;{HFNgi3e}dj0K0km_ zF}kLN$ztYDEKeMA`WOofJ=&E`w(dm}AC{T0!frMknA<88{k~hoU5WwTjUQsC0-R9x zxe?PNhu~+n%}b2$dA}@q_&3be6BO3)Ruhxn=G`DOnoVA%d6GCmw16hOI326S=Zdzz zd4NoR*|F9EDm6;t`<*7%FkLc#4brAl?HvkTgG#W^ zdR;MCqU$xa&qDL@C?wXHdR=WRG$8OOz5R7XfHmV8H5}ZC%A}`Cs88Z#F`^~*k<~{R zJTU#L)Q%?<;-or{nQp2{|6(MgJeg&&{$zKz&&$}E-K}S`yLH9c-CTBtm@PXQ_-3OW z;h$%eGdTCN=@+e`>kY+vDA)qZU*+aqz6_z?EffW1z67Tz<|dcJDf3fqe8Qh3u4 zNcvU_ZB0zDH3h-e#06V(6K%~OLanJ+Bj_4Stfi!px0L1QlqN{FHEapIG{<;SP!FE% zh6hL-Xcd2BHuh~{Efh0P7i)SU;dV$fPui$VGwmc-y2};?kAO!;xKij+*Kj2f4sf<& zW+7ABURf>v%L{pFBtoLTlRtiIuY@+$aN1ifhDjdCCeEs9!9CTk2I~7-FMbX$8z*KE zk>e{`KwBcmRjinHgPHUiDwsK(hjJ9F99}`ar}Y^}aDJq@r#-r;yIsefB0@xP=VhMq zoUH@JN4(dXnb4+;qM8a*sBA zer`JSwL6Dk(;ud=Q_irkob6#=~^zHY|=dryIMe3H#zs! z9yWYZ?&T(mJ72G@(>z_DzynwGOYKWuQhTkaKR8>YZGGKK>x*?Wro*7ydbd7pV#l)> z>uaW&hS=USI_(*%31El#epAk)NT=T(Mh`CY8j!Q~hn$|D<)q__etQKuuk#9N(H;7y z*G@|w;`+{E7c&kqGDp8hU;hE}%<)>&=D3Te9rq=(FTzLR^Dh1EGqDHL0EZbU6_Yb1 z=R;l08OHb`{27k>1cpVb5jkG4M&vBFt?kL-(sRr?7y~Ah4eC%yaL$i>y+PKKp|AC6 z&x6W`&kAYZbsP`2`3*Px`-8D}+`I|=kuY;Cu#Cadm9nFO%&?}Vx~wV89L$%S<2w?| z9|gx=i(ceIy{MtRI0^k%Yt`VNgZqxAoQtOvqVa^k- zM2Y(Ov$cR}>hKzxKa>(%b~z%7cl~eDz~3FRm(wnGwe_`GSV$z0z`;{4t8A*)vqF2U zFIr%*C*X*_^;nKW!HkBW;S>;O=$NKoS261+-7M|?eI8CkUKdx$^euNib_x1u}D(DU` zDCicYPs%Bs`@#ykah|JIa%<{YQ4c>pQoBN2CmqSBv-NnztkR;EY6yyBRLa&DCS|i@cx+7wZ!E`nB*P zd@}F;9)>fYTEF!vC82Y3-V_guomsh?NlpH&TvA#tDDtsAd1c5m`P72WS*5dpZ6pbu zfuR^52FCr~Lj^T93Wou2k-ZeckXu(DZNB2Op+6oXL0ujEk2(2%E;c7{4|I%y^;?hr zfvsQI68K|#Ulq%wujzY`3*6)OmTo=zK%MP;5R3WlLt(5r9avK-A?mjQFRF zaP{G!Yj`bR|GIL0Lqx54>Z6KvUu3Nr=MS=-R6|XDUbXd)DmIG-|2dXDN}6RmY($SL zxt9IdR|f0lm<%en)U$!g7rcQ#zSn1+*wk}sx>fFX0xK>j&novi*}AvF%v;HvCGK9` zZ%)JF*4yLc>fe}pO|TD-I?_dom3b?NT2;vJBsKCJZL#XF9r|T0Vcvt)n1@vhw_^q0 z`~mvx6`TS~9SZY>`Sf8tWabpiY$`R!|{{xU*18;)9*rd zKG($0Ufq#86+V-`L~Wf-f7YNdA2JzQg=u5voo~|2?)Pv{*V@8&XSw(c{^>MG5jW$! zK*Vn3XCilRktWne?Vdd~u#-|BQZA@!-A5^(kULIu&|ml^-HGYQ&aI9)TbXMi{|_$Q zb)<4T{P*@tv@iGOqd#9!{mf|Kk8eYAuKG#eEZkLRi-f1q2H8N~{dy~8=r`ROf$2=L zWQfxwGIz)mmN0j!erkL!(-Rg6|NFjoe2LM|cGTJG&rXIHOPG%dgCF?9@4@-P$Ubns zaPlnvBS;l)S4Ot7z}+RL?ZZXe`jU{MA6d9!rg#o{pg`Sqqdswf`v z3()py?fZ)jtr~m4OUuDmB&frnxZS`Ly$ykta-^6X#=$kl=Tn)JEsVvfoHj1jfwyvE zjcuN=nEJjyKLl?%c(70nUHBrhhseJj471a>utmHti_nyR4(bYZ_Tybwn1Yr=R}FO7 z!w8Kwq90xgeKz2cF9$T-{g&qB#bkE8D-xEKNY8ZpURxOc>+S?aY;`yvO`i$t5;qtn z?)UHB#q})bs_r-x=t#m7nq?ZznTfK&sBt&>oWJAUPUSX>rFENW$a{lH@j78oqj=JD$y8tP-d!4Tfz)4; ztjk=J;Et2^OuVb8-?{N$x&jyV3D~bIk}VvKTNy_%&B;*OrcPD;w~T2B|D_2(6SCK! zWHJ4+cMYsG zWjI3PYKu1R%o^>)G3aNyVsX}7?=jz*(Kt)C>I}gWlhp-dxi4zt&%FBk*ph>dOR=k# z^W*br4Vz0-Vb{9NFvW^9E`!wC(_iwIw_#0nF!r{WYDEZ+8WNu)hcR*k#o#pX!j2{2 zgmu=OuzJGb3r)v4^yCDL6S@zolz8~pziJ~VcSz5d%q;msLbEO6WIVj7M*QZX{Uzqy z{l%%`era{$e(ZW8&%T)$4-Mdmf9eqS{E{Vi#2-I&QCgVW;|-OG!P~zfTWrU(T2K?=LeOG|x) z_*al2!gEPVdof#I<#^Y@7ISN0wH_skb~`L$Xy)bUMI?z?V6aFTuK3^nD!@?hbE6%>0g#!MoVZr)|RYFT2nl=480Jf!9{89 zk8KHB*2h~yf-QLnwNSq)P!pW1E=bS&Ku?^A3sSVQIH{Z~2~l%9s5vk~Jq1G4{GYb} z`_UiUe*!1c{@=9!m%J|yJJlQ)A(U^>_^%Mp!n0*8jm8flPQQhP(&o`PH^ga2n^ zjdGLaU<)%tn99QXWPy)q9D#O%nQ1Q9RZS z)4j-H35^9fdO;|ULc{7u+&upk1d=p;smqSQ=?P}#FUIZ z)$}>gKY{wjIRQ^w*VGKIlPk2X(-|w*wXdVzdpP3(AAg)>g9pT!A4W_0$GhPpR2R7o=SZVnddeY*&RA2HNDX)=FcEqcGX*4vOP}eBs zriaJw6v4R%^dTdcw=gCv_7=g@^6&~8_V*yiad-*Q{`hg;rWmswBstPD>^~1UjQqf0 za2A(^W^q|F>8ao};?j}{(9N84#5YoZ?P33k(S0T3an~q4GeA#F;H=l%blnq>hm)CD zTK9H`0kB^OY&!ZG`P|#`VP*!P^7#)xYW+(3RnChgc@-v%{1>2ml;2@wKVXdK(T(M~ ztwi&)Ja-+XYZfq_!HX$It_-t9sa_gsu`2wn!~Q>@wkoA;DI*^oTq`9?rbgNi6hlag ztz5arOfd_GJoSi017DULolyeC5 z4Q>`1^I9h{H(|V0vuoC|#uwII zT=%Z`&_KmDBG)?)4Oq9m2(PtD3uE5rIjmF%y(iN<4-JqFOWaog*1iq%-1`UG)-vXr zjo{rux&)LnY`EHOz0BHbZQJ_G-@Mhnb{%Wl zzmAyNfiJCP8}9m`_0SVNFXDN;YwFGaURUlt3>wnfCIqpeJ-HKnBPH0Au&xFv$eB!K zbTm)Rc*e{7c5!RhF@S3-=gkIBXqM7B@%AW{NVw#+QkAl6X)^jTB)!o3iTMjRQY}0n z(Y_((Pu*+~_DSGZWf8=wT6j?~;b$26$w4NSce6N09QUT#UgtI2_j(!mkAr=|me5m> z`ZsBrSmZzCPSAq8pwx52uOnB@@T))M8hB$o*FJaRSgyN=>yYdA;itTDKlHH~vL_v} z*h>am(Dn6i8Ylhm^~VvgYINl5h#%5_Eae!zi2ag`wcrxMHwal{*l)pt9UB@j9-pW41+vDN?a@#PG=ZvtyyT{;3fcj`Y z_%gI`h0CNB(&~i0wm=6kp=TpIcR5&-zF05rsw~UjF72n1j}n*0mgFe8X*T>@)4~dK zl$5k%_$H7XB|eSC$;-$zg8zs#4&MxE6xNl{2ZZo|T%}SE3Dv(0@)c`8FYPUk7O;Vxsg7#zgq+ELV7PSrA(IOve&_N)J_A#UGaTVq-=~zsiHxJb5np^Do{{GP z+U((+M6I~rrag6kQtFgh;(W}>`NO^5@T)>l6+pe`9qfS6UZt6y9AV_>;poCx`2HKV zJ!jK;=HT>(1#7ATN*{B1N{&jo329SOU1@;Io~3rudeunJMHhtfJP@S60r1+OttKYJ zVS2tJ2lV*|`T`!oi%lhaaW<<$f?r5*e$+|fxpj~WxFCh7Hi(r>B6|F)6%OjVZN&bI zgC_))Dm+JPr3xt`w-%%HXuw$VWy#~f=LOqWXJc|{jxd~(S^?iE+8(MaxuCq`)cXv& zv>Rc=ft>JsphHQrzAAAzYj%A{TrT#iVP}BH`$(m8^#sl;xH{SEt&DGhN&~ z>S+=hQ|n8Jxx>xK_XkQ#_Vw^#m11FD)Jb|zpC>?!p|X0UZak;3SBqzK=Pa&a1-`|4z4Hu;$ZATXF`O6Dv3QuT-} z=AfsE&HNK?6G^~+gnAJ$=}3>{6*kHDgFil3p!#Ryeu)s5BrbZkHYE2?XPG&=pxhq; zTOTn|S$|SzXg{F$G+>oAx6oZdXivc7&Ju5naZZnW$otFvKo0QNHEU*HfmM!?r%dLi zOc|U1hC(KpsZsqkLpW)g995|LcMU}Wqt^yQ7=_N&hx%2A^gj&tdP8p%??(rFyeXhd z0i_M_hHuQ0$i;KSNN5x33AS}One}&;TG7K6seXs58Tk7qoX;bnv&pLeKQImpeoq8S zUmh?fAWWgKFyr-@X~X^rgYPwAmCWSIBU<9cvR3MEHthdiA*p@1zwR>nl#XF)jUM(Z zO4_3Lny7c%1>BdZzxs01Y@C{gF9qHVcw0L+0w-B&aCbpXO-j)PW$(VZ_(CEMKbiP&n_Eox58PUDb>39_2to-G0xhu z^IpAiQ84#@WpB$1Nzu3!giQ|%``|Y${CI->4rypb9)0JMWKVpie*U{&W`Bjk~)d5$LUqShq@+>4rV06hrcIodWM8jAwx?*EdJm6Uz_cmY8qU2>Ut7 zgL5$9g{vH_uR47dw9=8uCt;D)7Pc#VGEJjT_$<2qQby+jS#Dz1<>{Ma0Hd$P5Uhhc zb563!R+j3tX4I4uY*TotBP9Z5!_!&Q~re2k7`uf zT*no|JnFN!4<~dJgAm~FKkqaG{D`?w+%RvoE^zuRJPg4#KqGqZ1szugF|V8DzR0r~0o|`5vOr&EwD#)qk`4tyc)%GsDPz!-f`NzK|(<%{T)pu+yb2 zNuPW8j5>M}#aEt_Sderhb|upj?OCpPj4y>tcb&x@m(zebqv{+l_3)7y67Nf5=-I6d zhiUp*g_K<(Yji^%jKr&U*%m9D&>y^ON%ddCjU{S^fV;#v_;Y6j?*_=g3ebT2?~c0R zQ|OILCd(tyF5JDh+&}}~4bA$+rt;LrM2w^}IEig4!;a59?8Ze}SSiq7xDSN(FM4JP zZk^36k#1HZBZ&OEGBM2$|F_6{ac?fx!+YMLYyS6rF*}}Zfv;uN@jg9oF=aM}v|*N! zken2Hn>|t$l$t_)V}zar_gATg#cg^+Au(CIv&%lv?+ftX>ns5^$ zp(pe@oBF*3o_u8G1jv#}8&Y`9>7)%w>ykF)_LJPCb>WNIT$6ONDF-(RnH)MhgDf>wtI3teNKnImF6pJ9>+eRkR;;{*@@%tD@t;LH_MK{kKbH-5{+6UW$Q_1#s zr=3fJ^Z>i_E?XA8r!zU=A0A1B- zZwt}Wd!fez#ZO~@dVO*?VV+)_@Oxu7VH561{C$vT!!A_@dqheOF=C$1|FgvR*kYG4 zrxbY3rE1R6Cq3`ljwj*~V`&j%X%S5N+W04JxEJ^qgw>rVi=a_Dt|VnqS@&UvTC|vA zuB2W&e0n0rqPqol5!m}i{o6;w>^Ng!(c^!QMITJtG79S+(zL-eLu&)=ccQnJV=gb= zNaMV<3h}aLXoq0gTj{yM?pA87du=y)er2DKe7jJ$-X@bZb!a1f(l%!OKizn28TB6> znrFZ0n1>ok7BS%t69;0~x0y_iqJBPh|Jn>ljKk*`Q>2gqE?+j7fpd_dwv-}Hzmb`# z;$Ix9|5kOq1a6Mq999K{Bx&u@B-lqO_gh=MKWIJN?O7Ohq3}9jh#9}_h0=}?+jnaA(`q%0txG$&%vgS_1$uamiB^3+2 zvM7I{KEPDti9AaqaX#Rj6g^ZiSinq{v@)mNJdHJLda`5DW@eA;Ek5hUcEym0ammn| zTlTuNKIg9)cq#2JL41ISWcIc0|Jcd7wGBXUUc35;TMJTnWWr@U-k zQBpju{!r}B$9L81nK{+26*(QicyGL|oBLm_U42wr$CaP=AtV8@1xjoo>>>nqu~`EF zTw{}sACi!5(GY*=`M~&xUnu z2#`&aY|jd_N(@fU(zK}yY_`J2kpf2A-+hv(oA~TsedmnsotgV)-kUo!nz?iDeP#|` zgtM)`3U{$Qs{%ILHRuh8BC6SAjAS$BnIknjOTT8W=L#M~*=1Q~l-!E_)?vl$uGJrg zS!VV;t9S>HYR;Y!gds@FwhJk?JXm4F%dSv|@*a(Vn!G4&&6#Ir=;fmI)|BPUD3y@L zpuL#Lct0!w(>+6Yu4w3Jv;xOJhUzMz9++% z;?X*)Ab+4Xr}ic($62q|Gw#S3kn)cVN;z7`zGv?C5UtjHJQ!YX?ADG5 z6Q2JVIPTr~Or58HG59%KTxEP_K!)vy$@N`4L{K!uR^zj>a%ezXc21TM(=vh?;Vd^&|9#|GYp3{>Wv=qc*t!` z?q7j5vPvb)n(o%%eKB6tuxtpzdI$E|7zJwN(EDPR6(zi{nuE82QWXy!Iu0k`rMi}j zXzc>Dw!z>qc=VQnXO3iW_x*D5^Lc4zRH9P;9sfNvCK7E_&Ba^km@dezL^~Z@$MVPgT|55s+P^?=>rLor9)>N1VEr(xQ@8cMKHIkPw^uqmr{O*M(XjX& z+NtgItXkD&c>})fZeGz@QY;;g8pp4oUl*>%d)q~8llL|6*Q8bRZM98K!H+ttBcY)S ztRQ_dfEm3*?Y97{w{CqIIAEmM2du{zU zr9$3B`2#NmL>VuL{0z84#`7XR;7KxWjN}7X%J`bdA2}hQlJQlM7D1Xj(>AS4)cE7b zS>Ul6UyAGl9;>l4QV2X&KR%c!9@id@`~Tc&x^Qky*tP;HfH` zdIQd4E>U}+%pbDieDB%`B{zn7u1&d-pX2ybgYW@&yn05LxBZ&T z4e(+T9#nN0lPbeU(`?Plv#F^p`#EUd&}m|~XB#AJb@;7wY`B&d6jsJcYp=u%!5tZd z=R3Ky-$Sz|{G94MNk5*D?ah`#tK>CQEX@~BOT9?z1Ddsj*^0C=nrUIF`W7I~^S7mM zji+z@QhGW5f$m5jPnYS7&Wk0&DGt88#YJJ=ThK{Jsu6nxx1uMe2O}DXrd6h)>EtxC zy9jGVW~}fHgGx+8nz0%G){)Q#q?0}jY03tnIN^A9f6TwU!@1 z^F?sx4w`*}GZNzAdx&Jb(8%d?d6_}GHr>-&vVA*lE20ZOqJx5-Y7Z=vy-teldn~=KYtU2TPl+Ym0bx8zZ5I-UOdeFY(C;X_!4MmZ#9VAxCFjxHbZf9JFr9 zS6ep{%9r=&34Y~(U;4GLxIO_F{+wURFY$}|0D8c-ul9i3IR?2ZbYI91V4AEo^|Y@5 ze0v9)i^MhJ+1eK38;5VL^t#0H-*{pDwiWx7XiU@MGx`68o{nte6FO3C{p;2<(4yWY zbL=!YMw&>noSitP+@^nZHc9y+{?ArhrNYb!#hfHO92WEc$%Gvm?5|{QE%WM6wZ0G~ z&RZ)dE)(B=4bM{Bz^^wWy}rM;+;1rdzdpSdYv^t5kmiOpa__dA^Xi$wf zM!b5Y+b>qBgirDDGTzuUELy^}Xi60hVm4ry`>`Ji@x}>&opU&)e$;pTDF^bCg7E@5g>m39|z(`1vPv&5M^(K|Y zbUd9muobfQtcs6m&*F}~DYne!@qOgoVch+WQB~FL0{4q2UCh|+taDE~>LBl_bCUc< zE(iWxsn4lxknVcNJt@*ee~+>mR<3DIWnAAh61o(Z?c;qwE8>ZHGd-`yT#Kib`HpAW zhP`w2Uiw;*3-)!1eKLO=J{~?|7{Ql`2r{(S5%B#8yV5KLqmncqWzzhAW99r5yR!F6 zvjJ%aq#2NAh^L{Ku;v-b-aKQsqn9v>58X&+2^_ou-huLEh|)Via}sGMktRc=okUs} z(z=i)L!@;ftsQCYNRuJb+L3k&X{V5ON<&-)EMmd)0~nLwE6zZT_A0F7v+Y%NkCQKz zx`s*UF!TK6UeS29xvC1S?KvUd3fOEUW$SkAvQ6UjP49%(nW@`puIlzak6iE=zG3tZ zQgtz0iV*OrF?j`A^C7ag58(zz)8x;!#K4-csA7 ztJH=(DyvxUCojb$L-TXc`iQjAcUvk&g=h^fKlP;?7 zRnTYQemv^qH>lK1!f(~g|-Pxm|Patz{lVIyd-m<0GN%NIU*e5?I_eID^*$@kg zP$7zqn<&SQcBqOC4(8_7+>R9r)yFA=oPm+diPNYxQvjR>vE9|db0*dK%g}^@?i76B zLNlgMgid=(pB;Nos%a^-2mX&4|f1)*O&ZDnO;(RM)PDc&BNn#+~)(L7qs2zx{uxa<< zUU&q^Ml8kFiI^X;PZVN6Y11|$ud!=KFJhvt6EQzxB(c90@+aD4xsLB+>>f3^K)VWl zH*n|UT|06RLyd^}5t|al0M4_Ukk{0;<7LE9BVvBUT!^V`+GgZ6<37YtBVvBUVl}=< zXUX6Lt$&w7QkYutR;XRJ8z9;7z)~#bFwVA<;FVhi?d{jYN!d!nQs@_eD!|tO)qrOJ zlL31HR|EbSFb}XNtj_)(;EQ2pb}?WlPM~(<#Gm@Xv(Qhadd@7d;9cRR(58i@kmA-7 z{{L_uBiD`ZXJP#VeNtP76*_ z`r!ZC${XlwAsT3?(J2*X|0>XWAX~k_1{-m12|drPyrl!HGJJh+N@#^g)#_e&GSFp0 z-d}WG_Tkdo_pW|*D`$aT>s<7{b`wrCC*X;FO3``|o;^A7=2+^isQ3V01!R8)hwce; z&%&nVvtZ>-KlFr{U`46<y0xfAR+)~_{h?SNUZrMzsh(=x=6Eu%9&QQw)!y`<3<#%)So)bx| zqW9D54c_OKD9>E+EvseMV@`L&Hp2rA-}#PnZ-ZfX#RG=w?=~EGtg-p;vq58W)*C=4 zQyIKX^$o2BNR3^68<^^#5#LQMVyaI8=MdCi$9f}|seTT;58)WXeuTHzV=V%hR?Ji{ z1HObf`%$8#uflhCfc*$_2p=O%BLooMLijnt5(3@z8|VT58bJ-6;G2LP;Aemn2yY|Y zgE-M~^n=TdwwZ@cPc7C!q_)A@8bD+Gvhfn zRIH|%l?STGWg1SA%P~&O<#|PJ662JL9|$;rSBo6ulX0U`!SND-Lj+hl!WER2&S_8+ z)(hzs-$tRlfQJwTwHSXxR&;N1N$KWqY$@AXVKQ4Pt+86S0W3QI33-(VL9v&`U zW($pz#C7|9i8MtV`3W)!y_I;*1Oeck?n`9;V{xK0NMfHCH(|>EG`3?)&GOOMD%yMS};f6Dg7^*_J33Frf&cM literal 0 HcmV?d00001 From 2c946b92e9b80618ed95d60aab6b4c4f36431c66 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 12 Jan 2024 14:24:55 +1100 Subject: [PATCH 0495/1335] hwdef: added Pixhawk6X-PPPGW --- .../hwdef/Pixhawk6X-PPPGW/defaults.parm | 7 +++ .../hwdef/Pixhawk6X-PPPGW/hwdef.dat | 57 +++++++++++++++++++ 2 files changed, 64 insertions(+) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/defaults.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/hwdef.dat diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/defaults.parm new file mode 100644 index 00000000000000..6ce9cad8f915f6 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/defaults.parm @@ -0,0 +1,7 @@ +NET_ENABLED 1 + +# enable hw flow control +UART1_RTSCTS 1 + +# swap TX and RX +UART1_OPTIONS 8 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/hwdef.dat new file mode 100644 index 00000000000000..b9a4f3d6d82876 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/hwdef.dat @@ -0,0 +1,57 @@ +include ../Pixhawk6X/hwdef.dat + +undef IOMCU_UART +undef USART6 +undef ROMFS +undef HAL_HAVE_SAFETY_SWITCH +undef HAL_WITH_IO_MCU_BIDIR_DSHOT +undef COMPASS +undef BARO + +define AP_ADVANCEDFAILSAFE_ENABLED 0 + + +# board ID for firmware load +APJ_BOARD_ID AP_HW_PIXHAWK6X_PERIPH + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +define AP_CAN_SLCAN_ENABLED 0 + +define HAL_PERIPH_ENABLE_NETWORKING +define HAL_PERIPH_ENABLE_SERIAL_OPTIONS + +define AP_NETWORKING_BACKEND_PPP 1 + +define HAL_NO_MONITOR_THREAD +define HAL_DISABLE_LOOP_DELAY + +define HAL_USE_RTC FALSE +define DISABLE_SERIAL_ESC_COMM TRUE + +define HAL_NO_RCIN_THREAD + +define AP_SCRIPTING_ENABLED 0 + +# use blue LED +define HAL_GPIO_PIN_LED HAL_GPIO_PIN_LED_BLUE + +undef HAL_OS_FATFS_IO + +undef SDMMC1 + +MAIN_STACK 0x2000 +PROCESS_STACK 0x6000 + +define HAL_CAN_DRIVER_DEFAULT 1 + +# listen for reboot command from uploader.py script +# undefine to disable. Use -1 to allow on all ports, otherwise serial number index defined in SERIAL_ORDER starting at 0 +define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 + +// use main fw bootloader +define AP_BOOTLOADER_FLASHING_ENABLED 0 + +define AP_PERIPH_NET_PPP_PORT_DEFAULT 1 +define AP_PERIPH_NET_PPP_BAUD_DEFAULT 12500000 From 625b7b6ab7ba886cd45a090407d0f42deccbe82f Mon Sep 17 00:00:00 2001 From: Mehmet Keten Date: Sat, 13 Jan 2024 01:51:49 +0300 Subject: [PATCH 0496/1335] Tools: added name to GIT_Success.txt --- Tools/GIT_Test/GIT_Success.txt | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Tools/GIT_Test/GIT_Success.txt b/Tools/GIT_Test/GIT_Success.txt index abada8657bd71a..82f59f568a52ef 100644 --- a/Tools/GIT_Test/GIT_Success.txt +++ b/Tools/GIT_Test/GIT_Success.txt @@ -177,6 +177,7 @@ Torre Orazio seba czapnik Ramy Gad Matthew R. Cunningham +Mehmet Keten prathap devendran (Tamil) india, 11-23 Taqwaisneeded -FreeName \ No newline at end of file +FreeName From 9202a33ff47efa618967d74d1d066558006d8729 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 13 Jan 2024 12:20:33 +1100 Subject: [PATCH 0497/1335] AP_Scripting: added networking bindings and allow uart calls without GCS this allows for useful lua scripts on non-heavy peripherals --- .../AP_Scripting/generator/description/bindings.desc | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index 5788f9c64c1cf8..909defc96aa622 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -387,7 +387,6 @@ singleton RC_Channels method get_aux_cached boolean RC_Channel::AUX_FUNC'enum 0 include AP_SerialManager/AP_SerialManager.h -ap_object AP_HAL::UARTDriver depends HAL_GCS_ENABLED ap_object AP_HAL::UARTDriver method begin void uint32_t 1U UINT32_MAX ap_object AP_HAL::UARTDriver method read int16_t ap_object AP_HAL::UARTDriver manual readstring AP_HAL__UARTDriver_readstring 1 @@ -888,3 +887,12 @@ singleton AP_RTC depends AP_RTC_ENABLED singleton AP_RTC rename rtc singleton AP_RTC method clock_s_to_date_fields boolean uint32_t'skip_check uint16_t'Null uint8_t'Null uint8_t'Null uint8_t'Null uint8_t'Null uint8_t'Null uint8_t'Null singleton AP_RTC method date_fields_to_clock_s uint32_t uint16_t'skip_check int8_t'skip_check uint8_t'skip_check uint8_t'skip_check uint8_t'skip_check uint8_t'skip_check + +include AP_Networking/AP_Networking.h depends AP_NETWORKING_ENABLED +include AP_Networking/AP_Networking_Config.h +singleton AP_Networking depends AP_NETWORKING_ENABLED +singleton AP_Networking rename networking +singleton AP_Networking method get_ip_active uint32_t +singleton AP_Networking method get_netmask_active uint32_t +singleton AP_Networking method get_gateway_active uint32_t +singleton AP_Networking method address_to_str string uint32_t'skip_check From 30546f290328530b6d1b2b2a2b3bd7c406151639 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 13 Jan 2024 12:20:51 +1100 Subject: [PATCH 0498/1335] AP_Networking: added address_to_str() for scripting --- libraries/AP_Networking/AP_Networking.cpp | 7 +++++++ libraries/AP_Networking/AP_Networking.h | 3 +++ 2 files changed, 10 insertions(+) diff --git a/libraries/AP_Networking/AP_Networking.cpp b/libraries/AP_Networking/AP_Networking.cpp index dd926a31e541c3..303b50ab9861b6 100644 --- a/libraries/AP_Networking/AP_Networking.cpp +++ b/libraries/AP_Networking/AP_Networking.cpp @@ -442,6 +442,13 @@ int ap_networking_printf(const char *fmt, ...) return 0; } +// address to string using a static return buffer +const char *AP_Networking::address_to_str(uint32_t addr) +{ + static char buf[16]; // 16 for aaa.bbb.ccc.ddd + return SocketAPM::inet_addr_to_str(addr, buf, sizeof(buf)); +} + #ifdef LWIP_PLATFORM_ASSERT void ap_networking_platform_assert(const char *msg, int line, const char *file) { diff --git a/libraries/AP_Networking/AP_Networking.h b/libraries/AP_Networking/AP_Networking.h index c83f0e26da2331..f5db359962fddd 100644 --- a/libraries/AP_Networking/AP_Networking.h +++ b/libraries/AP_Networking/AP_Networking.h @@ -139,6 +139,9 @@ class AP_Networking // convert string to ethernet mac address static bool convert_str_to_macaddr(const char *mac_str, uint8_t addr[6]); + // address to string using a static return buffer for scripting + static const char *address_to_str(uint32_t addr); + // helper functions to convert between 32bit Netmask and counting consecutive bits and back static uint32_t convert_netmask_bitcount_to_ip(const uint32_t netmask_bitcount); static uint8_t convert_netmask_ip_to_bitcount(const uint32_t netmask_ip); From faea203af691537cfec885f8172e019587a5f1fc Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 13 Jan 2024 12:21:43 +1100 Subject: [PATCH 0499/1335] hwdef: added web UI to PPPGW example --- .../hwdef/Pixhawk6X-PPPGW/defaults.parm | 7 + .../hwdef/Pixhawk6X-PPPGW/hwdef.dat | 13 +- .../Pixhawk6X-PPPGW/scripts/pppgw_webui.lua | 962 ++++++++++++++++++ 3 files changed, 980 insertions(+), 2 deletions(-) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/scripts/pppgw_webui.lua diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/defaults.parm index 6ce9cad8f915f6..89ab4beebb035b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/defaults.parm +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/defaults.parm @@ -1,7 +1,14 @@ NET_ENABLED 1 +NET_OPTIONS 1 # enable hw flow control UART1_RTSCTS 1 # swap TX and RX UART1_OPTIONS 8 + +SCR_ENABLE 1 +SCR_VM_I_COUNT 1000000 + +WEB_ENABLE 1 +WEB_PORT 80 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/hwdef.dat index b9a4f3d6d82876..e6a89919116c34 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/hwdef.dat @@ -32,8 +32,6 @@ define DISABLE_SERIAL_ESC_COMM TRUE define HAL_NO_RCIN_THREAD -define AP_SCRIPTING_ENABLED 0 - # use blue LED define HAL_GPIO_PIN_LED HAL_GPIO_PIN_LED_BLUE @@ -55,3 +53,14 @@ define AP_BOOTLOADER_FLASHING_ENABLED 0 define AP_PERIPH_NET_PPP_PORT_DEFAULT 1 define AP_PERIPH_NET_PPP_BAUD_DEFAULT 12500000 + +// add scripting for web interface +define AP_SCRIPTING_ENABLED 1 + +// ROMFS filesystem only +define AP_FILESYSTEM_ROMFS_ENABLED 1 + +// allow scripts to add parameters +define AP_PARAM_DYNAMIC_ENABLED 1 + + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/scripts/pppgw_webui.lua b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/scripts/pppgw_webui.lua new file mode 100644 index 00000000000000..b7f9854e4d7611 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/Pixhawk6X-PPPGW/scripts/pppgw_webui.lua @@ -0,0 +1,962 @@ +--[[ + example script to test lua socket API +--]] + +PARAM_TABLE_KEY = 47 +PARAM_TABLE_PREFIX = "WEB_" + +-- add a parameter and bind it to a variable +function bind_add_param(name, idx, default_value) + assert(param:add_param(PARAM_TABLE_KEY, idx, name, default_value), string.format('could not add param %s', name)) + return Parameter(PARAM_TABLE_PREFIX .. name) +end + +-- Setup Parameters +assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 6), 'net_test: could not add param table') + +--[[ + // @Param: WEB_ENABLE + // @DisplayName: enable web server + // @Description: enable web server + // @Values: 0:Disabled,1:Enabled + // @User: Standard +--]] +local WEB_ENABLE = bind_add_param('ENABLE', 1, 1) + +--[[ + // @Param: WEB_BIND_PORT + // @DisplayName: web server TCP port + // @Description: web server TCP port + // @Range: 1 65535 + // @User: Standard +--]] +local WEB_BIND_PORT = bind_add_param('BIND_PORT', 2, 80) + +--[[ + // @Param: WEB_DEBUG + // @DisplayName: web server debugging + // @Description: web server debugging + // @Values: 0:Disabled,1:Enabled + // @User: Advanced +--]] +local WEB_DEBUG = bind_add_param('DEBUG', 3, 0) + +--[[ + // @Param: WEB_BLOCK_SIZE + // @DisplayName: web server block size + // @Description: web server block size for download + // @Range: 1 65535 + // @User: Advanced +--]] +local WEB_BLOCK_SIZE = bind_add_param('BLOCK_SIZE', 4, 10240) + +--[[ + // @Param: WEB_TIMEOUT + // @DisplayName: web server timeout + // @Description: timeout for inactive connections + // @Units: s + // @Range: 0.1 60 + // @User: Advanced +--]] +local WEB_TIMEOUT = bind_add_param('TIMEOUT', 5, 2.0) + +--[[ + // @Param: WEB_SENDFILE_MIN + // @DisplayName: web server minimum file size for sendfile + // @Description: sendfile is an offloading mechanism for faster file download. If this is non-zero and the file is larger than this size then sendfile will be used for file download + // @Range: 0 10000000 + // @User: Advanced +--]] +local WEB_SENDFILE_MIN = bind_add_param('SENDFILE_MIN', 6, 100000) + +if WEB_ENABLE:get() ~= 1 then + periph:can_printf("WebServer: disabled") + return +end + +periph:can_printf(string.format("WebServer: starting on port %u", WEB_BIND_PORT:get())) + +local sock_listen = Socket(0) +local clients = {} + +local DOCTYPE = "" +local SERVER_VERSION = "net_webserver 1.0" +local CONTENT_TEXT_HTML = "text/html;charset=UTF-8" +local CONTENT_OCTET_STREAM = "application/octet-stream" + +local HIDDEN_FOLDERS = { "@SYS", "@ROMFS", "@MISSION", "@PARAM" } + +local MNT_PREFIX = "/mnt" +local MNT_PREFIX2 = MNT_PREFIX .. "/" + +local MIME_TYPES = { + ["apj"] = CONTENT_OCTET_STREAM, + ["dat"] = CONTENT_OCTET_STREAM, + ["o"] = CONTENT_OCTET_STREAM, + ["obj"] = CONTENT_OCTET_STREAM, + ["lua"] = "text/x-lua", + ["py"] = "text/x-python", + ["shtml"] = CONTENT_TEXT_HTML, + ["js"] = "text/javascript", + -- thanks to https://developer.mozilla.org/en-US/docs/Web/HTTP/Basics_of_HTTP/MIME_types/Common_types + ["aac"] = "audio/aac", + ["abw"] = "application/x-abiword", + ["arc"] = "application/x-freearc", + ["avif"] = "image/avif", + ["avi"] = "video/x-msvideo", + ["azw"] = "application/vnd.amazon.ebook", + ["bin"] = "application/octet-stream", + ["bmp"] = "image/bmp", + ["bz"] = "application/x-bzip", + ["bz2"] = "application/x-bzip2", + ["cda"] = "application/x-cdf", + ["csh"] = "application/x-csh", + ["css"] = "text/css", + ["csv"] = "text/csv", + ["doc"] = "application/msword", + ["docx"] = "application/vnd.openxmlformats-officedocument.wordprocessingml.document", + ["eot"] = "application/vnd.ms-fontobject", + ["epub"] = "application/epub+zip", + ["gz"] = "application/gzip", + ["gif"] = "image/gif", + ["htm"] = CONTENT_TEXT_HTML, + ["html"] = CONTENT_TEXT_HTML, + ["ico"] = "image/vnd.microsoft.icon", + ["ics"] = "text/calendar", + ["jar"] = "application/java-archive", + ["jpeg"] = "image/jpeg", + ["json"] = "application/json", + ["jsonld"] = "application/ld+json", + ["mid"] = "audio/x-midi", + ["mjs"] = "text/javascript", + ["mp3"] = "audio/mpeg", + ["mp4"] = "video/mp4", + ["mpeg"] = "video/mpeg", + ["mpkg"] = "application/vnd.apple.installer+xml", + ["odp"] = "application/vnd.oasis.opendocument.presentation", + ["ods"] = "application/vnd.oasis.opendocument.spreadsheet", + ["odt"] = "application/vnd.oasis.opendocument.text", + ["oga"] = "audio/ogg", + ["ogv"] = "video/ogg", + ["ogx"] = "application/ogg", + ["opus"] = "audio/opus", + ["otf"] = "font/otf", + ["png"] = "image/png", + ["pdf"] = "application/pdf", + ["php"] = "application/x-httpd-php", + ["ppt"] = "application/vnd.ms-powerpoint", + ["pptx"] = "application/vnd.openxmlformats-officedocument.presentationml.presentation", + ["rar"] = "application/vnd.rar", + ["rtf"] = "application/rtf", + ["sh"] = "application/x-sh", + ["svg"] = "image/svg+xml", + ["tar"] = "application/x-tar", + ["tif"] = "image/tiff", + ["tiff"] = "image/tiff", + ["ts"] = "video/mp2t", + ["ttf"] = "font/ttf", + ["txt"] = "text/plain", + ["vsd"] = "application/vnd.visio", + ["wav"] = "audio/wav", + ["weba"] = "audio/webm", + ["webm"] = "video/webm", + ["webp"] = "image/webp", + ["woff"] = "font/woff", + ["woff2"] = "font/woff2", + ["xhtml"] = "application/xhtml+xml", + ["xls"] = "application/vnd.ms-excel", + ["xlsx"] = "application/vnd.openxmlformats-officedocument.spreadsheetml.sheet", + ["xml"] = "default.", + ["xul"] = "application/vnd.mozilla.xul+xml", + ["zip"] = "application/zip", + ["3gp"] = "video", + ["3g2"] = "video", + ["7z"] = "application/x-7z-compressed", +} + +--[[ + builtin dynamic pages +--]] +local DYNAMIC_PAGES = { + +-- main home page +["/"] = [[ + + + + + + ArduPilot + + + +

ArduPilot PPP Gateway

+ + + +

Controller Status

+
+ + +]], + +-- board status section on front page +["@DYNAMIC/board_status.shtml"] = [[ + + + + + + + +
Firmware
GIT Hash
Uptime
IP
Netmask
Gateway
+]] +} + +--[[ + builtin javascript library functions +--]] +JS_LIBRARY = { + ["dynamic_load"] = [[ + function dynamic_load(div_id, uri, period_ms) { + var xhr = new XMLHttpRequest(); + xhr.open('GET', uri); + + xhr.setRequestHeader("Cache-Control", "no-cache, no-store, max-age=0"); + xhr.setRequestHeader("Expires", "Tue, 01 Jan 1980 1:00:00 GMT"); + xhr.setRequestHeader("Pragma", "no-cache"); + + xhr.onload = function () { + if (xhr.status === 200) { + var output = document.getElementById(div_id); + if (uri.endsWith('.shtml') || uri.endsWith('.html')) { + output.innerHTML = xhr.responseText; + } else { + output.textContent = xhr.responseText; + } + } + setTimeout(function() { dynamic_load(div_id,uri, period_ms); }, period_ms); + } + xhr.send(); + } +]] +} + +if not sock_listen:bind("0.0.0.0", WEB_BIND_PORT:get()) then + periph:can_printf(string.format("WebServer: failed to bind to TCP %u", WEB_BIND_PORT:get())) + return +end + +if not sock_listen:listen(20) then + periph:can_printf("WebServer: failed to listen") + return +end + +function hms_uptime() + local s = (millis()/1000):toint() + local min = math.floor(s / 60) % 60 + local hr = math.floor(s / 3600) + return string.format("%u hours %u minutes %u seconds", hr, min, s%60) +end + +--[[ + split string by pattern +--]] +local function split(str, pattern) + local ret = {} + for s in string.gmatch(str, pattern) do + table.insert(ret, s) + end + return ret +end + +--[[ + return true if a string ends in the 2nd string +--]] +local function endswith(str, s) + local len1 = #str + local len2 = #s + return string.sub(str,1+len1-len2,len1) == s +end + +--[[ + return true if a string starts with the 2nd string +--]] +local function startswith(str, s) + return string.sub(str,1,#s) == s +end + +local debug_count=0 + +function DEBUG(txt) + if WEB_DEBUG:get() ~= 0 then + periph:can_printf(txt .. string.format(" [%u]", debug_count)) + debug_count = debug_count + 1 + end +end + +--[[ + return index of element in a table +--]] +function table_index(t,el) + for i,v in ipairs(t) do + if v == el then + return i + end + end + return nil +end + +--[[ + return true if a table contains a given element +--]] +function table_contains(t,el) + local i = table_index(t, el) + return i ~= nil +end + +function is_hidden_dir(path) + return table_contains(HIDDEN_FOLDERS, path) +end + +local DAYS = { "Sun", "Mon", "Tue", "Wed", "Thu", "Fri", "Sat" } +local MONTHS = { "Jan", "Feb", "Mar", "Apr", "May", "Jun", "Jul", "Aug", "Sep", "Oct", "Nov", "Dec" } + +function isdirectory(path) + local s = fs:stat(path) + return s and s:is_directory() +end + +--[[ + time string for directory listings +--]] +function file_timestring(path) + local s = fs:stat(path) + if not s then + return "" + end + local mtime = s:mtime() + local year, month, day, hour, min, sec, _ = rtc:clock_s_to_date_fields(mtime) + if not year then + return "" + end + return string.format("%04u-%02u-%02u %02u:%02u", year, month+1, day, hour, min, sec) +end + +--[[ + time string for Last-Modified +--]] +function file_timestring_http(mtime) + local year, month, day, hour, min, sec, wday = rtc:clock_s_to_date_fields(mtime) + if not year then + return "" + end + return string.format("%s, %02u %s %u %02u:%02u:%02u GMT", + DAYS[wday+1], + day, + MONTHS[month+1], + year, + hour, + min, + sec) +end + +--[[ + parse a http time string to a uint32_t seconds timestamp +--]] +function file_timestring_http_parse(tstring) + local dayname, day, monthname, year, hour, min, sec = + string.match(tstring, + '(%w%w%w), (%d+) (%w%w%w) (%d%d%d%d) (%d%d):(%d%d):(%d%d) GMT') + if not dayname then + return nil + end + local mon = table_index(MONTHS, monthname) + return rtc:date_fields_to_clock_s(year, mon-1, day, hour, min, sec) +end + +--[[ + return true if path exists and is not a directory +--]] +function file_exists(path) + local s = fs:stat(path) + if not s then + return false + end + return not s:is_directory() +end + +--[[ + substitute variables of form {xxx} from a table + from http://lua-users.org/wiki/StringInterpolation +--]] +function substitute_vars(s, vars) + s = (string.gsub(s, "({([^}]+)})", + function(whole,i) + return vars[i] or whole + end)) + return s +end + +--[[ + lat or lon as a string, working around limited type in ftoa_engine +--]] +function latlon_str(ll) + local ipart = tonumber(string.match(tostring(ll*1.0e-7), '(.*[.]).*')) + local fpart = math.abs(ll - ipart*10000000) + return string.format("%d.%u", ipart, fpart, ipart*10000000, ll) +end + +--[[ + location string for home page +--]] +function location_string(loc) + return substitute_vars([[{lat} {lon} {alt}]], + { ["lat"] = latlon_str(loc:lat()), + ["lon"] = latlon_str(loc:lng()), + ["alt"] = string.format("%.1fm", loc:alt()*1.0e-2) }) +end + +--[[ + client class for open connections +--]] +local function Client(_sock, _idx) + local self = {} + + self.closed = false + + local sock = _sock + local idx = _idx + local have_header = false + local header = "" + local header_lines = {} + local header_vars = {} + local run = nil + local protocol = nil + local file = nil + local start_time = millis() + local offset = 0 + + function self.read_header() + local s = sock:recv(2048) + if not s then + local now = millis() + if not sock:is_connected() or now - start_time > WEB_TIMEOUT:get()*1000 then + -- EOF while looking for header + DEBUG(string.format("%u: EOF", idx)) + self.remove() + return false + end + return false + end + if not s or #s == 0 then + return false + end + header = header .. s + local eoh = string.find(s, '\r\n\r\n') + if eoh then + DEBUG(string.format("%u: got header", idx)) + have_header = true + header_lines = split(header, "[^\r\n]+") + -- blocking for reply + sock:set_blocking(true) + return true + end + return false + end + + function self.sendstring(s) + sock:send(s, #s) + end + + function self.sendline(s) + self.sendstring(s .. "\r\n") + end + + --[[ + send a string with variable substitution using {varname} + --]] + function self.sendstring_vars(s, vars) + self.sendstring(substitute_vars(s, vars)) + end + + function self.send_header(code, codestr, vars) + self.sendline(string.format("%s %u %s", protocol, code, codestr)) + self.sendline(string.format("Server: %s", SERVER_VERSION)) + for k,v in pairs(vars) do + self.sendline(string.format("%s: %s", k, v)) + end + self.sendline("Connection: close") + self.sendline("") + end + + -- get size of a file + function self.file_size(fname) + local s = fs:stat(fname) + if not s then + return 0 + end + local ret = s:size():toint() + DEBUG(string.format("%u: size of '%s' -> %u", idx, fname, ret)) + return ret + end + + + --[[ + return full path with .. resolution + --]] + function self.full_path(path, name) + DEBUG(string.format("%u: full_path(%s,%s)", idx, path, name)) + local ret = path + if path == "/" and startswith(name,"@") then + return name + end + if name == ".." then + if path == "/" then + return "/" + end + if endswith(path,"/") then + path = string.sub(path, 1, #path-1) + end + local dir, _ = string.match(path, '(.*/)(.*)') + if not dir then + return path + end + return dir + end + if not endswith(ret, "/") then + ret = ret .. "/" + end + ret = ret .. name + DEBUG(string.format("%u: full_path(%s,%s) -> %s", idx, path, name, ret)) + return ret + end + + function self.directory_list(path) + sock:set_blocking(true) + if startswith(path, "/@") then + path = string.sub(path, 2, #path-1) + end + DEBUG(string.format("%u: directory_list(%s)", idx, path)) + local dlist = dirlist(path) + if not dlist then + dlist = {} + end + if not table_contains(dlist, "..") then + -- on ChibiOS we don't get .. + table.insert(dlist, "..") + end + if path == "/" then + for _,v in ipairs(HIDDEN_FOLDERS) do + table.insert(dlist, v) + end + end + + table.sort(dlist) + self.send_header(200, "OK", {["Content-Type"]=CONTENT_TEXT_HTML}) + self.sendline(DOCTYPE) + self.sendstring_vars([[ + + + Index of {path} + + +

Index of {path}

+ + +]], {path=path}) + for _,d in ipairs(dlist) do + local skip = d == "." + if not skip then + local fullpath = self.full_path(path, d) + local name = d + local sizestr = "0" + local stat = fs:stat(fullpath) + local size = stat and stat:size() or 0 + if is_hidden_dir(fullpath) or (stat and stat:is_directory()) then + name = name .. "/" + elseif size >= 100*1000*1000 then + sizestr = string.format("%uM", (size/(1000*1000)):toint()) + else + sizestr = tostring(size) + end + local modtime = file_timestring(fullpath) + self.sendstring_vars([[ +]], { name=name, size=sizestr, modtime=modtime }) + end + end + self.sendstring([[ +
NameLast modifiedSize
{name}{modtime}{size}
+ + +]]) + end + + -- send file content + function self.send_file() + if not sock:pollout(0) then + return + end + local chunk = WEB_BLOCK_SIZE:get() + local b = file:read(chunk) + sock:set_blocking(true) + if b and #b > 0 then + local sent = sock:send(b, #b) + if sent == -1 then + run = nil + self.remove() + return + end + if sent < #b then + file:seek(offset+sent) + end + offset = offset + sent + end + if not b or #b < chunk then + -- EOF + DEBUG(string.format("%u: sent file", idx)) + run = nil + self.remove() + return + end + end + + --[[ + load whole file as a string + --]] + function self.load_file() + local chunk = WEB_BLOCK_SIZE:get() + local ret = "" + while true do + local b = file:read(chunk) + if not b or #b == 0 then + break + end + ret = ret .. b + end + return ret + end + + --[[ + evaluate some lua code and return as a string + --]] + function self.evaluate(code) + local eval_code = "function eval_func()\n" .. code .. "\nend\n" + local f, errloc, err = load(eval_code, "eval_func", "t", _ENV) + if not f then + DEBUG(string.format("load failed: err=%s errloc=%s", err, errloc)) + return nil + end + local success, err2 = pcall(f) + if not success then + DEBUG(string.format("pcall failed: err=%s", err2)) + return nil + end + local ok, s2 = pcall(eval_func) + eval_func = nil + if ok then + return s2 + end + return nil + end + + --[[ + process a file as a lua CGI + --]] + function self.send_cgi() + sock:set_blocking(true) + local contents = self.load_file() + local s = self.evaluate(contents) + if s then + self.sendstring(s) + end + self.remove() + end + + --[[ + send file content with server side processsing + files ending in .shtml can have embedded lua lika this: + + + + Using 'lstr' a return tostring(yourcode) is added to the code + automatically + --]] + function self.send_processed_file(dynamic_page) + sock:set_blocking(true) + local contents + if dynamic_page then + contents = file + else + contents = self.load_file() + end + while #contents > 0 do + local pat1 = "(.-)[<][?]lua[ \n](.-)[?][>](.*)" + local pat2 = "(.-)[<][?]lstr[ \n](.-)[?][>](.*)" + local p1, p2, p3 = string.match(contents, pat1) + if not p1 then + p1, p2, p3 = string.match(contents, pat2) + if not p1 then + break + end + p2 = "return tostring(" .. p2 .. ")" + end + self.sendstring(p1) + local s2 = self.evaluate(p2) + if s2 then + self.sendstring(s2) + end + contents = p3 + end + self.sendstring(contents) + self.remove() + end + + -- return a content type + function self.content_type(path) + if path == "/" then + return MIME_TYPES["html"] + end + local _, ext = string.match(path, '(.*[.])(.*)') + ext = string.lower(ext) + local ret = MIME_TYPES[ext] + if not ret then + return CONTENT_OCTET_STREAM + end + return ret + end + + -- perform a file download + function self.file_download(path) + if startswith(path, "/@") then + path = string.sub(path, 2, #path) + end + DEBUG(string.format("%u: file_download(%s)", idx, path)) + file = DYNAMIC_PAGES[path] + dynamic_page = file ~= nil + if not dynamic_page then + file = io.open(path,"rb") + if not file then + DEBUG(string.format("%u: Failed to open '%s'", idx, path)) + return false + end + end + local vars = {["Content-Type"]=self.content_type(path)} + local cgi_processing = startswith(path, "/cgi-bin/") and endswith(path, ".lua") + local server_side_processing = endswith(path, ".shtml") + local stat = fs:stat(path) + if not startswith(path, "@") and + not server_side_processing and + not cgi_processing and stat and + not dynamic_page then + local fsize = stat:size() + local mtime = stat:mtime() + vars["Content-Length"]= tostring(fsize) + local modtime = file_timestring_http(mtime) + if modtime then + vars["Last-Modified"] = modtime + end + local if_modified_since = header_vars['If-Modified-Since'] + if if_modified_since then + local tsec = file_timestring_http_parse(if_modified_since) + if tsec and tsec >= mtime then + DEBUG(string.format("%u: Not modified: %s %s", idx, modtime, if_modified_since)) + self.send_header(304, "Not Modified", vars) + return true + end + end + end + self.send_header(200, "OK", vars) + if server_side_processing or dynamic_page then + DEBUG(string.format("%u: shtml processing %s", idx, path)) + run = self.send_processed_file(dynamic_page) + elseif cgi_processing then + DEBUG(string.format("%u: CGI processing %s", idx, path)) + run = self.send_cgi + elseif stat and + WEB_SENDFILE_MIN:get() > 0 and + stat:size() >= WEB_SENDFILE_MIN:get() and + sock:sendfile(file) then + return true + else + run = self.send_file + end + return true + end + + function self.not_found() + self.send_header(404, "Not found", {}) + end + + function self.moved_permanently(relpath) + if not startswith(relpath, "/") then + relpath = "/" .. relpath + end + local location = string.format("http://%s%s", header_vars['Host'], relpath) + DEBUG(string.format("%u: Redirect -> %s", idx, location)) + self.send_header(301, "Moved Permanently", {["Location"]=location}) + end + + -- process a single request + function self.process_request() + local h1 = header_lines[1] + if not h1 or #h1 == 0 then + DEBUG(string.format("%u: empty request", idx)) + return + end + local cmd = split(header_lines[1], "%S+") + if not cmd or #cmd < 3 then + DEBUG(string.format("bad request: %s", header_lines[1])) + return + end + if cmd[1] ~= "GET" then + DEBUG(string.format("bad op: %s", cmd[1])) + return + end + protocol = cmd[3] + if protocol ~= "HTTP/1.0" and protocol ~= "HTTP/1.1" then + DEBUG(string.format("bad protocol: %s", protocol)) + return + end + local path = cmd[2] + DEBUG(string.format("%u: path='%s'", idx, path)) + + -- extract header variables + for i = 2,#header_lines do + local key, var = string.match(header_lines[i], '(.*): (.*)') + if key then + header_vars[key] = var + end + end + + if DYNAMIC_PAGES[path] ~= nil then + self.file_download(path) + return + end + + if path == MNT_PREFIX then + path = "/" + end + if startswith(path, MNT_PREFIX2) then + path = string.sub(path,#MNT_PREFIX2,#path) + end + + if isdirectory(path) and + not endswith(path,"/") and + header_vars['Host'] and + not is_hidden_dir(path) then + self.moved_permanently(path .. "/") + return + end + + if path ~= "/" and endswith(path,"/") then + path = string.sub(path, 1, #path-1) + end + + if startswith(path,"/@") then + path = string.sub(path, 2, #path) + end + + -- see if we have an index file + if isdirectory(path) and file_exists(path .. "/index.html") then + DEBUG(string.format("%u: found index.html", idx)) + if self.file_download(path .. "/index.html") then + return + end + end + + -- see if it is a directory + if (path == "/" or + DYNAMIC_PAGES[path] == nil) and + (endswith(path,"/") or + isdirectory(path) or + is_hidden_dir(path)) then + self.directory_list(path) + return + end + + -- or a file + if self.file_download(path) then + return + end + self.not_found(path) + end + + -- update the client + function self.update() + if run then + run() + return + end + if not have_header then + if not self.read_header() then + return + end + end + self.process_request() + if not run then + -- nothing more to do + self.remove() + end + end + + function self.remove() + DEBUG(string.format("%u: removing client OFFSET=%u", idx, offset)) + sock:close() + self.closed = true + end + + -- return the instance + return self +end + +--[[ + see if any new clients want to connect +--]] +local function check_new_clients() + while sock_listen:pollin(0) do + local sock = sock_listen:accept() + if not sock then + return + end + -- non-blocking for header read + sock:set_blocking(false) + -- find free client slot + for i = 1, #clients+1 do + if clients[i] == nil then + local idx = i + local client = Client(sock, idx) + DEBUG(string.format("%u: New client", idx)) + clients[idx] = client + end + end + end +end + +--[[ + check for client activity +--]] +local function check_clients() + for idx,client in ipairs(clients) do + if not client.closed then + client.update() + end + if client.closed then + table.remove(clients,idx) + end + end +end + +local function update() + check_new_clients() + check_clients() + return update,5 +end + +return update,100 From 60c69d052b2b9076f010caa039af4ca4f0adf098 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 13 Jan 2024 12:52:48 +1100 Subject: [PATCH 0500/1335] hwdef: added scripting to CubePilot-PPPGW --- .../AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/hwdef.dat | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/hwdef.dat index dfaed04510e9c3..b221026451ee35 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-PPPGW/hwdef.dat @@ -14,8 +14,20 @@ PD14 UART8_CTS UART8 SERIAL_ORDER OTG1 UART8 +undef AP_RC_CHANNEL_ENABLED +define AP_RC_CHANNEL_ENABLED 0 + define HAL_PERIPH_ENABLE_SERIAL_OPTIONS define AP_NETWORKING_BACKEND_PPP 1 define AP_PERIPH_NET_PPP_PORT_DEFAULT 1 define AP_PERIPH_NET_PPP_BAUD_DEFAULT 12500000 + +// add scripting for web interface +define AP_SCRIPTING_ENABLED 1 + +// ROMFS filesystem only +define AP_FILESYSTEM_ROMFS_ENABLED 1 + +// allow scripts to add parameters +define AP_PARAM_DYNAMIC_ENABLED 1 From c59287bf9b5127d37498dfe46bae6ff789b02495 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 13 Jan 2024 12:22:22 +1100 Subject: [PATCH 0501/1335] AP_Periph: fixed version handling in periph --- Tools/AP_Periph/version.cpp | 3 +-- Tools/AP_Periph/version.h | 17 ++++++++++++----- 2 files changed, 13 insertions(+), 7 deletions(-) diff --git a/Tools/AP_Periph/version.cpp b/Tools/AP_Periph/version.cpp index f557ce9f89ca4e..e38ffded0c65ad 100644 --- a/Tools/AP_Periph/version.cpp +++ b/Tools/AP_Periph/version.cpp @@ -1,4 +1,3 @@ #define FORCE_VERSION_H_INCLUDE #include "version.h" -#include -#undef FORCE_VERSION_H_INCLUDE \ No newline at end of file +#undef FORCE_VERSION_H_INCLUDE diff --git a/Tools/AP_Periph/version.h b/Tools/AP_Periph/version.h index 090841e1d57fdc..6166fba32d1459 100644 --- a/Tools/AP_Periph/version.h +++ b/Tools/AP_Periph/version.h @@ -1,9 +1,19 @@ #pragma once -#include +#ifndef FORCE_VERSION_H_INCLUDE +#error version.h should never be included directly. You probably want to include AP_Common/AP_FWVersion.h +#endif + +#include "ap_version.h" #define THISFIRMWARE "AP_Periph V1.7.0-dev" +// defines needed due to lack of GCS includes +#define FIRMWARE_VERSION_TYPE_DEV 0 +#define FIRMWARE_VERSION_TYPE_BETA 255 +#define FIRMWARE_VERSION_TYPE_OFFICIAL 255 + + // the following line is parsed by the autotest scripts #define FIRMWARE_VERSION 1,7,0,FIRMWARE_VERSION_TYPE_DEV @@ -12,7 +22,4 @@ #define FW_PATCH 0 #define FW_TYPE FIRMWARE_VERSION_TYPE_DEV - - - - +#include From eacfd24cb982c82ff513ebfb88edf60866d7811a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 13 Jan 2024 12:27:13 +1100 Subject: [PATCH 0502/1335] AP_Scripting: document networking bindings --- libraries/AP_Scripting/docs/docs.lua | 21 +++++++++++++++++++++ 1 file changed, 21 insertions(+) diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index 00e2ee4ca174b7..05571a172ec80e 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -3367,3 +3367,24 @@ fs = {} ---@param param1 string ---@return stat_t_ud|nil function fs:stat(param1) end + +-- desc +---@class networking +networking = {} + +-- conver uint32_t address to string +---@param ip4addr uint32_t_ud +---@return string +function networking:address_to_str(ip4addr) end + +-- desc +---@return uint32_t_ud +function networking:get_gateway_active() end + +-- desc +---@return uint32_t_ud +function networking:get_netmask_active() end + +-- desc +---@return uint32_t_ud +function networking:get_ip_active() end From 2e8be66353c6545eb8e0bc00575e1c823c368217 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 13 Jan 2024 12:55:12 +1100 Subject: [PATCH 0503/1335] CI: added Pixhawk6X-PPPGW to CI builds --- .github/workflows/test_chibios.yml | 1 + Tools/scripts/build_ci.sh | 8 ++++++++ 2 files changed, 9 insertions(+) diff --git a/.github/workflows/test_chibios.yml b/.github/workflows/test_chibios.yml index f3c2861050d6ba..6fe345defd02f7 100644 --- a/.github/workflows/test_chibios.yml +++ b/.github/workflows/test_chibios.yml @@ -158,6 +158,7 @@ jobs: signing, CubeOrange-PPP, CubeOrange-SOHW, + Pixhawk6X-PPPGW, ] toolchain: [ chibios, diff --git a/Tools/scripts/build_ci.sh b/Tools/scripts/build_ci.sh index f4a8700d01ded0..84bb812a736c95 100755 --- a/Tools/scripts/build_ci.sh +++ b/Tools/scripts/build_ci.sh @@ -340,6 +340,14 @@ for t in $CI_BUILD_TARGET; do Tools/scripts/sitl-on-hardware/sitl-on-hw.py --vehicle plane --simclass Plane --board CubeOrange continue fi + + if [ "$t" == "Pixhawk6X-PPPGW" ]; then + echo "Building Pixhawk6X-PPPGW" + $waf configure --board Pixhawk6X-PPPGW + $waf clean + $waf AP_Periph + continue + fi if [ "$t" == "dds-stm32h7" ]; then echo "Building with DDS support on a STM32H7" From e0971c7d1a677e37e80041730f75db125642062b Mon Sep 17 00:00:00 2001 From: TsuyoshiKawamura Date: Sat, 13 Jan 2024 16:19:58 +0900 Subject: [PATCH 0504/1335] Tools: make target directory before linking --- Tools/environment_install/install-prereqs-mac.sh | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/environment_install/install-prereqs-mac.sh b/Tools/environment_install/install-prereqs-mac.sh index cfbf9858617225..6486b007d6452c 100755 --- a/Tools/environment_install/install-prereqs-mac.sh +++ b/Tools/environment_install/install-prereqs-mac.sh @@ -78,6 +78,7 @@ function install_arm_none_eabi_toolchain() { ) fi echo "Registering STM32 Toolchain for ccache" + sudo mkdir -p /usr/local/opt/ccache/libexec sudo ln -s -f $CCACHE_PATH /usr/local/opt/ccache/libexec/arm-none-eabi-g++ sudo ln -s -f $CCACHE_PATH /usr/local/opt/ccache/libexec/arm-none-eabi-gcc echo "Done!" From d278ed3f2c1d9d1d3e578c8390024323bfa529da Mon Sep 17 00:00:00 2001 From: Siddharth Purohit Date: Sat, 13 Jan 2024 18:35:20 +0800 Subject: [PATCH 0505/1335] Tools: add bin file when building binaries for Here4FC --- Tools/scripts/build_binaries.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/scripts/build_binaries.py b/Tools/scripts/build_binaries.py index 4d0c1c02f2bc27..6e85a9839a95ef 100755 --- a/Tools/scripts/build_binaries.py +++ b/Tools/scripts/build_binaries.py @@ -493,7 +493,7 @@ def build_vehicle(self, tag, vehicle, boards, vehicle_binaries_subdir, "".join([binaryname, framesuffix])) files_to_copy = [] extensions = [".apj", ".abin", "_with_bl.hex", ".hex"] - if vehicle == 'AP_Periph': + if vehicle == 'AP_Periph' or board == "Here4FC": # need bin file for uavcan-gui-tool and MissionPlanner extensions.append('.bin') for extension in extensions: From 5ee05b67992ee139ddd36d341e58865d9b6f4f10 Mon Sep 17 00:00:00 2001 From: Rhys Mainwaring Date: Mon, 8 Jan 2024 14:32:38 +0000 Subject: [PATCH 0506/1335] Tools: ros2: pass verbose flag to micro-ROS agent. Signed-off-by: Rhys Mainwaring --- Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py b/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py index 02c8230d5c7d9d..6578e537d8fbc7 100644 --- a/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py +++ b/Tools/ros2/ardupilot_sitl/src/ardupilot_sitl/launch.py @@ -142,6 +142,8 @@ def generate_action(context: LaunchContext, *args, **kwargs) -> ExecuteProcess: transport, "--middleware", middleware, + "--verbose", + verbose, ] if transport in ["udp4", "udp6", "tcp4", "tcp6"]: From d53807cb6ca57991c96355d73c2b7165ed71f212 Mon Sep 17 00:00:00 2001 From: AndersonRayner Date: Sat, 14 Oct 2023 16:13:37 -0700 Subject: [PATCH 0507/1335] Tools: Update sitl-on-hardware README.md to match new file paths. The sitl-on-hardware paths have changed. This updates the readme file to reflect the new file locations. --- Tools/scripts/sitl-on-hardware/README.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Tools/scripts/sitl-on-hardware/README.md b/Tools/scripts/sitl-on-hardware/README.md index 081b78c8494212..26135aac74d1c2 100644 --- a/Tools/scripts/sitl-on-hardware/README.md +++ b/Tools/scripts/sitl-on-hardware/README.md @@ -7,21 +7,21 @@ Run the sitl-on-hw.sh script to compile and flash for MatekH743. Adjust for you :: cd $HOME/ardupilot - ./libraries/SITL/examples/on-hardware/sitl-on-hw.py --board MatekH743 --vehicle copter + ./Tools/scripts/sitl-on-hardware/sitl-on-hw.py --board MatekH743 --vehicle copter Plane can also be simulated: :: cd $HOME/ardupilot - ./libraries/SITL/examples/on-hardware/sitl-on-hw.py --board MatekH743 --vehicle plane + ./Tools/scripts/sitl-on-hardware/sitl-on-hw.py --board MatekH743 --vehicle plane and quadplane: :: cd $HOME/ardupilot - ./libraries/SITL/examples/on-hardware/sitl-on-hw.py --board MatekH743 --vehicle plane --simclass QuadPlane + ./Tools/scripts/sitl-on-hardware/sitl-on-hw.py --board MatekH743 --vehicle plane --simclass QuadPlane ## Configuring From c7c2c54c2637297dceb891d26a670804ab2b717e Mon Sep 17 00:00:00 2001 From: MallikarjunSE Date: Fri, 12 Jan 2024 13:43:53 +0530 Subject: [PATCH 0508/1335] Tools: Reserve board IDs for Sierra --- Tools/AP_Bootloader/board_types.txt | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/Tools/AP_Bootloader/board_types.txt b/Tools/AP_Bootloader/board_types.txt index 4344ef812c6df0..63f3bba28ff906 100644 --- a/Tools/AP_Bootloader/board_types.txt +++ b/Tools/AP_Bootloader/board_types.txt @@ -284,6 +284,17 @@ AP_HW_AIRVOLUTE_DCS2 5200 AP_HW_AOCODA-RC-H743DUAL 5210 AP_HW_AOCODA-RC-F405V3 5211 +#IDs 5301-5399 reserved for Sierra Aerospace +AP_HW_Sierra-TrueNavPro-G4 5301 +AP_HW_Sierra-TrueNavIC 5302 +AP_HW_Sierra-TrueNorth-G4 5303 +AP_HW_Sierra-TrueSpeed-G4 5304 +AP_HW_Sierra-PrecisionPoint-G4 5305 +AP_HW_Sierra-AeroNex 5306 +AP_HW_Sierra-TrueFlow 5307 +AP_HW_Sierra-TrueNavIC-Pro 5308 +AP_HW_Sierra-F1-Pro 5309 + # IDs 6000-6099 reserved for SpektreWorks # OpenDroneID enabled boards. Use 10000 + the base board ID From f7e94bcc75999f63b2f8dd0e62f65abd434fe192 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 23:40:22 +1100 Subject: [PATCH 0509/1335] AP_AHRS: make AHRS attitude member variables private --- libraries/AP_AHRS/AP_AHRS.h | 9 +++++---- libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp | 6 +++--- 2 files changed, 8 insertions(+), 7 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index f8c87da36fd49f..abb36f2e13692b 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -548,10 +548,6 @@ class AP_AHRS { */ // roll/pitch/yaw euler angles, all in radians - float roll; - float pitch; - float yaw; - float get_roll() const { return roll; } float get_pitch() const { return pitch; } float get_yaw() const { return yaw; } @@ -681,6 +677,11 @@ class AP_AHRS { private: + // roll/pitch/yaw euler angles, all in radians + float roll; + float pitch; + float yaw; + // optional view class AP_AHRS_View *_view; diff --git a/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp b/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp index 38a4eaefa2becb..a4138916877693 100644 --- a/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp +++ b/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp @@ -84,9 +84,9 @@ void loop(void) hal.console->printf( "r:%4.1f p:%4.1f y:%4.1f " "drift=(%5.1f %5.1f %5.1f) hdg=%.1f rate=%.1f\n", - (double)ToDeg(ahrs.roll), - (double)ToDeg(ahrs.pitch), - (double)ToDeg(ahrs.yaw), + (double)ToDeg(ahrs.get_roll()), + (double)ToDeg(ahrs.get_pitch()), + (double)ToDeg(ahrs.get_yaw()), (double)ToDeg(drift.x), (double)ToDeg(drift.y), (double)ToDeg(drift.z), From cad4bd41e97f63673418bc05523b0826c50ca989 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 23:40:22 +1100 Subject: [PATCH 0510/1335] AP_Compass: make AHRS attitude member variables private --- libraries/AP_Compass/AP_Compass_Calibration.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Compass/AP_Compass_Calibration.cpp b/libraries/AP_Compass/AP_Compass_Calibration.cpp index ed8f338e549be9..d573888c77395f 100644 --- a/libraries/AP_Compass/AP_Compass_Calibration.cpp +++ b/libraries/AP_Compass/AP_Compass_Calibration.cpp @@ -538,7 +538,7 @@ MAV_RESULT Compass::mag_cal_fixed_yaw(float yaw_deg, uint8_t compass_mask, field = R * field; Matrix3f dcm; - dcm.from_euler(AP::ahrs().roll, AP::ahrs().pitch, radians(yaw_deg)); + dcm.from_euler(AP::ahrs().get_roll(), AP::ahrs().get_pitch(), radians(yaw_deg)); // Rotate into body frame using provided yaw field = dcm.transposed() * field; From a81b229997735250e4c09fc18d4008edb6132ef9 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 23:40:22 +1100 Subject: [PATCH 0511/1335] AP_InertialSensor: make AHRS attitude member variables private --- libraries/AP_InertialSensor/AP_InertialSensor.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index e8bfb60eaed66d..4d4480e43f3501 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -1340,7 +1340,7 @@ bool AP_InertialSensor::_calculate_trim(const Vector3f &accel_sample, Vector3f & if (view != nullptr) { // Use pitch to guess which axis the user is trying to trim // 5 deg buffer to favor normal AHRS and avoid floating point funny business - if (fabsf(view->pitch) < (fabsf(AP::ahrs().pitch)+radians(5)) ) { + if (fabsf(view->pitch) < (fabsf(AP::ahrs().get_pitch())+radians(5)) ) { // user is trying to calibrate view rotation = view->get_rotation(); if (!is_zero(view->get_pitch_trim())) { From 91fbe46466afa86fdad24a5d593a869753debf02 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 23:40:22 +1100 Subject: [PATCH 0512/1335] AP_L1_Control: make AHRS attitude member variables private --- libraries/AP_L1_Control/AP_L1_Control.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/libraries/AP_L1_Control/AP_L1_Control.cpp b/libraries/AP_L1_Control/AP_L1_Control.cpp index 816637af457c6f..2750c232298d0d 100644 --- a/libraries/AP_L1_Control/AP_L1_Control.cpp +++ b/libraries/AP_L1_Control/AP_L1_Control.cpp @@ -56,9 +56,9 @@ const AP_Param::GroupInfo AP_L1_Control::var_info[] = { float AP_L1_Control::get_yaw() const { if (_reverse) { - return wrap_PI(M_PI + _ahrs.yaw); + return wrap_PI(M_PI + _ahrs.get_yaw()); } - return _ahrs.yaw; + return _ahrs.get_yaw(); } /* @@ -88,7 +88,7 @@ int32_t AP_L1_Control::nav_roll_cd(void) const Made changes to avoid zero division as proposed by Andrew Tridgell: https://github.com/ArduPilot/ardupilot/pull/24331#discussion_r1267798397 */ float pitchLimL1 = radians(60); // Suggestion: constraint may be modified to pitch limits if their absolute values are less than 90 degree and more than 60 degrees. - float pitchL1 = constrain_float(_ahrs.pitch,-pitchLimL1,pitchLimL1); + float pitchL1 = constrain_float(_ahrs.get_pitch(),-pitchLimL1,pitchLimL1); ret = degrees(atanf(_latAccDem * (1.0f/(GRAVITY_MSS * cosf(pitchL1))))) * 100.0f; ret = constrain_float(ret, -9000, 9000); return ret; @@ -396,7 +396,7 @@ void AP_L1_Control::update_loiter(const Location ¢er_WP, float radius, int8_ A_air_unit = A_air.normalized(); } else { if (_groundspeed_vector.length() < 0.1f) { - A_air_unit = Vector2f(cosf(_ahrs.yaw), sinf(_ahrs.yaw)); + A_air_unit = Vector2f(cosf(_ahrs.get_yaw()), sinf(_ahrs.get_yaw())); } else { A_air_unit = _groundspeed_vector.normalized(); } @@ -504,7 +504,7 @@ void AP_L1_Control::update_level_flight(void) { // copy to _target_bearing_cd and _nav_bearing _target_bearing_cd = _ahrs.yaw_sensor; - _nav_bearing = _ahrs.yaw; + _nav_bearing = _ahrs.get_yaw(); _bearing_error = 0; _crosstrack_error = 0; From c821726bf4e7f6ef2fe7a53648e35cdbdd56c3d7 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 23:40:22 +1100 Subject: [PATCH 0513/1335] AP_Landing: make AHRS attitude member variables private --- libraries/AP_Landing/AP_Landing_Deepstall.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_Landing/AP_Landing_Deepstall.cpp b/libraries/AP_Landing/AP_Landing_Deepstall.cpp index d6f24c6ecaca82..0a690acbeb631d 100644 --- a/libraries/AP_Landing/AP_Landing_Deepstall.cpp +++ b/libraries/AP_Landing/AP_Landing_Deepstall.cpp @@ -644,7 +644,7 @@ float AP_Landing_Deepstall::update_steering() L1_xtrack_i = constrain_float(L1_xtrack_i, -0.5f, 0.5f); nu1 += L1_xtrack_i; } - desired_change = wrap_PI(radians(target_heading_deg) + nu1 - landing.ahrs.yaw) / time_constant; + desired_change = wrap_PI(radians(target_heading_deg) + nu1 - landing.ahrs.get_yaw()) / time_constant; } float yaw_rate = landing.ahrs.get_gyro().z; From 71a00dc7332e492fd2c237bf19126be8174bee71 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 23:40:22 +1100 Subject: [PATCH 0514/1335] APM_Control: make AHRS attitude member variables private --- libraries/APM_Control/AP_PitchController.cpp | 4 ++-- libraries/APM_Control/AP_YawController.cpp | 2 +- libraries/APM_Control/AR_AttitudeControl.cpp | 6 +++--- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/APM_Control/AP_PitchController.cpp b/libraries/APM_Control/AP_PitchController.cpp index 1c02fdb0a86bf9..be39a6cbdd9af6 100644 --- a/libraries/APM_Control/AP_PitchController.cpp +++ b/libraries/APM_Control/AP_PitchController.cpp @@ -273,7 +273,7 @@ float AP_PitchController::get_rate_out(float desired_rate, float scaler) float AP_PitchController::_get_coordination_rate_offset(float &aspeed, bool &inverted) const { float rate_offset; - float bank_angle = AP::ahrs().roll; + float bank_angle = AP::ahrs().get_roll(); // limit bank angle between +- 80 deg if right way up if (fabsf(bank_angle) < radians(90)) { @@ -296,7 +296,7 @@ float AP_PitchController::_get_coordination_rate_offset(float &aspeed, bool &inv // don't do turn coordination handling when at very high pitch angles rate_offset = 0; } else { - rate_offset = cosf(_ahrs.pitch)*fabsf(ToDeg((GRAVITY_MSS / MAX((aspeed * _ahrs.get_EAS2TAS()), MAX(aparm.airspeed_min, 1))) * tanf(bank_angle) * sinf(bank_angle))) * _roll_ff; + rate_offset = cosf(_ahrs.get_pitch())*fabsf(ToDeg((GRAVITY_MSS / MAX((aspeed * _ahrs.get_EAS2TAS()), MAX(aparm.airspeed_min, 1))) * tanf(bank_angle) * sinf(bank_angle))) * _roll_ff; } if (inverted) { rate_offset = -rate_offset; diff --git a/libraries/APM_Control/AP_YawController.cpp b/libraries/APM_Control/AP_YawController.cpp index f99333aca1e7e2..15f42c2fb505bd 100644 --- a/libraries/APM_Control/AP_YawController.cpp +++ b/libraries/APM_Control/AP_YawController.cpp @@ -206,7 +206,7 @@ int32_t AP_YawController::get_servo_out(float scaler, bool disable_integrator) // Calculate yaw rate required to keep up with a constant height coordinated turn float aspeed; float rate_offset; - float bank_angle = AP::ahrs().roll; + float bank_angle = AP::ahrs().get_roll(); // limit bank angle between +- 80 deg if right way up if (fabsf(bank_angle) < 1.5707964f) { bank_angle = constrain_float(bank_angle,-1.3962634f,1.3962634f); diff --git a/libraries/APM_Control/AR_AttitudeControl.cpp b/libraries/APM_Control/AR_AttitudeControl.cpp index 67f12c20e946af..c537a05868774a 100644 --- a/libraries/APM_Control/AR_AttitudeControl.cpp +++ b/libraries/APM_Control/AR_AttitudeControl.cpp @@ -613,7 +613,7 @@ float AR_AttitudeControl::get_steering_out_heading(float heading_rad, float rate // return a desired turn-rate given a desired heading in radians float AR_AttitudeControl::get_turn_rate_from_heading(float heading_rad, float rate_max_rads) const { - const float yaw_error = wrap_PI(heading_rad - AP::ahrs().yaw); + const float yaw_error = wrap_PI(heading_rad - AP::ahrs().get_yaw()); // Calculate the desired turn rate (in radians) from the angle error (also in radians) float desired_rate = _steer_angle_p.get_p(yaw_error); @@ -884,7 +884,7 @@ float AR_AttitudeControl::get_throttle_out_from_pitch(float desired_pitch, float } // initialise output to feed forward from current pitch angle - const float pitch_rad = AP::ahrs().pitch; + const float pitch_rad = AP::ahrs().get_pitch(); float output = sinf(pitch_rad) * _pitch_to_throttle_ff; // add regular PID control @@ -940,7 +940,7 @@ float AR_AttitudeControl::get_sail_out_from_heel(float desired_heel, float dt) } _heel_controller_last_ms = now; - _sailboat_heel_pid.update_all(desired_heel, fabsf(AP::ahrs().roll), dt); + _sailboat_heel_pid.update_all(desired_heel, fabsf(AP::ahrs().get_roll()), dt); // get feed-forward const float ff = _sailboat_heel_pid.get_ff(); From 49c697221afa3d44fc67ac8eec3f5f93451553fb Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 23:40:23 +1100 Subject: [PATCH 0515/1335] AP_Mount: make AHRS attitude member variables private --- libraries/AP_Mount/AP_Mount_Backend.cpp | 6 +++--- libraries/AP_Mount/AP_Mount_Servo.cpp | 4 ++-- libraries/AP_Mount/AP_Mount_Siyi.cpp | 8 ++++---- libraries/AP_Mount/AP_Mount_Viewpro.cpp | 2 +- libraries/AP_Mount/AP_Mount_Xacti.cpp | 2 +- 5 files changed, 11 insertions(+), 11 deletions(-) diff --git a/libraries/AP_Mount/AP_Mount_Backend.cpp b/libraries/AP_Mount/AP_Mount_Backend.cpp index b6080a6f22545b..e9760c7ae08e9d 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.cpp +++ b/libraries/AP_Mount/AP_Mount_Backend.cpp @@ -413,7 +413,7 @@ bool AP_Mount_Backend::handle_global_position_int(uint8_t msg_sysid, const mavli void AP_Mount_Backend::write_log(uint64_t timestamp_us) { // return immediately if no yaw estimate - float ahrs_yaw = AP::ahrs().yaw; + float ahrs_yaw = AP::ahrs().get_yaw(); if (isnan(ahrs_yaw)) { return; } @@ -734,7 +734,7 @@ float AP_Mount_Backend::MountTarget::get_bf_yaw() const { if (yaw_is_ef) { // convert to body-frame - return wrap_PI(yaw - AP::ahrs().yaw); + return wrap_PI(yaw - AP::ahrs().get_yaw()); } // target is already body-frame @@ -750,7 +750,7 @@ float AP_Mount_Backend::MountTarget::get_ef_yaw() const } // convert to earth-frame - return wrap_PI(yaw + AP::ahrs().yaw); + return wrap_PI(yaw + AP::ahrs().get_yaw()); } // sets roll, pitch, yaw and yaw_is_ef diff --git a/libraries/AP_Mount/AP_Mount_Servo.cpp b/libraries/AP_Mount/AP_Mount_Servo.cpp index 8c59eb6abfd28e..2f926c7d848a38 100644 --- a/libraries/AP_Mount/AP_Mount_Servo.cpp +++ b/libraries/AP_Mount/AP_Mount_Servo.cpp @@ -160,7 +160,7 @@ void AP_Mount_Servo::update_angle_outputs(const MountTarget& angle_rad) } // retrieve lean angles from ahrs - Vector2f ahrs_angle_rad = {ahrs.roll, ahrs.pitch}; + Vector2f ahrs_angle_rad = {ahrs.get_roll(), ahrs.get_pitch()}; // rotate ahrs roll and pitch angles to gimbal yaw if (has_pan_control()) { @@ -174,7 +174,7 @@ void AP_Mount_Servo::update_angle_outputs(const MountTarget& angle_rad) // lead filter const Vector3f &gyro = ahrs.get_gyro(); - if (!is_zero(_params.roll_stb_lead) && fabsf(ahrs.pitch) < M_PI/3.0f) { + if (!is_zero(_params.roll_stb_lead) && fabsf(ahrs.get_pitch()) < M_PI/3.0f) { // Compute rate of change of euler roll angle float roll_rate = gyro.x + (ahrs.sin_pitch() / ahrs.cos_pitch()) * (gyro.y * ahrs.sin_roll() + gyro.z * ahrs.cos_roll()); _angle_bf_output_rad.x -= roll_rate * _params.roll_stb_lead; diff --git a/libraries/AP_Mount/AP_Mount_Siyi.cpp b/libraries/AP_Mount/AP_Mount_Siyi.cpp index 2854a28c7466c5..2925e5b70e41fa 100644 --- a/libraries/AP_Mount/AP_Mount_Siyi.cpp +++ b/libraries/AP_Mount/AP_Mount_Siyi.cpp @@ -709,7 +709,7 @@ void AP_Mount_Siyi::send_target_angles(float pitch_rad, float yaw_rad, bool yaw_ const float pitch_rate_scalar = constrain_float(100.0 * pitch_err_rad * AP_MOUNT_SIYI_PITCH_P / AP_MOUNT_SIYI_RATE_MAX_RADS, -100, 100); // convert yaw angle to body-frame - float yaw_bf_rad = yaw_is_ef ? wrap_PI(yaw_rad - AP::ahrs().yaw) : yaw_rad; + float yaw_bf_rad = yaw_is_ef ? wrap_PI(yaw_rad - AP::ahrs().get_yaw()) : yaw_rad; // enforce body-frame yaw angle limits. If beyond limits always use body-frame control const float yaw_bf_min = radians(_params.yaw_angle_min); @@ -1127,9 +1127,9 @@ void AP_Mount_Siyi::send_attitude(void) const uint32_t now_ms = AP_HAL::millis(); attitude.time_boot_ms = now_ms; - attitude.roll = ahrs.roll; - attitude.pitch = ahrs.pitch; - attitude.yaw = ahrs.yaw; + attitude.roll = ahrs.get_roll(); + attitude.pitch = ahrs.get_pitch(); + attitude.yaw = ahrs.get_yaw(); attitude.rollspeed = gyro.x; attitude.pitchspeed = gyro.y; attitude.yawspeed = gyro.z; diff --git a/libraries/AP_Mount/AP_Mount_Viewpro.cpp b/libraries/AP_Mount/AP_Mount_Viewpro.cpp index a1180f85e3e58e..03dc19504261e1 100644 --- a/libraries/AP_Mount/AP_Mount_Viewpro.cpp +++ b/libraries/AP_Mount/AP_Mount_Viewpro.cpp @@ -544,7 +544,7 @@ bool AP_Mount_Viewpro::send_target_angles(float pitch_rad, float yaw_rad, bool y } // convert yaw angle to body-frame - float yaw_bf_rad = yaw_is_ef ? wrap_PI(yaw_rad - AP::ahrs().yaw) : yaw_rad; + float yaw_bf_rad = yaw_is_ef ? wrap_PI(yaw_rad - AP::ahrs().get_yaw()) : yaw_rad; // enforce body-frame yaw angle limits. If beyond limits always use body-frame control const float yaw_bf_min = radians(_params.yaw_angle_min); diff --git a/libraries/AP_Mount/AP_Mount_Xacti.cpp b/libraries/AP_Mount/AP_Mount_Xacti.cpp index adc752fd46947c..239d416455abcd 100644 --- a/libraries/AP_Mount/AP_Mount_Xacti.cpp +++ b/libraries/AP_Mount/AP_Mount_Xacti.cpp @@ -379,7 +379,7 @@ void AP_Mount_Xacti::send_target_rates(float pitch_rads, float yaw_rads, bool ya void AP_Mount_Xacti::send_target_angles(float pitch_rad, float yaw_rad, bool yaw_is_ef) { // convert yaw to body frame - const float yaw_bf_rad = yaw_is_ef ? wrap_PI(yaw_rad - AP::ahrs().yaw) : yaw_rad; + const float yaw_bf_rad = yaw_is_ef ? wrap_PI(yaw_rad - AP::ahrs().get_yaw()) : yaw_rad; // send angle target to gimbal send_gimbal_control(2, degrees(pitch_rad) * 100, degrees(yaw_bf_rad) * 100); From 49bc553cda5e93509cdd0684265b9f29a8c542a6 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 23:40:23 +1100 Subject: [PATCH 0516/1335] AP_OSD: make AHRS attitude member variables private --- libraries/AP_OSD/AP_OSD_Screen.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_OSD/AP_OSD_Screen.cpp b/libraries/AP_OSD/AP_OSD_Screen.cpp index c63a481417b3d7..53cb8ce8e50f1f 100644 --- a/libraries/AP_OSD/AP_OSD_Screen.cpp +++ b/libraries/AP_OSD/AP_OSD_Screen.cpp @@ -1571,7 +1571,7 @@ void AP_OSD_Screen::draw_gspeed(uint8_t x, uint8_t y) float angle = 0; const float length = v.length(); if (length > 1.0f) { - angle = atan2f(v.y, v.x) - ahrs.yaw; + angle = atan2f(v.y, v.x) - ahrs.get_yaw(); } draw_speed(x + 1, y, angle, length); } @@ -1822,7 +1822,7 @@ void AP_OSD_Screen::draw_wind(uint8_t x, uint8_t y) if (check_option(AP_OSD::OPTION_INVERTED_WIND)) { angle = M_PI; } - angle = angle + atan2f(v.y, v.x) - ahrs.yaw; + angle = angle + atan2f(v.y, v.x) - ahrs.get_yaw(); } draw_speed(x + 1, y, angle, length); From 57b1ab3ad96d131cd9c60f49f3dd4dac659fd4d4 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 23:40:23 +1100 Subject: [PATCH 0517/1335] AP_RCTelemetry: make AHRS attitude member variables private --- libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp b/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp index 43f68c4c6a13f5..30e16b6d0a8f46 100644 --- a/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp +++ b/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp @@ -931,9 +931,9 @@ void AP_CRSF_Telem::calc_attitude() const int16_t INT_PI = 31415; // units are radians * 10000 - _telem.bcast.attitude.roll_angle = htobe16(constrain_int16(roundf(wrap_PI(_ahrs.roll) * 10000.0f), -INT_PI, INT_PI)); - _telem.bcast.attitude.pitch_angle = htobe16(constrain_int16(roundf(wrap_PI(_ahrs.pitch) * 10000.0f), -INT_PI, INT_PI)); - _telem.bcast.attitude.yaw_angle = htobe16(constrain_int16(roundf(wrap_PI(_ahrs.yaw) * 10000.0f), -INT_PI, INT_PI)); + _telem.bcast.attitude.roll_angle = htobe16(constrain_int16(roundf(wrap_PI(_ahrs.get_roll()) * 10000.0f), -INT_PI, INT_PI)); + _telem.bcast.attitude.pitch_angle = htobe16(constrain_int16(roundf(wrap_PI(_ahrs.get_pitch()) * 10000.0f), -INT_PI, INT_PI)); + _telem.bcast.attitude.yaw_angle = htobe16(constrain_int16(roundf(wrap_PI(_ahrs.get_yaw()) * 10000.0f), -INT_PI, INT_PI)); _telem_size = sizeof(AP_CRSF_Telem::AttitudeFrame); _telem_type = AP_RCProtocol_CRSF::CRSF_FRAMETYPE_ATTITUDE; From ba68d0fcbe8742594a404d73f9be7fe9f7fa5d09 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 23:40:23 +1100 Subject: [PATCH 0518/1335] AP_Soaring: make AHRS attitude member variables private --- libraries/AP_Soaring/AP_Soaring.cpp | 4 ++-- libraries/AP_Soaring/Variometer.cpp | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Soaring/AP_Soaring.cpp b/libraries/AP_Soaring/AP_Soaring.cpp index 53e61652848043..47279b5d7b5149 100644 --- a/libraries/AP_Soaring/AP_Soaring.cpp +++ b/libraries/AP_Soaring/AP_Soaring.cpp @@ -280,8 +280,8 @@ void SoaringController::init_thermalling() // New state vector filter will be reset. Thermal location is placed in front of a/c const float init_xr[4] = {_vario.get_trigger_value(), INITIAL_THERMAL_RADIUS, - position.x + thermal_distance_ahead * cosf(_ahrs.yaw), - position.y + thermal_distance_ahead * sinf(_ahrs.yaw)}; + position.x + thermal_distance_ahead * cosf(_ahrs.get_yaw()), + position.y + thermal_distance_ahead * sinf(_ahrs.get_yaw())}; const VectorN xr{init_xr}; diff --git a/libraries/AP_Soaring/Variometer.cpp b/libraries/AP_Soaring/Variometer.cpp index a7a59f789e1623..835e32ea71d0a3 100644 --- a/libraries/AP_Soaring/Variometer.cpp +++ b/libraries/AP_Soaring/Variometer.cpp @@ -62,7 +62,7 @@ void Variometer::update(const float thermal_bank) float smoothed_climb_rate = _climb_filter.apply(raw_climb_rate, dt); // Compute still-air sinkrate - float roll = _ahrs.roll; + float roll = _ahrs.get_roll(); float sinkrate = calculate_aircraft_sinkrate(roll); reading = raw_climb_rate + dsp_cor*_aspd_filt_constrained/GRAVITY_MSS + sinkrate; From 7f43facb37a22391d4f582affe703d19fe104372 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 23:40:23 +1100 Subject: [PATCH 0519/1335] AP_TECS: make AHRS attitude member variables private --- libraries/AP_TECS/AP_TECS.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/AP_TECS/AP_TECS.cpp b/libraries/AP_TECS/AP_TECS.cpp index 48f848c8320781..7ca36846257b06 100644 --- a/libraries/AP_TECS/AP_TECS.cpp +++ b/libraries/AP_TECS/AP_TECS.cpp @@ -856,7 +856,7 @@ void AP_TECS::_update_throttle_without_airspeed(int16_t throttle_nudge) // so that the throttle mapping adjusts for the effect of pitch control errors _pitch_demand_lpf.apply(_pitch_dem, _DT); const float pitch_demand_hpf = _pitch_dem - _pitch_demand_lpf.get(); - _pitch_measured_lpf.apply(_ahrs.pitch, _DT); + _pitch_measured_lpf.apply(_ahrs.get_pitch(), _DT); const float pitch_corrected_lpf = _pitch_measured_lpf.get() - radians(0.01f * (float)aparm.pitch_trim_cd); const float pitch_blended = pitch_demand_hpf + pitch_corrected_lpf; @@ -1107,7 +1107,7 @@ void AP_TECS::_initialise_states(int32_t ptchMinCO_cd, float hgt_afe) _integSEBdot = 0.0f; _integKE = 0.0f; _last_throttle_dem = aparm.throttle_cruise * 0.01f; - _last_pitch_dem = _ahrs.pitch; + _last_pitch_dem = _ahrs.get_pitch(); _hgt_afe = hgt_afe; _hgt_dem_in_prev = hgt_afe; _hgt_dem_lpf = hgt_afe; @@ -1138,8 +1138,8 @@ void AP_TECS::_initialise_states(int32_t ptchMinCO_cd, float hgt_afe) const float fc = 1.0f / (M_2PI * _timeConst); _pitch_demand_lpf.set_cutoff_frequency(fc); _pitch_measured_lpf.set_cutoff_frequency(fc); - _pitch_demand_lpf.reset(_ahrs.pitch); - _pitch_measured_lpf.reset(_ahrs.pitch); + _pitch_demand_lpf.reset(_ahrs.get_pitch()); + _pitch_measured_lpf.reset(_ahrs.get_pitch()); } else if (_flight_stage == AP_FixedWing::FlightStage::TAKEOFF || _flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING) { _PITCHminf = 0.000174533f * ptchMinCO_cd; @@ -1159,8 +1159,8 @@ void AP_TECS::_initialise_states(int32_t ptchMinCO_cd, float hgt_afe) _max_climb_scaler = 1.0f; _max_sink_scaler = 1.0f; - _pitch_demand_lpf.reset(_ahrs.pitch); - _pitch_measured_lpf.reset(_ahrs.pitch); + _pitch_demand_lpf.reset(_ahrs.get_pitch()); + _pitch_measured_lpf.reset(_ahrs.get_pitch()); } if (_flight_stage != AP_FixedWing::FlightStage::TAKEOFF && _flight_stage != AP_FixedWing::FlightStage::ABORT_LANDING) { From 118332826672238cbebd1209ab2e1d86aa15be07 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 23:40:23 +1100 Subject: [PATCH 0520/1335] AP_Vehicle: make AHRS attitude member variables private --- libraries/AP_Vehicle/AP_Vehicle.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Vehicle/AP_Vehicle.cpp b/libraries/AP_Vehicle/AP_Vehicle.cpp index 2833a39fc293b1..c94a4c2ee1b5a0 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.cpp +++ b/libraries/AP_Vehicle/AP_Vehicle.cpp @@ -879,8 +879,8 @@ void AP_Vehicle::publish_osd_info() void AP_Vehicle::get_osd_roll_pitch_rad(float &roll, float &pitch) const { - roll = ahrs.roll; - pitch = ahrs.pitch; + roll = ahrs.get_roll(); + pitch = ahrs.get_pitch(); } #if HAL_INS_ACCELCAL_ENABLED From c4dc0ae1014875bb498cf1be12d0a50feee51e4c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 23:40:23 +1100 Subject: [PATCH 0521/1335] AP_WindVane: make AHRS attitude member variables private --- libraries/AP_WindVane/AP_WindVane.cpp | 8 ++++---- libraries/AP_WindVane/AP_WindVane_Home.cpp | 2 +- libraries/AP_WindVane/AP_WindVane_SITL.cpp | 2 +- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/AP_WindVane/AP_WindVane.cpp b/libraries/AP_WindVane/AP_WindVane.cpp index 3b3cb718352426..44845d4d469e87 100644 --- a/libraries/AP_WindVane/AP_WindVane.cpp +++ b/libraries/AP_WindVane/AP_WindVane.cpp @@ -321,7 +321,7 @@ void AP_WindVane::update() } } else { // only have direction, can't do true wind calcs, set true direction to apparent + heading - _direction_true_raw = wrap_PI(_direction_apparent_raw + AP::ahrs().yaw); + _direction_true_raw = wrap_PI(_direction_apparent_raw + AP::ahrs().get_yaw()); _speed_true_raw = 0.0f; } @@ -395,7 +395,7 @@ void AP_WindVane::update() void AP_WindVane::record_home_heading() { - _home_heading = AP::ahrs().yaw; + _home_heading = AP::ahrs().get_yaw(); } // to start direction calibration from mavlink or other @@ -454,7 +454,7 @@ void AP_WindVane::update_true_wind_speed_and_direction() } // convert apparent wind speed and direction to 2D vector in same frame as vehicle velocity - const float wind_dir_180 = _direction_apparent_raw + AP::ahrs().yaw + radians(180); + const float wind_dir_180 = _direction_apparent_raw + AP::ahrs().get_yaw() + radians(180); const Vector2f wind_apparent_vec(cosf(wind_dir_180) * _speed_apparent, sinf(wind_dir_180) * _speed_apparent); // add vehicle velocity @@ -482,7 +482,7 @@ void AP_WindVane::update_apparent_wind_dir_from_true() Vector2f wind_apparent_vec = Vector2f(wind_true_vec.x - veh_velocity.x, wind_true_vec.y - veh_velocity.y); // calculate apartment speed and direction - _direction_apparent_raw = wrap_PI(atan2f(wind_apparent_vec.y, wind_apparent_vec.x) - radians(180) - AP::ahrs().yaw); + _direction_apparent_raw = wrap_PI(atan2f(wind_apparent_vec.y, wind_apparent_vec.x) - radians(180) - AP::ahrs().get_yaw()); _speed_apparent_raw = wind_apparent_vec.length(); } diff --git a/libraries/AP_WindVane/AP_WindVane_Home.cpp b/libraries/AP_WindVane/AP_WindVane_Home.cpp index c291fb75dc8455..3271f6c1808c0c 100644 --- a/libraries/AP_WindVane/AP_WindVane_Home.cpp +++ b/libraries/AP_WindVane/AP_WindVane_Home.cpp @@ -32,7 +32,7 @@ void AP_WindVane_Home::update_direction() } } - _frontend._direction_apparent_raw = wrap_PI(direction_apparent_ef - AP::ahrs().yaw); + _frontend._direction_apparent_raw = wrap_PI(direction_apparent_ef - AP::ahrs().get_yaw()); } #endif // AP_WINDVANE_HOME_ENABLED diff --git a/libraries/AP_WindVane/AP_WindVane_SITL.cpp b/libraries/AP_WindVane/AP_WindVane_SITL.cpp index 061e42158eee41..8fb24172df71eb 100644 --- a/libraries/AP_WindVane/AP_WindVane_SITL.cpp +++ b/libraries/AP_WindVane/AP_WindVane_SITL.cpp @@ -41,7 +41,7 @@ void AP_WindVane_SITL::update_direction() wind_vector_ef.x += AP::sitl()->state.speedN; wind_vector_ef.y += AP::sitl()->state.speedE; - _frontend._direction_apparent_raw = wrap_PI(atan2f(wind_vector_ef.y, wind_vector_ef.x) - AP::ahrs().yaw); + _frontend._direction_apparent_raw = wrap_PI(atan2f(wind_vector_ef.y, wind_vector_ef.x) - AP::ahrs().get_yaw()); } else { // WINDVANE_SITL_APARRENT // directly read the body frame apparent wind set by physics backend From caf1e33f179dd4197e5723bc660a81ed6b400419 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 23:40:24 +1100 Subject: [PATCH 0522/1335] GCS_MAVLink: make AHRS attitude member variables private --- libraries/GCS_MAVLink/GCS_Common.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 913e9fe47b2b40..63e2424eb9539d 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -5443,9 +5443,9 @@ void GCS_MAVLINK::send_attitude() const mavlink_msg_attitude_send( chan, AP_HAL::millis(), - ahrs.roll, - ahrs.pitch, - ahrs.yaw, + ahrs.get_roll(), + ahrs.get_pitch(), + ahrs.get_yaw(), omega.x, omega.y, omega.z); From b3897c020efb4297226f80d8226e239efb32496c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 23:40:24 +1100 Subject: [PATCH 0523/1335] ArduPlane: make AHRS attitude member variables private --- ArduPlane/ArduPlane.cpp | 4 ++-- ArduPlane/GCS_Mavlink.cpp | 6 +++--- ArduPlane/commands_logic.cpp | 2 +- ArduPlane/mode_cruise.cpp | 2 +- ArduPlane/mode_guided.cpp | 2 +- ArduPlane/mode_takeoff.cpp | 2 +- ArduPlane/quadplane.cpp | 4 ++-- 7 files changed, 11 insertions(+), 11 deletions(-) diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 02dcd401eb2dda..dd6af0ab6e30bc 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -916,8 +916,8 @@ void Plane::get_osd_roll_pitch_rad(float &roll, float &pitch) const return; } #endif - pitch = ahrs.pitch; - roll = ahrs.roll; + pitch = ahrs.get_pitch(); + roll = ahrs.get_roll(); if (!(flight_option_enabled(FlightOptions::OSD_REMOVE_TRIM_PITCH_CD))) { // correct for TRIM_PITCH_CD pitch -= g.pitch_trim_cd * 0.01 * DEG_TO_RAD; } diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 3715776f77ab64..9a571e3b5e0ce9 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -129,9 +129,9 @@ void GCS_MAVLINK_Plane::send_attitude() const { const AP_AHRS &ahrs = AP::ahrs(); - float r = ahrs.roll; - float p = ahrs.pitch; - float y = ahrs.yaw; + float r = ahrs.get_roll(); + float p = ahrs.get_pitch(); + float y = ahrs.get_yaw(); if (!(plane.flight_option_enabled(FlightOptions::GCS_REMOVE_TRIM_PITCH_CD))) { p -= radians(plane.g.pitch_trim_cd * 0.01f); diff --git a/ArduPlane/commands_logic.cpp b/ArduPlane/commands_logic.cpp index 439c03d80a05e3..972da6f765c8e3 100644 --- a/ArduPlane/commands_logic.cpp +++ b/ArduPlane/commands_logic.cpp @@ -1090,7 +1090,7 @@ bool Plane::verify_landing_vtol_approach(const AP_Mission::Mission_Command &cmd) const float breakout_direction_rad = radians(vtol_approach_s.approach_direction_deg + (direction > 0 ? 270 : 90)); // breakout when within 5 degrees of the opposite direction - if (fabsF(wrap_PI(ahrs.yaw - breakout_direction_rad)) < radians(5.0f)) { + if (fabsF(wrap_PI(ahrs.get_yaw() - breakout_direction_rad)) < radians(5.0f)) { gcs().send_text(MAV_SEVERITY_INFO, "Starting VTOL land approach path"); vtol_approach_s.approach_stage = APPROACH_LINE; set_next_WP(cmd.content.location); diff --git a/ArduPlane/mode_cruise.cpp b/ArduPlane/mode_cruise.cpp index 2d8c4c428c2424..3e16928f15bcab 100644 --- a/ArduPlane/mode_cruise.cpp +++ b/ArduPlane/mode_cruise.cpp @@ -61,7 +61,7 @@ void ModeCruise::navigate() // check if we are moving in the direction of the front of the vehicle const int32_t ground_course_cd = plane.gps.ground_course_cd(); - const bool moving_forwards = fabsf(wrap_PI(radians(ground_course_cd * 0.01) - plane.ahrs.yaw)) < M_PI_2; + const bool moving_forwards = fabsf(wrap_PI(radians(ground_course_cd * 0.01) - plane.ahrs.get_yaw())) < M_PI_2; if (!locked_heading && plane.channel_roll->get_control_in() == 0 && diff --git a/ArduPlane/mode_guided.cpp b/ArduPlane/mode_guided.cpp index a523ddf87065ed..b4ae1241e757f6 100644 --- a/ArduPlane/mode_guided.cpp +++ b/ArduPlane/mode_guided.cpp @@ -52,7 +52,7 @@ void ModeGuided::update() float error = 0.0f; if (plane.guided_state.target_heading_type == GUIDED_HEADING_HEADING) { - error = wrap_PI(plane.guided_state.target_heading - AP::ahrs().yaw); + error = wrap_PI(plane.guided_state.target_heading - AP::ahrs().get_yaw()); } else { Vector2f groundspeed = AP::ahrs().groundspeed_vector(); error = wrap_PI(plane.guided_state.target_heading - atan2f(-groundspeed.y, -groundspeed.x) + M_PI); diff --git a/ArduPlane/mode_takeoff.cpp b/ArduPlane/mode_takeoff.cpp index c303d459b27ff3..b807c64777ec00 100644 --- a/ArduPlane/mode_takeoff.cpp +++ b/ArduPlane/mode_takeoff.cpp @@ -81,7 +81,7 @@ void ModeTakeoff::update() const float dist = target_dist; if (!takeoff_started) { const uint16_t altitude = plane.relative_ground_altitude(false,true); - const float direction = degrees(ahrs.yaw); + const float direction = degrees(ahrs.get_yaw()); // see if we will skip takeoff as already flying if (plane.is_flying() && (millis() - plane.started_flying_ms > 10000U) && ahrs.groundspeed() > 3) { if (altitude >= alt) { diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 06e18814c5a59a..25c7ff533ba2a2 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -2636,7 +2636,7 @@ void QuadPlane::vtol_position_controller(void) target_speed_xy_cms = diff_wp_norm * target_speed * 100; target_accel_cms = diff_wp_norm * (-target_accel*100); target_yaw_deg = degrees(diff_wp_norm.angle()); - const float yaw_err_deg = wrap_180(target_yaw_deg - degrees(plane.ahrs.yaw)); + const float yaw_err_deg = wrap_180(target_yaw_deg - degrees(plane.ahrs.get_yaw())); bool overshoot = (closing_groundspeed < 0 || fabsf(yaw_err_deg) > 60); if (overshoot && !poscontrol.overshoot) { gcs().send_text(MAV_SEVERITY_INFO,"VTOL Overshoot d=%.1f cs=%.1f yerr=%.1f", @@ -3046,7 +3046,7 @@ void QuadPlane::assign_tilt_to_fwd_thr(void) { */ float QuadPlane::get_scaled_wp_speed(float target_bearing_deg) const { - const float yaw_difference = fabsf(wrap_180(degrees(plane.ahrs.yaw) - target_bearing_deg)); + const float yaw_difference = fabsf(wrap_180(degrees(plane.ahrs.get_yaw()) - target_bearing_deg)); const float wp_speed = wp_nav->get_default_speed_xy() * 0.01; if (yaw_difference > 20) { // this gives a factor of 2x reduction in max speed when From 027549404248df6fd75cbd8b45ed460419d4e65d Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 23:40:24 +1100 Subject: [PATCH 0524/1335] ArduSub: make AHRS attitude member variables private --- ArduSub/turn_counter.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduSub/turn_counter.cpp b/ArduSub/turn_counter.cpp index f2260aa12e47f8..52df84fecb7486 100644 --- a/ArduSub/turn_counter.cpp +++ b/ArduSub/turn_counter.cpp @@ -8,11 +8,11 @@ void Sub::update_turn_counter() // Determine state // 0: 0-90 deg, 1: 90-180 deg, 2: -180--90 deg, 3: -90--0 deg uint8_t turn_state; - if (ahrs.yaw >= 0.0f && ahrs.yaw < radians(90)) { + if (ahrs.get_yaw() >= 0.0f && ahrs.get_yaw() < radians(90)) { turn_state = 0; - } else if (ahrs.yaw > radians(90)) { + } else if (ahrs.get_yaw() > radians(90)) { turn_state = 1; - } else if (ahrs.yaw < -radians(90)) { + } else if (ahrs.get_yaw() < -radians(90)) { turn_state = 2; } else { turn_state = 3; From bcf6578d56717588c2fe44e29d2f814fd563e361 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 13 Jan 2024 01:02:12 +1100 Subject: [PATCH 0525/1335] AP_Module: make AHRS attitude member variables private --- libraries/AP_Module/AP_Module.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Module/AP_Module.cpp b/libraries/AP_Module/AP_Module.cpp index 6d740ecce59a83..3bad1d59ef852c 100644 --- a/libraries/AP_Module/AP_Module.cpp +++ b/libraries/AP_Module/AP_Module.cpp @@ -165,9 +165,9 @@ void AP_Module::call_hook_AHRS_update(const AP_AHRS &ahrs) state.quat[2] = q[2]; state.quat[3] = q[3]; - state.eulers[0] = ahrs.roll; - state.eulers[1] = ahrs.pitch; - state.eulers[2] = ahrs.yaw; + state.eulers[0] = ahrs.get_roll(); + state.eulers[1] = ahrs.get_pitch(); + state.eulers[2] = ahrs.get_yaw(); Location loc; if (ahrs.get_origin(loc)) { From 6ca3f3114382f74288d422b758d7873c8c6ed3c7 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 13 Jan 2024 01:02:12 +1100 Subject: [PATCH 0526/1335] Rover: make AHRS attitude member variables private --- Rover/crash_check.cpp | 2 +- Rover/mode.cpp | 2 +- Rover/mode_circle.cpp | 4 ++-- Rover/sailboat.cpp | 8 ++++---- 4 files changed, 8 insertions(+), 8 deletions(-) diff --git a/Rover/crash_check.cpp b/Rover/crash_check.cpp index 284c125a4b9533..feafdf7f6f6ef7 100644 --- a/Rover/crash_check.cpp +++ b/Rover/crash_check.cpp @@ -20,7 +20,7 @@ void Rover::crash_check() } // Crashed if pitch/roll > crash_angle - if ((g2.crash_angle != 0) && ((fabsf(ahrs.pitch) > radians(g2.crash_angle)) || (fabsf(ahrs.roll) > radians(g2.crash_angle)))) { + if ((g2.crash_angle != 0) && ((fabsf(ahrs.get_pitch()) > radians(g2.crash_angle)) || (fabsf(ahrs.get_roll()) > radians(g2.crash_angle)))) { crashed = true; } diff --git a/Rover/mode.cpp b/Rover/mode.cpp index 842789c1006698..6173ac337dcdbe 100644 --- a/Rover/mode.cpp +++ b/Rover/mode.cpp @@ -290,7 +290,7 @@ void Mode::calc_throttle(float target_speed, bool avoidance_enabled) // apply object avoidance to desired speed using half vehicle's maximum deceleration if (avoidance_enabled) { - g2.avoid.adjust_speed(0.0f, 0.5f * attitude_control.get_decel_max(), ahrs.yaw, target_speed, rover.G_Dt); + g2.avoid.adjust_speed(0.0f, 0.5f * attitude_control.get_decel_max(), ahrs.get_yaw(), target_speed, rover.G_Dt); if (g2.sailboat.tack_enabled() && g2.avoid.limits_active()) { // we are a sailboat trying to avoid fence, try a tack if (rover.control_mode != &rover.mode_acro) { diff --git a/Rover/mode_circle.cpp b/Rover/mode_circle.cpp index 42d6f63833b79b..86ba7dbdae1193 100644 --- a/Rover/mode_circle.cpp +++ b/Rover/mode_circle.cpp @@ -116,7 +116,7 @@ void ModeCircle::init_target_yaw_rad() // if no position estimate use vehicle yaw Vector2f curr_pos_NE; if (!AP::ahrs().get_relative_position_NE_origin(curr_pos_NE)) { - target.yaw_rad = AP::ahrs().yaw; + target.yaw_rad = AP::ahrs().get_yaw(); return; } @@ -126,7 +126,7 @@ void ModeCircle::init_target_yaw_rad() // if current position is exactly at the center of the circle return vehicle yaw if (is_zero(dist_m)) { - target.yaw_rad = AP::ahrs().yaw; + target.yaw_rad = AP::ahrs().get_yaw(); } else { target.yaw_rad = center_to_veh.angle(); } diff --git a/Rover/sailboat.cpp b/Rover/sailboat.cpp index c547a9cb1fa36c..23f72e8a56af24 100644 --- a/Rover/sailboat.cpp +++ b/Rover/sailboat.cpp @@ -329,7 +329,7 @@ float Sailboat::get_VMG() const return speed; } - return (speed * cosf(wrap_PI(radians(rover.g2.wp_nav.wp_bearing_cd() * 0.01f) - rover.ahrs.yaw))); + return (speed * cosf(wrap_PI(radians(rover.g2.wp_nav.wp_bearing_cd() * 0.01f) - rover.ahrs.get_yaw()))); } // handle user initiated tack while in acro mode @@ -340,7 +340,7 @@ void Sailboat::handle_tack_request_acro() } // set tacking heading target to the current angle relative to the true wind but on the new tack currently_tacking = true; - tack_heading_rad = wrap_2PI(rover.ahrs.yaw + 2.0f * wrap_PI((rover.g2.windvane.get_true_wind_direction_rad() - rover.ahrs.yaw))); + tack_heading_rad = wrap_2PI(rover.ahrs.get_yaw() + 2.0f * wrap_PI((rover.g2.windvane.get_true_wind_direction_rad() - rover.ahrs.get_yaw()))); tack_request_ms = AP_HAL::millis(); } @@ -348,7 +348,7 @@ void Sailboat::handle_tack_request_acro() // return target heading in radians when tacking (only used in acro) float Sailboat::get_tack_heading_rad() { - if (fabsf(wrap_PI(tack_heading_rad - rover.ahrs.yaw)) < radians(SAILBOAT_TACKING_ACCURACY_DEG) || + if (fabsf(wrap_PI(tack_heading_rad - rover.ahrs.get_yaw())) < radians(SAILBOAT_TACKING_ACCURACY_DEG) || ((AP_HAL::millis() - tack_request_ms) > SAILBOAT_AUTO_TACKING_TIMEOUT_MS)) { clear_tack(); } @@ -494,7 +494,7 @@ float Sailboat::calc_heading(float desired_heading_cd) // if we are tacking we maintain the target heading until the tack completes or times out if (currently_tacking) { // check if we have reached target - if (fabsf(wrap_PI(tack_heading_rad - rover.ahrs.yaw)) <= radians(SAILBOAT_TACKING_ACCURACY_DEG)) { + if (fabsf(wrap_PI(tack_heading_rad - rover.ahrs.get_yaw())) <= radians(SAILBOAT_TACKING_ACCURACY_DEG)) { clear_tack(); } else if ((now - auto_tack_start_ms) > SAILBOAT_AUTO_TACKING_TIMEOUT_MS) { // tack has taken too long From 30146affa5911cd842bfaa4c00e066366a953035 Mon Sep 17 00:00:00 2001 From: Maxim Buzdalov Date: Sun, 14 Jan 2024 19:33:15 +0000 Subject: [PATCH 0527/1335] AP_ESC_Telem: Log RPM and raw RPM values as floats --- libraries/AP_ESC_Telem/AP_ESC_Telem.cpp | 10 +++++----- libraries/AP_ESC_Telem/LogStructure.h | 6 +++--- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp index 5fbaba7ae6dc5a..7bb347220d0c0b 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp @@ -502,12 +502,12 @@ void AP_ESC_Telem::update() float rpm = 0.0f; get_rpm(i, rpm); - float rawrpm = 0.0f; - get_raw_rpm(i, rawrpm); + float raw_rpm = 0.0f; + get_raw_rpm(i, raw_rpm); // Write ESC status messages // id starts from 0 - // rpm is eRPM (rpm * 100) + // rpm, raw_rpm is eRPM (in RPM units) // voltage is in Volt // current is in Ampere // esc_temp is in centi-degrees Celsius @@ -518,8 +518,8 @@ void AP_ESC_Telem::update() LOG_PACKET_HEADER_INIT(uint8_t(LOG_ESC_MSG)), time_us : AP_HAL::micros64(), instance : i, - rpm : (int32_t) rpm * 100, - raw_rpm : (int32_t) rawrpm * 100, + rpm : rpm, + raw_rpm : raw_rpm, voltage : _telem_data[i].voltage, current : _telem_data[i].current, esc_temp : _telem_data[i].temperature_cdeg, diff --git a/libraries/AP_ESC_Telem/LogStructure.h b/libraries/AP_ESC_Telem/LogStructure.h index 89d0578875e39a..a3c0dc791cd3df 100644 --- a/libraries/AP_ESC_Telem/LogStructure.h +++ b/libraries/AP_ESC_Telem/LogStructure.h @@ -21,8 +21,8 @@ struct PACKED log_Esc { LOG_PACKET_HEADER; uint64_t time_us; uint8_t instance; - int32_t rpm; - int32_t raw_rpm; + float rpm; + float raw_rpm; float voltage; float current; int16_t esc_temp; @@ -33,4 +33,4 @@ struct PACKED log_Esc { #define LOG_STRUCTURE_FROM_ESC_TELEM \ { LOG_ESC_MSG, sizeof(log_Esc), \ - "ESC", "QBeeffcfcf", "TimeUS,Instance,RPM,RawRPM,Volt,Curr,Temp,CTot,MotTemp,Err", "s#qqvAOaO%", "F-BB--BCB-" , true }, + "ESC", "QBffffcfcf", "TimeUS,Instance,RPM,RawRPM,Volt,Curr,Temp,CTot,MotTemp,Err", "s#qqvAOaO%", "F-00--BCB-" , true }, From 79eeb7b46162d948a93b7a20de162f78243bc0d0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 16:49:52 +1100 Subject: [PATCH 0528/1335] Blimp: correct compilation when fence compiled out --- Blimp/AP_Arming.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/Blimp/AP_Arming.cpp b/Blimp/AP_Arming.cpp index 23ba7790f9a175..adbc072e4bf834 100644 --- a/Blimp/AP_Arming.cpp +++ b/Blimp/AP_Arming.cpp @@ -29,8 +29,10 @@ bool AP_Arming_Blimp::run_pre_arm_checks(bool display_failure) return mandatory_checks(display_failure); } - return fence_checks(display_failure) - & parameter_checks(display_failure) + return parameter_checks(display_failure) +#if AP_FENCE_ENABLED + & fence_checks(display_failure) +#endif & motor_checks(display_failure) & gcs_failsafe_check(display_failure) & alt_checks(display_failure) From 7898d6f107d1fa3ac2010d8c14152fc42a4f0fcb Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 17:29:46 +1100 Subject: [PATCH 0529/1335] AP_ExternalAHRS: correct compilation when baro and compass externalahrs disabled --- libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp index ebf844f32493bf..9019eaef461f01 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp @@ -466,13 +466,17 @@ bool AP_ExternalAHRS_InertialLabs::check_uart() last_gps_ms = now_ms; } } +#if AP_BARO_EXTERNALAHRS_ENABLED if (GOT_MSG(BARO_DATA) && GOT_MSG(TEMPERATURE)) { AP::baro().handle_external(baro_data); } +#endif + #if AP_COMPASS_EXTERNALAHRS_ENABLED if (GOT_MSG(MAG_DATA)) { AP::compass().handle_external(mag_data); } +#endif #if AP_AIRSPEED_EXTERNAL_ENABLED && (APM_BUILD_COPTER_OR_HELI || APM_BUILD_TYPE(APM_BUILD_ArduPlane)) // only on plane and copter as others do not link AP_Airspeed if (GOT_MSG(DIFFERENTIAL_PRESSURE) && From f72245785484d790b0ee62bb2479ec4c074b946b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 20:41:03 +1100 Subject: [PATCH 0530/1335] AP_ExternalAHRS: correct compilation with MicroStrain5 disabled --- libraries/AP_ExternalAHRS/AP_ExternalAHRS_config.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_config.h b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_config.h index 0119e6857eceac..75e8e5228021bb 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_config.h +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_config.h @@ -19,7 +19,7 @@ #endif #ifndef AP_MICROSTRAIN_ENABLED -#define AP_MICROSTRAIN_ENABLED AP_EXTERNAL_AHRS_MICROSTRAIN5_ENABLED +#define AP_MICROSTRAIN_ENABLED AP_EXTERNAL_AHRS_MICROSTRAIN5_ENABLED || AP_EXTERNAL_AHRS_MICROSTRAIN7_ENABLED #endif #ifndef AP_EXTERNAL_AHRS_VECTORNAV_ENABLED From fe30a93602fa6e097d033c70e72374a32c0d1c27 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 13 Jan 2024 13:50:16 +1100 Subject: [PATCH 0531/1335] build_options.py: correct entries for Ghost telem protocol --- Tools/scripts/build_options.py | 2 +- Tools/scripts/extract_features.py | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/Tools/scripts/build_options.py b/Tools/scripts/build_options.py index dd632f33d0f7c7..6a8de5da742a18 100644 --- a/Tools/scripts/build_options.py +++ b/Tools/scripts/build_options.py @@ -72,7 +72,7 @@ def __init__(self, Feature('Telemetry', 'FrSky D', 'AP_FRSKY_D_TELEM_ENABLED', 'Enable FrSkyD Telemetry', 0, 'FrSky'), Feature('Telemetry', 'FrSky SPort', 'AP_FRSKY_SPORT_TELEM_ENABLED', 'Enable FrSkySPort Telemetry', 0, 'FrSky'), # noqa Feature('Telemetry', 'FrSky SPort PassThrough', 'AP_FRSKY_SPORT_PASSTHROUGH_ENABLED', 'Enable FrSkySPort PassThrough Telemetry', 0, 'FrSky SPort,FrSky'), # noqa - Feature('Telemetry', 'GHST', 'HAL_GHST_TELEM_ENABLED', 'Enable Ghost Telemetry', 0, None), # noqa + Feature('Telemetry', 'GHST', 'AP_GHST_TELEM_ENABLED', 'Enable Ghost Telemetry', 0, None), # noqa Feature('Notify', 'PLAY_TUNE', 'AP_NOTIFY_MAVLINK_PLAY_TUNE_SUPPORT_ENABLED', 'Enable MAVLink Play Tune', 0, None), # noqa Feature('Notify', 'TONEALARM', 'AP_NOTIFY_TONEALARM_ENABLED', 'Enable ToneAlarm on PWM', 0, None), # noqa diff --git a/Tools/scripts/extract_features.py b/Tools/scripts/extract_features.py index 8fe5436843064d..7977fabfa36440 100755 --- a/Tools/scripts/extract_features.py +++ b/Tools/scripts/extract_features.py @@ -110,6 +110,7 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"): ('HAL_MOUNT_STORM32MAVLINK_ENABLED', 'AP_Mount_SToRM32::init',), ('HAL_{type}_TELEM_ENABLED', r'AP_(?P.*)_Telem::init',), + ('AP_{type}_TELEM_ENABLED', r'AP_(?P.*)_Telem::init',), ('HAL_CRSF_TELEM_TEXT_SELECTION_ENABLED', 'AP_CRSF_Telem::calc_text_selection',), ('AP_LTM_TELEM_ENABLED', 'AP_LTM_Telem::init',), ('HAL_HIGH_LATENCY2_ENABLED', 'GCS_MAVLINK::handle_control_high_latency',), From 4f56691f05fd09790c9f830a625917e13de2643c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 13 Jan 2024 23:07:39 +1100 Subject: [PATCH 0532/1335] AP_Relay: correct compilation when many features removed --- libraries/AP_Relay/AP_Relay.cpp | 17 +++++++++-------- 1 file changed, 9 insertions(+), 8 deletions(-) diff --git a/libraries/AP_Relay/AP_Relay.cpp b/libraries/AP_Relay/AP_Relay.cpp index 7225c6c3d30e03..3b70fcb5d18010 100644 --- a/libraries/AP_Relay/AP_Relay.cpp +++ b/libraries/AP_Relay/AP_Relay.cpp @@ -202,29 +202,30 @@ void AP_Relay::convert_params() // Dont need this conversion on periph as relay support is more recent // Before converting local params we must find any relays being used by index from external libs - int8_t relay_index; - int8_t ice_relay = -1; #if AP_ICENGINE_ENABLED AP_ICEngine *ice = AP::ice(); - if (ice != nullptr && ice->get_legacy_ignition_relay_index(relay_index)) { - ice_relay = relay_index; + int8_t ice_relay_index; + if (ice != nullptr && ice->get_legacy_ignition_relay_index(ice_relay_index)) { + ice_relay = ice_relay_index; } #endif int8_t chute_relay = -1; #if HAL_PARACHUTE_ENABLED AP_Parachute *parachute = AP::parachute(); - if (parachute != nullptr && parachute->get_legacy_relay_index(relay_index)) { - chute_relay = relay_index; + int8_t parachute_relay_index; + if (parachute != nullptr && parachute->get_legacy_relay_index(parachute_relay_index)) { + chute_relay = parachute_relay_index; } #endif int8_t cam_relay = -1; #if AP_CAMERA_ENABLED AP_Camera *camera = AP::camera(); - if ((camera != nullptr) && (camera->get_legacy_relay_index(relay_index))) { - cam_relay = relay_index; + int8_t camera_relay_index; + if ((camera != nullptr) && (camera->get_legacy_relay_index(camera_relay_index))) { + cam_relay = camera_relay_index; } #endif From 2ca8cc572c94f8e173d7b100386bee92f4441268 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 14 Jan 2024 17:10:20 +1100 Subject: [PATCH 0533/1335] Tools: build_options.py: Ghost telem requires ghost RC --- Tools/scripts/build_options.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/scripts/build_options.py b/Tools/scripts/build_options.py index 6a8de5da742a18..5fcd74bb75b0c3 100644 --- a/Tools/scripts/build_options.py +++ b/Tools/scripts/build_options.py @@ -72,7 +72,7 @@ def __init__(self, Feature('Telemetry', 'FrSky D', 'AP_FRSKY_D_TELEM_ENABLED', 'Enable FrSkyD Telemetry', 0, 'FrSky'), Feature('Telemetry', 'FrSky SPort', 'AP_FRSKY_SPORT_TELEM_ENABLED', 'Enable FrSkySPort Telemetry', 0, 'FrSky'), # noqa Feature('Telemetry', 'FrSky SPort PassThrough', 'AP_FRSKY_SPORT_PASSTHROUGH_ENABLED', 'Enable FrSkySPort PassThrough Telemetry', 0, 'FrSky SPort,FrSky'), # noqa - Feature('Telemetry', 'GHST', 'AP_GHST_TELEM_ENABLED', 'Enable Ghost Telemetry', 0, None), # noqa + Feature('Telemetry', 'GHST', 'AP_GHST_TELEM_ENABLED', 'Enable Ghost Telemetry', 0, "RC_GHST"), # noqa Feature('Notify', 'PLAY_TUNE', 'AP_NOTIFY_MAVLINK_PLAY_TUNE_SUPPORT_ENABLED', 'Enable MAVLink Play Tune', 0, None), # noqa Feature('Notify', 'TONEALARM', 'AP_NOTIFY_TONEALARM_ENABLED', 'Enable ToneAlarm on PWM', 0, None), # noqa From ad90e37f214553c540e1a5f5749205531c86f67c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 11 Jan 2024 13:44:36 +1100 Subject: [PATCH 0534/1335] hwdef: remove bad AP_PERIPH_HAVE_LED lines from bootloaders this define is only used within the AP_Periph directory --- libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef-bl.dat | 2 -- libraries/AP_HAL_ChibiOS/hwdef/Here4FC/hwdef-bl.dat | 2 -- libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef-bl.dat | 2 -- 3 files changed, 6 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef-bl.dat index d94c02e9142b35..e3e6dca8be5ea1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Here4AP/hwdef-bl.dat @@ -50,8 +50,6 @@ define HAL_NO_MONITOR_THREAD PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD -define AP_PERIPH_HAVE_LED - # order of UARTs SERIAL_ORDER define HAL_USE_UART FALSE diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Here4FC/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Here4FC/hwdef-bl.dat index 0236dbff1c3a1e..8c302244adfb3b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Here4FC/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Here4FC/hwdef-bl.dat @@ -51,8 +51,6 @@ define HAL_NO_MONITOR_THREAD PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD -define AP_PERIPH_HAVE_LED - define CAN_APP_NODE_NAME "com.cubepilot.here4fc" PB6 USART1_TX USART1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef-bl.dat index d1d9f2bae5a491..5f8cffae714cd1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HerePro/hwdef-bl.dat @@ -65,8 +65,6 @@ define HAL_DEVICE_THREAD_STACK 2048 define HAL_BARO_ALLOW_INIT_NO_BARO -define AP_PERIPH_HAVE_LED - define HAL_COMPASS_MAX_SENSORS 1 # GPS+MAG From d4f59cbe5f2358a44f3f1d9716f013569de4d24e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 11 Jan 2024 13:57:23 +1100 Subject: [PATCH 0535/1335] hwdef: remove HAL_NO_LOGGING from Here4FC-bl.dat this was removed from master a long time ago --- libraries/AP_HAL_ChibiOS/hwdef/Here4FC/hwdef-bl.dat | 1 - 1 file changed, 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/Here4FC/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/Here4FC/hwdef-bl.dat index 8c302244adfb3b..b83fa886e228f1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/Here4FC/hwdef-bl.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/Here4FC/hwdef-bl.dat @@ -45,7 +45,6 @@ STM32_VDD 330U PB8 LED_SCK OUTPUT LOW PB9 LED_DI OUTPUT HIGH -define HAL_NO_LOGGING TRUE define HAL_NO_MONITOR_THREAD PA13 JTMS-SWDIO SWD From 7cf66d917c80622fd7ced353fd7a8954f9636355 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 15 Jan 2024 13:39:14 +1100 Subject: [PATCH 0536/1335] hwdef: correct compilation of revo-mini-sd this isn't built on the firmware server, so we won't notice when it dies In this case the SMBUS batter define was being set differently Also remove some redundant defines which come from includes anyway --- libraries/AP_HAL_ChibiOS/hwdef/revo-mini-sd/hwdef.dat | 6 ------ 1 file changed, 6 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/revo-mini-sd/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/revo-mini-sd/hwdef.dat index ce593b2d0efc29..8f1cc5d398adf4 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/revo-mini-sd/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/revo-mini-sd/hwdef.dat @@ -17,12 +17,8 @@ undef HAL_LOGGING_DATAFLASH_ENABLED # filesystem setup on sdcard define HAL_OS_FATFS_IO 1 -# disable SMBUS monitors to save flash -define AP_BATTERY_SMBUS_ENABLED 0 - # disable parachute and sprayer to save flash define HAL_PARACHUTE_ENABLED 0 -define HAL_SPRAYER_ENABLED 0 # reduce max size of embedded params for apj_tool.py define AP_PARAM_MAX_EMBEDDED_PARAM 1024 @@ -30,5 +26,3 @@ define HAL_GYROFFT_ENABLED 0 # save some flash include ../include/save_some_flash.inc - -define AP_GRIPPER_ENABLED 0 From d0e7039b684a991ecbe08624ab04388f75e6ae43 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 15 Jan 2024 13:28:22 +1100 Subject: [PATCH 0537/1335] hwdef: remove un-needed AP_PARAM_MAX_EMBEDDED_PARAM default these boards have <= 1024, and we have code in place which defaults this value tto 1024 --- libraries/AP_HAL_ChibiOS/hwdef/HEEWING-F405/hwdef.dat | 2 -- libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-GSF405A/hwdef.dat | 2 -- libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat | 3 --- libraries/AP_HAL_ChibiOS/hwdef/KakuteF7Mini/hwdef.dat | 3 --- libraries/AP_HAL_ChibiOS/hwdef/MatekF405-CAN/hwdef.dat | 5 ----- libraries/AP_HAL_ChibiOS/hwdef/MatekF405-TE/hwdef.dat | 2 -- libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing/hwdef.dat | 2 -- libraries/AP_HAL_ChibiOS/hwdef/MatekF405/hwdef.dat | 3 --- libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/hwdef.dat | 2 -- libraries/AP_HAL_ChibiOS/hwdef/SuccexF4/hwdef.dat | 3 --- libraries/AP_HAL_ChibiOS/hwdef/VRUBrain-v51/hwdef.dat | 2 -- libraries/AP_HAL_ChibiOS/hwdef/omnibusf4pro/hwdef.dat | 3 --- libraries/AP_HAL_ChibiOS/hwdef/revo-mini-sd/hwdef.dat | 2 -- 13 files changed, 34 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/HEEWING-F405/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/HEEWING-F405/hwdef.dat index 086240a0f809e9..ea20a6af98b863 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/HEEWING-F405/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/HEEWING-F405/hwdef.dat @@ -157,8 +157,6 @@ define HAL_BATT_CURR_SCALE 26.7 #define BOARD_RSSI_ANA_PIN 8 #define HAL_DEFAULT_AIRSPEED_PIN 10 -# reduce max size of embedded params for apj_tool.py -define AP_PARAM_MAX_EMBEDDED_PARAM 1024 define HAL_WITH_DSP FALSE define HAL_GYROFFT_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-GSF405A/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-GSF405A/hwdef.dat index 85ee746142daea..d1e3894302df9c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-GSF405A/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/JHEMCU-GSF405A/hwdef.dat @@ -149,8 +149,6 @@ define HAL_OSD_TYPE_DEFAULT 1 # Font for OSD ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin -# -------reduce max size of embedded params for apj_tool.py -define AP_PARAM_MAX_EMBEDDED_PARAM 1024 define HAL_GYROFFT_ENABLED 0 # --------------------- save flash ---------------------- diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat index 4c8b7c627e6643..ad7c9ee0344ded 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7/hwdef.dat @@ -164,6 +164,3 @@ define HAL_MSP_ENABLED 1 # need to probe external baros even 'though we're minimised: undef AP_BARO_PROBE_EXTERNAL_I2C_BUSES define AP_BARO_PROBE_EXTERNAL_I2C_BUSES 1 - -# reduce max size of embedded params for apj_tool.py -define AP_PARAM_MAX_EMBEDDED_PARAM 1024 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7Mini/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7Mini/hwdef.dat index 561fc3011616a4..21f6b672626e0c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7Mini/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteF7Mini/hwdef.dat @@ -156,9 +156,6 @@ define STM32_PWM_USE_ADVANCED TRUE define HAL_PARACHUTE_ENABLED 0 define HAL_SPRAYER_ENABLED 0 -# reduce max size of embedded params for apj_tool.py -define AP_PARAM_MAX_EMBEDDED_PARAM 1024 - define HAL_MOUNT_ENABLED 0 # save some flash diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-CAN/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-CAN/hwdef.dat index 78cd31eaaaf3d4..ad148e79bf6622 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-CAN/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-CAN/hwdef.dat @@ -170,9 +170,4 @@ undef AP_BATTERY_SMBUS_ENABLED define AP_BATTERY_SMBUS_ENABLED 0 define HAL_PARACHUTE_ENABLED 0 -# reduce max size of embedded params for apj_tool.py -define AP_PARAM_MAX_EMBEDDED_PARAM 1024 - - - define DEFAULT_NTF_LED_TYPES 487 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-TE/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-TE/hwdef.dat index a69d9a94cf9ca6..ca85f8defc52cc 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-TE/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-TE/hwdef.dat @@ -170,8 +170,6 @@ define HAL_BATT_CURR_SCALE 66.7 define BOARD_RSSI_ANA_PIN 8 define HAL_DEFAULT_AIRSPEED_PIN 10 -# -------reduce max size of embedded params for apj_tool.py -define AP_PARAM_MAX_EMBEDDED_PARAM 1024 define HAL_GYROFFT_ENABLED 0 # --------------------- save flash ---------------------- diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing/hwdef.dat index 089fd07fdfebdc..9c942c302b9d98 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405-Wing/hwdef.dat @@ -182,8 +182,6 @@ ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin define STM32_PWM_USE_ADVANCED TRUE -# reduce max size of embedded params for apj_tool.py -define AP_PARAM_MAX_EMBEDDED_PARAM 1024 define HAL_GYROFFT_ENABLED 0 # save some flash diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405/hwdef.dat index effd88691850e2..650d1f960be605 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekF405/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekF405/hwdef.dat @@ -160,9 +160,6 @@ ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin define HAL_PARACHUTE_ENABLED 0 define HAL_SPRAYER_ENABLED 0 -# reduce max size of embedded params for apj_tool.py -define AP_PARAM_MAX_EMBEDDED_PARAM 1024 - # save some flash include ../include/save_some_flash.inc include ../include/minimize_fpv_osd.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/hwdef.dat index 1ddcd7c9eb8aa9..f6052add8b9772 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/SpeedyBeeF405WING/hwdef.dat @@ -169,8 +169,6 @@ PC13 PINIO1 OUTPUT GPIO(81) LOW define STM32_PWM_USE_ADVANCED TRUE -# reduce max size of embedded params for apj_tool.py -define AP_PARAM_MAX_EMBEDDED_PARAM 1024 define HAL_WITH_DSP FALSE # save some flash diff --git a/libraries/AP_HAL_ChibiOS/hwdef/SuccexF4/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/SuccexF4/hwdef.dat index e5a1777c032cca..69124a38f631f3 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/SuccexF4/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/SuccexF4/hwdef.dat @@ -128,9 +128,6 @@ ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin define HAL_PARACHUTE_ENABLED 0 define HAL_SPRAYER_ENABLED 0 -# reduce max size of embedded params for apj_tool.py -define AP_PARAM_MAX_EMBEDDED_PARAM 1024 - # minimal drivers to reduce flash usage include ../include/minimize_fpv_osd.inc include ../include/no_bootloader_DFU.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/VRUBrain-v51/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/VRUBrain-v51/hwdef.dat index f5e2451e2d4538..6cb3544f3ccedb 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/VRUBrain-v51/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/VRUBrain-v51/hwdef.dat @@ -136,8 +136,6 @@ FLASH_RESERVE_START_KB 64 # enable RAMTROM parameter storage #define HAL_WITH_RAMTRON 1 -define AP_PARAM_MAX_EMBEDDED_PARAM 1024 - # enable FAT filesystem define HAL_OS_FATFS_IO 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4pro/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4pro/hwdef.dat index d3ed1d6f221517..0c7f94e691e3bc 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4pro/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/omnibusf4pro/hwdef.dat @@ -154,9 +154,6 @@ ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin define HAL_PARACHUTE_ENABLED 0 define HAL_SPRAYER_ENABLED 0 -# reduce max size of embedded params for apj_tool.py -define AP_PARAM_MAX_EMBEDDED_PARAM 1024 - # save some flash include ../include/save_some_flash.inc diff --git a/libraries/AP_HAL_ChibiOS/hwdef/revo-mini-sd/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/revo-mini-sd/hwdef.dat index 8f1cc5d398adf4..28432ba816d6e9 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/revo-mini-sd/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/revo-mini-sd/hwdef.dat @@ -20,8 +20,6 @@ define HAL_OS_FATFS_IO 1 # disable parachute and sprayer to save flash define HAL_PARACHUTE_ENABLED 0 -# reduce max size of embedded params for apj_tool.py -define AP_PARAM_MAX_EMBEDDED_PARAM 1024 define HAL_GYROFFT_ENABLED 0 # save some flash From 6ecb8ce0230bed67575bbbd62c63bc77cd4deea6 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 11 Jan 2024 17:51:06 +1100 Subject: [PATCH 0538/1335] AP_Relay: add missing SITL include was being satisfied transitively --- libraries/AP_Relay/AP_Relay.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_Relay/AP_Relay.cpp b/libraries/AP_Relay/AP_Relay.cpp index 3b70fcb5d18010..47d2b030b8031b 100644 --- a/libraries/AP_Relay/AP_Relay.cpp +++ b/libraries/AP_Relay/AP_Relay.cpp @@ -29,6 +29,10 @@ #include #endif +#if AP_SIM_ENABLED +#include +#endif + #if CONFIG_HAL_BOARD == HAL_BOARD_SITL #define RELAY1_PIN_DEFAULT 13 From 38a9960b31e4ac4d68e90ce892fe6455642a359f Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 11 Jan 2024 20:37:43 +1100 Subject: [PATCH 0539/1335] AP_Periph: add missing include for AP_RTC shouldn't be instantiating one of these without directly including the header. Was being included transitively --- Tools/AP_Periph/AP_Periph.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Tools/AP_Periph/AP_Periph.h b/Tools/AP_Periph/AP_Periph.h index 488f05cc0c025c..9d4328b0ddeb6b 100644 --- a/Tools/AP_Periph/AP_Periph.h +++ b/Tools/AP_Periph/AP_Periph.h @@ -32,6 +32,9 @@ #if HAL_WITH_ESC_TELEM #include #endif +#ifdef HAL_PERIPH_ENABLE_RTC +#include +#endif #include #include "rc_in.h" #include "batt_balance.h" From fb1209ff3c40551ec91e84fe6b6346e10825054a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 11 Jan 2024 22:08:57 +1100 Subject: [PATCH 0540/1335] AP_Periph: add missing AP_AHRS include --- Tools/AP_Periph/AP_Periph.h | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/AP_Periph/AP_Periph.h b/Tools/AP_Periph/AP_Periph.h index 9d4328b0ddeb6b..d0e0c279be8ffc 100644 --- a/Tools/AP_Periph/AP_Periph.h +++ b/Tools/AP_Periph/AP_Periph.h @@ -43,6 +43,7 @@ #if AP_SIM_ENABLED #include #endif +#include #ifdef HAL_PERIPH_ENABLE_RELAY #ifdef HAL_PERIPH_ENABLE_PWM_HARDPOINT From 5f5673b58fc4ddb407bf521c23345e66b08e0740 Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Mon, 15 Jan 2024 14:16:23 -0600 Subject: [PATCH 0541/1335] AP_HAL_ChibiOS: match thread stack pointer types to ChibiOS `__main_thread_stack_base__` and `__main_thread_stack_end__` are variables whose address is defined to be the corresponding part of the stack. These are declared as `extern stkalign_t` in ChibiOS code, and being declared as `extern uint32_t` in ArduPilot code creates a warning at link time when using LTO. Correct the declaration to eliminate this warning. Also update `__main_stack_base__` and `__main_stack_end__` which don't currently trigger this warning but serve similar purposes and so might in the future. The hardware expects an alignment of `stkalign_t` (which is 8 bytes) and the linker script defines the variable values with this alignment as well, so this is safe. No code size or functional change. --- libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h index 5a24edd59fe97c..828ceed09ca69a 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/stm32_util.h @@ -186,10 +186,10 @@ void stm32_flash_protect_flash(bool bootloader, bool protect); void stm32_flash_unprotect_flash(void); // allow stack view code to show free ISR stack -extern uint32_t __main_stack_base__; -extern uint32_t __main_stack_end__; -extern uint32_t __main_thread_stack_base__; -extern uint32_t __main_thread_stack_end__; +extern stkalign_t __main_stack_base__; +extern stkalign_t __main_stack_end__; +extern stkalign_t __main_thread_stack_base__; +extern stkalign_t __main_thread_stack_end__; #ifdef __cplusplus } From d554ade7cea7c43f54c46f30032b1779c140b229 Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Mon, 15 Jan 2024 14:32:17 -0600 Subject: [PATCH 0542/1335] AP_IOMCU: match thread stack pointer types to ChibiOS `__main_thread_stack_base__` and `__main_thread_stack_end__` are variables whose address is defined to be the corresponding part of the stack. These are declared as `extern stkalign_t` in ChibiOS code, and being declared as `extern uint32_t` in ArduPilot code creates a warning at link time when using LTO. Correct the declaration to eliminate this warning. Also update `__main_stack_base__` and `__main_stack_end__` which don't currently trigger this warning but serve similar purposes and so might in the future. The hardware expects an alignment of `stkalign_t` (which is 8 bytes) and the linker script defines the variable values with this alignment as well, so this is safe. No code size or functional change. --- libraries/AP_IOMCU/iofirmware/iofirmware.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_IOMCU/iofirmware/iofirmware.cpp b/libraries/AP_IOMCU/iofirmware/iofirmware.cpp index 2b1e65d145a1ab..6e97fa4cf2714f 100644 --- a/libraries/AP_IOMCU/iofirmware/iofirmware.cpp +++ b/libraries/AP_IOMCU/iofirmware/iofirmware.cpp @@ -341,8 +341,8 @@ void AP_IOMCU_FW::init() #if CH_DBG_ENABLE_STACK_CHECK == TRUE static void stackCheck(uint16_t& mstack, uint16_t& pstack) { - extern uint32_t __main_stack_base__[]; - extern uint32_t __main_stack_end__[]; + extern stkalign_t __main_stack_base__[]; + extern stkalign_t __main_stack_end__[]; uint32_t stklimit = (uint32_t)__main_stack_end__; uint32_t stkbase = (uint32_t)__main_stack_base__; uint32_t *crawl = (uint32_t *)stkbase; @@ -354,8 +354,8 @@ static void stackCheck(uint16_t& mstack, uint16_t& pstack) { chDbgAssert(free > 0, "mstack exhausted"); mstack = (uint16_t)free; - extern uint32_t __main_thread_stack_base__[]; - extern uint32_t __main_thread_stack_end__[]; + extern stkalign_t __main_thread_stack_base__[]; + extern stkalign_t __main_thread_stack_end__[]; stklimit = (uint32_t)__main_thread_stack_end__; stkbase = (uint32_t)__main_thread_stack_base__; crawl = (uint32_t *)stkbase; From f7365556d0ec681ba1d7a8a683e3469c7d2a843a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 11 Jan 2024 14:10:40 +1100 Subject: [PATCH 0543/1335] AP_HAL_ChibiOS: tidy disabling of GHST on iomcu --- libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_iofirmware.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_iofirmware.h b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_iofirmware.h index 269610f5543523..8c441c3397cedc 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_iofirmware.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_iofirmware.h @@ -35,6 +35,9 @@ // no crossfire telemetry from iomcu! #define HAL_CRSF_TELEM_ENABLED 0 +// no ghost telemtry from IOMCU: +#define AP_GHST_TELEM_ENABLED 0 + // allow the IOMCU to have its allowed protocols to be set: #define AP_RCPROTOCOL_ENABLE_SET_RC_PROTOCOLS 1 From 61c4e4750a848333ecf2d9b3941fab20506fea3e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 11 Jan 2024 14:10:40 +1100 Subject: [PATCH 0544/1335] AP_RCProtocol: tidy disabling of GHST on iomcu --- libraries/AP_RCProtocol/AP_RCProtocol_GHST.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_GHST.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_GHST.cpp index 195e56bfb91641..9a8a68f871383f 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_GHST.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_GHST.cpp @@ -358,7 +358,7 @@ bool AP_RCProtocol_GHST::process_telemetry(bool check_constraint) } if (!telem_available) { -#if AP_GHST_TELEM_ENABLED && !APM_BUILD_TYPE(APM_BUILD_iofirmware) +#if AP_GHST_TELEM_ENABLED if (AP_GHST_Telem::get_telem_data(&_telemetry_frame, is_tx_active())) { telem_available = true; } else { From 2e23fa7612952498c4d8f8e25cf4c092c2e812a9 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 11 Jan 2024 14:12:08 +1100 Subject: [PATCH 0545/1335] hwdef: remove ghost telemetry from peripherals --- libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h index e0b0f894a666a9..e7f32d724f475e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/defaults_periph.h @@ -147,6 +147,7 @@ #endif #define HAL_CRSF_TELEM_ENABLED 0 +#define AP_GHST_TELEM_ENABLED 0 #ifndef AP_SERVORELAYEVENTS_ENABLED #define AP_SERVORELAYEVENTS_ENABLED 0 From 3e955d12fa35543161ea21da8ba5f1b4a9ae8c2b Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 22 Dec 2023 16:07:45 +0000 Subject: [PATCH 0546/1335] Plane: Quadaplane: add helper `allow_forward_throttle_in_vtol_mode` --- ArduPlane/quadplane.cpp | 6 ++++++ ArduPlane/quadplane.h | 5 +++++ ArduPlane/servos.cpp | 6 ++---- 3 files changed, 13 insertions(+), 4 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 25c7ff533ba2a2..4a372fc15ffc62 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -4742,4 +4742,10 @@ float QuadPlane::get_throttle_input() const return ret; } +// return true if forward throttle from forward_throttle_pct() should be used +bool QuadPlane::allow_forward_throttle_in_vtol_mode() const +{ + return in_vtol_mode() && motors->armed() && (motors->get_desired_spool_state() != AP_Motors::DesiredSpoolState::SHUT_DOWN); +} + #endif // HAL_QUADPLANE_ENABLED diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index 2c5a624ff4a4e4..140c47e585aa79 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -729,6 +729,11 @@ class QuadPlane */ void setup_rp_fw_angle_gains(void); + /* + return true if forward throttle from forward_throttle_pct() should be used + */ + bool allow_forward_throttle_in_vtol_mode() const; + public: void motor_test_output(); MAV_RESULT mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_seq, uint8_t throttle_type, diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index c8f03bb8968486..d77ed1a1723079 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -591,10 +591,8 @@ void Plane::set_throttle(void) #if HAL_QUADPLANE_ENABLED } else if (quadplane.in_vtol_mode()) { float fwd_thr = 0; - // if armed and not spooled down ask quadplane code for forward throttle - if (quadplane.motors->armed() && - quadplane.motors->get_desired_spool_state() != AP_Motors::DesiredSpoolState::SHUT_DOWN) { - + // if enabled ask quadplane code for forward throttle + if (quadplane.allow_forward_throttle_in_vtol_mode()) { fwd_thr = constrain_float(quadplane.forward_throttle_pct(), min_throttle, max_throttle); } SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, fwd_thr); From 17fb9455a9ce091b15ce00f5e58f1123ab5a0623 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 22 Dec 2023 16:09:42 +0000 Subject: [PATCH 0547/1335] Plane: `set_throttle` add early return for disarmed and throttle suppression --- ArduPlane/servos.cpp | 13 ++++++++++--- 1 file changed, 10 insertions(+), 3 deletions(-) diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index d77ed1a1723079..65b5260079f217 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -551,7 +551,10 @@ void Plane::set_throttle(void) SRV_Channels::set_output_limit(SRV_Channel::k_throttleLeft, SRV_Channel::Limit::ZERO_PWM); SRV_Channels::set_output_limit(SRV_Channel::k_throttleRight, SRV_Channel::Limit::ZERO_PWM); } - } else if (suppress_throttle()) { + return; + } + + if (suppress_throttle()) { if (g.throttle_suppress_manual) { // manual pass through of throttle while throttle is suppressed SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, get_throttle_input(true)); @@ -565,11 +568,15 @@ void Plane::set_throttle(void) SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0); } + return; + } + #if AP_SCRIPTING_ENABLED - } else if (nav_scripting_active()) { + if (nav_scripting_active()) { SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, plane.nav_scripting.throttle_pct); + } else #endif - } else if (control_mode == &mode_stabilize || + if (control_mode == &mode_stabilize || control_mode == &mode_training || control_mode == &mode_acro || control_mode == &mode_fbwa || From 01c8717308009bedf2ce3e72a49444b775a5417c Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 22 Dec 2023 16:18:29 +0000 Subject: [PATCH 0548/1335] Plane: ask flight mode if min/max throttle limits should be applied --- ArduPlane/Plane.h | 1 + ArduPlane/mode.cpp | 32 ++++++++++++++++++++++++++++++++ ArduPlane/mode.h | 2 ++ ArduPlane/servos.cpp | 33 ++++++++++++++++++++++++--------- 4 files changed, 59 insertions(+), 9 deletions(-) diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 8dcb90e47d8dd0..1b8e5ccea25467 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -1095,6 +1095,7 @@ class Plane : public AP_Vehicle { // servos.cpp void set_servos_idle(void); void set_servos(); + float apply_throttle_limits(float throttle_in); void set_throttle(void); void set_takeoff_expected(void); void set_servos_old_elevons(void); diff --git a/ArduPlane/mode.cpp b/ArduPlane/mode.cpp index 6eef3fb0fab389..2d97c9cb1acd7b 100644 --- a/ArduPlane/mode.cpp +++ b/ArduPlane/mode.cpp @@ -258,3 +258,35 @@ void Mode::output_rudder_and_steering(float val) SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, val); SRV_Channels::set_output_scaled(SRV_Channel::k_steering, val); } + +// true if throttle min/max limits should be applied +bool Mode::use_throttle_limits() const +{ +#if AP_SCRIPTING_ENABLED + if (plane.nav_scripting_active()) { + return false; + } +#endif + + if (this == &plane.mode_stabilize || + this == &plane.mode_training || + this == &plane.mode_acro || + this == &plane.mode_fbwa || + this == &plane.mode_autotune) { + // a manual throttle mode + return !plane.g.throttle_passthru_stabilize; + } + + if (is_guided_mode() && plane.guided_throttle_passthru) { + // manual pass through of throttle while in GUIDED + return false; + } + +#if HAL_QUADPLANE_ENABLED + if (quadplane.in_vtol_mode()) { + return quadplane.allow_forward_throttle_in_vtol_mode(); + } +#endif + + return true; +} diff --git a/ArduPlane/mode.h b/ArduPlane/mode.h index 2f745074c6f270..1de286f8667e28 100644 --- a/ArduPlane/mode.h +++ b/ArduPlane/mode.h @@ -135,6 +135,8 @@ class Mode // true if is taking virtual bool is_taking_off() const; + // true if throttle min/max limits should be applied + bool use_throttle_limits() const; protected: diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index 65b5260079f217..c04cc8dbb3e8a0 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -495,11 +495,11 @@ void Plane::throttle_watt_limiter(int8_t &min_throttle, int8_t &max_throttle) } } #endif // #if AP_BATTERY_WATT_MAX_ENABLED - + /* - setup output channels all non-manual modes + Apply min/max limits to throttle */ -void Plane::set_throttle(void) +float Plane::apply_throttle_limits(float throttle_in) { // convert 0 to 100% (or -100 to +100) into PWM int8_t min_throttle = aparm.throttle_min.get(); @@ -531,7 +531,6 @@ void Plane::set_throttle(void) } // compensate for battery voltage drop - g2.fwd_batt_cmp.update(); g2.fwd_batt_cmp.apply_min_max(min_throttle, max_throttle); #if AP_BATTERY_WATT_MAX_ENABLED @@ -539,6 +538,15 @@ void Plane::set_throttle(void) throttle_watt_limiter(min_throttle, max_throttle); #endif + return constrain_float(throttle_in, min_throttle, max_throttle); +} + +/* + setup output channels all non-manual modes + */ +void Plane::set_throttle(void) +{ + if (!arming.is_armed_and_safety_off()) { // Always set 0 scaled even if overriding to zero pwm. // This ensures slew limits and other functions using the scaled value pick up in the correct place @@ -571,6 +579,9 @@ void Plane::set_throttle(void) return; } + // Update voltage scaling + g2.fwd_batt_cmp.update(); + #if AP_SCRIPTING_ENABLED if (nav_scripting_active()) { SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, plane.nav_scripting.throttle_pct); @@ -588,8 +599,7 @@ void Plane::set_throttle(void) SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, get_throttle_input(true)); } else { // get throttle, but adjust center to output TRIM_THROTTLE if flight option set - SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, - constrain_int16(get_adjusted_throttle_input(true), min_throttle, max_throttle)); + SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, get_adjusted_throttle_input(true)); } } else if (control_mode->is_guided_mode() && guided_throttle_passthru) { @@ -600,17 +610,22 @@ void Plane::set_throttle(void) float fwd_thr = 0; // if enabled ask quadplane code for forward throttle if (quadplane.allow_forward_throttle_in_vtol_mode()) { - fwd_thr = constrain_float(quadplane.forward_throttle_pct(), min_throttle, max_throttle); + fwd_thr = quadplane.forward_throttle_pct(); } SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, fwd_thr); #endif // HAL_QUADPLANE_ENABLED } else { - // Apply min/max limits and voltage compensation to throttle output from flight mode + // Apply voltage compensation to throttle output from flight mode const float throttle = g2.fwd_batt_cmp.apply_throttle(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)); - SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, constrain_float(throttle, min_throttle, max_throttle)); + SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, throttle); } + if (control_mode->use_throttle_limits()) { + // Apply min/max throttle limits + const float limited_throttle = apply_throttle_limits(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)); + SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, limited_throttle); + } } /* From c0a503d74d8aa05b6803a523fe7506ce9a8a7189 Mon Sep 17 00:00:00 2001 From: Simon Hancock Date: Fri, 22 Dec 2023 10:52:52 +0000 Subject: [PATCH 0549/1335] autotest: Provide format and unit/multiplier info for log messages Definitions of each character are extracted from LogStructure.h Data is extracted by parsing the logging definition struct Also parse WriteMessage() calls for messages not defined in struct Add support to separate log descriptions for messages with same field list Compute derived unit from combination of format, unit and multiplier For XML output the format and derived unit into new attributes Add enumerations to the XML output (bitmasks were already done) For MD,RST,HTML, output either derived unit, 'char[n]', 'bitmask' or 'enum' Fix support for Blimp by adding it to the parse_enum.py lookup table --- Tools/autotest/logger_metadata/emit_html.py | 14 +- Tools/autotest/logger_metadata/emit_md.py | 14 +- Tools/autotest/logger_metadata/emit_rst.py | 14 +- Tools/autotest/logger_metadata/emit_xml.py | 35 ++- Tools/autotest/logger_metadata/parse.py | 288 +++++++++++++++++++- 5 files changed, 339 insertions(+), 26 deletions(-) diff --git a/Tools/autotest/logger_metadata/emit_html.py b/Tools/autotest/logger_metadata/emit_html.py index 08f16160f0c4a2..506dfbc104565b 100644 --- a/Tools/autotest/logger_metadata/emit_html.py +++ b/Tools/autotest/logger_metadata/emit_html.py @@ -37,14 +37,24 @@ def emit(self, doccos, enumerations): print('

%s

' % docco.description, file=self.fh) print(' ', file=self.fh) - print(" ", + print(" ", file=self.fh) for f in docco.fields_order: if "description" in docco.fields[f]: fdesc = docco.fields[f]["description"] else: fdesc = "" - print(' ' % (f, fdesc), + if "units" in docco.fields[f] and docco.fields[f]["units"]!="": + ftypeunits = docco.fields[f]["units"] + elif "fmt" in docco.fields[f] and "char" in docco.fields[f]["fmt"]: + ftypeunits = docco.fields[f]["fmt"] + elif "bitmaskenum" in docco.fields[f]: + ftypeunits = "bitmask" + elif "valueenum" in docco.fields[f]: + ftypeunits = "enum" + else: + ftypeunits = "" + print(' ' % (f, ftypeunits, fdesc), file=self.fh) print('
FieldNameDescription
FieldNameUnits/TypeDescription
%s%s
%s%s%s
', file=self.fh) diff --git a/Tools/autotest/logger_metadata/emit_md.py b/Tools/autotest/logger_metadata/emit_md.py index d6d1cb78778ba4..f9ae44492b5744 100644 --- a/Tools/autotest/logger_metadata/emit_md.py +++ b/Tools/autotest/logger_metadata/emit_md.py @@ -67,13 +67,23 @@ def emit(self, doccos, enumerations=None): if docco.url is not None: desc += f' ([Read more...]({docco.url}))' print(desc, file=self.fh) - print("\n|FieldName|Description|\n|---|---|", file=self.fh) + print("\n|FieldName|Units/Type|Description|\n|---|---|---|", file=self.fh) for f in docco.fields_order: if "description" in docco.fields[f]: fdesc = docco.fields[f]["description"] else: fdesc = "" - print(f'|{f}|{fdesc}|', file=self.fh) + if "units" in docco.fields[f] and docco.fields[f]["units"]!="": + ftypeunits = docco.fields[f]["units"] + elif "fmt" in docco.fields[f] and "char" in docco.fields[f]["fmt"]: + ftypeunits = docco.fields[f]["fmt"] + elif "bitmaskenum" in docco.fields[f]: + ftypeunits = "bitmask" + elif "valueenum" in docco.fields[f]: + ftypeunits = "enum" + else: + ftypeunits = "" + print(f'|{f}|{ftypeunits}|{fdesc}|', file=self.fh) print("", file=self.fh) self.stop() diff --git a/Tools/autotest/logger_metadata/emit_rst.py b/Tools/autotest/logger_metadata/emit_rst.py index 6b48ca5b315e36..7e513a0cc82f07 100644 --- a/Tools/autotest/logger_metadata/emit_rst.py +++ b/Tools/autotest/logger_metadata/emit_rst.py @@ -37,17 +37,23 @@ def emit(self, doccos, enumerations): rows = [] for f in docco.fields_order: + # Populate the description column if "description" in docco.fields[f]: fdesc = docco.fields[f]["description"] else: fdesc = "" + # Initialise Type/Unit and check for enum/bitfields + ftypeunit = "" fieldnamething = None if "bitmaskenum" in docco.fields[f]: fieldnamething = "bitmaskenum" table_label = "Bitmask values" + ftypeunit = "bitmask" elif "valueenum" in docco.fields[f]: fieldnamething = "valueenum" table_label = "Values" + ftypeunit = "enum" + # If an enum/bitmask is defined, build the table if fieldnamething is not None: enum_name = docco.fields[f][fieldnamething] if enum_name not in enumerations: @@ -62,7 +68,13 @@ def emit(self, doccos, enumerations): comment = "" bitmaskrows.append([enumentry.name, str(enumentry.value), comment]) fdesc += "\n%s:\n\n%s" % (table_label, self.tablify(bitmaskrows)) - rows.append([f, fdesc]) + # Populate the Type/Units column + if "units" in docco.fields[f] and docco.fields[f]["units"] != "": + ftypeunit = docco.fields[f]["units"] + elif "fmt" in docco.fields[f] and "char" in docco.fields[f]["fmt"]: + ftypeunit = docco.fields[f]["fmt"] + # Add the new row + rows.append([f, ftypeunit, fdesc]) print(self.tablify(rows), file=self.fh) diff --git a/Tools/autotest/logger_metadata/emit_xml.py b/Tools/autotest/logger_metadata/emit_xml.py index c0fc39b0c0dc83..05073364c91aa4 100644 --- a/Tools/autotest/logger_metadata/emit_xml.py +++ b/Tools/autotest/logger_metadata/emit_xml.py @@ -31,24 +31,37 @@ def emit(self, doccos, enumerations): xml_fields = etree.SubElement(xml_logformat, 'fields') for f in docco.fields_order: - xml_field = etree.SubElement(xml_fields, 'field', name=f) + units = docco.fields[f]['units'] if "units" in docco.fields[f] else "" + fmt = docco.fields[f]['fmt'] if "fmt" in docco.fields[f] else "" + xml_field = etree.SubElement(xml_fields, 'field', name=f, units=units, type=fmt) if "description" in docco.fields[f]: xml_description2 = etree.SubElement(xml_field, 'description') xml_description2.text = docco.fields[f]["description"] + # Check for enum/bitfield + fieldnamething = None if "bitmaskenum" in docco.fields[f]: - enum_name = docco.fields[f]["bitmaskenum"] + fieldnamething = "bitmaskenum" + xmlenumtag = "bitmask" + xmlentrytag = "bit" + elif "valueenum" in docco.fields[f]: + fieldnamething = "valueenum" + xmlenumtag = "enum" + xmlentrytag = "element" + # If an enum/bitmask is defined, include this in the XML + if fieldnamething is not None: + enum_name = docco.fields[f][fieldnamething] if enum_name not in enumerations: raise Exception("Unknown enum (%s) (have %s)" % (enum_name, "\n".join(sorted(enumerations.keys())))) - bit_mask = enumerations[enum_name] - xml_bitmask = etree.SubElement(xml_field, 'bitmask') - for bit in bit_mask.entries: - xml_bitmask_bit = etree.SubElement(xml_bitmask, 'bit', name=bit.name) - xml_bitmask_bit_value = etree.SubElement(xml_bitmask_bit, 'value') - xml_bitmask_bit_value.text = str(bit.value) - if bit.comment is not None: - xml_bitmask_bit_comment = etree.SubElement(xml_bitmask_bit, 'description') - xml_bitmask_bit_comment.text = bit.comment + enum = enumerations[enum_name] + xml_enum = etree.SubElement(xml_field, xmlenumtag, name=enum_name) + for entry in enum.entries: + xml_enum_entry = etree.SubElement(xml_enum, xmlentrytag, name=entry.name) + xml_enum_entry_value = etree.SubElement(xml_enum_entry, 'value') + xml_enum_entry_value.text = str(entry.value) + if entry.comment is not None: + xml_enum_entry_comment = etree.SubElement(xml_enum_entry, 'description') + xml_enum_entry_comment.text = entry.comment if xml_fields.text is None and not len(xml_fields): xml_fields.text = '\n' # add on next line in case of empty element. self.stop() diff --git a/Tools/autotest/logger_metadata/parse.py b/Tools/autotest/logger_metadata/parse.py index ea58198ea2bcc8..a3ce3221c6c1ae 100755 --- a/Tools/autotest/logger_metadata/parse.py +++ b/Tools/autotest/logger_metadata/parse.py @@ -19,6 +19,7 @@ topdir = os.path.join(os.path.dirname(os.path.realpath(__file__)), '../../../') topdir = os.path.realpath(topdir) +# Regular expressions for finding message information in code comments re_loggermessage = re.compile(r"@LoggerMessage\s*:\s*([\w,]+)", re.MULTILINE) re_commentline = re.compile(r"\s*//") re_description = re.compile(r"\s*//\s*@Description\s*:\s*(.*)") @@ -29,9 +30,39 @@ re_fieldvalueenum = re.compile(r"\s*//\s*@FieldValueEnum\s*:\s*(\w+):\s*(.*)") re_vehicles = re.compile(r"\s*//\s*@Vehicles\s*:\s*(.*)") +# Regular expressions for finding message definitions in structure format +re_start_messagedef = re.compile(r"^\s*{?\s*LOG_[A-Z0-9_]+_[MSGTA]+[A-Z0-9_]*\s*,") +re_deffield = r'[\s\\]*"?([\w\-#?%]+)"?\s*' +re_full_messagedef = re.compile(r'\s*LOG_\w+\s*,\s*\w+\([^)]+\)[\s\\]*,' + f'{re_deffield},{re_deffield},' + r'[\s\\]*"?([\w,]+)"?[\s\\]*,' + f'{re_deffield},{re_deffield}' , re.MULTILINE) +re_fmt_define = re.compile(r'#define\s+(\w+_FMT)\s+"([\w\-#?%]+)"') +re_units_define = re.compile(r'#define\s+(\w+_UNITS)\s+"([\w\-#?%]+)"') +re_mults_define = re.compile(r'#define\s+(\w+_MULTS)\s+"([\w\-#?%]+)"') + +# Regular expressions for finding message definitions in Write calls +re_start_writecall = re.compile(r"\s*[AP:]*logger[\(\)]*.Write[StreamingCrcl]*\(") +re_writefield = r'\s*"([\w\-#?%,]+)"\s*' +re_full_writecall = re.compile(r'\s*[AP:]*logger[\(\)]*.Write[StreamingCrcl]*\(' + f'{re_writefield},{re_writefield},{re_writefield},({re_writefield},{re_writefield})?' , re.MULTILINE) + +# Regular expression for extracting unit and multipliers from structure +re_units_mults_struct = re.compile(r"^\s*{\s*'([\w\-#?%!/])',"+r'\s*"?([\w\-#?%./]*)"?\s*}') + # TODO: validate URLS actually return 200 -# TODO: augment with other information from log definitions; type and units... +# Lookup tables are populated by reading LogStructure.h +log_fmt_lookup = {} +log_units_lookup = {} +log_mult_lookup = {} + +# Lookup table to convert multiplier to prefix +mult_prefix_lookup = { + 0: "", + 1: "", + 1e-1: "d", # deci- + 1e-2: "c", # centi- + 1e-3: "m", # milli- + 1e-6: "μ", # micro- + 1e-9: "n" # nano- +} class LoggerDocco(object): @@ -53,20 +84,48 @@ def __init__(self, vehicle): emit_xml.XMLEmitter(), emit_md.MDEmitter(), ] + self.msg_fmts_list = {} + self.msg_units_list = {} + self.msg_mults_list = {} class Docco(object): def __init__(self, name): self.name = name self.url = None - self.description = None + if isinstance(name,list): + self.description = [None] * len(name) + else: + self.description = None self.fields = {} self.fields_order = [] self.vehicles = None self.bits_enums = [] + def add_name(self, name): + # If self.name/description aren't lists, convert them + if isinstance(self.name,str): + self.name = [self.name] + self.description = [self.description] + # Replace any existing empty descriptions with empty strings + for i in range(0,len(self.description)): + if self.description[i] is None: + self.description[i] = "" + # Extend the name and description lists + if isinstance(name,list): + self.name.extend(name) + self.description.extend([None] * len(name)) + else: + self.name.append(name) + self.description.append(None) + def set_description(self, desc): - self.description = desc + if isinstance(self.description,list): + for i in range(0,len(self.description)): + if self.description[i] is None: + self.description[i] = desc + else: + self.description = desc def set_url(self, url): self.url = url @@ -99,13 +158,107 @@ def set_fieldbitmaskenum(self, field, bits): self.ensure_field(field) self.fields[field]["bitmaskenum"] = bits - def set_fieldbitmaskvalue(self, field, bits): + def set_fieldvalueenum(self, field, bits): self.ensure_field(field) self.fields[field]["valueenum"] = bits def set_vehicles(self, vehicles): self.vehicles = vehicles + def set_fmts(self, fmts): + # If no fields are defined, do nothing + if len(self.fields_order)==0: + return + # Make sure lengths match up + if len(fmts) != len(self.fields_order): + print(f"Number of fmts don't match fields: msg={self.name} fmts={fmts} num_fields={len(self.fields_order)}") + return + # Loop through the list + for idx in range(0,len(fmts)): + if fmts[idx] in log_fmt_lookup: + self.fields[self.fields_order[idx]]["fmt"] = log_fmt_lookup[fmts[idx]] + else: + print(f"Unrecognised format character: {fmts[idx]} in message {self.name}") + + def set_units(self, units, mults): + # If no fields are defined, do nothing + if len(self.fields_order)==0: + return + # Make sure lengths match up + if len(units) != len(self.fields_order) or len(units) != len(mults): + print(f"Number of units/mults/fields don't match: msg={self.name} units={units} mults={mults} num_fields={len(self.fields_order)}") + return + # Loop through the list + for idx in range(0,len(units)): + # Get the index into fields from field_order + f = self.fields_order[idx] + # Convert unit char to base unit + if units[idx] in log_units_lookup: + baseunit = log_units_lookup[units[idx]] + else: + print(f"Unrecognised units character: {units[idx]} in message {self.name}") + continue + # Do nothing if this field has no unit defined + if baseunit == "": + continue + # Convert mult char to value + if mults[idx] in log_mult_lookup: + mult = log_mult_lookup[mults[idx]] + mult_num = float(mult) + else: + print(f"Unrecognised multiplier character: {mults[idx]} in message {self.name}") + continue + # Check if the defined format for this field contains its own multiplier + # If so, the presented value will be the base-unit directly + if 'fmt' in self.fields[f] and self.fields[f]['fmt'].endswith("* 100"): + self.fields[f]["units"] = baseunit + elif 'fmt' in self.fields[f] and "latitude/longitude" in self.fields[f]['fmt']: + self.fields[f]["units"] = baseunit + # Check if we have a defined prefix for this multiplier + elif mult_num in mult_prefix_lookup: + self.fields[f]["units"] = f"{mult_prefix_lookup[mult_num]}{baseunit}" + # If all else fails, set the unit as the multipler and base unit together + else: + self.fields[f]["units"] = f"{mult} {baseunit}" + + def populate_lookups(self): + # Initialise the lookup tables + # Read the contents of the LogStructure.h file + structfile = os.path.join(topdir, "libraries", "AP_Logger", "LogStructure.h") + with open(structfile) as f: + lines = f.readlines() + f.close() + # Initialise current section to none + section = "none" + # Loop through the lines in the file + for line in lines: + # Look for the start of fmt/unit/mult info + if line.startswith("Format characters"): + section = "fmt" + elif line.startswith("const struct UnitStructure"): + section = "units" + elif line.startswith("const struct MultiplierStructure"): + section = "mult" + # Read formats from code comment, e.g.: + # b : int8_t + elif section == "fmt": + if "*/" in line: + section = "none" + else: + parts = line.split(":") + log_fmt_lookup[parts[0].strip()] = parts[1].strip() + # Read units or multipliers from C struct definition, e.g.: + # { '2', 1e2 }, or { 'J', "W.s" }, + elif section != "none": + if "};" in line: + section = "none" + else: + u = re_units_mults_struct.search(line) + if u is not None and section == "units": + log_units_lookup[u.group(1)] = u.group(2) + if u is not None and section == "mult": + log_mult_lookup[u.group(1)] = u.group(2) + def search_for_files(self, dirs_to_search): _next = [] for _dir in dirs_to_search: @@ -122,17 +275,86 @@ def search_for_files(self, dirs_to_search): if len(_next): self.search_for_files(_next) + def parse_messagedef(self,messagedef): + # Merge concatinated strings and remove comments + messagedef = re.sub(r'"\s+"', '', messagedef) + messagedef = re.sub(r'//[^\n]*', '', messagedef) + # Extract details from a structure definition + d = re_full_messagedef.search(messagedef) + if d is not None: + self.msg_fmts_list[d.group(1)] = d.group(2) + self.msg_units_list[d.group(1)] = d.group(4) + self.msg_mults_list[d.group(1)] = d.group(5) + return + # Extract details from a WriteStreaming call + d = re_full_writecall.search(messagedef) + if d is not None: + if d.group(1) in self.msg_fmts_list: + return + if d.group(5) is None: + self.msg_fmts_list[d.group(1)] = d.group(3) + else: + self.msg_fmts_list[d.group(1)] = d.group(6) + self.msg_units_list[d.group(1)] = d.group(3) + self.msg_mults_list[d.group(1)] = d.group(5) + return + # Didn't parse + #print(f"Unable to parse: {messagedef}") + + def search_messagedef_start(self,line,prevmessagedef=""): + # Look for the start of a structure definition + d = re_start_messagedef.search(line) + if d is not None: + messagedef = line + if "}" in line: + self.parse_messagedef(messagedef) + return "" + else: + return messagedef + # Look for a new call to WriteStreaming + d = re_start_writecall.search(line) + if d is not None: + messagedef = line + if ";" in line: + self.parse_messagedef(messagedef) + return "" + else: + return messagedef + # If we didn't find a new one, continue with any previous state + return prevmessagedef + def parse_file(self, filepath): with open(filepath) as f: # print("Opened (%s)" % filepath) lines = f.readlines() f.close() - state_outside = "outside" - state_inside = "inside" - state = state_outside - docco = None + state_outside = "outside" + state_inside = "inside" + messagedef = "" + state = state_outside + docco = None for line in lines: + if messagedef: + messagedef = messagedef + line + if "}" in line or ";" in line: + self.parse_messagedef(messagedef) + messagedef = "" if state == state_outside: + # Check for start of a message definition + messagedef = self.search_messagedef_start(line,messagedef) + + # Check for fmt/unit/mult #define + u = re_fmt_define.search(line) + if u is not None: + self.msg_fmts_list[u.group(1)] = u.group(2) + u = re_units_define.search(line) + if u is not None: + self.msg_units_list[u.group(1)] = u.group(2) + u = re_mults_define.search(line) + if u is not None: + self.msg_mults_list[u.group(1)] = u.group(2) + + # Check for the @LoggerMessage tag indicating the start of the docco block m = re_loggermessage.search(line) if m is None: continue @@ -142,11 +364,22 @@ def parse_file(self, filepath): state = state_inside docco = LoggerDocco.Docco(name) elif state == state_inside: + # If this line is not a comment, then this is the end of the docco block if not re_commentline.match(line): state = state_outside if docco.vehicles is None or self.vehicle in docco.vehicles: self.finalise_docco(docco) + messagedef = self.search_messagedef_start(line) continue + # Check for an multiple @LoggerMessage lines in this docco block + m = re_loggermessage.search(line) + if m is not None: + name = m.group(1) + if "," in name: + name = name.split(",") + docco.add_name(name) + continue + # Find and extract data from the various docco fields m = re_description.match(line) if m is not None: docco.set_description(m.group(1)) @@ -169,7 +402,7 @@ def parse_file(self, filepath): continue m = re_fieldvalueenum.match(line) if m is not None: - docco.set_fieldbitmaskvalue(m.group(1), m.group(2)) + docco.set_fieldvalueenum(m.group(1), m.group(2)) continue m = re_vehicles.match(line) if m is not None: @@ -187,14 +420,48 @@ def emit_output(self): new_doccos = [] for docco in self.doccos: if isinstance(docco.name, list): - for name in docco.name: + for name,desc in zip(docco.name, docco.description): tmpdocco = copy.copy(docco) tmpdocco.name = name + tmpdocco.description = desc new_doccos.append(tmpdocco) else: new_doccos.append(docco) new_doccos = sorted(new_doccos, key=lambda x : x.name) + # Try to attach the formats/units/multipliers + for docco in new_doccos: + # Apply the Formats to the docco + if docco.name in self.msg_fmts_list: + if "FMT" in self.msg_fmts_list[docco.name]: + if self.msg_fmts_list[docco.name] in self.msg_fmts_list: + docco.set_fmts(self.msg_fmts_list[self.msg_fmts_list[docco.name]]) + else: + docco.set_fmts(self.msg_fmts_list[docco.name]) + else: + print(f"No formats found for message {docco.name}") + # Get the Units + units = None + if docco.name in self.msg_units_list: + if "UNITS" in self.msg_units_list[docco.name]: + if self.msg_units_list[docco.name] in self.msg_units_list: + units = self.msg_units_list[self.msg_units_list[docco.name]] + else: + units = self.msg_units_list[docco.name] + # Get the Multipliers + mults = None + if docco.name in self.msg_mults_list: + if "MULTS" in self.msg_mults_list[docco.name]: + if self.msg_mults_list[docco.name] in self.msg_mults_list: + mults = self.msg_mults_list[self.msg_mults_list[docco.name]] + else: + mults = self.msg_mults_list[docco.name] + # Apply the units/mults to the docco + if units is not None and mults is not None: + docco.set_units(units,mults) + elif units is not None or mults is not None: + print(f"Cannot find matching units/mults for message {docco.name}") + enums_by_name = {} for enum in self.enumerations: enums_by_name[enum.name] = enum @@ -202,6 +469,7 @@ def emit_output(self): emitter.emit(new_doccos, enums_by_name) def run(self): + self.populate_lookups() self.enumerations = enum_parse.EnumDocco(self.vehicle).get_enumerations() self.files = [] self.search_for_files([self.vehicle_map[self.vehicle], "libraries"]) From f8078a1e743a712d03aa1869b27e13d08fb98ea8 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 17:20:40 +1100 Subject: [PATCH 0550/1335] AP_ADSB: de-duplicate packing of operating message the same message is sent in two places, and much code was duplicated. --- libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.cpp | 102 +++++++++------------ libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.h | 6 ++ 2 files changed, 51 insertions(+), 57 deletions(-) diff --git a/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.cpp b/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.cpp index c7fc9990b30446..5d170297a7146f 100644 --- a/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.cpp +++ b/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.cpp @@ -324,38 +324,13 @@ void AP_ADSB_Sagetech_MXS::auto_config_operating() mxs_state.op.altHostAvlbl = false; mxs_state.op.altRes25 = !mxs_state.inst.altRes100; // Host Altitude Resolution from install - int32_t height; - if (_frontend._my_loc.initialised() && _frontend._my_loc.get_alt_cm(Location::AltFrame::ABSOLUTE, height)) { - mxs_state.op.altitude = height * SAGETECH_SCALE_CM_TO_FEET; // Height above sealevel in feet - } else { - mxs_state.op.altitude = 0; - } - mxs_state.op.identOn = false; const auto &my_loc = _frontend._my_loc; - float vertRateD; - if (my_loc.get_vert_pos_rate_D(vertRateD)) { - // convert from down to up, and scale appropriately: - mxs_state.op.climbRate = -1 * vertRateD * SAGETECH_SCALE_M_PER_SEC_TO_FT_PER_MIN; - mxs_state.op.climbValid = true; - } else { - mxs_state.op.climbValid = false; - mxs_state.op.climbRate = -CLIMB_RATE_LIMIT; - } - const Vector2f speed = my_loc.groundspeed_vector(); - if (!speed.is_nan() && !speed.is_zero()) { - mxs_state.op.headingValid = true; - mxs_state.op.airspdValid = true; - } else { - mxs_state.op.headingValid = false; - mxs_state.op.airspdValid = false; - } - const uint16_t speed_knots = speed.length() * M_PER_SEC_TO_KNOTS; - double heading = wrap_360(degrees(speed.angle())); - mxs_state.op.airspd = speed_knots; - mxs_state.op.heading = heading; + populate_op_altitude(my_loc); + populate_op_climbrate(my_loc); + populate_op_airspeed_and_heading(my_loc); last.msg.type = SG_MSG_TYPE_HOST_OPMSG; @@ -587,35 +562,9 @@ void AP_ADSB_Sagetech_MXS::send_operating_msg() const auto &my_loc = _frontend._my_loc; - int32_t height; - if (_frontend._my_loc.initialised() && _frontend._my_loc.get_alt_cm(Location::AltFrame::ABSOLUTE, height)) { - mxs_state.op.altitude = height * SAGETECH_SCALE_CM_TO_FEET; // Height above sealevel in feet - } else { - mxs_state.op.altitude = 0; - } - - float vertRateD; - if (my_loc.get_vert_pos_rate_D(vertRateD)) { - mxs_state.op.climbRate = -1 * vertRateD * SAGETECH_SCALE_M_PER_SEC_TO_FT_PER_MIN; - mxs_state.op.climbValid = true; - } else { - mxs_state.op.climbValid = false; - mxs_state.op.climbRate = -CLIMB_RATE_LIMIT; - } - - const Vector2f speed = my_loc.groundspeed_vector(); - if (!speed.is_nan() && !speed.is_zero()) { - mxs_state.op.headingValid = true; - mxs_state.op.airspdValid = true; - } else { - mxs_state.op.headingValid = false; - mxs_state.op.airspdValid = false; - } - const uint16_t speed_knots = (speed.length() * M_PER_SEC_TO_KNOTS); - const double heading = wrap_360(degrees(speed.angle())); - - mxs_state.op.airspd = speed_knots; - mxs_state.op.heading = heading; + populate_op_altitude(my_loc); + populate_op_climbrate(my_loc); + populate_op_airspeed_and_heading(my_loc); mxs_state.op.identOn = _frontend.out_state.ctrl.identActive; _frontend.out_state.ctrl.identActive = false; // only send identButtonActive once per request @@ -785,5 +734,44 @@ sg_airspeed_t AP_ADSB_Sagetech_MXS::convert_airspeed_knots_to_sg(const float max } } +void AP_ADSB_Sagetech_MXS::populate_op_altitude(const AP_ADSB::Loc &loc) +{ + int32_t height; + if (loc.initialised() && loc.get_alt_cm(Location::AltFrame::ABSOLUTE, height)) { + mxs_state.op.altitude = height * SAGETECH_SCALE_CM_TO_FEET; // Height above sealevel in feet + } else { + mxs_state.op.altitude = 0; + } +} + +void AP_ADSB_Sagetech_MXS::populate_op_climbrate(const AP_ADSB::Loc &my_loc) +{ + float vertRateD; + if (my_loc.get_vert_pos_rate_D(vertRateD)) { + // convert from down to up, and scale appropriately: + mxs_state.op.climbRate = -1 * vertRateD * SAGETECH_SCALE_M_PER_SEC_TO_FT_PER_MIN; + mxs_state.op.climbValid = true; + } else { + mxs_state.op.climbValid = false; + mxs_state.op.climbRate = -CLIMB_RATE_LIMIT; + } +} + +void AP_ADSB_Sagetech_MXS::populate_op_airspeed_and_heading(const AP_ADSB::Loc &my_loc) +{ + const Vector2f speed = my_loc.groundspeed_vector(); + if (!speed.is_nan() && !speed.is_zero()) { + mxs_state.op.headingValid = true; + mxs_state.op.airspdValid = true; + } else { + mxs_state.op.headingValid = false; + mxs_state.op.airspdValid = false; + } + const uint16_t speed_knots = speed.length() * M_PER_SEC_TO_KNOTS; + double heading = wrap_360(degrees(speed.angle())); + mxs_state.op.airspd = speed_knots; + mxs_state.op.heading = heading; +} + #endif // HAL_ADSB_SAGETECH_MXS_ENABLED diff --git a/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.h b/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.h index 5ba13cfc048735..5e8c841039bfeb 100644 --- a/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.h +++ b/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.h @@ -260,6 +260,12 @@ class AP_ADSB_Sagetech_MXS : public AP_ADSB_Backend { sg_flightid_t fid; sg_ack_t ack; } mxs_state; + + // helper functions for populating the operating message: + void populate_op_altitude(const struct AP_ADSB::Loc &loc); + void populate_op_climbrate(const struct AP_ADSB::Loc &loc); + void populate_op_airspeed_and_heading(const struct AP_ADSB::Loc &loc); + }; #endif // HAL_ADSB_SAGETECH_MXS_ENABLED From bced484263a3df5e8379404af6364eec7a7f12ea Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 13:50:43 +1100 Subject: [PATCH 0551/1335] AP_CheckFirmware: rename sim_periph_gps to sim_gps_universal, recreate sim_periph_gps --- libraries/AP_CheckFirmware/AP_CheckFirmware.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_CheckFirmware/AP_CheckFirmware.h b/libraries/AP_CheckFirmware/AP_CheckFirmware.h index 648994fe292f8f..99189642e983df 100644 --- a/libraries/AP_CheckFirmware/AP_CheckFirmware.h +++ b/libraries/AP_CheckFirmware/AP_CheckFirmware.h @@ -39,7 +39,7 @@ enum class check_fw_result_t : uint8_t { #endif #if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(APJ_BOARD_ID) -// this allows for sitl_periph_gps to build +// this allows for sitl_periph to build #define APJ_BOARD_ID 0 #endif From 48b555f8e651bd00502bec3455ece443829c468a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 13:50:43 +1100 Subject: [PATCH 0552/1335] .github: rename sim_periph_gps to sim_gps_universal, recreate sim_periph_gps --- .github/workflows/test_coverage.yml | 2 +- .github/workflows/test_sitl_periph.yml | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/.github/workflows/test_coverage.yml b/.github/workflows/test_coverage.yml index dda488770f7762..c6dba24a392fc1 100644 --- a/.github/workflows/test_coverage.yml +++ b/.github/workflows/test_coverage.yml @@ -72,7 +72,7 @@ jobs: Tools/scripts/run_coverage.py -f else Tools/scripts/run_coverage.py -i - ./waf configure --board sitl_periph_gps --debug --coverage + ./waf configure --board sitl_periph_universal --debug --coverage ./waf build --target bin/AP_Periph Tools/scripts/run_coverage.py -i Tools/autotest/autotest.py test.CAN --debug --coverage diff --git a/.github/workflows/test_sitl_periph.yml b/.github/workflows/test_sitl_periph.yml index 0f4b5453fbef42..df6588792cfe7c 100644 --- a/.github/workflows/test_sitl_periph.yml +++ b/.github/workflows/test_sitl_periph.yml @@ -187,12 +187,12 @@ jobs: PATH="/github/home/.local/bin:$PATH" python modules/DroneCAN/dronecan_dsdlc/dronecan_dsdlc.py -O dsdlc_generated modules/DroneCAN/DSDL/uavcan modules/DroneCAN/DSDL/dronecan modules/DroneCAN/DSDL/com --run-test - - name: build sitl_periph_gps + - name: build sitl_periph_universal shell: bash run: | git config --global --add safe.directory ${GITHUB_WORKSPACE} PATH="/github/home/.local/bin:$PATH" - ./waf configure --board sitl_periph_gps + ./waf configure --board sitl_periph_universal ./waf build --target bin/AP_Periph ccache -s ccache -z From a77df87b01e053b52a2de297e01d5c2462a62e9e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 13:50:43 +1100 Subject: [PATCH 0553/1335] Tools: rename sim_periph_gps to sim_gps_universal, recreate sim_periph_gps --- Tools/AP_Periph/can.cpp | 1 + Tools/ardupilotwaf/boards.py | 106 ++++++++++++++++++---------- Tools/autotest/autotest.py | 12 ++-- Tools/autotest/pysim/vehicleinfo.py | 6 +- Tools/autotest/sim_vehicle.py | 8 +-- Tools/scripts/build_ci.sh | 2 +- Tools/scripts/run_coverage.py | 4 +- 7 files changed, 84 insertions(+), 55 deletions(-) diff --git a/Tools/AP_Periph/can.cpp b/Tools/AP_Periph/can.cpp index 9000ab4e33431a..e60d11295188cb 100644 --- a/Tools/AP_Periph/can.cpp +++ b/Tools/AP_Periph/can.cpp @@ -34,6 +34,7 @@ #include #elif CONFIG_HAL_BOARD == HAL_BOARD_SITL #include +#include #endif #define IFACE_ALL ((1U<<(HAL_NUM_CAN_IFACES))-1U) diff --git a/Tools/ardupilotwaf/boards.py b/Tools/ardupilotwaf/boards.py index 9330bb6e02804f..35f3ec24b80b4f 100644 --- a/Tools/ardupilotwaf/boards.py +++ b/Tools/ardupilotwaf/boards.py @@ -837,14 +837,65 @@ def get_name(self): return self.__class__.__name__ -class sitl_periph_gps(sitl): +class sitl_periph(sitl): def configure_env(self, cfg, env): cfg.env.AP_PERIPH = 1 - super(sitl_periph_gps, self).configure_env(cfg, env) + super(sitl_periph, self).configure_env(cfg, env) env.DEFINES.update( HAL_BUILD_AP_PERIPH = 1, PERIPH_FW = 1, - CAN_APP_NODE_NAME = '"org.ardupilot.ap_periph"', + HAL_RAM_RESERVE_START = 0, + + CANARD_ENABLE_CANFD = 1, + CANARD_ENABLE_TAO_OPTION = 1, + CANARD_MULTI_IFACE = 1, + + # FIXME: SITL library should not be using AP_AHRS: + AP_AHRS_ENABLED = 1, + AP_AHRS_BACKEND_DEFAULT_ENABLED = 0, + AP_AHRS_DCM_ENABLED = 1, # need a default backend + HAL_EXTERNAL_AHRS_ENABLED = 0, + + HAL_MAVLINK_BINDINGS_ENABLED = 1, + + AP_AIRSPEED_AUTOCAL_ENABLE = 0, + AP_CAN_SLCAN_ENABLED = 0, + AP_ICENGINE_ENABLED = 0, + AP_MISSION_ENABLED = 0, + AP_RCPROTOCOL_ENABLED = 0, + AP_RTC_ENABLED = 0, + AP_SCHEDULER_ENABLED = 0, + AP_SCRIPTING_ENABLED = 0, + AP_STATS_ENABLED = 0, + AP_UART_MONITOR_ENABLED = 1, + COMPASS_CAL_ENABLED = 0, + COMPASS_LEARN_ENABLED = 0, + COMPASS_MOT_ENABLED = 0, + HAL_CAN_DEFAULT_NODE_ID = 0, + HAL_CANMANAGER_ENABLED = 0, + HAL_GCS_ENABLED = 0, + HAL_GENERATOR_ENABLED = 0, + HAL_LOGGING_ENABLED = 0, + HAL_LOGGING_MAVLINK_ENABLED = 0, + HAL_PROXIMITY_ENABLED = 0, + HAL_RALLY_ENABLED = 0, + HAL_SUPPORT_RCOUT_SERIAL = 0, + AP_TERRAIN_AVAILABLE = 0, + ) + + try: + env.CXXFLAGS.remove('-DHAL_NAVEKF2_AVAILABLE=1') + except ValueError: + pass + env.CXXFLAGS += ['-DHAL_NAVEKF2_AVAILABLE=0'] + +class sitl_periph_universal(sitl_periph): + def configure_env(self, cfg, env): + super(sitl_periph_universal, self).configure_env(cfg, env) + env.DEFINES.update( + CAN_APP_NODE_NAME = '"org.ardupilot.ap_periph_universal"', + APJ_BOARD_ID = 100, + HAL_PERIPH_ENABLE_GPS = 1, HAL_PERIPH_ENABLE_AIRSPEED = 1, HAL_PERIPH_ENABLE_MAG = 1, @@ -856,48 +907,25 @@ def configure_env(self, cfg, env): HAL_PERIPH_ENABLE_RC_OUT = 1, HAL_PERIPH_ENABLE_ADSB = 1, HAL_PERIPH_ENABLE_SERIAL_OPTIONS = 1, - AP_ICENGINE_ENABLED = 0, AP_AIRSPEED_ENABLED = 1, - AP_AIRSPEED_AUTOCAL_ENABLE = 0, - AP_AHRS_ENABLED = 1, - AP_UART_MONITOR_ENABLED = 1, - HAL_CAN_DEFAULT_NODE_ID = 0, - HAL_RAM_RESERVE_START = 0, - APJ_BOARD_ID = 100, - HAL_GCS_ENABLED = 0, - HAL_MAVLINK_BINDINGS_ENABLED = 1, - HAL_LOGGING_ENABLED = 0, - HAL_LOGGING_MAVLINK_ENABLED = 0, - AP_MISSION_ENABLED = 0, - HAL_RALLY_ENABLED = 0, - AP_SCHEDULER_ENABLED = 0, - CANARD_ENABLE_TAO_OPTION = 1, - AP_RCPROTOCOL_ENABLED = 0, - CANARD_ENABLE_CANFD = 1, - CANARD_MULTI_IFACE = 1, - HAL_CANMANAGER_ENABLED = 0, - COMPASS_CAL_ENABLED = 0, - COMPASS_MOT_ENABLED = 0, - COMPASS_LEARN_ENABLED = 0, AP_BATTERY_ESC_ENABLED = 1, - HAL_EXTERNAL_AHRS_ENABLED = 0, - HAL_GENERATOR_ENABLED = 0, - AP_STATS_ENABLED = 0, - HAL_SUPPORT_RCOUT_SERIAL = 0, - AP_CAN_SLCAN_ENABLED = 0, - HAL_PROXIMITY_ENABLED = 0, - AP_SCRIPTING_ENABLED = 0, - HAL_NAVEKF3_AVAILABLE = 0, HAL_PWM_COUNT = 32, HAL_WITH_ESC_TELEM = 1, - AP_RTC_ENABLED = 0, + AP_TERRAIN_AVAILABLE = 1, ) - try: - env.CXXFLAGS.remove('-DHAL_NAVEKF2_AVAILABLE=1') - except ValueError: - pass - env.CXXFLAGS += ['-DHAL_NAVEKF2_AVAILABLE=0'] +class sitl_periph_gps(sitl_periph): + def configure_env(self, cfg, env): + cfg.env.AP_PERIPH = 1 + super(sitl_periph_gps, self).configure_env(cfg, env) + env.DEFINES.update( + HAL_BUILD_AP_PERIPH = 1, + PERIPH_FW = 1, + CAN_APP_NODE_NAME = '"org.ardupilot.ap_periph_gps"', + APJ_BOARD_ID = 101, + + HAL_PERIPH_ENABLE_GPS = 1, + ) class esp32(Board): abstract = True diff --git a/Tools/autotest/autotest.py b/Tools/autotest/autotest.py index 616411b7165a8a..970dc3bde03372 100755 --- a/Tools/autotest/autotest.py +++ b/Tools/autotest/autotest.py @@ -286,7 +286,7 @@ def should_run_step(step): "Blimp": "blimp", "BalanceBot": "ardurover", "Sailboat": "ardurover", - "SITLPeriphGPS": "sitl_periph_gp.AP_Periph", + "SITLPeriphUniversal": "sitl_periph_universal.AP_Periph", "CAN": "arducopter", } @@ -362,8 +362,8 @@ def find_specific_test_to_run(step): } supplementary_test_binary_map = { - "test.CAN": ["sitl_periph_gps:AP_Periph:0:Tools/autotest/default_params/periph.parm,Tools/autotest/default_params/quad-periph.parm", # noqa: E501 - "sitl_periph_gps:AP_Periph:1:Tools/autotest/default_params/periph.parm"], + "test.CAN": ["sitl_periph_universal:AP_Periph:0:Tools/autotest/default_params/periph.parm,Tools/autotest/default_params/quad-periph.parm", # noqa: E501 + "sitl_periph_universal:AP_Periph:1:Tools/autotest/default_params/periph.parm"], } @@ -441,8 +441,8 @@ def run_step(step): if step == 'build.Sub': vehicle_binary = 'bin/ardusub' - if step == 'build.SITLPeriphGPS': - vehicle_binary = 'sitl_periph_gps.bin/AP_Periph' + if step == 'build.SITLPeriphUniversal': + vehicle_binary = 'sitl_periph_universal.bin/AP_Periph' if step == 'build.Replay': return util.build_replay(board='SITL') @@ -1085,7 +1085,7 @@ def format_epilog(self, formatter): 'build.Blimp', 'test.Blimp', - 'build.SITLPeriphGPS', + 'build.SITLPeriphUniversal', 'test.CAN', # convertgps disabled as it takes 5 hours diff --git a/Tools/autotest/pysim/vehicleinfo.py b/Tools/autotest/pysim/vehicleinfo.py index 9709dcd917e0d2..0bba80193313ef 100644 --- a/Tools/autotest/pysim/vehicleinfo.py +++ b/Tools/autotest/pysim/vehicleinfo.py @@ -424,10 +424,10 @@ def __init__(self): }, }, }, - "sitl_periph_gps": { + "sitl_periph_universal": { "frames": { - "gps": { - "configure_target": "sitl_periph_gps", + "universal": { + "configure_target": "sitl_periph_universal", "waf_target": "bin/AP_Periph", "default_params_filename": "default_params/periph.parm", }, diff --git a/Tools/autotest/sim_vehicle.py b/Tools/autotest/sim_vehicle.py index 1b46b85a87e31d..80e19d40ae49f2 100755 --- a/Tools/autotest/sim_vehicle.py +++ b/Tools/autotest/sim_vehicle.py @@ -672,8 +672,8 @@ def start_antenna_tracker(opts): def start_CAN_Periph(opts, frame_info): """Compile and run the sitl_periph""" - progress("Preparing sitl_periph_gps") - options = vinfo.options["sitl_periph_gps"]['frames']['gps'] + progress("Preparing sitl_periph_universal") + options = vinfo.options["sitl_periph_universal"]['frames']['universal'] defaults_path = frame_info.get('periph_params_filename', None) if defaults_path is None: defaults_path = options.get('default_params_filename', None) @@ -686,9 +686,9 @@ def start_CAN_Periph(opts, frame_info): if not cmd_opts.no_rebuild: do_build(opts, options) - exe = os.path.join(root_dir, 'build/sitl_periph_gps', 'bin/AP_Periph') + exe = os.path.join(root_dir, 'build/sitl_periph_universal', 'bin/AP_Periph') cmd = ["nice"] - cmd_name = "sitl_periph_gps" + cmd_name = "sitl_periph_universal" if opts.valgrind: cmd_name += " (valgrind)" cmd.append("valgrind") diff --git a/Tools/scripts/build_ci.sh b/Tools/scripts/build_ci.sh index 84bb812a736c95..57e90829111e93 100755 --- a/Tools/scripts/build_ci.sh +++ b/Tools/scripts/build_ci.sh @@ -132,7 +132,7 @@ for t in $CI_BUILD_TARGET; do echo "Building SITL Periph GPS" $waf configure --board sitl $waf copter - run_autotest "Copter" "build.SITLPeriphGPS" "test.CAN" + run_autotest "Copter" "build.SITLPeriphUniversal" "test.CAN" continue fi if [ "$t" == "sitltest-plane" ]; then diff --git a/Tools/scripts/run_coverage.py b/Tools/scripts/run_coverage.py index ee6e4c24a34bc6..00036982128b03 100755 --- a/Tools/scripts/run_coverage.py +++ b/Tools/scripts/run_coverage.py @@ -238,8 +238,8 @@ def update_stats(self) -> None: root_dir + "/build/linux/modules/*", root_dir + "/build/sitl/libraries/*", root_dir + "/build/sitl/modules/*", - root_dir + "/build/sitl_periph_gps/libraries/*", - root_dir + "/build/sitl_periph_gps/modules/*", + root_dir + "/build/sitl_periph_universal/libraries/*", + root_dir + "/build/sitl_periph_universal/modules/*", root_dir + "/libraries/*/examples/*", root_dir + "/libraries/*/tests/*", "-o", self.INFO_FILE From 18c5daaa38b3e5f1855a7b680f10e9e9caa58291 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 13:51:47 +1100 Subject: [PATCH 0554/1335] AP_AHRS: use a switch statement when falling back to DCM --- libraries/AP_AHRS/AP_AHRS.cpp | 29 ++++++++++++++++------------- 1 file changed, 16 insertions(+), 13 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index d0985bd80315bd..6be34de803c212 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -1932,35 +1932,38 @@ AP_AHRS::EKFType AP_AHRS::_active_EKF_type(void) const #if AP_AHRS_DCM_ENABLED // Handle fallback for fixed wing planes (including VTOL's) and ground vehicles. - if (ret != EKFType::DCM && - (_vehicle_class == VehicleClass::FIXED_WING || - _vehicle_class == VehicleClass::GROUND)) { - + if (_vehicle_class == VehicleClass::FIXED_WING || + _vehicle_class == VehicleClass::GROUND) { bool should_use_gps = true; - nav_filter_status filt_state; + nav_filter_status filt_state {}; + switch (ret) { + case EKFType::DCM: + // already using DCM + break; #if HAL_NAVEKF2_AVAILABLE - if (ret == EKFType::TWO) { + case EKFType::TWO: EKF2.getFilterStatus(filt_state); should_use_gps = EKF2.configuredToUseGPSForPosXY(); - } + break; #endif #if HAL_NAVEKF3_AVAILABLE - if (ret == EKFType::THREE) { + case EKFType::THREE: EKF3.getFilterStatus(filt_state); should_use_gps = EKF3.configuredToUseGPSForPosXY(); - } + break; #endif #if AP_AHRS_SIM_ENABLED - if (ret == EKFType::SIM) { + case EKFType::SIM: get_filter_status(filt_state); - } + break; #endif #if HAL_EXTERNAL_AHRS_ENABLED - if (ret == EKFType::EXTERNAL) { + case EKFType::EXTERNAL: get_filter_status(filt_state); should_use_gps = true; - } + break; #endif + } // Handle fallback for the case where the DCM or EKF is unable to provide attitude or height data. const bool can_use_dcm = dcm.yaw_source_available() || fly_forward; From 02ef8bf18a0c8dbaee0aa4267b847d9595f93480 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 13:52:09 +1100 Subject: [PATCH 0555/1335] AP_AHRS: use AP_AHRS_BACKEND_DEFAULT_ENABLED for sim and navkef3 --- libraries/AP_AHRS/AP_AHRS_config.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS_config.h b/libraries/AP_AHRS/AP_AHRS_config.h index 7338a02787a875..9cfa1715fbec61 100644 --- a/libraries/AP_AHRS/AP_AHRS_config.h +++ b/libraries/AP_AHRS/AP_AHRS_config.h @@ -21,11 +21,11 @@ #endif #ifndef HAL_NAVEKF3_AVAILABLE -#define HAL_NAVEKF3_AVAILABLE AP_INERTIALSENSOR_ENABLED +#define HAL_NAVEKF3_AVAILABLE AP_AHRS_BACKEND_DEFAULT_ENABLED && AP_INERTIALSENSOR_ENABLED #endif #ifndef AP_AHRS_SIM_ENABLED -#define AP_AHRS_SIM_ENABLED AP_SIM_ENABLED && AP_INERTIALSENSOR_ENABLED +#define AP_AHRS_SIM_ENABLED AP_AHRS_BACKEND_DEFAULT_ENABLED && AP_SIM_ENABLED && AP_INERTIALSENSOR_ENABLED #endif #ifndef AP_AHRS_POSITION_RESET_ENABLED From 3c57e9c14a75bc897ae1cf1fb1f13f59baba65c0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 11 Jan 2024 17:22:38 +1100 Subject: [PATCH 0556/1335] AP_HAL: correct blimp SITL-on-hardware build --- libraries/AP_HAL/SIMState.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_HAL/SIMState.cpp b/libraries/AP_HAL/SIMState.cpp index 47cd3d4e79bbf8..fa22817f29cfde 100644 --- a/libraries/AP_HAL/SIMState.cpp +++ b/libraries/AP_HAL/SIMState.cpp @@ -39,6 +39,8 @@ using namespace AP_HAL; #define AP_SIM_FRAME_CLASS Plane #elif APM_BUILD_TYPE(APM_BUILD_Rover) #define AP_SIM_FRAME_CLASS SimRover +#elif APM_BUILD_TYPE(APM_BUILD_Blimp) +#define AP_SIM_FRAME_CLASS Blimp #endif #endif @@ -51,6 +53,8 @@ using namespace AP_HAL; #define AP_SIM_FRAME_STRING "plane" #elif APM_BUILD_TYPE(APM_BUILD_Rover) #define AP_SIM_FRAME_STRING "rover" +#elif APM_BUILD_TYPE(APM_BUILD_Blimp) +#define AP_SIM_FRAME_STRING "blimp" #endif #endif From ba97a422b426df62f197b6d9f4a2433e5d8a0f88 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 11 Jan 2024 17:53:45 +1100 Subject: [PATCH 0557/1335] AP_WindVane: correct sitl-on-hardware build for Rover --- libraries/AP_WindVane/AP_WindVane_SITL.h | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/libraries/AP_WindVane/AP_WindVane_SITL.h b/libraries/AP_WindVane/AP_WindVane_SITL.h index f84d0a815d4e9c..bdfe547f4e088b 100644 --- a/libraries/AP_WindVane/AP_WindVane_SITL.h +++ b/libraries/AP_WindVane/AP_WindVane_SITL.h @@ -28,10 +28,8 @@ class AP_WindVane_SITL : public AP_WindVane_Backend using AP_WindVane_Backend::AP_WindVane_Backend; // update state - #if CONFIG_HAL_BOARD == HAL_BOARD_SITL - void update_direction() override; - void update_speed() override; - #endif + void update_direction() override; + void update_speed() override; }; #endif // AP_WINDVANE_SIM_ENABLED From b17b70d1d4026924572c4bb73f5066f6f5456e73 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 11 Jan 2024 17:55:48 +1100 Subject: [PATCH 0558/1335] AP_HAL: correct tracker SITL-on-hardware build --- libraries/AP_HAL/SIMState.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_HAL/SIMState.cpp b/libraries/AP_HAL/SIMState.cpp index fa22817f29cfde..deb8d90c730ceb 100644 --- a/libraries/AP_HAL/SIMState.cpp +++ b/libraries/AP_HAL/SIMState.cpp @@ -35,6 +35,8 @@ using namespace AP_HAL; #define AP_SIM_FRAME_CLASS MultiCopter #elif APM_BUILD_TYPE(APM_BUILD_Heli) #define AP_SIM_FRAME_CLASS Helicopter +#elif APM_BUILD_TYPE(APM_BUILD_AntennaTracker) +#define AP_SIM_FRAME_CLASS Tracker #elif APM_BUILD_TYPE(APM_BUILD_ArduPlane) #define AP_SIM_FRAME_CLASS Plane #elif APM_BUILD_TYPE(APM_BUILD_Rover) @@ -49,6 +51,8 @@ using namespace AP_HAL; #define AP_SIM_FRAME_STRING "+" #elif APM_BUILD_TYPE(APM_BUILD_Heli) #define AP_SIM_FRAME_STRING "heli" +#elif APM_BUILD_TYPE(APM_BUILD_AntennaTracker) +#define AP_SIM_FRAME_STRING "tracker" #elif APM_BUILD_TYPE(APM_BUILD_ArduPlane) #define AP_SIM_FRAME_STRING "plane" #elif APM_BUILD_TYPE(APM_BUILD_Rover) From e27a3531078ca11eb7b4304166689618be5c0645 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 11 Jan 2024 17:57:29 +1100 Subject: [PATCH 0559/1335] AP_HAL: correct Sub SITL-on-hardware build --- libraries/AP_HAL/SIMState.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_HAL/SIMState.cpp b/libraries/AP_HAL/SIMState.cpp index deb8d90c730ceb..70fcb9abfaca1b 100644 --- a/libraries/AP_HAL/SIMState.cpp +++ b/libraries/AP_HAL/SIMState.cpp @@ -43,6 +43,8 @@ using namespace AP_HAL; #define AP_SIM_FRAME_CLASS SimRover #elif APM_BUILD_TYPE(APM_BUILD_Blimp) #define AP_SIM_FRAME_CLASS Blimp +#elif APM_BUILD_TYPE(APM_BUILD_ArduSub) +#define AP_SIM_FRAME_CLASS Submarine #endif #endif @@ -59,6 +61,8 @@ using namespace AP_HAL; #define AP_SIM_FRAME_STRING "rover" #elif APM_BUILD_TYPE(APM_BUILD_Blimp) #define AP_SIM_FRAME_STRING "blimp" +#elif APM_BUILD_TYPE(APM_BUILD_ArduSub) +#define AP_SIM_FRAME_STRING "sub" #endif #endif From e5ec596a03ba80fcf8588cc16ffa4cae8e1ef4c6 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 1 Nov 2023 15:30:14 +1100 Subject: [PATCH 0560/1335] AP_ADSB: emit last char for callsign in statustext --- libraries/AP_ADSB/AP_ADSB.cpp | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/libraries/AP_ADSB/AP_ADSB.cpp b/libraries/AP_ADSB/AP_ADSB.cpp index 53ba4291dc0cec..5d1508873149ad 100644 --- a/libraries/AP_ADSB/AP_ADSB.cpp +++ b/libraries/AP_ADSB/AP_ADSB.cpp @@ -681,10 +681,9 @@ void AP_ADSB::handle_out_cfg(const mavlink_uavionix_adsb_out_cfg_t &packet) out_state.cfg.stall_speed_cm = packet.stallSpeed; // guard against string with non-null end char - const char c = out_state.cfg.callsign[MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN-1]; - out_state.cfg.callsign[MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN-1] = 0; - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ADSB: Using ICAO_id %d and Callsign %s", (int)out_state.cfg.ICAO_id, out_state.cfg.callsign); - out_state.cfg.callsign[MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN-1] = c; + char tmp_callsign[MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN+1] {}; + memcpy(tmp_callsign, out_state.cfg.callsign, MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "ADSB: Using ICAO_id %d and Callsign %s", (int)out_state.cfg.ICAO_id, tmp_callsign); // send now out_state.last_config_ms = 0; From 5dbe08c454222b0aca69b47499814604e283d012 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 12 Jan 2024 15:28:00 +1100 Subject: [PATCH 0561/1335] AP_ADSB: send absolute height in GPS packet to MXS device Documentation specifies WGS-84 ellipsoid. --- libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.cpp b/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.cpp index 5d170297a7146f..d4964ba131b682 100644 --- a/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.cpp +++ b/libraries/AP_ADSB/AP_ADSB_Sagetech_MXS.cpp @@ -641,7 +641,7 @@ void AP_ADSB_Sagetech_MXS::send_gps_msg() } int32_t height; - if (_frontend._my_loc.initialised() && _frontend._my_loc.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, height)) { + if (_frontend._my_loc.initialised() && _frontend._my_loc.get_alt_cm(Location::AltFrame::ABSOLUTE, height)) { gps.height = height * 0.01; } else { gps.height = 0.0; From cd44d09d84504f276fc872da11bf7d5f504e202c Mon Sep 17 00:00:00 2001 From: David Buzz Date: Mon, 8 Jan 2024 20:00:11 +1000 Subject: [PATCH 0562/1335] github: actions problem solvers , annotations and summary --- .github/problem-matchers/autotestfail.json | 17 +++++ .github/problem-matchers/autotestwarn.json | 17 +++++ .github/problem-matchers/gcc.json | 18 +++++ .github/problem-matchers/python.json | 22 +++++++ .github/workflows/esp32_build.yml | 76 +++++++++++++++------- 5 files changed, 127 insertions(+), 23 deletions(-) create mode 100644 .github/problem-matchers/autotestfail.json create mode 100644 .github/problem-matchers/autotestwarn.json create mode 100644 .github/problem-matchers/gcc.json create mode 100644 .github/problem-matchers/python.json diff --git a/.github/problem-matchers/autotestfail.json b/.github/problem-matchers/autotestfail.json new file mode 100644 index 00000000000000..ccda5c1a940f7e --- /dev/null +++ b/.github/problem-matchers/autotestfail.json @@ -0,0 +1,17 @@ +{ + "__comment": "by buzz try to match common autotest warnings and errors that arent caught by gcc.json or python.json", + "problemMatcher": [ + { + "owner": "autotest-fail-matcher", + "severity": "error", + "pattern": [ + { + "regexp": "^(.*)(TIMEOUT|Build failed|FAILED STEP):(.*)$", + "column": 1, + "code": 2, + "message": 3 + } + ] + } + ] +} \ No newline at end of file diff --git a/.github/problem-matchers/autotestwarn.json b/.github/problem-matchers/autotestwarn.json new file mode 100644 index 00000000000000..6aa77a7ece6baa --- /dev/null +++ b/.github/problem-matchers/autotestwarn.json @@ -0,0 +1,17 @@ +{ + "__comment": "by buzz try to match common autotest warnings and errors that arent caught by gcc.json or python.json", + "problemMatcher": [ + { + "owner": "autotest-warn-matcher", + "severity": "warning", + "pattern": [ + { + "regexp": "^(.*)(WARN|WARNING):(.*)$", + "column": 1, + "code": 2, + "message": 3 + } + ] + } + ] +} \ No newline at end of file diff --git a/.github/problem-matchers/gcc.json b/.github/problem-matchers/gcc.json new file mode 100644 index 00000000000000..bd5ab6c00a7608 --- /dev/null +++ b/.github/problem-matchers/gcc.json @@ -0,0 +1,18 @@ +{ + "__comment": "Taken from vscode-cpptools's Extension/package.json gcc rule", + "problemMatcher": [ + { + "owner": "gcc-problem-matcher", + "pattern": [ + { + "regexp": "^(.*):(\\d+):(\\d+):\\s+(?:fatal\\s+)?(warning|error):\\s+(.*)$", + "file": 1, + "line": 2, + "column": 3, + "severity": 4, + "message": 5 + } + ] + } + ] +} \ No newline at end of file diff --git a/.github/problem-matchers/python.json b/.github/problem-matchers/python.json new file mode 100644 index 00000000000000..a14ab2dd7610b0 --- /dev/null +++ b/.github/problem-matchers/python.json @@ -0,0 +1,22 @@ +{ + "__comment": "inspired by https://github.com/microsoft/vscode-python/issues/3828#issuecomment-575439587", + "problemMatcher": [ + { + "owner": "python-problem-matcher", + "pattern": [ + { + "regexp": "^.*File \\\"([^\\\"]|.*)\\\", line (\\d+).*", + "file": 1, + "line": 2 + }, + { + "regexp": "^.*raise.*$" + }, + { + "regexp": "^\\s*(.*)\\s*$", + "message": 1 + } + ] + } + ] +} \ No newline at end of file diff --git a/.github/workflows/esp32_build.yml b/.github/workflows/esp32_build.yml index 7f2a11bf060ca8..26185663fe7ac5 100644 --- a/.github/workflows/esp32_build.yml +++ b/.github/workflows/esp32_build.yml @@ -151,6 +151,7 @@ jobs: matrix: config: [ esp32buzz, + esp32s3empty, ] gcc: [10] @@ -158,6 +159,19 @@ jobs: - uses: actions/checkout@v4 with: submodules: 'recursive' + + - name: Register gcc problem matcher + run: echo "::add-matcher::.github/problem-matchers/gcc.json" + + - name: Register python problem matcher + run: echo "::add-matcher::.github/problem-matchers/python.json" + + - name: Register autotest warn matcher + run: echo "::add-matcher::.github/problem-matchers/autotestwarn.json" + + - name: Register autotest fail matcher + run: echo "::add-matcher::.github/problem-matchers/autotestfail.json" + - name: Install Prerequisites shell: bash run: | @@ -169,8 +183,8 @@ jobs: # we actualy want 3.11 .. but the above only gave us 3.10, not ok with esp32 builds. sudo add-apt-repository ppa:deadsnakes/ppa - sudo apt update - sudo apt install python3.11 python3.11-venv python3.11-distutils -y + sudo apt-get update + sudo apt-get install python3.11 python3.11-venv python3.11-distutils -y sudo apt-get install python3 python3-pip python3-venv python3-setuptools python3-serial python3-cryptography python3-future python3-pyparsing python3-pyelftools update-alternatives --query python pip3 install gevent @@ -181,14 +195,14 @@ jobs: update-alternatives --query python rm -rf /usr/local/bin/cmake - sudo apt remove --purge --auto-remove cmake - sudo apt update && \ - sudo apt install -y software-properties-common lsb-release && \ - sudo apt clean all + sudo apt-get remove --purge --auto-remove cmake + sudo apt-get update && \ + sudo apt-get install -y software-properties-common lsb-release && \ + sudo apt-get clean all wget -O - https://apt.kitware.com/keys/kitware-archive-latest.asc 2>/dev/null | gpg --dearmor - | sudo tee /etc/apt/trusted.gpg.d/kitware.gpg >/dev/null sudo apt-add-repository "deb https://apt.kitware.com/ubuntu/ $(lsb_release -cs) main" - sudo apt update - sudo apt install cmake + sudo apt-get update + sudo apt-get install cmake git submodule update --init --recursive --depth=1 @@ -198,7 +212,7 @@ jobs: cd modules/esp_idf echo "Installing ESP-IDF tools...." - ./install.sh esp32,esp32s3 2>&1 > /dev/null + ./install.sh esp32,esp32s3 cd ../.. @@ -210,32 +224,48 @@ jobs: source ~/.bash_profile PATH="/github/home/.local/bin:$PATH" echo $PATH - + echo "### Configure ${{matrix.config}} :rocket:" >> $GITHUB_STEP_SUMMARY cd modules/esp_idf ./install.sh source ./export.sh cd ../.. python -m pip install --progress-bar off future lxml pymavlink MAVProxy pexpect flake8 geocoder empy==3.3.4 dronecan which cmake - ./waf configure --board ${{matrix.config}} - ./waf plane - cp build/esp32buzz/esp-idf_build/ardupilot.bin ./ArduPlane.bin - cp build/esp32buzz/esp-idf_build/ardupilot.elf ./ArduPlane.elf - ./waf copter - cp build/esp32buzz/esp-idf_build/ardupilot.bin ./ArduCopter.bin - cp build/esp32buzz/esp-idf_build/ardupilot.elf ./ArduCopter.elf + ./waf configure --board ${{matrix.config}} + echo './waf configure --board ${{matrix.config}}' >> $GITHUB_STEP_SUMMARY + echo "### Build Plane ${{matrix.config}} :rocket:" >> $GITHUB_STEP_SUMMARY + echo './waf plane' >> $GITHUB_STEP_SUMMARY + ./waf plane | tee >( grep -vE 'Compiling|Generat|includes.list|Parsing|Validation|Building|Linking|Detecting|linker|\*\*\*\*\*\*\*|Partition|SubType|Checking|esp-idf' --color=never --line-buffered > summary.log) + cat summary.log >> $GITHUB_STEP_SUMMARY + + cp build/${{matrix.config}}/esp-idf_build/ardupilot.bin ./ArduPlane.${{matrix.config}}.bin + cp build/${{matrix.config}}/esp-idf_build/ardupilot.elf ./ArduPlane.${{matrix.config}}.elf + echo "### Build Copter ${{matrix.config}} :rocket:" >> $GITHUB_STEP_SUMMARY + echo './waf copter' >> $GITHUB_STEP_SUMMARY + ./waf copter | tee >( grep -vE 'Compiling|Generat|includes.list|Parsing|Validation|Building|Linking|Detecting|linker|\*\*\*\*\*\*\*|Partition|SubType|Checking|esp-idf' --color=never --line-buffered > summary2.log) + + cat summary2.log >> $GITHUB_STEP_SUMMARY + + cp build/${{matrix.config}}/esp-idf_build/ardupilot.bin ./ArduCopter.${{matrix.config}}.bin + cp build/${{matrix.config}}/esp-idf_build/ardupilot.elf ./ArduCopter.${{matrix.config}}.elf + + cp build/${{matrix.config}}/esp-idf_build/bootloader/bootloader.bin ./bootloader.${{matrix.config}}.bin + cp build/${{matrix.config}}/esp-idf_build/partition_table/partition-table.bin ./partition-table.${{matrix.config}}.bin + + echo "### Assets avail in artifact:" >> $GITHUB_STEP_SUMMARY + ls bootloader* partition* Ardu*.elf Ardu*.bin >> $GITHUB_STEP_SUMMARY - name: Archive artifacts uses: actions/upload-artifact@v3 with: name: esp32-binaries -${{matrix.config}} path: | - /home/runner/work/ardupilot/ardupilot/ArduPlane.bin - /home/runner/work/ardupilot/ardupilot/ArduPlane.elf - /home/runner/work/ardupilot/ardupilot/ArduCopter.bin - /home/runner/work/ardupilot/ardupilot/ArduCopter.elf - /home/runner/work/ardupilot/ardupilot/build/esp32buzz/esp-idf_build/bootloader/bootloader.bin - /home/runner/work/ardupilot/ardupilot/build/esp32buzz/esp-idf_build/partition_table/partition-table.bin + /home/runner/work/ardupilot/ardupilot/ArduPlane.${{matrix.config}}.bin + /home/runner/work/ardupilot/ardupilot/ArduPlane.${{matrix.config}}.elf + /home/runner/work/ardupilot/ardupilot/ArduCopter.${{matrix.config}}.bin + /home/runner/work/ardupilot/ardupilot/ArduCopter.${{matrix.config}}.elf + /home/runner/work/ardupilot/ardupilot/bootloader.${{matrix.config}}.bin + /home/runner/work/ardupilot/ardupilot/partition-table.${{matrix.config}}.bin retention-days: 14 From 8b9831dc74aa5daf8a0ac9b0e92fd8655bc18505 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 11 Jan 2024 09:16:57 +1100 Subject: [PATCH 0563/1335] AP_AHRS: correct compilation when AP_AHRS_ENABLED is off e.g. CubeOrange-periph-heavy --- libraries/AP_AHRS/AP_AHRS_config.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_AHRS/AP_AHRS_config.h b/libraries/AP_AHRS/AP_AHRS_config.h index 9cfa1715fbec61..fd56a5f6deabf8 100644 --- a/libraries/AP_AHRS/AP_AHRS_config.h +++ b/libraries/AP_AHRS/AP_AHRS_config.h @@ -29,6 +29,6 @@ #endif #ifndef AP_AHRS_POSITION_RESET_ENABLED -#define AP_AHRS_POSITION_RESET_ENABLED (BOARD_FLASH_SIZE>1024) +#define AP_AHRS_POSITION_RESET_ENABLED (BOARD_FLASH_SIZE>1024 && AP_AHRS_ENABLED) #endif From 4dd958bdd71ff425461cc989a09365baf32d31e8 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 11 Jan 2024 09:16:57 +1100 Subject: [PATCH 0564/1335] AP_Arming: correct compilation when AP_AHRS_ENABLED is off e.g. CubeOrange-periph-heavy --- libraries/AP_Arming/AP_Arming.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index ff6362b68849d4..eb9fca91e0e7d3 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -579,6 +579,7 @@ bool AP_Arming::compass_checks(bool report) return false; } +#if AP_AHRS_ENABLED // if ahrs is using compass and we have location, check mag field versus expected earth magnetic model Location ahrs_loc; AP_AHRS &ahrs = AP::ahrs(); @@ -597,6 +598,7 @@ bool AP_Arming::compass_checks(bool report) return false; } } +#endif // AP_AHRS_ENABLED } return true; From 1051da5cb484ded75ac92d6ed59c9516f2fbeb64 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 11 Jan 2024 09:16:57 +1100 Subject: [PATCH 0565/1335] AP_InertialSensor: correct compilation when AP_AHRS_ENABLED is off e.g. CubeOrange-periph-heavy --- libraries/AP_InertialSensor/AP_InertialSensor.cpp | 11 +++++++++-- .../AP_InertialSensor/AP_InertialSensor_Backend.cpp | 10 ++++++++-- 2 files changed, 17 insertions(+), 4 deletions(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index 4d4480e43f3501..37504d8897abf3 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -1460,7 +1460,7 @@ bool AP_InertialSensor::get_accel_health_all(void) const return (get_accel_count() > 0); } -#if HAL_GCS_ENABLED +#if HAL_GCS_ENABLED && AP_AHRS_ENABLED /* calculate the trim_roll and trim_pitch. This is used for redoing the trim without needing a full accel cal @@ -1521,6 +1521,7 @@ MAV_RESULT AP_InertialSensor::calibrate_trim() // reset ahrs's trim to suggested values from calibration routine ahrs.set_trim(trim_rad); + last_accel_cal_ms = AP_HAL::millis(); _trimming_accel = false; return MAV_RESULT_ACCEPTED; @@ -1530,7 +1531,7 @@ MAV_RESULT AP_InertialSensor::calibrate_trim() _trimming_accel = false; return MAV_RESULT_FAILED; } -#endif // HAL_GCS_ENABLED +#endif // HAL_GCS_ENABLED && AP_AHRS_ENABLED /* check if the accelerometers are calibrated in 3D and that current number of accels matched number when calibrated @@ -2408,7 +2409,9 @@ bool AP_InertialSensor::calibrate_gyros() if (!gyro_calibrated_ok_all()) { return false; } +#if AP_AHRS_ENABLED AP::ahrs().reset_gyro_drift(); +#endif return true; } @@ -2550,8 +2553,10 @@ MAV_RESULT AP_InertialSensor::simple_accel_cal() #endif } +#if AP_AHRS_ENABLED // force trim to zero AP::ahrs().set_trim(Vector3f(0, 0, 0)); +#endif } else { DEV_PRINTF("\nFAILED\n"); // restore old values @@ -2572,8 +2577,10 @@ MAV_RESULT AP_InertialSensor::simple_accel_cal() update(); } +#if AP_AHRS_ENABLED // and reset state estimators AP::ahrs().reset(); +#endif // stop flashing leds AP_Notify::flags.initialising = false; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp index 9ceb54c12d210a..3c45c611b1b3c4 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp @@ -218,7 +218,7 @@ void AP_InertialSensor_Backend::apply_gyro_filters(const uint8_t instance, const continue; } bool inactive = notch.is_inactive(); -#ifndef HAL_BUILD_AP_PERIPH +#if AP_AHRS_ENABLED // by default we only run the expensive notch filters on the // currently active IMU we reset the inactive notch filters so // that if we switch IMUs we're not left with old data @@ -442,8 +442,14 @@ void AP_InertialSensor_Backend::log_gyro_raw(uint8_t instance, const uint64_t sa return; } +#if AP_AHRS_ENABLED + const bool log_because_primary_gyro = _imu.raw_logging_option_set(AP_InertialSensor::RAW_LOGGING_OPTION::PRIMARY_GYRO_ONLY) && (instance == AP::ahrs().get_primary_gyro_index()); +#else + const bool log_because_primary_gyro = false; +#endif + if (_imu.raw_logging_option_set(AP_InertialSensor::RAW_LOGGING_OPTION::ALL_GYROS) || - (_imu.raw_logging_option_set(AP_InertialSensor::RAW_LOGGING_OPTION::PRIMARY_GYRO_ONLY) && (instance == AP::ahrs().get_primary_gyro_index())) || + log_because_primary_gyro || should_log_imu_raw()) { if (_imu.raw_logging_option_set(AP_InertialSensor::RAW_LOGGING_OPTION::PRE_AND_POST_FILTER)) { From 7b5a4d9f2c5ccf4f84baac762852ba55606a8127 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 11 Jan 2024 09:16:57 +1100 Subject: [PATCH 0566/1335] AP_LTM_Telem: correct compilation when AP_AHRS_ENABLED is off e.g. CubeOrange-periph-heavy --- libraries/AP_LTM_Telem/AP_LTM_Telem.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/libraries/AP_LTM_Telem/AP_LTM_Telem.cpp b/libraries/AP_LTM_Telem/AP_LTM_Telem.cpp index e6ad80edbf21d8..d4599d28d16fd4 100644 --- a/libraries/AP_LTM_Telem/AP_LTM_Telem.cpp +++ b/libraries/AP_LTM_Telem/AP_LTM_Telem.cpp @@ -70,6 +70,7 @@ void AP_LTM_Telem::send_Gframe(void) int32_t lon = 0; // longtitude uint8_t gndspeed = 0; // gps ground speed (m/s) int32_t alt = 0; +#if AP_AHRS_ENABLED { AP_AHRS &ahrs = AP::ahrs(); WITH_SEMAPHORE(ahrs.get_semaphore()); @@ -83,6 +84,7 @@ void AP_LTM_Telem::send_Gframe(void) gndspeed = (uint8_t) roundf(gps.ground_speed()); } } +#endif uint8_t lt_buff[LTM_GFRAME_SIZE]; // protocol: START(2 bytes)FRAMEID(1byte)LAT(cm,4 bytes)LON(cm,4bytes)SPEED(m/s,1bytes)ALT(cm,4bytes)SATS(6bits)FIX(2bits)CRC(xor,1byte) @@ -168,6 +170,7 @@ void AP_LTM_Telem::send_Aframe(void) int16_t pitch; int16_t roll; int16_t heading; +#if AP_AHRS_ENABLED { AP_AHRS &ahrs = AP::ahrs(); WITH_SEMAPHORE(ahrs.get_semaphore()); @@ -175,6 +178,11 @@ void AP_LTM_Telem::send_Aframe(void) roll = roundf(ahrs.roll_sensor * 0.01); // attitude roll in degrees heading = roundf(ahrs.yaw_sensor * 0.01); // heading in degrees } +#else + pitch = 0; + roll = 0; + heading = 0; +#endif uint8_t lt_buff[LTM_AFRAME_SIZE]; // A Frame: $T(2 bytes)A(1byte)PITCH(2 bytes)ROLL(2bytes)HEADING(2bytes)CRC(xor,1byte) From 7e0ea05ae9c5a6d8607e49d425bd8bd66c0ecda3 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 11 Jan 2024 09:16:57 +1100 Subject: [PATCH 0567/1335] AP_VisualOdom: correct compilation when AP_AHRS_ENABLED is off e.g. CubeOrange-periph-heavy --- libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp b/libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp index 5519f86d452d8c..568a4b6a0112d9 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp +++ b/libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp @@ -56,6 +56,7 @@ void AP_VisualOdom_Backend::handle_vision_position_delta_msg(const mavlink_messa // send to EKF const float time_delta_sec = packet.time_delta_usec * 1.0E-6; +#if AP_AHRS_ENABLED AP::ahrs().writeBodyFrameOdom(packet.confidence, position_delta, angle_delta, @@ -63,6 +64,7 @@ void AP_VisualOdom_Backend::handle_vision_position_delta_msg(const mavlink_messa now_ms, _frontend.get_delay_ms(), _frontend.get_pos_offset()); +#endif // log sensor data Write_VisualOdom(time_delta_sec, From 5b5ee4e95d964eaf3bc07c7b69fa04a39ff759e8 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 11 Jan 2024 09:16:57 +1100 Subject: [PATCH 0568/1335] GCS_MAVLink: correct compilation when AP_AHRS_ENABLED is off e.g. CubeOrange-periph-heavy --- libraries/GCS_MAVLink/GCS.cpp | 7 +++++- libraries/GCS_MAVLink/GCS_Common.cpp | 35 ++++++++++++++++++++++++++++ 2 files changed, 41 insertions(+), 1 deletion(-) diff --git a/libraries/GCS_MAVLink/GCS.cpp b/libraries/GCS_MAVLink/GCS.cpp index 0393f04930bb0a..f79133297f16ad 100644 --- a/libraries/GCS_MAVLink/GCS.cpp +++ b/libraries/GCS_MAVLink/GCS.cpp @@ -261,7 +261,7 @@ void GCS::update_sensor_status_flags() control_sensors_health |= MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS; #endif -#if CONFIG_HAL_BOARD == HAL_BOARD_SITL +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && AP_AHRS_ENABLED if (ahrs.get_ekf_type() == 10) { // always show EKF type 10 as healthy. This prevents spurious error // messages in xplane and other simulators that use EKF type 10 @@ -290,7 +290,12 @@ void GCS::update_sensor_status_flags() if (airspeed && airspeed->enabled()) { control_sensors_present |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE; const bool use = airspeed->use(); +#if AP_AHRS_ENABLED const bool enabled = AP::ahrs().airspeed_sensor_enabled(); +#else + const AP_Airspeed *_airspeed = AP::airspeed(); + const bool enabled = (_airspeed != nullptr && _airspeed->use()); +#endif if (use) { control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE; } diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 63e2424eb9539d..b5afa34ea05577 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -554,6 +554,7 @@ void GCS_MAVLINK::send_proximity() // report AHRS2 state void GCS_MAVLINK::send_ahrs2() { +#if AP_AHRS_ENABLED const AP_AHRS &ahrs = AP::ahrs(); Vector3f euler; Location loc {}; @@ -568,6 +569,7 @@ void GCS_MAVLINK::send_ahrs2() loc.lat, loc.lng); } +#endif } MissionItemProtocol *GCS::get_prot_for_mission_type(const MAV_MISSION_TYPE mission_type) const @@ -2191,6 +2193,7 @@ void GCS_MAVLINK::send_scaled_pressure3() void GCS_MAVLINK::send_ahrs() { +#if AP_AHRS_ENABLED const AP_AHRS &ahrs = AP::ahrs(); const Vector3f &omega_I = ahrs.get_gyro_drift(); mavlink_msg_ahrs_send( @@ -2202,6 +2205,7 @@ void GCS_MAVLINK::send_ahrs() 0, ahrs.get_error_rp(), ahrs.get_error_yaw()); +#endif } /* @@ -2752,6 +2756,7 @@ void GCS_MAVLINK::send_autopilot_version() const */ void GCS_MAVLINK::send_local_position() const { +#if AP_AHRS_ENABLED const AP_AHRS &ahrs = AP::ahrs(); Vector3f local_position, velocity; @@ -2770,6 +2775,7 @@ void GCS_MAVLINK::send_local_position() const velocity.x, velocity.y, velocity.z); +#endif } /* @@ -3134,11 +3140,13 @@ float GCS_MAVLINK::vfr_hud_airspeed() const float GCS_MAVLINK::vfr_hud_climbrate() const { +#if AP_AHRS_ENABLED Vector3f velned; if (AP::ahrs().get_velocity_NED(velned) || AP::ahrs().get_vert_pos_rate_D(velned.z)) { return -velned.z; } +#endif return 0; } @@ -3149,6 +3157,7 @@ float GCS_MAVLINK::vfr_hud_alt() const void GCS_MAVLINK::send_vfr_hud() { +#if AP_AHRS_ENABLED AP_AHRS &ahrs = AP::ahrs(); // return values ignored; we send stale data @@ -3162,6 +3171,7 @@ void GCS_MAVLINK::send_vfr_hud() abs(vfr_hud_throttle()), vfr_hud_alt(), vfr_hud_climbrate()); +#endif } /* @@ -3514,6 +3524,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_camera(const mavlink_command_int_t &packe #endif +#if AP_AHRS_ENABLED // sets ekf_origin if it has not been set. // should only be used when there is no GPS to provide an absolute position void GCS_MAVLINK::set_ekf_origin(const Location& loc) @@ -3561,6 +3572,7 @@ void GCS_MAVLINK::handle_set_gps_global_origin(const mavlink_message_t &msg) ekf_origin.alt = packet.altitude / 10; set_ekf_origin(ekf_origin); } +#endif // AP_AHRS_ENABLED /* handle a DATA96 message @@ -3931,9 +3943,11 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg) handle_common_param_message(msg); break; +#if AP_AHRS_ENABLED case MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN: handle_set_gps_global_origin(msg); break; +#endif #if AP_MAVLINK_MSG_DEVICE_OP_ENABLED case MAVLINK_MSG_ID_DEVICE_OP_READ: @@ -4448,9 +4462,11 @@ MAV_RESULT GCS_MAVLINK::_handle_command_preflight_calibration(const mavlink_comm #endif #if AP_INERTIALSENSOR_ENABLED +#if AP_AHRS_ENABLED if (packet.x == 2) { return AP::ins().calibrate_trim(); } +#endif if (packet.x == 4) { // simple accel calibration @@ -4623,6 +4639,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_debug_trap(const mavlink_command_int_t &p return MAV_RESULT_UNSUPPORTED; } +#if AP_AHRS_ENABLED MAV_RESULT GCS_MAVLINK::handle_command_set_ekf_source_set(const mavlink_command_int_t &packet) { // source set must be between 1 and 3 @@ -4634,6 +4651,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_set_ekf_source_set(const mavlink_command_ } return MAV_RESULT_DENIED; } +#endif #if AP_GRIPPER_ENABLED MAV_RESULT GCS_MAVLINK::handle_command_do_gripper(const mavlink_command_int_t &packet) @@ -5242,8 +5260,10 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_packet(const mavlink_command_int_t &p } #endif // AP_SCRIPTING_ENABLED +#if AP_AHRS_ENABLED case MAV_CMD_SET_EKF_SOURCE_SET: return handle_command_set_ekf_source_set(packet); +#endif case MAV_CMD_START_RX_PAIR: return handle_START_RX_PAIR(packet); @@ -5438,6 +5458,7 @@ void GCS_MAVLINK::send_extended_sys_state() const void GCS_MAVLINK::send_attitude() const { +#if AP_AHRS_ENABLED const AP_AHRS &ahrs = AP::ahrs(); const Vector3f omega = ahrs.get_gyro(); mavlink_msg_attitude_send( @@ -5449,10 +5470,12 @@ void GCS_MAVLINK::send_attitude() const omega.x, omega.y, omega.z); +#endif } void GCS_MAVLINK::send_attitude_quaternion() const { +#if AP_AHRS_ENABLED const AP_AHRS &ahrs = AP::ahrs(); Quaternion quat; if (!ahrs.get_quaternion(quat)) { @@ -5472,19 +5495,26 @@ void GCS_MAVLINK::send_attitude_quaternion() const omega.z, // yawspeed repr_offseq_q ); +#endif } int32_t GCS_MAVLINK::global_position_int_alt() const { return global_position_current_loc.alt * 10UL; } int32_t GCS_MAVLINK::global_position_int_relative_alt() const { +#if AP_AHRS_ENABLED float posD; AP::ahrs().get_relative_position_D_home(posD); posD *= -1000.0f; // change from down to up and metres to millimeters return posD; +#else + return 0; +#endif } + void GCS_MAVLINK::send_global_position_int() { +#if AP_AHRS_ENABLED AP_AHRS &ahrs = AP::ahrs(); UNUSED_RESULT(ahrs.get_location(global_position_current_loc)); // return value ignored; we send stale data @@ -5505,6 +5535,7 @@ void GCS_MAVLINK::send_global_position_int() vel.y * 100, // Y speed cm/s (+ve East) vel.z * 100, // Z speed cm/s (+ve Down) ahrs.yaw_sensor); // compass heading in 1/100 degree +#endif // AP_AHRS_ENABLED } #if HAL_MOUNT_ENABLED @@ -5802,10 +5833,12 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) #endif #endif // AP_BATTERY_ENABLED +#if AP_AHRS_ENABLED case MSG_EKF_STATUS_REPORT: CHECK_PAYLOAD_SIZE(EKF_STATUS_REPORT); AP::ahrs().send_ekf_status_report(*this); break; +#endif case MSG_MEMINFO: CHECK_PAYLOAD_SIZE(MEMINFO); @@ -6721,6 +6754,7 @@ GCS &gcs() #if HAL_HIGH_LATENCY2_ENABLED void GCS_MAVLINK::send_high_latency2() const { +#if AP_AHRS_ENABLED AP_AHRS &ahrs = AP::ahrs(); Location global_position_current; UNUSED_RESULT(ahrs.get_location(global_position_current)); @@ -6799,6 +6833,7 @@ void GCS_MAVLINK::send_high_latency2() const base_mode(), // Field for custom payload. base mode (arming status) in ArduPilot's case 0, // Field for custom payload. 0); // Field for custom payload. +#endif } int8_t GCS_MAVLINK::high_latency_air_temperature() const From b42138bfb682a9579305f3ab2919ec24e2aa4dbc Mon Sep 17 00:00:00 2001 From: Joshua Henderson Date: Tue, 16 Jan 2024 01:12:10 -0500 Subject: [PATCH 0569/1335] Tools : completion add submoduleclean & submodule_force_clean --- Tools/completion/bash/_waf | 2 ++ Tools/completion/zsh/_waf | 4 +++- 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/Tools/completion/bash/_waf b/Tools/completion/bash/_waf index 5eb71bd2e76cdd..a62a4a12510c61 100755 --- a/Tools/completion/bash/_waf +++ b/Tools/completion/bash/_waf @@ -31,6 +31,8 @@ _waf() opts+=" configure" opts+=" clean" opts+=" distclean" + opts+=" submodule_force_clean" + opts+=" submodulesync" # Prevent word reuse TODO: add -vvv case lim=$((COMP_CWORD - 1)) diff --git a/Tools/completion/zsh/_waf b/Tools/completion/zsh/_waf index e2d0ce6d632cb0..4b70537d005ba5 100644 --- a/Tools/completion/zsh/_waf +++ b/Tools/completion/zsh/_waf @@ -89,7 +89,9 @@ _waf_cmds() { 'build:executes the build' \ 'configure:configures the project' \ 'clean:cleans the project' \ - 'distclean:removes build folders and data' + 'distclean:removes build folders and data' \ + 'submodule_force_clean:removes all submodules, then checkouts all current submodules and synchronizes them' \ + 'submodulesync:checkouts all current submodules and synchronizes them' ) _describe -t commands 'command' commands "$@" && ret=0 } From f1ca5bea49cffef2feb1745ae0cec8834d330229 Mon Sep 17 00:00:00 2001 From: Joshua Henderson Date: Tue, 16 Jan 2024 01:17:00 -0500 Subject: [PATCH 0570/1335] waf : wscript add submoduleclean & submodule_force_clean --- BUILD.md | 5 +++++ wscript | 23 +++++++++++++++++++++++ 2 files changed, 28 insertions(+) diff --git a/BUILD.md b/BUILD.md index ae32c0a9107e7a..5e11d2c83808ee 100644 --- a/BUILD.md +++ b/BUILD.md @@ -102,6 +102,11 @@ list some basic and more used commands as example. Cleaning the build is very often not necessary and discouraged. We do incremental builds reducing the build time by orders of magnitude. + If submodules are failing to be synchronized, `submodulesync` may be used + to resync the submodules. This is usually necessary when shifting development + between stable releases or a stable release and the master branch. + + In some some cases `submodule_force_clean` may be necessary. This removes all submodules and then performs a `submodulesync`. (Note whitelisted modules like esp_idf is not removed.) * **Upload or install** diff --git a/wscript b/wscript index 8d2c2a68b2b299..c21a031e52f920 100644 --- a/wscript +++ b/wscript @@ -86,6 +86,29 @@ def _set_build_context_variant(board): continue c.variant = board +# Remove all submodules and then sync +@conf +def submodule_force_clean(ctx): + whitelist = { + 'COLCON_IGNORE', + 'esp_idf', + } + + # Get all items in the modules folder + module_list = os.scandir('modules') + + # Delete all directories except those in the whitelist + for module in module_list: + if (module.is_dir()) and (module.name not in whitelist): + shutil.rmtree(module) + + submodulesync(ctx) + +# run Tools/gittools/submodule-sync.sh to sync submodules +@conf +def submodulesync(ctx): + subprocess.call(['Tools/gittools/submodule-sync.sh']) + def init(ctx): # Generate Task List, so that VS Code extension can keep track # of changes to possible build targets From 94cc6fbe96fe067b432feb3f2fcd6ad6ea366602 Mon Sep 17 00:00:00 2001 From: Henry Wurzburg Date: Tue, 16 Jan 2024 16:17:32 -0600 Subject: [PATCH 0571/1335] RC_Channel:update aux switch name to RELAY1 --- libraries/RC_Channel/RC_Channel.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index f454515aefab8c..f3c6653f3478d9 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -131,7 +131,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = { // @Values{Copter}: 25:AttCon Feed Forward // @Values{Copter}: 26:AttCon Accel Limits // @Values{Copter, Rover, Plane}: 27:Retract Mount1 - // @Values{Copter, Rover, Plane}: 28:Relay On/Off + // @Values{Copter, Rover, Plane}: 28:Relay1 On/Off // @Values{Copter, Plane}: 29:Landing Gear // @Values{Copter}: 30:Lost Copter Sound // @Values{Rover}: 30:Lost Rover Sound From 4853ba632fab5e8503a3ff686c384e34086eb5a2 Mon Sep 17 00:00:00 2001 From: "Dr.-Ing. Amilcar do Carmo Lucas" Date: Mon, 15 Jan 2024 17:15:19 +0100 Subject: [PATCH 0572/1335] AC_AttitudeControl: Spell correction --- libraries/AC_AttitudeControl/ControlMonitor.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_AttitudeControl/ControlMonitor.cpp b/libraries/AC_AttitudeControl/ControlMonitor.cpp index 5efdb1606c56da..6bd67607358201 100644 --- a/libraries/AC_AttitudeControl/ControlMonitor.cpp +++ b/libraries/AC_AttitudeControl/ControlMonitor.cpp @@ -38,7 +38,7 @@ void AC_AttitudeControl::control_monitor_update(void) } /* - log a CRTL message + log a CTRL message */ void AC_AttitudeControl::control_monitor_log(void) const { From bfab6e5ee70444dd5c5b6a92f6a5c6c8638acc42 Mon Sep 17 00:00:00 2001 From: "Dr.-Ing. Amilcar do Carmo Lucas" Date: Mon, 15 Jan 2024 17:15:19 +0100 Subject: [PATCH 0573/1335] AP_BattMonitor: Spell correction --- libraries/AP_BattMonitor/AP_BattMonitor.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.cpp b/libraries/AP_BattMonitor/AP_BattMonitor.cpp index bf04aeb514aac4..e62ddc28b112cf 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor.cpp @@ -651,7 +651,7 @@ void AP_BattMonitor::convert_dynamic_param_groups(uint8_t instance) } } -// read - For all active instances read voltage & current; log BAT, BCL, POWR +// read - For all active instances read voltage & current; log BAT, BCL, POWR, MCU void AP_BattMonitor::read() { #if HAL_LOGGING_ENABLED From 413af641be20d289938949f917d235697f204c6a Mon Sep 17 00:00:00 2001 From: "Dr.-Ing. Amilcar do Carmo Lucas" Date: Mon, 15 Jan 2024 17:15:19 +0100 Subject: [PATCH 0574/1335] ArduCopter: Spell correction --- ArduCopter/system.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 4c740a2e3b3e1c..40c077fc627773 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -207,7 +207,7 @@ void Copter::init_ardupilot() motors->output_min(); // output lowest possible value to motors - // attempt to set the intial_mode, else set to STABILIZE + // attempt to set the initial_mode, else set to STABILIZE if (!set_mode((enum Mode::Number)g.initial_mode.get(), ModeReason::INITIALISED)) { // set mode to STABILIZE will trigger mode change notification to pilot set_mode(Mode::Number::STABILIZE, ModeReason::UNAVAILABLE); From 2564ca03e2f68d53ce441006561b266d55927aed Mon Sep 17 00:00:00 2001 From: "Dr.-Ing. Amilcar do Carmo Lucas" Date: Mon, 15 Jan 2024 17:15:19 +0100 Subject: [PATCH 0575/1335] Tools: Spell correction --- Tools/autotest/param_metadata/param_parse.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/autotest/param_metadata/param_parse.py b/Tools/autotest/param_metadata/param_parse.py index fdb1465e29cc4d..b76a23bf4b41ab 100755 --- a/Tools/autotest/param_metadata/param_parse.py +++ b/Tools/autotest/param_metadata/param_parse.py @@ -66,7 +66,7 @@ def find_vehicle_parameter_filepath(vehicle_name): "Sub": "ArduSub", } - # first try ArduCopter/Parmameters.cpp + # first try ArduCopter/Parameters.cpp for top_dir in apm_path, apm_tools_path: path = os.path.join(top_dir, vehicle_name, "Parameters.cpp") if os.path.exists(path): From 51ed5b8dd9c65a9ace01f635dff11a216f403968 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 16 Jan 2024 17:49:18 +1100 Subject: [PATCH 0576/1335] Tools: param_parse.py: remove xmlemit_mp this was used for a while to create xml files suitable for MissionPlanner toconsume. MissionPlanner now uses apm.pdef.xml --- Tools/autotest/param_metadata/param_parse.py | 4 +- Tools/autotest/param_metadata/xmlemit_mp.py | 91 -------------------- 2 files changed, 1 insertion(+), 94 deletions(-) delete mode 100644 Tools/autotest/param_metadata/xmlemit_mp.py diff --git a/Tools/autotest/param_metadata/param_parse.py b/Tools/autotest/param_metadata/param_parse.py index b76a23bf4b41ab..60466c75ec9234 100755 --- a/Tools/autotest/param_metadata/param_parse.py +++ b/Tools/autotest/param_metadata/param_parse.py @@ -22,7 +22,6 @@ from xmlemit import XmlEmit from mdemit import MDEmit from jsonemit import JSONEmit -from xmlemit_mp import XmlEmitMP parser = ArgumentParser(description="Parse ArduPilot parameters.") parser.add_argument("-v", "--verbose", dest='verbose', action='store_true', default=False, help="show debugging output") @@ -36,7 +35,7 @@ dest='output_format', action='store', default='all', - choices=['all', 'html', 'rst', 'rstlatexpdf', 'wiki', 'xml', 'json', 'edn', 'md', 'xml_mp'], + choices=['all', 'html', 'rst', 'rstlatexpdf', 'wiki', 'xml', 'json', 'edn', 'md'], help="what output format to use") args = parser.parse_args() @@ -631,7 +630,6 @@ def validate(param, is_library=False): 'rst': RSTEmit, 'rstlatexpdf': RSTLATEXPDFEmit, 'md': MDEmit, - 'xml_mp': XmlEmitMP, } try: diff --git a/Tools/autotest/param_metadata/xmlemit_mp.py b/Tools/autotest/param_metadata/xmlemit_mp.py deleted file mode 100644 index 846993ee59e67f..00000000000000 --- a/Tools/autotest/param_metadata/xmlemit_mp.py +++ /dev/null @@ -1,91 +0,0 @@ -from xml.sax.saxutils import escape, quoteattr - -from emit import Emit -from param import known_param_fields, known_units -from lxml import etree - -# Emit ArduPilot documentation in an machine readable XML format for Mission Planner -class XmlEmitMP(Emit): - def __init__(self, *args, **kwargs): - Emit.__init__(self, *args, **kwargs) - self.mp_fname = 'ParameterMetaData.xml' - self.f = open(self.mp_fname, mode='w') - self.preamble = '''\n''' - self.f.write(self.preamble) - self.f.write('\n') - self.gname = None - self.skip_name = False - - def close(self): - self.f.write(' \n' % self.gname) - self.f.write('''\n''') - self.f.close() - # sort and reformat XML - parser = etree.XMLParser(remove_blank_text=True) - tree = etree.parse(self.mp_fname, parser) - root = tree.getroot() - vehicle = tree.find(self.gname) - sort_xml_node(vehicle) - sorted_unicode = etree.tostring(root, pretty_print=True, encoding='unicode') - f = open(self.mp_fname, mode='w') - f.write(self.preamble) - f.write(sorted_unicode) - f.close() - - def emit_comment(self, s): - self.f.write("") - - def start_libraries(self): - self.skip_name = True - - def emit(self, g): - t = "" - if not self.skip_name: - self.gname = g.reference - if self.gname == "ArduCopter": - self.gname = "ArduCopter2" - if self.gname == "APMrover2" or self.gname == "Rover": - self.gname = "ArduRover" - t = ' <%s>\n' % self.gname - - for param in g.params: - # Begin our parameter node - # Get param name and and remove key - name = param.name.split(':')[-1] - - t += ' <%s>\n' % name - - if hasattr(param, 'DisplayName'): - t += ' %s\n' % param.DisplayName - - if hasattr(param, 'Description'): - t += ' %s\n' % escape(param.Description) # i.e. parameter docs - if hasattr(param, 'User'): - t += ' %s\n' % param.User # i.e. Standard or Advanced - - # not used yet - # if hasattr(param, 'Calibration'): - # t += ' %s Date: Tue, 16 Jan 2024 17:50:25 +1100 Subject: [PATCH 0577/1335] Tools: remove script which generates MissionPlanner-style xml files it now uses apm.pdef.xml --- Tools/scripts/generate_mp_paramfile.sh | 45 -------------------------- 1 file changed, 45 deletions(-) delete mode 100755 Tools/scripts/generate_mp_paramfile.sh diff --git a/Tools/scripts/generate_mp_paramfile.sh b/Tools/scripts/generate_mp_paramfile.sh deleted file mode 100755 index 753d14bff6c891..00000000000000 --- a/Tools/scripts/generate_mp_paramfile.sh +++ /dev/null @@ -1,45 +0,0 @@ -#!/usr/bin/env bash - -set -e -set -x - -echo "Remove previous param file" -rm -f ParameterMetaDataBackup.xml -rm -f ParameterMetaData.xml - -echo "Create first parameter file" -./Tools/autotest/param_metadata/param_parse.py --vehicle ArduCopter --format xml_mp -echo "Remove the last line" -sed -i -e '$d' ParameterMetaData.xml -echo "Copy parameters to the complete file" -cp ParameterMetaData.xml ParameterMetaDataBackup.xml - -echo "Create the second parameter file" -./Tools/autotest/param_metadata/param_parse.py --vehicle ArduPlane --format xml_mp -echo "Remove the two first lines and the last one" -sed -i -e '1d' -e '2d' -e '$d' ParameterMetaData.xml -echo "Append parameters to the complete file" -cat ParameterMetaData.xml >> ParameterMetaDataBackup.xml - -./Tools/autotest/param_metadata/param_parse.py --vehicle Rover --format xml_mp -echo "Remove the two first lines and the last one" -sed -i -e '1d' -e '2d' -e '$d' ParameterMetaData.xml -echo "Append parameters to the complete file" -cat ParameterMetaData.xml >> ParameterMetaDataBackup.xml - -./Tools/autotest/param_metadata/param_parse.py --vehicle ArduSub --format xml_mp -echo "Remove the two first lines and the last one" -sed -i -e '1d' -e '2d' -e '$d' ParameterMetaData.xml -echo "Append parameters to the complete file" -cat ParameterMetaData.xml >> ParameterMetaDataBackup.xml - -./Tools/autotest/param_metadata/param_parse.py --vehicle AntennaTracker --format xml_mp -echo "Remove the two first lines" -sed -i -e '1d' -e '2d' ParameterMetaData.xml -echo "Append parameters to the complete file" -cat ParameterMetaData.xml >> ParameterMetaDataBackup.xml - -echo "Remove vehile param file" -rm -f ParameterMetaData.xml -echo "Rename complete param file" -mv ParameterMetaDataBackup.xml ParameterMetaData.xml From 0850a5fa43652bd7590594081946023ff7850b17 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 28 Nov 2023 12:13:11 +1100 Subject: [PATCH 0578/1335] AP_AHRS: create and use an AP_AHRS_EXTERNAL_ENABLED --- libraries/AP_AHRS/AP_AHRS.cpp | 126 ++++++++++++------------- libraries/AP_AHRS/AP_AHRS.h | 6 +- libraries/AP_AHRS/AP_AHRS_External.cpp | 2 +- libraries/AP_AHRS/AP_AHRS_External.h | 6 +- libraries/AP_AHRS/AP_AHRS_config.h | 5 + 5 files changed, 76 insertions(+), 69 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index 6be34de803c212..f77ea3551c1c79 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -252,7 +252,7 @@ void AP_AHRS::init() #if AP_AHRS_DCM_ENABLED dcm.init(); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED external.init(); #endif @@ -321,7 +321,7 @@ void AP_AHRS::reset_gyro_drift(void) #if AP_AHRS_DCM_ENABLED dcm.reset_gyro_drift(); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED external.reset_gyro_drift(); #endif @@ -400,7 +400,7 @@ void AP_AHRS::update(bool skip_ins_update) update_SITL(); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED update_external(); #endif @@ -458,7 +458,7 @@ void AP_AHRS::update(bool skip_ins_update) shortname = "SIM"; break; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: shortname = "External"; break; @@ -685,7 +685,7 @@ void AP_AHRS::update_EKF3(void) } #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED void AP_AHRS::update_external(void) { external.update(); @@ -695,7 +695,7 @@ void AP_AHRS::update_external(void) copy_estimates_from_backend_estimates(external_estimates); } } -#endif // HAL_EXTERNAL_AHRS_ENABLED +#endif // AP_AHRS_EXTERNAL_ENABLED void AP_AHRS::reset() { @@ -709,7 +709,7 @@ void AP_AHRS::reset() sim.reset(); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED external.reset(); #endif @@ -754,7 +754,7 @@ bool AP_AHRS::_get_location(Location &loc) const return sim_estimates.get_location(loc); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return external_estimates.get_location(loc); #endif @@ -812,7 +812,7 @@ bool AP_AHRS::_wind_estimate(Vector3f &wind) const return EKF3.getWind(wind); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return external.wind_estimate(wind); #endif @@ -942,7 +942,7 @@ bool AP_AHRS::_airspeed_estimate(float &airspeed_ret, AirspeedEstimateType &airs break; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: #if AP_AHRS_DCM_ENABLED airspeed_estimate_type = AirspeedEstimateType::DCM_SYNTHETIC; @@ -996,7 +996,7 @@ bool AP_AHRS::_airspeed_estimate_true(float &airspeed_ret) const #if AP_AHRS_SIM_ENABLED case EKFType::SIM: #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: #endif break; @@ -1033,7 +1033,7 @@ bool AP_AHRS::_airspeed_vector_true(Vector3f &vec) const break; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: break; #endif @@ -1065,7 +1065,7 @@ bool AP_AHRS::airspeed_health_data(float &innovation, float &innovationVariance, break; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: break; #endif @@ -1108,7 +1108,7 @@ bool AP_AHRS::use_compass(void) return sim.use_compass(); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: break; #endif @@ -1155,7 +1155,7 @@ bool AP_AHRS::_get_quaternion(Quaternion &quat) const } break; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: // we assume the external AHRS isn't trimmed with the autopilot! return external.get_quaternion(quat); @@ -1206,7 +1206,7 @@ bool AP_AHRS::_get_secondary_attitude(Vector3f &eulers) const return false; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: { // External is secondary eulers[0] = external_estimates.roll_rad; @@ -1267,7 +1267,7 @@ bool AP_AHRS::_get_secondary_quaternion(Quaternion &quat) const return false; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: // External is secondary return external.get_quaternion(quat); @@ -1319,7 +1319,7 @@ bool AP_AHRS::_get_secondary_position(Location &loc) const return false; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: // External is secondary return external_estimates.get_location(loc); @@ -1359,7 +1359,7 @@ Vector2f AP_AHRS::_groundspeed_vector(void) case EKFType::SIM: return sim.groundspeed_vector(); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: { return external.groundspeed_vector(); } @@ -1383,7 +1383,7 @@ float AP_AHRS::_groundspeed(void) case EKFType::THREE: #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: #endif @@ -1431,7 +1431,7 @@ bool AP_AHRS::set_origin(const Location &loc) // simulation backend return false; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: // don't allow origin set with external AHRS return false; @@ -1485,7 +1485,7 @@ bool AP_AHRS::_get_velocity_NED(Vector3f &vec) const case EKFType::SIM: return sim.get_velocity_NED(vec); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return external.get_velocity_NED(vec); #endif @@ -1520,7 +1520,7 @@ bool AP_AHRS::get_mag_field_NED(Vector3f &vec) const case EKFType::SIM: return false; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return false; #endif @@ -1552,7 +1552,7 @@ bool AP_AHRS::get_mag_field_correction(Vector3f &vec) const case EKFType::SIM: return false; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return false; #endif @@ -1587,7 +1587,7 @@ bool AP_AHRS::get_vert_pos_rate_D(float &velocity) const case EKFType::SIM: return sim.get_vert_pos_rate_D(velocity); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return external.get_vert_pos_rate_D(velocity); #endif @@ -1618,7 +1618,7 @@ bool AP_AHRS::get_hagl(float &height) const case EKFType::SIM: return sim.get_hagl(height); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: { return false; } @@ -1672,7 +1672,7 @@ bool AP_AHRS::get_relative_position_NED_origin(Vector3f &vec) const case EKFType::SIM: return sim.get_relative_position_NED_origin(vec); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: { return external.get_relative_position_NED_origin(vec); } @@ -1725,7 +1725,7 @@ bool AP_AHRS::get_relative_position_NE_origin(Vector2f &posNE) const return sim.get_relative_position_NE_origin(posNE); } #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return external.get_relative_position_NE_origin(posNE); #endif @@ -1780,7 +1780,7 @@ bool AP_AHRS::get_relative_position_D_origin(float &posD) const case EKFType::SIM: return sim.get_relative_position_D_origin(posD); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return external.get_relative_position_D_origin(posD); #endif @@ -1832,7 +1832,7 @@ AP_AHRS::EKFType AP_AHRS::ekf_type(void) const case EKFType::SIM: return type; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return type; #endif @@ -1923,7 +1923,7 @@ AP_AHRS::EKFType AP_AHRS::_active_EKF_type(void) const ret = EKFType::SIM; break; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: ret = EKFType::EXTERNAL; break; @@ -1957,7 +1957,7 @@ AP_AHRS::EKFType AP_AHRS::_active_EKF_type(void) const get_filter_status(filt_state); break; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: get_filter_status(filt_state); should_use_gps = true; @@ -2053,7 +2053,7 @@ AP_AHRS::EKFType AP_AHRS::fallback_active_EKF_type(void) const } #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED if (external.healthy()) { return EKFType::EXTERNAL; } @@ -2064,7 +2064,7 @@ AP_AHRS::EKFType AP_AHRS::fallback_active_EKF_type(void) const return EKFType::THREE; #elif HAL_NAVEKF2_AVAILABLE return EKFType::TWO; -#elif HAL_EXTERNAL_AHRS_ENABLED +#elif AP_AHRS_EXTERNAL_ENABLED return EKFType::EXTERNAL; #endif } @@ -2089,7 +2089,7 @@ bool AP_AHRS::_get_secondary_EKF_type(EKFType &secondary_ekf_type) const return true; } #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED if ((EKFType)_ekf_type.get() == EKFType::EXTERNAL) { secondary_ekf_type = EKFType::EXTERNAL; return true; @@ -2106,7 +2106,7 @@ bool AP_AHRS::_get_secondary_EKF_type(EKFType &secondary_ekf_type) const #if AP_AHRS_SIM_ENABLED case EKFType::SIM: #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: #endif // DCM is secondary @@ -2171,7 +2171,7 @@ bool AP_AHRS::healthy(void) const case EKFType::SIM: return sim.healthy(); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return external.healthy(); #endif @@ -2192,7 +2192,7 @@ bool AP_AHRS::pre_arm_check(bool requires_position, char *failure_msg, uint8_t f ret = false; } -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED // Always check external AHRS if enabled // it is a source for IMU data even if not being used as direct AHRS replacement if (AP::externalAHRS().enabled() || (ekf_type() == EKFType::EXTERNAL)) { @@ -2223,7 +2223,7 @@ bool AP_AHRS::pre_arm_check(bool requires_position, char *failure_msg, uint8_t f return dcm.pre_arm_check(requires_position, failure_msg, failure_msg_len) && ret; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return external.pre_arm_check(requires_position, failure_msg, failure_msg_len); #endif @@ -2277,7 +2277,7 @@ bool AP_AHRS::initialised(void) const case EKFType::SIM: return true; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return external.initialised(); #endif @@ -2310,7 +2310,7 @@ bool AP_AHRS::get_filter_status(nav_filter_status &status) const case EKFType::SIM: return sim.get_filter_status(status); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return external.get_filter_status(status); #endif @@ -2407,7 +2407,7 @@ void AP_AHRS::getControlLimits(float &ekfGndSpdLimit, float &ekfNavVelGainScaler sim.get_control_limits(ekfGndSpdLimit, ekfNavVelGainScaler); break; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: // no limit on gains, large vel limit ekfGndSpdLimit = 400; @@ -2455,7 +2455,7 @@ bool AP_AHRS::getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const case EKFType::SIM: return sim.get_mag_offsets(mag_idx, magOffsets); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return false; #endif @@ -2490,7 +2490,7 @@ void AP_AHRS::_getCorrectedDeltaVelocityNED(Vector3f& ret, float& dt) const case EKFType::SIM: break; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: break; #endif @@ -2634,7 +2634,7 @@ uint32_t AP_AHRS::getLastYawResetAngle(float &yawAng) case EKFType::SIM: return sim.getLastYawResetAngle(yawAng); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return external.getLastYawResetAngle(yawAng); #endif @@ -2667,7 +2667,7 @@ uint32_t AP_AHRS::getLastPosNorthEastReset(Vector2f &pos) case EKFType::SIM: return sim.getLastPosNorthEastReset(pos); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return 0; #endif @@ -2700,7 +2700,7 @@ uint32_t AP_AHRS::getLastVelNorthEastReset(Vector2f &vel) const case EKFType::SIM: return sim.getLastVelNorthEastReset(vel); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return 0; #endif @@ -2733,7 +2733,7 @@ uint32_t AP_AHRS::getLastPosDownReset(float &posDelta) case EKFType::SIM: return sim.getLastPosDownReset(posDelta); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return 0; #endif @@ -2784,7 +2784,7 @@ bool AP_AHRS::resetHeightDatum(void) case EKFType::SIM: return sim.resetHeightDatum(); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return false; #endif @@ -2808,7 +2808,7 @@ void AP_AHRS::send_ekf_status_report(GCS_MAVLINK &link) const break; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: { external.send_ekf_status_report(link); break; @@ -2851,7 +2851,7 @@ bool AP_AHRS::_get_origin(EKFType type, Location &ret) const case EKFType::SIM: return sim.get_origin(ret); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return external.get_origin(ret); #endif @@ -2960,7 +2960,7 @@ bool AP_AHRS::get_hgt_ctrl_limit(float& limit) const case EKFType::SIM: return sim.get_hgt_ctrl_limit(limit); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return false; #endif @@ -3027,7 +3027,7 @@ bool AP_AHRS::get_innovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f & return sim.get_innovations(velInnov, posInnov, magInnov, tasInnov, yawInnov); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return false; #endif @@ -3053,7 +3053,7 @@ bool AP_AHRS::is_vibration_affected() const #if AP_AHRS_SIM_ENABLED case EKFType::SIM: #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: #endif return false; @@ -3095,7 +3095,7 @@ bool AP_AHRS::get_variances(float &velVar, float &posVar, float &hgtVar, Vector3 return sim.get_variances(velVar, posVar, hgtVar, magVar, tasVar); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return false; #endif @@ -3133,7 +3133,7 @@ bool AP_AHRS::get_vel_innovations_and_variances_for_source(uint8_t source, Vecto return false; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: return false; #endif @@ -3194,7 +3194,7 @@ uint8_t AP_AHRS::_get_primary_IMU_index() const case EKFType::SIM: break; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: break; #endif @@ -3219,7 +3219,7 @@ int8_t AP_AHRS::_get_primary_core_index() const // we have only one core return 0; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: // we have only one core return 0; @@ -3267,7 +3267,7 @@ void AP_AHRS::check_lane_switch(void) break; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: break; #endif @@ -3299,7 +3299,7 @@ void AP_AHRS::request_yaw_reset(void) break; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: break; #endif @@ -3371,7 +3371,7 @@ bool AP_AHRS::using_noncompass_for_yaw(void) const #if AP_AHRS_SIM_ENABLED case EKFType::SIM: #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: #endif return false; @@ -3398,7 +3398,7 @@ bool AP_AHRS::using_extnav_for_yaw(void) const #if AP_AHRS_SIM_ENABLED case EKFType::SIM: #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: #endif return false; @@ -3441,7 +3441,7 @@ const EKFGSF_yaw *AP_AHRS::get_yaw_estimator(void) const #if AP_AHRS_SIM_ENABLED case EKFType::SIM: #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED case EKFType::EXTERNAL: #endif return nullptr; diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index abb36f2e13692b..a4bd0c3979d4f8 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -443,7 +443,7 @@ class AP_AHRS { #if AP_AHRS_SIM_ENABLED SIM = 10, #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED EXTERNAL = 11, #endif }; @@ -800,7 +800,7 @@ class AP_AHRS { void update_SITL(void); #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED void update_external(void); #endif @@ -1002,7 +1002,7 @@ class AP_AHRS { struct AP_AHRS_Backend::Estimates sim_estimates; #endif -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED AP_AHRS_External external; struct AP_AHRS_Backend::Estimates external_estimates; #endif diff --git a/libraries/AP_AHRS/AP_AHRS_External.cpp b/libraries/AP_AHRS/AP_AHRS_External.cpp index 0c4be3d5bd614e..8cdf8ecb52bb03 100644 --- a/libraries/AP_AHRS/AP_AHRS_External.cpp +++ b/libraries/AP_AHRS/AP_AHRS_External.cpp @@ -1,6 +1,6 @@ #include "AP_AHRS_External.h" -#if HAL_EXTERNAL_AHRS_ENABLED +#if AP_AHRS_EXTERNAL_ENABLED #include #include diff --git a/libraries/AP_AHRS/AP_AHRS_External.h b/libraries/AP_AHRS/AP_AHRS_External.h index 4d63a0702907de..6ca69f73f8f4ac 100644 --- a/libraries/AP_AHRS/AP_AHRS_External.h +++ b/libraries/AP_AHRS/AP_AHRS_External.h @@ -21,9 +21,11 @@ * */ -#include "AP_AHRS_Backend.h" +#include "AP_AHRS_config.h" + +#if AP_AHRS_EXTERNAL_ENABLED -#if HAL_EXTERNAL_AHRS_ENABLED +#include "AP_AHRS_Backend.h" class AP_AHRS_External : public AP_AHRS_Backend { public: diff --git a/libraries/AP_AHRS/AP_AHRS_config.h b/libraries/AP_AHRS/AP_AHRS_config.h index fd56a5f6deabf8..3b27e786065181 100644 --- a/libraries/AP_AHRS/AP_AHRS_config.h +++ b/libraries/AP_AHRS/AP_AHRS_config.h @@ -2,6 +2,7 @@ #include #include +#include #ifndef AP_AHRS_ENABLED #define AP_AHRS_ENABLED 1 @@ -15,6 +16,10 @@ #define AP_AHRS_DCM_ENABLED AP_AHRS_BACKEND_DEFAULT_ENABLED && AP_INERTIALSENSOR_ENABLED #endif +#ifndef AP_AHRS_EXTERNAL_ENABLED +#define AP_AHRS_EXTERNAL_ENABLED AP_AHRS_BACKEND_DEFAULT_ENABLED && HAL_EXTERNAL_AHRS_ENABLED +#endif + #ifndef HAL_NAVEKF2_AVAILABLE // EKF2 slated compiled out by default in 4.5, slated to be removed. #define HAL_NAVEKF2_AVAILABLE 0 From d7fa5a47def67a7551e6a9f2b895bfa8877e60d5 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 28 Nov 2023 13:09:41 +1100 Subject: [PATCH 0579/1335] AP_AHRS: add missing include for GPSUse --- libraries/AP_AHRS/AP_AHRS.h | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index a4bd0c3979d4f8..31130035514442 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -25,6 +25,7 @@ #include +#include "AP_AHRS_Backend.h" #include #include #include // definitions shared by inertial and ekf nav filters From 29f1953ad7c557f1bd1692e4284a021bdc30bf3e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 11 Jan 2024 18:54:04 +1100 Subject: [PATCH 0580/1335] AP_HAL_ChibiOS: remove bad default from kha_eth hwdef off is the default, but you have to use 0 not FALSE or it's a redefinition error --- libraries/AP_HAL_ChibiOS/hwdef/kha_eth/hwdef.dat | 1 - 1 file changed, 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/kha_eth/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/kha_eth/hwdef.dat index 72def407252939..fa1157f699a4f5 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/kha_eth/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/kha_eth/hwdef.dat @@ -140,7 +140,6 @@ define HAL_PERIPH_SHOW_SERIAL_MANAGER_PARAMS define PERIPH_FW TRUE #define NO_DATAFLASH TRUE -define HAL_LOGGING_ENABLED FALSE ################################# # AP_Periph - configurations specific to this App From 2359ffc7da2794c831f7165442e8f38ef5cf47de Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:03 +1000 Subject: [PATCH 0581/1335] AC_AttitudeControl: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AC_AttitudeControl/AC_PosControl.cpp | 2 ++ libraries/AC_AttitudeControl/ControlMonitor.cpp | 2 ++ 2 files changed, 4 insertions(+) diff --git a/libraries/AC_AttitudeControl/AC_PosControl.cpp b/libraries/AC_AttitudeControl/AC_PosControl.cpp index 282237fb3a961d..e82241ab3c5d45 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -1160,6 +1160,7 @@ void AC_PosControl::standby_xyz_reset() init_ekf_xy_reset(); } +#if HAL_LOGGING_ENABLED // write PSC and/or PSCZ logs void AC_PosControl::write_log() { @@ -1180,6 +1181,7 @@ void AC_PosControl::write_log() -_accel_desired.z, -get_accel_target_cmss().z, -get_z_accel_cmss()); } } +#endif // HAL_LOGGING_ENABLED /// crosstrack_error - returns horizontal error to the closest point to the current track float AC_PosControl::crosstrack_error() const diff --git a/libraries/AC_AttitudeControl/ControlMonitor.cpp b/libraries/AC_AttitudeControl/ControlMonitor.cpp index 6bd67607358201..1535a9f273a376 100644 --- a/libraries/AC_AttitudeControl/ControlMonitor.cpp +++ b/libraries/AC_AttitudeControl/ControlMonitor.cpp @@ -37,6 +37,7 @@ void AC_AttitudeControl::control_monitor_update(void) control_monitor_filter_pid(iyaw.P + iyaw.D + iyaw.FF, _control_monitor.rms_yaw); } +#if HAL_LOGGING_ENABLED /* log a CTRL message */ @@ -59,6 +60,7 @@ void AC_AttitudeControl::control_monitor_log(void) const (double)safe_sqrt(_control_monitor.rms_yaw)); } +#endif // HAL_LOGGING_ENABLED /* return current controller RMS filter value for roll From 65baf8abc794266068a2e2bd750e07debcc3901b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:04 +1000 Subject: [PATCH 0582/1335] AC_Autorotation: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AC_Autorotation/AC_Autorotation.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/libraries/AC_Autorotation/AC_Autorotation.cpp b/libraries/AC_Autorotation/AC_Autorotation.cpp index 7ce790517d942b..627dd7894ec317 100644 --- a/libraries/AC_Autorotation/AC_Autorotation.cpp +++ b/libraries/AC_Autorotation/AC_Autorotation.cpp @@ -252,6 +252,7 @@ float AC_Autorotation::get_rpm(bool update_counter) } +#if HAL_LOGGING_ENABLED void AC_Autorotation::Log_Write_Autorotation(void) const { // @LoggerMessage: AROT @@ -289,7 +290,7 @@ void AC_Autorotation::Log_Write_Autorotation(void) const (double)_accel_target, (double)_pitch_target); } - +#endif // HAL_LOGGING_ENABLED // Initialise forward speed controller void AC_Autorotation::init_fwd_spd_controller(void) From 2eede45f3ad138820750ff421937fdb3e5f114c5 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:04 +1000 Subject: [PATCH 0583/1335] AC_AutoTune: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AC_AutoTune/AC_AutoTune.cpp | 13 ++++++--- libraries/AC_AutoTune/AC_AutoTune.h | 5 ++++ libraries/AC_AutoTune/AC_AutoTune_Heli.cpp | 20 ++++++++------ libraries/AC_AutoTune/AC_AutoTune_Heli.h | 2 ++ libraries/AC_AutoTune/AC_AutoTune_Multi.cpp | 30 +++++++++++---------- libraries/AC_AutoTune/AC_AutoTune_Multi.h | 2 ++ 6 files changed, 46 insertions(+), 26 deletions(-) diff --git a/libraries/AC_AutoTune/AC_AutoTune.cpp b/libraries/AC_AutoTune/AC_AutoTune.cpp index 3c081f31488f11..998297d0219877 100644 --- a/libraries/AC_AutoTune/AC_AutoTune.cpp +++ b/libraries/AC_AutoTune/AC_AutoTune.cpp @@ -75,7 +75,7 @@ bool AC_AutoTune::init_internals(bool _use_poshold, level_start_time_ms = step_start_time_ms; // reset gains to tuning-start gains (i.e. low I term) load_gains(GAIN_INTRA_TEST); - AP::logger().Write_Event(LogEvent::AUTOTUNE_RESTART); + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_RESTART); update_gcs(AUTOTUNE_MESSAGE_STARTED); break; @@ -83,7 +83,7 @@ bool AC_AutoTune::init_internals(bool _use_poshold, // we have completed a tune and the pilot wishes to test the new gains load_gains(GAIN_TUNED); update_gcs(AUTOTUNE_MESSAGE_TESTING); - AP::logger().Write_Event(LogEvent::AUTOTUNE_PILOT_TESTING); + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_PILOT_TESTING); break; } @@ -102,7 +102,8 @@ void AC_AutoTune::stop() attitude_control->use_sqrt_controller(true); update_gcs(AUTOTUNE_MESSAGE_STOPPED); - AP::logger().Write_Event(LogEvent::AUTOTUNE_OFF); + + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_OFF); // Note: we leave the mode as it was so that we know how the autotune ended // we expect the caller will change the flight mode back to the flight mode indicated by the flight mode switch @@ -400,10 +401,12 @@ void AC_AutoTune::control_attitude() step = WAITING_FOR_LEVEL; } +#if HAL_LOGGING_ENABLED // log this iterations lean angle and rotation rate Log_AutoTuneDetails(); ahrs_view->Write_Rate(*motors, *attitude_control, *pos_control); log_pids(); +#endif break; } @@ -412,8 +415,10 @@ void AC_AutoTune::control_attitude() // re-enable rate limits attitude_control->use_sqrt_controller(true); +#if HAL_LOGGING_ENABLED // log the latest gains Log_AutoTune(); +#endif // Announce tune type test results // must be done before updating method because this method changes parameters for next test @@ -519,7 +524,7 @@ void AC_AutoTune::control_attitude() if (complete) { mode = SUCCESS; update_gcs(AUTOTUNE_MESSAGE_SUCCESS); - AP::logger().Write_Event(LogEvent::AUTOTUNE_SUCCESS); + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_SUCCESS); AP_Notify::events.autotune_complete = true; } else { AP_Notify::events.autotune_next_axis = true; diff --git a/libraries/AC_AutoTune/AC_AutoTune.h b/libraries/AC_AutoTune/AC_AutoTune.h index a901b50e06b692..4c2198c11ac88c 100644 --- a/libraries/AC_AutoTune/AC_AutoTune.h +++ b/libraries/AC_AutoTune/AC_AutoTune.h @@ -92,8 +92,10 @@ class AC_AutoTune // init pos controller Z velocity and accel limits virtual void init_z_limits() = 0; +#if HAL_LOGGING_ENABLED // log PIDs at full rate for during twitch virtual void log_pids() = 0; +#endif // // methods to load and save gains @@ -151,9 +153,12 @@ class AC_AutoTune // reverse direction for twitch test virtual bool twitch_reverse_direction() = 0; + +#if HAL_LOGGING_ENABLED virtual void Log_AutoTune() = 0; virtual void Log_AutoTuneDetails() = 0; virtual void Log_AutoTuneSweep() = 0; +#endif // internal init function, should be called from init() bool init_internals(bool use_poshold, diff --git a/libraries/AC_AutoTune/AC_AutoTune_Heli.cpp b/libraries/AC_AutoTune/AC_AutoTune_Heli.cpp index 0defc67f671503..0f972a48938076 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_Heli.cpp +++ b/libraries/AC_AutoTune/AC_AutoTune_Heli.cpp @@ -250,12 +250,12 @@ void AC_AutoTune_Heli::test_run(AxisType test_axis, const float dir_sign) if ((tune_type == RP_UP || tune_type == RD_UP) && (max_rate_p.max_allowed <= 0.0f || max_rate_d.max_allowed <= 0.0f)) { gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: Max Gain Determination Failed"); mode = FAILED; - AP::logger().Write_Event(LogEvent::AUTOTUNE_FAILED); + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_FAILED); update_gcs(AUTOTUNE_MESSAGE_FAILED); } else if ((tune_type == MAX_GAINS || tune_type == RP_UP || tune_type == RD_UP || tune_type == SP_UP) && exceeded_freq_range(start_freq)){ gcs().send_text(MAV_SEVERITY_INFO, "AutoTune: Exceeded frequency range"); mode = FAILED; - AP::logger().Write_Event(LogEvent::AUTOTUNE_FAILED); + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_FAILED); update_gcs(AUTOTUNE_MESSAGE_FAILED); } else if (tune_type == TUNE_COMPLETE) { counter = AUTOTUNE_SUCCESS_COUNT; @@ -442,7 +442,7 @@ void AC_AutoTune_Heli::backup_gains_and_initialise() tune_yaw_sp = attitude_control->get_angle_yaw_p().kP(); tune_yaw_accel = attitude_control->get_accel_yaw_max_cdss(); - AP::logger().Write_Event(LogEvent::AUTOTUNE_INITIALISED); + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_INITIALISED); } // load_orig_gains - set gains to their original values @@ -660,7 +660,7 @@ void AC_AutoTune_Heli::save_tuning_gains() // update GCS and log save gains event update_gcs(AUTOTUNE_MESSAGE_SAVED_GAINS); - AP::logger().Write_Event(LogEvent::AUTOTUNE_SAVEDGAINS); + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_SAVEDGAINS); reset(); } @@ -1166,8 +1166,10 @@ void AC_AutoTune_Heli::dwell_test_run(uint8_t freq_resp_input, float start_frq, if (dwell_type == DRB) {test_accel_max = freqresp.get_accel_max();} // reset cycle_complete to allow indication of next cycle freqresp.reset_cycle_complete(); +#if HAL_LOGGING_ENABLED // log sweep data Log_AutoTuneSweep(); +#endif } else { dwell_gain = freqresp.get_gain(); dwell_phase = freqresp.get_phase(); @@ -1383,14 +1385,14 @@ void AC_AutoTune_Heli::updating_rate_ff_up(float &tune_ff, float rate_target, fl if (tune_ff <= AUTOTUNE_RFF_MIN) { tune_ff = AUTOTUNE_RFF_MIN; counter = AUTOTUNE_SUCCESS_COUNT; - AP::logger().Write_Event(LogEvent::AUTOTUNE_REACHED_LIMIT); + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT); } } else if (is_positive(rate_target * meas_rate) && fabsf(meas_rate) < 0.95f * fabsf(rate_target)) { tune_ff = 1.02f * tune_ff; if (tune_ff >= AUTOTUNE_RFF_MAX) { tune_ff = AUTOTUNE_RFF_MAX; counter = AUTOTUNE_SUCCESS_COUNT; - AP::logger().Write_Event(LogEvent::AUTOTUNE_REACHED_LIMIT); + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT); } } else { if (!is_zero(meas_rate)) { @@ -1547,7 +1549,7 @@ void AC_AutoTune_Heli::updating_angle_p_up(float &tune_p, float *freq, float *ga // exceeded max response gain at the minimum allowable tuning gain. terminate testing. tune_p = AUTOTUNE_SP_MIN; counter = AUTOTUNE_SUCCESS_COUNT; - AP::logger().Write_Event(LogEvent::AUTOTUNE_REACHED_LIMIT); + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT); } else if (gain[freq_cnt] > gain[freq_cnt_max]) { freq_cnt_max = freq_cnt; phase_max = phase[freq_cnt]; @@ -1579,7 +1581,7 @@ void AC_AutoTune_Heli::updating_angle_p_up(float &tune_p, float *freq, float *ga if (tune_p >= AUTOTUNE_SP_MAX) { tune_p = AUTOTUNE_SP_MAX; counter = AUTOTUNE_SUCCESS_COUNT; - AP::logger().Write_Event(LogEvent::AUTOTUNE_REACHED_LIMIT); + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT); } } curr_test.freq = freq[freq_cnt]; @@ -1722,6 +1724,7 @@ void AC_AutoTune_Heli::updating_max_gains(float *freq, float *gain, float *phase } +#if HAL_LOGGING_ENABLED // log autotune summary data void AC_AutoTune_Heli::Log_AutoTune() { @@ -1840,6 +1843,7 @@ void AC_AutoTune_Heli::Log_Write_AutoTuneSweep(float freq, float gain, float pha gain, phase); } +#endif // HAL_LOGGING_ENABLED // reset the test variables for each vehicle void AC_AutoTune_Heli::reset_vehicle_test_variables() diff --git a/libraries/AC_AutoTune/AC_AutoTune_Heli.h b/libraries/AC_AutoTune/AC_AutoTune_Heli.h index 5da4dc658182e9..4890a0da8e2cef 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_Heli.h +++ b/libraries/AC_AutoTune/AC_AutoTune_Heli.h @@ -103,6 +103,7 @@ class AC_AutoTune_Heli : public AC_AutoTune // reverse direction for twitch test bool twitch_reverse_direction() override { return positive_direction; } +#if HAL_LOGGING_ENABLED // methods to log autotune summary data void Log_AutoTune() override; void Log_Write_AutoTune(uint8_t _axis, uint8_t tune_step, float dwell_freq, float meas_gain, float meas_phase, float new_gain_rff, float new_gain_rp, float new_gain_rd, float new_gain_sp, float max_accel); @@ -114,6 +115,7 @@ class AC_AutoTune_Heli : public AC_AutoTune // methods to log autotune frequency response results void Log_AutoTuneSweep() override; void Log_Write_AutoTuneSweep(float freq, float gain, float phase); +#endif // send intermittent updates to user on status of tune void do_gcs_announcements() override; diff --git a/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp b/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp index c8ff8cc4114b3e..f304c3e70acb91 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp +++ b/libraries/AC_AutoTune/AC_AutoTune_Multi.cpp @@ -192,7 +192,7 @@ void AC_AutoTune_Multi::backup_gains_and_initialise() tune_yaw_sp = attitude_control->get_angle_yaw_p().kP(); tune_yaw_accel = attitude_control->get_accel_yaw_max_cdss(); - AP::logger().Write_Event(LogEvent::AUTOTUNE_INITIALISED); + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_INITIALISED); } // load_orig_gains - set gains to their original values @@ -464,7 +464,7 @@ void AC_AutoTune_Multi::save_tuning_gains() // update GCS and log save gains event update_gcs(AUTOTUNE_MESSAGE_SAVED_GAINS); - AP::logger().Write_Event(LogEvent::AUTOTUNE_SAVEDGAINS); + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_SAVEDGAINS); reset(); } @@ -796,7 +796,7 @@ void AC_AutoTune_Multi::updating_rate_d_up(float &tune_d, float tune_d_min, floa // We have reached minimum D gain so stop tuning tune_d = tune_d_min; counter = AUTOTUNE_SUCCESS_COUNT; - AP::logger().Write_Event(LogEvent::AUTOTUNE_REACHED_LIMIT); + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT); } } } else if ((meas_rate_max < rate_target*(1.0f-AUTOTUNE_D_UP_DOWN_MARGIN)) && (tune_p <= tune_p_max)) { @@ -805,7 +805,7 @@ void AC_AutoTune_Multi::updating_rate_d_up(float &tune_d, float tune_d_min, floa tune_p += tune_p*tune_p_step_ratio; if (tune_p >= tune_p_max) { tune_p = tune_p_max; - AP::logger().Write_Event(LogEvent::AUTOTUNE_REACHED_LIMIT); + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT); } } else { // we have a good measurement of bounce back @@ -826,7 +826,7 @@ void AC_AutoTune_Multi::updating_rate_d_up(float &tune_d, float tune_d_min, floa if (tune_d >= tune_d_max) { tune_d = tune_d_max; counter = AUTOTUNE_SUCCESS_COUNT; - AP::logger().Write_Event(LogEvent::AUTOTUNE_REACHED_LIMIT); + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT); } } else { ignore_next = false; @@ -851,7 +851,7 @@ void AC_AutoTune_Multi::updating_rate_d_down(float &tune_d, float tune_d_min, fl // We have reached minimum D so stop tuning tune_d = tune_d_min; counter = AUTOTUNE_SUCCESS_COUNT; - AP::logger().Write_Event(LogEvent::AUTOTUNE_REACHED_LIMIT); + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT); } } } else if ((meas_rate_max < rate_target*(1.0f-AUTOTUNE_D_UP_DOWN_MARGIN)) && (tune_p <= tune_p_max)) { @@ -860,7 +860,7 @@ void AC_AutoTune_Multi::updating_rate_d_down(float &tune_d, float tune_d_min, fl tune_p += tune_p*tune_p_step_ratio; if (tune_p >= tune_p_max) { tune_p = tune_p_max; - AP::logger().Write_Event(LogEvent::AUTOTUNE_REACHED_LIMIT); + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT); } } else { // we have a good measurement of bounce back @@ -884,7 +884,7 @@ void AC_AutoTune_Multi::updating_rate_d_down(float &tune_d, float tune_d_min, fl if (tune_d <= tune_d_min) { tune_d = tune_d_min; counter = AUTOTUNE_SUCCESS_COUNT; - AP::logger().Write_Event(LogEvent::AUTOTUNE_REACHED_LIMIT); + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT); } } } @@ -909,14 +909,14 @@ void AC_AutoTune_Multi::updating_rate_p_up_d_down(float &tune_d, float tune_d_mi // do not decrease the D term past the minimum if (tune_d <= tune_d_min) { tune_d = tune_d_min; - AP::logger().Write_Event(LogEvent::AUTOTUNE_REACHED_LIMIT); + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT); } // decrease P gain to match D gain reduction tune_p -= tune_p*tune_p_step_ratio; // do not decrease the P term past the minimum if (tune_p <= tune_p_min) { tune_p = tune_p_min; - AP::logger().Write_Event(LogEvent::AUTOTUNE_REACHED_LIMIT); + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT); } // cancel change in direction positive_direction = !positive_direction; @@ -932,7 +932,7 @@ void AC_AutoTune_Multi::updating_rate_p_up_d_down(float &tune_d, float tune_d_mi if (tune_p >= tune_p_max) { tune_p = tune_p_max; counter = AUTOTUNE_SUCCESS_COUNT; - AP::logger().Write_Event(LogEvent::AUTOTUNE_REACHED_LIMIT); + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT); } } else { ignore_next = false; @@ -964,8 +964,8 @@ void AC_AutoTune_Multi::updating_angle_p_down(float &tune_p, float tune_p_min, f if (tune_p <= tune_p_min) { tune_p = tune_p_min; counter = AUTOTUNE_SUCCESS_COUNT; - AP::logger().Write_Event(LogEvent::AUTOTUNE_REACHED_LIMIT); - } + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT); + } } } @@ -991,7 +991,7 @@ void AC_AutoTune_Multi::updating_angle_p_up(float &tune_p, float tune_p_max, flo if (tune_p >= tune_p_max) { tune_p = tune_p_max; counter = AUTOTUNE_SUCCESS_COUNT; - AP::logger().Write_Event(LogEvent::AUTOTUNE_REACHED_LIMIT); + LOGGER_WRITE_EVENT(LogEvent::AUTOTUNE_REACHED_LIMIT); } } else { ignore_next = false; @@ -999,6 +999,7 @@ void AC_AutoTune_Multi::updating_angle_p_up(float &tune_p, float tune_p_max, flo } } +#if HAL_LOGGING_ENABLED void AC_AutoTune_Multi::Log_AutoTune() { if ((tune_type == SP_DOWN) || (tune_type == SP_UP)) { @@ -1093,6 +1094,7 @@ void AC_AutoTune_Multi::Log_Write_AutoTuneDetails(float angle_cd, float rate_cds angle_cd*0.01f, rate_cds*0.01f); } +#endif // HAL_LOGGING_ENABLED void AC_AutoTune_Multi::twitch_test_init() { diff --git a/libraries/AC_AutoTune/AC_AutoTune_Multi.h b/libraries/AC_AutoTune/AC_AutoTune_Multi.h index c199c18ca2dc9b..ac2a0c6892a0e0 100644 --- a/libraries/AC_AutoTune/AC_AutoTune_Multi.h +++ b/libraries/AC_AutoTune/AC_AutoTune_Multi.h @@ -108,6 +108,7 @@ class AC_AutoTune_Multi : public AC_AutoTune // reverse direction for twitch test bool twitch_reverse_direction() override { return !positive_direction; } +#if HAL_LOGGING_ENABLED void Log_AutoTune() override; void Log_AutoTuneDetails() override; void Log_AutoTuneSweep() override { @@ -116,6 +117,7 @@ class AC_AutoTune_Multi : public AC_AutoTune } void Log_Write_AutoTune(uint8_t axis, uint8_t tune_step, float meas_target, float meas_min, float meas_max, float new_gain_rp, float new_gain_rd, float new_gain_sp, float new_ddt); void Log_Write_AutoTuneDetails(float angle_cd, float rate_cds); +#endif void set_tune_sequence() override { tune_seq[0] = RD_UP; From b1c29c50336ded4ddce4588ee1fef6f3d8e4dbc5 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:04 +1000 Subject: [PATCH 0584/1335] AC_Avoidance: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AC_Avoidance/AC_Avoid.cpp | 2 ++ libraries/AC_Avoidance/AC_Avoidance_Logging.cpp | 6 ++++++ libraries/AC_Avoidance/AP_OABendyRuler.cpp | 2 +- libraries/AC_Avoidance/AP_OABendyRuler.h | 5 +++++ libraries/AC_Avoidance/AP_OADijkstra.h | 6 ++++++ 5 files changed, 20 insertions(+), 1 deletion(-) diff --git a/libraries/AC_Avoidance/AC_Avoid.cpp b/libraries/AC_Avoidance/AC_Avoid.cpp index 8e5067f3be6935..9745d4abb62b5b 100644 --- a/libraries/AC_Avoidance/AC_Avoid.cpp +++ b/libraries/AC_Avoidance/AC_Avoid.cpp @@ -259,6 +259,7 @@ void AC_Avoid::adjust_velocity(Vector3f &desired_vel_cms, bool &backing_up, floa _last_limit_time = AP_HAL::millis(); } +#if HAL_LOGGING_ENABLED if (limits_active()) { // log at not more than 10hz (adjust_velocity method can be potentially called at 400hz!) uint32_t now = AP_HAL::millis(); @@ -275,6 +276,7 @@ void AC_Avoid::adjust_velocity(Vector3f &desired_vel_cms, bool &backing_up, floa _last_log_ms = 0; } } +#endif } /* diff --git a/libraries/AC_Avoidance/AC_Avoidance_Logging.cpp b/libraries/AC_Avoidance/AC_Avoidance_Logging.cpp index f02ad8a2fd743d..7a6b3354f9b4c0 100644 --- a/libraries/AC_Avoidance/AC_Avoidance_Logging.cpp +++ b/libraries/AC_Avoidance/AC_Avoidance_Logging.cpp @@ -1,3 +1,7 @@ +#include + +#if HAL_LOGGING_ENABLED + #include "AC_Avoid.h" #include "AP_OADijkstra.h" #include "AP_OABendyRuler.h" @@ -76,3 +80,5 @@ void AC_Avoid::Write_SimpleAvoidance(const uint8_t state, const Vector3f& desire }; AP::logger().WriteBlock(&pkt, sizeof(pkt)); } + +#endif // HAL_LOGGING_ENABLED diff --git a/libraries/AC_Avoidance/AP_OABendyRuler.cpp b/libraries/AC_Avoidance/AP_OABendyRuler.cpp index de7f42fce20fb4..ed122bff29c414 100644 --- a/libraries/AC_Avoidance/AP_OABendyRuler.cpp +++ b/libraries/AC_Avoidance/AP_OABendyRuler.cpp @@ -318,7 +318,7 @@ bool AP_OABendyRuler::search_vertical_path(const Location ¤t_loc, const Lo destination_new = current_loc; destination_new.offset_bearing_and_pitch(bearing_to_dest, pitch_delta, distance_to_dest); _current_lookahead = MIN(_lookahead, _current_lookahead * 1.1f); - + Write_OABendyRuler((uint8_t)OABendyType::OA_BENDY_VERTICAL, active, bearing_to_dest, pitch_delta, false, margin, destination, destination_new); return active; } diff --git a/libraries/AC_Avoidance/AP_OABendyRuler.h b/libraries/AC_Avoidance/AP_OABendyRuler.h index 1b480bdbcfcab5..35e9b4a1c38328 100644 --- a/libraries/AC_Avoidance/AP_OABendyRuler.h +++ b/libraries/AC_Avoidance/AP_OABendyRuler.h @@ -3,6 +3,7 @@ #include #include #include +#include /* * BendyRuler avoidance algorithm for avoiding the polygon and circular fence and dynamic objects detected by the proximity sensor @@ -67,7 +68,11 @@ class AP_OABendyRuler { bool calc_margin_from_object_database(const Location &start, const Location &end, float &margin) const; // Logging function +#if HAL_LOGGING_ENABLED void Write_OABendyRuler(const uint8_t type, const bool active, const float target_yaw, const float target_pitch, const bool resist_chg, const float margin, const Location &final_dest, const Location &oa_dest) const; +#else + void Write_OABendyRuler(const uint8_t type, const bool active, const float target_yaw, const float target_pitch, const bool resist_chg, const float margin, const Location &final_dest, const Location &oa_dest) const {} +#endif // OA common parameters float _margin_max; // object avoidance will ignore objects more than this many meters from vehicle diff --git a/libraries/AC_Avoidance/AP_OADijkstra.h b/libraries/AC_Avoidance/AP_OADijkstra.h index 97c832a78a2515..b0beeea2113fe9 100644 --- a/libraries/AC_Avoidance/AP_OADijkstra.h +++ b/libraries/AC_Avoidance/AP_OADijkstra.h @@ -4,6 +4,7 @@ #include #include #include "AP_OAVisGraph.h" +#include /* * Dijkstra's algorithm for path planning around polygon fence @@ -204,9 +205,14 @@ class AP_OADijkstra { AP_OADijkstra_Error _error_last_id; // last error id sent to GCS uint32_t _error_last_report_ms; // last time an error message was sent to GCS +#if HAL_LOGGING_ENABLED // Logging functions void Write_OADijkstra(const uint8_t state, const uint8_t error_id, const uint8_t curr_point, const uint8_t tot_points, const Location &final_dest, const Location &oa_dest) const; void Write_Visgraph_point(const uint8_t version, const uint8_t point_num, const int32_t Lat, const int32_t Lon) const; +#else + void Write_OADijkstra(const uint8_t state, const uint8_t error_id, const uint8_t curr_point, const uint8_t tot_points, const Location &final_dest, const Location &oa_dest) const {} + void Write_Visgraph_point(const uint8_t version, const uint8_t point_num, const int32_t Lat, const int32_t Lon) const {} +#endif uint8_t _log_num_points; uint8_t _log_visgraph_version; From 78daf8911b977ba2ac915824e5d018651bfbe472 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:04 +1000 Subject: [PATCH 0585/1335] AC_Fence: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AC_Fence/AC_Fence.cpp | 6 ++++++ libraries/AC_Fence/AC_PolyFence_loader.cpp | 2 ++ 2 files changed, 8 insertions(+) diff --git a/libraries/AC_Fence/AC_Fence.cpp b/libraries/AC_Fence/AC_Fence.cpp index b537085e42113f..ac9d7f50a031ab 100644 --- a/libraries/AC_Fence/AC_Fence.cpp +++ b/libraries/AC_Fence/AC_Fence.cpp @@ -160,11 +160,13 @@ AC_Fence::AC_Fence() /// enable the Fence code generally; a master switch for all fences void AC_Fence::enable(bool value) { +#if HAL_LOGGING_ENABLED if (_enabled && !value) { AP::logger().Write_Event(LogEvent::FENCE_DISABLE); } else if (!_enabled && value) { AP::logger().Write_Event(LogEvent::FENCE_ENABLE); } +#endif _enabled.set(value); if (!value) { clear_breach(AC_FENCE_TYPE_ALT_MIN | AC_FENCE_TYPE_ALT_MAX | AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON); @@ -177,19 +179,23 @@ void AC_Fence::enable(bool value) /// enable/disable fence floor only void AC_Fence::enable_floor() { +#if HAL_LOGGING_ENABLED if (!_floor_enabled) { // Floor is currently disabled, enable it AP::logger().Write_Event(LogEvent::FENCE_FLOOR_ENABLE); } +#endif _floor_enabled = true; } void AC_Fence::disable_floor() { +#if HAL_LOGGING_ENABLED if (_floor_enabled) { // Floor is currently enabled, disable it AP::logger().Write_Event(LogEvent::FENCE_FLOOR_DISABLE); } +#endif _floor_enabled = false; clear_breach(AC_FENCE_TYPE_ALT_MIN); } diff --git a/libraries/AC_Fence/AC_PolyFence_loader.cpp b/libraries/AC_Fence/AC_PolyFence_loader.cpp index 1b42ded2738094..12ddba86bbb5a4 100644 --- a/libraries/AC_Fence/AC_PolyFence_loader.cpp +++ b/libraries/AC_Fence/AC_PolyFence_loader.cpp @@ -1121,8 +1121,10 @@ bool AC_PolyFence_loader::write_fence(const AC_PolyFenceItem *new_items, uint16_ gcs().send_text(MAV_SEVERITY_DEBUG, "Fence Indexed OK"); #endif +#if HAL_LOGGING_ENABLED // start logger logging new fence AP::logger().Write_Fence(); +#endif void_index(); From 26b665ed82149dd7fe4ee3e04e5e9965a8abadc2 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:04 +1000 Subject: [PATCH 0586/1335] AC_PrecLand: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AC_PrecLand/AC_PrecLand.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index 57223e1f666c93..49c7a11060a90a 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -310,11 +310,13 @@ void AC_PrecLand::update(float rangefinder_alt_cm, bool rangefinder_alt_valid) // check the status of the landing target location check_target_status(rangefinder_alt_m, rangefinder_alt_valid); +#if HAL_LOGGING_ENABLED const uint32_t now = AP_HAL::millis(); if (now - last_log_ms > 40) { // 25Hz last_log_ms = now; Write_Precland(); } +#endif } // check the status of the target @@ -740,6 +742,7 @@ void AC_PrecLand::run_output_prediction() _last_valid_target_ms = AP_HAL::millis(); } +#if HAL_LOGGING_ENABLED // Write a precision landing entry void AC_PrecLand::Write_Precland() { @@ -773,6 +776,7 @@ void AC_PrecLand::Write_Precland() }; AP::logger().WriteBlock(&pkt, sizeof(pkt)); } +#endif // singleton instance AC_PrecLand *AC_PrecLand::_singleton; From d28a867453ddc2a20b37f62332a63f148d9bcc94 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:04 +1000 Subject: [PATCH 0587/1335] AC_WPNav: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AC_WPNav/AC_Circle.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AC_WPNav/AC_Circle.cpp b/libraries/AC_WPNav/AC_Circle.cpp index ca804a54916c94..b1f88a40947f3b 100644 --- a/libraries/AC_WPNav/AC_Circle.cpp +++ b/libraries/AC_WPNav/AC_Circle.cpp @@ -121,7 +121,7 @@ void AC_Circle::set_center(const Location& center) } else { // failed to convert location so set to current position and log error set_center(_inav.get_position_neu_cm(), false); - AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_CIRCLE_INIT); + LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_CIRCLE_INIT); } } else { // convert Location with alt-above-home, alt-above-origin or absolute alt @@ -129,7 +129,7 @@ void AC_Circle::set_center(const Location& center) if (!center.get_vector_from_origin_NEU(circle_center_neu)) { // default to current position and log error circle_center_neu = _inav.get_position_neu_cm(); - AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_CIRCLE_INIT); + LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_CIRCLE_INIT); } set_center(circle_center_neu, false); } From 7cf033efd936929c1855ef3d765f90be4860a594 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:04 +1000 Subject: [PATCH 0588/1335] AP_AHRS: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_AHRS/AP_AHRS.cpp | 8 +++++++- libraries/AP_AHRS/AP_AHRS_Backend.cpp | 2 ++ libraries/AP_AHRS/AP_AHRS_Logging.cpp | 6 ++++++ 3 files changed, 15 insertions(+), 1 deletion(-) diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index f77ea3551c1c79..889272b2d438bb 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -559,6 +559,7 @@ void AP_AHRS::update_EKF2(void) if (start_time_ms == 0) { start_time_ms = AP_HAL::millis(); } +#if HAL_LOGGING_ENABLED // if we're doing Replay logging then don't allow any data // into the EKF yet. Don't allow it to block us for long. if (!hal.util->was_watchdog_reset()) { @@ -568,6 +569,7 @@ void AP_AHRS::update_EKF2(void) } } } +#endif if (AP_HAL::millis() - start_time_ms > startup_delay_ms) { _ekf2_started = EKF2.InitialiseFilter(); @@ -626,6 +628,7 @@ void AP_AHRS::update_EKF3(void) if (start_time_ms == 0) { start_time_ms = AP_HAL::millis(); } +#if HAL_LOGGING_ENABLED // if we're doing Replay logging then don't allow any data // into the EKF yet. Don't allow it to block us for long. if (!hal.util->was_watchdog_reset()) { @@ -635,6 +638,7 @@ void AP_AHRS::update_EKF3(void) } } } +#endif if (AP_HAL::millis() - start_time_ms > startup_delay_ms) { _ekf3_started = EKF3.InitialiseFilter(); } @@ -2896,7 +2900,7 @@ bool AP_AHRS::set_home(const Location &loc) return false; } -#if !APM_BUILD_TYPE(APM_BUILD_UNKNOWN) +#if !APM_BUILD_TYPE(APM_BUILD_UNKNOWN) && HAL_LOGGING_ENABLED if (!_home_is_set) { // record home is set AP::logger().Write_Event(LogEvent::SET_HOME); @@ -2906,7 +2910,9 @@ bool AP_AHRS::set_home(const Location &loc) _home = tmp; _home_is_set = true; +#if HAL_LOGGING_ENABLED Log_Write_Home_And_Origin(); +#endif // send new home and ekf origin to GCS GCS_SEND_MESSAGE(MSG_HOME); diff --git a/libraries/AP_AHRS/AP_AHRS_Backend.cpp b/libraries/AP_AHRS/AP_AHRS_Backend.cpp index 763716e148c694..5075f824ef44dd 100644 --- a/libraries/AP_AHRS/AP_AHRS_Backend.cpp +++ b/libraries/AP_AHRS/AP_AHRS_Backend.cpp @@ -244,6 +244,7 @@ Vector2f AP_AHRS::body_to_earth2D(const Vector2f &bf) const bf.x * _sin_yaw + bf.y * _cos_yaw); } +#if HAL_LOGGING_ENABLED // log ahrs home and EKF origin void AP_AHRS::Log_Write_Home_And_Origin() { @@ -260,6 +261,7 @@ void AP_AHRS::Log_Write_Home_And_Origin() Write_Origin(LogOriginType::ahrs_home, _home); } } +#endif // get apparent to true airspeed ratio float AP_AHRS_Backend::get_EAS2TAS(void) { diff --git a/libraries/AP_AHRS/AP_AHRS_Logging.cpp b/libraries/AP_AHRS/AP_AHRS_Logging.cpp index 8d602b81cedd10..a5d77476238d53 100644 --- a/libraries/AP_AHRS/AP_AHRS_Logging.cpp +++ b/libraries/AP_AHRS/AP_AHRS_Logging.cpp @@ -1,3 +1,7 @@ +#include + +#if HAL_LOGGING_ENABLED + #include "AP_AHRS.h" #include @@ -184,3 +188,5 @@ void AP_AHRS_View::Write_Rate(const AP_Motors &motors, const AC_AttitudeControl AP::logger().WriteBlock(&pkt_ATSC, sizeof(pkt_ATSC)); } } + +#endif // HAL_LOGGING_ENABLED From 43ed929b0ab4a9acf9136edbe14b7c08b49db75a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:04 +1000 Subject: [PATCH 0589/1335] AP_Airspeed: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_Airspeed/AP_Airspeed.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index 65c0b7b2911312..8191cc41ee9322 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -755,6 +755,7 @@ void AP_Airspeed::handle_external(const AP_ExternalAHRS::airspeed_data_message_t } #endif +#if HAL_LOGGING_ENABLED // @LoggerMessage: HYGR // @Description: Hygrometer data // @Field: TimeUS: Time since system startup @@ -812,6 +813,7 @@ void AP_Airspeed::Log_Airspeed() #endif } } +#endif bool AP_Airspeed::use(uint8_t i) const { From 8640a96851c424983d38906e283e5b12e8761e7f Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:05 +1000 Subject: [PATCH 0590/1335] AP_Arming: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_Arming/AP_Arming.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index eb9fca91e0e7d3..a2fa77d6e092b1 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -1666,6 +1666,7 @@ bool AP_Arming::arm_checks(AP_Arming::Method method) // the arming check flag is set - disabling the arming check // should not stop logging from working. +#if HAL_LOGGING_ENABLED AP_Logger *logger = AP_Logger::get_singleton(); if (logger->logging_present()) { // If we're configured to log, prep it @@ -1676,6 +1677,8 @@ bool AP_Arming::arm_checks(AP_Arming::Method method) return false; } } +#endif // HAL_LOGGING_ENABLED + return true; } From 4f6f6a7ff6f4e9e577f508987fcc664d79a49f65 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:05 +1000 Subject: [PATCH 0591/1335] AP_Baro: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_Baro/AP_Baro.cpp | 2 ++ libraries/AP_Baro/AP_Baro_Logging.cpp | 6 ++++++ 2 files changed, 8 insertions(+) diff --git a/libraries/AP_Baro/AP_Baro.cpp b/libraries/AP_Baro/AP_Baro.cpp index 5435ae060c86cc..84bfbadc9fd989 100644 --- a/libraries/AP_Baro/AP_Baro.cpp +++ b/libraries/AP_Baro/AP_Baro.cpp @@ -874,6 +874,7 @@ void AP_Baro::_probe_i2c_barometers(void) } } +#if HAL_LOGGING_ENABLED bool AP_Baro::should_log() const { AP_Logger *logger = AP_Logger::get_singleton(); @@ -888,6 +889,7 @@ bool AP_Baro::should_log() const } return true; } +#endif /* call update on all drivers diff --git a/libraries/AP_Baro/AP_Baro_Logging.cpp b/libraries/AP_Baro/AP_Baro_Logging.cpp index a697d22661074f..91c622aaa0f207 100644 --- a/libraries/AP_Baro/AP_Baro_Logging.cpp +++ b/libraries/AP_Baro/AP_Baro_Logging.cpp @@ -1,3 +1,7 @@ +#include + +#if HAL_LOGGING_ENABLED + #include "AP_Baro.h" #include @@ -44,3 +48,5 @@ void AP_Baro::Write_Baro(void) Write_Baro_instance(time_us, i); } } + +#endif From cddb58e105e360ad517538d8ea7d28fccbb3e3f6 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:05 +1000 Subject: [PATCH 0592/1335] AP_BattMonitor: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_BattMonitor/AP_BattMonitor_Logging.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Logging.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Logging.cpp index 4f3433d87added..4b5d4fe2c57e1d 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Logging.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Logging.cpp @@ -1,3 +1,7 @@ +#include + +#if HAL_LOGGING_ENABLED + #include "AP_BattMonitor_Backend.h" #include @@ -83,3 +87,5 @@ void AP_BattMonitor_Backend::Log_Write_BCL(const uint8_t instance, const uint64_ } #endif } + +#endif // HAL_LOGGING_ENABLED From 6e27488bfdf951e9b00307b6047b136f9628b2f1 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:05 +1000 Subject: [PATCH 0593/1335] AP_Beacon: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_Beacon/AP_Beacon.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_Beacon/AP_Beacon.cpp b/libraries/AP_Beacon/AP_Beacon.cpp index 23c8e217245f22..0a2a04e71cb983 100644 --- a/libraries/AP_Beacon/AP_Beacon.cpp +++ b/libraries/AP_Beacon/AP_Beacon.cpp @@ -391,6 +391,7 @@ bool AP_Beacon::device_ready(void) const return ((_driver != nullptr) && (_type != AP_BeaconType_None)); } +#if HAL_LOGGING_ENABLED // Write beacon sensor (position) data void AP_Beacon::log() { @@ -417,6 +418,7 @@ void AP_Beacon::log() }; AP::logger().WriteBlock(&pkt_beacon, sizeof(pkt_beacon)); } +#endif // singleton instance AP_Beacon *AP_Beacon::_singleton; From 4b30963d1df0decf1a58e4e411b69565a4b5091c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:05 +1000 Subject: [PATCH 0594/1335] AP_Camera: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_Camera/AP_Camera_Backend.cpp | 8 ++++++++ libraries/AP_Camera/AP_Camera_Logging.cpp | 5 +++-- 2 files changed, 11 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Camera/AP_Camera_Backend.cpp b/libraries/AP_Camera/AP_Camera_Backend.cpp index f6cf2c2d2b6089..4781c4180721a9 100644 --- a/libraries/AP_Camera/AP_Camera_Backend.cpp +++ b/libraries/AP_Camera/AP_Camera_Backend.cpp @@ -140,7 +140,9 @@ bool AP_Camera_Backend::take_picture() image_index++; last_picture_time_ms = now_ms; IGNORE_RETURN(AP::ahrs().get_location(last_location)); +#if HAL_LOGGING_ENABLED log_picture(); +#endif return true; } @@ -358,16 +360,20 @@ void AP_Camera_Backend::feedback_pin_timer() void AP_Camera_Backend::check_feedback() { if (feedback_trigger_logged_count != feedback_trigger_count) { +#if HAL_LOGGING_ENABLED const uint32_t timestamp32 = feedback_trigger_timestamp_us; +#endif feedback_trigger_logged_count = feedback_trigger_count; // we should consider doing this inside the ISR and pin_timer prep_mavlink_msg_camera_feedback(feedback_trigger_timestamp_us); +#if HAL_LOGGING_ENABLED // log camera message uint32_t tdiff = AP_HAL::micros() - timestamp32; uint64_t timestamp = AP_HAL::micros64(); Write_Camera(timestamp - tdiff); +#endif } } @@ -386,6 +392,7 @@ void AP_Camera_Backend::prep_mavlink_msg_camera_feedback(uint64_t timestamp_us) GCS_SEND_MESSAGE(MSG_CAMERA_FEEDBACK); } +#if HAL_LOGGING_ENABLED // log picture void AP_Camera_Backend::log_picture() { @@ -404,5 +411,6 @@ void AP_Camera_Backend::log_picture() Write_Trigger(); } } +#endif #endif // AP_CAMERA_ENABLED diff --git a/libraries/AP_Camera/AP_Camera_Logging.cpp b/libraries/AP_Camera/AP_Camera_Logging.cpp index 903f42a8a8ab58..d49a6200c13d95 100644 --- a/libraries/AP_Camera/AP_Camera_Logging.cpp +++ b/libraries/AP_Camera/AP_Camera_Logging.cpp @@ -1,7 +1,8 @@ #include "AP_Camera_Backend.h" #include +#include -#if AP_CAMERA_ENABLED +#if AP_CAMERA_ENABLED && HAL_LOGGING_ENABLED #include #include @@ -85,4 +86,4 @@ void AP_Camera_Backend::Write_Trigger() Write_CameraInfo(LOG_TRIGGER_MSG, 0); } -#endif +#endif // AP_CAMERA_ENABLED && HAL_LOGGING_ENABLED From 8828659b3362ff47b42df375b74fd2de97313746 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:05 +1000 Subject: [PATCH 0595/1335] AP_DAL: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_DAL/AP_DAL.cpp | 4 ++++ libraries/AP_DAL/AP_DAL.h | 7 +++++++ 2 files changed, 11 insertions(+) diff --git a/libraries/AP_DAL/AP_DAL.cpp b/libraries/AP_DAL/AP_DAL.cpp index b05c411e5d523c..986fe66bcf0251 100644 --- a/libraries/AP_DAL/AP_DAL.cpp +++ b/libraries/AP_DAL/AP_DAL.cpp @@ -38,11 +38,13 @@ void AP_DAL::start_frame(AP_DAL::FrameType frametype) _last_imu_time_us = imu_us; // we force write all msgs when logging starts +#if HAL_LOGGING_ENABLED bool logging = AP::logger().logging_started() && AP::logger().allow_start_ekf(); if (logging && !logging_started) { force_write = true; } logging_started = logging; +#endif end_frame(); @@ -280,6 +282,7 @@ uint8_t AP_DAL::logging_core(uint8_t c) const #endif } +#if HAL_LOGGING_ENABLED // write out a DAL log message. If old_msg is non-null, then // only write if the content has changed void AP_DAL::WriteLogMessage(enum LogMessages msg_type, void *msg, const void *old_msg, uint8_t msg_size) @@ -301,6 +304,7 @@ void AP_DAL::WriteLogMessage(enum LogMessages msg_type, void *msg, const void *o _end = 0; } } +#endif /* check if we are low on CPU for this core. This needs to capture the diff --git a/libraries/AP_DAL/AP_DAL.h b/libraries/AP_DAL/AP_DAL.h index 671499b547baa2..d8c92e01b53912 100644 --- a/libraries/AP_DAL/AP_DAL.h +++ b/libraries/AP_DAL/AP_DAL.h @@ -324,9 +324,11 @@ class AP_DAL { // map core number for replay uint8_t logging_core(uint8_t c) const; +#if HAL_LOGGING_ENABLED // write out a DAL log message. If old_msg is non-null, then // only write if the content has changed static void WriteLogMessage(enum LogMessages msg_type, void *msg, const void *old_msg, uint8_t msg_size); +#endif private: @@ -376,10 +378,15 @@ class AP_DAL { bool init_done; }; +#if HAL_LOGGING_ENABLED #define WRITE_REPLAY_BLOCK(sname,v) AP_DAL::WriteLogMessage(LOG_## sname ##_MSG, &v, nullptr, offsetof(log_ ##sname, _end)) #define WRITE_REPLAY_BLOCK_IFCHANGED(sname,v,old) do { static_assert(sizeof(v) == sizeof(old), "types must match"); \ AP_DAL::WriteLogMessage(LOG_## sname ##_MSG, &v, &old, offsetof(log_ ##sname, _end)); } \ while (0) +#else +#define WRITE_REPLAY_BLOCK(sname,v) do { (void)v; } while (false) +#define WRITE_REPLAY_BLOCK_IFCHANGED(sname,v,old) do { (void)old; } while (false) +#endif namespace AP { AP_DAL &dal(); From dd4d01771759e160c697c18bd6db5bba4797c4f2 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:05 +1000 Subject: [PATCH 0596/1335] AP_DroneCAN: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_DroneCAN/AP_DroneCAN.cpp | 6 ++++++ libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp | 6 +++++- 2 files changed, 11 insertions(+), 1 deletion(-) diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.cpp b/libraries/AP_DroneCAN/AP_DroneCAN.cpp index 5667f5a54af4f5..810e1ba0748578 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN.cpp @@ -1354,6 +1354,7 @@ void AP_DroneCAN::handle_traffic_report(const CanardRxTransfer& transfer, const */ void AP_DroneCAN::handle_actuator_status(const CanardRxTransfer& transfer, const uavcan_equipment_actuator_Status& msg) { +#if HAL_LOGGING_ENABLED // log as CSRV message AP::logger().Write_ServoStatus(AP_HAL::micros64(), msg.actuator_id, @@ -1362,6 +1363,7 @@ void AP_DroneCAN::handle_actuator_status(const CanardRxTransfer& transfer, const msg.speed, msg.power_rating_pct, 0, 0, 0, 0, 0, 0); +#endif } #if AP_DRONECAN_HIMARK_SERVO_SUPPORT @@ -1370,6 +1372,7 @@ void AP_DroneCAN::handle_actuator_status(const CanardRxTransfer& transfer, const */ void AP_DroneCAN::handle_himark_servoinfo(const CanardRxTransfer& transfer, const com_himark_servo_ServoInfo &msg) { +#if HAL_LOGGING_ENABLED // log as CSRV message AP::logger().Write_ServoStatus(AP_HAL::micros64(), msg.servo_id, @@ -1383,12 +1386,14 @@ void AP_DroneCAN::handle_himark_servoinfo(const CanardRxTransfer& transfer, cons msg.motor_temp*0.2-40, msg.pcb_temp*0.2-40, msg.error_status); +#endif } #endif // AP_DRONECAN_HIMARK_SERVO_SUPPORT #if AP_DRONECAN_VOLZ_FEEDBACK_ENABLED void AP_DroneCAN::handle_actuator_status_Volz(const CanardRxTransfer& transfer, const com_volz_servo_ActuatorStatus& msg) { +#if HAL_LOGGING_ENABLED AP::logger().WriteStreaming( "CVOL", "TimeUS,Id,Pos,Cur,V,Pow,T", @@ -1402,6 +1407,7 @@ void AP_DroneCAN::handle_actuator_status_Volz(const CanardRxTransfer& transfer, msg.voltage * 0.2f, msg.motor_pwm * (100.0/255.0), int16_t(msg.motor_temperature) - 50); +#endif } #endif diff --git a/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp index 02b5ed7453647a..1164d4f7346c5d 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN_DNA_Server.cpp @@ -352,12 +352,14 @@ void AP_DroneCAN_DNA_Server::verify_nodes() return; } +#if HAL_LOGGING_ENABLED uint8_t log_count = AP::logger().get_log_start_count(); if (log_count != last_logging_count) { last_logging_count = log_count; logged.clearall(); } - +#endif + //Check if we got acknowledgement from previous request //except for requests using our own node_id if (curr_verifying_node == self_node_id) { @@ -438,6 +440,7 @@ void AP_DroneCAN_DNA_Server::handleNodeInfo(const CanardRxTransfer& transfer, co /* if we haven't logged this node then log it now */ +#if HAL_LOGGING_ENABLED if (!logged.get(transfer.source_node_id) && AP::logger().logging_started()) { logged.set(transfer.source_node_id); uint64_t uid[2]; @@ -462,6 +465,7 @@ void AP_DroneCAN_DNA_Server::handleNodeInfo(const CanardRxTransfer& transfer, co rsp.software_version.minor, rsp.software_version.vcs_commit); } +#endif if (isNodeIDOccupied(transfer.source_node_id)) { //if node_id already registered, just verify if Unique ID matches as well From a7b658c260e5b11371b8975b095cfa8151dfc64f Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:05 +1000 Subject: [PATCH 0597/1335] AP_ESC_Telem: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_ESC_Telem/AP_ESC_Telem.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp index 7bb347220d0c0b..4af6e8bd72dcb0 100644 --- a/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp +++ b/libraries/AP_ESC_Telem/AP_ESC_Telem.cpp @@ -490,11 +490,14 @@ void AP_ESC_Telem::update_rpm(const uint8_t esc_index, const float new_rpm, cons void AP_ESC_Telem::update() { +#if HAL_LOGGING_ENABLED AP_Logger *logger = AP_Logger::get_singleton(); +#endif const uint32_t now_us = AP_HAL::micros(); for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) { +#if HAL_LOGGING_ENABLED // Push received telemetry data into the logging system if (logger && logger->logging_enabled()) { if (_telem_data[i].last_update_ms != _last_telem_log_ms[i] @@ -532,6 +535,7 @@ void AP_ESC_Telem::update() _last_rpm_log_us[i] = _rpm_data[i].last_update_us; } } +#endif // HAL_LOGGING_ENABLED if ((now_us - _rpm_data[i].last_update_us) > ESC_RPM_DATA_TIMEOUT_US) { _rpm_data[i].data_valid = false; From f92b02afd06b70ef5ebc8799154b1b3b94120d17 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:05 +1000 Subject: [PATCH 0598/1335] AP_ExternalAHRS: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp | 4 +++- libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp | 5 ++++- 2 files changed, 7 insertions(+), 2 deletions(-) diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp index 9019eaef461f01..d10ca6997c7cd7 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_InertialLabs.cpp @@ -489,6 +489,7 @@ bool AP_ExternalAHRS_InertialLabs::check_uart() #endif // AP_AIRSPEED_EXTERNAL_ENABLED buffer_ofs = 0; +#if HAL_LOGGING_ENABLED if (GOT_MSG(POSITION) && GOT_MSG(ORIENTATION_ANGLES) && GOT_MSG(VELOCITIES)) { @@ -564,7 +565,8 @@ bool AP_ExternalAHRS_InertialLabs::check_uart() state2.true_airspeed, state2.wind_speed.x, state2.wind_speed.y, state2.wind_speed.z); } - +#endif // HAL_LOGGING_ENABLED + return true; } diff --git a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp index 66c20f05590e22..26f379868a2dff 100644 --- a/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp +++ b/libraries/AP_ExternalAHRS/AP_ExternalAHRS_VectorNav.cpp @@ -513,6 +513,7 @@ void AP_ExternalAHRS_VectorNav::process_packet1(const uint8_t *b) } +#if HAL_LOGGING_ENABLED // @LoggerMessage: EAH1 // @Description: External AHRS data // @Field: TimeUS: Time since system startup @@ -541,6 +542,7 @@ void AP_ExternalAHRS_VectorNav::process_packet1(const uint8_t *b) float(pkt1.positionLLA[2]), pkt1.posU, pkt1.velU, pkt1.yprU[2], pkt1.yprU[1], pkt1.yprU[0]); +#endif // HAL_LOGGING_ENABLED } /* @@ -651,6 +653,7 @@ void AP_ExternalAHRS_VectorNav::process_packet_VN_100(const uint8_t *b) AP::ins().handle_external(ins); } +#if HAL_LOGGING_ENABLED // @LoggerMessage: EAH3 // @Description: External AHRS data // @Field: TimeUS: Time since system startup @@ -681,7 +684,7 @@ void AP_ExternalAHRS_VectorNav::process_packet_VN_100(const uint8_t *b) state.accel[0], state.accel[1], state.accel[2], state.gyro[0], state.gyro[1], state.gyro[2], state.quat[0], state.quat[1], state.quat[2], state.quat[3]); - +#endif // HAL_LOGGING_ENABLED } From 6627c1f4e4150feac704a409a8d08f39ea23caf5 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:05 +1000 Subject: [PATCH 0599/1335] AP_Follow: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_Follow/AP_Follow.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Follow/AP_Follow.cpp b/libraries/AP_Follow/AP_Follow.cpp index 274ddf4d935c22..a06b922feaac2c 100644 --- a/libraries/AP_Follow/AP_Follow.cpp +++ b/libraries/AP_Follow/AP_Follow.cpp @@ -395,8 +395,9 @@ void AP_Follow::handle_msg(const mavlink_message_t &msg) break; } } - + if (updated) { +#if HAL_LOGGING_ENABLED // get estimated location and velocity Location loc_estimate{}; Vector3f vel_estimate; @@ -431,6 +432,7 @@ void AP_Follow::handle_msg(const mavlink_message_t &msg) loc_estimate.lng, loc_estimate.alt ); +#endif } } From 52c806e32ed1b870074e7a970692cee3e4f1e7be Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:05 +1000 Subject: [PATCH 0600/1335] AP_Generator: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_Generator/AP_Generator_IE_2400.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_Generator/AP_Generator_IE_2400.h b/libraries/AP_Generator/AP_Generator_IE_2400.h index c98238f53f7c53..a52c53cc856166 100644 --- a/libraries/AP_Generator/AP_Generator_IE_2400.h +++ b/libraries/AP_Generator/AP_Generator_IE_2400.h @@ -4,6 +4,8 @@ #if AP_GENERATOR_IE_2400_ENABLED +#include + class AP_Generator_IE_2400 : public AP_Generator_IE_FuelCell { // Inherit constructor From fa8f3b57157cdad993a7cb954f2d66746fd63402 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:06 +1000 Subject: [PATCH 0601/1335] AP_GPS: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_GPS/AP_GPS.cpp | 2 ++ libraries/AP_GPS/AP_GPS_DroneCAN.cpp | 2 ++ libraries/AP_GPS/GPS_Backend.cpp | 1 + 3 files changed, 5 insertions(+) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index b947175b0bf620..3257eb82308c5f 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -2254,6 +2254,7 @@ bool AP_GPS::get_undulation(uint8_t instance, float &undulation) const return true; } +#if HAL_LOGGING_ENABLED // Logging support: // Write an GPS packet void AP_GPS::Write_GPS(uint8_t i) @@ -2310,6 +2311,7 @@ void AP_GPS::Write_GPS(uint8_t i) }; AP::logger().WriteBlock(&pkt2, sizeof(pkt2)); } +#endif /* get GPS based yaw diff --git a/libraries/AP_GPS/AP_GPS_DroneCAN.cpp b/libraries/AP_GPS/AP_GPS_DroneCAN.cpp index 2471d3958019f4..5da56758a517c3 100644 --- a/libraries/AP_GPS/AP_GPS_DroneCAN.cpp +++ b/libraries/AP_GPS/AP_GPS_DroneCAN.cpp @@ -526,10 +526,12 @@ void AP_GPS_DroneCAN::handle_status_msg(const ardupilot_gnss_Status& msg) healthy = msg.healthy; status_flags = msg.status; if (error_code != msg.error_codes) { +#if HAL_LOGGING_ENABLED AP::logger().Write_MessageF("GPS %d: error changed (0x%08x/0x%08x)", (unsigned int)(state.instance + 1), error_code, msg.error_codes); +#endif error_code = msg.error_codes; } } diff --git a/libraries/AP_GPS/GPS_Backend.cpp b/libraries/AP_GPS/GPS_Backend.cpp index 095bb27366d7a4..7dc6dfd670e167 100644 --- a/libraries/AP_GPS/GPS_Backend.cpp +++ b/libraries/AP_GPS/GPS_Backend.cpp @@ -23,6 +23,7 @@ #include #include #include +#include #define GPS_BACKEND_DEBUGGING 0 From 1c395966ce088d7958d37e10926ba987541a0031 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:06 +1000 Subject: [PATCH 0602/1335] AP_Gripper: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_Gripper/AP_Gripper_EPM.cpp | 4 ++-- libraries/AP_Gripper/AP_Gripper_Servo.cpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Gripper/AP_Gripper_EPM.cpp b/libraries/AP_Gripper/AP_Gripper_EPM.cpp index 5762597f50f010..76c2f67381f900 100644 --- a/libraries/AP_Gripper/AP_Gripper_EPM.cpp +++ b/libraries/AP_Gripper/AP_Gripper_EPM.cpp @@ -66,7 +66,7 @@ void AP_Gripper_EPM::grab() SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.grab_pwm); } GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Gripper load grabbing"); - AP::logger().Write_Event(LogEvent::GRIPPER_GRAB); + LOGGER_WRITE_EVENT(LogEvent::GRIPPER_GRAB); } // release - move epm pwm output to the release position @@ -90,7 +90,7 @@ void AP_Gripper_EPM::release() SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.release_pwm); } GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Gripper load releasing"); - AP::logger().Write_Event(LogEvent::GRIPPER_RELEASE); + LOGGER_WRITE_EVENT(LogEvent::GRIPPER_RELEASE); } // neutral - return the epm pwm output to the neutral position diff --git a/libraries/AP_Gripper/AP_Gripper_Servo.cpp b/libraries/AP_Gripper/AP_Gripper_Servo.cpp index 0ef9957da0fec9..a2d13897727ba0 100644 --- a/libraries/AP_Gripper/AP_Gripper_Servo.cpp +++ b/libraries/AP_Gripper/AP_Gripper_Servo.cpp @@ -40,7 +40,7 @@ void AP_Gripper_Servo::grab() SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.grab_pwm); _last_grab_or_release = AP_HAL::millis(); GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Gripper load grabbing"); - AP::logger().Write_Event(LogEvent::GRIPPER_GRAB); + LOGGER_WRITE_EVENT(LogEvent::GRIPPER_GRAB); } void AP_Gripper_Servo::release() @@ -65,7 +65,7 @@ void AP_Gripper_Servo::release() SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.release_pwm); _last_grab_or_release = AP_HAL::millis(); GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Gripper load releasing"); - AP::logger().Write_Event(LogEvent::GRIPPER_RELEASE); + LOGGER_WRITE_EVENT(LogEvent::GRIPPER_RELEASE); } bool AP_Gripper_Servo::has_state_pwm(const uint16_t pwm) const From d89d8ee564376878b5b2837c486c529fda75f2c1 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:06 +1000 Subject: [PATCH 0603/1335] AP_GyroFFT: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_GyroFFT/AP_GyroFFT.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/libraries/AP_GyroFFT/AP_GyroFFT.cpp b/libraries/AP_GyroFFT/AP_GyroFFT.cpp index 886baa3749c370..5a1c0e79666842 100644 --- a/libraries/AP_GyroFFT/AP_GyroFFT.cpp +++ b/libraries/AP_GyroFFT/AP_GyroFFT.cpp @@ -473,7 +473,7 @@ uint16_t AP_GyroFFT::run_cycle() _thread_state._last_output_us[_update_axis] = AP_HAL::micros(); _output_cycle_micros = _thread_state._last_output_us[_update_axis] - now; -#if AP_SIM_ENABLED +#if AP_SIM_ENABLED && HAL_LOGGING_ENABLED // extra logging when running simulations AP::logger().WriteStreaming( "FTN3", @@ -966,6 +966,8 @@ float AP_GyroFFT::calculate_weighted_freq_hz(const Vector3f& energy, const Vecto // @Field: FHZ: FFT health, Z-axis // @Field: Tc: FFT cycle time +#if HAL_LOGGING_ENABLED + // log gyro fft messages void AP_GyroFFT::write_log_messages() { @@ -1048,6 +1050,8 @@ void AP_GyroFFT::log_noise_peak(uint8_t id, FrequencyPeak peak) const get_center_freq_energy(peak).z); } +#endif + // return an average noise bandwidth weighted by bin energy // called from main thread float AP_GyroFFT::get_weighted_noise_center_bandwidth_hz() const From 6a897f01d8ca768d3a9afb583559499c328fa1d2 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:06 +1000 Subject: [PATCH 0604/1335] AP_InertialSensor: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp | 3 +++ libraries/AP_InertialSensor/AP_InertialSensor_Backend.h | 2 +- libraries/AP_InertialSensor/AP_InertialSensor_Logging.cpp | 6 ++++++ libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp | 1 + 4 files changed, 11 insertions(+), 1 deletion(-) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp index 3c45c611b1b3c4..85c9ed8f34e359 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp @@ -1,6 +1,7 @@ #define AP_INLINE_VECTOR_OPS #include +#include #include "AP_InertialSensor.h" #include "AP_InertialSensor_Backend.h" #include @@ -816,6 +817,7 @@ void AP_InertialSensor_Backend::update_accel(uint8_t instance) /* front end */ } } +#if HAL_LOGGING_ENABLED bool AP_InertialSensor_Backend::should_log_imu_raw() const { if (_imu._log_raw_bit == (uint32_t)-1) { @@ -831,6 +833,7 @@ bool AP_InertialSensor_Backend::should_log_imu_raw() const } return true; } +#endif // HAL_LOGGING_ENABLED // log an unexpected change in a register for an IMU void AP_InertialSensor_Backend::log_register_change(uint32_t bus_id, const AP_HAL::Device::checkreg ®) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h index 880571ee4f51e1..e51d9362b80b50 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h @@ -312,7 +312,7 @@ class AP_InertialSensor_Backend */ void notify_accel_fifo_reset(uint8_t instance) __RAMFUNC__; void notify_gyro_fifo_reset(uint8_t instance) __RAMFUNC__; - + // log an unexpected change in a register for an IMU void log_register_change(uint32_t bus_id, const AP_HAL::Device::checkreg ®) __RAMFUNC__; diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Logging.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Logging.cpp index e59019d7ded194..2318766a6720a6 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Logging.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Logging.cpp @@ -1,3 +1,7 @@ +#include + +#if HAL_LOGGING_ENABLED + #include "AP_InertialSensor.h" #include "AP_InertialSensor_Backend.h" @@ -188,3 +192,5 @@ void AP_InertialSensor::write_notch_log_messages() const } } } + +#endif // HAL_LOGGING_ENABLED diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp index 486d14965a116f..ef5062cb93d257 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_tempcal.cpp @@ -26,6 +26,7 @@ #include #include #include +#include "AP_InertialSensor.h" // this scale factor ensures params are easy to work with in GUI parameter editors #define SCALE_FACTOR 1.0e6 From 14beb2f1918b0cbcc9e594803d0b4ab672decfec Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:06 +1000 Subject: [PATCH 0605/1335] AP_IOMCU: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_IOMCU/AP_IOMCU.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AP_IOMCU/AP_IOMCU.cpp b/libraries/AP_IOMCU/AP_IOMCU.cpp index 4768ec6e2fb925..bfefb6c253cb78 100644 --- a/libraries/AP_IOMCU/AP_IOMCU.cpp +++ b/libraries/AP_IOMCU/AP_IOMCU.cpp @@ -504,6 +504,7 @@ void AP_IOMCU::write_log() uint32_t now = AP_HAL::millis(); if (now - last_log_ms >= 1000U) { last_log_ms = now; +#if HAL_LOGGING_ENABLED if (AP_Logger::get_singleton()) { // @LoggerMessage: IOMC // @Description: IOMCU diagnostic information @@ -525,6 +526,7 @@ void AP_IOMCU::write_log() reg_status.num_errors, num_delayed); } +#endif // HAL_LOGGING_ENABLED #if IOMCU_DEBUG_ENABLE static uint32_t last_io_print; if (now - last_io_print >= 5000) { @@ -548,6 +550,7 @@ void AP_IOMCU::write_log() } } + /* read servo output values */ From 97c8d149f7b185a3fea7782a948e4d6da4a3c070 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:06 +1000 Subject: [PATCH 0606/1335] AP_LandingGear: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_LandingGear/AP_LandingGear.cpp | 6 ++++-- libraries/AP_LandingGear/AP_LandingGear.h | 5 +++++ 2 files changed, 9 insertions(+), 2 deletions(-) diff --git a/libraries/AP_LandingGear/AP_LandingGear.cpp b/libraries/AP_LandingGear/AP_LandingGear.cpp index 8f77d5e3df7501..7ac89719947864 100644 --- a/libraries/AP_LandingGear/AP_LandingGear.cpp +++ b/libraries/AP_LandingGear/AP_LandingGear.cpp @@ -174,7 +174,7 @@ void AP_LandingGear::deploy() // set deployed flag _deployed = true; _have_changed = true; - AP::logger().Write_Event(LogEvent::LANDING_GEAR_DEPLOYED); + LOGGER_WRITE_EVENT(LogEvent::LANDING_GEAR_DEPLOYED); } /// retract - retract landing gear @@ -190,7 +190,7 @@ void AP_LandingGear::retract() // reset deployed flag _deployed = false; _have_changed = true; - AP::logger().Write_Event(LogEvent::LANDING_GEAR_RETRACTED); + LOGGER_WRITE_EVENT(LogEvent::LANDING_GEAR_RETRACTED); // send message only if output has been configured if (SRV_Channels::function_assigned(SRV_Channel::k_landing_gear_control)) { @@ -303,6 +303,7 @@ void AP_LandingGear::update(float height_above_ground_m) _last_height_above_ground = alt_m; } +#if HAL_LOGGING_ENABLED // log weight on wheels state void AP_LandingGear::log_wow_state(LG_WOW_State state) { @@ -310,6 +311,7 @@ void AP_LandingGear::log_wow_state(LG_WOW_State state) AP_HAL::micros64(), (int8_t)gear_state_current, (int8_t)state); } +#endif bool AP_LandingGear::check_before_land(void) { diff --git a/libraries/AP_LandingGear/AP_LandingGear.h b/libraries/AP_LandingGear/AP_LandingGear.h index 6cafc77d5ad89d..cfa0eebaae7faf 100644 --- a/libraries/AP_LandingGear/AP_LandingGear.h +++ b/libraries/AP_LandingGear/AP_LandingGear.h @@ -8,6 +8,7 @@ #include #include +#include /// @class AP_LandingGear /// @brief Class managing the control of landing gear @@ -122,8 +123,12 @@ class AP_LandingGear { /// deploy - deploy the landing gear void deploy(); +#if HAL_LOGGING_ENABLED // log weight on wheels state void log_wow_state(LG_WOW_State state); +#else + void log_wow_state(LG_WOW_State state) {} +#endif static AP_LandingGear *_singleton; }; From a5ccb1d3128d59abffa4312a4731ab454938f093 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:06 +1000 Subject: [PATCH 0607/1335] AP_Landing: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_Landing/AP_Landing.cpp | 2 ++ libraries/AP_Landing/AP_Landing_Deepstall.cpp | 2 ++ libraries/AP_Landing/AP_Landing_Slope.cpp | 2 ++ 3 files changed, 6 insertions(+) diff --git a/libraries/AP_Landing/AP_Landing.cpp b/libraries/AP_Landing/AP_Landing.cpp index 211ecdd46f1da3..ca396805cf3128 100644 --- a/libraries/AP_Landing/AP_Landing.cpp +++ b/libraries/AP_Landing/AP_Landing.cpp @@ -625,6 +625,7 @@ bool AP_Landing::is_complete(void) const void AP_Landing::Log(void) const { +#if HAL_LOGGING_ENABLED switch (type) { case TYPE_STANDARD_GLIDE_SLOPE: type_slope_log(); @@ -637,6 +638,7 @@ void AP_Landing::Log(void) const default: break; } +#endif } /* diff --git a/libraries/AP_Landing/AP_Landing_Deepstall.cpp b/libraries/AP_Landing/AP_Landing_Deepstall.cpp index 0a690acbeb631d..e465b869de1a60 100644 --- a/libraries/AP_Landing/AP_Landing_Deepstall.cpp +++ b/libraries/AP_Landing/AP_Landing_Deepstall.cpp @@ -456,6 +456,7 @@ const AP_PIDInfo& AP_Landing_Deepstall::get_pid_info(void) const return ds_PID.get_pid_info(); } +#if HAL_LOGGING_ENABLED void AP_Landing_Deepstall::Log(void) const { const AP_PIDInfo& pid_info = ds_PID.get_pid_info(); struct log_DSTL pkt = { @@ -479,6 +480,7 @@ void AP_Landing_Deepstall::Log(void) const { }; AP::logger().WriteBlock(&pkt, sizeof(pkt)); } +#endif // termination handling, expected to set the servo outputs bool AP_Landing_Deepstall::terminate(void) { diff --git a/libraries/AP_Landing/AP_Landing_Slope.cpp b/libraries/AP_Landing/AP_Landing_Slope.cpp index 4ec0c7cfa7c15d..7b4182e0afd6a7 100644 --- a/libraries/AP_Landing/AP_Landing_Slope.cpp +++ b/libraries/AP_Landing/AP_Landing_Slope.cpp @@ -407,6 +407,7 @@ bool AP_Landing::type_slope_is_complete(void) const return (type_slope_stage == SlopeStage::FINAL); } +#if HAL_LOGGING_ENABLED void AP_Landing::type_slope_log(void) const { // @LoggerMessage: LAND @@ -429,6 +430,7 @@ void AP_Landing::type_slope_log(void) const (double)alt_offset, (double)height_flare_log); } +#endif bool AP_Landing::type_slope_is_throttle_suppressed(void) const { From 9168a8fc500cf40ae710b96d99c3f1057f87f49f Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:06 +1000 Subject: [PATCH 0608/1335] AP_Math: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_Math/SCurve.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AP_Math/SCurve.cpp b/libraries/AP_Math/SCurve.cpp index 074b3e06036e7e..fa907ec87c48ce 100644 --- a/libraries/AP_Math/SCurve.cpp +++ b/libraries/AP_Math/SCurve.cpp @@ -883,6 +883,7 @@ void SCurve::calculate_path(float Sm, float Jm, float V0, float Am, float Vm, fl // @Field: t4_out: segment duration // @Field: t6_out: segment duration +#if HAL_LOGGING_ENABLED static bool logged_scve; // only log once if (!logged_scve) { logged_scve = true; @@ -906,6 +907,8 @@ void SCurve::calculate_path(float Sm, float Jm, float V0, float Am, float Vm, fl (double)t6_out ); } +#endif // HAL_LOGGING_ENABLED + #endif // APM_BUILD_COPTER_OR_HELI Jm_out = 0.0f; From f930c38712b045cd7fb419ac37e689cf76102315 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:06 +1000 Subject: [PATCH 0609/1335] APM_Control: allow compilation with HAL_LOGGING_ENABLED false --- libraries/APM_Control/AP_AutoTune.cpp | 2 ++ libraries/APM_Control/AR_PosControl.cpp | 2 ++ 2 files changed, 4 insertions(+) diff --git a/libraries/APM_Control/AP_AutoTune.cpp b/libraries/APM_Control/AP_AutoTune.cpp index 87c84ee94a1c34..d93dbb0d3a6bee 100644 --- a/libraries/APM_Control/AP_AutoTune.cpp +++ b/libraries/APM_Control/AP_AutoTune.cpp @@ -247,6 +247,7 @@ void AP_AutoTune::update(AP_PIDInfo &pinfo, float scaler, float angle_err_deg) const uint32_t now = AP_HAL::millis(); +#if HAL_LOGGING_ENABLED if (now - last_log_ms >= 40) { // log at 25Hz struct log_ATRP pkt = { @@ -269,6 +270,7 @@ void AP_AutoTune::update(AP_PIDInfo &pinfo, float scaler, float angle_err_deg) AP::logger().WriteBlock(&pkt, sizeof(pkt)); last_log_ms = now; } +#endif if (new_state == state) { if (state == ATState::IDLE && diff --git a/libraries/APM_Control/AR_PosControl.cpp b/libraries/APM_Control/AR_PosControl.cpp index 4107082558054b..112c508934b609 100644 --- a/libraries/APM_Control/AR_PosControl.cpp +++ b/libraries/APM_Control/AR_PosControl.cpp @@ -363,6 +363,7 @@ void AR_PosControl::get_srate(float &velocity_srate) velocity_srate = _pid_vel.get_pid_info_x().slew_rate; } +#if HAL_LOGGING_ENABLED // write PSC logs void AR_PosControl::write_log() { @@ -401,6 +402,7 @@ void AR_PosControl::write_log() _accel_target.y * 100.0, // target accel curr_accel_NED.y); // accel } +#endif /// initialise ekf xy position reset check void AR_PosControl::init_ekf_xy_reset() From bccfd98d0e3bd3584273bee325e1fa8fbccc1dfe Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:07 +1000 Subject: [PATCH 0610/1335] AP_Motors: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_Motors/AP_MotorsMulticopter.cpp | 2 ++ libraries/AP_Motors/AP_MotorsMulticopter.h | 2 ++ libraries/AP_Motors/AP_Motors_Class.h | 3 +++ 3 files changed, 7 insertions(+) diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.cpp b/libraries/AP_Motors/AP_MotorsMulticopter.cpp index 5359ad16e70409..cc7eb0fd3e7f7a 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -378,6 +378,7 @@ float AP_MotorsMulticopter::get_current_limit_max_throttle() return get_throttle_hover() + ((1.0 - get_throttle_hover()) * _throttle_limit); } +#if HAL_LOGGING_ENABLED // 10hz logging of voltage scaling and max trust void AP_MotorsMulticopter::Log_Write() { @@ -393,6 +394,7 @@ void AP_MotorsMulticopter::Log_Write() }; AP::logger().WriteBlock(&pkt_mot, sizeof(pkt_mot)); } +#endif // convert actuator output (0~1) range to pwm range int16_t AP_MotorsMulticopter::output_to_pwm(float actuator) diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.h b/libraries/AP_Motors/AP_MotorsMulticopter.h index f6e07e204a74c4..3f97e5105a3bda 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.h +++ b/libraries/AP_Motors/AP_MotorsMulticopter.h @@ -89,8 +89,10 @@ class AP_MotorsMulticopter : public AP_Motors { // convert values to PWM min and max if not configured void convert_pwm_min_max_param(int16_t radio_min, int16_t radio_max); +#if HAL_LOGGING_ENABLED // 10hz logging of voltage scaling and max trust void Log_Write() override; +#endif // Run arming checks bool arming_checks(size_t buflen, char *buffer) const override; diff --git a/libraries/AP_Motors/AP_Motors_Class.h b/libraries/AP_Motors/AP_Motors_Class.h index b8b39fbfb55665..92c62bf0540773 100644 --- a/libraries/AP_Motors/AP_Motors_Class.h +++ b/libraries/AP_Motors/AP_Motors_Class.h @@ -5,6 +5,7 @@ #include // filter library #include #include +#include // offsets for motors in motor_out and _motor_filtered arrays #define AP_MOTORS_MOT_1 0U @@ -275,8 +276,10 @@ class AP_Motors { void set_frame_string(const char * str); #endif +#if HAL_LOGGING_ENABLED // write log, to be called at 10hz virtual void Log_Write() {}; +#endif enum MotorOptions : uint8_t { BATT_RAW_VOLTAGE = (1 << 0U) From a6db3bd069efc21817d93cbdc9894da53fbc4b98 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:07 +1000 Subject: [PATCH 0611/1335] AP_Mount: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_Mount/AP_Mount.cpp | 2 ++ libraries/AP_Mount/AP_Mount_Backend.cpp | 2 ++ libraries/AP_Mount/AP_Mount_SoloGimbal.cpp | 11 +++++++++-- libraries/AP_Mount/SoloGimbal.cpp | 2 ++ libraries/AP_Mount/SoloGimbal_Parameters.cpp | 4 +++- 5 files changed, 18 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Mount/AP_Mount.cpp b/libraries/AP_Mount/AP_Mount.cpp index 4bb18ad3608b58..b6e7543ec01ce8 100644 --- a/libraries/AP_Mount/AP_Mount.cpp +++ b/libraries/AP_Mount/AP_Mount.cpp @@ -712,6 +712,7 @@ void AP_Mount::set_attitude_euler(uint8_t instance, float roll_deg, float pitch_ backend->set_attitude_euler(roll_deg, pitch_deg, yaw_bf_deg); } +#if HAL_LOGGING_ENABLED // write mount log packet for all backends void AP_Mount::write_log() { @@ -731,6 +732,7 @@ void AP_Mount::write_log(uint8_t instance, uint64_t timestamp_us) } backend->write_log(timestamp_us); } +#endif // point at system ID sysid void AP_Mount::set_target_sysid(uint8_t instance, uint8_t sysid) diff --git a/libraries/AP_Mount/AP_Mount_Backend.cpp b/libraries/AP_Mount/AP_Mount_Backend.cpp index e9760c7ae08e9d..28536134adaee3 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.cpp +++ b/libraries/AP_Mount/AP_Mount_Backend.cpp @@ -409,6 +409,7 @@ bool AP_Mount_Backend::handle_global_position_int(uint8_t msg_sysid, const mavli return true; } +#if HAL_LOGGING_ENABLED // write mount log packet void AP_Mount_Backend::write_log(uint64_t timestamp_us) { @@ -456,6 +457,7 @@ void AP_Mount_Backend::write_log(uint64_t timestamp_us) }; AP::logger().WriteCriticalBlock(&pkt, sizeof(pkt)); } +#endif #if AP_MOUNT_POI_TO_LATLONALT_ENABLED // get poi information. Returns true on success and fills in gimbal attitude, location and poi location diff --git a/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp b/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp index 6dbf8cdbd3b260..b188f945a2f23f 100644 --- a/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp +++ b/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp @@ -125,19 +125,26 @@ void AP_Mount_SoloGimbal::handle_gimbal_report(mavlink_channel_t chan, const mav _gimbal.update_target(Vector3f{mnt_target.angle_rad.roll, mnt_target.angle_rad.pitch, mnt_target.angle_rad.get_bf_yaw()}); _gimbal.receive_feedback(chan,msg); +#if HAL_LOGGING_ENABLED AP_Logger *logger = AP_Logger::get_singleton(); if (logger == nullptr) { return; } - - if(!_params_saved && logger->logging_started()) { +#endif + if(!_params_saved +#if HAL_LOGGING_ENABLED + && logger->logging_started() +#endif + ) { _gimbal.fetch_params(); //last parameter save might not be stored in logger so retry _params_saved = true; } +#if HAL_LOGGING_ENABLED if (_gimbal.get_log_dt() > 1.0f/25.0f) { _gimbal.write_logs(); } +#endif } void AP_Mount_SoloGimbal::handle_param_value(const mavlink_message_t &msg) diff --git a/libraries/AP_Mount/SoloGimbal.cpp b/libraries/AP_Mount/SoloGimbal.cpp index 01b8aec8297b5e..4503c02cec3f5c 100644 --- a/libraries/AP_Mount/SoloGimbal.cpp +++ b/libraries/AP_Mount/SoloGimbal.cpp @@ -400,6 +400,7 @@ void SoloGimbal::update_target(const Vector3f &newTarget) _att_target_euler_rad.x = constrain_float(_att_target_euler_rad.x,radians(-30),radians(30)); } +#if HAL_LOGGING_ENABLED void SoloGimbal::write_logs() { AP_Logger &logger = AP::logger(); @@ -481,6 +482,7 @@ void SoloGimbal::write_logs() _log_del_ang.zero(); _log_del_vel.zero(); } +#endif bool SoloGimbal::joints_near_limits() const { diff --git a/libraries/AP_Mount/SoloGimbal_Parameters.cpp b/libraries/AP_Mount/SoloGimbal_Parameters.cpp index 8245086ba32a72..60bf156acb3ba2 100644 --- a/libraries/AP_Mount/SoloGimbal_Parameters.cpp +++ b/libraries/AP_Mount/SoloGimbal_Parameters.cpp @@ -187,10 +187,12 @@ void SoloGimbal_Parameters::handle_param_value(const mavlink_message_t &msg) mavlink_param_value_t packet; mavlink_msg_param_value_decode(&msg, &packet); +#if HAL_LOGGING_ENABLED AP_Logger *logger = AP_Logger::get_singleton(); if (logger != nullptr) { logger->Write_Parameter(packet.param_id, packet.param_value); } +#endif for(uint8_t i=0; i Date: Fri, 14 Jul 2023 10:58:07 +1000 Subject: [PATCH 0612/1335] AP_NavEKF2: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_NavEKF2/AP_NavEKF2_Logging.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Logging.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Logging.cpp index 5f5d25f048ae6c..73874b775f95cf 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Logging.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Logging.cpp @@ -1,3 +1,7 @@ +#include + +#if HAL_LOGGING_ENABLED + #include "AP_NavEKF2.h" #include "AP_NavEKF2_core.h" @@ -331,3 +335,5 @@ void NavEKF2_core::Log_Write_GSF(uint64_t time_us) const } yawEstimator->Log_Write(time_us, LOG_NKY0_MSG, LOG_NKY1_MSG, DAL_CORE(core_index)); } + +#endif // HAL_LOGGING_ENABLED From 0afed2f8c2fd8f53afa8d29e908a40c8e672ec47 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:07 +1000 Subject: [PATCH 0613/1335] AP_NavEKF3: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_NavEKF3/AP_NavEKF3_Logging.cpp | 6 ++++++ libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp | 2 ++ 2 files changed, 8 insertions(+) diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_Logging.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_Logging.cpp index 100c47a253c87d..1f60ae65f932c6 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_Logging.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_Logging.cpp @@ -1,3 +1,7 @@ +#include + +#if HAL_LOGGING_ENABLED + #include "AP_NavEKF3.h" #include "AP_NavEKF3_core.h" @@ -440,3 +444,5 @@ void NavEKF3_core::Log_Write_GSF(uint64_t time_us) } yawEstimator->Log_Write(time_us, LOG_XKY0_MSG, LOG_XKY1_MSG, DAL_CORE(core_index)); } + +#endif // HAL_LOGGING_ENABLED diff --git a/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp b/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp index e409061698bf2c..9ebe777515a84e 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3_Measurements.cpp @@ -1394,6 +1394,7 @@ void NavEKF3_core::updateMovementCheck(void) if (logStatusChange || imuSampleTime_ms - lastMoveCheckLogTime_ms > 200) { lastMoveCheckLogTime_ms = imuSampleTime_ms; +#if HAL_LOGGING_ENABLED const struct log_XKFM pkt{ LOG_PACKET_HEADER_INIT(LOG_XKFM_MSG), time_us : dal.micros64(), @@ -1405,6 +1406,7 @@ void NavEKF3_core::updateMovementCheck(void) accel_diff_ratio : float(accel_diff_ratio), }; AP::logger().WriteBlock(&pkt, sizeof(pkt)); +#endif } } From a9b328e4de6710df3df068831fb2cda216a4d0f1 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:07 +1000 Subject: [PATCH 0614/1335] AP_NavEKF: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_NavEKF/AP_NavEKF_Source.cpp | 2 ++ libraries/AP_NavEKF/EKFGSF_Logging.cpp | 4 ++++ 2 files changed, 6 insertions(+) diff --git a/libraries/AP_NavEKF/AP_NavEKF_Source.cpp b/libraries/AP_NavEKF/AP_NavEKF_Source.cpp index 0f80af9f69e37f..2805bb81fbf0cc 100644 --- a/libraries/AP_NavEKF/AP_NavEKF_Source.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF_Source.cpp @@ -153,12 +153,14 @@ void AP_NavEKF_Source::setPosVelYawSourceSet(uint8_t source_set_idx) // sanity check source idx if (source_set_idx < AP_NAKEKF_SOURCE_SET_MAX) { active_source_set = source_set_idx; +#if HAL_LOGGING_ENABLED static const LogEvent evt[AP_NAKEKF_SOURCE_SET_MAX] { LogEvent::EK3_SOURCES_SET_TO_PRIMARY, LogEvent::EK3_SOURCES_SET_TO_SECONDARY, LogEvent::EK3_SOURCES_SET_TO_TERTIARY, }; AP::logger().Write_Event(evt[active_source_set]); +#endif } } diff --git a/libraries/AP_NavEKF/EKFGSF_Logging.cpp b/libraries/AP_NavEKF/EKFGSF_Logging.cpp index 64673085ce9f91..68e57afa7b7bd7 100644 --- a/libraries/AP_NavEKF/EKFGSF_Logging.cpp +++ b/libraries/AP_NavEKF/EKFGSF_Logging.cpp @@ -2,6 +2,8 @@ #include +#if HAL_LOGGING_ENABLED + #pragma GCC diagnostic ignored "-Wnarrowing" void EKFGSF_yaw::Log_Write(uint64_t time_us, LogMessages id0, LogMessages id1, uint8_t core_index) @@ -48,3 +50,5 @@ void EKFGSF_yaw::Log_Write(uint64_t time_us, LogMessages id0, LogMessages id1, u }; AP::logger().WriteBlock(&ky1, sizeof(ky1)); } + +#endif // HAL_LOGGING_ENABLED From db5591a0ea29924d9827bb92e9a87166ca65b099 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:07 +1000 Subject: [PATCH 0615/1335] AP_OpticalFlow: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_OpticalFlow/AP_OpticalFlow.cpp | 1 + libraries/AP_OpticalFlow/AP_OpticalFlow_Calibrator.cpp | 1 + libraries/AP_OpticalFlow/AP_OpticalFlow_Calibrator.h | 3 +++ 3 files changed, 5 insertions(+) diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp index be86676d59ac56..0a5c89aa6689d0 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow.cpp @@ -14,6 +14,7 @@ #include "AP_OpticalFlow_UPFLOW.h" #include #include +#include extern const AP_HAL::HAL& hal; diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_Calibrator.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_Calibrator.cpp index a23397881e3aaa..6b28d68d4c5448 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_Calibrator.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_Calibrator.cpp @@ -22,6 +22,7 @@ #include #include +#include const uint32_t AP_OPTICALFLOW_CAL_TIMEOUT_SEC = 120; // calibration timesout after 120 seconds const uint32_t AP_OPTICALFLOW_CAL_STATUSINTERVAL_SEC = 3; // status updates printed at 3 second intervals diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_Calibrator.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_Calibrator.h index 13b9c5c0dc8c99..3f894ce4751472 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_Calibrator.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_Calibrator.h @@ -1,6 +1,7 @@ #pragma once #include +#include #define AP_OPTICALFLOW_CAL_MAX_SAMPLES 50 // number of samples required before calibration begins @@ -53,8 +54,10 @@ class AP_OpticalFlow_Calibrator { // calculate mean squared residual for all samples of a single axis (0 or 1) given a scalar parameter float calc_mean_squared_residuals(uint8_t axis, float scalar) const; +#if HAL_LOGGING_ENABLED // log a sample void log_sample(uint8_t axis, uint8_t sample_num, float flow_rate, float body_rate, float los_pred); +#endif // calibration states enum class CalState { From 1cc2517e1e95d74a803afeed3aba894fc50c39b8 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:07 +1000 Subject: [PATCH 0616/1335] AP_Parachute: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_Parachute/AP_Parachute.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Parachute/AP_Parachute.cpp b/libraries/AP_Parachute/AP_Parachute.cpp index 4cdf7ce692443c..aae6ea9bc9b942 100644 --- a/libraries/AP_Parachute/AP_Parachute.cpp +++ b/libraries/AP_Parachute/AP_Parachute.cpp @@ -93,7 +93,7 @@ void AP_Parachute::enabled(bool on_off) // clear release_time _release_time = 0; - AP::logger().Write_Event(_enabled ? LogEvent::PARACHUTE_ENABLED : LogEvent::PARACHUTE_DISABLED); + LOGGER_WRITE_EVENT(_enabled ? LogEvent::PARACHUTE_ENABLED : LogEvent::PARACHUTE_DISABLED); } /// release - release parachute @@ -105,7 +105,7 @@ void AP_Parachute::release() } GCS_SEND_TEXT(MAV_SEVERITY_INFO,"Parachute: Released"); - AP::logger().Write_Event(LogEvent::PARACHUTE_RELEASED); + LOGGER_WRITE_EVENT(LogEvent::PARACHUTE_RELEASED); // set release time to current system time if (_release_time == 0) { From bf49716520d895178721fdd7d88661f35c50a9b0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:07 +1000 Subject: [PATCH 0617/1335] AP_PiccoloCAN: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_PiccoloCAN/AP_PiccoloCAN.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_PiccoloCAN/AP_PiccoloCAN.cpp b/libraries/AP_PiccoloCAN/AP_PiccoloCAN.cpp index ef07781772cec2..bbaec88f3e4d03 100644 --- a/libraries/AP_PiccoloCAN/AP_PiccoloCAN.cpp +++ b/libraries/AP_PiccoloCAN/AP_PiccoloCAN.cpp @@ -361,6 +361,7 @@ void AP_PiccoloCAN::update() } #endif // AP_EFI_CURRAWONG_ECU_ENABLED +#if HAL_LOGGING_ENABLED AP_Logger *logger = AP_Logger::get_singleton(); // Push received telemetry data into the logging system @@ -397,6 +398,9 @@ void AP_PiccoloCAN::update() } } } +#else + (void)timestamp; +#endif // HAL_LOGGING_ENABLED } #if HAL_GCS_ENABLED From 38115bd5fbadf0c65e221be626b16cc1d665b000 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:07 +1000 Subject: [PATCH 0618/1335] AP_Rally: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_Rally/AP_Rally.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_Rally/AP_Rally.cpp b/libraries/AP_Rally/AP_Rally.cpp index d3b8284a963aa6..eb112d1c81e71a 100644 --- a/libraries/AP_Rally/AP_Rally.cpp +++ b/libraries/AP_Rally/AP_Rally.cpp @@ -116,7 +116,9 @@ bool AP_Rally::set_rally_point_with_index(uint8_t i, const RallyLocation &rallyL _last_change_time_ms = AP_HAL::millis(); +#if HAL_LOGGING_ENABLED AP::logger().Write_RallyPoint(_rally_point_total_count, i, rallyLoc); +#endif return true; } From 330dd7221f19eb042c17385600f24f9130d3b790 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:07 +1000 Subject: [PATCH 0619/1335] AP_RangeFinder: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_RangeFinder/AP_RangeFinder.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder.cpp b/libraries/AP_RangeFinder/AP_RangeFinder.cpp index b9ea6f90765edd..8d245855c6e4b2 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder.cpp @@ -786,6 +786,7 @@ bool RangeFinder::get_temp(enum Rotation orientation, float &temp) const return backend->get_temp(temp); } +#if HAL_LOGGING_ENABLED // Write an RFND (rangefinder) packet void RangeFinder::Log_RFND() const { @@ -816,6 +817,7 @@ void RangeFinder::Log_RFND() const AP::logger().WriteBlock(&pkt, sizeof(pkt)); } } +#endif // HAL_LOGGING_ENABLED bool RangeFinder::prearm_healthy(char *failure_msg, const uint8_t failure_msg_len) const { From 2d3fed97845c44473cf92de3ff046072fa0047f3 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:08 +1000 Subject: [PATCH 0620/1335] AP_Scheduler: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_Scheduler/AP_Scheduler.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_Scheduler/AP_Scheduler.cpp b/libraries/AP_Scheduler/AP_Scheduler.cpp index 93f55a22778646..5fd91703b114b3 100644 --- a/libraries/AP_Scheduler/AP_Scheduler.cpp +++ b/libraries/AP_Scheduler/AP_Scheduler.cpp @@ -420,6 +420,7 @@ void AP_Scheduler::loop() #endif } +#if HAL_LOGGING_ENABLED void AP_Scheduler::update_logging() { if (debug_flags()) { @@ -462,6 +463,7 @@ void AP_Scheduler::Log_Write_Performance() }; AP::logger().WriteCriticalBlock(&pkt, sizeof(pkt)); } +#endif // HAL_LOGGING_ENABLED // display task statistics as text buffer for @SYS/tasks.txt void AP_Scheduler::task_info(ExpandingString &str) From 5bb3e0aa18e8fc52a5e5caddb55d7b3373e625c9 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:08 +1000 Subject: [PATCH 0621/1335] AP_SmartRTL: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_SmartRTL/AP_SmartRTL.cpp | 2 ++ libraries/AP_SmartRTL/AP_SmartRTL.h | 5 +++++ 2 files changed, 7 insertions(+) diff --git a/libraries/AP_SmartRTL/AP_SmartRTL.cpp b/libraries/AP_SmartRTL/AP_SmartRTL.cpp index 0de442dc7faaad..173d12c8f4079c 100644 --- a/libraries/AP_SmartRTL/AP_SmartRTL.cpp +++ b/libraries/AP_SmartRTL/AP_SmartRTL.cpp @@ -869,6 +869,7 @@ void AP_SmartRTL::deactivate(SRTL_Actions action, const char *reason) GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "SmartRTL deactivated: %s", reason); } +#if HAL_LOGGING_ENABLED // logging void AP_SmartRTL::log_action(SRTL_Actions action, const Vector3f &point) const { @@ -876,6 +877,7 @@ void AP_SmartRTL::log_action(SRTL_Actions action, const Vector3f &point) const AP::logger().Write_SRTL(_active, _path_points_count, _path_points_max, action, point); } } +#endif // returns true if the two loops overlap (used within add_loop to determine which loops to keep or throw away) bool AP_SmartRTL::loops_overlap(const prune_loop_t &loop1, const prune_loop_t &loop2) const diff --git a/libraries/AP_SmartRTL/AP_SmartRTL.h b/libraries/AP_SmartRTL/AP_SmartRTL.h index a83cad692a0344..144762e512839d 100644 --- a/libraries/AP_SmartRTL/AP_SmartRTL.h +++ b/libraries/AP_SmartRTL/AP_SmartRTL.h @@ -3,6 +3,7 @@ #include #include #include +#include // definitions and macros #define SMARTRTL_ACCURACY_DEFAULT 2.0f // default _ACCURACY parameter value. Points will be no closer than this distance (in meters) together. @@ -172,8 +173,12 @@ class AP_SmartRTL { // de-activate SmartRTL, send warning to GCS and logger void deactivate(SRTL_Actions action, const char *reason); +#if HAL_LOGGING_ENABLED // logging void log_action(SRTL_Actions action, const Vector3f &point = Vector3f()) const; +#else + void log_action(SRTL_Actions action, const Vector3f &point = Vector3f()) const {} +#endif // parameters AP_Float _accuracy; From 7d798943fc5cf9705ce4185b8159d6e94a0e1860 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:08 +1000 Subject: [PATCH 0622/1335] AP_Soaring: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_Soaring/AP_Soaring.cpp | 4 ++++ libraries/AP_Soaring/Variometer.cpp | 6 +++++- 2 files changed, 9 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Soaring/AP_Soaring.cpp b/libraries/AP_Soaring/AP_Soaring.cpp index 47279b5d7b5149..56fb621b19b7a8 100644 --- a/libraries/AP_Soaring/AP_Soaring.cpp +++ b/libraries/AP_Soaring/AP_Soaring.cpp @@ -337,6 +337,7 @@ void SoaringController::update_thermalling() _position_x_filter.apply(_ekf.X[2], deltaT); _position_y_filter.apply(_ekf.X[3], deltaT); +#if HAL_LOGGING_ENABLED // write log - save the data. // @LoggerMessage: SOAR // @Vehicles: Plane @@ -367,6 +368,7 @@ void SoaringController::update_thermalling() (double)wind_drift.x, (double)wind_drift.y, (double)_thermalability); +#endif } void SoaringController::update_cruising() @@ -388,6 +390,7 @@ void SoaringController::update_cruising() // Update the calculation. _speedToFly.update(wx, wz, thermal_vspeed, CLmin, CLmax); +#if HAL_LOGGING_ENABLED AP::logger().WriteStreaming("SORC", "TimeUS,wx,wz,wexp,CLmin,CLmax,Vopt", "Qffffff", AP_HAL::micros64(), (double)wx, @@ -396,6 +399,7 @@ void SoaringController::update_cruising() (double)CLmin, (double)CLmax, (double)_speedToFly.speed_to_fly()); +#endif } void SoaringController::update_vario() diff --git a/libraries/AP_Soaring/Variometer.cpp b/libraries/AP_Soaring/Variometer.cpp index 835e32ea71d0a3..c3ed0fc0cd24e6 100644 --- a/libraries/AP_Soaring/Variometer.cpp +++ b/libraries/AP_Soaring/Variometer.cpp @@ -79,6 +79,7 @@ void Variometer::update(const float thermal_bank) _expected_thermalling_sink = calculate_aircraft_sinkrate(radians(thermal_bank)); +#if HAL_LOGGING_ENABLED // @LoggerMessage: VAR // @Vehicles: Plane // @Description: Variometer data @@ -107,9 +108,12 @@ void Variometer::update(const float thermal_bank) (double)_expected_thermalling_sink, (double)dsp, (double)dsp_bias); +#else + (void)filtered_reading; + (void)smoothed_climb_rate; +#endif } - float Variometer::calculate_aircraft_sinkrate(float phi) const { // Remove aircraft sink rate From 512c1f030fd3a9a6fd95685dbc5a5e69f79c6f75 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:08 +1000 Subject: [PATCH 0623/1335] AP_TECS: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_TECS/AP_TECS.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/libraries/AP_TECS/AP_TECS.cpp b/libraries/AP_TECS/AP_TECS.cpp index 7ca36846257b06..c5aaeabc0e082d 100644 --- a/libraries/AP_TECS/AP_TECS.cpp +++ b/libraries/AP_TECS/AP_TECS.cpp @@ -788,6 +788,7 @@ void AP_TECS::_update_throttle_with_airspeed(void) // Sum the components. _throttle_dem = _throttle_dem + _integTHR_state; +#if HAL_LOGGING_ENABLED if (AP::logger().should_log(_log_bitmask)){ AP::logger().WriteStreaming("TEC3","TimeUS,KED,PED,KEDD,PEDD,TEE,TEDE,FFT,Imin,Imax,I,Emin,Emax", "Qffffffffffff", @@ -805,6 +806,7 @@ void AP_TECS::_update_throttle_with_airspeed(void) (double)SPE_err_min, (double)SPE_err_max); } +#endif } // Constrain throttle demand and record clipping @@ -1057,6 +1059,7 @@ void AP_TECS::_update_pitch(void) _last_pitch_dem = _pitch_dem; +#if HAL_LOGGING_ENABLED if (AP::logger().should_log(_log_bitmask)){ // log to AP_Logger // @LoggerMessage: TEC2 @@ -1094,6 +1097,7 @@ void AP_TECS::_update_pitch(void) (double)_PITCHminf, (double)_PITCHmaxf); } +#endif } void AP_TECS::_initialise_states(int32_t ptchMinCO_cd, float hgt_afe) @@ -1372,6 +1376,7 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm, _flags.badDescent = false; } +#if HAL_LOGGING_ENABLED if (AP::logger().should_log(_log_bitmask)){ // log to AP_Logger // @LoggerMessage: TECS @@ -1414,4 +1419,5 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm, (double)_TAS_rate_dem, _flags_byte); } +#endif } From 3ae9e36bd3b20df344f47cad4021fd8b4a0c85f9 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:08 +1000 Subject: [PATCH 0624/1335] AP_TemperatureSensor: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_TemperatureSensor/AP_TemperatureSensor_Backend.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Backend.cpp b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Backend.cpp index 4aadb2cf49a03f..e1a68421e2b693 100644 --- a/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Backend.cpp +++ b/libraries/AP_TemperatureSensor/AP_TemperatureSensor_Backend.cpp @@ -40,6 +40,7 @@ bool AP_TemperatureSensor_Backend::healthy(void) const return (_state.last_time_ms > 0) && (AP_HAL::millis() - _state.last_time_ms < 5000); } +#if HAL_LOGGING_ENABLED void AP_TemperatureSensor_Backend::Log_Write_TEMP() const { AP::logger().Write("TEMP", @@ -49,6 +50,7 @@ void AP_TemperatureSensor_Backend::Log_Write_TEMP() const "Q" "B" "f" , // types AP_HAL::micros64(), _state.instance, _state.temperature); } +#endif void AP_TemperatureSensor_Backend::set_temperature(const float temperature) { From 573a7b172ea9b2a5bedcef3f95ec80c5b5b0ec46 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:08 +1000 Subject: [PATCH 0625/1335] AP_Terrain: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_Terrain/AP_Terrain.cpp | 3 +++ libraries/AP_Terrain/AP_Terrain.h | 3 +++ 2 files changed, 6 insertions(+) diff --git a/libraries/AP_Terrain/AP_Terrain.cpp b/libraries/AP_Terrain/AP_Terrain.cpp index 7e9e75403662ec..d2aab8bf1d8aba 100644 --- a/libraries/AP_Terrain/AP_Terrain.cpp +++ b/libraries/AP_Terrain/AP_Terrain.cpp @@ -26,6 +26,7 @@ #include #include #include +#include extern const AP_HAL::HAL& hal; @@ -439,6 +440,7 @@ bool AP_Terrain::pre_arm_checks(char *failure_msg, uint8_t failure_msg_len) cons return true; } +#if HAL_LOGGING_ENABLED void AP_Terrain::log_terrain_data() { if (!allocate()) { @@ -472,6 +474,7 @@ void AP_Terrain::log_terrain_data() }; AP::logger().WriteBlock(&pkt, sizeof(pkt)); } +#endif /* allocate terrain cache. Making this dynamically allocated allows diff --git a/libraries/AP_Terrain/AP_Terrain.h b/libraries/AP_Terrain/AP_Terrain.h index ff55ce0dbbcb05..8a6be4579db06c 100644 --- a/libraries/AP_Terrain/AP_Terrain.h +++ b/libraries/AP_Terrain/AP_Terrain.h @@ -27,6 +27,7 @@ #include #include #include +#include #define TERRAIN_DEBUG 0 @@ -172,10 +173,12 @@ class AP_Terrain { */ float lookahead(float bearing, float distance, float climb_ratio); +#if HAL_LOGGING_ENABLED /* log terrain status to AP_Logger */ void log_terrain_data(); +#endif /* get some statistics for TERRAIN_REPORT From 6c10b384422bc7e359587aa9507093e518fb5731 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:08 +1000 Subject: [PATCH 0626/1335] AP_Torqeedo: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_Torqeedo/AP_Torqeedo.cpp | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/libraries/AP_Torqeedo/AP_Torqeedo.cpp b/libraries/AP_Torqeedo/AP_Torqeedo.cpp index 1fd14eded794b3..fab624127f46ac 100644 --- a/libraries/AP_Torqeedo/AP_Torqeedo.cpp +++ b/libraries/AP_Torqeedo/AP_Torqeedo.cpp @@ -564,6 +564,7 @@ void AP_Torqeedo::parse_message() esc_temp, motor_temp); +#if HAL_LOGGING_ENABLED // log data if ((_options & options::LOG) != 0) { // @LoggerMessage: TRST @@ -592,6 +593,7 @@ void AP_Torqeedo::parse_message() _display_system_state.batt_voltage, _display_system_state.batt_current); } +#endif // send to GCS if ((_options & options::DEBUG_TO_GCS) != 0) { @@ -625,6 +627,7 @@ void AP_Torqeedo::parse_message() _display_system_setup.batt_type = _received_buff[9]; _display_system_setup.master_sw_version = UINT16_VALUE(_received_buff[10], _received_buff[11]); +#if HAL_LOGGING_ENABLED // log data if ((_options & options::LOG) != 0) { // @LoggerMessage: TRSE @@ -647,6 +650,7 @@ void AP_Torqeedo::parse_message() _display_system_setup.batt_type, _display_system_setup.master_sw_version); } +#endif // send to GCS if ((_options & options::DEBUG_TO_GCS) != 0) { @@ -694,6 +698,7 @@ void AP_Torqeedo::parse_message() _motor_param.pcb_temp, // esc temp _motor_param.stator_temp); // motor temp +#if HAL_LOGGING_ENABLED // log data if ((_options & options::LOG) != 0) { // @LoggerMessage: TRMP @@ -714,6 +719,7 @@ void AP_Torqeedo::parse_message() _motor_param.pcb_temp, _motor_param.stator_temp); } +#endif // send to GCS if ((_options & options::DEBUG_TO_GCS) != 0) { @@ -736,6 +742,7 @@ void AP_Torqeedo::parse_message() _motor_status.status_flags_value = _received_buff[2]; _motor_status.error_flags_value = UINT16_VALUE(_received_buff[3], _received_buff[4]); +#if HAL_LOGGING_ENABLED // log data if ((_options & options::LOG) != 0) { // @LoggerMessage: TRMS @@ -748,6 +755,7 @@ void AP_Torqeedo::parse_message() _motor_status.status_flags_value, _motor_status.error_flags_value); } +#endif // send to GCS if ((_options & options::DEBUG_TO_GCS) != 0) { @@ -1084,6 +1092,7 @@ void AP_Torqeedo::log_TRQD(bool force_logging) const bool health = healthy(); int16_t actual_motor_speed = get_motor_speed_limited(); +#if HAL_LOGGING_ENABLED if ((_options & options::LOG) != 0) { // @LoggerMessage: TRQD // @Description: Torqeedo Status @@ -1101,6 +1110,7 @@ void AP_Torqeedo::log_TRQD(bool force_logging) _parse_success_count, _parse_error_count); } +#endif if ((_options & options::DEBUG_TO_GCS) != 0) { GCS_SEND_TEXT(MAV_SEVERITY_INFO,"TRQD h:%u dspd:%d spd:%d succ:%ld err:%ld", From 62ac11666921bb504460b9b9bed1cb9ec3f89a84 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:08 +1000 Subject: [PATCH 0627/1335] AP_Tuning: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_Tuning/AP_Tuning.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/libraries/AP_Tuning/AP_Tuning.cpp b/libraries/AP_Tuning/AP_Tuning.cpp index b07aec2d8e6510..490416fdab8405 100644 --- a/libraries/AP_Tuning/AP_Tuning.cpp +++ b/libraries/AP_Tuning/AP_Tuning.cpp @@ -227,10 +227,14 @@ void AP_Tuning::check_input(uint8_t flightmode) changed = true; need_revert |= (1U << current_parm_index); set_value(current_parm, new_value); + +#if HAL_LOGGING_ENABLED Log_Write_Parameter_Tuning(new_value); +#endif } +#if HAL_LOGGING_ENABLED /* log a tuning change */ @@ -250,6 +254,7 @@ void AP_Tuning::Log_Write_Parameter_Tuning(float value) (double)value, (double)center_value); } +#endif /* save parameters in the set From 1b288416e161831bd0da4e8a786fee31f40c7f1f Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:08 +1000 Subject: [PATCH 0628/1335] AP_Vehicle: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_Vehicle/AP_Vehicle.cpp | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Vehicle/AP_Vehicle.cpp b/libraries/AP_Vehicle/AP_Vehicle.cpp index c94a4c2ee1b5a0..83a0e80fc76fb8 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.cpp +++ b/libraries/AP_Vehicle/AP_Vehicle.cpp @@ -476,7 +476,7 @@ void AP_Vehicle::loop() } const uint32_t new_internal_errors = AP::internalerror().errors(); if(_last_internal_errors != new_internal_errors) { - AP::logger().Write_Error(LogErrorSubsystem::INTERNAL_ERROR, LogErrorCode::INTERNAL_ERRORS_DETECTED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::INTERNAL_ERROR, LogErrorCode::INTERNAL_ERRORS_DETECTED); GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Internal Errors 0x%x", (unsigned)new_internal_errors); _last_internal_errors = new_internal_errors; } @@ -598,10 +598,12 @@ void AP_Vehicle::scheduler_delay_callback() static uint32_t last_1hz, last_50hz, last_5s; +#if HAL_LOGGING_ENABLED AP_Logger &logger = AP::logger(); // don't allow potentially expensive logging calls: logger.EnableWrites(false); +#endif const uint32_t tnow = AP_HAL::millis(); if (tnow - last_1hz > 1000) { @@ -626,7 +628,9 @@ void AP_Vehicle::scheduler_delay_callback() } } +#if HAL_LOGGING_ENABLED logger.EnableWrites(true); +#endif } // if there's been a watchdog reset, notify the world via a statustext: @@ -807,7 +811,7 @@ void AP_Vehicle::update_dynamic_notch_at_specified_rate() void AP_Vehicle::notify_no_such_mode(uint8_t mode_number) { GCS_SEND_TEXT(MAV_SEVERITY_WARNING,"No such mode %u", mode_number); - AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode_number)); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode_number)); } // reboot the vehicle in an orderly manner, doing various cleanups and From 03be6e13b75884a7f073c0ddd7c1296355e5f1d9 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:09 +1000 Subject: [PATCH 0629/1335] AP_VisualOdom: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp | 2 ++ libraries/AP_VisualOdom/AP_VisualOdom_Backend.h | 4 ++++ libraries/AP_VisualOdom/AP_VisualOdom_IntelT265.cpp | 4 ++++ libraries/AP_VisualOdom/AP_VisualOdom_Logging.cpp | 3 ++- libraries/AP_VisualOdom/AP_VisualOdom_MAV.cpp | 5 +++++ 5 files changed, 17 insertions(+), 1 deletion(-) diff --git a/libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp b/libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp index 568a4b6a0112d9..051981041d8421 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp +++ b/libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp @@ -66,11 +66,13 @@ void AP_VisualOdom_Backend::handle_vision_position_delta_msg(const mavlink_messa _frontend.get_pos_offset()); #endif +#if HAL_LOGGING_ENABLED // log sensor data Write_VisualOdom(time_delta_sec, angle_delta, position_delta, packet.confidence); +#endif } #endif // HAL_GCS_ENABLED diff --git a/libraries/AP_VisualOdom/AP_VisualOdom_Backend.h b/libraries/AP_VisualOdom/AP_VisualOdom_Backend.h index ce2033ca4ce2f2..9f5225aa9e9a4d 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom_Backend.h +++ b/libraries/AP_VisualOdom/AP_VisualOdom_Backend.h @@ -18,6 +18,8 @@ #if HAL_VISUALODOM_ENABLED +#include + class AP_VisualOdom_Backend { public: @@ -57,10 +59,12 @@ class AP_VisualOdom_Backend return _frontend.get_type(); } +#if HAL_LOGGING_ENABLED // Logging Functions void Write_VisualOdom(float time_delta, const Vector3f &angle_delta, const Vector3f &position_delta, float confidence); void Write_VisualPosition(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, float roll, float pitch, float yaw, float pos_err, float ang_err, uint8_t reset_counter, bool ignored); void Write_VisualVelocity(uint64_t remote_time_us, uint32_t time_ms, const Vector3f &vel, uint8_t reset_counter, bool ignored); +#endif AP_VisualOdom &_frontend; // reference to frontend uint32_t _last_update_ms; // system time of last update from sensor (used by health checks) diff --git a/libraries/AP_VisualOdom/AP_VisualOdom_IntelT265.cpp b/libraries/AP_VisualOdom/AP_VisualOdom_IntelT265.cpp index ebec6eebdd0e91..cc063d85901049 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom_IntelT265.cpp +++ b/libraries/AP_VisualOdom/AP_VisualOdom_IntelT265.cpp @@ -72,8 +72,10 @@ void AP_VisualOdom_IntelT265::handle_pose_estimate(uint64_t remote_time_us, uint float yaw; att.to_euler(roll, pitch, yaw); +#if HAL_LOGGING_ENABLED // log sensor data Write_VisualPosition(remote_time_us, time_ms, pos.x, pos.y, pos.z, degrees(roll), degrees(pitch), wrap_360(degrees(yaw)), posErr, angErr, reset_counter, !consume); +#endif // store corrected attitude for use in pre-arm checks _attitude_last = att; @@ -99,7 +101,9 @@ void AP_VisualOdom_IntelT265::handle_vision_speed_estimate(uint64_t remote_time_ // record time for health monitoring _last_update_ms = AP_HAL::millis(); +#if HAL_LOGGING_ENABLED Write_VisualVelocity(remote_time_us, time_ms, vel_corrected, reset_counter, !consume); +#endif } // apply rotation and correction to position diff --git a/libraries/AP_VisualOdom/AP_VisualOdom_Logging.cpp b/libraries/AP_VisualOdom/AP_VisualOdom_Logging.cpp index 36486b1e4a9f20..4a92a983606f8c 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom_Logging.cpp +++ b/libraries/AP_VisualOdom/AP_VisualOdom_Logging.cpp @@ -1,6 +1,7 @@ #include "AP_VisualOdom_Backend.h" +#include -#if HAL_VISUALODOM_ENABLED +#if HAL_VISUALODOM_ENABLED && HAL_LOGGING_ENABLED #include diff --git a/libraries/AP_VisualOdom/AP_VisualOdom_MAV.cpp b/libraries/AP_VisualOdom/AP_VisualOdom_MAV.cpp index 0117e56af84575..5e4af959fabcda 100644 --- a/libraries/AP_VisualOdom/AP_VisualOdom_MAV.cpp +++ b/libraries/AP_VisualOdom/AP_VisualOdom_MAV.cpp @@ -21,6 +21,7 @@ #include #include +#include // consume vision pose estimate data and send to EKF. distances in meters void AP_VisualOdom_MAV::handle_pose_estimate(uint64_t remote_time_us, uint32_t time_ms, float x, float y, float z, const Quaternion &attitude, float posErr, float angErr, uint8_t reset_counter) @@ -39,8 +40,10 @@ void AP_VisualOdom_MAV::handle_pose_estimate(uint64_t remote_time_us, uint32_t t float yaw; attitude.to_euler(roll, pitch, yaw); +#if HAL_LOGGING_ENABLED // log sensor data Write_VisualPosition(remote_time_us, time_ms, pos.x, pos.y, pos.z, degrees(roll), degrees(pitch), degrees(yaw), posErr, angErr, reset_counter, false); +#endif // record time for health monitoring _last_update_ms = AP_HAL::millis(); @@ -54,7 +57,9 @@ void AP_VisualOdom_MAV::handle_vision_speed_estimate(uint64_t remote_time_us, ui // record time for health monitoring _last_update_ms = AP_HAL::millis(); +#if HAL_LOGGING_ENABLED Write_VisualVelocity(remote_time_us, time_ms, vel, reset_counter, false); +#endif } #endif // AP_VISUALODOM_MAV_ENABLED From 9de01998c39b9c905205c740319b005ec8839f6c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:09 +1000 Subject: [PATCH 0630/1335] AP_WheelEncoder: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_WheelEncoder/AP_WheelEncoder.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_WheelEncoder/AP_WheelEncoder.cpp b/libraries/AP_WheelEncoder/AP_WheelEncoder.cpp index 2ca8cde3a34e38..610a7cd8e2bd7e 100644 --- a/libraries/AP_WheelEncoder/AP_WheelEncoder.cpp +++ b/libraries/AP_WheelEncoder/AP_WheelEncoder.cpp @@ -201,6 +201,7 @@ void AP_WheelEncoder::update(void) } } +#if HAL_LOGGING_ENABLED // log wheel encoder information void AP_WheelEncoder::Log_Write() const { @@ -219,6 +220,7 @@ void AP_WheelEncoder::Log_Write() const }; AP::logger().WriteBlock(&pkt, sizeof(pkt)); } +#endif // check if an instance is healthy bool AP_WheelEncoder::healthy(uint8_t instance) const From 8801b78a9cac2ee84b89a49796befe590df34a6c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:09 +1000 Subject: [PATCH 0631/1335] AP_Winch: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_Winch/AP_Winch.cpp | 2 ++ libraries/AP_Winch/AP_Winch.h | 3 +++ libraries/AP_Winch/AP_Winch_Backend.h | 4 ++++ libraries/AP_Winch/AP_Winch_Daiwa.cpp | 2 ++ libraries/AP_Winch/AP_Winch_Daiwa.h | 2 ++ libraries/AP_Winch/AP_Winch_PWM.cpp | 2 ++ libraries/AP_Winch/AP_Winch_PWM.h | 2 ++ 7 files changed, 17 insertions(+) diff --git a/libraries/AP_Winch/AP_Winch.cpp b/libraries/AP_Winch/AP_Winch.cpp index 4a3a41db4021e9..5738fdfea957b0 100644 --- a/libraries/AP_Winch/AP_Winch.cpp +++ b/libraries/AP_Winch/AP_Winch.cpp @@ -159,7 +159,9 @@ bool AP_Winch::pre_arm_check(char *failmsg, uint8_t failmsg_len) const } PASS_TO_BACKEND(update) +#if HAL_LOGGING_ENABLED PASS_TO_BACKEND(write_log) +#endif #undef PASS_TO_BACKEND diff --git a/libraries/AP_Winch/AP_Winch.h b/libraries/AP_Winch/AP_Winch.h index df1ecf9c896c8c..8a3b0f72a82179 100644 --- a/libraries/AP_Winch/AP_Winch.h +++ b/libraries/AP_Winch/AP_Winch.h @@ -23,6 +23,7 @@ #include #include #include +#include class AP_Winch_Backend; @@ -64,8 +65,10 @@ class AP_Winch { // send status to ground station void send_status(const class GCS_MAVLINK &channel); +#if HAL_LOGGING_ENABLED // write log void write_log(); +#endif // returns true if pre arm checks have passed bool pre_arm_check(char *failmsg, uint8_t failmsg_len) const; diff --git a/libraries/AP_Winch/AP_Winch_Backend.h b/libraries/AP_Winch/AP_Winch_Backend.h index 0504a753db86b0..d03adde34595b1 100644 --- a/libraries/AP_Winch/AP_Winch_Backend.h +++ b/libraries/AP_Winch/AP_Winch_Backend.h @@ -19,6 +19,8 @@ #if AP_WINCH_ENABLED +#include + class AP_Winch_Backend { public: AP_Winch_Backend(struct AP_Winch::Backend_Config &_config) : @@ -39,8 +41,10 @@ class AP_Winch_Backend { // send status to ground station virtual void send_status(const GCS_MAVLINK &channel) = 0; +#if HAL_LOGGING_ENABLED // write log virtual void write_log() = 0; +#endif // helper to check if option enabled bool option_enabled(AP_Winch::Options option) const { diff --git a/libraries/AP_Winch/AP_Winch_Daiwa.cpp b/libraries/AP_Winch/AP_Winch_Daiwa.cpp index d80a8f58760d3c..88f61844726317 100644 --- a/libraries/AP_Winch/AP_Winch_Daiwa.cpp +++ b/libraries/AP_Winch/AP_Winch_Daiwa.cpp @@ -86,6 +86,7 @@ void AP_Winch_Daiwa::send_status(const GCS_MAVLINK &channel) status_bitmask); } +#if HAL_LOGGING_ENABLED // write log void AP_Winch_Daiwa::write_log() { @@ -102,6 +103,7 @@ void AP_Winch_Daiwa::write_log() latest.voltage, constrain_int16(latest.motor_temp, INT8_MIN, INT8_MAX)); } +#endif // read incoming data from winch and update intermediate and latest structures void AP_Winch_Daiwa::read_data_from_winch() diff --git a/libraries/AP_Winch/AP_Winch_Daiwa.h b/libraries/AP_Winch/AP_Winch_Daiwa.h index 301a73d9e9b070..a49eb9e58fa3f2 100644 --- a/libraries/AP_Winch/AP_Winch_Daiwa.h +++ b/libraries/AP_Winch/AP_Winch_Daiwa.h @@ -52,8 +52,10 @@ class AP_Winch_Daiwa : public AP_Winch_Backend { // send status to ground station void send_status(const GCS_MAVLINK &channel) override; +#if HAL_LOGGING_ENABLED // write log void write_log() override; +#endif private: diff --git a/libraries/AP_Winch/AP_Winch_PWM.cpp b/libraries/AP_Winch/AP_Winch_PWM.cpp index ba8d89a8c4498b..7607cd97e26a46 100644 --- a/libraries/AP_Winch/AP_Winch_PWM.cpp +++ b/libraries/AP_Winch/AP_Winch_PWM.cpp @@ -93,6 +93,7 @@ void AP_Winch_PWM::send_status(const GCS_MAVLINK &channel) } // write log +#if HAL_LOGGING_ENABLED void AP_Winch_PWM::write_log() { AP::logger().Write_Winch( @@ -108,5 +109,6 @@ void AP_Winch_PWM::write_log() 0, // voltage (unsupported) 0); // temp (unsupported) } +#endif #endif // AP_WINCH_PWM_ENABLED diff --git a/libraries/AP_Winch/AP_Winch_PWM.h b/libraries/AP_Winch/AP_Winch_PWM.h index 58ef71f3c6bbc1..9fd6ff2eda6aad 100644 --- a/libraries/AP_Winch/AP_Winch_PWM.h +++ b/libraries/AP_Winch/AP_Winch_PWM.h @@ -36,8 +36,10 @@ class AP_Winch_PWM : public AP_Winch_Backend { // send status to ground station void send_status(const GCS_MAVLINK &channel) override; +#if HAL_LOGGING_ENABLED // write log void write_log() override; +#endif private: From 4cf71de64689d414dbd19c7d23d739b14ae163a4 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:09 +1000 Subject: [PATCH 0632/1335] GCS_MAVLink: allow compilation with HAL_LOGGING_ENABLED false --- libraries/GCS_MAVLink/GCS.cpp | 1 + libraries/GCS_MAVLink/GCS_Common.cpp | 25 ++++++++++++++++++- libraries/GCS_MAVLink/GCS_Param.cpp | 6 ++++- .../GCS_MAVLink/MissionItemProtocol_Rally.cpp | 2 ++ .../MissionItemProtocol_Waypoints.cpp | 2 ++ 5 files changed, 34 insertions(+), 2 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS.cpp b/libraries/GCS_MAVLink/GCS.cpp index f79133297f16ad..ee191bdef24a27 100644 --- a/libraries/GCS_MAVLink/GCS.cpp +++ b/libraries/GCS_MAVLink/GCS.cpp @@ -17,6 +17,7 @@ #include #include #include +#include #include "MissionItemProtocol_Waypoints.h" #include "MissionItemProtocol_Rally.h" diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index b5afa34ea05577..e72ed983fa9790 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -872,10 +872,12 @@ void GCS_MAVLINK::handle_radio_status(const mavlink_message_t &msg, bool log_rad } #endif +#if HAL_LOGGING_ENABLED //log rssi, noise, etc if logging Performance monitoring data if (log_radio) { AP::logger().Write_Radio(packet); } +#endif } void GCS_MAVLINK::handle_mission_item(const mavlink_message_t &msg) @@ -1838,6 +1840,7 @@ GCS_MAVLINK::update_receive(uint32_t max_time_us) } } +#if HAL_LOGGING_ENABLED // consider logging mavlink stats: if (is_active() || is_streaming()) { if (tnow - last_mavlink_stats_logged > 1000) { @@ -1845,6 +1848,7 @@ GCS_MAVLINK::update_receive(uint32_t max_time_us) last_mavlink_stats_logged = tnow; } } +#endif #if GCS_DEBUG_SEND_MESSAGE_TIMINGS @@ -1921,6 +1925,7 @@ GCS_MAVLINK::update_receive(uint32_t max_time_us) #endif } +#if HAL_LOGGING_ENABLED /* record stats about this link to logger */ @@ -1957,6 +1962,7 @@ void GCS_MAVLINK::log_mavlink_stats() AP::logger().WriteBlock(&pkt, sizeof(pkt)); } +#endif /* send the SYSTEM_TIME message @@ -2279,12 +2285,14 @@ void GCS::send_textv(MAV_SEVERITY severity, const char *fmt, va_list arg_list, u } } while (false); +#if HAL_LOGGING_ENABLED // given we don't really know what these methods get up to, we // don't hold the statustext semaphore while doing them: AP_Logger *logger = AP_Logger::get_singleton(); if (logger != nullptr) { logger->Write_Message(first_piece_of_text); } +#endif #if AP_FRSKY_TELEM_ENABLED frsky = AP::frsky_telem(); @@ -3394,13 +3402,15 @@ void GCS_MAVLINK::handle_timesync(const mavlink_message_t &msg) // response to an ancient request... return; } - const uint64_t round_trip_time_us = (timesync_receive_timestamp_ns() - _timesync_request.sent_ts1)*0.001f; #if 0 gcs().send_text(MAV_SEVERITY_INFO, "timesync response sysid=%u (latency=%fms)", msg.sysid, round_trip_time_us*0.001f); #endif + +#if HAL_LOGGING_ENABLED + const uint64_t round_trip_time_us = (timesync_receive_timestamp_ns() - _timesync_request.sent_ts1)*0.001f; AP_Logger *logger = AP_Logger::get_singleton(); if (logger != nullptr) { AP::logger().Write( @@ -3414,6 +3424,7 @@ void GCS_MAVLINK::handle_timesync(const mavlink_message_t &msg) round_trip_time_us ); } +#endif // HAL_LOGGING_ENABLED return; } @@ -3452,6 +3463,7 @@ void GCS_MAVLINK::send_timesync() void GCS_MAVLINK::handle_statustext(const mavlink_message_t &msg) const { +#if HAL_LOGGING_ENABLED AP_Logger *logger = AP_Logger::get_singleton(); if (logger == nullptr) { return; @@ -3476,6 +3488,7 @@ void GCS_MAVLINK::handle_statustext(const mavlink_message_t &msg) const memcpy(&text[offset], packet.text, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN); logger->Write_Message(text); +#endif } @@ -3484,6 +3497,7 @@ void GCS_MAVLINK::handle_statustext(const mavlink_message_t &msg) const */ void GCS_MAVLINK::handle_named_value(const mavlink_message_t &msg) const { +#if HAL_LOGGING_ENABLED auto *logger = AP_Logger::get_singleton(); if (logger == nullptr) { return; @@ -3499,6 +3513,7 @@ void GCS_MAVLINK::handle_named_value(const mavlink_message_t &msg) const p.value, msg.sysid, msg.compid); +#endif } #if AP_RTC_ENABLED @@ -3546,7 +3561,9 @@ void GCS_MAVLINK::set_ekf_origin(const Location& loc) return; } +#if HAL_LOGGING_ENABLED ahrs.Log_Write_Home_And_Origin(); +#endif // send ekf origin to GCS if (!try_send_message(MSG_ORIGIN)) { @@ -3961,6 +3978,7 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg) case MAVLINK_MSG_ID_TIMESYNC: handle_timesync(msg); break; +#if HAL_LOGGING_ENABLED case MAVLINK_MSG_ID_LOG_REQUEST_LIST: case MAVLINK_MSG_ID_LOG_REQUEST_DATA: case MAVLINK_MSG_ID_LOG_ERASE: @@ -3968,6 +3986,7 @@ void GCS_MAVLINK::handle_common_message(const mavlink_message_t &msg) case MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS: AP::logger().handle_mavlink_msg(*this, msg); break; +#endif case MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL: handle_file_transfer_protocol(msg); @@ -4923,10 +4942,12 @@ void GCS_MAVLINK::handle_command_long(const mavlink_message_t &msg) msg.sysid, msg.compid); +#if HAL_LOGGING_ENABLED // log the packet: mavlink_command_int_t packet_int; convert_COMMAND_LONG_to_COMMAND_INT(packet, packet_int); AP::logger().Write_Command(packet_int, msg.sysid, msg.compid, result, true); +#endif hal.util->persistent_data.last_mavlink_cmd = 0; } @@ -5313,7 +5334,9 @@ void GCS_MAVLINK::handle_command_int(const mavlink_message_t &msg) msg.sysid, msg.compid); +#if HAL_LOGGING_ENABLED AP::logger().Write_Command(packet, msg.sysid, msg.compid, result); +#endif hal.util->persistent_data.last_mavlink_cmd = 0; } diff --git a/libraries/GCS_MAVLink/GCS_Param.cpp b/libraries/GCS_MAVLink/GCS_Param.cpp index 75cc85b63f6c0a..a4c8c1df5182cb 100644 --- a/libraries/GCS_MAVLink/GCS_Param.cpp +++ b/libraries/GCS_MAVLink/GCS_Param.cpp @@ -314,11 +314,13 @@ void GCS_MAVLINK::handle_param_set(const mavlink_message_t &msg) if (force_save && (parameter_flags & AP_PARAM_FLAG_ENABLE)) { AP_Param::invalidate_count(); } - + +#if HAL_LOGGING_ENABLED AP_Logger *logger = AP_Logger::get_singleton(); if (logger != nullptr) { logger->Write_Parameter(key, vp->cast_to_float(var_type)); } +#endif } void GCS_MAVLINK::send_parameter_value(const char *param_name, ap_var_type param_type, float param_value) @@ -351,11 +353,13 @@ void GCS::send_parameter_value(const char *param_name, ap_var_type param_type, f gcs().send_to_active_channels(MAVLINK_MSG_ID_PARAM_VALUE, (const char *)&packet); +#if HAL_LOGGING_ENABLED // also log to AP_Logger AP_Logger *logger = AP_Logger::get_singleton(); if (logger != nullptr) { logger->Write_Parameter(param_name, param_value); } +#endif } diff --git a/libraries/GCS_MAVLink/MissionItemProtocol_Rally.cpp b/libraries/GCS_MAVLink/MissionItemProtocol_Rally.cpp index 8c9271884537cd..ee33e55188e35c 100644 --- a/libraries/GCS_MAVLink/MissionItemProtocol_Rally.cpp +++ b/libraries/GCS_MAVLink/MissionItemProtocol_Rally.cpp @@ -43,7 +43,9 @@ MAV_MISSION_RESULT MissionItemProtocol_Rally::append_item(const mavlink_mission_ MAV_MISSION_RESULT MissionItemProtocol_Rally::complete(const GCS_MAVLINK &_link) { +#if HAL_LOGGING_ENABLED AP::logger().Write_Rally(); +#endif return MAV_MISSION_ACCEPTED; } diff --git a/libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.cpp b/libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.cpp index 311b27e157d85e..3605dc152b85f1 100644 --- a/libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.cpp +++ b/libraries/GCS_MAVLink/MissionItemProtocol_Waypoints.cpp @@ -58,7 +58,9 @@ bool MissionItemProtocol_Waypoints::clear_all_items() MAV_MISSION_RESULT MissionItemProtocol_Waypoints::complete(const GCS_MAVLINK &_link) { _link.send_text(MAV_SEVERITY_INFO, "Flight plan received"); +#if HAL_LOGGING_ENABLED AP::logger().Write_EntireMission(); +#endif return MAV_MISSION_ACCEPTED; } From fdfe6eeb65029a9333c2461925a76340500f4d0a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:09 +1000 Subject: [PATCH 0633/1335] RC_Channel: allow compilation with HAL_LOGGING_ENABLED false --- libraries/RC_Channel/RC_Channel.cpp | 9 +++++++-- libraries/RC_Channel/RC_Channels.cpp | 2 ++ 2 files changed, 9 insertions(+), 2 deletions(-) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index f3c6653f3478d9..cebb53ae2f9e54 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -877,14 +877,14 @@ void RC_Channel::do_aux_function_avoid_adsb(const AuxSwitchPos ch_flag) return; } avoidance->enable(); - AP::logger().Write_Event(LogEvent::AVOIDANCE_ADSB_ENABLE); + LOGGER_WRITE_EVENT(LogEvent::AVOIDANCE_ADSB_ENABLE); GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "ADSB Avoidance Enabled"); return; } // disable AP_Avoidance avoidance->disable(); - AP::logger().Write_Event(LogEvent::AVOIDANCE_ADSB_DISABLE); + LOGGER_WRITE_EVENT(LogEvent::AVOIDANCE_ADSB_DISABLE); GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "ADSB Avoidance Disabled"); #endif } @@ -1216,6 +1216,7 @@ bool RC_Channel::run_aux_function(aux_func_t ch_option, AuxSwitchPos pos, AuxFun #endif const bool ret = do_aux_function(ch_option, pos); +#if HAL_LOGGING_ENABLED // @LoggerMessage: AUXF // @Description: Auxiliary function invocation information // @Field: TimeUS: Time since system startup @@ -1238,6 +1239,8 @@ bool RC_Channel::run_aux_function(aux_func_t ch_option, AuxSwitchPos pos, AuxFun uint8_t(source), uint8_t(ret) ); +#endif + return ret; } @@ -1544,6 +1547,7 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos } #endif +#if HAL_LOGGING_ENABLED case AUX_FUNC::LOG_PAUSE: { AP_Logger *logger = AP_Logger::get_singleton(); switch (ch_flag) { @@ -1559,6 +1563,7 @@ bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos } break; } +#endif #if COMPASS_CAL_ENABLED case AUX_FUNC::MAG_CAL: { diff --git a/libraries/RC_Channel/RC_Channels.cpp b/libraries/RC_Channel/RC_Channels.cpp index 8578904f5a4603..0ecdaba6d9fbf9 100644 --- a/libraries/RC_Channel/RC_Channels.cpp +++ b/libraries/RC_Channel/RC_Channels.cpp @@ -169,10 +169,12 @@ void RC_Channels::read_aux_all() } need_log |= c->read_aux(); } +#if HAL_LOGGING_ENABLED if (need_log) { // guarantee that we log when a switch changes AP::logger().Write_RCIN(); } +#endif } void RC_Channels::init_aux_all() From 7377b3f8f2336c43d9fbdf254c0df8612f46af87 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:09 +1000 Subject: [PATCH 0634/1335] ArduCopter: allow compilation with HAL_LOGGING_ENABLED false --- ArduCopter/AP_Arming.cpp | 8 +++++++- ArduCopter/AP_State.cpp | 8 ++++---- ArduCopter/Copter.cpp | 23 ++++++++++++++++++++--- ArduCopter/Copter.h | 4 ++++ ArduCopter/GCS_Mavlink.cpp | 4 ++++ ArduCopter/Log.cpp | 27 ++------------------------- ArduCopter/Parameters.cpp | 2 ++ ArduCopter/RC_Channel.cpp | 16 ++++++++-------- ArduCopter/avoidance_adsb.cpp | 6 ++++-- ArduCopter/config.h | 5 +---- ArduCopter/crash_check.cpp | 10 +++++----- ArduCopter/ekf_check.cpp | 16 ++++++++-------- ArduCopter/events.cpp | 20 ++++++++++---------- ArduCopter/failsafe.cpp | 4 ++-- ArduCopter/fence.cpp | 4 ++-- ArduCopter/heli.cpp | 4 ++-- ArduCopter/land_detector.cpp | 4 +++- ArduCopter/mode.cpp | 12 +++++++----- ArduCopter/mode.h | 2 ++ ArduCopter/mode_auto.cpp | 14 ++++++++++---- ArduCopter/mode_autotune.cpp | 2 ++ ArduCopter/mode_flip.cpp | 6 +++--- ArduCopter/mode_flowhold.cpp | 5 +++++ ArduCopter/mode_guided.cpp | 25 +++++++++++++++++++++---- ArduCopter/mode_land.cpp | 2 +- ArduCopter/mode_rtl.cpp | 16 +++++++++------- ArduCopter/mode_systemid.cpp | 2 ++ ArduCopter/mode_throw.cpp | 6 ++++-- ArduCopter/mode_zigzag.cpp | 4 ++-- ArduCopter/motors.cpp | 4 ++-- ArduCopter/radio.cpp | 2 +- ArduCopter/system.cpp | 10 +++++----- ArduCopter/terrain.cpp | 2 ++ ArduCopter/toy_mode.cpp | 3 ++- ArduCopter/tuning.cpp | 2 ++ 35 files changed, 170 insertions(+), 114 deletions(-) diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index 72bc9addf073bf..30226a9020bbc5 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -694,8 +694,10 @@ bool AP_Arming_Copter::arm(const AP_Arming::Method method, const bool do_arming_ return false; } +#if HAL_LOGGING_ENABLED // let logger know that we're armed (it may open logs e.g.) AP::logger().set_vehicle_armed(true); +#endif // disable cpu failsafe because initialising everything takes a while copter.failsafe_disable(); @@ -722,7 +724,7 @@ bool AP_Arming_Copter::arm(const AP_Arming::Method method, const bool do_arming_ if (!ahrs.home_is_set()) { // Reset EKF altitude if home hasn't been set yet (we use EKF altitude as substitute for alt above home) ahrs.resetHeightDatum(); - AP::logger().Write_Event(LogEvent::EKF_ALT_RESET); + LOGGER_WRITE_EVENT(LogEvent::EKF_ALT_RESET); // we have reset height, so arming height is zero copter.arming_altitude_m = 0; @@ -755,8 +757,10 @@ bool AP_Arming_Copter::arm(const AP_Arming::Method method, const bool do_arming_ // finally actually arm the motors copter.motors->armed(true); +#if HAL_LOGGING_ENABLED // log flight mode in case it was changed while vehicle was disarmed AP::logger().Write_Mode((uint8_t)copter.flightmode->mode_number(), copter.control_mode_reason); +#endif // re-enable failsafe copter.failsafe_enable(); @@ -837,7 +841,9 @@ bool AP_Arming_Copter::disarm(const AP_Arming::Method method, bool do_disarm_che copter.mode_auto.mission.reset(); #endif +#if HAL_LOGGING_ENABLED AP::logger().set_vehicle_armed(false); +#endif hal.util->set_soft_armed(false); diff --git a/ArduCopter/AP_State.cpp b/ArduCopter/AP_State.cpp index a3e60e80763791..3fe709b83e756d 100644 --- a/ArduCopter/AP_State.cpp +++ b/ArduCopter/AP_State.cpp @@ -9,7 +9,7 @@ void Copter::set_auto_armed(bool b) ap.auto_armed = b; if(b){ - AP::logger().Write_Event(LogEvent::AUTO_ARMED); + LOGGER_WRITE_EVENT(LogEvent::AUTO_ARMED); } } @@ -24,17 +24,17 @@ void Copter::set_simple_mode(SimpleMode b) if (simple_mode != b) { switch (b) { case SimpleMode::NONE: - AP::logger().Write_Event(LogEvent::SET_SIMPLE_OFF); + LOGGER_WRITE_EVENT(LogEvent::SET_SIMPLE_OFF); gcs().send_text(MAV_SEVERITY_INFO, "SIMPLE mode off"); break; case SimpleMode::SIMPLE: - AP::logger().Write_Event(LogEvent::SET_SIMPLE_ON); + LOGGER_WRITE_EVENT(LogEvent::SET_SIMPLE_ON); gcs().send_text(MAV_SEVERITY_INFO, "SIMPLE mode on"); break; case SimpleMode::SUPERSIMPLE: // initialise super simple heading update_super_simple_bearing(true); - AP::logger().Write_Event(LogEvent::SET_SUPERSIMPLE_ON); + LOGGER_WRITE_EVENT(LogEvent::SET_SUPERSIMPLE_ON); gcs().send_text(MAV_SEVERITY_INFO, "SUPERSIMPLE mode on"); break; } diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index c1218651342394..740bb95e5f45f0 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -143,7 +143,9 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { // camera mount's fast update FAST_TASK_CLASS(AP_Mount, &copter.camera_mount, update_fast), #endif +#if HAL_LOGGING_ENABLED FAST_TASK(Log_Video_Stabilisation), +#endif SCHED_TASK(rc_loop, 250, 130, 3), SCHED_TASK(throttle_loop, 50, 75, 6), @@ -188,7 +190,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { #if FRAME_CONFIG == HELI_FRAME SCHED_TASK(check_dynamic_flight, 50, 75, 72), #endif -#if LOGGING_ENABLED == ENABLED +#if HAL_LOGGING_ENABLED SCHED_TASK(loop_rate_logging, LOOP_RATE, 50, 75), #endif SCHED_TASK(one_hz_loop, 1, 100, 81), @@ -209,14 +211,16 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { #if AP_CAMERA_ENABLED SCHED_TASK_CLASS(AP_Camera, &copter.camera, update, 50, 75, 111), #endif -#if LOGGING_ENABLED == ENABLED +#if HAL_LOGGING_ENABLED SCHED_TASK(ten_hz_logging_loop, 10, 350, 114), SCHED_TASK(twentyfive_hz_logging, 25, 110, 117), SCHED_TASK_CLASS(AP_Logger, &copter.logger, periodic_tasks, 400, 300, 120), #endif SCHED_TASK_CLASS(AP_InertialSensor, &copter.ins, periodic, 400, 50, 123), +#if HAL_LOGGING_ENABLED SCHED_TASK_CLASS(AP_Scheduler, &copter.scheduler, update_logging, 0.1, 75, 126), +#endif #if AP_RPM_ENABLED SCHED_TASK_CLASS(AP_RPM, &copter.rpm_sensor, update, 40, 200, 129), #endif @@ -512,6 +516,7 @@ void Copter::update_batt_compass(void) } } +#if HAL_LOGGING_ENABLED // Full rate logging of attitude, rate and pid loops // should be run at loop rate void Copter::loop_rate_logging() @@ -609,6 +614,7 @@ void Copter::twentyfive_hz_logging() } #endif } +#endif // HAL_LOGGING_ENABLED // three_hz_loop - 3hz loop void Copter::three_hz_loop() @@ -638,9 +644,11 @@ void Copter::three_hz_loop() // one_hz_loop - runs at 1Hz void Copter::one_hz_loop() { +#if HAL_LOGGING_ENABLED if (should_log(MASK_LOG_ANY)) { Log_Write_Data(LogDataID::AP_STATE, ap.value); } +#endif if (!motors->armed()) { update_using_interlock(); @@ -657,8 +665,10 @@ void Copter::one_hz_loop() // update assigned functions and enable auxiliary servos SRV_Channels::enable_aux_servos(); +#if HAL_LOGGING_ENABLED // log terrain data terrain_logging(); +#endif #if HAL_ADSB_ENABLED adsb.set_is_flying(!ap.land_complete); @@ -685,10 +695,12 @@ void Copter::init_simple_bearing() super_simple_cos_yaw = simple_cos_yaw; super_simple_sin_yaw = simple_sin_yaw; +#if HAL_LOGGING_ENABLED // log the simple bearing if (should_log(MASK_LOG_ANY)) { Log_Write_Data(LogDataID::INIT_SIMPLE_BEARING, ahrs.yaw_sensor); } +#endif } // update_simple_mode - rotates pilot input if we are in simple mode @@ -757,6 +769,7 @@ void Copter::update_altitude() // read in baro altitude read_barometer(); +#if HAL_LOGGING_ENABLED if (should_log(MASK_LOG_CTUN)) { Log_Write_Control_Tuning(); if (!should_log(MASK_LOG_FTN_FAST)) { @@ -766,6 +779,7 @@ void Copter::update_altitude() #endif } } +#endif } // vehicle specific waypoint info helpers @@ -808,7 +822,10 @@ bool Copter::get_rate_ef_targets(Vector3f& rate_ef_targets) const constructor for main Copter class */ Copter::Copter(void) - : logger(g.log_bitmask), + : +#if HAL_LOGGING_ENABLED + logger(g.log_bitmask), +#endif flight_modes(&g.flight_mode1), simple_cos_yaw(1.0f), super_simple_cos_yaw(1.0), diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index bb468a39939a52..8685f4cb8f6262 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -252,7 +252,9 @@ class Copter : public AP_Vehicle { RC_Channel *channel_throttle; RC_Channel *channel_yaw; +#if HAL_LOGGING_ENABLED AP_Logger logger; +#endif // flight modes convenience array AP_Int8 *flight_modes; @@ -836,6 +838,7 @@ class Copter : public AP_Vehicle { // standby.cpp void standby_update(); +#if HAL_LOGGING_ENABLED // Log.cpp void Log_Write_Control_Tuning(); void Log_Write_Attitude(); @@ -857,6 +860,7 @@ class Copter : public AP_Vehicle { void Log_Write_SysID_Data(float waveform_time, float waveform_sample, float waveform_freq, float angle_x, float angle_y, float angle_z, float accel_x, float accel_y, float accel_z); void Log_Write_Vehicle_Startup_Messages(); void log_init(void); +#endif // HAL_LOGGING_ENABLED // mode.cpp bool set_mode(Mode::Number mode, ModeReason reason); diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 7f86eabc8ef5ea..e07bd005d0275c 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -1488,7 +1488,11 @@ void GCS_MAVLINK_Copter::handleMessage(const mavlink_message_t &msg) case MAVLINK_MSG_ID_RADIO: case MAVLINK_MSG_ID_RADIO_STATUS: // MAV ID: 109 { +#if HAL_LOGGING_ENABLED handle_radio_status(msg, copter.should_log(MASK_LOG_PM)); +#else + handle_radio_status(msg, false); +#endif break; } diff --git a/ArduCopter/Log.cpp b/ArduCopter/Log.cpp index 027544771d9112..4d9e4ef87b01b6 100644 --- a/ArduCopter/Log.cpp +++ b/ArduCopter/Log.cpp @@ -1,6 +1,6 @@ #include "Copter.h" -#if LOGGING_ENABLED == ENABLED +#if HAL_LOGGING_ENABLED // Code to Write and Read packets from AP_Logger log memory // Code to interact with the user to dump or erase logs @@ -576,27 +576,4 @@ void Copter::log_init(void) logger.Init(log_structure, ARRAY_SIZE(log_structure)); } -#else // LOGGING_ENABLED - -void Copter::Log_Write_Control_Tuning() {} -void Copter::Log_Write_Attitude(void) {} -void Copter::Log_Write_EKF_POS() {} -void Copter::Log_Write_Data(LogDataID id, int32_t value) {} -void Copter::Log_Write_Data(LogDataID id, uint32_t value) {} -void Copter::Log_Write_Data(LogDataID id, int16_t value) {} -void Copter::Log_Write_Data(LogDataID id, uint16_t value) {} -void Copter::Log_Write_Data(LogDataID id, float value) {} -void Copter::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, float tune_min, float tune_max) {} -void Copter::Log_Write_Guided_Position_Target(ModeGuided::SubMode target_type, const Vector3f& pos_target, bool terrain_alt, const Vector3f& vel_target, const Vector3f& accel_target) {} -void Copter::Log_Write_Guided_Attitude_Target(ModeGuided::SubMode target_type, float roll, float pitch, float yaw, const Vector3f &ang_vel, float thrust, float climb_rate) {} -void Copter::Log_Write_SysID_Setup(uint8_t systemID_axis, float waveform_magnitude, float frequency_start, float frequency_stop, float time_fade_in, float time_const_freq, float time_record, float time_fade_out) {} -void Copter::Log_Write_SysID_Data(float waveform_time, float waveform_sample, float waveform_freq, float angle_x, float angle_y, float angle_z, float accel_x, float accel_y, float accel_z) {} -void Copter::Log_Write_Vehicle_Startup_Messages() {} - -#if FRAME_CONFIG == HELI_FRAME -void Copter::Log_Write_Heli() {} -#endif - -void Copter::log_init(void) {} - -#endif // LOGGING_ENABLED +#endif // HAL_LOGGING_ENABLED diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index e3b949b7c322f5..d1de6fe45d78fc 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -554,9 +554,11 @@ const AP_Param::Info Copter::var_info[] = { GOBJECT(camera_mount, "MNT", AP_Mount), #endif +#if HAL_LOGGING_ENABLED // @Group: LOG // @Path: ../libraries/AP_Logger/AP_Logger.cpp GOBJECT(logger, "LOG", AP_Logger), +#endif // @Group: BATT // @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp diff --git a/ArduCopter/RC_Channel.cpp b/ArduCopter/RC_Channel.cpp index f400694b451b38..b613cb141aee43 100644 --- a/ArduCopter/RC_Channel.cpp +++ b/ArduCopter/RC_Channel.cpp @@ -229,7 +229,7 @@ bool RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwi // only altitude will matter to the AP mission script for takeoff. if (copter.mode_auto.mission.add_cmd(cmd)) { // log event - AP::logger().Write_Event(LogEvent::SAVEWP_ADD_WP); + LOGGER_WRITE_EVENT(LogEvent::SAVEWP_ADD_WP); } } @@ -247,7 +247,7 @@ bool RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwi // save command if (copter.mode_auto.mission.add_cmd(cmd)) { // log event - AP::logger().Write_Event(LogEvent::SAVEWP_ADD_WP); + LOGGER_WRITE_EVENT(LogEvent::SAVEWP_ADD_WP); } } #endif @@ -276,15 +276,15 @@ bool RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwi switch(ch_flag) { case AuxSwitchPos::LOW: copter.g.acro_trainer.set((uint8_t)ModeAcro::Trainer::OFF); - AP::logger().Write_Event(LogEvent::ACRO_TRAINER_OFF); + LOGGER_WRITE_EVENT(LogEvent::ACRO_TRAINER_OFF); break; case AuxSwitchPos::MIDDLE: copter.g.acro_trainer.set((uint8_t)ModeAcro::Trainer::LEVELING); - AP::logger().Write_Event(LogEvent::ACRO_TRAINER_LEVELING); + LOGGER_WRITE_EVENT(LogEvent::ACRO_TRAINER_LEVELING); break; case AuxSwitchPos::HIGH: copter.g.acro_trainer.set((uint8_t)ModeAcro::Trainer::LIMITED); - AP::logger().Write_Event(LogEvent::ACRO_TRAINER_LIMITED); + LOGGER_WRITE_EVENT(LogEvent::ACRO_TRAINER_LIMITED); break; } #endif @@ -540,12 +540,12 @@ bool RC_Channel_Copter::do_aux_function(const aux_func_t ch_option, const AuxSwi switch (ch_flag) { case AuxSwitchPos::HIGH: copter.standby_active = true; - AP::logger().Write_Event(LogEvent::STANDBY_ENABLE); + LOGGER_WRITE_EVENT(LogEvent::STANDBY_ENABLE); gcs().send_text(MAV_SEVERITY_INFO, "Stand By Enabled"); break; default: copter.standby_active = false; - AP::logger().Write_Event(LogEvent::STANDBY_DISABLE); + LOGGER_WRITE_EVENT(LogEvent::STANDBY_DISABLE); gcs().send_text(MAV_SEVERITY_INFO, "Stand By Disabled"); break; } @@ -683,7 +683,7 @@ void Copter::save_trim() float roll_trim = ToRad((float)channel_roll->get_control_in()/100.0f); float pitch_trim = ToRad((float)channel_pitch->get_control_in()/100.0f); ahrs.add_trim(roll_trim, pitch_trim); - AP::logger().Write_Event(LogEvent::SAVE_TRIM); + LOGGER_WRITE_EVENT(LogEvent::SAVE_TRIM); gcs().send_text(MAV_SEVERITY_INFO, "Trim saved"); } diff --git a/ArduCopter/avoidance_adsb.cpp b/ArduCopter/avoidance_adsb.cpp index 85fee2d7525225..bd541c355117af 100644 --- a/ArduCopter/avoidance_adsb.cpp +++ b/ArduCopter/avoidance_adsb.cpp @@ -88,10 +88,12 @@ MAV_COLLISION_ACTION AP_Avoidance_Copter::handle_avoidance(const AP_Avoidance::O } } +#if HAL_LOGGING_ENABLED if (failsafe_state_change) { AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_ADSB, LogErrorCode(actual_action)); } +#endif // return with action taken return actual_action; @@ -102,8 +104,8 @@ void AP_Avoidance_Copter::handle_recovery(RecoveryAction recovery_action) // check we are coming out of failsafe if (copter.failsafe.adsb) { copter.failsafe.adsb = false; - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_ADSB, - LogErrorCode::ERROR_RESOLVED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_ADSB, + LogErrorCode::ERROR_RESOLVED); // restore flight mode if requested and user has not changed mode since if (copter.control_mode_reason == ModeReason::AVOIDANCE) { diff --git a/ArduCopter/config.h b/ArduCopter/config.h index ace8cc43f2edc3..97793741c9895f 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -239,7 +239,7 @@ ////////////////////////////////////////////////////////////////////////////// // System ID - conduct system identification tests on vehicle #ifndef MODE_SYSTEMID_ENABLED -# define MODE_SYSTEMID_ENABLED ENABLED +# define MODE_SYSTEMID_ENABLED HAL_LOGGING_ENABLED #endif ////////////////////////////////////////////////////////////////////////////// @@ -529,9 +529,6 @@ ////////////////////////////////////////////////////////////////////////////// // Logging control // -#ifndef LOGGING_ENABLED - # define LOGGING_ENABLED ENABLED -#endif // Default logging bitmask #ifndef DEFAULT_LOG_BITMASK diff --git a/ArduCopter/crash_check.cpp b/ArduCopter/crash_check.cpp index 786e56b5a0e522..2ce5d89420cc84 100644 --- a/ArduCopter/crash_check.cpp +++ b/ArduCopter/crash_check.cpp @@ -88,7 +88,7 @@ void Copter::crash_check() // check if crashing for 2 seconds if (crash_counter >= (CRASH_CHECK_TRIGGER_SEC * scheduler.get_loop_rate_hz())) { - AP::logger().Write_Error(LogErrorSubsystem::CRASH_CHECK, LogErrorCode::CRASH_CHECK_CRASH); + LOGGER_WRITE_ERROR(LogErrorSubsystem::CRASH_CHECK, LogErrorCode::CRASH_CHECK_CRASH); // send message to gcs gcs().send_text(MAV_SEVERITY_EMERGENCY,"Crash: Disarming: AngErr=%.0f>%.0f, Accel=%.1f<%.1f", angle_error, CRASH_CHECK_ANGLE_DEVIATION_DEG, filtered_acc, CRASH_CHECK_ACCEL_MAX); // disarm motors @@ -163,7 +163,7 @@ void Copter::thrust_loss_check() if (thrust_loss_counter >= (THRUST_LOSS_CHECK_TRIGGER_SEC * scheduler.get_loop_rate_hz())) { // reset counter thrust_loss_counter = 0; - AP::logger().Write_Error(LogErrorSubsystem::THRUST_LOSS_CHECK, LogErrorCode::FAILSAFE_OCCURRED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::THRUST_LOSS_CHECK, LogErrorCode::FAILSAFE_OCCURRED); // send message to gcs gcs().send_text(MAV_SEVERITY_EMERGENCY, "Potential Thrust Loss (%d)", (int)motors->get_lost_motor() + 1); // enable thrust loss handling @@ -322,7 +322,7 @@ void Copter::parachute_check() } else if (control_loss_count >= (PARACHUTE_CHECK_TRIGGER_SEC*scheduler.get_loop_rate_hz())) { // reset control loss counter control_loss_count = 0; - AP::logger().Write_Error(LogErrorSubsystem::CRASH_CHECK, LogErrorCode::CRASH_CHECK_LOSS_OF_CONTROL); + LOGGER_WRITE_ERROR(LogErrorSubsystem::CRASH_CHECK, LogErrorCode::CRASH_CHECK_LOSS_OF_CONTROL); // release parachute parachute_release(); } @@ -357,7 +357,7 @@ void Copter::parachute_manual_release() if (ap.land_complete) { // warn user of reason for failure gcs().send_text(MAV_SEVERITY_INFO,"Parachute: Landed"); - AP::logger().Write_Error(LogErrorSubsystem::PARACHUTES, LogErrorCode::PARACHUTE_LANDED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::PARACHUTES, LogErrorCode::PARACHUTE_LANDED); return; } @@ -365,7 +365,7 @@ void Copter::parachute_manual_release() if ((parachute.alt_min() != 0 && (current_loc.alt < (int32_t)parachute.alt_min() * 100))) { // warn user of reason for failure gcs().send_text(MAV_SEVERITY_ALERT,"Parachute: Too low"); - AP::logger().Write_Error(LogErrorSubsystem::PARACHUTES, LogErrorCode::PARACHUTE_TOO_LOW); + LOGGER_WRITE_ERROR(LogErrorSubsystem::PARACHUTES, LogErrorCode::PARACHUTE_TOO_LOW); return; } diff --git a/ArduCopter/ekf_check.cpp b/ArduCopter/ekf_check.cpp index 12a582d71c790a..87cbd20f6e7a34 100644 --- a/ArduCopter/ekf_check.cpp +++ b/ArduCopter/ekf_check.cpp @@ -80,7 +80,7 @@ void Copter::ekf_check() // limit count from climbing too high ekf_check_state.fail_count = EKF_CHECK_ITERATIONS_MAX; ekf_check_state.bad_variance = true; - AP::logger().Write_Error(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_BAD_VARIANCE); + LOGGER_WRITE_ERROR(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_BAD_VARIANCE); // send message to gcs if ((AP_HAL::millis() - ekf_check_state.last_warn_time) > EKF_CHECK_WARNING_TIME) { gcs().send_text(MAV_SEVERITY_CRITICAL,"EKF variance"); @@ -97,7 +97,7 @@ void Copter::ekf_check() // if variances are flagged as bad and the counter reaches zero then clear flag if (ekf_check_state.bad_variance && ekf_check_state.fail_count == 0) { ekf_check_state.bad_variance = false; - AP::logger().Write_Error(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_VARIANCE_CLEARED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_VARIANCE_CLEARED); // clear failsafe failsafe_ekf_off_event(); } @@ -156,7 +156,7 @@ void Copter::failsafe_ekf_event() { // EKF failsafe event has occurred failsafe.ekf = true; - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_OCCURRED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_OCCURRED); // if disarmed take no action if (!motors->armed()) { @@ -207,7 +207,7 @@ void Copter::failsafe_ekf_off_event(void) AP_Notify::flags.failsafe_ekf = false; gcs().send_text(MAV_SEVERITY_CRITICAL, "EKF Failsafe Cleared"); } - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_RESOLVED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_RESOLVED); } // re-check if the flight mode requires GPS but EKF failsafe is active @@ -232,14 +232,14 @@ void Copter::check_ekf_reset() if (new_ekfYawReset_ms != ekfYawReset_ms) { attitude_control->inertial_frame_reset(); ekfYawReset_ms = new_ekfYawReset_ms; - AP::logger().Write_Event(LogEvent::EKF_YAW_RESET); + LOGGER_WRITE_EVENT(LogEvent::EKF_YAW_RESET); } // check for change in primary EKF, reset attitude target and log. AC_PosControl handles position target adjustment if ((ahrs.get_primary_core_index() != ekf_primary_core) && (ahrs.get_primary_core_index() != -1)) { attitude_control->inertial_frame_reset(); ekf_primary_core = ahrs.get_primary_core_index(); - AP::logger().Write_Error(LogErrorSubsystem::EKF_PRIMARY, LogErrorCode(ekf_primary_core)); + LOGGER_WRITE_ERROR(LogErrorSubsystem::EKF_PRIMARY, LogErrorCode(ekf_primary_core)); gcs().send_text(MAV_SEVERITY_WARNING, "EKF primary changed:%d", (unsigned)ekf_primary_core); } } @@ -285,7 +285,7 @@ void Copter::check_vibration() vibration_check.clear_ms = 0; vibration_check.high_vibes = true; pos_control->set_vibe_comp(true); - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_VIBE, LogErrorCode::FAILSAFE_OCCURRED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_VIBE, LogErrorCode::FAILSAFE_OCCURRED); gcs().send_text(MAV_SEVERITY_CRITICAL, "Vibration compensation ON"); } } else { @@ -300,7 +300,7 @@ void Copter::check_vibration() vibration_check.high_vibes = false; pos_control->set_vibe_comp(false); vibration_check.clear_ms = 0; - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_VIBE, LogErrorCode::FAILSAFE_RESOLVED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_VIBE, LogErrorCode::FAILSAFE_RESOLVED); gcs().send_text(MAV_SEVERITY_CRITICAL, "Vibration compensation OFF"); } } diff --git a/ArduCopter/events.cpp b/ArduCopter/events.cpp index 94077c5088040c..2160e222498b41 100644 --- a/ArduCopter/events.cpp +++ b/ArduCopter/events.cpp @@ -12,7 +12,7 @@ bool Copter::failsafe_option(FailsafeOption opt) const void Copter::failsafe_radio_on_event() { - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_RADIO, LogErrorCode::FAILSAFE_OCCURRED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_RADIO, LogErrorCode::FAILSAFE_OCCURRED); // set desired action based on FS_THR_ENABLE parameter FailsafeAction desired_action; @@ -83,7 +83,7 @@ void Copter::failsafe_radio_off_event() { // no need to do anything except log the error as resolved // user can now override roll, pitch, yaw and throttle and even use flight mode switch to restore previous flight mode - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_RADIO, LogErrorCode::FAILSAFE_RESOLVED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_RADIO, LogErrorCode::FAILSAFE_RESOLVED); gcs().send_text(MAV_SEVERITY_WARNING, "Radio Failsafe Cleared"); } @@ -98,7 +98,7 @@ void Copter::announce_failsafe(const char *type, const char *action_undertaken) void Copter::handle_battery_failsafe(const char *type_str, const int8_t action) { - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_BATT, LogErrorCode::FAILSAFE_OCCURRED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_BATT, LogErrorCode::FAILSAFE_OCCURRED); FailsafeAction desired_action = (FailsafeAction)action; @@ -162,7 +162,7 @@ void Copter::failsafe_gcs_check() // failsafe_gcs_on_event - actions to take when GCS contact is lost void Copter::failsafe_gcs_on_event(void) { - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_GCS, LogErrorCode::FAILSAFE_OCCURRED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_GCS, LogErrorCode::FAILSAFE_OCCURRED); RC_Channels::clear_overrides(); // convert the desired failsafe response to the FailsafeAction enum @@ -236,7 +236,7 @@ void Copter::failsafe_gcs_on_event(void) void Copter::failsafe_gcs_off_event(void) { gcs().send_text(MAV_SEVERITY_WARNING, "GCS Failsafe Cleared"); - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_GCS, LogErrorCode::FAILSAFE_RESOLVED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_GCS, LogErrorCode::FAILSAFE_RESOLVED); } // executes terrain failsafe if data is missing for longer than a few seconds @@ -251,7 +251,7 @@ void Copter::failsafe_terrain_check() if (trigger_event) { failsafe_terrain_on_event(); } else { - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_TERRAIN, LogErrorCode::ERROR_RESOLVED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_TERRAIN, LogErrorCode::ERROR_RESOLVED); failsafe.terrain = false; } } @@ -282,7 +282,7 @@ void Copter::failsafe_terrain_on_event() { failsafe.terrain = true; gcs().send_text(MAV_SEVERITY_CRITICAL,"Failsafe: Terrain data missing"); - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_TERRAIN, LogErrorCode::FAILSAFE_OCCURRED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_TERRAIN, LogErrorCode::FAILSAFE_OCCURRED); if (should_disarm_on_failsafe()) { arming.disarm(AP_Arming::Method::TERRAINFAILSAFE); @@ -306,10 +306,10 @@ void Copter::gpsglitch_check() if (ap.gps_glitching != gps_glitching) { ap.gps_glitching = gps_glitching; if (gps_glitching) { - AP::logger().Write_Error(LogErrorSubsystem::GPS, LogErrorCode::GPS_GLITCH); + LOGGER_WRITE_ERROR(LogErrorSubsystem::GPS, LogErrorCode::GPS_GLITCH); gcs().send_text(MAV_SEVERITY_CRITICAL,"GPS Glitch or Compass error"); } else { - AP::logger().Write_Error(LogErrorSubsystem::GPS, LogErrorCode::ERROR_RESOLVED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::GPS, LogErrorCode::ERROR_RESOLVED); gcs().send_text(MAV_SEVERITY_CRITICAL,"Glitch cleared"); } } @@ -361,7 +361,7 @@ void Copter::failsafe_deadreckon_check() if (failsafe.deadreckon && copter.flightmode->requires_GPS()) { // log error - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_DEADRECKON, LogErrorCode::FAILSAFE_OCCURRED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_DEADRECKON, LogErrorCode::FAILSAFE_OCCURRED); // immediately disarm while landed if (should_disarm_on_failsafe()) { diff --git a/ArduCopter/failsafe.cpp b/ArduCopter/failsafe.cpp index 9adf95db03489b..88ae35572f7939 100644 --- a/ArduCopter/failsafe.cpp +++ b/ArduCopter/failsafe.cpp @@ -43,7 +43,7 @@ void Copter::failsafe_check() failsafe_last_timestamp = tnow; if (in_failsafe) { in_failsafe = false; - AP::logger().Write_Error(LogErrorSubsystem::CPU, LogErrorCode::FAILSAFE_RESOLVED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::CPU, LogErrorCode::FAILSAFE_RESOLVED); } return; } @@ -58,7 +58,7 @@ void Copter::failsafe_check() motors->output_min(); } - AP::logger().Write_Error(LogErrorSubsystem::CPU, LogErrorCode::FAILSAFE_OCCURRED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::CPU, LogErrorCode::FAILSAFE_OCCURRED); } if (failsafe_enabled && in_failsafe && tnow - failsafe_last_timestamp > 1000000) { diff --git a/ArduCopter/fence.cpp b/ArduCopter/fence.cpp index 122d49a96544a5..3bfe085c2b8697 100644 --- a/ArduCopter/fence.cpp +++ b/ArduCopter/fence.cpp @@ -79,11 +79,11 @@ void Copter::fence_check() } } - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode(new_breaches)); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode(new_breaches)); } else if (orig_breaches) { // record clearing of breach - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode::ERROR_RESOLVED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode::ERROR_RESOLVED); } } diff --git a/ArduCopter/heli.cpp b/ArduCopter/heli.cpp index fb7bb9babfcbf7..a9c9fde1ac7cfa 100644 --- a/ArduCopter/heli.cpp +++ b/ArduCopter/heli.cpp @@ -184,9 +184,9 @@ void Copter::heli_update_rotor_speed_targets() // when rotor_runup_complete changes to true, log event if (!rotor_runup_complete_last && motors->rotor_runup_complete()) { - AP::logger().Write_Event(LogEvent::ROTOR_RUNUP_COMPLETE); + LOGGER_WRITE_EVENT(LogEvent::ROTOR_RUNUP_COMPLETE); } else if (rotor_runup_complete_last && !motors->rotor_runup_complete() && !heli_flags.in_autorotation) { - AP::logger().Write_Event(LogEvent::ROTOR_SPEED_BELOW_CRITICAL); + LOGGER_WRITE_EVENT(LogEvent::ROTOR_SPEED_BELOW_CRITICAL); } rotor_runup_complete_last = motors->rotor_runup_complete(); } diff --git a/ArduCopter/land_detector.cpp b/ArduCopter/land_detector.cpp index c6b038c4a7c484..4a4cdd3fca86b5 100644 --- a/ArduCopter/land_detector.cpp +++ b/ArduCopter/land_detector.cpp @@ -139,11 +139,13 @@ void Copter::set_land_complete(bool b) land_detector_count = 0; +#if HAL_LOGGING_ENABLED if(b){ AP::logger().Write_Event(LogEvent::LAND_COMPLETE); } else { AP::logger().Write_Event(LogEvent::NOT_LANDED); } +#endif ap.land_complete = b; #if STATS_ENABLED == ENABLED @@ -170,7 +172,7 @@ void Copter::set_land_complete_maybe(bool b) return; if (b) { - AP::logger().Write_Event(LogEvent::LAND_COMPLETE_MAYBE); + LOGGER_WRITE_EVENT(LogEvent::LAND_COMPLETE_MAYBE); } ap.land_complete_maybe = b; } diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index 3313ab35509bb9..f235cc22ef3906 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -191,7 +191,7 @@ Mode *Copter::mode_from_mode_num(const Mode::Number mode) void Copter::mode_change_failed(const Mode *mode, const char *reason) { gcs().send_text(MAV_SEVERITY_WARNING, "Mode change to %s failed: %s", mode->name(), reason); - AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode->mode_number())); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode->mode_number())); // make sad noise if (copter.ap.initialised) { AP_Notify::events.user_mode_change_failed = 1; @@ -360,7 +360,9 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason) // update flight mode flightmode = new_flightmode; control_mode_reason = reason; +#if HAL_LOGGING_ENABLED logger.Write_Mode((uint8_t)flightmode->mode_number(), reason); +#endif gcs().send_message(MSG_HEARTBEAT); #if HAL_ADSB_ENABLED @@ -700,7 +702,7 @@ void Mode::land_run_horizontal_control() // process pilot inputs if (!copter.failsafe.radio) { if ((g.throttle_behavior & THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND) != 0 && copter.rc_throttle_control_in_filter.get() > LAND_CANCEL_TRIGGER_THR){ - AP::logger().Write_Event(LogEvent::LAND_CANCELLED_BY_PILOT); + LOGGER_WRITE_EVENT(LogEvent::LAND_CANCELLED_BY_PILOT); // exit land if throttle is high if (!set_mode(Mode::Number::LOITER, ModeReason::THROTTLE_LAND_ESCAPE)) { set_mode(Mode::Number::ALT_HOLD, ModeReason::THROTTLE_LAND_ESCAPE); @@ -720,7 +722,7 @@ void Mode::land_run_horizontal_control() // record if pilot has overridden roll or pitch if (!vel_correction.is_zero()) { if (!copter.ap.land_repo_active) { - AP::logger().Write_Event(LogEvent::LAND_REPO_ACTIVE); + LOGGER_WRITE_EVENT(LogEvent::LAND_REPO_ACTIVE); } copter.ap.land_repo_active = true; #if AC_PRECLAND_ENABLED @@ -815,7 +817,7 @@ void Mode::precland_retry_position(const Vector3f &retry_pos) { if (!copter.failsafe.radio) { if ((g.throttle_behavior & THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND) != 0 && copter.rc_throttle_control_in_filter.get() > LAND_CANCEL_TRIGGER_THR){ - AP::logger().Write_Event(LogEvent::LAND_CANCELLED_BY_PILOT); + LOGGER_WRITE_EVENT(LogEvent::LAND_CANCELLED_BY_PILOT); // exit land if throttle is high if (!set_mode(Mode::Number::LOITER, ModeReason::THROTTLE_LAND_ESCAPE)) { set_mode(Mode::Number::ALT_HOLD, ModeReason::THROTTLE_LAND_ESCAPE); @@ -833,7 +835,7 @@ void Mode::precland_retry_position(const Vector3f &retry_pos) // record if pilot has overridden roll or pitch if (!is_zero(target_roll) || !is_zero(target_pitch)) { if (!copter.ap.land_repo_active) { - AP::logger().Write_Event(LogEvent::LAND_REPO_ACTIVE); + LOGGER_WRITE_EVENT(LogEvent::LAND_REPO_ACTIVE); } // this flag will be checked by prec land state machine later and any further landing retires will be cancelled copter.ap.land_repo_active = true; diff --git a/ArduCopter/mode.h b/ArduCopter/mode.h index afb348c1dc6526..dd06ee0149c296 100644 --- a/ArduCopter/mode.h +++ b/ArduCopter/mode.h @@ -743,7 +743,9 @@ class AutoTune : public AC_AutoTune_Multi float get_pilot_desired_climb_rate_cms(void) const override; void get_pilot_desired_rp_yrate_cd(float &roll_cd, float &pitch_cd, float &yaw_rate_cds) override; void init_z_limits() override; +#if HAL_LOGGING_ENABLED void log_pids() override; +#endif }; class ModeAutoTune : public Mode { diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index c33c9d98d7ecba..4185f35e032082 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -167,7 +167,9 @@ void ModeAuto::run() if (auto_RTL && (!(mission.get_in_landing_sequence_flag() || mission.state() == AP_Mission::mission_state::MISSION_COMPLETE))) { auto_RTL = false; // log exit from Auto RTL +#if HAL_LOGGING_ENABLED copter.logger.Write_Mode((uint8_t)copter.flightmode->mode_number(), ModeReason::AUTO_RTL_EXIT); +#endif } } @@ -219,8 +221,10 @@ bool ModeAuto::jump_to_landing_sequence_auto_RTL(ModeReason reason) // if not already in auto switch to auto if ((copter.flightmode == &copter.mode_auto) || set_mode(Mode::Number::AUTO, reason)) { auto_RTL = true; +#if HAL_LOGGING_ENABLED // log entry into AUTO RTL copter.logger.Write_Mode((uint8_t)copter.flightmode->mode_number(), reason); +#endif // make happy noise if (copter.ap.initialised) { @@ -236,7 +240,7 @@ bool ModeAuto::jump_to_landing_sequence_auto_RTL(ModeReason reason) gcs().send_text(MAV_SEVERITY_WARNING, "Mode change to AUTO RTL failed: No landing sequence found"); } - AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(Number::AUTO_RTL)); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(Number::AUTO_RTL)); // make sad noise if (copter.ap.initialised) { AP_Notify::events.user_mode_change_failed = 1; @@ -338,7 +342,7 @@ void ModeAuto::takeoff_start(const Location& dest_loc) // get altitude target above EKF origin if (!dest.get_alt_cm(Location::AltFrame::ABOVE_ORIGIN, alt_target_cm)) { // this failure could only happen if take-off alt was specified as an alt-above terrain and we have no terrain data - AP::logger().Write_Error(LogErrorSubsystem::TERRAIN, LogErrorCode::MISSING_TERRAIN_DATA); + LOGGER_WRITE_ERROR(LogErrorSubsystem::TERRAIN, LogErrorCode::MISSING_TERRAIN_DATA); // fall back to altitude above current altitude alt_target_cm = current_alt_cm + dest.alt; } @@ -618,10 +622,12 @@ bool ModeAuto::set_speed_down(float speed_down_cms) // start_command - this function will be called when the ap_mission lib wishes to start a new command bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) { +#if HAL_LOGGING_ENABLED // To-Do: logging when new commands start/end if (copter.should_log(MASK_LOG_CMD)) { copter.logger.Write_Mission_Cmd(mission, cmd); } +#endif switch(cmd.id) { @@ -1577,7 +1583,7 @@ void ModeAuto::do_land(const AP_Mission::Mission_Command& cmd) // this can only fail due to missing terrain database alt or rangefinder alt // use current alt-above-home and report error target_loc.set_alt_cm(copter.current_loc.alt, Location::AltFrame::ABOVE_HOME); - AP::logger().Write_Error(LogErrorSubsystem::TERRAIN, LogErrorCode::MISSING_TERRAIN_DATA); + LOGGER_WRITE_ERROR(LogErrorSubsystem::TERRAIN, LogErrorCode::MISSING_TERRAIN_DATA); gcs().send_text(MAV_SEVERITY_CRITICAL, "Land: no terrain data, using alt-above-home"); } @@ -1954,7 +1960,7 @@ void ModeAuto::do_payload_place(const AP_Mission::Mission_Command& cmd) // this can only fail due to missing terrain database alt or rangefinder alt // use current alt-above-home and report error target_loc.set_alt_cm(copter.current_loc.alt, Location::AltFrame::ABOVE_HOME); - AP::logger().Write_Error(LogErrorSubsystem::TERRAIN, LogErrorCode::MISSING_TERRAIN_DATA); + LOGGER_WRITE_ERROR(LogErrorSubsystem::TERRAIN, LogErrorCode::MISSING_TERRAIN_DATA); gcs().send_text(MAV_SEVERITY_CRITICAL, "PayloadPlace: no terrain data, using alt-above-home"); } if (!wp_start(target_loc)) { diff --git a/ArduCopter/mode_autotune.cpp b/ArduCopter/mode_autotune.cpp index 73699663a35926..0a7da76b07932f 100644 --- a/ArduCopter/mode_autotune.cpp +++ b/ArduCopter/mode_autotune.cpp @@ -98,12 +98,14 @@ void AutoTune::init_z_limits() copter.pos_control->set_correction_speed_accel_z(-copter.get_pilot_speed_dn(), copter.g.pilot_speed_up, copter.g.pilot_accel_z); } +#if HAL_LOGGING_ENABLED void AutoTune::log_pids() { copter.logger.Write_PID(LOG_PIDR_MSG, copter.attitude_control->get_rate_roll_pid().get_pid_info()); copter.logger.Write_PID(LOG_PIDP_MSG, copter.attitude_control->get_rate_pitch_pid().get_pid_info()); copter.logger.Write_PID(LOG_PIDY_MSG, copter.attitude_control->get_rate_yaw_pid().get_pid_info()); } +#endif /* check if we have a good position estimate diff --git a/ArduCopter/mode_flip.cpp b/ArduCopter/mode_flip.cpp index bade71e5e95264..938b44db7db10e 100644 --- a/ArduCopter/mode_flip.cpp +++ b/ArduCopter/mode_flip.cpp @@ -76,7 +76,7 @@ bool ModeFlip::init(bool ignore_checks) } // log start of flip - AP::logger().Write_Event(LogEvent::FLIP_START); + LOGGER_WRITE_EVENT(LogEvent::FLIP_START); // capture current attitude which will be used during the FlipState::Recovery stage const float angle_max = copter.aparm.angle_max; @@ -194,7 +194,7 @@ void ModeFlip::run() copter.set_mode(Mode::Number::STABILIZE, ModeReason::UNKNOWN); } // log successful completion - AP::logger().Write_Event(LogEvent::FLIP_END); + LOGGER_WRITE_EVENT(LogEvent::FLIP_END); } break; @@ -206,7 +206,7 @@ void ModeFlip::run() copter.set_mode(Mode::Number::STABILIZE, ModeReason::UNKNOWN); } // log abandoning flip - AP::logger().Write_Error(LogErrorSubsystem::FLIP, LogErrorCode::FLIP_ABANDONED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FLIP, LogErrorCode::FLIP_ABANDONED); break; } diff --git a/ArduCopter/mode_flowhold.cpp b/ArduCopter/mode_flowhold.cpp index 91814ab45f3469..ddb55d3d6d6adf 100644 --- a/ArduCopter/mode_flowhold.cpp +++ b/ArduCopter/mode_flowhold.cpp @@ -202,6 +202,7 @@ void ModeFlowHold::flowhold_flow_to_angle(Vector2f &bf_angles, bool stick_input) bf_angles.x = constrain_float(bf_angles.x, -copter.aparm.angle_max, copter.aparm.angle_max); bf_angles.y = constrain_float(bf_angles.y, -copter.aparm.angle_max, copter.aparm.angle_max); +#if HAL_LOGGING_ENABLED // @LoggerMessage: FHLD // @Description: FlowHold mode messages // @URL: https://ardupilot.org/copter/docs/flowhold-mode.html @@ -222,6 +223,7 @@ void ModeFlowHold::flowhold_flow_to_angle(Vector2f &bf_angles, bool stick_input) (double)quality_filtered, (double)xy_I.x, (double)xy_I.y); } +#endif // HAL_LOGGING_ENABLED } // flowhold_run - runs the flowhold controller @@ -478,6 +480,7 @@ void ModeFlowHold::update_height_estimate(void) // new height estimate for logging height_estimate = ins_height + height_offset; +#if HAL_LOGGING_ENABLED // @LoggerMessage: FHXY // @Description: Height estimation using optical flow sensor // @Field: TimeUS: Time since system startup @@ -504,6 +507,8 @@ void ModeFlowHold::update_height_estimate(void) (double)ins_height, (double)last_ins_height, dt_ms); +#endif + gcs().send_named_float("HEST", height_estimate); delta_velocity_ne.zero(); last_ins_height = ins_height; diff --git a/ArduCopter/mode_guided.cpp b/ArduCopter/mode_guided.cpp index 9c2914de8b7bf4..ba9a52f60ed269 100644 --- a/ArduCopter/mode_guided.cpp +++ b/ArduCopter/mode_guided.cpp @@ -332,7 +332,7 @@ bool ModeGuided::set_destination(const Vector3f& destination, bool use_yaw, floa // reject destination if outside the fence const Location dest_loc(destination, terrain_alt ? Location::AltFrame::ABOVE_TERRAIN : Location::AltFrame::ABOVE_ORIGIN); if (!copter.fence.check_destination_within_fence(dest_loc)) { - AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE); + LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE); // failure is propagated to GCS with NAK return false; } @@ -351,8 +351,10 @@ bool ModeGuided::set_destination(const Vector3f& destination, bool use_yaw, floa // no need to check return status because terrain data is not used wp_nav->set_wp_destination(destination, terrain_alt); +#if HAL_LOGGING_ENABLED // log target copter.Log_Write_Guided_Position_Target(guided_mode, destination, terrain_alt, Vector3f(), Vector3f()); +#endif send_notification = true; return true; } @@ -391,8 +393,10 @@ bool ModeGuided::set_destination(const Vector3f& destination, bool use_yaw, floa guided_accel_target_cmss.zero(); update_time_ms = millis(); +#if HAL_LOGGING_ENABLED // log target copter.Log_Write_Guided_Position_Target(guided_mode, guided_pos_target_cm.tofloat(), guided_pos_terrain_alt, guided_vel_target_cms, guided_accel_target_cmss); +#endif send_notification = true; @@ -424,7 +428,7 @@ bool ModeGuided::set_destination(const Location& dest_loc, bool use_yaw, float y // reject destination outside the fence. // Note: there is a danger that a target specified as a terrain altitude might not be checked if the conversion to alt-above-home fails if (!copter.fence.check_destination_within_fence(dest_loc)) { - AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE); + LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE); // failure is propagated to GCS with NAK return false; } @@ -438,7 +442,7 @@ bool ModeGuided::set_destination(const Location& dest_loc, bool use_yaw, float y if (!wp_nav->set_wp_destination_loc(dest_loc)) { // failure to set destination can only be because of missing terrain data - AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_TO_SET_DESTINATION); + LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_TO_SET_DESTINATION); // failure is propagated to GCS with NAK return false; } @@ -446,8 +450,11 @@ bool ModeGuided::set_destination(const Location& dest_loc, bool use_yaw, float y // set yaw state set_yaw_state(use_yaw, yaw_cd, use_yaw_rate, yaw_rate_cds, relative_yaw); +#if HAL_LOGGING_ENABLED // log target copter.Log_Write_Guided_Position_Target(guided_mode, Vector3f(dest_loc.lat, dest_loc.lng, dest_loc.alt), (dest_loc.get_alt_frame() == Location::AltFrame::ABOVE_TERRAIN), Vector3f(), Vector3f()); +#endif + send_notification = true; return true; } @@ -493,7 +500,9 @@ bool ModeGuided::set_destination(const Location& dest_loc, bool use_yaw, float y update_time_ms = millis(); // log target +#if HAL_LOGGING_ENABLED copter.Log_Write_Guided_Position_Target(guided_mode, Vector3f(dest_loc.lat, dest_loc.lng, dest_loc.alt), guided_pos_terrain_alt, guided_vel_target_cms, guided_accel_target_cmss); +#endif send_notification = true; @@ -518,10 +527,12 @@ void ModeGuided::set_accel(const Vector3f& acceleration, bool use_yaw, float yaw guided_accel_target_cmss = acceleration; update_time_ms = millis(); +#if HAL_LOGGING_ENABLED // log target if (log_request) { copter.Log_Write_Guided_Position_Target(guided_mode, guided_pos_target_cm.tofloat(), guided_pos_terrain_alt, guided_vel_target_cms, guided_accel_target_cmss); } +#endif } // set_velocity - sets guided mode's target velocity @@ -548,10 +559,12 @@ void ModeGuided::set_velaccel(const Vector3f& velocity, const Vector3f& accelera guided_accel_target_cmss = acceleration; update_time_ms = millis(); +#if HAL_LOGGING_ENABLED // log target if (log_request) { copter.Log_Write_Guided_Position_Target(guided_mode, guided_pos_target_cm.tofloat(), guided_pos_terrain_alt, guided_vel_target_cms, guided_accel_target_cmss); } +#endif } // set_destination_posvel - set guided mode position and velocity target @@ -567,7 +580,7 @@ bool ModeGuided::set_destination_posvelaccel(const Vector3f& destination, const // reject destination if outside the fence const Location dest_loc(destination, Location::AltFrame::ABOVE_ORIGIN); if (!copter.fence.check_destination_within_fence(dest_loc)) { - AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE); + LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE); // failure is propagated to GCS with NAK return false; } @@ -587,8 +600,10 @@ bool ModeGuided::set_destination_posvelaccel(const Vector3f& destination, const guided_vel_target_cms = velocity; guided_accel_target_cmss = acceleration; +#if HAL_LOGGING_ENABLED // log target copter.Log_Write_Guided_Position_Target(guided_mode, guided_pos_target_cm.tofloat(), guided_pos_terrain_alt, guided_vel_target_cms, guided_accel_target_cmss); +#endif return true; } @@ -648,8 +663,10 @@ void ModeGuided::set_angle(const Quaternion &attitude_quat, const Vector3f &ang_ float roll_rad, pitch_rad, yaw_rad; attitude_quat.to_euler(roll_rad, pitch_rad, yaw_rad); +#if HAL_LOGGING_ENABLED // log target copter.Log_Write_Guided_Attitude_Target(guided_mode, roll_rad, pitch_rad, yaw_rad, ang_vel, guided_angle_state.thrust, guided_angle_state.climb_rate_cms * 0.01); +#endif } // takeoff_run - takeoff in guided mode diff --git a/ArduCopter/mode_land.cpp b/ArduCopter/mode_land.cpp index 377bef5ee9253b..1f34e20fbf3380 100644 --- a/ArduCopter/mode_land.cpp +++ b/ArduCopter/mode_land.cpp @@ -102,7 +102,7 @@ void ModeLand::nogps_run() // process pilot inputs if (!copter.failsafe.radio) { if ((g.throttle_behavior & THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND) != 0 && copter.rc_throttle_control_in_filter.get() > LAND_CANCEL_TRIGGER_THR){ - AP::logger().Write_Event(LogEvent::LAND_CANCELLED_BY_PILOT); + LOGGER_WRITE_EVENT(LogEvent::LAND_CANCELLED_BY_PILOT); // exit land if throttle is high copter.set_mode(Mode::Number::ALT_HOLD, ModeReason::THROTTLE_LAND_ESCAPE); } diff --git a/ArduCopter/mode_rtl.cpp b/ArduCopter/mode_rtl.cpp index a8421d9009741e..b8a6cd9bbe7af5 100644 --- a/ArduCopter/mode_rtl.cpp +++ b/ArduCopter/mode_rtl.cpp @@ -39,7 +39,9 @@ bool ModeRTL::init(bool ignore_checks) // re-start RTL with terrain following disabled void ModeRTL::restart_without_terrain() { - AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::RESTARTED_RTL); +#if HAL_LOGGING_ENABLED + LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::RESTARTED_RTL); +#endif terrain_following_allowed = false; _state = SubMode::STARTING; _state_complete = true; @@ -134,7 +136,7 @@ void ModeRTL::climb_start() if (!wp_nav->set_wp_destination_loc(rtl_path.climb_target) || !wp_nav->set_wp_destination_next_loc(rtl_path.return_target)) { // this should not happen because rtl_build_path will have checked terrain data was available gcs().send_text(MAV_SEVERITY_CRITICAL,"RTL: unexpected error setting climb target"); - AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_TO_SET_DESTINATION); + LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_TO_SET_DESTINATION); copter.set_mode(Mode::Number::LAND, ModeReason::TERRAIN_FAILSAFE); return; } @@ -275,7 +277,7 @@ void ModeRTL::descent_run() // process pilot's input if (!copter.failsafe.radio) { if ((g.throttle_behavior & THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND) != 0 && copter.rc_throttle_control_in_filter.get() > LAND_CANCEL_TRIGGER_THR){ - AP::logger().Write_Event(LogEvent::LAND_CANCELLED_BY_PILOT); + LOGGER_WRITE_EVENT(LogEvent::LAND_CANCELLED_BY_PILOT); // exit land if throttle is high if (!copter.set_mode(Mode::Number::LOITER, ModeReason::THROTTLE_LAND_ESCAPE)) { copter.set_mode(Mode::Number::ALT_HOLD, ModeReason::THROTTLE_LAND_ESCAPE); @@ -292,7 +294,7 @@ void ModeRTL::descent_run() // record if pilot has overridden roll or pitch if (!vel_correction.is_zero()) { if (!copter.ap.land_repo_active) { - AP::logger().Write_Event(LogEvent::LAND_REPO_ACTIVE); + LOGGER_WRITE_EVENT(LogEvent::LAND_REPO_ACTIVE); } copter.ap.land_repo_active = true; } @@ -426,7 +428,7 @@ void ModeRTL::compute_return_target() switch (wp_nav->get_terrain_source()) { case AC_WPNav::TerrainSource::TERRAIN_UNAVAILABLE: alt_type = ReturnTargetAltType::RELATIVE; - AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::RTL_MISSING_RNGFND); + LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::RTL_MISSING_RNGFND); gcs().send_text(MAV_SEVERITY_CRITICAL, "RTL: no terrain data, using alt-above-home"); break; case AC_WPNav::TerrainSource::TERRAIN_FROM_RANGEFINDER: @@ -447,7 +449,7 @@ void ModeRTL::compute_return_target() // fallback to relative alt and warn user alt_type = ReturnTargetAltType::RELATIVE; gcs().send_text(MAV_SEVERITY_CRITICAL, "RTL: rangefinder unhealthy, using alt-above-home"); - AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::RTL_MISSING_RNGFND); + LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::RTL_MISSING_RNGFND); } } @@ -463,7 +465,7 @@ void ModeRTL::compute_return_target() } else { // fallback to relative alt and warn user alt_type = ReturnTargetAltType::RELATIVE; - AP::logger().Write_Error(LogErrorSubsystem::TERRAIN, LogErrorCode::MISSING_TERRAIN_DATA); + LOGGER_WRITE_ERROR(LogErrorSubsystem::TERRAIN, LogErrorCode::MISSING_TERRAIN_DATA); gcs().send_text(MAV_SEVERITY_CRITICAL, "RTL: no terrain data, using alt-above-home"); } } diff --git a/ArduCopter/mode_systemid.cpp b/ArduCopter/mode_systemid.cpp index 15dc1eba4f0ede..801f903205deb2 100644 --- a/ArduCopter/mode_systemid.cpp +++ b/ArduCopter/mode_systemid.cpp @@ -99,7 +99,9 @@ bool ModeSystemId::init(bool ignore_checks) gcs().send_text(MAV_SEVERITY_INFO, "SystemID Starting: axis=%d", (unsigned)axis); +#if HAL_LOGGING_ENABLED copter.Log_Write_SysID_Setup(axis, waveform_magnitude, frequency_start, frequency_stop, time_fade_in, time_const_freq, time_record, time_fade_out); +#endif return true; } diff --git a/ArduCopter/mode_throw.cpp b/ArduCopter/mode_throw.cpp index a2f71ff42f24d4..884b7a22be88d5 100644 --- a/ArduCopter/mode_throw.cpp +++ b/ArduCopter/mode_throw.cpp @@ -200,6 +200,7 @@ void ModeThrow::run() break; } +#if HAL_LOGGING_ENABLED // log at 10hz or if stage changes uint32_t now = AP_HAL::millis(); if ((stage != prev_stage) || (now - last_log_ms) > 100) { @@ -213,7 +214,7 @@ void ModeThrow::run() const bool attitude_ok = (stage > Throw_Uprighting) || throw_attitude_good(); const bool height_ok = (stage > Throw_HgtStabilise) || throw_height_good(); const bool pos_ok = (stage > Throw_PosHold) || throw_position_good(); - + // @LoggerMessage: THRO // @Description: Throw Mode messages // @URL: https://ardupilot.org/copter/docs/throw-mode.html @@ -227,7 +228,7 @@ void ModeThrow::run() // @Field: AttOk: True if the vehicle is upright // @Field: HgtOk: True if the vehicle is within 50cm of the demanded height // @Field: PosOk: True if the vehicle is within 50cm of the demanded horizontal position - + AP::logger().WriteStreaming( "THRO", "TimeUS,Stage,Vel,VelZ,Acc,AccEfZ,Throw,AttOk,HgtOk,PosOk", @@ -245,6 +246,7 @@ void ModeThrow::run() height_ok, pos_ok); } +#endif // HAL_LOGGING_ENABLED } bool ModeThrow::throw_detected() diff --git a/ArduCopter/mode_zigzag.cpp b/ArduCopter/mode_zigzag.cpp index 2952158ec615a6..fbf43aa50ed458 100644 --- a/ArduCopter/mode_zigzag.cpp +++ b/ArduCopter/mode_zigzag.cpp @@ -171,12 +171,12 @@ void ModeZigZag::save_or_move_to_destination(Destination ab_dest) // store point A dest_A = curr_pos; gcs().send_text(MAV_SEVERITY_INFO, "ZigZag: point A stored"); - AP::logger().Write_Event(LogEvent::ZIGZAG_STORE_A); + LOGGER_WRITE_EVENT(LogEvent::ZIGZAG_STORE_A); } else { // store point B dest_B = curr_pos; gcs().send_text(MAV_SEVERITY_INFO, "ZigZag: point B stored"); - AP::logger().Write_Event(LogEvent::ZIGZAG_STORE_B); + LOGGER_WRITE_EVENT(LogEvent::ZIGZAG_STORE_B); } // if both A and B have been stored advance state if (!dest_A.is_zero() && !dest_B.is_zero() && !is_zero((dest_B - dest_A).length_squared())) { diff --git a/ArduCopter/motors.cpp b/ArduCopter/motors.cpp index 84ab92733927ff..34a3ff201b6ce3 100644 --- a/ArduCopter/motors.cpp +++ b/ArduCopter/motors.cpp @@ -165,10 +165,10 @@ void Copter::motors_output() bool interlock = motors->armed() && !ap.in_arming_delay && (!ap.using_interlock || ap.motor_interlock_switch) && !SRV_Channels::get_emergency_stop(); if (!motors->get_interlock() && interlock) { motors->set_interlock(true); - AP::logger().Write_Event(LogEvent::MOTORS_INTERLOCK_ENABLED); + LOGGER_WRITE_EVENT(LogEvent::MOTORS_INTERLOCK_ENABLED); } else if (motors->get_interlock() && !interlock) { motors->set_interlock(false); - AP::logger().Write_Event(LogEvent::MOTORS_INTERLOCK_DISABLED); + LOGGER_WRITE_EVENT(LogEvent::MOTORS_INTERLOCK_DISABLED); } if (ap.motor_test) { diff --git a/ArduCopter/radio.cpp b/ArduCopter/radio.cpp index 57043fba918396..430bed7e93836b 100644 --- a/ArduCopter/radio.cpp +++ b/ArduCopter/radio.cpp @@ -121,7 +121,7 @@ void Copter::read_radio() } // Log an error and enter failsafe. - AP::logger().Write_Error(LogErrorSubsystem::RADIO, LogErrorCode::RADIO_LATE_FRAME); + LOGGER_WRITE_ERROR(LogErrorSubsystem::RADIO, LogErrorCode::RADIO_LATE_FRAME); set_failsafe_radio(true); } diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 40c077fc627773..83c4cbf5b8db50 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -55,7 +55,7 @@ void Copter::init_ardupilot() osd.init(); #endif -#if LOGGING_ENABLED == ENABLED +#if HAL_LOGGING_ENABLED log_init(); #endif @@ -183,8 +183,10 @@ void Copter::init_ardupilot() g2.smart_rtl.init(); #endif +#if HAL_LOGGING_ENABLED // initialise AP_Logger library logger.setVehicle_Startup_Writer(FUNCTOR_BIND(&copter, &Copter::Log_Write_Vehicle_Startup_Messages, void)); +#endif startup_INS_ground(); @@ -352,18 +354,16 @@ void Copter::update_auto_armed() } } +#if HAL_LOGGING_ENABLED /* should we log a message type now? */ bool Copter::should_log(uint32_t mask) { -#if LOGGING_ENABLED == ENABLED ap.logging_started = logger.logging_started(); return logger.should_log(mask); -#else - return false; -#endif } +#endif /* allocate the motors class diff --git a/ArduCopter/terrain.cpp b/ArduCopter/terrain.cpp index 77765bb61b86b6..5933de460ee752 100644 --- a/ArduCopter/terrain.cpp +++ b/ArduCopter/terrain.cpp @@ -17,6 +17,7 @@ void Copter::terrain_update() #endif } +#if HAL_LOGGING_ENABLED // log terrain data - should be called at 1hz void Copter::terrain_logging() { @@ -26,3 +27,4 @@ void Copter::terrain_logging() } #endif } +#endif diff --git a/ArduCopter/toy_mode.cpp b/ArduCopter/toy_mode.cpp index d212cb43358817..c1cea4d4cc3328 100644 --- a/ArduCopter/toy_mode.cpp +++ b/ArduCopter/toy_mode.cpp @@ -991,6 +991,7 @@ void ToyMode::thrust_limiting(float *thrust, uint8_t num_motors) uint16_t pwm[4]; hal.rcout->read(pwm, 4); +#if HAL_LOGGING_ENABLED // @LoggerMessage: THST // @Description: Maximum thrust limitation based on battery voltage in Toy Mode // @Field: TimeUS: Time since system startup @@ -1008,7 +1009,7 @@ void ToyMode::thrust_limiting(float *thrust, uint8_t num_motors) (double)thrust_mul, pwm[0], pwm[1], pwm[2], pwm[3]); } - +#endif } #if ENABLE_LOAD_TEST diff --git a/ArduCopter/tuning.cpp b/ArduCopter/tuning.cpp index db7f15c8899a21..babc53b9ff2672 100644 --- a/ArduCopter/tuning.cpp +++ b/ArduCopter/tuning.cpp @@ -28,7 +28,9 @@ void Copter::tuning() const uint16_t radio_in = rc6->get_radio_in(); float tuning_value = linear_interpolate(g2.tuning_min, g2.tuning_max, radio_in, rc6->get_radio_min(), rc6->get_radio_max()); +#if HAL_LOGGING_ENABLED Log_Write_Parameter_Tuning(g.radio_tuning, tuning_value, g2.tuning_min, g2.tuning_max); +#endif switch(g.radio_tuning) { From 6ee5ab41fd6aff617178102c2fbcc4a11219fbbd Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:09 +1000 Subject: [PATCH 0635/1335] ArduPlane: allow compilation with HAL_LOGGING_ENABLED false --- ArduPlane/AP_Arming.cpp | 2 ++ ArduPlane/ArduPlane.cpp | 17 ++++++++++++++--- ArduPlane/GCS_Mavlink.cpp | 4 ++++ ArduPlane/GCS_Mavlink.h | 2 +- ArduPlane/Log.cpp | 18 ++---------------- ArduPlane/Parameters.cpp | 2 ++ ArduPlane/Plane.cpp | 2 ++ ArduPlane/Plane.h | 2 ++ ArduPlane/commands_logic.cpp | 4 ++++ ArduPlane/config.h | 4 ---- ArduPlane/ekf_check.cpp | 8 ++++---- ArduPlane/fence.cpp | 4 ++-- ArduPlane/is_flying.cpp | 2 ++ ArduPlane/qautotune.cpp | 2 ++ ArduPlane/qautotune.h | 2 ++ ArduPlane/quadplane.cpp | 19 +++++++++++++++++-- ArduPlane/system.cpp | 12 ++++++------ ArduPlane/tailsitter.cpp | 2 ++ 18 files changed, 70 insertions(+), 38 deletions(-) diff --git a/ArduPlane/AP_Arming.cpp b/ArduPlane/AP_Arming.cpp index 2905175fdeb151..01783e023bf2d0 100644 --- a/ArduPlane/AP_Arming.cpp +++ b/ArduPlane/AP_Arming.cpp @@ -397,7 +397,9 @@ void AP_Arming_Plane::update_soft_armed() #endif hal.util->set_soft_armed(_armed); +#if HAL_LOGGING_ENABLED AP::logger().set_vehicle_armed(hal.util->get_soft_armed()); +#endif // update delay_arming oneshot if (delay_arming && diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index dd6af0ab6e30bc..afab49e76f42cb 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -104,11 +104,15 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = { #if AP_CAMERA_ENABLED SCHED_TASK_CLASS(AP_Camera, &plane.camera, update, 50, 100, 108), #endif // CAMERA == ENABLED +#if HAL_LOGGING_ENABLED SCHED_TASK_CLASS(AP_Scheduler, &plane.scheduler, update_logging, 0.2, 100, 111), +#endif SCHED_TASK(compass_save, 0.1, 200, 114), +#if HAL_LOGGING_ENABLED SCHED_TASK(Log_Write_FullRate, 400, 300, 117), SCHED_TASK(update_logging10, 10, 300, 120), SCHED_TASK(update_logging25, 25, 300, 123), +#endif #if HAL_SOARING_ENABLED SCHED_TASK(update_soaring, 50, 400, 126), #endif @@ -117,7 +121,7 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = { SCHED_TASK_CLASS(AP_Terrain, &plane.terrain, update, 10, 200, 132), #endif // AP_TERRAIN_AVAILABLE SCHED_TASK(update_is_flying_5Hz, 5, 100, 135), -#if LOGGING_ENABLED == ENABLED +#if HAL_LOGGING_ENABLED SCHED_TASK_CLASS(AP_Logger, &plane.logger, periodic_tasks, 50, 400, 138), #endif SCHED_TASK_CLASS(AP_InertialSensor, &plane.ins, periodic, 50, 50, 141), @@ -161,9 +165,11 @@ void Plane::ahrs_update() ahrs.update(); +#if HAL_LOGGING_ENABLED if (should_log(MASK_LOG_IMU)) { AP::ins().Write_IMU(); } +#endif // calculate a scaled roll limit based on current pitch roll_limit_cd = aparm.roll_limit_cd; @@ -194,9 +200,11 @@ void Plane::ahrs_update() quadplane.inertial_nav.update(); #endif +#if HAL_LOGGING_ENABLED if (should_log(MASK_LOG_VIDEO_STABILISATION)) { ahrs.write_video_stabilisation(); } +#endif } /* @@ -234,6 +242,7 @@ void Plane::update_compass(void) compass.read(); } +#if HAL_LOGGING_ENABLED /* do 10Hz logging */ @@ -286,7 +295,7 @@ void Plane::update_logging25(void) if (should_log(MASK_LOG_IMU)) AP::ins().Write_Vibration(); } - +#endif // HAL_LOGGING_ENABLED /* check for AFS failsafe check @@ -333,7 +342,7 @@ void Plane::one_second_loop() AP_Notify::flags.pre_arm_gps_check = true; AP_Notify::flags.armed = arming.is_armed() || arming.arming_required() == AP_Arming::Required::NO; -#if AP_TERRAIN_AVAILABLE +#if AP_TERRAIN_AVAILABLE && HAL_LOGGING_ENABLED if (should_log(MASK_LOG_GPS)) { terrain.log_terrain_data(); } @@ -528,7 +537,9 @@ void Plane::set_flight_stage(AP_FixedWing::FlightStage fs) } flight_stage = fs; +#if HAL_LOGGING_ENABLED Log_Write_Status(); +#endif } void Plane::update_alt() diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 9a571e3b5e0ce9..ca666ee1957b95 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -1230,7 +1230,11 @@ void GCS_MAVLINK_Plane::handleMessage(const mavlink_message_t &msg) case MAVLINK_MSG_ID_RADIO: case MAVLINK_MSG_ID_RADIO_STATUS: { +#if HAL_LOGGING_ENABLED handle_radio_status(msg, plane.should_log(MASK_LOG_PM)); +#else + handle_radio_status(msg, false); +#endif break; } diff --git a/ArduPlane/GCS_Mavlink.h b/ArduPlane/GCS_Mavlink.h index 41cb8e6b123f5f..e497a567106a9d 100644 --- a/ArduPlane/GCS_Mavlink.h +++ b/ArduPlane/GCS_Mavlink.h @@ -48,7 +48,7 @@ class GCS_MAVLINK_Plane : public GCS_MAVLINK private: - void send_pid_info(const AP_PIDInfo *pid_info, const uint8_t axis, const float achieved); + void send_pid_info(const struct AP_PIDInfo *pid_info, const uint8_t axis, const float achieved); void handleMessage(const mavlink_message_t &msg) override; bool handle_guided_request(AP_Mission::Mission_Command &cmd) override; diff --git a/ArduPlane/Log.cpp b/ArduPlane/Log.cpp index a5e97fe2ae4970..d8a729dd2ab1e6 100644 --- a/ArduPlane/Log.cpp +++ b/ArduPlane/Log.cpp @@ -1,6 +1,6 @@ #include "Plane.h" -#if LOGGING_ENABLED == ENABLED +#if HAL_LOGGING_ENABLED // Write an attitude packet void Plane::Log_Write_Attitude(void) @@ -500,18 +500,4 @@ void Plane::log_init(void) logger.Init(log_structure, ARRAY_SIZE(log_structure)); } -#else // LOGGING_ENABLED - -void Plane::Log_Write_Attitude(void) {} -void Plane::Log_Write_Fast(void) {} -void Plane::Log_Write_Control_Tuning() {} -void Plane::Log_Write_OFG_Guided() {} -void Plane::Log_Write_Nav_Tuning() {} -void Plane::Log_Write_Status() {} -void Plane::Log_Write_Guided(void) {} -void Plane::Log_Write_RC(void) {} -void Plane::Log_Write_Vehicle_Startup_Messages() {} - -void Plane::log_init(void) {} - -#endif // LOGGING_ENABLED +#endif // HAL_LOGGING_ENABLED diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index dd55010d46adce..fc651b1db717b2 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -909,9 +909,11 @@ const AP_Param::Info Plane::var_info[] = { GOBJECT(camera_mount, "MNT", AP_Mount), #endif +#if HAL_LOGGING_ENABLED // @Group: LOG // @Path: ../libraries/AP_Logger/AP_Logger.cpp GOBJECT(logger, "LOG", AP_Logger), +#endif // @Group: BATT // @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp diff --git a/ArduPlane/Plane.cpp b/ArduPlane/Plane.cpp index dff3166b02ea12..07055294b523a0 100644 --- a/ArduPlane/Plane.cpp +++ b/ArduPlane/Plane.cpp @@ -24,7 +24,9 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); constructor for main Plane class */ Plane::Plane(void) +#if HAL_LOGGING_ENABLED : logger(g.log_bitmask) +#endif { // C++11 doesn't allow in-class initialisation of bitfields auto_state.takeoff_complete = true; diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 1b8e5ccea25467..f8fe4b1747d7ea 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -193,7 +193,9 @@ class Plane : public AP_Vehicle { RC_Channel *channel_flap; RC_Channel *channel_airbrake; +#if HAL_LOGGING_ENABLED AP_Logger logger; +#endif // scaled roll limit based on pitch int32_t roll_limit_cd; diff --git a/ArduPlane/commands_logic.cpp b/ArduPlane/commands_logic.cpp index 972da6f765c8e3..256827193a141e 100644 --- a/ArduPlane/commands_logic.cpp +++ b/ArduPlane/commands_logic.cpp @@ -12,10 +12,12 @@ bool Plane::start_command(const AP_Mission::Mission_Command& cmd) plane.target_altitude.terrain_following_pending = false; #endif +#if HAL_LOGGING_ENABLED // log when new commands start if (should_log(MASK_LOG_CMD)) { logger.Write_Mission_Cmd(mission, cmd); } +#endif // special handling for nav vs non-nav commands if (AP_Mission::is_nav_cmd(cmd)) { @@ -359,7 +361,9 @@ void Plane::do_RTL(int32_t rtl_altitude_AMSL_cm) setup_glide_slope(); setup_turn_angle(); +#if HAL_LOGGING_ENABLED logger.Write_Mode(control_mode->mode_number(), control_mode_reason); +#endif } Location Plane::calc_best_rally_or_home_location(const Location &_current_loc, float rtl_home_alt_amsl_cm) const diff --git a/ArduPlane/config.h b/ArduPlane/config.h index a8c6c890c96cb0..8675b3dc45d935 100644 --- a/ArduPlane/config.h +++ b/ArduPlane/config.h @@ -186,10 +186,6 @@ // Logging control // -#ifndef LOGGING_ENABLED - # define LOGGING_ENABLED ENABLED -#endif - #define DEFAULT_LOG_BITMASK 0xffff diff --git a/ArduPlane/ekf_check.cpp b/ArduPlane/ekf_check.cpp index e36e4ef1abcdf7..ae8f2415bbf7c1 100644 --- a/ArduPlane/ekf_check.cpp +++ b/ArduPlane/ekf_check.cpp @@ -74,7 +74,7 @@ void Plane::ekf_check() // limit count from climbing too high ekf_check_state.fail_count = EKF_CHECK_ITERATIONS_MAX; ekf_check_state.bad_variance = true; - AP::logger().Write_Error(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_BAD_VARIANCE); + LOGGER_WRITE_ERROR(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_BAD_VARIANCE); // send message to gcs if ((AP_HAL::millis() - ekf_check_state.last_warn_time) > EKF_CHECK_WARNING_TIME) { gcs().send_text(MAV_SEVERITY_CRITICAL,"EKF variance"); @@ -91,7 +91,7 @@ void Plane::ekf_check() // if compass is flagged as bad and the counter reaches zero then clear flag if (ekf_check_state.bad_variance && ekf_check_state.fail_count == 0) { ekf_check_state.bad_variance = false; - AP::logger().Write_Error(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_VARIANCE_CLEARED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_VARIANCE_CLEARED); // clear failsafe failsafe_ekf_off_event(); } @@ -155,7 +155,7 @@ void Plane::failsafe_ekf_event() // EKF failsafe event has occurred ekf_check_state.failsafe_on = true; - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_OCCURRED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_OCCURRED); // if not in a VTOL mode requiring position, then nothing needs to be done #if HAL_QUADPLANE_ENABLED @@ -182,5 +182,5 @@ void Plane::failsafe_ekf_off_event(void) } ekf_check_state.failsafe_on = false; - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_RESOLVED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_RESOLVED); } diff --git a/ArduPlane/fence.cpp b/ArduPlane/fence.cpp index 640ad65869926d..22dfbf2015d4c8 100644 --- a/ArduPlane/fence.cpp +++ b/ArduPlane/fence.cpp @@ -114,10 +114,10 @@ void Plane::fence_check() break; } - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode(new_breaches)); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode(new_breaches)); } else if (orig_breaches) { // record clearing of breach - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode::ERROR_RESOLVED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode::ERROR_RESOLVED); } } diff --git a/ArduPlane/is_flying.cpp b/ArduPlane/is_flying.cpp index ffe578736aff14..bbb24ebe16eb4e 100644 --- a/ArduPlane/is_flying.cpp +++ b/ArduPlane/is_flying.cpp @@ -170,7 +170,9 @@ void Plane::update_is_flying_5Hz(void) crash_detection_update(); +#if HAL_LOGGING_ENABLED Log_Write_Status(); +#endif // tell AHRS flying state set_likely_flying(new_is_flying); diff --git a/ArduPlane/qautotune.cpp b/ArduPlane/qautotune.cpp index 141ae621d88bfc..916908c8530483 100644 --- a/ArduPlane/qautotune.cpp +++ b/ArduPlane/qautotune.cpp @@ -51,6 +51,7 @@ void QAutoTune::init_z_limits() } +#if HAL_LOGGING_ENABLED // log VTOL PIDs for during twitch void QAutoTune::log_pids(void) { @@ -58,6 +59,7 @@ void QAutoTune::log_pids(void) AP::logger().Write_PID(LOG_PIQP_MSG, plane.quadplane.attitude_control->get_rate_pitch_pid().get_pid_info()); AP::logger().Write_PID(LOG_PIQY_MSG, plane.quadplane.attitude_control->get_rate_yaw_pid().get_pid_info()); } +#endif #endif // QAUTOTUNE_ENABLED diff --git a/ArduPlane/qautotune.h b/ArduPlane/qautotune.h index 3ec890ac3dc3f9..938c8e47e43323 100644 --- a/ArduPlane/qautotune.h +++ b/ArduPlane/qautotune.h @@ -26,7 +26,9 @@ class QAutoTune : public AC_AutoTune_Multi float get_pilot_desired_climb_rate_cms(void) const override; void get_pilot_desired_rp_yrate_cd(float &roll_cd, float &pitch_cd, float &yaw_rate_cds) override; void init_z_limits() override; +#if HAL_LOGGING_ENABLED void log_pids() override; +#endif }; #endif // QAUTOTUNE_ENABLED diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 4a372fc15ffc62..b8e5e99735810d 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -1053,7 +1053,7 @@ void QuadPlane::check_yaw_reset(void) if (new_ekfYawReset_ms != ekfYawReset_ms) { attitude_control->inertial_frame_reset(); ekfYawReset_ms = new_ekfYawReset_ms; - AP::logger().Write_Event(LogEvent::EKF_YAW_RESET); + LOGGER_WRITE_EVENT(LogEvent::EKF_YAW_RESET); } } @@ -1866,6 +1866,7 @@ void QuadPlane::update(void) tiltrotor.update(); +#if HAL_LOGGING_ENABLED // motors logging if (motors->armed()) { const bool motors_active = in_vtol_mode() || assisted_flight; @@ -1886,7 +1887,9 @@ void QuadPlane::update(void) Log_Write_QControl_Tuning(); } } - +#else + (void)now; +#endif // HAL_LOGGING_ENABLED } /* @@ -2296,6 +2299,7 @@ void QuadPlane::poscontrol_init_approach(void) poscontrol.slow_descent = false; } +#if HAL_LOGGING_ENABLED /* log the QPOS message */ @@ -2309,6 +2313,7 @@ void QuadPlane::log_QPOS(void) poscontrol.target_accel, poscontrol.overshoot); } +#endif /* change position control state @@ -2346,9 +2351,13 @@ void QuadPlane::PosControlState::set_state(enum position_control_state s) qp.landing_detect.lower_limit_start_ms = 0; } // double log to capture the state change +#if HAL_LOGGING_ENABLED qp.log_QPOS(); +#endif state = s; +#if HAL_LOGGING_ENABLED qp.log_QPOS(); +#endif last_log_ms = now; overshoot = false; } @@ -2926,11 +2935,13 @@ void QuadPlane::vtol_position_controller(void) run_z_controller(); } +#if HAL_LOGGING_ENABLED if (now_ms - poscontrol.last_log_ms >= 40) { // log poscontrol at 25Hz poscontrol.last_log_ms = now_ms; log_QPOS(); } +#endif } /* @@ -3025,6 +3036,7 @@ void QuadPlane::assign_tilt_to_fwd_thr(void) { // acceleration capability. const float nav_pitch_lower_limit_cd = - (int32_t)((float)aparm.angle_max * (1.0f - fwd_thr_scaler) + q_fwd_pitch_lim_cd * fwd_thr_scaler); +#if HAL_LOGGING_ENABLED // Diagnostics logging - remove when feature is fully flight tested. AP::logger().WriteStreaming("FWDT", "TimeUS,fts,qfplcd,npllcd,npcd,qft", // labels @@ -3035,6 +3047,7 @@ void QuadPlane::assign_tilt_to_fwd_thr(void) { (double)nav_pitch_lower_limit_cd, (double)plane.nav_pitch_cd, (double)q_fwd_throttle); +#endif plane.nav_pitch_cd = MAX(plane.nav_pitch_cd, (int32_t)nav_pitch_lower_limit_cd); } @@ -3640,6 +3653,7 @@ bool QuadPlane::verify_vtol_land(void) return false; } +#if HAL_LOGGING_ENABLED // Write a control tuning packet void QuadPlane::Log_Write_QControl_Tuning() { @@ -3671,6 +3685,7 @@ void QuadPlane::Log_Write_QControl_Tuning() // write multicopter position control message pos_control->write_log(); } +#endif /* diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index 7c7066bef06b60..1cb09f97b28de0 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -76,7 +76,7 @@ void Plane::init_ardupilot() osd.init(); #endif -#if LOGGING_ENABLED == ENABLED +#if HAL_LOGGING_ENABLED log_init(); #endif @@ -182,7 +182,7 @@ void Plane::startup_ground(void) mission.init(); // initialise AP_Logger library -#if LOGGING_ENABLED == ENABLED +#if HAL_LOGGING_ENABLED logger.setVehicle_Startup_Writer( FUNCTOR_BIND(&plane, &Plane::Log_Write_Vehicle_Startup_Messages, void) ); @@ -341,7 +341,9 @@ bool Plane::set_mode(Mode &new_mode, const ModeReason reason) old_mode.exit(); // log and notify mode change +#if HAL_LOGGING_ENABLED logger.Write_Mode(control_mode->mode_number(), control_mode_reason); +#endif notify_mode(*control_mode); gcs().send_message(MSG_HEARTBEAT); @@ -466,17 +468,15 @@ void Plane::notify_mode(const Mode& mode) notify.set_flight_mode_str(mode.name4()); } +#if HAL_LOGGING_ENABLED /* should we log a message type now? */ bool Plane::should_log(uint32_t mask) { -#if LOGGING_ENABLED == ENABLED return logger.should_log(mask); -#else - return false; -#endif } +#endif /* return throttle percentage from 0 to 100 for normal use and -100 to 100 when using reverse thrust diff --git a/ArduPlane/tailsitter.cpp b/ArduPlane/tailsitter.cpp index a94e4cb8c5ea0a..93055be44a6e8c 100644 --- a/ArduPlane/tailsitter.cpp +++ b/ArduPlane/tailsitter.cpp @@ -783,6 +783,7 @@ void Tailsitter::speed_scaling(void) } +#if HAL_LOGGING_ENABLED // Write tailsitter specific log void Tailsitter::write_log() { @@ -799,6 +800,7 @@ void Tailsitter::write_log() }; plane.logger.WriteBlock(&pkt, sizeof(pkt)); } +#endif // HAL_LOGGING_ENABLED // return true if pitch control should be relaxed // on vectored belly sitters the pitch control is not relaxed in order to keep motors pointing and avoid risk of props hitting the ground From 8e91c72089f0c1c8072cb9f0c33de523f57d3efe Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 10 Jan 2024 14:37:03 +1100 Subject: [PATCH 0636/1335] Blimp: allow compilation with HAL_LOGGING_ENABLED false --- Blimp/AP_Arming.cpp | 8 +++++++- Blimp/AP_State.cpp | 2 +- Blimp/Blimp.cpp | 19 ++++++++++++++++--- Blimp/Blimp.h | 4 ++++ Blimp/Fins.cpp | 4 ++++ Blimp/GCS_Mavlink.cpp | 4 ++++ Blimp/Log.cpp | 21 ++------------------- Blimp/Loiter.cpp | 6 ++++++ Blimp/Parameters.cpp | 2 ++ Blimp/RC_Channel.cpp | 2 +- Blimp/config.h | 7 ------- Blimp/ekf_check.cpp | 16 ++++++++-------- Blimp/events.cpp | 10 +++++----- Blimp/failsafe.cpp | 4 ++-- Blimp/mode.cpp | 8 +++++--- Blimp/radio.cpp | 4 ++-- Blimp/system.cpp | 10 +++++----- 17 files changed, 74 insertions(+), 57 deletions(-) diff --git a/Blimp/AP_Arming.cpp b/Blimp/AP_Arming.cpp index adbc072e4bf834..2011502b2f98df 100644 --- a/Blimp/AP_Arming.cpp +++ b/Blimp/AP_Arming.cpp @@ -304,8 +304,10 @@ bool AP_Arming_Blimp::arm(const AP_Arming::Method method, const bool do_arming_c return false; } +#if HAL_LOGGING_ENABLED // let logger know that we're armed (it may open logs e.g.) AP::logger().set_vehicle_armed(true); +#endif // notify that arming will occur (we do this early to give plenty of warning) AP_Notify::flags.armed = true; @@ -323,7 +325,7 @@ bool AP_Arming_Blimp::arm(const AP_Arming::Method method, const bool do_arming_c if (!ahrs.home_is_set()) { // Reset EKF altitude if home hasn't been set yet (we use EKF altitude as substitute for alt above home) ahrs.resetHeightDatum(); - AP::logger().Write_Event(LogEvent::EKF_ALT_RESET); + LOGGER_WRITE_EVENT(LogEvent::EKF_ALT_RESET); // we have reset height, so arming height is zero blimp.arming_altitude_m = 0; @@ -342,8 +344,10 @@ bool AP_Arming_Blimp::arm(const AP_Arming::Method method, const bool do_arming_c // finally actually arm the motors blimp.motors->armed(true); +#if HAL_LOGGING_ENABLED // log flight mode in case it was changed while vehicle was disarmed AP::logger().Write_Mode((uint8_t)blimp.control_mode, blimp.control_mode_reason); +#endif // perf monitor ignores delay due to arming AP::scheduler().perf_info.ignore_this_loop(); @@ -391,7 +395,9 @@ bool AP_Arming_Blimp::disarm(const AP_Arming::Method method, bool do_disarm_chec // send disarm command to motors blimp.motors->armed(false); +#if HAL_LOGGING_ENABLED AP::logger().set_vehicle_armed(false); +#endif hal.util->set_soft_armed(false); diff --git a/Blimp/AP_State.cpp b/Blimp/AP_State.cpp index 47214730d99b8e..5dcebd68952333 100644 --- a/Blimp/AP_State.cpp +++ b/Blimp/AP_State.cpp @@ -10,7 +10,7 @@ void Blimp::set_auto_armed(bool b) ap.auto_armed = b; if (b) { - AP::logger().Write_Event(LogEvent::AUTO_ARMED); + LOGGER_WRITE_EVENT(LogEvent::AUTO_ARMED); } } diff --git a/Blimp/Blimp.cpp b/Blimp/Blimp.cpp index fc03cc4c8fb04b..45a1c0d65bcc69 100644 --- a/Blimp/Blimp.cpp +++ b/Blimp/Blimp.cpp @@ -76,7 +76,7 @@ const AP_Scheduler::Task Blimp::scheduler_tasks[] = { SCHED_TASK_CLASS(AP_ServoRelayEvents, &blimp.ServoRelayEvents, update_events, 50, 75, 27), #endif SCHED_TASK_CLASS(AP_Baro, &blimp.barometer, accumulate, 50, 90, 30), -#if LOGGING_ENABLED == ENABLED +#if HAL_LOGGING_ENABLED SCHED_TASK(full_rate_logging, 50, 50, 33), #endif SCHED_TASK_CLASS(AP_Notify, &blimp.notify, update, 50, 90, 36), @@ -86,13 +86,15 @@ const AP_Scheduler::Task Blimp::scheduler_tasks[] = { SCHED_TASK(gpsglitch_check, 10, 50, 48), SCHED_TASK_CLASS(GCS, (GCS*)&blimp._gcs, update_receive, 400, 180, 51), SCHED_TASK_CLASS(GCS, (GCS*)&blimp._gcs, update_send, 400, 550, 54), -#if LOGGING_ENABLED == ENABLED +#if HAL_LOGGING_ENABLED SCHED_TASK(ten_hz_logging_loop, 10, 350, 57), SCHED_TASK(twentyfive_hz_logging, 25, 110, 60), SCHED_TASK_CLASS(AP_Logger, &blimp.logger, periodic_tasks, 400, 300, 63), #endif SCHED_TASK_CLASS(AP_InertialSensor, &blimp.ins, periodic, 400, 50, 66), +#if HAL_LOGGING_ENABLED SCHED_TASK_CLASS(AP_Scheduler, &blimp.scheduler, update_logging, 0.1, 75, 69), +#endif #if STATS_ENABLED == ENABLED SCHED_TASK_CLASS(AP_Stats, &blimp.g2.stats, update, 1, 100, 75), #endif @@ -141,6 +143,7 @@ void Blimp::update_batt_compass(void) } } +#if HAL_LOGGING_ENABLED // Full rate logging of attitude, rate and pid loops void Blimp::full_rate_logging() { @@ -190,6 +193,7 @@ void Blimp::twentyfive_hz_logging() AP::ins().Write_IMU(); } } +#endif // HAL_LOGGING_ENABLED // three_hz_loop - 3.3hz loop void Blimp::three_hz_loop() @@ -201,9 +205,11 @@ void Blimp::three_hz_loop() // one_hz_loop - runs at 1Hz void Blimp::one_hz_loop() { +#if HAL_LOGGING_ENABLED if (should_log(MASK_LOG_ANY)) { Log_Write_Data(LogDataID::AP_STATE, ap.value); } +#endif // update assigned functions and enable auxiliary servos SRV_Channels::enable_aux_servos(); @@ -226,6 +232,7 @@ void Blimp::read_AHRS(void) vel_ned_filtd = {vel_xy_filtd.x, vel_xy_filtd.y, vel_z_filter.apply(vel_ned.z)}; vel_yaw_filtd = vel_yaw_filter.apply(vel_yaw); +#if HAL_LOGGING_ENABLED AP::logger().WriteStreaming("VNF", "TimeUS,X,XF,Y,YF,Z,ZF,Yaw,YawF,PX,PY,PZ,PYaw", "Qffffffffffff", AP_HAL::micros64(), vel_ned.x, @@ -240,6 +247,7 @@ void Blimp::read_AHRS(void) pos_ned.y, pos_ned.z, blimp.ahrs.get_yaw()); +#endif } // read baro and log control tuning @@ -248,12 +256,14 @@ void Blimp::update_altitude() // read in baro altitude read_barometer(); +#if HAL_LOGGING_ENABLED if (should_log(MASK_LOG_CTUN)) { AP::ins().write_notch_log_messages(); #if HAL_GYROFFT_ENABLED gyro_fft.write_log_messages(); #endif } +#endif } //Conversions are in 2D so that up remains up in world frame when the blimp is not exactly level. @@ -278,7 +288,10 @@ void Blimp::rotate_NE_to_BF(Vector2f &vec) constructor for main Blimp class */ Blimp::Blimp(void) - : logger(g.log_bitmask), + : +#if HAL_LOGGING_ENABLED + logger(g.log_bitmask), +#endif flight_modes(&g.flight_mode1), control_mode(Mode::Number::MANUAL), rc_throttle_control_in_filter(1.0f), diff --git a/Blimp/Blimp.h b/Blimp/Blimp.h index 32ac39b5bddf4f..1b3d3309b3ac7f 100644 --- a/Blimp/Blimp.h +++ b/Blimp/Blimp.h @@ -114,7 +114,9 @@ class Blimp : public AP_Vehicle RC_Channel *channel_up; RC_Channel *channel_yaw; +#if HAL_LOGGING_ENABLED AP_Logger logger; +#endif // flight modes convenience array AP_Int8 *flight_modes; @@ -352,6 +354,7 @@ class Blimp : public AP_Vehicle // landing_gear.cpp void landinggear_update(); +#if HAL_LOGGING_ENABLED // Log.cpp void Log_Write_Performance(); void Log_Write_Attitude(); @@ -370,6 +373,7 @@ class Blimp : public AP_Vehicle void log_init(void); void Write_FINI(float right, float front, float down, float yaw); void Write_FINO(float *amp, float *off); +#endif // mode.cpp bool set_mode(Mode::Number mode, ModeReason reason); diff --git a/Blimp/Fins.cpp b/Blimp/Fins.cpp index 0247a5795fbc0c..8e1eade2a2e6b7 100644 --- a/Blimp/Fins.cpp +++ b/Blimp/Fins.cpp @@ -80,7 +80,9 @@ void Fins::output() yaw_out = 0; } +#if HAL_LOGGING_ENABLED blimp.Write_FINI(right_out, front_out, down_out, yaw_out); +#endif //Constrain after logging so as to still show when sub-optimal tuning is causing massive overshoots. right_out = constrain_float(right_out, -1, 1); @@ -130,7 +132,9 @@ void Fins::output() SRV_Channels::set_output_scaled(SRV_Channels::get_motor_function(i), _pos[i] * FIN_SCALE_MAX); } +#if HAL_LOGGING_ENABLED blimp.Write_FINO(_amp, _off); +#endif } void Fins::output_min() diff --git a/Blimp/GCS_Mavlink.cpp b/Blimp/GCS_Mavlink.cpp index 8eaf6473dd9738..3e7f084ff0034c 100644 --- a/Blimp/GCS_Mavlink.cpp +++ b/Blimp/GCS_Mavlink.cpp @@ -518,7 +518,11 @@ void GCS_MAVLINK_Blimp::handleMessage(const mavlink_message_t &msg) case MAVLINK_MSG_ID_RADIO: case MAVLINK_MSG_ID_RADIO_STATUS: { // MAV ID: 109 +#if HAL_LOGGING_ENABLED handle_radio_status(msg, blimp.should_log(MASK_LOG_PM)); +#else + handle_radio_status(msg, false); +#endif break; } diff --git a/Blimp/Log.cpp b/Blimp/Log.cpp index 17c3161faba385..7d62fc9d5ebc6b 100644 --- a/Blimp/Log.cpp +++ b/Blimp/Log.cpp @@ -1,6 +1,6 @@ #include "Blimp.h" -#if LOGGING_ENABLED == ENABLED +#if HAL_LOGGING_ENABLED // Code to Write and Read packets from AP_Logger log memory // Code to interact with the user to dump or erase logs @@ -407,21 +407,4 @@ void Blimp::log_init(void) logger.Init(log_structure, ARRAY_SIZE(log_structure)); } -#else // LOGGING_ENABLED - -void Blimp::Log_Write_Performance() {} -void Blimp::Log_Write_Attitude(void) {} -void Blimp::Log_Write_PIDs(void) {} -void Blimp::Log_Write_EKF_POS() {} -void Blimp::Log_Write_Data(LogDataID id, int32_t value) {} -void Blimp::Log_Write_Data(LogDataID id, uint32_t value) {} -void Blimp::Log_Write_Data(LogDataID id, int16_t value) {} -void Blimp::Log_Write_Data(LogDataID id, uint16_t value) {} -void Blimp::Log_Write_Data(LogDataID id, float value) {} -void Blimp::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, float tune_min, float tune_max) {} -void Blimp::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target) {} -void Blimp::Log_Write_Vehicle_Startup_Messages() {} - -void Blimp::log_init(void) {} - -#endif // LOGGING_ENABLED +#endif // HAL_LOGGING_ENABLED diff --git a/Blimp/Loiter.cpp b/Blimp/Loiter.cpp index 8c6b5d5e7aea7c..52e85f1b536990 100644 --- a/Blimp/Loiter.cpp +++ b/Blimp/Loiter.cpp @@ -25,10 +25,12 @@ void Loiter::run(Vector3f& target_pos, float& target_yaw, Vector4b axes_disabled } scaler_yyaw = scaler_yyaw*MA + scaler_yyaw_n*MO; +#if HAL_LOGGING_ENABLED AP::logger().WriteStreaming("BSC", "TimeUS,xz,yyaw,xzn,yyawn", "Qffff", AP_HAL::micros64(), scaler_xz, scaler_yyaw, scaler_xz_n, scaler_yyaw_n); +#endif float yaw_ef = blimp.ahrs.get_yaw(); Vector3f err_xyz = target_pos - blimp.pos_ned; @@ -120,9 +122,11 @@ void Loiter::run(Vector3f& target_pos, float& target_yaw, Vector4b axes_disabled blimp.motors->yaw_out = act_yaw; } +#if HAL_LOGGING_ENABLED AP::logger().Write_PSCN(target_pos.x * 100.0, blimp.pos_ned.x * 100.0, 0.0, target_vel_ef_c.x * 100.0, blimp.vel_ned_filtd.x * 100.0, 0.0, 0.0, 0.0); AP::logger().Write_PSCE(target_pos.y * 100.0, blimp.pos_ned.y * 100.0, 0.0, target_vel_ef_c.y * 100.0, blimp.vel_ned_filtd.y * 100.0, 0.0, 0.0, 0.0); AP::logger().Write_PSCD(-target_pos.z * 100.0, -blimp.pos_ned.z * 100.0, 0.0, -target_vel_ef_c.z * 100.0, -blimp.vel_ned_filtd.z * 100.0, 0.0, 0.0, 0.0); +#endif } void Loiter::run_vel(Vector3f& target_vel_ef, float& target_vel_yaw, Vector4b axes_disabled) @@ -196,7 +200,9 @@ void Loiter::run_vel(Vector3f& target_vel_ef, float& target_vel_yaw, Vector4b ax blimp.motors->yaw_out = act_yaw; } +#if HAL_LOGGING_ENABLED AP::logger().Write_PSCN(0.0, blimp.pos_ned.x * 100.0, 0.0, target_vel_ef_c.x * 100.0, blimp.vel_ned_filtd.x * 100.0, 0.0, 0.0, 0.0); AP::logger().Write_PSCE(0.0, blimp.pos_ned.y * 100.0, 0.0, target_vel_ef_c.y * 100.0, blimp.vel_ned_filtd.y * 100.0, 0.0, 0.0, 0.0); AP::logger().Write_PSCD(0.0, -blimp.pos_ned.z * 100.0, 0.0, -target_vel_ef_c.z * 100.0, -blimp.vel_ned_filtd.z * 100.0, 0.0, 0.0, 0.0); +#endif } diff --git a/Blimp/Parameters.cpp b/Blimp/Parameters.cpp index 593e9f26687f74..3c19c9f516be85 100644 --- a/Blimp/Parameters.cpp +++ b/Blimp/Parameters.cpp @@ -341,9 +341,11 @@ const AP_Param::Info Blimp::var_info[] = { // @Path: ../libraries/AP_AHRS/AP_AHRS.cpp GOBJECT(ahrs, "AHRS_", AP_AHRS), +#if HAL_LOGGING_ENABLED // @Group: LOG // @Path: ../libraries/AP_Logger/AP_Logger.cpp GOBJECT(logger, "LOG", AP_Logger), +#endif // @Group: BATT // @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp diff --git a/Blimp/RC_Channel.cpp b/Blimp/RC_Channel.cpp index 7709867cf25c4a..ba94d82a173df4 100644 --- a/Blimp/RC_Channel.cpp +++ b/Blimp/RC_Channel.cpp @@ -132,7 +132,7 @@ void Blimp::save_trim() float roll_trim = ToRad((float)channel_right->get_control_in()/100.0f); float pitch_trim = ToRad((float)channel_front->get_control_in()/100.0f); ahrs.add_trim(roll_trim, pitch_trim); - AP::logger().Write_Event(LogEvent::SAVE_TRIM); + LOGGER_WRITE_EVENT(LogEvent::SAVE_TRIM); gcs().send_text(MAV_SEVERITY_INFO, "Trim saved"); } diff --git a/Blimp/config.h b/Blimp/config.h index 9c5908f65fed98..90985635a29432 100644 --- a/Blimp/config.h +++ b/Blimp/config.h @@ -111,13 +111,6 @@ # define AUTO_DISARMING_DELAY 10 #endif -////////////////////////////////////////////////////////////////////////////// -// Logging control -// -#ifndef LOGGING_ENABLED -# define LOGGING_ENABLED ENABLED -#endif - // Default logging bitmask #ifndef DEFAULT_LOG_BITMASK # define DEFAULT_LOG_BITMASK \ diff --git a/Blimp/ekf_check.cpp b/Blimp/ekf_check.cpp index fd524b99ab91a5..6b91eb6ec8ab1c 100644 --- a/Blimp/ekf_check.cpp +++ b/Blimp/ekf_check.cpp @@ -69,7 +69,7 @@ void Blimp::ekf_check() // limit count from climbing too high ekf_check_state.fail_count = EKF_CHECK_ITERATIONS_MAX; ekf_check_state.bad_variance = true; - AP::logger().Write_Error(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_BAD_VARIANCE); + LOGGER_WRITE_ERROR(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_BAD_VARIANCE); // send message to gcs if ((AP_HAL::millis() - ekf_check_state.last_warn_time) > EKF_CHECK_WARNING_TIME) { gcs().send_text(MAV_SEVERITY_CRITICAL,"EKF variance"); @@ -86,7 +86,7 @@ void Blimp::ekf_check() // if compass is flagged as bad and the counter reaches zero then clear flag if (ekf_check_state.bad_variance && ekf_check_state.fail_count == 0) { ekf_check_state.bad_variance = false; - AP::logger().Write_Error(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_VARIANCE_CLEARED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_VARIANCE_CLEARED); // clear failsafe failsafe_ekf_off_event(); } @@ -145,7 +145,7 @@ void Blimp::failsafe_ekf_event() // EKF failsafe event has occurred failsafe.ekf = true; - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_OCCURRED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_OCCURRED); // does this mode require position? if (!blimp.flightmode->requires_GPS() && (g.fs_ekf_action != FS_EKF_ACTION_LAND_EVEN_MANUAL)) { @@ -171,7 +171,7 @@ void Blimp::failsafe_ekf_off_event(void) } failsafe.ekf = false; - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_RESOLVED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_RESOLVED); } // check for ekf yaw reset and adjust target heading, also log position reset @@ -182,13 +182,13 @@ void Blimp::check_ekf_reset() uint32_t new_ekfYawReset_ms = ahrs.getLastYawResetAngle(yaw_angle_change_rad); if (new_ekfYawReset_ms != ekfYawReset_ms) { ekfYawReset_ms = new_ekfYawReset_ms; - AP::logger().Write_Event(LogEvent::EKF_YAW_RESET); + LOGGER_WRITE_EVENT(LogEvent::EKF_YAW_RESET); } // check for change in primary EKF, reset attitude target and log. AC_PosControl handles position target adjustment if ((ahrs.get_primary_core_index() != ekf_primary_core) && (ahrs.get_primary_core_index() != -1)) { ekf_primary_core = ahrs.get_primary_core_index(); - AP::logger().Write_Error(LogErrorSubsystem::EKF_PRIMARY, LogErrorCode(ekf_primary_core)); + LOGGER_WRITE_ERROR(LogErrorSubsystem::EKF_PRIMARY, LogErrorCode(ekf_primary_core)); gcs().send_text(MAV_SEVERITY_WARNING, "EKF primary changed:%d", (unsigned)ekf_primary_core); } } @@ -232,7 +232,7 @@ void Blimp::check_vibration() // restore ekf gains, reset timers and update user vibration_check.high_vibes = false; vibration_check.clear_ms = 0; - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_VIBE, LogErrorCode::FAILSAFE_RESOLVED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_VIBE, LogErrorCode::FAILSAFE_RESOLVED); gcs().send_text(MAV_SEVERITY_CRITICAL, "Vibration compensation OFF"); } } @@ -252,7 +252,7 @@ void Blimp::check_vibration() if (!vibration_check.high_vibes) { // switch ekf to use resistant gains vibration_check.high_vibes = true; - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_VIBE, LogErrorCode::FAILSAFE_OCCURRED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_VIBE, LogErrorCode::FAILSAFE_OCCURRED); gcs().send_text(MAV_SEVERITY_CRITICAL, "Vibration compensation ON"); } } diff --git a/Blimp/events.cpp b/Blimp/events.cpp index 452f624c5b879f..d7d7f7f52c33df 100644 --- a/Blimp/events.cpp +++ b/Blimp/events.cpp @@ -14,7 +14,7 @@ bool Blimp::failsafe_option(FailsafeOption opt) const void Blimp::failsafe_radio_on_event() { - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_RADIO, LogErrorCode::FAILSAFE_OCCURRED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_RADIO, LogErrorCode::FAILSAFE_OCCURRED); // set desired action based on FS_THR_ENABLE parameter Failsafe_Action desired_action; @@ -59,13 +59,13 @@ void Blimp::failsafe_radio_off_event() { // no need to do anything except log the error as resolved // user can now override roll, pitch, yaw and throttle and even use flight mode switch to restore previous flight mode - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_RADIO, LogErrorCode::FAILSAFE_RESOLVED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_RADIO, LogErrorCode::FAILSAFE_RESOLVED); gcs().send_text(MAV_SEVERITY_WARNING, "Radio Failsafe Cleared"); } void Blimp::handle_battery_failsafe(const char *type_str, const int8_t action) { - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_BATT, LogErrorCode::FAILSAFE_OCCURRED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_BATT, LogErrorCode::FAILSAFE_OCCURRED); Failsafe_Action desired_action = (Failsafe_Action)action; @@ -168,10 +168,10 @@ void Blimp::gpsglitch_check() if (ap.gps_glitching != gps_glitching) { ap.gps_glitching = gps_glitching; if (gps_glitching) { - AP::logger().Write_Error(LogErrorSubsystem::GPS, LogErrorCode::GPS_GLITCH); + LOGGER_WRITE_ERROR(LogErrorSubsystem::GPS, LogErrorCode::GPS_GLITCH); gcs().send_text(MAV_SEVERITY_CRITICAL,"GPS Glitch"); } else { - AP::logger().Write_Error(LogErrorSubsystem::GPS, LogErrorCode::ERROR_RESOLVED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::GPS, LogErrorCode::ERROR_RESOLVED); gcs().send_text(MAV_SEVERITY_CRITICAL,"GPS Glitch cleared"); } } diff --git a/Blimp/failsafe.cpp b/Blimp/failsafe.cpp index 0c05d3ea9183c0..3ea0d1199c43e5 100644 --- a/Blimp/failsafe.cpp +++ b/Blimp/failsafe.cpp @@ -43,7 +43,7 @@ void Blimp::failsafe_check() failsafe_last_timestamp = tnow; if (in_failsafe) { in_failsafe = false; - AP::logger().Write_Error(LogErrorSubsystem::CPU, LogErrorCode::FAILSAFE_RESOLVED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::CPU, LogErrorCode::FAILSAFE_RESOLVED); } return; } @@ -59,7 +59,7 @@ void Blimp::failsafe_check() //TODO: this may not work correctly. } - AP::logger().Write_Error(LogErrorSubsystem::CPU, LogErrorCode::FAILSAFE_OCCURRED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::CPU, LogErrorCode::FAILSAFE_OCCURRED); } if (failsafe_enabled && in_failsafe && tnow - failsafe_last_timestamp > 1000000) { diff --git a/Blimp/mode.cpp b/Blimp/mode.cpp index b7d80bd906100f..9165036cb7639e 100644 --- a/Blimp/mode.cpp +++ b/Blimp/mode.cpp @@ -78,7 +78,7 @@ bool Blimp::set_mode(Mode::Number mode, ModeReason reason) new_flightmode->requires_GPS() && !blimp.position_ok()) { gcs().send_text(MAV_SEVERITY_WARNING, "Mode change failed: %s requires position", new_flightmode->name()); - AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode)); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode)); return false; } @@ -89,13 +89,13 @@ bool Blimp::set_mode(Mode::Number mode, ModeReason reason) flightmode->has_manual_throttle() && !new_flightmode->has_manual_throttle()) { gcs().send_text(MAV_SEVERITY_WARNING, "Mode change failed: %s need alt estimate", new_flightmode->name()); - AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode)); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode)); return false; } if (!new_flightmode->init(ignore_checks)) { gcs().send_text(MAV_SEVERITY_WARNING,"Flight mode change failed %s", new_flightmode->name()); - AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode)); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode)); return false; } @@ -109,7 +109,9 @@ bool Blimp::set_mode(Mode::Number mode, ModeReason reason) flightmode = new_flightmode; control_mode = mode; control_mode_reason = reason; +#if HAL_LOGGING_ENABLED logger.Write_Mode((uint8_t)control_mode, reason); +#endif gcs().send_message(MSG_HEARTBEAT); // update notify object diff --git a/Blimp/radio.cpp b/Blimp/radio.cpp index 861c057820a5fc..02a42672e1843e 100644 --- a/Blimp/radio.cpp +++ b/Blimp/radio.cpp @@ -93,7 +93,7 @@ void Blimp::read_radio() } // Nobody ever talks to us. Log an error and enter failsafe. - AP::logger().Write_Error(LogErrorSubsystem::RADIO, LogErrorCode::RADIO_LATE_FRAME); + LOGGER_WRITE_ERROR(LogErrorSubsystem::RADIO, LogErrorCode::RADIO_LATE_FRAME); set_failsafe_radio(true); } @@ -155,4 +155,4 @@ void Blimp::set_throttle_zero_flag(int16_t throttle_control) ap.throttle_zero = true; } //TODO: This may not be needed -} \ No newline at end of file +} diff --git a/Blimp/system.cpp b/Blimp/system.cpp index f3d8bdc08e69f1..83b2b832e184ac 100644 --- a/Blimp/system.cpp +++ b/Blimp/system.cpp @@ -38,7 +38,7 @@ void Blimp::init_ardupilot() // setup telem slots with serial ports gcs().setup_uarts(); -#if LOGGING_ENABLED == ENABLED +#if HAL_LOGGING_ENABLED log_init(); #endif @@ -81,8 +81,10 @@ void Blimp::init_ardupilot() barometer.set_log_baro_bit(MASK_LOG_IMU); barometer.calibrate(); +#if HAL_LOGGING_ENABLED // initialise AP_Logger library logger.setVehicle_Startup_Writer(FUNCTOR_BIND(&blimp, &Blimp::Log_Write_Vehicle_Startup_Messages, void)); +#endif startup_INS_ground(); @@ -224,18 +226,16 @@ void Blimp::update_auto_armed() } } +#if HAL_LOGGING_ENABLED /* should we log a message type now? */ bool Blimp::should_log(uint32_t mask) { -#if LOGGING_ENABLED == ENABLED ap.logging_started = logger.logging_started(); return logger.should_log(mask); -#else - return false; -#endif } +#endif // return MAV_TYPE corresponding to frame class MAV_TYPE Blimp::get_frame_mav_type() From b94fc26c5f88ce4ce9ddf1b5c85af6ac455cc163 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 10 Jan 2024 15:21:39 +1100 Subject: [PATCH 0637/1335] AP_AIS: correct compilation when HAL_LOGGING_ENABLED is false --- libraries/AP_AIS/AP_AIS.cpp | 56 +++++++++++++++++++++++++++++++++++++ 1 file changed, 56 insertions(+) diff --git a/libraries/AP_AIS/AP_AIS.cpp b/libraries/AP_AIS/AP_AIS.cpp index c08a4dea0318f9..a47c57ee6fc315 100644 --- a/libraries/AP_AIS/AP_AIS.cpp +++ b/libraries/AP_AIS/AP_AIS.cpp @@ -31,6 +31,7 @@ #include #include #include +#include const AP_Param::GroupInfo AP_AIS::var_info[] = { @@ -120,20 +121,26 @@ void AP_AIS::update() if (_incoming.total > AIVDM_BUFFER_SIZE) { // no point in trying to decode it wont fit +#if HAL_LOGGING_ENABLED if (log_all || log_unsupported) { log_raw(&_incoming); } +#endif break; } +#if HAL_LOGGING_ENABLED if (log_all) { log_raw(&_incoming); } +#endif if (_incoming.num == 1 && _incoming.total == 1) { // single part message if (!payload_decode(_incoming.payload) && log_unsupported) { +#if HAL_LOGGING_ENABLED // could not decode so log log_raw(&_incoming); +#endif } } else if (_incoming.num == _incoming.total) { // last part of a multi part message @@ -154,12 +161,14 @@ void AP_AIS::update() // did we find the right number? if (_incoming.num != index) { // could not find all of the message, save messages +#if HAL_LOGGING_ENABLED if (log_unsupported) { for (uint8_t i = 0; i < index; i++) { log_raw(&_AIVDM_buffer[msg_parts[i]]); } log_raw(&_incoming); } +#endif // remove for (uint8_t i = 0; i < index; i++) { buffer_shift(msg_parts[i]); @@ -174,17 +183,23 @@ void AP_AIS::update() strncat(multi,_AIVDM_buffer[msg_parts[i]].payload,sizeof(multi)); } strncat(multi,_incoming.payload,sizeof(multi)); +#if HAL_LOGGING_ENABLED const bool decoded = payload_decode(multi); +#endif for (uint8_t i = 0; i < _incoming.total; i++) { +#if HAL_LOGGING_ENABLED // unsupported type, log and discard if (!decoded && log_unsupported) { log_raw(&_AIVDM_buffer[msg_parts[i]]); } +#endif buffer_shift(msg_parts[i]); } +#if HAL_LOGGING_ENABLED if (!decoded && log_unsupported) { log_raw(&_incoming); } +#endif } else { // multi part message, store in buffer bool fits_in = false; @@ -198,10 +213,12 @@ void AP_AIS::update() } if (!fits_in) { // remove the oldest message +#if HAL_LOGGING_ENABLED if (log_unsupported) { // log the unused message before removing it log_raw(&_AIVDM_buffer[0]); } +#endif buffer_shift(0); _AIVDM_buffer[AIVDM_BUFFER_SIZE - 1] = _incoming; } @@ -393,6 +410,7 @@ bool AP_AIS::decode_position_report(const char *payload, uint8_t type) bool raim = get_bits(payload, 148, 148); uint32_t radio = get_bits(payload, 149, 167); +#if HAL_LOGGING_ENABLED // log the raw infomation if ((_log_options & AIS_OPTIONS_LOG_DECODED) != 0) { const struct log_AIS_msg1 pkt{ @@ -416,6 +434,19 @@ bool AP_AIS::decode_position_report(const char *payload, uint8_t type) }; AP::logger().WriteBlock(&pkt, sizeof(pkt)); } +#else + (void)repeat; + (void)nav; + (void)rot; + (void)sog; + (void)pos_acc; + (void)cog; + (void)head; + (void)sec_utc; + (void)maneuver; + (void)raim; + (void)radio; +#endif uint16_t index; if (!get_vessel_index(mmsi, index, lat, lon)) { @@ -482,6 +513,7 @@ bool AP_AIS::decode_base_station_report(const char *payload) bool raim = get_bits(payload, 148, 148); uint32_t radio = get_bits(payload, 149, 167); +#if HAL_LOGGING_ENABLED // log the raw infomation if ((_log_options & AIS_OPTIONS_LOG_DECODED) != 0) { struct log_AIS_msg4 pkt { @@ -504,6 +536,19 @@ bool AP_AIS::decode_base_station_report(const char *payload) }; AP::logger().WriteBlock(&pkt, sizeof(pkt)); } +#else + (void)repeat; + (void)year; + (void)month; + (void)day; + (void)hour; + (void)minute; + (void)second; + (void)fix; + (void)epfd; + (void)raim; + (void)radio; +#endif uint16_t index; if (!get_vessel_index(mmsi, index)) { @@ -548,6 +593,7 @@ bool AP_AIS::decode_static_and_voyage_data(const char *payload) bool dte = get_bits(payload, 422, 422); // 423 - 426: spare +#if HAL_LOGGING_ENABLED // log the raw infomation if ((_log_options & AIS_OPTIONS_LOG_DECODED) != 0) { struct log_AIS_msg5 pkt { @@ -574,6 +620,14 @@ bool AP_AIS::decode_static_and_voyage_data(const char *payload) strncpy(pkt.dest, dest, sizeof(pkt.dest)); AP::logger().WriteBlock(&pkt, sizeof(pkt)); } +#else + (void)repeat; + (void)ver; + (void)imo; + (void)fix; + (void)draught; + (void)dte; +#endif uint16_t index; if (!get_vessel_index(mmsi, index)) { @@ -699,6 +753,7 @@ uint8_t AP_AIS::payload_char_decode(const char c) ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// // Functions for decoding and logging AIVDM NMEA sentence +#if HAL_LOGGING_ENABLED // log a raw AIVDM a message void AP_AIS::log_raw(const AIVDM *msg) { @@ -713,6 +768,7 @@ void AP_AIS::log_raw(const AIVDM *msg) memcpy(pkt.payload, msg->payload, sizeof(pkt.payload)); AP::logger().WriteBlock(&pkt, sizeof(pkt)); } +#endif // add a single character to the buffer and attempt to decode // returns true if a complete sentence was successfully decoded From 8bdd0294b87a63cf712e92a015b4ddae01816a20 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 10 Jan 2024 15:21:43 +1100 Subject: [PATCH 0638/1335] Rover: correct compilation when HAL_LOGGING_ENABLED is false --- Rover/AP_Arming.cpp | 2 ++ Rover/GCS_Mavlink.cpp | 4 ++++ Rover/Log.cpp | 2 +- Rover/Parameters.cpp | 2 ++ Rover/Rover.cpp | 13 +++++++++++-- Rover/Rover.h | 4 ++++ Rover/config.h | 7 ------- Rover/crash_check.cpp | 4 ++-- Rover/cruise_learn.cpp | 8 ++++++++ Rover/ekf_check.cpp | 8 ++++---- Rover/fence.cpp | 4 ++-- Rover/mode_auto.cpp | 2 ++ Rover/mode_dock.cpp | 2 ++ Rover/system.cpp | 12 ++++++++---- 14 files changed, 52 insertions(+), 22 deletions(-) diff --git a/Rover/AP_Arming.cpp b/Rover/AP_Arming.cpp index 02744eacd19190..36a28aea8780d4 100644 --- a/Rover/AP_Arming.cpp +++ b/Rover/AP_Arming.cpp @@ -106,7 +106,9 @@ void AP_Arming_Rover::update_soft_armed() { hal.util->set_soft_armed(is_armed() && hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED); +#if HAL_LOGGING_ENABLED AP::logger().set_vehicle_armed(hal.util->get_soft_armed()); +#endif } /* diff --git a/Rover/GCS_Mavlink.cpp b/Rover/GCS_Mavlink.cpp index e13e35bebc255c..bf86b9c7e3ba88 100644 --- a/Rover/GCS_Mavlink.cpp +++ b/Rover/GCS_Mavlink.cpp @@ -1065,7 +1065,11 @@ void GCS_MAVLINK_Rover::handle_set_position_target_global_int(const mavlink_mess void GCS_MAVLINK_Rover::handle_radio(const mavlink_message_t &msg) { +#if HAL_LOGGING_ENABLED handle_radio_status(msg, rover.should_log(MASK_LOG_PM)); +#else + handle_radio_status(msg, false); +#endif } /* diff --git a/Rover/Log.cpp b/Rover/Log.cpp index 36403f66d253ed..f102fa95c0ca41 100644 --- a/Rover/Log.cpp +++ b/Rover/Log.cpp @@ -2,7 +2,7 @@ #include -#if LOGGING_ENABLED == ENABLED +#if HAL_LOGGING_ENABLED // Write an attitude packet void Rover::Log_Write_Attitude() diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index ac1bdb29abdc14..ec6c8063cac8ad 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -316,9 +316,11 @@ const AP_Param::Info Rover::var_info[] = { // @Path: ../libraries/AP_Arming/AP_Arming.cpp GOBJECT(arming, "ARMING_", AP_Arming), +#if HAL_LOGGING_ENABLED // @Group: LOG // @Path: ../libraries/AP_Logger/AP_Logger.cpp GOBJECT(logger, "LOG", AP_Logger), +#endif // @Group: BATT // @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp diff --git a/Rover/Rover.cpp b/Rover/Rover.cpp index 82b7f46e371397..8e0faed41e530c 100644 --- a/Rover/Rover.cpp +++ b/Rover/Rover.cpp @@ -89,8 +89,10 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = { SCHED_TASK_CLASS(AP_WindVane, &rover.g2.windvane, update, 20, 100, 30), SCHED_TASK(update_wheel_encoder, 50, 200, 36), SCHED_TASK(update_compass, 10, 200, 39), +#if HAL_LOGGING_ENABLED SCHED_TASK(update_logging1, 10, 200, 45), SCHED_TASK(update_logging2, 10, 200, 48), +#endif SCHED_TASK_CLASS(GCS, (GCS*)&rover._gcs, update_receive, 400, 500, 51), SCHED_TASK_CLASS(GCS, (GCS*)&rover._gcs, update_send, 400, 1000, 54), SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&rover.g2.rc_channels, read_mode_switch, 7, 200, 57), @@ -123,11 +125,13 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = { SCHED_TASK_CLASS(AC_Sprayer, &rover.g2.sprayer, update, 3, 90, 99), #endif SCHED_TASK(compass_save, 0.1, 200, 105), -#if LOGGING_ENABLED == ENABLED +#if HAL_LOGGING_ENABLED SCHED_TASK_CLASS(AP_Logger, &rover.logger, periodic_tasks, 50, 300, 108), #endif SCHED_TASK_CLASS(AP_InertialSensor, &rover.ins, periodic, 400, 200, 111), +#if HAL_LOGGING_ENABLED SCHED_TASK_CLASS(AP_Scheduler, &rover.scheduler, update_logging, 0.1, 200, 114), +#endif #if HAL_BUTTON_ENABLED SCHED_TASK_CLASS(AP_Button, &rover.button, update, 5, 200, 117), #endif @@ -156,7 +160,9 @@ constexpr int8_t Rover::_failsafe_priorities[7]; Rover::Rover(void) : AP_Vehicle(), param_loader(var_info), +#if HAL_LOGGING_ENABLED logger{g.log_bitmask}, +#endif modes(&g.mode1), control_mode(&mode_initializing) { @@ -336,6 +342,7 @@ void Rover::ahrs_update() ground_speed = ahrs.groundspeed(); } +#if HAL_LOGGING_ENABLED if (should_log(MASK_LOG_ATTITUDE_FAST)) { Log_Write_Attitude(); Log_Write_Sail(); @@ -348,6 +355,7 @@ void Rover::ahrs_update() if (should_log(MASK_LOG_VIDEO_STABILISATION)) { ahrs.write_video_stabilisation(); } +#endif } /* @@ -376,6 +384,7 @@ void Rover::gcs_failsafe_check(void) failsafe_trigger(FAILSAFE_EVENT_GCS, "GCS", do_failsafe); } +#if HAL_LOGGING_ENABLED /* log some key data - 10Hz */ @@ -435,7 +444,7 @@ void Rover::update_logging2(void) } #endif } - +#endif // HAL_LOGGING_ENABLED /* once a second events diff --git a/Rover/Rover.h b/Rover/Rover.h index c6aa6db49702cc..cbc508cd2c0a84 100644 --- a/Rover/Rover.h +++ b/Rover/Rover.h @@ -136,7 +136,9 @@ class Rover : public AP_Vehicle { RC_Channel *channel_pitch; RC_Channel *channel_walking_height; +#if HAL_LOGGING_ENABLED AP_Logger logger; +#endif // flight modes convenience array AP_Int8 *modes; @@ -226,7 +228,9 @@ class Rover : public AP_Vehicle { static const AP_Scheduler::Task scheduler_tasks[]; static const AP_Param::Info var_info[]; +#if HAL_LOGGING_ENABLED static const LogStructure log_structure[]; +#endif // time that rudder/steering arming has been running uint32_t rudder_arm_timer; diff --git a/Rover/config.h b/Rover/config.h index 7a280e88f3497a..ef64d393c06927 100644 --- a/Rover/config.h +++ b/Rover/config.h @@ -45,13 +45,6 @@ #define CRUISE_SPEED 2 // in m/s #endif -////////////////////////////////////////////////////////////////////////////// -// Logging control -// -#ifndef LOGGING_ENABLED - #define LOGGING_ENABLED ENABLED -#endif - #define DEFAULT_LOG_BITMASK 0xffff ////////////////////////////////////////////////////////////////////////////// diff --git a/Rover/crash_check.cpp b/Rover/crash_check.cpp index feafdf7f6f6ef7..061e57ae9ce639 100644 --- a/Rover/crash_check.cpp +++ b/Rover/crash_check.cpp @@ -45,8 +45,8 @@ void Rover::crash_check() } if (crashed) { - AP::logger().Write_Error(LogErrorSubsystem::CRASH_CHECK, - LogErrorCode::CRASH_CHECK_CRASH); + LOGGER_WRITE_ERROR(LogErrorSubsystem::CRASH_CHECK, + LogErrorCode::CRASH_CHECK_CRASH); if (is_balancebot()) { // send message to gcs diff --git a/Rover/cruise_learn.cpp b/Rover/cruise_learn.cpp index 55d0e338ca155d..e844011296e2cc 100644 --- a/Rover/cruise_learn.cpp +++ b/Rover/cruise_learn.cpp @@ -15,7 +15,9 @@ void Rover::cruise_learn_start() cruise_learn.throttle_filt.reset(g2.motors.get_throttle()); cruise_learn.learn_start_ms = AP_HAL::millis(); cruise_learn.log_count = 0; +#if HAL_LOGGING_ENABLED log_write_cruise_learn(); +#endif gcs().send_text(MAV_SEVERITY_CRITICAL, "Cruise Learning started"); } @@ -29,10 +31,12 @@ void Rover::cruise_learn_update() cruise_learn.speed_filt.apply(speed, 0.02f); cruise_learn.throttle_filt.apply(g2.motors.get_throttle(), 0.02f); // 10Hz logging +#if HAL_LOGGING_ENABLED if (cruise_learn.log_count % 5 == 0) { log_write_cruise_learn(); } cruise_learn.log_count += 1; +#endif // check how long it took to learn if (AP_HAL::millis() - cruise_learn.learn_start_ms >= 2000) { cruise_learn_complete(); @@ -56,10 +60,13 @@ void Rover::cruise_learn_complete() gcs().send_text(MAV_SEVERITY_CRITICAL, "Cruise Learning failed"); } cruise_learn.learn_start_ms = 0; +#if HAL_LOGGING_ENABLED log_write_cruise_learn(); +#endif } } +#if HAL_LOGGING_ENABLED // logging for cruise learn void Rover::log_write_cruise_learn() const { @@ -77,3 +84,4 @@ void Rover::log_write_cruise_learn() const cruise_learn.speed_filt.get(), cruise_learn.throttle_filt.get()); } +#endif diff --git a/Rover/ekf_check.cpp b/Rover/ekf_check.cpp index 7f6d04b6376979..cf20b559703d73 100644 --- a/Rover/ekf_check.cpp +++ b/Rover/ekf_check.cpp @@ -53,7 +53,7 @@ void Rover::ekf_check() ekf_check_state.fail_count = EKF_CHECK_ITERATIONS_MAX; ekf_check_state.bad_variance = true; - AP::logger().Write_Error(LogErrorSubsystem::EKFCHECK, + LOGGER_WRITE_ERROR(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_BAD_VARIANCE); // send message to gcs if ((AP_HAL::millis() - ekf_check_state.last_warn_time) > EKF_CHECK_WARNING_TIME) { @@ -71,7 +71,7 @@ void Rover::ekf_check() // if variance is flagged as bad and the counter reaches zero then clear flag if (ekf_check_state.bad_variance && ekf_check_state.fail_count == 0) { ekf_check_state.bad_variance = false; - AP::logger().Write_Error(LogErrorSubsystem::EKFCHECK, + LOGGER_WRITE_ERROR(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_VARIANCE_CLEARED); // clear failsafe failsafe_ekf_off_event(); @@ -156,7 +156,7 @@ void Rover::failsafe_ekf_event() // EKF failsafe event has occurred failsafe.ekf = true; - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_EKFINAV, + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_OCCURRED); // does this mode require position? @@ -189,7 +189,7 @@ void Rover::failsafe_ekf_off_event(void) } failsafe.ekf = false; - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_EKFINAV, + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_EKFINAV, LogErrorCode::FAILSAFE_RESOLVED); gcs().send_text(MAV_SEVERITY_CRITICAL,"EKF failsafe cleared"); } diff --git a/Rover/fence.cpp b/Rover/fence.cpp index 7150c88c467ccc..4c29b48d243dcd 100644 --- a/Rover/fence.cpp +++ b/Rover/fence.cpp @@ -51,11 +51,11 @@ void Rover::fence_check() set_mode(mode_hold, ModeReason::FENCE_BREACHED); } } - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode(new_breaches)); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode(new_breaches)); } else if (orig_breaches) { // record clearing of breach - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_FENCE, + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode::ERROR_RESOLVED); } #endif // AP_FENCE_ENABLED diff --git a/Rover/mode_auto.cpp b/Rover/mode_auto.cpp index 5d2029b8201d25..d10f64fdfd81fc 100644 --- a/Rover/mode_auto.cpp +++ b/Rover/mode_auto.cpp @@ -512,10 +512,12 @@ void ModeAuto::send_guided_position_target() /********************************************************************************/ bool ModeAuto::start_command(const AP_Mission::Mission_Command& cmd) { +#if HAL_LOGGING_ENABLED // log when new commands start if (rover.should_log(MASK_LOG_CMD)) { rover.logger.Write_Mission_Cmd(mission, cmd); } +#endif switch (cmd.id) { case MAV_CMD_NAV_WAYPOINT: // Navigate to Waypoint diff --git a/Rover/mode_dock.cpp b/Rover/mode_dock.cpp index 4d52cb2af8ee03..89f8d89af7361a 100644 --- a/Rover/mode_dock.cpp +++ b/Rover/mode_dock.cpp @@ -171,6 +171,7 @@ void ModeDock::update() calc_steering_from_turn_rate(desired_turn_rate); calc_throttle(desired_speed, true); +#if HAL_LOGGING_ENABLED // @LoggerMessage: DOCK // @Description: Dock mode target information // @Field: TimeUS: Time since system startup @@ -196,6 +197,7 @@ void ModeDock::update() target_cm.y, desired_speed, desired_turn_rate); +#endif } float ModeDock::apply_slowdown(float desired_speed) diff --git a/Rover/system.cpp b/Rover/system.cpp index 492463e8a2345a..07ff6415499f8b 100644 --- a/Rover/system.cpp +++ b/Rover/system.cpp @@ -54,7 +54,7 @@ void Rover::init_ardupilot() osd.init(); #endif -#if LOGGING_ENABLED == ENABLED +#if HAL_LOGGING_ENABLED log_init(); #endif @@ -179,7 +179,7 @@ void Rover::startup_ground(void) mode_auto.mission.init(); // initialise AP_Logger library -#if LOGGING_ENABLED == ENABLED +#if HAL_LOGGING_ENABLED logger.setVehicle_Startup_Writer( FUNCTOR_BIND(&rover, &Rover::Log_Write_Vehicle_Startup_Messages, void) ); @@ -259,8 +259,8 @@ bool Rover::set_mode(Mode &new_mode, ModeReason reason) Mode &old_mode = *control_mode; if (!new_mode.enter()) { // Log error that we failed to enter desired flight mode - AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE, - LogErrorCode(new_mode.mode_number())); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FLIGHT_MODE, + LogErrorCode(new_mode.mode_number())); gcs().send_text(MAV_SEVERITY_WARNING, "Flight mode change failed"); return false; } @@ -281,7 +281,9 @@ bool Rover::set_mode(Mode &new_mode, ModeReason reason) old_mode.exit(); control_mode_reason = reason; +#if HAL_LOGGING_ENABLED logger.Write_Mode((uint8_t)control_mode->mode_number(), control_mode_reason); +#endif gcs().send_message(MSG_HEARTBEAT); notify_mode(control_mode); @@ -340,6 +342,7 @@ uint8_t Rover::check_digital_pin(uint8_t pin) return hal.gpio->read(pin); } +#if HAL_LOGGING_ENABLED /* should we log a message type now? */ @@ -347,6 +350,7 @@ bool Rover::should_log(uint32_t mask) { return logger.should_log(mask); } +#endif // returns true if vehicle is a boat // this affects whether the vehicle tries to maintain position after reaching waypoints From 9a853b3d4af105da64a34030aa3930aaf2e8580c Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 10 Jan 2024 15:21:23 +1100 Subject: [PATCH 0639/1335] AP_WindVane: correct compilation when HAL_LOGGING_ENABLED is false --- libraries/AP_WindVane/AP_WindVane.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/libraries/AP_WindVane/AP_WindVane.cpp b/libraries/AP_WindVane/AP_WindVane.cpp index 44845d4d469e87..7d336a41c570c2 100644 --- a/libraries/AP_WindVane/AP_WindVane.cpp +++ b/libraries/AP_WindVane/AP_WindVane.cpp @@ -372,6 +372,7 @@ void AP_WindVane::update() _direction_true = _direction_true_raw; } +#if HAL_LOGGING_ENABLED // @LoggerMessage: WIND // @Description: Windvane readings // @Field: TimeUS: Time since system startup @@ -390,6 +391,7 @@ void AP_WindVane::update() _speed_apparent_raw, _speed_apparent, _speed_true); +#endif } From 852944a1b102dea6b7931920b4031f41065ebba4 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 10 Jan 2024 15:34:30 +1100 Subject: [PATCH 0640/1335] Sub: correct compilation when HAL_LOGGING_ENABLED is false --- ArduSub/AP_Arming_Sub.cpp | 6 ++++++ ArduSub/ArduSub.cpp | 12 ++++++++++++ ArduSub/Log.cpp | 18 ++---------------- ArduSub/Parameters.cpp | 2 ++ ArduSub/Sub.cpp | 5 ++++- ArduSub/Sub.h | 5 +++++ ArduSub/commands_logic.cpp | 4 +++- ArduSub/config.h | 3 --- ArduSub/failsafe.cpp | 28 ++++++++++++++-------------- ArduSub/fence.cpp | 4 ++-- ArduSub/mode.cpp | 8 +++++--- ArduSub/mode_guided.cpp | 27 +++++++++++++++++++++------ ArduSub/surface_bottom_detector.cpp | 8 ++++---- ArduSub/system.cpp | 10 ++++------ ArduSub/terrain.cpp | 2 ++ 15 files changed, 86 insertions(+), 56 deletions(-) diff --git a/ArduSub/AP_Arming_Sub.cpp b/ArduSub/AP_Arming_Sub.cpp index 66dfecff2b37bd..463d78a4eaabcf 100644 --- a/ArduSub/AP_Arming_Sub.cpp +++ b/ArduSub/AP_Arming_Sub.cpp @@ -91,8 +91,10 @@ bool AP_Arming_Sub::arm(AP_Arming::Method method, bool do_arming_checks) return false; } +#if HAL_LOGGING_ENABLED // let logger know that we're armed (it may open logs e.g.) AP::logger().set_vehicle_armed(true); +#endif // disable cpu failsafe because initialising everything takes a while sub.mainloop_failsafe_disable(); @@ -133,8 +135,10 @@ bool AP_Arming_Sub::arm(AP_Arming::Method method, bool do_arming_checks) // finally actually arm the motors sub.motors.armed(true); +#if HAL_LOGGING_ENABLED // log flight mode in case it was changed while vehicle was disarmed AP::logger().Write_Mode((uint8_t)sub.control_mode, sub.control_mode_reason); +#endif // reenable failsafe sub.mainloop_failsafe_enable(); @@ -182,7 +186,9 @@ bool AP_Arming_Sub::disarm(const AP_Arming::Method method, bool do_disarm_checks // reset the mission sub.mission.reset(); +#if HAL_LOGGING_ENABLED AP::logger().set_vehicle_armed(false); +#endif hal.util->set_soft_armed(false); diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index e8012d2e91f612..d70b7e1e822441 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -89,11 +89,15 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = { #if AP_CAMERA_ENABLED SCHED_TASK_CLASS(AP_Camera, &sub.camera, update, 50, 75, 48), #endif +#if HAL_LOGGING_ENABLED SCHED_TASK(ten_hz_logging_loop, 10, 350, 51), SCHED_TASK(twentyfive_hz_logging, 25, 110, 54), SCHED_TASK_CLASS(AP_Logger, &sub.logger, periodic_tasks, 400, 300, 57), +#endif SCHED_TASK_CLASS(AP_InertialSensor, &sub.ins, periodic, 400, 50, 60), +#if HAL_LOGGING_ENABLED SCHED_TASK_CLASS(AP_Scheduler, &sub.scheduler, update_logging, 0.1, 75, 63), +#endif #if AP_RPM_ENABLED SCHED_TASK_CLASS(AP_RPM, &sub.rpm_sensor, update, 10, 200, 66), #endif @@ -177,6 +181,7 @@ void Sub::update_batt_compass() } } +#if HAL_LOGGING_ENABLED // ten_hz_logging_loop // should be run at 10hz void Sub::ten_hz_logging_loop() @@ -237,6 +242,7 @@ void Sub::twentyfive_hz_logging() AP::ins().Write_IMU(); } } +#endif // HAL_LOGGING_ENABLED // three_hz_loop - 3.3hz loop void Sub::three_hz_loop() @@ -274,9 +280,11 @@ void Sub::one_hz_loop() AP_Notify::flags.pre_arm_gps_check = position_ok(); AP_Notify::flags.flying = motors.armed(); +#if HAL_LOGGING_ENABLED if (should_log(MASK_LOG_ANY)) { Log_Write_Data(LogDataID::AP_STATE, ap.value); } +#endif if (!motors.armed()) { motors.update_throttle_range(); @@ -285,8 +293,10 @@ void Sub::one_hz_loop() // update assigned functions and enable auxiliary servos SRV_Channels::enable_aux_servos(); +#if HAL_LOGGING_ENABLED // log terrain data terrain_logging(); +#endif // need to set "likely flying" when armed to allow for compass // learning to run @@ -311,6 +321,7 @@ void Sub::update_altitude() // read in baro altitude read_barometer(); +#if HAL_LOGGING_ENABLED if (should_log(MASK_LOG_CTUN)) { Log_Write_Control_Tuning(); AP::ins().write_notch_log_messages(); @@ -318,6 +329,7 @@ void Sub::update_altitude() gyro_fft.write_log_messages(); #endif } +#endif // HAL_LOGGING_ENABLED } bool Sub::control_check_barometer() diff --git a/ArduSub/Log.cpp b/ArduSub/Log.cpp index f2649bc8417a92..63d3feb8ff222d 100644 --- a/ArduSub/Log.cpp +++ b/ArduSub/Log.cpp @@ -1,6 +1,6 @@ #include "Sub.h" -#if LOGGING_ENABLED == ENABLED +#if HAL_LOGGING_ENABLED // Code to Write and Read packets from AP_Logger log memory // Code to interact with the user to dump or erase logs @@ -289,18 +289,4 @@ void Sub::log_init() logger.Init(log_structure, ARRAY_SIZE(log_structure)); } -#else // LOGGING_ENABLED - -void Sub::Log_Write_Control_Tuning() {} -void Sub::Log_Write_Attitude(void) {} -void Sub::Log_Write_Data(LogDataID id, int32_t value) {} -void Sub::Log_Write_Data(LogDataID id, uint32_t value) {} -void Sub::Log_Write_Data(LogDataID id, int16_t value) {} -void Sub::Log_Write_Data(LogDataID id, uint16_t value) {} -void Sub::Log_Write_Data(LogDataID id, float value) {} -void Sub::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target) {} -void Sub::Log_Write_Vehicle_Startup_Messages() {} - -void Sub::log_init(void) {} - -#endif // LOGGING_ENABLED +#endif // HAL_LOGGING_ENABLED diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index 5711f4fe31dc8e..d58bbf275a970d 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -561,9 +561,11 @@ const AP_Param::Info Sub::var_info[] = { GOBJECT(camera_mount, "MNT", AP_Mount), #endif +#if HAL_LOGGING_ENABLED // @Group: LOG // @Path: ../libraries/AP_Logger/AP_Logger.cpp GOBJECT(logger, "LOG", AP_Logger), +#endif // @Group: BATT // @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp diff --git a/ArduSub/Sub.cpp b/ArduSub/Sub.cpp index 2a90c7f3a685e3..304ed327249e55 100644 --- a/ArduSub/Sub.cpp +++ b/ArduSub/Sub.cpp @@ -24,7 +24,10 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); constructor for main Sub class */ Sub::Sub() - : logger(g.log_bitmask), + : +#if HAL_LOGGING_ENABLED + logger(g.log_bitmask), +#endif control_mode(Mode::Number::MANUAL), motors(MAIN_LOOP_RATE), auto_mode(Auto_WP), diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 482aabfc388920..53de38af092b79 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -62,6 +62,7 @@ #include // Joystick/gamepad button function assignment #include // Leak detector #include +#include // Local modules #include "defines.h" @@ -145,7 +146,9 @@ class Sub : public AP_Vehicle { RC_Channel *channel_forward; RC_Channel *channel_lateral; +#if HAL_LOGGING_ENABLED AP_Logger logger; +#endif AP_LeakDetector leak_detector; @@ -399,6 +402,7 @@ class Sub : public AP_Vehicle { float get_pilot_desired_climb_rate(float throttle_control); float get_surface_tracking_climb_rate(int16_t target_rate, float current_alt_target, float dt); void rotate_body_frame_to_NE(float &x, float &y); +#if HAL_LOGGING_ENABLED void Log_Write_Control_Tuning(); void Log_Write_Attitude(); void Log_Write_Data(LogDataID id, int32_t value); @@ -408,6 +412,7 @@ class Sub : public AP_Vehicle { void Log_Write_Data(LogDataID id, float value); void Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target); void Log_Write_Vehicle_Startup_Messages(); +#endif void load_parameters(void) override; void userhook_init(); void userhook_FastLoop(); diff --git a/ArduSub/commands_logic.cpp b/ArduSub/commands_logic.cpp index 681022a3dd93bf..48051f9ff42837 100644 --- a/ArduSub/commands_logic.cpp +++ b/ArduSub/commands_logic.cpp @@ -7,10 +7,12 @@ static enum AutoSurfaceState auto_surface_state = AUTO_SURFACE_STATE_GO_TO_LOCAT // start_command - this function will be called when the ap_mission lib wishes to start a new command bool Sub::start_command(const AP_Mission::Mission_Command& cmd) { +#if HAL_LOGGING_ENABLED // To-Do: logging when new commands start/end if (should_log(MASK_LOG_CMD)) { logger.Write_Mission_Cmd(mission, cmd); } +#endif const Location &target_loc = cmd.content.location; @@ -347,7 +349,7 @@ void Sub::do_circle(const AP_Mission::Mission_Command& cmd) } else { // default to current altitude above origin circle_center.set_alt_cm(current_loc.alt, current_loc.get_alt_frame()); - AP::logger().Write_Error(LogErrorSubsystem::TERRAIN, LogErrorCode::MISSING_TERRAIN_DATA); + LOGGER_WRITE_ERROR(LogErrorSubsystem::TERRAIN, LogErrorCode::MISSING_TERRAIN_DATA); } } diff --git a/ArduSub/config.h b/ArduSub/config.h index 4a517afe13adbb..bb77f88ea24084 100644 --- a/ArduSub/config.h +++ b/ArduSub/config.h @@ -186,9 +186,6 @@ ////////////////////////////////////////////////////////////////////////////// // Logging control // -#ifndef LOGGING_ENABLED -# define LOGGING_ENABLED ENABLED -#endif // Statistics #ifndef STATS_ENABLED diff --git a/ArduSub/failsafe.cpp b/ArduSub/failsafe.cpp index 5c0d08d32499cf..80c74ed45829d1 100644 --- a/ArduSub/failsafe.cpp +++ b/ArduSub/failsafe.cpp @@ -37,7 +37,7 @@ void Sub::mainloop_failsafe_check() failsafe_last_timestamp = tnow; if (in_failsafe) { in_failsafe = false; - AP::logger().Write_Error(LogErrorSubsystem::CPU,LogErrorCode::FAILSAFE_RESOLVED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::CPU,LogErrorCode::FAILSAFE_RESOLVED); } return; } @@ -51,7 +51,7 @@ void Sub::mainloop_failsafe_check() if (motors.armed()) { motors.output_min(); } - AP::logger().Write_Error(LogErrorSubsystem::CPU,LogErrorCode::FAILSAFE_OCCURRED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::CPU,LogErrorCode::FAILSAFE_OCCURRED); } if (failsafe_enabled && in_failsafe && tnow - failsafe_last_timestamp > 1000000) { @@ -73,7 +73,7 @@ void Sub::failsafe_sensors_check() // We need a depth sensor to do any sort of auto z control if (sensor_health.depth) { if (failsafe.sensor_health) { - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_SENSORS, LogErrorCode::ERROR_RESOLVED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_SENSORS, LogErrorCode::ERROR_RESOLVED); failsafe.sensor_health = false; } return; @@ -86,7 +86,7 @@ void Sub::failsafe_sensors_check() failsafe.sensor_health = true; gcs().send_text(MAV_SEVERITY_CRITICAL, "Depth sensor error!"); - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_SENSORS, LogErrorCode::BAD_DEPTH); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_SENSORS, LogErrorCode::BAD_DEPTH); if (control_mode == Mode::Number::ALT_HOLD || control_mode == Mode::Number::SURFACE || sub.flightmode->requires_GPS()) { // This should always succeed @@ -137,7 +137,7 @@ void Sub::failsafe_ekf_check() failsafe.ekf = true; AP_Notify::flags.ekf_bad = true; - AP::logger().Write_Error(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_BAD_VARIANCE); + LOGGER_WRITE_ERROR(LogErrorSubsystem::EKFCHECK, LogErrorCode::EKFCHECK_BAD_VARIANCE); if (AP_HAL::millis() > failsafe.last_ekf_warn_ms + 20000) { failsafe.last_ekf_warn_ms = AP_HAL::millis(); @@ -152,7 +152,7 @@ void Sub::failsafe_ekf_check() // Battery failsafe handler void Sub::handle_battery_failsafe(const char* type_str, const int8_t action) { - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_BATT, LogErrorCode::FAILSAFE_OCCURRED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_BATT, LogErrorCode::FAILSAFE_OCCURRED); switch((Failsafe_Action)action) { case Failsafe_Action_Surface: @@ -187,7 +187,7 @@ void Sub::failsafe_pilot_input_check() failsafe.pilot_input = true; - AP::logger().Write_Error(LogErrorSubsystem::PILOT_INPUT, LogErrorCode::FAILSAFE_OCCURRED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::PILOT_INPUT, LogErrorCode::FAILSAFE_OCCURRED); gcs().send_text(MAV_SEVERITY_CRITICAL, "Lost manual control"); set_neutral_controls(); @@ -270,7 +270,7 @@ void Sub::failsafe_leak_check() // Do nothing if we are dry, or if leak failsafe action is disabled if (status == false || g.failsafe_leak == FS_LEAK_DISABLED) { if (failsafe.leak) { - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_LEAK, LogErrorCode::FAILSAFE_RESOLVED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_LEAK, LogErrorCode::FAILSAFE_RESOLVED); } AP_Notify::flags.leak_detected = false; failsafe.leak = false; @@ -295,7 +295,7 @@ void Sub::failsafe_leak_check() failsafe.leak = true; - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_LEAK, LogErrorCode::FAILSAFE_OCCURRED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_LEAK, LogErrorCode::FAILSAFE_OCCURRED); // Handle failsafe action if (failsafe.leak && g.failsafe_leak == FS_LEAK_SURFACE && motors.armed()) { @@ -324,7 +324,7 @@ void Sub::failsafe_gcs_check() if (tnow - gcs_last_seen_ms < FS_GCS_TIMEOUT_MS) { // Log event if we are recovering from previous gcs failsafe if (failsafe.gcs) { - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_GCS, LogErrorCode::FAILSAFE_RESOLVED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_GCS, LogErrorCode::FAILSAFE_RESOLVED); } failsafe.gcs = false; return; @@ -346,7 +346,7 @@ void Sub::failsafe_gcs_check() } failsafe.gcs = true; - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_GCS, LogErrorCode::FAILSAFE_OCCURRED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_GCS, LogErrorCode::FAILSAFE_OCCURRED); // handle failsafe action if (g.failsafe_gcs == FS_GCS_DISARM) { @@ -412,7 +412,7 @@ void Sub::failsafe_crash_check() } failsafe.crash = true; - AP::logger().Write_Error(LogErrorSubsystem::CRASH_CHECK, LogErrorCode::CRASH_CHECK_CRASH); + LOGGER_WRITE_ERROR(LogErrorSubsystem::CRASH_CHECK, LogErrorCode::CRASH_CHECK_CRASH); // disarm motors if (g.fs_crash_check == FS_CRASH_DISARM) { @@ -435,7 +435,7 @@ void Sub::failsafe_terrain_check() gcs().send_text(MAV_SEVERITY_CRITICAL,"Failsafe terrain triggered"); failsafe_terrain_on_event(); } else { - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_TERRAIN, LogErrorCode::ERROR_RESOLVED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_TERRAIN, LogErrorCode::ERROR_RESOLVED); failsafe.terrain = false; } } @@ -467,7 +467,7 @@ void Sub::failsafe_terrain_set_status(bool data_ok) void Sub::failsafe_terrain_on_event() { failsafe.terrain = true; - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_TERRAIN, LogErrorCode::FAILSAFE_OCCURRED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_TERRAIN, LogErrorCode::FAILSAFE_OCCURRED); // If rangefinder is enabled, we can recover from this failsafe if (!rangefinder_state.enabled || !sub.mode_auto.auto_terrain_recover_start()) { diff --git a/ArduSub/fence.cpp b/ArduSub/fence.cpp index c39e84aebf5319..7e895c20da429e 100644 --- a/ArduSub/fence.cpp +++ b/ArduSub/fence.cpp @@ -41,10 +41,10 @@ void Sub::fence_check() // } } - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode(new_breaches)); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode(new_breaches)); } else if (orig_breaches) { // record clearing of breach - AP::logger().Write_Error(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode::ERROR_RESOLVED); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode::ERROR_RESOLVED); } } diff --git a/ArduSub/mode.cpp b/ArduSub/mode.cpp index 323836c2f94abb..9a945d85e49eb1 100644 --- a/ArduSub/mode.cpp +++ b/ArduSub/mode.cpp @@ -86,7 +86,7 @@ bool Sub::set_mode(Mode::Number mode, ModeReason reason) if (new_flightmode->requires_GPS() && !sub.position_ok()) { gcs().send_text(MAV_SEVERITY_WARNING, "Mode change failed: %s requires position", new_flightmode->name()); - AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode)); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode)); return false; } @@ -96,13 +96,13 @@ bool Sub::set_mode(Mode::Number mode, ModeReason reason) flightmode->has_manual_throttle() && !new_flightmode->has_manual_throttle()) { gcs().send_text(MAV_SEVERITY_WARNING, "Mode change failed: %s need alt estimate", new_flightmode->name()); - AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode)); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode)); return false; } if (!new_flightmode->init(false)) { gcs().send_text(MAV_SEVERITY_WARNING,"Flight mode change failed %s", new_flightmode->name()); - AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode)); + LOGGER_WRITE_ERROR(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode)); return false; } @@ -116,7 +116,9 @@ bool Sub::set_mode(Mode::Number mode, ModeReason reason) flightmode = new_flightmode; control_mode = mode; control_mode_reason = reason; +#if HAL_LOGGING_ENABLED logger.Write_Mode((uint8_t)control_mode, reason); +#endif gcs().send_message(MSG_HEARTBEAT); // update notify object diff --git a/ArduSub/mode_guided.cpp b/ArduSub/mode_guided.cpp index 25857bf5c94e64..ff1bb07df5681a 100644 --- a/ArduSub/mode_guided.cpp +++ b/ArduSub/mode_guided.cpp @@ -170,7 +170,7 @@ bool ModeGuided::guided_set_destination(const Vector3f& destination) // reject destination if outside the fence const Location dest_loc(destination, Location::AltFrame::ABOVE_ORIGIN); if (!sub.fence.check_destination_within_fence(dest_loc)) { - AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE); + LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE); // failure is propagated to GCS with NAK return false; } @@ -179,8 +179,11 @@ bool ModeGuided::guided_set_destination(const Vector3f& destination) // no need to check return status because terrain data is not used sub.wp_nav.set_wp_destination(destination, false); +#if HAL_LOGGING_ENABLED // log target sub.Log_Write_GuidedTarget(sub.guided_mode, destination, Vector3f()); +#endif + return true; } @@ -198,7 +201,7 @@ bool ModeGuided::guided_set_destination(const Location& dest_loc) // reject destination outside the fence. // Note: there is a danger that a target specified as a terrain altitude might not be checked if the conversion to alt-above-home fails if (!sub.fence.check_destination_within_fence(dest_loc)) { - AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE); + LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE); // failure is propagated to GCS with NAK return false; } @@ -206,13 +209,16 @@ bool ModeGuided::guided_set_destination(const Location& dest_loc) if (!sub.wp_nav.set_wp_destination_loc(dest_loc)) { // failure to set destination can only be because of missing terrain data - AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_TO_SET_DESTINATION); + LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_TO_SET_DESTINATION); // failure is propagated to GCS with NAK return false; } +#if HAL_LOGGING_ENABLED // log target sub.Log_Write_GuidedTarget(sub.guided_mode, Vector3f(dest_loc.lat, dest_loc.lng, dest_loc.alt),Vector3f()); +#endif + return true; } @@ -230,7 +236,7 @@ bool ModeGuided::guided_set_destination(const Vector3f& destination, bool use_ya // reject destination if outside the fence const Location dest_loc(destination, Location::AltFrame::ABOVE_ORIGIN); if (!sub.fence.check_destination_within_fence(dest_loc)) { - AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE); + LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE); // failure is propagated to GCS with NAK return false; } @@ -244,8 +250,11 @@ bool ModeGuided::guided_set_destination(const Vector3f& destination, bool use_ya // no need to check return status because terrain data is not used sub.wp_nav.set_wp_destination(destination, false); +#if HAL_LOGGING_ENABLED // log target sub.Log_Write_GuidedTarget(sub.guided_mode, destination, Vector3f()); +#endif + return true; } @@ -293,7 +302,7 @@ bool ModeGuided::guided_set_destination_posvel(const Vector3f& destination, cons // reject destination if outside the fence const Location dest_loc(destination, Location::AltFrame::ABOVE_ORIGIN); if (!sub.fence.check_destination_within_fence(dest_loc)) { - AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE); + LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE); // failure is propagated to GCS with NAK return false; } @@ -308,8 +317,11 @@ bool ModeGuided::guided_set_destination_posvel(const Vector3f& destination, cons position_control->input_pos_vel_accel_z(dz, posvel_vel_target_cms.z, 0); posvel_pos_target_cm.z = dz; +#if HAL_LOGGING_ENABLED // log target sub.Log_Write_GuidedTarget(sub.guided_mode, destination, velocity); +#endif + return true; } @@ -325,7 +337,7 @@ bool ModeGuided::guided_set_destination_posvel(const Vector3f& destination, cons // reject destination if outside the fence const Location dest_loc(destination, Location::AltFrame::ABOVE_ORIGIN); if (!sub.fence.check_destination_within_fence(dest_loc)) { - AP::logger().Write_Error(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE); + LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::DEST_OUTSIDE_FENCE); // failure is propagated to GCS with NAK return false; } @@ -344,8 +356,11 @@ bool ModeGuided::guided_set_destination_posvel(const Vector3f& destination, cons position_control->input_pos_vel_accel_z(dz, posvel_vel_target_cms.z, 0); posvel_pos_target_cm.z = dz; +#if HAL_LOGGING_ENABLED // log target sub.Log_Write_GuidedTarget(sub.guided_mode, destination, velocity); +#endif + return true; } diff --git a/ArduSub/surface_bottom_detector.cpp b/ArduSub/surface_bottom_detector.cpp index 0338e77c99d4c3..ca1b58646e337b 100644 --- a/ArduSub/surface_bottom_detector.cpp +++ b/ArduSub/surface_bottom_detector.cpp @@ -90,9 +90,9 @@ void Sub::set_surfaced(bool at_surface) surface_detector_count = 0; if (ap.at_surface) { - AP::logger().Write_Event(LogEvent::SURFACED); + LOGGER_WRITE_EVENT(LogEvent::SURFACED); } else { - AP::logger().Write_Event(LogEvent::NOT_SURFACED); + LOGGER_WRITE_EVENT(LogEvent::NOT_SURFACED); } } @@ -108,8 +108,8 @@ void Sub::set_bottomed(bool at_bottom) bottom_detector_count = 0; if (ap.at_bottom) { - AP::logger().Write_Event(LogEvent::BOTTOMED); + LOGGER_WRITE_EVENT(LogEvent::BOTTOMED); } else { - AP::logger().Write_Event(LogEvent::NOT_BOTTOMED); + LOGGER_WRITE_EVENT(LogEvent::NOT_BOTTOMED); } } diff --git a/ArduSub/system.cpp b/ArduSub/system.cpp index 487abe625e063a..67a5d15c70b913 100644 --- a/ArduSub/system.cpp +++ b/ArduSub/system.cpp @@ -62,7 +62,7 @@ void Sub::init_ardupilot() // setup telem slots with serial ports gcs().setup_uarts(); -#if LOGGING_ENABLED == ENABLED +#if HAL_LOGGING_ENABLED log_init(); #endif @@ -161,7 +161,7 @@ void Sub::init_ardupilot() mission.init(); // initialise AP_Logger library -#if LOGGING_ENABLED == ENABLED +#if HAL_LOGGING_ENABLED logger.setVehicle_Startup_Writer(FUNCTOR_BIND(&sub, &Sub::Log_Write_Vehicle_Startup_Messages, void)); #endif @@ -264,18 +264,16 @@ bool Sub::optflow_position_ok() return (filt_status.flags.horiz_pos_rel && !filt_status.flags.const_pos_mode); } +#if HAL_LOGGING_ENABLED /* should we log a message type now? */ bool Sub::should_log(uint32_t mask) { -#if LOGGING_ENABLED == ENABLED ap.logging_started = logger.logging_started(); return logger.should_log(mask); -#else - return false; -#endif } +#endif #include #include diff --git a/ArduSub/terrain.cpp b/ArduSub/terrain.cpp index 30b7351ce4b8c4..50249ade7b3322 100644 --- a/ArduSub/terrain.cpp +++ b/ArduSub/terrain.cpp @@ -17,6 +17,7 @@ void Sub::terrain_update() #endif } +#if HAL_LOGGING_ENABLED // log terrain data - should be called at 1hz void Sub::terrain_logging() { @@ -26,4 +27,5 @@ void Sub::terrain_logging() } #endif } +#endif // HAL_LOGGING_ENABLED From dae819ba5478ead5464d6a771a951121e9ddd622 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 10 Jan 2024 15:40:09 +1100 Subject: [PATCH 0641/1335] Tracker: correct compilation when HAL_LOGGING_ENABLED is false --- AntennaTracker/Log.cpp | 13 ++----------- AntennaTracker/Parameters.cpp | 2 ++ AntennaTracker/Tracker.cpp | 6 +++++- AntennaTracker/Tracker.h | 2 ++ AntennaTracker/config.h | 3 --- AntennaTracker/system.cpp | 13 +++++++++++-- AntennaTracker/tracking.cpp | 4 ++++ 7 files changed, 26 insertions(+), 17 deletions(-) diff --git a/AntennaTracker/Log.cpp b/AntennaTracker/Log.cpp index 742d0247189d56..5a70a09eb44305 100644 --- a/AntennaTracker/Log.cpp +++ b/AntennaTracker/Log.cpp @@ -1,6 +1,6 @@ #include "Tracker.h" -#if LOGGING_ENABLED == ENABLED +#if HAL_LOGGING_ENABLED // Code to Write and Read packets from AP_Logger log memory @@ -98,13 +98,4 @@ void Tracker::log_init(void) logger.Init(log_structure, ARRAY_SIZE(log_structure)); } -#else // LOGGING_ENABLED - -void Tracker::Log_Write_Attitude(void) {} - -void Tracker::log_init(void) {} -void Tracker::Log_Write_Vehicle_Pos(int32_t lat, int32_t lng, int32_t alt, const Vector3f& vel) {} -void Tracker::Log_Write_Vehicle_Baro(float pressure, float altitude) {} -void Tracker::Log_Write_Vehicle_Startup_Messages() {} - -#endif // LOGGING_ENABLED +#endif // HAL_LOGGING_ENABLED diff --git a/AntennaTracker/Parameters.cpp b/AntennaTracker/Parameters.cpp index 2d20396ecfc694..2d7dc5d80513ca 100644 --- a/AntennaTracker/Parameters.cpp +++ b/AntennaTracker/Parameters.cpp @@ -576,9 +576,11 @@ const AP_Param::Info Tracker::var_info[] = { // @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp PARAM_VEHICLE_INFO, +#if HAL_LOGGING_ENABLED // @Group: LOG // @Path: ../libraries/AP_Logger/AP_Logger.cpp GOBJECT(logger, "LOG", AP_Logger), +#endif #if HAL_NAVEKF2_AVAILABLE // @Group: EK2_ diff --git a/AntennaTracker/Tracker.cpp b/AntennaTracker/Tracker.cpp index fbf3427c501c55..c81279dd832e5e 100644 --- a/AntennaTracker/Tracker.cpp +++ b/AntennaTracker/Tracker.cpp @@ -59,8 +59,8 @@ const AP_Scheduler::Task Tracker::scheduler_tasks[] = { SCHED_TASK_CLASS(GCS, (GCS*)&tracker._gcs, update_receive, 50, 1700, 45), SCHED_TASK_CLASS(GCS, (GCS*)&tracker._gcs, update_send, 50, 3000, 50), SCHED_TASK_CLASS(AP_Baro, &tracker.barometer, accumulate, 50, 900, 55), +#if HAL_LOGGING_ENABLED SCHED_TASK(ten_hz_logging_loop, 10, 300, 60), -#if LOGGING_ENABLED == ENABLED SCHED_TASK_CLASS(AP_Logger, &tracker.logger, periodic_tasks, 50, 300, 65), #endif SCHED_TASK_CLASS(AP_InertialSensor, &tracker.ins, periodic, 50, 50, 70), @@ -107,6 +107,7 @@ void Tracker::one_second_loop() g.pidYaw2Srv.set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz()); } +#if HAL_LOGGING_ENABLED void Tracker::ten_hz_logging_loop() { if (should_log(MASK_LOG_IMU)) { @@ -122,6 +123,7 @@ void Tracker::ten_hz_logging_loop() logger.Write_RCOUT(); } } +#endif Mode *Tracker::mode_from_mode_num(const Mode::Number num) { @@ -164,7 +166,9 @@ void Tracker::stats_update(void) const AP_HAL::HAL& hal = AP_HAL::get_HAL(); Tracker::Tracker(void) +#if HAL_LOGGING_ENABLED : logger(g.log_bitmask) +#endif { } diff --git a/AntennaTracker/Tracker.h b/AntennaTracker/Tracker.h index 55c76985b22b55..d003b038b6fb22 100644 --- a/AntennaTracker/Tracker.h +++ b/AntennaTracker/Tracker.h @@ -79,7 +79,9 @@ class Tracker : public AP_Vehicle { uint32_t start_time_ms = 0; +#if HAL_LOGGING_ENABLED AP_Logger logger; +#endif /** antenna control channels diff --git a/AntennaTracker/config.h b/AntennaTracker/config.h index 745f266a1a41c9..1aa7984e6e6317 100644 --- a/AntennaTracker/config.h +++ b/AntennaTracker/config.h @@ -57,9 +57,6 @@ // // Logging control // -#ifndef LOGGING_ENABLED -# define LOGGING_ENABLED ENABLED -#endif // Default logging bitmask #ifndef DEFAULT_LOG_BITMASK diff --git a/AntennaTracker/system.cpp b/AntennaTracker/system.cpp index 3e296c3fa5a77f..db008dc75f05f9 100644 --- a/AntennaTracker/system.cpp +++ b/AntennaTracker/system.cpp @@ -32,7 +32,7 @@ void Tracker::init_ardupilot() // try to initialise stream rates in the main loop. gcs().update_send(); -#if LOGGING_ENABLED == ENABLED +#if HAL_LOGGING_ENABLED log_init(); #endif @@ -56,8 +56,10 @@ void Tracker::init_ardupilot() barometer.calibrate(); +#if HAL_LOGGING_ENABLED // initialise AP_Logger library logger.setVehicle_Startup_Writer(FUNCTOR_BIND(&tracker, &Tracker::Log_Write_Vehicle_Startup_Messages, void)); +#endif // initialise rc channels including setting mode rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, RC_Channel::AUX_FUNC::ARMDISARM); @@ -152,13 +154,17 @@ bool Tracker::set_home(const Location &temp) void Tracker::arm_servos() { hal.util->set_soft_armed(true); +#if HAL_LOGGING_ENABLED logger.set_vehicle_armed(true); +#endif } void Tracker::disarm_servos() { hal.util->set_soft_armed(false); +#if HAL_LOGGING_ENABLED logger.set_vehicle_armed(false); +#endif } /* @@ -189,8 +195,10 @@ void Tracker::set_mode(Mode &newmode, const ModeReason reason) disarm_servos(); } +#if HAL_LOGGING_ENABLED // log mode change logger.Write_Mode((uint8_t)mode->number(), reason); +#endif gcs().send_message(MSG_HEARTBEAT); nav_status.bearing = ahrs.yaw_sensor * 0.01f; @@ -228,6 +236,7 @@ bool Tracker::set_mode(const uint8_t new_mode, const ModeReason reason) return true; } +#if HAL_LOGGING_ENABLED /* should we log a message type now? */ @@ -238,7 +247,7 @@ bool Tracker::should_log(uint32_t mask) } return true; } - +#endif #include #include diff --git a/AntennaTracker/tracking.cpp b/AntennaTracker/tracking.cpp index cd0bf531336ede..facd7141b53ebc 100644 --- a/AntennaTracker/tracking.cpp +++ b/AntennaTracker/tracking.cpp @@ -138,10 +138,12 @@ void Tracker::tracking_update_position(const mavlink_global_position_int_t &msg) vehicle.vel = Vector3f(msg.vx/100.0f, msg.vy/100.0f, msg.vz/100.0f); vehicle.last_update_us = AP_HAL::micros(); vehicle.last_update_ms = AP_HAL::millis(); +#if HAL_LOGGING_ENABLED // log vehicle as GPS2 if (should_log(MASK_LOG_GPS)) { Log_Write_Vehicle_Pos(vehicle.location.lat, vehicle.location.lng, vehicle.location.alt, vehicle.vel); } +#endif } @@ -167,8 +169,10 @@ void Tracker::tracking_update_pressure(const mavlink_scaled_pressure_t &msg) } } +#if HAL_LOGGING_ENABLED // log vehicle baro data Log_Write_Vehicle_Baro(aircraft_pressure, alt_diff); +#endif } /** From 5ae4355e26b9280249267291463b93d66fbea6cd Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 11 Jan 2024 17:17:05 +1100 Subject: [PATCH 0642/1335] SITL: correct compilation when HAL_LOGGING_ENABLED is false --- libraries/SITL/SIM_Aircraft.cpp | 2 ++ libraries/SITL/SIM_Blimp.cpp | 2 ++ libraries/SITL/SIM_JSON_Master.cpp | 2 ++ libraries/SITL/SIM_Morse.cpp | 1 - libraries/SITL/SIM_Webots.cpp | 1 - libraries/SITL/SITL.cpp | 2 ++ 6 files changed, 8 insertions(+), 2 deletions(-) diff --git a/libraries/SITL/SIM_Aircraft.cpp b/libraries/SITL/SIM_Aircraft.cpp index 58b22308a0e80c..12a96753d0924a 100644 --- a/libraries/SITL/SIM_Aircraft.cpp +++ b/libraries/SITL/SIM_Aircraft.cpp @@ -456,6 +456,7 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm) last_speedup = sitl->speedup; } +#if HAL_LOGGING_ENABLED // for EKF comparison log relhome pos and velocity at loop rate static uint16_t last_ticks; uint16_t ticks = AP::scheduler().ticks(); @@ -482,6 +483,7 @@ void Aircraft::fill_fdm(struct sitl_fdm &fdm) airspeed_pitot, achieved_rate_hz/rate_hz); } +#endif } // returns perpendicular height to surface downward-facing rangefinder diff --git a/libraries/SITL/SIM_Blimp.cpp b/libraries/SITL/SIM_Blimp.cpp index c5f8835b851b50..844fed4f8d6736 100644 --- a/libraries/SITL/SIM_Blimp.cpp +++ b/libraries/SITL/SIM_Blimp.cpp @@ -106,6 +106,7 @@ void Blimp::calculate_forces(const struct sitl_input &input, Vector3f &body_acc, Vector3f rot_T{0,0,0}; +#if HAL_LOGGING_ENABLED AP::logger().WriteStreaming("SFT", "TimeUS,f0,f1,f2,f3", "Qffff", AP_HAL::micros64(), @@ -138,6 +139,7 @@ void Blimp::calculate_forces(const struct sitl_input &input, Vector3f &body_acc, "Qfff", AP_HAL::micros64(), rot_T.x, rot_T.y, rot_T.z); +#endif // HAL_LOGGING_ENABLED #if 0 //"Wobble" attempt rot_T.y = fin[0].Fz * radius + fin[1].Fz * radius; diff --git a/libraries/SITL/SIM_JSON_Master.cpp b/libraries/SITL/SIM_JSON_Master.cpp index 885e469564c168..0130a7067dc068 100644 --- a/libraries/SITL/SIM_JSON_Master.cpp +++ b/libraries/SITL/SIM_JSON_Master.cpp @@ -99,6 +99,7 @@ void JSON_Master::receive(struct sitl_input &input) } } +#if HAL_LOGGING_ENABLED const bool use_servos = list->instance == master_instance; // @LoggerMessage: SLV1 @@ -158,6 +159,7 @@ void JSON_Master::receive(struct sitl_input &input) buffer.pwm[11], buffer.pwm[12], buffer.pwm[13]); +#endif if (list->instance == master_instance) { // Use the servo outs from this instance diff --git a/libraries/SITL/SIM_Morse.cpp b/libraries/SITL/SIM_Morse.cpp index c4c62498697301..a23669b0f5fb76 100644 --- a/libraries/SITL/SIM_Morse.cpp +++ b/libraries/SITL/SIM_Morse.cpp @@ -29,7 +29,6 @@ #include #include -#include #include "pthread.h" #include diff --git a/libraries/SITL/SIM_Webots.cpp b/libraries/SITL/SIM_Webots.cpp index 134fdc62369791..80a8583c410922 100644 --- a/libraries/SITL/SIM_Webots.cpp +++ b/libraries/SITL/SIM_Webots.cpp @@ -29,7 +29,6 @@ #include #include -#include #include "pthread.h" #include diff --git a/libraries/SITL/SITL.cpp b/libraries/SITL/SITL.cpp index 2ff2220aa7ed7f..2aeed73ab6ed28 100644 --- a/libraries/SITL/SITL.cpp +++ b/libraries/SITL/SITL.cpp @@ -1169,6 +1169,7 @@ void SIM::sim_state_send(mavlink_channel_t chan) const (int32_t)(state.longitude*1.0e7)); } +#if HAL_LOGGING_ENABLED /* report SITL state to AP_Logger */ void SIM::Log_Write_SIMSTATE() { @@ -1196,6 +1197,7 @@ void SIM::Log_Write_SIMSTATE() }; AP::logger().WriteBlock(&pkt, sizeof(pkt)); } +#endif /* convert a set of roll rates from earth frame to body frame From 486cbb78909ed03e65d090e0b092bb5892d62554 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 14 Jul 2023 10:58:06 +1000 Subject: [PATCH 0643/1335] AP_Logger: allow compilation with HAL_LOGGING_ENABLED false --- libraries/AP_Logger/AP_Logger.h | 12 ++++++++++++ libraries/AP_Logger/AP_Logger_MAVLinkLogTransfer.cpp | 8 +++++--- 2 files changed, 17 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Logger/AP_Logger.h b/libraries/AP_Logger/AP_Logger.h index cf6d232f85c582..cab112ea654c38 100644 --- a/libraries/AP_Logger/AP_Logger.h +++ b/libraries/AP_Logger/AP_Logger.h @@ -5,6 +5,8 @@ #include "AP_Logger_config.h" +#if HAL_LOGGING_ENABLED + #include #include #include @@ -609,3 +611,13 @@ class AP_Logger namespace AP { AP_Logger &logger(); }; + +#define LOGGER_WRITE_ERROR(subsys, err) AP::logger().Write_Error(subsys, err) +#define LOGGER_WRITE_EVENT(evt) AP::logger().Write_Event(evt) + +#else + +#define LOGGER_WRITE_ERROR(subsys, err) +#define LOGGER_WRITE_EVENT(evt) + +#endif // HAL_LOGGING_ENABLED diff --git a/libraries/AP_Logger/AP_Logger_MAVLinkLogTransfer.cpp b/libraries/AP_Logger/AP_Logger_MAVLinkLogTransfer.cpp index 3403d5f059363b..08486b60e9b19e 100644 --- a/libraries/AP_Logger/AP_Logger_MAVLinkLogTransfer.cpp +++ b/libraries/AP_Logger/AP_Logger_MAVLinkLogTransfer.cpp @@ -17,13 +17,15 @@ along with this program. If not, see . */ +#include +#include + +#if HAL_LOGGING_ENABLED && HAL_GCS_ENABLED #include #include #include // for LOG_ENTRY -#if HAL_GCS_ENABLED - extern const AP_HAL::HAL& hal; /** @@ -327,4 +329,4 @@ bool AP_Logger::handle_log_send_data() return true; } -#endif +#endif // HAL_LOGGING_ENABLED && HAL_GCS_ENABLED From c4a342f0af95556620ec77ccf94b7b58452dec68 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 15 Jan 2024 11:34:04 +1100 Subject: [PATCH 0644/1335] AP_HAL_ChibiOS: use @ROMFS/defaults.parm rather than apj_tool for defaul parms --- libraries/AP_HAL_ChibiOS/Util.h | 5 ++ .../hwdef/scripts/chibios_hwdef.py | 48 ++++++++++++++++--- 2 files changed, 47 insertions(+), 6 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/Util.h b/libraries/AP_HAL_ChibiOS/Util.h index f0aecae053c953..5af64e1c7791bc 100644 --- a/libraries/AP_HAL_ChibiOS/Util.h +++ b/libraries/AP_HAL_ChibiOS/Util.h @@ -39,6 +39,11 @@ class ChibiOS::Util : public AP_HAL::Util { bool run_debug_shell(AP_HAL::BetterStream *stream) override { return false; } uint32_t available_memory() override; + // get path to custom defaults file for AP_Param + const char* get_custom_defaults_file() const override { + return "@ROMFS/defaults.parm"; + } + // Special Allocation Routines void *malloc_type(size_t size, AP_HAL::Util::Memory_Type mem_type) override; void free_type(void *ptr, size_t size, AP_HAL::Util::Memory_Type mem_type) override; diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index 7f248d2d358efe..f093f63c3bbb6c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -33,6 +33,10 @@ def __init__(self, quiet=False, bootloader=False, signed_fw=False, outdir=None, self.default_params_filepath = default_params_filepath self.quiet = quiet + # if true then parameters will be appended in special apj-tool + # section at end of binary: + self.force_apj_default_parameters = False + self.default_gpio = ['INPUT', 'FLOATING'] self.vtypes = [] @@ -2520,6 +2524,9 @@ def write_all_lines(self, hwdat): if not self.is_periph_fw(): self.romfs["hwdef.dat"] = hwdat + def write_define(self, f, name, value): + f.write(f"#define {name} {value}\n") + def write_hwdef_header(self, outfilename): '''write hwdef header file''' self.progress("Writing hwdef setup in %s" % outfilename) @@ -2582,6 +2589,11 @@ def write_hwdef_header(self, outfilename): self.write_peripheral_enable(f) + if os.path.exists(self.processed_defaults_filepath()): + self.write_define(f, 'AP_PARAM_DEFAULTS_FILE_PARSING_ENABLED', 1) + else: + self.write_define(f, 'AP_PARAM_DEFAULTS_FILE_PARSING_ENABLED', 0) + if self.mcu_series.startswith("STM32H7"): # add in ADC3 on H7 to get MCU temperature and reference voltage self.periph_list.append('ADC3') @@ -2827,14 +2839,14 @@ def write_processed_defaults_file(self, filepath): if defaults_abspath is None: self.progress("No default parameter file found") - return + return False content = self.get_processed_defaults_file(defaults_abspath) with open(filepath, "w") as processed_defaults_fh: processed_defaults_fh.write(content) - self.env_vars['DEFAULT_PARAMETERS'] = filepath + return True def write_env_py(self, filename): '''write out env.py for environment variables to control the build process''' @@ -3046,7 +3058,6 @@ def process_line(self, line): if result: self.intdefines[result.group(1)] = int(result.group(2)) - def progress(self, message): if self.quiet: return @@ -3141,6 +3152,31 @@ def add_normal_firmware_defaults(self, f): self.add_firmware_defaults_from_file(f, "defaults_normal.h", "normal") + def processed_defaults_filepath(self): + return os.path.join(self.outdir, "processed_defaults.parm") + + def write_default_parameters(self): + '''handle default parameters''' + + if self.is_bootloader_fw(): + return + + if self.is_io_fw(): + return + + filepath = self.processed_defaults_filepath() + if not self.write_processed_defaults_file(filepath): + return + + if self.get_config('FORCE_APJ_DEFAULT_PARAMETERS', default=False): + # set env variable so that post-processing in waf uses + # apj-tool to append parameters to image: + if os.path.exists(filepath): + self.env_vars['DEFAULT_PARAMETERS'] = filepath + return + + self.romfs_add('defaults.parm', filepath) + def run(self): # process input file @@ -3156,6 +3192,9 @@ def run(self): # build a list for peripherals for DMA resolver self.periph_list = self.build_peripheral_list() + # write out a default parameters file, decide how to use it: + self.write_default_parameters() + # write out hw.dat for ROMFS self.write_all_lines(os.path.join(self.outdir, "hw.dat")) @@ -3174,9 +3213,6 @@ def run(self): # exist in the same directory as the ldscript.ld file we generate. self.copy_common_linkerscript(self.outdir) - if not self.is_bootloader_fw(): - self.write_processed_defaults_file(os.path.join(self.outdir, "processed_defaults.parm")) - self.write_env_py(os.path.join(self.outdir, "env.py")) From 58408cd0b5a2d6e10fe1ec3f7fa7e6f05402f43d Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 15 Jan 2024 11:34:05 +1100 Subject: [PATCH 0645/1335] AP_Logger: use @ROMFS/defaults.parm rather than apj_tool for defaul parms --- libraries/AP_Logger/AP_Logger.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_Logger/AP_Logger.cpp b/libraries/AP_Logger/AP_Logger.cpp index 6373b9d2d64c6d..aa19981e0f2962 100644 --- a/libraries/AP_Logger/AP_Logger.cpp +++ b/libraries/AP_Logger/AP_Logger.cpp @@ -1573,6 +1573,7 @@ void AP_Logger::prepare_at_arming_sys_file_logging() "@ROMFS/hwdef.dat", "@SYS/storage.bin", "@SYS/crash_dump.bin", + "@ROMFS/defaults.parm", }; for (const auto *name : log_content_filenames) { log_file_content(at_arm_file_content, name); From 27fa5f8d2c823e6506103320dd3aa4a223067eff Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 15 Jan 2024 11:34:05 +1100 Subject: [PATCH 0646/1335] AP_Param: use @ROMFS/defaults.parm rather than apj_tool for defaul parms --- libraries/AP_Param/AP_Param.cpp | 29 +++++++++++++++++----------- libraries/AP_Param/AP_Param.h | 16 ++++++++++----- libraries/AP_Param/AP_Param_config.h | 13 +++++++++++++ 3 files changed, 42 insertions(+), 16 deletions(-) create mode 100644 libraries/AP_Param/AP_Param_config.h diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index 56d9cbf8ecbf63..f1c6d949f60441 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -39,6 +39,8 @@ #include #endif +#include "AP_Param_config.h" + extern const AP_HAL::HAL &hal; uint16_t AP_Param::sentinal_offset; @@ -1543,14 +1545,7 @@ bool AP_Param::load_all() */ void AP_Param::reload_defaults_file(bool last_pass) { -#if AP_PARAM_MAX_EMBEDDED_PARAM > 0 - if (param_defaults_data.length != 0) { - load_embedded_param_defaults(last_pass); - return; - } -#endif - -#if AP_FILESYSTEM_POSIX_ENABLED +#if AP_PARAM_DEFAULTS_FILE_PARSING_ENABLED /* if the HAL specifies a defaults parameter file then override defaults using that file @@ -1558,12 +1553,25 @@ void AP_Param::reload_defaults_file(bool last_pass) const char *default_file = hal.util->get_custom_defaults_file(); if (default_file) { if (load_defaults_file(default_file, last_pass)) { +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL printf("Loaded defaults from %s\n", default_file); +#endif } else { +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL AP_HAL::panic("Failed to load defaults from %s\n", default_file); +#else + printf("Failed to load defaults from %s\n", default_file); +#endif } } +#endif // AP_PARAM_DEFAULTS_FILE_PARSING_ENABLED + +#if AP_PARAM_MAX_EMBEDDED_PARAM > 0 + if (param_defaults_data.length != 0) { + load_embedded_param_defaults(last_pass); + } #endif + #if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !defined(HAL_BUILD_AP_PERIPH) hal.util->set_cmdline_parameters(); #endif @@ -2136,8 +2144,7 @@ bool AP_Param::parse_param_line(char *line, char **vname, float &value, bool &re } -// FIXME: make this AP_FILESYSTEM_FILE_READING_ENABLED -#if AP_FILESYSTEM_FATFS_ENABLED || AP_FILESYSTEM_POSIX_ENABLED +#if AP_PARAM_DEFAULTS_FILE_PARSING_ENABLED // increments num_defaults for each default found in filename bool AP_Param::count_defaults_in_file(const char *filename, uint16_t &num_defaults) @@ -2283,8 +2290,8 @@ bool AP_Param::load_defaults_file(const char *filename, bool last_pass) return true; } +#endif // AP_PARAM_DEFAULTS_FILE_PARSING_ENABLED -#endif // AP_FILESYSTEM_FATFS_ENABLED || AP_FILESYSTEM_POSIX_ENABLED #if AP_PARAM_MAX_EMBEDDED_PARAM > 0 /* diff --git a/libraries/AP_Param/AP_Param.h b/libraries/AP_Param/AP_Param.h index db8fbde15f4607..85b211f7ade376 100644 --- a/libraries/AP_Param/AP_Param.h +++ b/libraries/AP_Param/AP_Param.h @@ -29,6 +29,8 @@ #include #include +#include "AP_Param_config.h" + #include "float.h" #define AP_MAX_NAME_SIZE 16 @@ -46,11 +48,15 @@ maximum size of embedded parameter file */ #ifndef AP_PARAM_MAX_EMBEDDED_PARAM -#if BOARD_FLASH_SIZE <= 1024 -# define AP_PARAM_MAX_EMBEDDED_PARAM 1024 -#else -# define AP_PARAM_MAX_EMBEDDED_PARAM 8192 -#endif + #if FORCE_APJ_DEFAULT_PARAMETERS + #if BOARD_FLASH_SIZE <= 1024 + #define AP_PARAM_MAX_EMBEDDED_PARAM 1024 + #else + #define AP_PARAM_MAX_EMBEDDED_PARAM 8192 + #endif + #else + #define AP_PARAM_MAX_EMBEDDED_PARAM 0 + #endif #endif // allow for dynamically added tables when scripting enabled diff --git a/libraries/AP_Param/AP_Param_config.h b/libraries/AP_Param/AP_Param_config.h new file mode 100644 index 00000000000000..181c9f04c39b70 --- /dev/null +++ b/libraries/AP_Param/AP_Param_config.h @@ -0,0 +1,13 @@ +#pragma once + +#include + +#include + +#ifndef AP_PARAM_DEFAULTS_FILE_PARSING_ENABLED +#define AP_PARAM_DEFAULTS_FILE_PARSING_ENABLED AP_FILESYSTEM_FILE_READING_ENABLED +#endif + +#ifndef FORCE_APJ_DEFAULT_PARAMETERS +#define FORCE_APJ_DEFAULT_PARAMETERS 0 +#endif From 3aab3bac524ef80f509312c6fa32964b256ed506 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 15 Jan 2024 14:49:35 +1100 Subject: [PATCH 0647/1335] Tools/AP_HAL_ChibiOS: move defaults from tools to hwdef directory Tools: move defaults from tools to hwdef directory --- .../AP_HAL_ChibiOS/hwdef/CubeGreen-solo/defaults.parm | 0 libraries/AP_HAL_ChibiOS/hwdef/CubeGreen-solo/hwdef.dat | 4 ---- .../AP_HAL_ChibiOS/hwdef/CubeOrange-bdshot/defaults.parm | 1 + libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-bdshot/hwdef.dat | 2 -- .../AP_HAL_ChibiOS/hwdef/CubeOrangePlus-bdshot/defaults.parm | 1 + .../AP_HAL_ChibiOS/hwdef/CubeOrangePlus-bdshot/hwdef.dat | 2 -- .../AP_HAL_ChibiOS/hwdef/CubeSolo/defaults.parm | 0 libraries/AP_HAL_ChibiOS/hwdef/CubeSolo/hwdef.dat | 4 ---- libraries/AP_HAL_ChibiOS/hwdef/luminousbee4/hwdef.dat | 2 -- .../AP_HAL_ChibiOS/hwdef/skyviper-v2450}/defaults.parm | 0 libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat | 2 -- 11 files changed, 2 insertions(+), 16 deletions(-) rename Tools/Frame_params/Solo_Copter-4_GreenCube.param => libraries/AP_HAL_ChibiOS/hwdef/CubeGreen-solo/defaults.parm (100%) create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-bdshot/defaults.parm create mode 100644 libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus-bdshot/defaults.parm rename Tools/Frame_params/Solo_Copter-4.param => libraries/AP_HAL_ChibiOS/hwdef/CubeSolo/defaults.parm (100%) rename {Tools/Frame_params/SkyViper-2450GPS => libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450}/defaults.parm (100%) diff --git a/Tools/Frame_params/Solo_Copter-4_GreenCube.param b/libraries/AP_HAL_ChibiOS/hwdef/CubeGreen-solo/defaults.parm similarity index 100% rename from Tools/Frame_params/Solo_Copter-4_GreenCube.param rename to libraries/AP_HAL_ChibiOS/hwdef/CubeGreen-solo/defaults.parm diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeGreen-solo/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeGreen-solo/hwdef.dat index 0266753fe17401..c02f667fd2ad56 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeGreen-solo/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeGreen-solo/hwdef.dat @@ -6,10 +6,6 @@ include ../CubeBlack/hwdef.dat -# pull Solo's default parameters from /Tools/Frame_params -# these are parameters the Solo requires for proper operation that are different from the 4 standard defaults. -env DEFAULT_PARAMETERS 'Tools/Frame_params/Solo_Copter-4_GreenCube.param' - undef AP_NOTIFY_OREOLED_ENABLED define AP_NOTIFY_OREOLED_ENABLED 1 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-bdshot/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-bdshot/defaults.parm new file mode 100644 index 00000000000000..e189e7c80162da --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-bdshot/defaults.parm @@ -0,0 +1 @@ +@include ../CubeOrange/defaults.parm diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-bdshot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-bdshot/hwdef.dat index 4f3c0cd9ba3c36..6666bb218600ea 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-bdshot/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrange-bdshot/hwdef.dat @@ -10,5 +10,3 @@ PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52) BIDIR PE9 TIM1_CH1 TIM1 PWM(4) GPIO(53) # this will automatically be shared with TIM1_CH1 PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54) BIDIR PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55) BIDIR - -env DEFAULT_PARAMETERS libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/defaults.parm diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus-bdshot/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus-bdshot/defaults.parm new file mode 100644 index 00000000000000..591b7847763ef2 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus-bdshot/defaults.parm @@ -0,0 +1 @@ +@include ../CubeOrangePlus/defaults.parm diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus-bdshot/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus-bdshot/hwdef.dat index 4962342835feeb..d2f45607b7eea2 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus-bdshot/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus-bdshot/hwdef.dat @@ -10,5 +10,3 @@ PE11 TIM1_CH2 TIM1 PWM(3) GPIO(52) BIDIR PE9 TIM1_CH1 TIM1 PWM(4) GPIO(53) # this will automatically be shared with TIM1_CH1 PD13 TIM4_CH2 TIM4 PWM(5) GPIO(54) BIDIR PD14 TIM4_CH3 TIM4 PWM(6) GPIO(55) BIDIR - -env DEFAULT_PARAMETERS libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus/defaults.parm diff --git a/Tools/Frame_params/Solo_Copter-4.param b/libraries/AP_HAL_ChibiOS/hwdef/CubeSolo/defaults.parm similarity index 100% rename from Tools/Frame_params/Solo_Copter-4.param rename to libraries/AP_HAL_ChibiOS/hwdef/CubeSolo/defaults.parm diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubeSolo/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubeSolo/hwdef.dat index 8f15b713acb7da..899a75f1e9858e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubeSolo/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubeSolo/hwdef.dat @@ -12,10 +12,6 @@ env OPTIMIZE -O2 SPIDEV icm20948_ext SPI4 DEVID1 MPU_EXT_CS MODE3 4*MHZ 8*MHZ SPIDEV icm20602_ext SPI4 DEVID3 GYRO_EXT_CS MODE3 4*MHZ 8*MHZ -# pull Solo's default parameters from /Tools/Frame_params -# these are parameters the Solo requires for proper operation that are different from the copter defaults. -env DEFAULT_PARAMETERS 'Tools/Frame_params/Solo_Copter-4.param' - # three IMUs, but allow for different variants. First two IMUs are # isolated, 3rd isn't IMU Invensense SPI:mpu9250_ext ROTATION_PITCH_180 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/luminousbee4/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/luminousbee4/hwdef.dat index b79ad277a9f5fc..e3d937b832b72b 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/luminousbee4/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/luminousbee4/hwdef.dat @@ -188,7 +188,5 @@ BARO MS56XX SPI:ms5611_int # reserve plenty of memory for DMA for LED buffers define DMA_RESERVE_SIZE 32768 -# .env DEFAULT_PARAMETERS 'Tools/Frame_params/LuminousBee4_outdoor.param' - # bootloader embedding / bootloader flashing not available define AP_BOOTLOADER_FLASHING_ENABLED 0 diff --git a/Tools/Frame_params/SkyViper-2450GPS/defaults.parm b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/defaults.parm similarity index 100% rename from Tools/Frame_params/SkyViper-2450GPS/defaults.parm rename to libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/defaults.parm diff --git a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat index 831c079648e98b..7ca9230dffddbd 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat @@ -61,8 +61,6 @@ PA1 UART4_RX UART4 NODMA # use flash storage STORAGE_FLASH_PAGE 22 -env DEFAULT_PARAMETERS 'Tools/Frame_params/SkyViper-2450GPS/defaults.parm' - # the web UI uses an abin file for firmware uploads env BUILD_ABIN True From 0b7f6c90e56a27254281ffe2a206dfea997ec13a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 17 Jan 2024 12:33:16 +1100 Subject: [PATCH 0648/1335] autotest: stop testing embedded param parser we're moving to ROMFS defaults files --- Tools/autotest/arduplane.py | 1 - 1 file changed, 1 deletion(-) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index be66a0447821f3..629d71de4c3f24 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -5392,7 +5392,6 @@ def tests(self): self.GlideSlopeThresh, self.HIGH_LATENCY2, self.MidAirDisarmDisallowed, - self.EmbeddedParamParser, self.AerobaticsScripting, self.MANUAL_CONTROL, self.RunMissionScript, From 3f9062d676c449555a02d29471f3c5fef3afb4c0 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 17 Jan 2024 12:48:19 +1100 Subject: [PATCH 0649/1335] Tools: extend error message when not finding defaults --- Tools/scripts/apj_tool.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/scripts/apj_tool.py b/Tools/scripts/apj_tool.py index 55f6a9496f059c..e52e178fc439dd 100755 --- a/Tools/scripts/apj_tool.py +++ b/Tools/scripts/apj_tool.py @@ -232,7 +232,7 @@ def defaults_contents(firmware, ofs, length): have_defaults = defaults.find() if not have_defaults and not args.extract: - print("Error: Param defaults support not found in firmware") + print("Error: Param defaults support not found in firmware; see https://ardupilot.org/copter/docs/common-oem-customizations.html for embedding defaults.parm") sys.exit(1) if have_defaults: From 7c52d8b468845213b5b3d7dc22ec045b436a03a7 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 17 Jan 2024 13:11:52 +1100 Subject: [PATCH 0650/1335] build_options.py: add option to force APJ_TOOL parameter area --- Tools/scripts/build_options.py | 1 + Tools/scripts/extract_features.py | 1 + 2 files changed, 2 insertions(+) diff --git a/Tools/scripts/build_options.py b/Tools/scripts/build_options.py index 5fcd74bb75b0c3..eab4918c876299 100644 --- a/Tools/scripts/build_options.py +++ b/Tools/scripts/build_options.py @@ -375,6 +375,7 @@ def __init__(self, # Feature('Filesystem', 'FILESYSTEM_POSIX', 'AP_FILESYSTEM_POSIX_ENABLED', 'Enable POSIX filesystem', 0, None), Feature('Filesystem', 'FILESYSTEM_ROMFS', 'AP_FILESYSTEM_ROMFS_ENABLED', 'Enable @ROMFS/ filesystem', 0, None), Feature('Filesystem', 'FILESYSTEM_SYS', 'AP_FILESYSTEM_SYS_ENABLED', 'Enable @SYS/ filesystem', 0, None), + Feature('Filesystem', 'APJ_TOOL_PARAMETERS', 'FORCE_APJ_DEFAULT_PARAMETERS', 'Enable apj_tool parameter area', 0, None), Feature('Networking', 'PPP Support', 'AP_NETWORKING_BACKEND_PPP', 'Enable PPP networking', 0, None), ] diff --git a/Tools/scripts/extract_features.py b/Tools/scripts/extract_features.py index 7977fabfa36440..31b63b2ddad875 100755 --- a/Tools/scripts/extract_features.py +++ b/Tools/scripts/extract_features.py @@ -239,6 +239,7 @@ def __init__(self, filename, nm="arm-none-eabi-nm", strings="strings"): ('AP_DRONECAN_SERIAL_ENABLED', 'AP_DroneCAN_Serial::update'), ('AP_SERIALMANAGER_IMUOUT_ENABLED', 'AP_InertialSensor::send_uart_data'), ('AP_NETWORKING_BACKEND_PPP', 'AP_Networking_PPP::init'), + ('FORCE_APJ_DEFAULT_PARAMETERS', 'AP_Param::param_defaults_data'), ] def progress(self, msg): From efd5fec24da45f1334763719e3044bcc657fccc8 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 17 Jan 2024 12:29:44 +1100 Subject: [PATCH 0651/1335] AP_HAL_SITL: allow sim_vehicle.py -I to work again ... or at least not die instantly because instance-0 has bound this port --- libraries/AP_HAL_SITL/SITL_State.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_HAL_SITL/SITL_State.cpp b/libraries/AP_HAL_SITL/SITL_State.cpp index 02810a9ac3b433..5bc6b410dd4d29 100644 --- a/libraries/AP_HAL_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_State.cpp @@ -663,7 +663,7 @@ void SITL_State::multicast_state_open(void) } sockaddr.sin_addr.s_addr = htonl(INADDR_ANY); - sockaddr.sin_port = htons(SITL_SERVO_PORT); + sockaddr.sin_port = htons(SITL_SERVO_PORT + _instance); ret = bind(servo_in_fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr)); if (ret == -1) { From 407b8a6003e7028034f67fc300fa6b1b386fcd3b Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 14 Jan 2024 13:38:02 +0000 Subject: [PATCH 0652/1335] AP_RCProtocol: add is_detected() so that telemetry implementations can defer actions --- libraries/AP_RCProtocol/AP_RCProtocol_Backend.h | 4 ++++ libraries/AP_RCProtocol/AP_RCProtocol_CRSF.cpp | 2 +- 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_Backend.h b/libraries/AP_RCProtocol/AP_RCProtocol_Backend.h index cbb0b1135be712..e0a128dc30a3cd 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_Backend.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol_Backend.h @@ -95,6 +95,10 @@ class AP_RCProtocol_Backend { return true; } + bool is_detected() const { + return frontend._detected_protocol != AP_RCProtocol::NONE && frontend.backend[frontend._detected_protocol] == this; + } + #if AP_VIDEOTX_ENABLED // called by static methods to confiig video transmitters: static void configure_vtx(uint8_t band, uint8_t channel, uint8_t power, uint8_t pitmode); diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.cpp index df47ab768d619e..b9d68b63900b5a 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_CRSF.cpp @@ -302,7 +302,7 @@ void AP_RCProtocol_CRSF::update(void) // never received RC frames, but have received CRSF frames so make sure we give the telemetry opportunity to run uint32_t now = AP_HAL::micros(); - if (_last_frame_time_us > 0 && (!get_rc_frame_count() || !is_tx_active()) + if (_last_frame_time_us > 0 && (!get_rc_input_count() || !is_tx_active()) && now - _last_frame_time_us > CRSF_INTER_FRAME_TIME_US_250HZ) { process_telemetry(false); _last_frame_time_us = now; From 567c7a2b1bfbcd7a884827f2b0046c08d42ebe9a Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Sun, 14 Jan 2024 13:38:22 +0000 Subject: [PATCH 0653/1335] AP_RCTelemetry: check that CRSF and GHST have been detected before sending a version ping or doing rf changes --- libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp | 9 +++++++-- libraries/AP_RCTelemetry/AP_GHST_Telem.cpp | 5 +++++ 2 files changed, 12 insertions(+), 2 deletions(-) diff --git a/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp b/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp index 30e16b6d0a8f46..145f4b867cdce8 100644 --- a/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp +++ b/libraries/AP_RCTelemetry/AP_CRSF_Telem.cpp @@ -185,9 +185,14 @@ bool AP_CRSF_Telem::process_rf_mode_changes() if (crsf != nullptr) { uart = crsf->get_UART(); } + if (uart == nullptr) { return true; } + + if (!crsf->is_detected()) { + return false; + } // not ready yet if (!uart->is_initialized()) { return false; @@ -402,11 +407,11 @@ bool AP_CRSF_Telem::is_packet_ready(uint8_t idx, bool queue_empty) case GENERAL_COMMAND: return _baud_rate_request.pending; case VERSION_PING: - return _crsf_version.pending; + return _crsf_version.pending && AP::crsf()->is_detected(); // only send pings if protocol has been detected case HEARTBEAT: return true; // always send heartbeat if enabled case DEVICE_PING: - return !_crsf_version.pending; // only send pings if version has been negotiated + return !_crsf_version.pending; // only send pings if version has been negotiated default: return _enable_telemetry; } diff --git a/libraries/AP_RCTelemetry/AP_GHST_Telem.cpp b/libraries/AP_RCTelemetry/AP_GHST_Telem.cpp index 72e2d2a09e7e00..cdbcea0a543332 100644 --- a/libraries/AP_RCTelemetry/AP_GHST_Telem.cpp +++ b/libraries/AP_RCTelemetry/AP_GHST_Telem.cpp @@ -111,9 +111,14 @@ bool AP_GHST_Telem::process_rf_mode_changes() if (ghost != nullptr) { uart = ghost->get_UART(); } + if (uart == nullptr) { return true; } + + if (!ghost->is_detected()) { + return false; + } // not ready yet if (!uart->is_initialized()) { return false; From 0154277989c8bfe42e3a0d1fe383855bce655d98 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 16 Jan 2024 15:11:45 +1100 Subject: [PATCH 0654/1335] RC_Channel: param_parse.py: sort RCn_OPTIONS progamatically --- libraries/RC_Channel/RC_Channel.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index cebb53ae2f9e54..296afb878ba854 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -107,6 +107,7 @@ const AP_Param::GroupInfo RC_Channel::var_info[] = { // @Param: OPTION // @DisplayName: RC input option // @Description: Function assigned to this RC channel + // @SortValues: AlphabeticalZeroAtTop // @Values{Copter, Rover, Plane, Blimp}: 0:Do Nothing // @Values{Copter}: 2:FLIP Mode // @Values{Copter}: 3:Simple Mode From e7cd43ad8666b8b365c2f92dec5d2df1f2835c92 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 16 Jan 2024 15:11:45 +1100 Subject: [PATCH 0655/1335] Tools: param_parse.py: sort RCn_OPTIONS progamatically --- Tools/autotest/param_metadata/htmlemit.py | 2 +- Tools/autotest/param_metadata/jsonemit.py | 9 ++++-- Tools/autotest/param_metadata/mdemit.py | 2 +- Tools/autotest/param_metadata/param.py | 1 + Tools/autotest/param_metadata/rstemit.py | 2 +- Tools/autotest/param_metadata/xmlemit.py | 38 +++++++++++++++++++++-- 6 files changed, 45 insertions(+), 9 deletions(-) diff --git a/Tools/autotest/param_metadata/htmlemit.py b/Tools/autotest/param_metadata/htmlemit.py index 1d9e76534168a7..201a13ef9a85b6 100644 --- a/Tools/autotest/param_metadata/htmlemit.py +++ b/Tools/autotest/param_metadata/htmlemit.py @@ -65,7 +65,7 @@ def emit(self, g): t += "

N3$Lp+vPYU$H9 zr!bbw&oeu1fk3#TS21QYY-XcObkLF+{M&;FJx^zw8yW@$d+&1oAOv%Kd5+lSqZ5rE zaF-w4Dfbe_W|hW4y3Ak;o$He*eG7_DO`07+L=}1+J1#>Hd505*s0~mxdW#qal zL>>vxW1X?9b+hWVlCWb>tXEnK(p8rYL}7TJGiykzWO0Wty9$ZyuuSE}G@-!97o|sHW*E zMKS0YwzcHk%W|@*`X6Ug@y?B&(~kg!__>YO<`$V%-7Rw z=3-Npj>6E!`P!Tz^fC2@OV~gCu}FdWb43TvGZ_mp-mg!8>NS>)-a{6ZQ9+!QjnydG)mU>E2q!NiSAlP00qLqf`c%gDWgR)&b*ULiB#jh? zMf2`Ys6hG`$PAvcQJA2Tz02oc60nq-#L{Cc|sgGz(!@6IGM_W7cA#+oWD0%>5ivj~Y!b6jvU?)FC zsVQ9J55mCX3t4yEvxKh?Ea5It4DOq|YxDgM|3z?d#XC5#AxZdX4kuEiU$ZYA!@7PCS}V5~^zW-0EMP zXg~jh!~-xT;H5KjrstCi%CFzP__Kz9{OZlCSK{z}?B|bwf|(`ly&9PbH#yM2;zQswBM;@V5ZqZ;4m$FnY#~19%Jq``|LuPx#%ZEQjr?;dDRZ+v+Nx~#Y* z`1-b!lG5H^aw{8i}^0YZ> z0wCX9rmrgAB;GRC70!u;QED^CGPg06lmN0Afal7IWlFMiA#PF(X;d7)0jDtJV@4lq6S2@LnXWFxh_j!Jx7zjH zk*;HvtjSe_?4{p6CbX!{YaS5B{kD6Dx)4RLX+=pD?%5;tRI+g5{=$}Aw1#}pFb1)Y zM_v>0umkkFL_|-iJSX5|;10ih4v}UO!U;pSxHK<1WC90ahAS8As43VG1a!xCYsCd# zvzqK?S6kj4mX*Ck*}~mZXaQpUbrGy?% zpSfDz3PB!oHp1DY0)YILY?^ZHJ!wS^A-w!-{gY)yB0C%t$BofPf-wd0)?`D{dJfwW znbe2UiqW$1qR?<$B33V^@fKQ@@^+oObzt+#iSLLBjhpP+u+alnL+Xaq5{;3pI>&6I zq=l>Umjj?Z8m(E3aLO8wq3#tw+Z^ZTSSJXXRSN4^5Z^*Pvc$``#tGK{?d!$0ip%=i z(*3RFjO9GbXvB=-k()3^5kWG0(G{&g#0l@oVW@qb1dJQTdsoosRdfNio6){vRY}m+wao z1IsS=4pu7$B3J{%9&EZ-#H zji8v_M*Tr(`#Edj*g#RQ$@KfgQccT{us~Z;6_N~cK4l3t(I5+-&2-~=0V-hbchLIF zj_^=w$|of=m9;;65Z&VCyQZ)FsB4%u0ef|Emlt|>@f{hmpN9vuOb zUDluzpsJ@=_gUfA&gCPn6o%f~^BScGzX_#3Ye&eyf5y|v6v|=ciQon$O!L)DH!k^H zRB04o(Rr! zH3LeTUAal#%+J@%Q6w|yI!3jYaFq|nD3mvdY$h?4%;uEe(iQomi&3W8`l%&LlpA>@ zZ{*6Z*l1X0*nRUD2Ol)*b?Og7bjr%E{8NAbK z8z~-gLpjZ$mXU@9rIhiy*qAa46>o<>2nYcd1-^qU3?CE+f`(RWZcj2J2)SlYeRW)g zSFZ`QJ88lMKg9sFa6zGD zH!lm(56UbR)wA2vRq-NrlRIrrzHyla(YV$me18yr)=|1DHoxz`FBajmNX~i0>Tl}E z(TRhJi1#-fc26{v&07QWY(yNBD4mJSV<^nqV&WCWXZSYm$7JYK`WwumUGFnR#0k>X zki3fB9<^?G+nf~?t!^en_VcZu*o7cU3i~qs^_J@ESG+wK#I4L8(rifSq9c@Q$4z%X zm?nSmk>XXN8@+JBSRNQBo?b0T^^^~R)$YG8o-O9qw3tpbf|}Kw_=L!c^~`_sW)|Tu zES?nZ$+q52R~Cv2*)pt~gMxeQnlA zZ!KaTI!E<~@8V;$k7&hSm{!0^7ZDXY^Ic4_31~N>6;hxut}xNrmd$b z5J;jXA!pJoL3A0YR5K7FrO;k}8GEli=oL^(+%%28rJ;guOo{SQM0_xRFDXk@deh>b zf)8D9Z!(6{&RZ*^UP?*`RPj-piPE-61QR-$-e1#!Vi~m-6{5e3oW5-+V2EbvPy2qv&<` z0-QI2`q7qOGWX0FX0PJe(Z?d-=i@QPEhD&XvgERxszc~IBDHD-56W-Z-&>o@o9c5OTf9QLcQt$G*>9y<#aJ zSsA)!m^fh{e5wAo-3>?X=>knDA`emBq&4B@#g*q$uyiH8o74}`af2z z!P*GlVX*wSW}`Ov`|7+4)b~%glX^k?`^V|&-`jEcZ>Ty`ZZSo%GMkF+6|HIW!4|U1 zi+O*A{HG>r3vuBfb>G~ZsmNLi&z`9;nrY3R<)_yl1iFM%8pk6kQni)Ug>@A`kZ9B!S2*cw8?1l}%CxHBV=E;79NJeD+=i`~chr_?! z7r8bJlTl43I7)h*q!vYw=|83AZ?@?F+e(6Z6E~HEa?#RPPuUS41xVwD()7%3N?d)y%3iI1b+r__LkcSG9JzfI-vu!>#OIi~|j*+wGbmID>+u42Q_WxJ5 ztB#)s4L94HSOo#4tcD|!H<%wz(}bk5&0+iyTYd_WH^%4CG{k(4n^5vD1PDxw*;7ijQTd%koM4o|S!B}l~N7t0&;{Hs^@`bTNH1MRY>%dA;}ebvEHlKV2h}aBlMQG0FPrS(JAHB+^jm6RG!0)r5AP8YbFE z3H-SjiVw>dM88gU;>05Mq20)P$1Gq0-+-vgaDt?YYe>zNT>pW z0SiqSYN*l$6ok;E1PBNis^@j)JNKS*&pPL>d++(eJl;HQ0bzfmePoM}`ItRyn^*$zZD{_p1H;OV)FE66tvYgJaD60nAl5iK8h zI_B{XnZ{)$Q#({P)f~u)#6Lj zuKrKE){X`cDl)S1iL0n!ssIvok@!<>bZH=lps9$V4aBQ8TpXz@nYl4rv$`D+vrFrJ zt`E01LcP8!zn>Rz@>-Ck{UTE*H-R4~oC8r0?0&Jgvp8Gjpt+iHeRg~DjMy^Jq^ty$bHrD!;vfS!0p8Bj&v9To!({WcccQxnF2 zy9BgVO;KgJR=$TJs(UEwzK1I_(TNW2;Tqew9j|W8D@DB`{1i4gp~>=-#8^W?qBFmd zkVa`C1u6c>E9%})>8C^>>Ev@za}CKRPmjIg8=W-@1juuY=>Bl1_FM!1$p5yJd7OuH zw@4!M^`zR*(6c_if{4YKtQqZ2%pJGNJ+5;{6HcE-P3+dY@Iovx$a6hXqx!5E>(Tyo zm8%Qf7`qR(MLyO#;m%l3+>XCS9sEuIaWnsn(5KaKyZE>9dQ`@rj?CQ%ZDJxxSHKykOfY^ESTH)#5_xqqeM@=fM!dH@x^QhQU?L$ z8>yId*QG6S&f}cjA9ws)Iv*TBlVg#utC#kY5~lx=|IQE>e?pq6#i^c(H?BycJA^XA zFT)`n!AN6*3OOWhmk=6xRQVX9#nYF1HWpC-cqdnrHc;3A)V$XQW~5xm17*Ni!@Obg zp9{jj30Y3uhyYD6Wn5rMIp`n`#?Y?kCA$|QH=$m<*Fi{qe?oFe)4Y$6(4&*oit&;_ zo`0@-;~1u6HCclGQr3bkx$fNG;_Tu!_>T%%$_co4B52exA?N~-ys7AoeY-S3#O$6u z-`f;#^ex1a5LV(m*O^MH|Ixo!PifNhzCCJNK;gK|7ZOYp2mdi~|JUoZ6hYqi!ef41 zd2^Tvu9w zq<;F|VM1Qi>?If43o!r+om@^6KRh*L8uKq{U1526r;gQp26w`dE*PQTFu($u`P%@C zjNy}|9`}%60SQ#q*$4Xso&95I|w!g%&$en?@9i-B2O2#MyhBiAFBH#w%YGPZ4 zbh31Ybi?^a0K(H2Xv@COySLr+_p=Gje$r|5#-EPAcE71pSfJm9%Xs1Vk0=^7SD)iV z7B`uIOcUW;aYgefrQ^8$c^+yh4|SAL>L>Qk%zp6es_yuh1>8tPpgo35@HFv|2Q>ZD z55X|+dUOaIgq-RacaWp#jul((RmX=ZylP{uv>mX7_^f)M9#5hcHt$s?^dB4ENh+dRLb{!s zBu|P+yZrx8k0oI5lSG4DKP4%2z1Tn$y=UM#HD5+kQ1d^x{vDGbyJkzW*NX>yDzPp; zWWm~hM)f+4GDL;2cHa9Z^iNkgnxQU#%Ck1H|1FJz+jzN~kgXCnbM34S(#y!ox#w;H z>SG;Ce_KN)vJdNVvIwnAwjpZ3+4Xfm`>mo0i-rF@7A@xg#*qA18&jThuJUuz)E{^J zGjL*K4OCH^%ch?$Bgs92JBRW$;m@#y2?b?--oVQoluH5N&ZrRJ zScgbN2#3u8$3;1-$k{JHovMTOdh^%)ldedT=cWPjRel{k>!7Q{jVFx@P!I&XalcV; zLu874-+5VNsm)or&fqxh1jn3-9}h!ou+ggCJ(S|E&cI?#3>AQ9G(v``^cF zv!W5uRJcMEf;@f!Z-gK513$G*SkKbH=JLYj6k~fj|M}GS#)DOE=M~Eup@`RH8(>HA z+`?3*gpoc{EBKFCp%T%mp~VyX7N%0li6?7*L`pm3VBF3s!7Fb0cAjMf0txGzYs^s^ zoBd$7?hVjv&I&|?Jjp87+Pb8S>F%KXdfKqi&spgc%A|E}d)6a!A59_l{6`I5jshF# zQi+IE{-m%0<-dp(MaJh@^T*QZgOs|jOA|>Or+HvA){`jt>(Qn*7vJ@w7zfJJ)~315 zZWfhtfLjz{JmmfNeT+Ad>EF-t-_wqpc?yu`Tpq8VansWsy_=eLyD0vOiiq-=E``~2 zhWF8p4}n6aV&=JaV4KqE8A|#KLV>9hO8Rlu*EB5rN`?ZcVqFZW8~uCHx-`Capx?S2 z^eNiQ{ibQ|!%hQZ1@F%5R-D8589C3O)){fsV!(s4d0cD3^SC>_w9-T|g(5C<}0!5gjGv`H>zosBYJhM`9N}{vPkkK1v%Q5*z#03JMWB z2e%(avdOwvtQvKt4+$Z7nc`ce)P+nW9MIeD@wEGVW)L$%I#*@+5SOI7ntEV(=5!v# z{S9|W0i&VFcfp;=`4)BLS!Hb0J4z~YhQ!>MF}Bt!mX=d=o(*dg$BV86(eGn~R8=|- z1C#+{EwvzjJwXG?)fwdrR1<%me?7!8`*FLdfeAZX)O-f%K9=`%Fh<1BPHh#H+|k4p z^or$hh);)RjK-qQnD)gFGDTat&P`T_XgY8&rZh|=-P-P%m8}GZ-+lBsA2ML@7KgQM zKw{eQ&g=Di+S7aUOnA5I|b|GZL3Z4T=hKHyT2)Q!liEbNTJ5m{SEW@ zhowk~-(WspDk6-JxE`hSF7KD~;#w4o#58n*;e?&dO{-sh&-GsU<9IWooAimxj|g4n zt&K)6ZK5EJnu%~(ji>jz*UtQ37J*X-C9!nLX|f##@%|cV*=RECvKmCYz2;;EWF8Eq zPV9T^f18Z^QfeiP8Dy65`)nU$GvQ+WAQ6&U9<-u=V%{RlhCyh(w)7#+Y)G&w9#sa7 z4KJ7O<-YZ@jeNRrOFKs^57uoTaaZ39&u3CG`RD%Ae^X(M=e!L=r_)7JN}T-cpL=IE z=}cq6CM?16i_^L``>BX)$ZL|kUezL9cAx_dAgdZV+##h)6X9MY=bvQ2&zTPp3RDE5 z77ME#Y4rMfuQ`mLR++{_>?l9>thtBM<%b7oI29v?uY{jqIMDJVd8 z#@xO%%8mo;WxPIbFC4z4t%vIR}G=8+q6jpR7vKmR9ToO6Wb^p9alBsFBd zIyzF9Lz44eo{#n%Zt;+(sFyyTYsJ_tEb$1wa$357fuLSijZ-g8U5^YxD~goA&(%$Z zn}#S-f^`%6Yd+dZj+EgMf^#(ETsbZPVx;rq3YLQhl;?}N)qBQuI<$3p`|}fZiFfh! zH4i_;%{gA9iVkQZeH;3yW2d*A%N{zTA1bA}EbhN&wNAgdxl9$n*N{}6WS!JLy1KV{ z7l2p(KG=>@t;E-`mJH&{PY|a@0`Y!>cm(O*mMn9i%>uhDvz2VTfBaZGtH^mm8@B(F zCY`LG`cG&btR~=e@p(CqA5h+ELIc?PiAZNYzTqTn?uFivS|W?q0Wqc{b%TtI3_Fxd zUUBtrXUvY}mKuV~&{$9YlWmh*YJQUSv*T zNx+`~&@O%Fs{`R(*qh=dfq;*hnp4)KdB-BVITLlU@ri<$v0;0jiuag}r9Wuv3SsL?uM7u`8WCVsZIQ)~Pm1MdHP5(S zpV#NbUsnuakDJ~Ve%o>cb4@*l$CdYQo}W^6qHZ+7*d6~eK#JeI_A^B(&Ty?$^3*BN z)Oz!eO`S^(-jm)yjY7HyU332upI&@vdCmld?+fpjzEbIFxLK(d8 zD#_d82THT_w~tjX(mGJ}v)jiK@9w&{G0M96D2CCs!1u5nbt6h=!auGky;$J-Ml^oE za?K?l+TlUKFzeEXB}Y?5R-^7aT7NQC&~nD{5V|ak~;;?joZBHX4r$v`p z<-gQ#8nZW55_lT6W(SL91p%l!MqKd1lOPc~p`{LCuUi~Mso!Vj-5ti~+v7SGl- zB-fv0JjzHQJbSCn!z+$&Z{>%O_@$o$ox;VS0>j2jrid3bhvmRi4669q9x^)416w?- z@s=r<8EuR{In8iMKK_kWbMsjjWM090sh<$E)CA*;83-f^>-EK^^{?oA>tw$3jVxWl z6CFIyvc%>7Dy~fi=S5P)RF*kZ%83EbF0{LG-P4_;E$MM?C~;5TyrS z;ods`x_r9$F;ed3h3h|!x(hUj>!V)q`k(t`Qx5q)jIL+pZZiHHyWj;;Cj6gnt^$-R@xoJwW#Kz%lF5MuZ>q=wYG+Ni}EEk+&i$-wRtK-HtqNA>P z?_TmIPGd{!#gdiYSgJ!zZNe^Bqq?UQv`gG@2f~m9QB>lql$-kgrH`7t0OvyU@wUsZ zgy3HPhpw#e5|PuDXwj8lKh-qnNajUrijMlofBlL`hCJRG*RwawzrAkrnZ2o~PKGIv ze1Dc$qG9Kp;A~razp0o1Q(4u*9x`5VAt*bQ=eFTeLDK{`=;6!X5Xv+1AgDGSE?m^7xlpJ|O^$qC^H;pPN8@Xv~tEifS z7%(XsPi{aTSrK1!M~pHLVa0St>C@9>OQ)Rd=XPwO5br}&s2zwM&h}*>Qb`LPw6*Si z>o{Wt=kJ=yeQ=^ z$1wcaS%GUR!6{qac#J6bItUiUrpvY=%XoqwlB530{@c*JQAc|1NH*t$Klp=+fZvJ} z;WLv9;CA|HMNIO%2qM{8U#m}L){~~%ZGtpo0j*Wyi*ds@)d4<}b-Q#2wj-eQsj_3S7MP}<#^*gpq4?utw-I}=C}&R1OQ$e z#gUaNx9YYWKn|C^vz%!!&wqsV=DIzofuv)8=Jia3C5XXo-$m@|C|%IwAekhCoR9GU z)K^z2ii%EFz%F*_=u1e%L|}9=E>S|V>wJUI_?P`Hf_CRcM@&U{DS}e5SfJB~rQ=4c_tScn3RiZ?ZCA()i-=>(oJ2n~pJB{%Ght5_8lT&_o9JpOP&I30S5`$V z@Pw>d_K8e+3xz2O?#0=t^xnrUr+UZU$=;7;2}rZYPzzuk~){ zTqtlDl75y}-pE@M_tsQ-hnwz$$Eu3v({jybiFtZc3D-$rPfTf>7w6hr*6CF1lBidU z7ks8w9Tb%ijh*+5hu<%k1p{}wFLY-tQgxsxJvzBh?~3?;T%qoZi163mQ*zrMy-?u{ z;>b>(A0BL~TfGs8#@nWgEv7Ne2*sT3$NO%$yDZ|d&UIX3Q6Wasdm zD9de)#5o<6rikOa+qN^urEnKdubd@7!KPE?2aIwm9x* zdO{>R5tY-GRcnan-+guVJ2*m%MQL9woqn&1Hd_t-1fXI4UHMb6C-%m~JGk9H^e}3I zd5SY>LYTLR1JM==p0CGsU@#iZyREJ&3xOwyk-uz`TAN|tyMEeqy@@1dXewZ!+0Gb- z!4|k1WP4ggzQon-Grkrjn#BXjUDQy+^?#pzYP6R2C0>{kNnx1$w4k%N98od)T;K^6 z)?Uc3_&zR=K0X|w1qz;Z_7mOxjZnL8fmFhhEhEp5E0ehE*YmL7xJsMWXgODmA9L(+ zH=p4^R^ki_PP>M*IE>i*r@40}{L6~fl*Vq$82)9Zw<9r2W*)tJoV<2GV$mTp)CdT& z9;}2Tlg(>h>@Y#rQgApa5E*Tr^Ya0T?PC9y{3smtg5A`@^VOUCiPcXwqAFgl6u4qr zr-f`y!3w+lQ|?705ZA=5h*HZ5g-~cKq*$abJ}qd>xO?WFY&jPX!KRS027Cw#ko3_o zst_A1wq#c6nD`VdGF^y>xY6na*_kC?6V!Pr|qs;F*z5>*elyF;i;yc%qjQs`JjqPtEo_RbL`>h5yxd`PVkqCY_rc33Jrb} zqHY3wK1d^B$&}Dn7~G2KA&Z^{gqZzdLS9X%dtC>M(jo~TFUizHrOKuHe{Zj~rbZAa6Kc zUqCExD&kR6XTM~>;3z)JYLqH#aj^~yf&*C~v;w{q}@*b3o-?v9Du}NE` zr}As=Zkbq_?Ca&Im)Fd?t#lZ1=8s+M_X{IrNmn_L1xu&=Wc=%aCouVh4YpG<)f|ZOhNNP3o#}#`+MVn?n zg?x87vTdUGOtKUiZAtfXeG7Y|DAvU5o>1TEhN!l6tNH#o2ioD-hqveSDH#gCz{7eL5r%R7AxzcQsih{@lQi^?8;Db*85zlbWkVyxR+8t3IhRCieRhYB zb&qwQ^#Nq}&(syy$G}=CnR6NNWVv;{VmQ_)90t(&D$2R%lMJ{coWfG$;_Hf}hn}dk z7;v70u1P=Z3H=I`W~{sCXTMA?QNmdJ%O;%l+4<1EfSvo+eTCSHpRnxp@%5nl2`gUR zSss5n4nwt?p7xsqwQ%;#|@>lJG zswkUcl}Tn;tRZ;ZP`XVDGAmm)?dzmN7ct^#Dw+75q$kj&p2mW`3GSnMS|1`w7pP;B zcB7Pe=hUS5K?b&K&Lz1%!@GdKoW3Agy5X`?wwS~XNH5o&w-5R$W*Ggbs(=;vrBMOd z=t4K&lfc_7|8-HwRf$KL3jRT z&RoK>U=OEtl}(Kig3F)Y>#TwD+^8lM_>6}BMNkf}=skck^@U~;uWNU$u0_}P!26qE zj9at&d+gW3)x@xFK-DAXcQC3+!MRgB_Z6_ExB-tyAlxix)inh`a1}233SH-o%#?4% zRBRk0(|h;4Z&QupypN4odQSKEh@gObwg~N&q07P(xwPgVS9FV*FFMDa&^62>SWk4p z&2Fqm6s?_;`6&RXUq8CXqYyfSxWk-OYN;8Pw!(5M18}6(>r&G2=JqsSp8=Bh%a-T| z=kG`?3@)i?y941)q2y`ke4S4-_~ZCRdgh*AbkFKHG8$7byTIU-*M@C_FUYTbdHNN8 z`-`5HK^^?sMu1X54|&Q7>8IdEd8u$+F0bv8q-djj8hziBhoVwc-A+of^uyR}rOu0c zs<&NdWeoYt6`a#EmU<8GUxt^~(~{CmA&r(f`KT%9>>8JxsR$$C1#S)X_cej3#*!(x z5`u4!F0z<^DzTB^%t=yAu%|gb_~WAy`ns^2yn1c{#<`AeH1+Ewg0%13ZARj_zWOtf zkXp`m1S@Y0kS1gu0*g{y0oS1MY8C=(ve$@W;JQXhaMG$TxyIRyn3+p3PXg> z88#*gBJ$%(eOCmw`05|iovS_LrCs}7P3MVgHm~xHlSPFunbk#r>)$vj{&oSFG7R6- zIMPymF3FJqR?VwU4}{y47w70&^A=}LtURv1yf=DBUS8R)&F>E~X&nsfMCa&q-__g;~;j_vGJ<3s_7#s}Y)W1Yo zo-n~yRZ|55apJPNDa9yIB-ah@)h~rbyw7g8f^BMtX0dXpFYYI{QI(X$Y^Ajhk!)nt z{r~Dt0*y>Rig;_AzL<)2{peq#LpE)Af_4)pNks zd@}xA><=H-8I~pw3|e3<9=`AqYGK8ra-yC6RS06~^d9rmk<(>VA ztBDG!gDjU^KR-{+xG+z@9V=Jb8i!mILN|!-w)+|PI4R39TP=^)1Ik)2Zkwg#Qd}BpLDGb6Bh%~qvX{4tVT09dUho6>aaMSoKNX-mmEg>UJ>0e$9C+uX^K*teZ~u zi*?cT_lp9nrUvANHjFxWbyVf8ZBaUBlnvC&9-t79zt4>DO(G!aeQ4 z%kN*;Uj$XV3pJ!ZoZnJ{2 zHIgRyrE|1AWa&uBVOX_h2e@w-=xh!V>2mQauS!}?|b|I}E;VM26&e~t2(B0mw-h{-T5SBGfAakSl z&z5&P4J$&Y^xS5Un*+C>=tPaPS!CH1+_UXFcc^2QX1@anItdb%fnsKEruo-QCGd?-l@<*CX22~LpaF#i~adgnlYmXO9>$&-PLM%k0u4-eo;#()IV>~ zRpMF2&oA*c-qK9}H1nnL>DFB85^;DlmQ7j)cg0mbBTgC5KSUot zTrSr;e&~7|fW4%LA93@3=0G%%zl>FkkTZuGVnx$X==A_@5JK>iQe(JEDuea5?D_98 zN;(H~ure_n5sawpvOPne0sXE(dV=ZT&tKOzhB70_#2k07UGaR-o%Yg8*_^8aCn8-i z{gjiU-N~=Shgwd8-gk|L+iIO039lQB1nSZ=?oqPPQ{H<2=i#MwR}*;)PXjJz5xvuT z_<)Znoh_eDHJknAhVo-QHi_92t5kXk!u|6lkN0vDT( z;JpF^ojg4SZ)kxrPP{J_;C$l329AWLqDi8LqT_$`H5p_5f+dHaLX)m3Ai*IVPI~%0 z`aSVlryz`gp!UxHB=RsX^-y<7E{oST=6wL-`wA}7%DhR(i|iw`$H=)rpI~+j zEhr;@Z1vpa14!3dCrFlCaj-szTLPbBx%5tf8?!2Zf=FV(ClI!&zP3D$mwHOh`h!%2 zg8^F0~WckfmWYcx20AkrHujngwG`c6-~( z;{E+p!F;BgDkmi99g6A-9IPVgCCfGF=JfufNWHa8=HH7q-tDEAQ7d|4^x*_U|t3Tk)+> zv6*XI=jjE`1C+Rotka-#i}QiR43gX(U*iViTKr9J@e-X`5l2E`S_Ai2?+7-U)SSbZ zAa#V0B5n1|8mWFLI8c3bzdA*fV zP3ynxozyi&*WF~^JiKc}0unS*{WvXMR&W$_wvh4^cW>3Ouc_g~+9T^5>_(M0p#>(D zYf3aeP(#3F8QI}ng)L-9`|_0-sX>~EcXG><$70Av-oa~)$UQ)(*0 z$tCrWFgz7gOuLf01-KQB!6f@}s`Jl+E#$epp$!ueLm62U({! z1)*OCWcFfk`surA&&LK8tsv?d1WgyCG^N$s&O(3L4GM~~~w zf+a5!7C8OAvhq{f7Gs_%@n)p^Gr%vN6`!eS9{Wd;SD$61i(CK3tV~{IvMUuu`S!F6 z3I=Ke2scrA+(pam*|&kKRr!;9?MjMi%n1KJc1U$$G(J!BUnvJ`{0$OoGQU0 z*BQ(ycCQQ!LHV6&^wB-SGv^uc~hKR2VTQVp-8R$ayg1W8=yO=d)xJrEePPQKCi$ia)>oHY?iEH+EVf zb?r4mQz_D6&RKbCr-#9E6974c%_Zk>0~QmWOvuc0dfK3j6=E&m1r~h-0YzFya?gve z)!JVpN9xp?bC)*juND@5e0 zwX(b(>OdquEwW47D<|H8SCJ`3lv!EzD%2b?3dU zxA$@h(7~#_@KXb%gV9m_a#bDe3QtMck1G(ql!%@d#^=*muGdLixRjilzg_B|B@FdT zik$#|q+w`@DktcY(@B4Vybiw|&>-!FK`@P7vQ!R-F7>kU_v&eN>bLk#L!h)20qG3%`Gu$Izpec*rzXX2H$%G$MXW z&ftUt2Sl8+d9IPnAzi6>0GL^?ULGseW!|u9Ibp5p5Ohh!9k#IFmvnSGAMq^-Bt_~@ zMz7TM@54**{Ri3`ie8gaS=?Vz1=F5v_i-KT_9aF6sqmE9rS|3suBt!*B;4Iz0*O28 zcGWJ~Erk6n^F9Gd!K@sOIPQw+9jkPhsLE}=7;o~SLS@T+OA^l|aT1R89Ag$+(iPuA z8+g0()ngX0uP#)X59VC zG#<<40iq(ovmS`H?JtxO1_+QYo7p4xOdIG^%>(3x}IUvVHuiCJqc3w~3|I zuJ&kqulBbpQ0a-p9Tu^y(PrKW;)(8yq3;@alkh%Xt{}~9F;YwAMI|W=SX`NIx_*Zv z&ZF3^IMxGL_J(TOcnFH~m^sFFD;l+#bsagDohw;>ORThrDd!SEJ@Vht6G=9hgfv1M z^{2)2jq^j_uA-;ip@(`{*#gY7;g&-FPx`$DW?XNHz(7S>s3`0YxxR6iB8>jk=u`J( z+MRow$z7nPc_m0Edj|e{c7E0(?m^?zaFu=$`ZkM(_FTL_k$bs6IhwOQX0|0$C&tYj zs3(2HW4@dOVSII=1_;LiVzxsP2xop=`2`}99;yG<_9tx#ppt_hITkWT>(bxAaE!e{ zo`4nRP6(%3;6AzLrBJ_@>Mn4zbj{0{)lwd`H1(k7an(LK^gvnpSd+Jxpt|civ)o;| zE^m^p+GZH2ID_X`elxqDaB%SBit(7z4sJelK7A^Xw>F`)`B_XWgLImFwzAMVkO;9i zqkV=-3wFtQ?=;kmtu?5|fMv^=ON1?iQ<78QhdqA)k0dBd=XA;<)OA&N7FEbQZrUUN z`x)a>&h>Nl^Qux-uV)do(q@C_nch;-k$Uyf%#!V~%Zdaf>8Nq@22r_;Oi?{ne)_)B zlDJltrZ~9sOegYj3+j~X3Kf<)ulYyvTkt>raD>m!%OaUrIaoea;$!) zB#Cws2N!N22*e2smFTQ}CoMq074AjQlmtpYW(pSFcsA05)^blR71Tx@x#5$bS$20# zVtoMtt6vfW{2daF`9dPAf;mnXsP`Q_PyR_U;ut%!Q5jd5RWU!+y4@!eq|O4>M5pMl zKC%Dc1zSfx7~pF_^D5tldxdkgUFSCjb~Debm{^`bt#PW$G0^Rad}r4evoiF3*mQ75 z_G|K5=C`xBxQmy_m5#kbi2@{#ZsUvQ(s1GVB&XEeY56WO&aUtjLUKkaFB3G=xR8p9 z(1$&7DQT2v`F7sU^6(n4|V=XXyr2S-I5`;hcAK`tJ{(X<22PSe{o`^ zf74a#7I9TJHm3_Hk9Bei>CK4*ucUw{BN1t*oh|ApADa~6`?FX7n(~$&f98iAX`{opY;HhyHKn{u;S9!$ksY2v};Gy~K`iP~DY;>fJlqETv~Rt$ zsMvI()??1G;b^j^L6~RsGF6uG`$a)qk0|Vhb4>47lytOoG#|^-0#8CKVC{sob!j)k z$dDm6y$qh-w7i2;Rq*O;p4h|5iJHc1nB*RfNylWU-3JS_x+zE=%7Ob1Ci$J@?Khtf zhq>#1Sy6D%Np}vMNPgdE(_B`YR)h#?${JLFo5`MG8SW=^pW2&#Z(GAMeU4$nb@`j# zkgsQj|R^c?(MVAd`Gqrqz3Crh90 zI9B{yCoSQ+R_+0BH$a+oZ~xhch%nkGAYg&bD@wX^uV=kwW2KhzBtW@ZBoXxFpQT+t z`En%PM?fUtllWnvY?l?XPZb=s1ISq5p4|ew-IZACaC@-Z7SS%)|qi3e~pGzom-NV(d(>LfiM!fFUuIn1x( z5wt8k90d#;d8r=rj5N+zxLUi-O3e#1nQhPO!! zw$_w(&)&$!I_}mVzMYwTl{# zMBD21gCSIt8x|}b*pYPQnYIV{0}M~1;N)TD@13pe5~g>KQUJ#~qr~06 z|piT8?zPo-xbg%C603A?>Pc&095!MMUZ1sa==elKP;0eRo?-H&o+a z@hv0L3av%oMEP!F_5MuD2>)Wr&tE#0qA)6Ene}{b{&P7pXLg!2Hbk3*D;a*Rd7Qm_28vBmz=YsY*@LkolpGKCz1V^Hsefw>EeE>c!o>0o;{D!?t-<%#R-j4S0j!3 zjE}u5JS|8W)5WlUYR4e4`f^(c*e>QX3RuV@2)FO~-775h%TaRg_Cmw`m)k+uo*B>E z=rxaQR8LU)v+rdxKDJ~HowuK~W?Wj_j^kDWHG*xc!C(EYb&lo)w^HusD8JKrGiO;1 zMz05@%X=Isz0sL8ythY_?$RL`jq3SetK#Ke5_T6z6jAlDNiNu}(PoA|*fQB~8Ca|+5MwzNk>{XSmR7;!>NCmCPb>l{cylx*JCTODD& zJ!n)yje7gl&z@Q6GM8u#)av#*0gF)mxYCPXTnC*x(ahY&o;t{#Vb47@B|y~IJm#Vfh^+f4FX}G{N49C&DqwgsO>Q_C(025# zeRkOAYmFEWK2;-|=nlPzr%m4oXTg!_j<1E&YQ#AT&H6Ly%H@&0j`iXz-98f0&`_V9 zBRkf2jAHBJ+-jZr$p$=D|{OPZk(WCgN!D}0^ zrZXPDGQa&7@TRN^ire+-9se$q6G{J`P>&x@ytn$a_55K%%VW~ZK|aiT)A=wy<@+)` zIDLB~t*wXK+8cqw6RPaVaP8+CukWkUR7k4w(ZcU25aD_$6PML`aj>i>eIRJ)!6D^S^Boi<`x3YSfSNDS+; z^B%)PV-~EnC$yF6cAousL&bfwpNywR;`sNHfWlSdpvW}?K@yIvpo|=3rSnLHCJqh= zv>r}y*GT|Og?Y#8Q~0EdA6EnbUf-crExBiJKp=#=$YRooAiW@R6(D)#UQnOWL#tIL ze_Sb*eaks}ZgEYofSRgchP9tj#x21}%yj!U}GfS*Fn)4}0}yb1})7s++yonbr3I zuaS)ueh+t0&_<+r4dw7F)E?Ig2Pv1SbZMA*^vGDr_N=5?7>^(J*;A(bR?zvf7R}t{ zcLUQ{JpCL0WgBWnSjL{Z#>jdgaOEFSlm(rsc4zf)1N%|p>!_+orRO=1ij%1R!DX7P zl+_wPMrO+FQA4Es^Jl@$oac_+`+b?%zC#eOdX8I;J3n|i_sH+_uMNx%oTsUG0YB}| zq(GK%0PcfMBTEtKlqP2k@aqBUUsun7W)g;@7e>1T^5;uvF9Y3?2kI$ApKj)5v5+wr z3PxiNu4kvZ1<6Y6A}$f^1A=r7Kl6`DvLacCc;;TdvO~ZAT{wxF!X5gjX-dAbbFd~u z--8JvQ?UW>SJKn7+(1On4%h4b;aJkRBZQl?b0N=HIw_t+h=TC*ake(ttcdS`;wsK? zl&QkGAzNrVWoluL>gqVG&ECHwMymE9W8-x(!^-T!!(TunAx#c!j$hml=VPs0$7(;2 z&t)P@%}Q-xXm2s4bxqoi-P;=~rsV0(=FO;a>O)|41pa7LE9AkKs+{=NbK)z-kHhb{ zbjDqiV&w~YRQ5%(nf0h5`T;RH7M9U>9aPzE@GAI$uZb@|=ON08(s!SG+&wAUpW6CR z`c}pT2?*HA+!JV;w2#{3ujAxQ}}->%ynkxQ#Q%! zVl}pTbx|{s)qw%mp}n1OUqWN%2P1Z7Pxp|{2$jEYCJ2-}T(E9@dB_UnG(*=VGIAGA z-3TW@d@BvGajwivSaJd2ha*9n@EN6tw-rr@G~!rH&2EAQt|-@5r(P?P^bl>}ZQBV; zEgUJg=9Nt-6Hd}LOzE}$ZC&3fiZ<$BR5@T`qzgg;6vZW{i#T&!cv1^2w*d8FY5y75LODgmSj1du#KN$3zzic%Cpl@20k2+ttBhZdS3p$p1TR1k!r zC4}CTA_}1ih#0B~&2yvk{LVRRo%f%2t@rn?v)E!FA$#ZEd*Am}zSrkcSpZj0ZSRrr z{m@fqRCEG!n8XIw6HP8C6LZw9=fBA=Y?`R-8 zYE-|UuoU;X*k-?A%pHw1ZmvjwuZ!1xRL)o2 zXxlqa|5Ns5ux&_oGH3TZfTRl%AaznoFnPF}hy2$G1NP5CBp;69*@u|Dw2f;pw)@kR z3UWNR{O%P@RJ9Nt-(Fb(yYdt<#^*LqSaa|spF_j(oFDfCtz0<8+CdrR*^izQj{;kC`~TVr}X@B1x2< zq&re@L7iM>g)7h@e-Pm3Fzc+EQj#<28UrpklfzA=ko;V+BD;_s{_NSfdOwjb2^(K5 zJujh2P5JCqW1fp*LlkR&)2ynFvQI0vt|9-% zcKB&j-?Il5Hc5i05pk4Hgy4BGXkI{cdfwWx=M~e5Z4kkr7Hq8>WLd^AI&qR%hf^D- z;hW;(#+ius99CLyz^fc*yV__T{o%2C*8?}Jq0qMY5v+)O7!!8z94X%;)RcoDXY)en zOpcr(Pi!SW((_8+Q>5TU84cxmWZ3q>CZ@$T;7s)V=n4a^)N)4PW;DSMt#;9`5;4~A zLeTDb zV_wHUnaS+sA@J{bbRxw^(7ZQDEqu+@;hRJU9q;)0vCr*sFgru`7O9yM>_cCi;XKx% zy7gU)%=tnmwt18zMS;}6mdv*$8<}7@S{TSfpb`3pKkeG)_G2ZUj%}ff$5)kVio51t zw|;S*&zTv+!Ji+Z=3mc@Aq3tX6>WUEzsj9-Hw;Z*dbI;d`mE^>Nm#{H`c)35qW#k} zgtx?BWzSP7`ycu~_V;~z$ZF61g0I@y!uB}{(LQ}6XAon$Ck|E~u<#BX+G)ap5ZSxDE^gzr zj)(!d7MlHa!(}z>U5S9nCzAvYVWBAIyU-vRC8paEW`+J-Fw9?bMC-K2tfTFb;pZrS zNb%6L^d7kJZd7@pDfG!A_^vm|sk}fPG)!OCv z|0aI6lbophP*d5tlz@46)$o|8z_LTX$}y_Ul&ktpui#tWUi z?IACD6*=)`Po1h{@q5dn^jzyBej*=?!AXMB4h^j8lT@UBR4w_JEMy?zCXA8M z27+oJyhcD3ocV;5k+q${pYOOQw{MgKqrau_1Ww+Ad?}*!JFG}hrxH9C*@XnM#n33~ z>w*!}ju%%f=U@TpFN<;9Pb;Tzg5?fVZocrPNoeP$|5bjGKVCN6<36OhYPFEjHeW;g zHqtlhgI##Hl=XAo_Vf&uh)quq^U9a88o1RxU9*jtekgb|)JT!wVk(R1*iFl-z4Kw`8W7Og=2&aI?1iBgb=~Q)h18T!;2qlMzdY4cP7*G)1H?UE28D}z5Z zdKn-AkbIp}Yk<2eq~BU_D)sIXc*yV5P^-@Zo9TNgMG=@hB&*0Sw%(}iJQB{7;)*qh z7rF^m=f>CEurVA{36+TNHXjax{$u+(kfN;_L))Ib5a4x^6Xnk^3Ka-)(!4w8O3e~ z#_o4s6m3i#rP5b9J^^Q}+PsU}$UN*&(o%W1T2~~eh;mh7W zlr<*LSB$>~ILq7%O-3O?8coagh?nX?1xbNx?k`sPqSH6{`pcK(vM+wj4{7%GM@23j z5h*Dfyj9t+WSOJS0aUAM(3Qb3tp{)!@qKxW!DU#cv{Q#3;p~0+piLKGJAP`zip(B> zf<19-x*1+<GAH8E~W)a-!5fzYLWZcltErnRX6-BN&Viv)`858n&)(2%+_ zy7h{4Yj!Uwsxy`2M#0fJTes@Q;SfRjo$KaL=YeliJAQI<=)G&y?I@$S&@Khk#fo-O zwQ5r|H_SWvOy{So0?{#T9g2EWUY^OXHKMj*G3G|SK&5)Fj~|_ScY@6*0iP^qZZc>5 zo|?!r#jiJ=xMaiqWBEUOd;z^VX(JKF8`$UX8+yjuxV1{$dL~;<<-*Tz#5u1*LL0y5 zdwXQ$kWb&x>kCIm$xFy4(3#}x{KI@mCZ8t(+WFGuEnJ5@qM7eSxv3;DJqdl)_%wl$ zXxd15HNA+0D5m7D`=>t?$c3|B%a+TAq4)EW_qibZ&?M=?HHL86^o-UyeAIisZ%p5) zfv`k@cLPq)l-w5S6?L@`hf_2Vozy%J>`eM#c1d`8;`Qs!qq~( zeXW3hrjR-nysGd8KgWN?Bk$~6-?~CqEfT#Yiuh4^E?Cwo&M!TF#JPJBpY69?`N1WQ z&&ENiKVGY7Jx6cFwxmyCZpiDK5zqGihtxJAx=C12z1IPXFML|(eJa02hvpV^Q*pIM zL!g{z<|YRl(Y!qED>+kA5oou@&+VD^eHdaeAg5@r7O~uTX$~fo&*?azA}!%u(gV5_ zJLBp|P2iJ&@M{c2}kYby}cFvyz_&w$L(PmZ>8?lJ4!C^ zv?QXCd=#Cxj@GrRd7ZHaa&;WT>zaKZQ_4>?4Poc%^9k=2o4_D?-WPOOiq>cd$^21sfOobty$rHc#yx%u~@3GJ;Cp#%2}dC z(j44(I5YT2MPq8e&tvBOz3OI6mjJ!T&cyq&gesi1H!7iyyeX{8 zB7Rw=!?)IP%D}Id*H4!{A0BiCsbEAIj^9<6BudlO5ZQdaN&o)3QJ{#5o>K68%m}+xog_Y@=x7%b)|xo z{(2BncJi)3iMlht?k*hJk?Btn&49c|^&}X&6`WZJf9bRwKcBS*;Nxnp^fA92l*R=H48+POgZE9M=sU`As^c}xGu;_!hvJ}mh8wgey!qa31Hn}D% zdP#nFQ?J|c;1dcTqUd~AI9YL3W2El%EjyjDhNXj|1Cm^y(?Q8SiS?q>DCNFUU-`xE z5769P+z8yYrTD(BqFi9qwJ&M6bfu51Jthf;IjYk~4uZ1HoCm#Fna75%1HF#R_t#~^ zudjK0$QBs|psdnwyDD`7Dy=o*lSag|)k=bwx)WCfMsu7WGo)AEZuo>#9o4xUm_mf7 zJNGVFos8;RK*%T8*g9BThB9LGw>V=3nG}^mKSNzcPb;sHlL=d#g3K@K3-ozf<%RI< zMJm=={{EQ0(WR`z$(!&*%rufk>D##xsEb37;m0EF(D#yyuL7^NfhV6XSTqz)X1ptFfX4>Y$EgAkmTxbg!4N+}VKrp;@Xj zR7>hr+!bcT1Z^t*PS9>U><<(ZQ80Z93pMtJFSgJBM)R__&5$J(brj|5QW*K?sc9qA zwZg9&YWs0I^_z7POO6?PZe21JY22Ib5@}`|FE$TzQaTU%Tpsv$`s1GNEl+yP2?Vgh&uPxE~Zs6K>ov1|>8C=Ufdm!dVfozsQb z$fGA?)n6cc(KqalAGYG@N0n<~3u*;56&qg2r~KCG1V5yMs8`sbKzoOX&f&lf=o0AB-V%WpF#X*G+q7QoZp&X2Zej3qcz$o8A(cJLzB65_XFsr zoM;0m97IJl$3L2VgK7);@%hGHtQj$mdT_eit{}75A@^@Gxa1RJ2k`x?PLGox@fLtT z{nZla(~xm<0Q)cta&f(`{tcoxLcoy$stjSFMjjDsx7Isn5*+f-hzze$*XaKYj>(z z{rxvi_ZZVG9*%-mGl_5TFe!?6C;H-k(0=5 zu0Wk2RgMy~i2Vr@{RxY81YsvvnY@?&lfAAo@%(VlMa9$sLm}n3>i5aB>_vV+D!E~g zYV$p=EUp&8zdlGFvDb-c5tsg`*oC;b*Pa;1;S}2o;`Re*AcK>nu=!R0+ay|+vyEM@ zr#t)FLweU3v4`jJ-Ye3zKDj6KrDPI`jev0+#&kQcwM4`x?mmUI(Jh@!jAY zMFbmmA5%I+qJE5Zp-7yh;T&O_5Zma^aInItI?V_A=+3a<(;5l01P;^iO}#(UR*YhG z?@78r^FT!jX`I>L&-4y%@u(0Mu8g?_Ro9 zX3TT8WhvHFXnM$nxG?!UhD#dCFm)5_4I3VG#!ZP~LfFfKQ>zH2pJN|Bdl26Zwl@-O z*y~21^E!(Y-I-?ku9Eu?y(pce5RFU&UA&93#1Lh=m*$od8#0Wz31*AsVl(;=IhWb6 zJrM}*4+g_QCPC<6e?}X-tnd^`O6-j z{ujY%2^&2Vza?%ntyd_HNr-IZSvUfHJsNsz@b{#5M`z=IOm+RFc|V*-&2#DF3+11K zrMS!kS+O^GUOi*OPi#*0Q)zJgD_VUJ%(NGG7pCj$MvU7YExaeBz{AhLk02T~IJZPA zBUs}kFqlxI{5K)2!faa#m;2)0xcNG5TNH}e$}?t8ON5=J%U)W)^JT$<9Fd@$NW(Po zK0e@5ZB8xfsE-!_;-#o+galD^;c&@ghiip>_045=q6N3bfETkTmO)UFUNtb1 zcs(;CYoes?1*li<>GD+x-S~21H$)e+2nkkW~UV|LEZ>mLZt zG96AeN1b!B*v0NVB(j;AzX93Pjg!z92wND2~~{Le9oPkMDf8 zrqp*@H#M!BT4QvR-{~fgVN@l4CJ~OQUi@`(e~UYCub_29-D$S`rP@%vrI!Ibn~FID zci~k_bvfjW-1lO%v$Qn0Gpll&l-N#nsbux z**%SG6m+q1V(nAH%8vIJY;PL%CXvrUzEl#Kdo-C?x(}6Q&;RGTr^v~0SaG1@sj_(@ zU9yk55wSYWn!X+Vt>LYI5}V(y*8VE_ql-}jP-aJ2(ezr46-e~)A-Or}_;n;#WDF?J zN%c>%>48Jr{mTpfmfa4vmw8GL&NTQ_+FwH!F{)v3HEoQP#wqf3;U0(QVqT47YZh(1 zZ!v5V=5Q>f&Xj;;jdI4?^w!}q+wC1XTqEGt3~6M`%A%wmzI@Do+BB{O9aGx73* zA;Otsv!z_xMfLKrpaJR#cUvsVOpHl48`oCb8IDtd{wp;W+9fs?mQH)D72%!_#hXf0 zB-&h$SuDzn&K$U1=Bf~#*}rBXWWaSxV7S33p4HNvPm(g!BD5hazayUY{e-u}$;hEU zhmH}`xHPB#SPI?Eshe^#Oy{4Jp|04trLSQnYXarw&}m9yh3~^o9fP+){|B_r1K-qn zTdOmx3Ig)nZLdK>ei4sItiH+^k-SSC`_V(nPdS5@vhKJFq`P2k%Sd(c`FH2xywAK`_DZ047?tV98yhF~I8RQGv z_7b9*f$}`$;vMGjpyN5DfTsar-YZ8P=jxS<O1TQt&5Rm{1UevQSf00&Bw<^I^>M~)~M30LcVRfNr zK@F`(yxiO902XiNc*WjA^=bD>SnN4Vv}*RDI+Ry`M4oP0DYqD#+rASVrh&|Ju<+@l zRlQtpA;&n*{OVh=BeA|$Bj4x61q$+#Flg~&RgRebQov|l5@;LfQm`rilsBIP+lEgz z+gx;SSP~$?CmmimoLT^*4(U)j&Ko{I-#x7RfOSh#9&%=bb=}!_SN=d`tB}FXeOztv zG)ntCel3x`eYl<|N%}GLC$g~)qr(WbHN)`0`y9rPVzsvmfzhJv7NAE_8rG}@-Gbl~ z_aXG7?GyFclCRVMjk+Jn{3zK*wyjb3lr3+gSd(Bq{kkCR23*$Cwwoz)Qv{ zsW!Z+8d{uGG`+T=Kn`@2Pa9?3>7hJ7}oLU2Vdm%%3QLD_z39O^|O|f?SM0}_bOQAwY zdHyYd_tF(q$ethc-sfRkJ_*6$sX@+;?lDCOfYPelyzzp5g<6&E#tc`C7@q9ih7|!- zko-OAULXsqpdH^MXCE_(L^bzz_sqRPks_LtLBYz>5387`g%gKye!qqqq!P-b7jbpJ zi<~rxNOkGd6%7=dC92=juE#xcTCMcH;0)A$H@i4He?1QYH*++6%aapA{zg-|kv~XRc^so(Oj8h3u zCLOUNh^r5(qR;k$)OJoll6yZqBBA=->rJzv!v}N&$=HU}twJ_nzDgEC@8cB?)z#C* z#@Z%4GiAu)2@U0p{7V4TmMHsxMWUv?A4qs_l@^1)rfl6bn=+q@TxtW&kLg< zTT&4u;L`}ZQ{;O$MYk?QlM+#N!%f;p}Vo7I3d;kC^i)e9VUU{Y2$h*HPi9{=*L!P6bFBm#JE(4D%2-_%KSbRAnO>@(TnpAYX3+n4w@y4@Ha2CrF$GeNMK^!AkIB`^Q80 z=_-sw-IwmeYqPh;Re~I!yV~No;QL0 zq%GfxLp90gaxZjI=g2-?gc;Y zNc#iWQRIknkg2aZ_DBLVD@6wv+v_-q3Lox=L7hHT<; z6IHfzKO4v7i%Z=?L~29GE$1VSR}hovvEVgBpoB^2Qu|hH>ea$1or-MX<%-DhvQbM zRFVVFPDqGtO(4Bw!A{k%`{31QojQoQyqHY!rnkx^N`1mBwq$LI0J*lA3UDQdF-IYu zSOH2&5Nz7UG2_DI#Pod$c9kwM7qPKq$GF)B`8u=m))~2QV1I*+E&%|M*`e%9*I=Q^ zAzSov23ihER}x{@v%zb`rsA6u5Nrkp zbf;sYvGQ5O8&HV=iBWUDYE!@F)_?yD?zD*y7I-Wjg;$} zB$Fl6QlbOTp;#Nu;TK0t0ZCrj8=mm73m-2JpP`*%;y~zw2$y&-`wn}dQ9uoT8Pt^# zMQ&=KM|`RyYdG71vR#)cBnODWEVU!f2J+SXJ%JRvkjwUCYZ3AqQlgl<2Z`TTRYD8ZNIlb1q&kB5g z=|@|~t{q)&{=6iRU2rbynbl>2>Ij%#g7G7g>Nw|bZd9j4-`Xq60!;$atFMd-Vk_Jk z*B#nRz2*9kBTC?+0XI$Sjg-xMYU%WE>b!!7e}L)!t;;*5VIvc|jn=9e-MdiFzfcbl z>p)+ZZMn!0X*wxx`D$Cpu#n^!&m6|vz9 zGyJetQ8Zv8&|->oIgEYdR?)ibwj!@%Iotgi9blqyf&X3V;7x)?ygi zjVLco;WaCBp&I4AViCL$Qwh>9{ZS+6*}ZgyXnvl)P*8O1R?^Uoh^(d-qjm5)P-juN zsPcOVSmS(cd4KW6bZR$l&TC#;$2Rm~)Z<_A0@4Kc8Jb}thuM*^TsA#Q&Ux_y_NbXI z_f!X`BcZi=)mCgGv{RP+X7jSM;gW^qar`ATdK#ndM{=g$X#0MGxfF?_(GWLzYroqDJktWgp^3d@}UNPO{Qd16uSf)cZ=OUpKN~=CXsQdodk%TVe zQunr)0!4U^L$X#jk+h-DTvUU_Xt>ID4e7ZkV;o3Qnc_Cii8N4m2`1MV<{Aa;@5Knp4}3sipF@N}>AWpBo|%MM!yYmDhINGoW0x6w)lcYC zJN(2wL7a9CfCl4|n&J+_$uqmgOxDK=GYh!UqGCGG3xnn2Ct~54w2=6SjFS1UA2qzr zI)?DBSDB^A-YJDNuyDr!}w=s8ZfyO_OmAwk~8Au9MB92taZ61cdbSoq4?emB+ zLKw<|W8C7j>f4-*-l~`p!yHBg@#RZLeaiY3Pzy9PW-qm_Gy@Mk6g=f2Z+Koq?fk`q zGzQcYYJ>nGF?hp0L@9m%$CB$1!2^Iya&h8=pM3 zF9!D}jC($w;Ar8&LHg9If6;u>Xhn6Xu=eB~*$oK~p^euwh1vGX?(FDQ=SP(Ftlu}@ zly#F67d=Oxy$TayFG)Z;k_*;QZGO=KJWcF@22S1Dk|hlVcT#{b`2$<_o2(@X zOcVRM6St%Pl%eG2r5-77iHU9y**M!E+ZkaeNV&WtyyzmAor0?cRQLGwyoVQ!^C)kv zr?YZ(N*Br#%7ps7O`F)NwHL$;A~~{ayr&gd&DOlM;*yu=1z?E&R53%-h0I7-RtUEgLu64u;?H6uB5FQHYPXP zF;`Mz3LHcG9M@bdjXD0{L2Hu!_y!PNL7J}JjuNXyPFnp_4ZH4iF#nokc5^+Sfy4$n5W_>R9BahGKZGC_xyK8WZ)pTKx?gzzYNsGO*<;8?7D#NYv=l#(3o}@4 zC96%JkfkLpk% zyPxHXxaws4TZMs^+*ty-Vf4`sG`464q_&@^ASv+w21tUb@RPn$9d-Y~S-iRE_Azn! zc#Adq2v5lo7=Clk?PIi(4|3tA3L5UPnP$hr?0pkN*&8zmVb+!MD>c1Zk6Cu@fblv$ z1aRbhWa;Br^Un^3_OQ}pf;)9QGSgu*-ZBVT(CJ*(Rl{4Lb}O#Bih7r}jo83HkM5>@ z;ZU6SMuPk0x%6lB28vnW87Rl*)wI>%KPW=a^Q^mGbnpb<%`kLl4hPyIEdlw z;Zhr;ZzyYaUCvj^kt!;beCL(dEgdh~ZaXDQ>KeY2$9k^Wb}nHliM;SKxmFtlmj zPmMVR=Q`pp>J85(70FJr0mPl#AoYQp)^I$RO72~4+8fbAOtYeK?QoCnmr}^tQ4?CB4( zT}B$`)L_A3!qgliwFpKu^``bMDqY_3!*3l*w6TQ>miEAk(W~~{C0*xZi`tTvk;P76 z-vkSlNcW=CbBI>JTV)Rkb%G*J}=d(P7P$TAKmg2xrQOTL+j zPO}6G*=iVn^4+NZlTnxCW(3oyZgDdEaEGy6;EAusy*&z` zg(56$sC3^sZ%Nu0ae;N)!IWk>JrAskDYG|PDHvMb`%;| zPG8an!aS0F-Ov59Xo15>kQdWq_L+T3QFBuWTiqnL1Y=nB?IyJP zFWz??`{XdK!ML@q()gaM2=-8MDgaw-58Ru{VKw2 z3zJ&f1xM8kQoe~5NUva=CGW+4;VlSZ(X{$N*aC07^bmP>xtpFBT98SeIe79~jS%+z zgnJ_J1b@1_&0}bXg`2=mNB^jg#|Pb)G#tcPfp|(H=aFu;J}CZJMr_LdFrzlA#Tc+U zVA$G({rWa6#jyM6GV8R4zfsuymk>!H90K{0>Z{m`OcvsqqXbM^a>i@9gL|M@lN8-9 zb^%1?+YU}c`dn};0=cF^Zkd<)+-x~KJtB|PWR=7gJbFZyYq5ONaiCABnj^M5ZMl1! z5$AOfRU}L;dX^<`lV+j{QY@DKm;pnv#7^t!BqQ);3%-oViO)aDq$bU5;2*%W#E#?C zG-k4Lb{a(frm_Ld0>gpP@V?d+sqEC55G#r?&^Fdob6a<9;sFa>dEfp+9$~!zw2-qf zCLY6Kqmeb2ken-qg!#Q6d)I}mJaDR3;M)`x(am&7JvtqwEjyaa%OoyE65Udyv?HWJZJm6mN#&p zNt*L8HvY*AHoNGGluZL2|KTsNkOdPHjQ=Fyxai+6UrNwTESs9 z^cooC{J_hjYnE_WF+`(5Edk&iQ#dr0jUrzpV>clUSIXbB-=|KT{pHtRenI^5{lt+vvR9V~0H3mhUHaKHVUsS4|SooRU4skz--qSn;AGZR%CXCWNW{`-v2~G3p??-2<_p$&Lo~ zQ?#6921~^M|1UcaYPeJAURDRu9UeFalc93HN|5`O#_%ifvG4VNjW7xx`~825B>h)N z>HqW~nq!ZhESTQU+!8`QYW_U4vjI@L7p5#-Z)N11vXMA`&+jLeQ-v;S|wAU&&W3~_{ z@k*y6u{U;*UMqm41LnDjF86T!BN^nNZITz z!nAD-SMX@!5OJnv569xPeIP_$p?|z!bgBFxk+6z0`Z@tI!p}<=qYAdB>!I9wD z@SMvAhcrtWico~=vuF^>mF{3VdAH`!$}p*#N-Y0>w;8mC!*Z1;it4AuoXkg@-H&b{DhuxU5MP zX+7y~qv~ngU%#JtMwt=p0zP$+%1ZaT?AfQ=kkj65^UJ79Z-Q)1-bs(B#yNOR#KGd@($ z*VZMp^BI#D?;XfR4;g@cb{dP?JN5Z$m7%>1|hy6?2`9Q z$E~JL*L9W^)E0H@WDBPj+>-BIsMSpJnL?`9Uc5Bn9u^q6+`>$RDnJ6bPql%bnsOD) zkMJN}gi`!|LgztGPxap9=z1_A>HyWxj+*UP=@X_-u&p6jM#--=&l?|&&eqR-`SD=; zP@@TIMOE3qz!GV~-pG2(N$dXd!fNb%#zBdz3qhdpA=nce^_MhD&mhMer2aAENuJ5; zKInC+t~8<`Xg=s=V<$;$2viePwYvB*J(3kI`~X(dMCG=XjoZ&n$>DXL)X_Azouaas#LojnA<=w(B3D2s!AU;B zd-CdL_MSXkQ9p5~22t~}^(t1;V?LP(L8yPxqJ2Ibt=sP2kMAJ1d|KJ~hA>TT+{13s(h9!b?LHr9!knrA`5(5eBKg^o@064MNxmRG^+>{#DtBUgBK-2CenOLR;R zk=U}t0}IBVt}NgBLot_c85UauaGy5;4q(_;=Azz5d_xP1h*5|+M;h>(#grniLQBBU z32DdAWo?QLeT@0h{CaQcRiL~fp&~tOnd?5r;j(34PLj{WXgxt&+4$*T660xt#mA}^ zHicEV%LP}38%S((hRd}Fxlg%oU=+sx=uRMy#a)GmxJAcam8rj-NuTUfiL>>89<^Rl z>gXUJdWsQ+uDoACieo6p0nY4|wa+fF`)m%dy-R~Wcj1R_T?O|idhfa9n0OUQ7-hH^ zRhYxSpSa2*)05CB04kDzkQpm}Tg#>ETMo}<^g-ll$NNJzCC2#trP zx=7iGe@hF5e~HZd_Dw9m1T-iY#>cciOMPQ&b@*!@EV$?!mj(vPv#Ut<7b|<1!0KlU zOTO+=(-@?bCC2;yD%wAiFI3}ON|+QUC_;9d##cVdS#}y3yqCov;bsma_3}$>vA1_c zJxoyDeO}CmX;s+gtKPDvhZXnb;ge*Xgin7OOOohUzAAp(xYp0)qy<^gv({N6?$&^9 zV-(CZd+hCeOM9df7u-i=w=;MVR@UL*A3Ti`B+D8nL%Q!gN{DruuIm0Uocvqiye|g2 zS$hcpo9}5qa?vv^d`jMT%T$9{%4G=O)4H+K$^Z(0C;s6nHAQ#+T7)_Zsl&A*1?rKk zF&m{YGzvtP0kpTEVFMA636oqr&nZykq^o$>@w%F$;ly1(=7$KSpNFn{P!hE??-g{o3~v3wR$<$#IVmHPyfG zatMQkS$~x)jCncOyYgazzz3T`@mQ3v()W2D_=ffJfKGUj2q-r3C0ZX%B?&?X2;&AUd? z4I&hz4*O-JWz#g5TcYDu$|}Px-L4oK$2!%f##Yh3mG_mnsCtGUv>su?R_E6|TKk=- z7rQPhRKk6{=i~`U6LocdHHg#;*?Ge?F_f$vu-2-jyDbzDG^%ae%C7VV^sJ6<>^ct&TIFo!%__`t;#DW^j2^A zMDW1#2ku((`}n?%Wk$j%{kd*_*<|*np-}eXpT)hE<31iYkhz^ZXbNr9HOBev?MHt2 zC-iB&Mcy9&<;P(HdUtjF3E78IhMn#wj5_5S^dwgcb4AJ zoXeb(MGYKqyz6%Xr@Wh%6E}^;NsRQ}jG^2}8=oV6_PgMn3tgt%v&@#UXZERz@hD2$ ztqD4Kb^PhPV|rp;1L4PN5{z?w=3VXkE1JbOE{YG!%GlITC6@3T%%hw_oNEkXP=11H z&zJOuwf%RwPl8S`-%tEAx!5_mDI zTrx&wu-YrI${V%U9D|>Ss|5$3sW)LZ@>Rvemm?Yurv?0`oAS@ZjizNa;XvaI1w?<< zYgxLSbfA>Osbx)NiO+gvE<7^u}Gon4`=6bJ3k+5h->~a=19Y zb-~{AqeQk>?3}8?qS@bxs0bJOgIy);I58L$&dQ1F4WJ^)X$6?!`H5-Tb(XVa$(8Fi zh}6?wxPv6nhB&uH4xmRGkE+46vxH)V-rL#9>0ZGnlPy>Mu6*`gv~ukP4yFWfFje0S z#scrt1QK8|r&{y;v5~#{))zl{%o1rF1b=!OkXpE>%CRqY;Z^BX9$kEFM0ilLImPfk zpK>hD{pZ~pcVjFcW}{BzDZ1EM({3`gs+3cdmKdaEASmKr`0;gGf!@bzL1wHud!#PXqZ0E#Gn}(0^t%mEt133X!Y--rLhi+}N*=776v}v%` zuLv#5(fl^7VEyL z>tgfml+P31-G3XtOENCgNc(V@@N?3>jDG2~!Gr1VK~~=q6e!|7?8?8|w036$YZKs~ zF!_$BQIq_6;=`BNvJFog!cpIm>R&B2N*}KZ>ZGFAC3tb8qVut~efDzk%DC$+z#+Q% zsG#XG4J2K zs>b{}Z&j{_&{ne zB($)En=i>O6|@I=G-hho7~`yt?;%tmTx`1kSzB@wByQHU;lR~&9amHO4Pia{u%OEQ z&EPwwkDosC`2_4Fsxidbw`v;0cE4zEP zG=JnZSZP;LxSeTaCstOG>Q`_+fo|(!tg^4?z8EH-q;6F_lM3CEgKpXheA1mcv)~+i zbnl<*)@f;PAi56@E0LFToVJbS_r$Xf*^O|qr3jr-2+=+H|C1+#va>b#e?2Vq(lkEP z&+YQ)dfi-27;`sy`|XzwuOPL@CM6G^i+Rl+^Et9ZAYA?JvWbf`e4=q8(U;-H&SC$o zH6m$t$R|zbpGrNC+*YoTeUuoaqJN+JP1-7INp$#}>|pC+*cNo#KQJ6vjp7SprkvzYBcyIs=Q)XaUoMio$}koYP(ARiG4m(w*FQ;p|N`K*=Xrp zFwTLM!YLIbkS9Fen0xDKekI`yG8Ilef>k+O2ARhn>v~cD5x<7?!C2aX(LPV>ei?04 z$7=4Dz%tPF8uUm5rO_YkbX>|gJHr>juNs>ESIZ&Ep>8y_diU%*^(E0t>?*48RG$GBAv*h3(mCZfHA4VgsD&s;@eBK<_B)$ zjb*fh2e%B@ooLH?=^4*`Z!(qhY$ej9lO2oBGcH?ekI{ zmKN#RyYgY*OsN$*;niJ1uw3CT!2aB{JBy2W%)X}VEz(_!$o*-8NEb?@OcI_w@2XAy zxc7L$+0P?VDB7ud&y4tf)yrd#b@itSS=9f(zi}yQgCzoQgs!~BHCfUJ05>2h5SQ_fu4c6#==S!&`HTv6* zfHEUN5ODIxC*O$kAg+~7I{-dpU-IzMVFIms%l|)Td+hP0`}7>{OiHd^Iwmsr>}9It zMA6DsObwa>O+Z%<{4_1uysy-|Z<&g}P8J%}u<=WM3%e=Usqm@eYNlzCqVtEsrJ{~P z!H2nh`#j&CnTlUS&+T!Rh39BU>k2ev-V)=P>+)4ty_0*R)?CTqLjU_X9p{m_GKRxJ z_o0x_#Nav5uv@NkuqOWdiPvEljL3}BW(3eG*j*&1df=y{!?94oE0)&LtQ{%@&BsZk zs-x#rH!%@c{xwE-DRh6SH`*&b)a*GFj5F#LZBp!Tkk+J-E9Qe=tvtOp_$!G@MB`I0 zbhyiCD82qL$*p~E=2`RQl()J+Egn?vu3~#@fA5Ckn&bBq>jfRkR~r(5nEaQYyJq!* z$}+=S9|)Ip#ZH@T)6%~sN?mqrOAL*Sy7cDpMWe8zQX@lAbIk8gQe(#`rR0q1ga=sb z55@n3y7!K1YF+n6-Fw+-iy|GeAXI54Gy@oxl+eY1l&BDe5Q-G(pp>(u1_&|q&LVU{ zFn~yBQA6)&z_92L5D}0Ps^7%D&-u>1@9=8L;zX%|2k98 zRkzMLm_N^&hmwyT-MaI)cq8MPD1heq_Z12xS(ytrV+Q;6KYk(8OHDVmH5^&G0sg*5 zQ&pg!ZqMm65IL&r9oB}qMU}w09w)5Gykj7W%Hws1GFmi3?Tr>jCNWc7@ZI1qKWAr^ zxBTVaBQAkGW9um-^@xcC0_`mQRPo4hcX%y#T(c3gF9r8v)fd_1y zDCoIi{BdpPi?TGlTlQ859`R3f%FoeWRc;trxq;9;l77k69An$1V3$fZq84tL?f(xi zbP&$)tw$V{xPhgOO{tofbda0!204ia3c!j7*{zcv-rkBwd zS90nGDyy$48CzMQe6JU2kq{)9Cb~9W>+13qv_9hgZ}Y`}O&tI8lYQlf_;0D4ri9e^ z))cYwSC!^mwbfZAff>Q9LGk}Oe4>{>Oa!KkxzCOsAgqB9{$xDIAUT~R8+8MHMa53RGhBWFuhoujJmNb%qLHZav&2qj_ z7J6boYM+8w!i?A_y#OO)6P1Yhsr^(mP{`di;*w~=U`7pDw+&+_wfFa64d3iDEB0a2 z-|Vyh|NrBuA@iD_r!~pPbt^s>+yJ;SAsH=_=B%sVQM#$=D+%$A)NDrkE z;(uJwUu>`(xF$tBIYrgvlmGX^`9Jsnf4#@iyY$mB-WR^O*0#&ps$iTbWd`PzUzO zdr(?Hh=D_w2Ysai{0I}I<5DudR|N=eY0t&(6t3qNeeY9Sngof{paeCj5l8&*&&ls3G zkCn%}*O-dpn(wc8JJFATB7a82ow0neeJJdactXS-`ifKobQpm4`tKiu*PkhUL0;$i ze@wQI8_yl~ncLuY)3i>#}`%%gbtvAEb>E%$@ z!BY0o5nyrwDH>K^BUH^qz`6NiD!+A9D9@sO__+d?c1lHD8nYR%KVL}jH`?| zM;QF?mpdrzLYF8~WmizYGjCS_kcuK5$6jPLB-lH!hxT)JwHV+E=+7T*Ox0RS1$~ZU z%jluhZTo`bUvF2Z8sd}rxzw&%UBRnp5?NJxBqCVKdp_J0iA~bun8E4;d|eXV3+~qb z%8WdoocThq%+Jk)jmP|}p3K`=(%B42KWYKwEmOkjofQ9IeNcRJJ(%!;2q5{BpI3z8 zsNV9OrlK+8CF`MW^tP||AM1?2Ua3th{!To6eL}zk6hVmMhEbk$LXRvxkP{K~P zhj7aN7=6wi2~Eama>|$VM$F!AfAFMxeEsg&PAhbd;W4fC64#E)R|~cCPC^YQ3((T3 zVYkTaKQ54DB98nK^Lsm*eLYcSy63}2zSuP1flbWHa|Oqr>JD%=wdZ0MB~Xu|-xgF^ zA0@oXM_zJZw=u|5Q~J)%$8FsZn`i&yLf$j_?6P&UaXrk5LBaUmswnPUgiG>m-yX(w z2i=1{OtZS{@`%Xij@FaZ?>SIRS|3!Mef9lQGAX<%5&FanI`1i6OcAWD7S`2Mky??E z#00b+aRbOXTf=!X0y=(54`ij<* z+JxFY_w#PB;Ku+eK0FyGDeietvuW>3ax@nu7f-;GiM-&oVJI)LB0I>Y6vvSi_bdVk zNVIv1BH9SOfNV!pS-)*$*KWm4{pFKRJ5n9wg+h3jouw;B1#>;9o->SQXCNA24^~On zBlkkq4tTdplF|KNNAF;s&?Bt}1!85ZpRazXm&2Ho__zS}M;$<3VC_0ohy~iVM%QZW z)98oxz}i@(2bph{b>TaJwXx&52I*<0++*dIx<4vz*KHqhG$3 zk?OjUrt&<|R=meH9wjFMQ^!2z^_vGM4u$edH6!jlU3WwHo&$WTjaHdGOYUBK&vQ6d z-V@g(L3nfLtIEzkfw*_ekmdK(u?}y{3l<>J>7~m3vt!uZ93V@frDmCA$t~Fcg427g_P+k#8`b?!F57m)XNQBMPdf8;PtEPl{<3|c zl5Cr}2Q^IwJ!$K1Wwi1|r2TP2|XIXmG%w=ZCPg$dg3K+Wvu}_A{P&t4uKDxosHTW3TY) zaDz(W=X1gF8}#0YkDBF6)L1NDKn_>Ltj%T7JzNjQX#i z5g)qXEaNx=Wn#t^(jUat{5Vo!wXloR68_46cLLDY-%DqWL)qIH0ChU2swLPItDkoE z>p-lY#>jh?0|2rZX^Sn7dp6eNTc!DUYKCKrhAQ;ZM2u&c2;ULkI8JX;=MLN?9;u}F zjME{`%bv>ovJVM=KNDe52_`F5%|yJYP|>yeKC@+P>Y2zVoU84SA|Yn+Tni^_Z?O(k z)`QjATfuIuL&Y8)Vw#HIt#^pYTfru|f0RiJ)wyX~hSImAzkWm&q-@AcdXp4qPZ)K& zBS)mNkFG7!Tw-EwDgru@xJpZ%Y#Gdn5wo}%#09c~mIlC%#)$^Ll9e5}$+YhjC|#jF z@94q(kxyn!K$4xs=UI~`-0j}?d$o(mJ*?eXa8(yIHz(>`UYxuKxBEc zI6P{S(_&pw?7V=Z-8Icnn&B^zjkf*5`uviimG9YX7?m=O@uUbzHQZ_iO^96 zF_cp(ksGIJ890F=+yrEU9?Ee?j_h5R?Mim|x(k;+a~=C};Z?Jx-r?a@G%Vqtheop1 z^;(FwZUBZ^2Y&_9em-?sOQ(UrOUAiz;o7^)CbTWhcN&AFf>~8h8h#hslctsd2 zQI_|U@zD|NvOQT5ah}ue;t5gez=x*`^WAR4<99(92bM(7R0heJh~MK{)K z^^RY~M`?XxI-71Cu8>Z@t@A*i%n7=7)rllUmx!E9*pN*yyLE3A5F!Ztb=4suG~1pX z_&n$@pr;3O5!BxW8JdGOQk9tgU2m-x6>bk!<#rq_0s#qN3e z=zIs%DU@wjyZ&O-fp~sdm7vf%|e7K{t&tl1*o z5&rm;@-7tL+KJg_QIY19N7~$@R~x+ji;Pg6NC|o#zoxina_4{tHnStru!)_E;N#GEd-S$I{V>DNSBHff#K|FMmH)o&Vv`+ zw&7E$BM7f?lcMA(W>Tc91y;n<8)&blJ^KfG$5x%U7IKQB848N~IRf*u*N*WX5k}?- zC<$P!_d0KiJV@z*+zK1m7g^z3F@ z=CYaPUx(cEZ*PuoQh#ovk<^$Y{l{`o1|m`b5-1j3*`XKSs?hjW7+e|PEE*z{+_JjP zmy30h%vAMz6y*iF-KrjX*EUnu^qA#WAHa~S#4d_u9+=LXm9n0x5^&lA8DWkKjd{sPY1JI@7+mEz{qJ1wJ-tO z6x(Djt9^dJgSeb}`x??=yXwbX{gnfIqC zIYHis-}h8YFypfRr2XusWpIq28|I~uKgi<^dcY4A`j_m-FIC!BwGz@EuR_; zgJdg;f*5%>6Cld6{_K9c3+&TF07^lg%p-R6r0hvj_zft z6}+(Uj|)dWk|9aaEv+3MulCaSc?uW`OX&L2$;Gj=`GA)6iX~s`stzC28*48Y|9U_m zelCNWp4xe9K4+@>a&KDQ($U6^U;?@33>+JQOt4puO6I(^|#>_ybD9!`kN7;d|Q)`&P@u5>dGN(LfX|= z{_tAHR_avQ749pkxu(6>gz!6{`icES6HiaKU6>aT9eL?t?#_;AzCrJ44RwF;@7C!} zxZjx}SnStp&=Z$oGhntl@0`KH({6I|$=(+XN2kq#U*1~zQbS;7ua$MO9uvnYiWVbK zmMX*71~m>>GDWV&-}b9pMs5->?qps^9Ayw?@j|;!X0!*4yS?vwI6$JWkLtpN}%N1&IgW?Z# zg{BbI8&AicKE$sc#odWNQ9S$CrGTe0;#V|LSILCQR+Esxi~$0-qIm|Yc;d^Z(_%v~ zs;Gl^QB~H1B>L?v;N~0@0u$I zC#egVSNh`>k$w{q$F_^Vlgo#lMz&RsU*q}fP9k%)6Zk7UA8d4d6nkUS z)1Ip>2LvigWu-)SVYOSk#uNS`UlhQWZv4Bsm(~;s3}0mSPN1j}c<49aUwOMM(^IYxKSv@ub(j!r{+xw;#V zTXtw}V)IWV0>qZL6i3XNbbhE^LZ=b}m~z0M7iZv$mG2{nw8RLA_c9@bpWB z7tlo{E+VM&YKE_$(VsiIyAU5->H#MKDkluexAulf`^zlD9%Wa_IKTPw%e_LDKpPXa zLjwbZju{p`9o$_$mflcINa{*NnSc%+=QK zT9r2qk7)y)MXXb^$bq;H3Hiqs`T;OOTF`nU*~}Y^C;P}_N{1@&g2EO}nS3Qd^nkaD z^Jl#<7s(8BTCYrcYK68yU1$8X6JOF2X-abl9rp=<^HDTtfL#~T zqT|sqvw&^m2WD21+q%y=*j~|)!j24P{nL2*}OD?0H6dc#<&T+)_FES&r z!UFjNch&2NbCn(-wCILMh>jY&!~m6kkms)Q!*uQY2^=enhfxJlREAEF7<{FHJwAPO z4%8?f|A9~G3mDD{9{akXcU?z4+H6{OATTPs23{VVbJm?Y@3s?-bqY)$!Wz`)bBAg8 z(%MLho^X*|j$W*nz^}!|t2IGJaFJ@U&yZ8-LKi@$TYjYIk{^4(*5#=i+f6==3jq&q z=&8)BpG`Rc&;wCbb z6<-fUvUV&I(9&OEh|Ly*tIzU45;L7If}!((ql=?g(V$!`j94XxM3c7v)iSv7=vMyt=Jd~#m*p28h@UhOwb40wTc6qU zeE8mUeqWq+Qt}%6FcEtgDXHhD;sUgV|Ks8coU{^0O&tJBD1{$Eo zp4-83>6Y^4qb}R)Vq*{N%EU(n=kE<#Q3F+UYn^?G!^9H6P-H)w36U2RDR-IIam9Kx z_JG4DDl7beKfc_ZSp2d;C1Ks0gm6KWM{NzB&yfFI?eEut^h;|fa8@&a)(L%=QRCP{ zURZbf-T{57e*og44w1I|hOZdH9I*T|Be`G2v<7u|6&2R>w?emzo}NY;xMCzeE6$3i zy;poO7)9+mj?1lap8CTF8?w}>Xh7?KpjQ2lGLe&8fT#_S%k$D@+i{&VTxM5Dn($NV zKW4SEVf%IMKeo_&v2~1=&azEs@}il$1ZxfEl;r$c*=oeb?ttIgE>iDZ*T;+G&+9#R zB^*P?uyPXmF7?SBJe!hoC9~Xi>n>_g8@$3Mw1Mz+<8xidXEN}Oif9yi>OeR3P?b7y zwxq4($0ynF;3;0@$Azcr$NWi!u`5cRUA!mZFA1?5EQ5_oT_Km;`Q?ZX!OPAw-+l(jne!)s&i|aL~oi#mEEUv@Yu!~$3 zN-jXY=O$T`0*!A+Ct%Asono_Wczrfay?JzXf$wHS?3i9@&FG>9q3y+lO_N6G^_=bl zLZhksDLwj=$|HSQe~u~fOBVM^zf2SA^mR2~$9g0UsHa9VcOB!-#$VF3$)%ghPUCN@ z6dPh-!|vnE_(zb|#YacGkPt1cuZMTu*bGPEr{3#**a!PO^E8s@*Na>$E;jY25zhP1 z5Hi+j>l9&JFNVJ}Yv!^bYZt*^NF7?{eQe4$IV^!fAXv%5?Dj=ipp`WvR)B&w5$Hme z@o2N_cvJ6(Y^XdL4bzft#M#r z*spmhJ!}eGmg?**&2?AHq38DUfc4(QliU=@z+m$_>jpfKLfPxE3bf!l`EK`#EFnGuh}LV+#Ma`+HwW)o&$rX?tgbKO ztp1^tizMIwvLT5zTs9ECnhN*PE;i37K_LebL75rKHW0=3s&-g$Ff)IXvZeQ2Lv4`l z_0w*k782L?ChL7;z}>HQeHpM(;X+Yw8qiSkq@nb|=Kn|-%+iCNp&UqZzqD6 zDob@e0kPe!P^t|<$YcHpbP{st)xt!tT3#ktMwCSX1YEstJGdhIcG_?pK++ANP(;2U z2};2-luho*o;1;XQcHVsw0)wGpd&p#-(vuL1i%bp?Qx5#>J zXMZZ}_wCicB|M5G>-^mF)cIaoe-0+3t-HB~Kbs7W>yWKc9T|g1I)3NIK_FF~{fP8E ztm7%NHH{4I?pG*{I0>H}cqrC6U`CSvwC&3l#_kYJ-jfOm10=F@^R)!=pV|)DL#gg9 zt9af1OW?m2r4|7XL7wP_X?5^yX)Fl(Qg6QR=4Z%SU|dcN`&Y0;YAQ>|-1sfW=UCb8 z9{l!!Dup%+@(v0f{P$DOCEOrz3<1aRAHz}gnP#bW{AceGssok|KH8!pa-9u)UP!@R zqx)y=F@5VgL8|{G*b8S0D;w}<3t!%hc7C@Q%${(&O1^|)tX>g4PmyxVXH8|zrm-iW zy)%siDM{@c?gQ`jAR-P(?V)KB2U+h=qN;JEP5yw9NL-mB?{~oo%pjHW9gw(^?{=I> z)k3i>IbdT;OH+pti=Nz&rTkz3o7||_SH&hdAWh9qG7=Z;@Hb~;U{OI`DLUP8!93d$ z0(v9vLq#j$8;@^NM(&+VoL2(mxm6^r>&{beWJ&69Di`ErB~@OQc$Rx<*H-*2hpE2U zd({W-tdK<*x)6b|pqA(`@Q6Cgg7YQubKaSI*Z5aMjOr^^tCSkT_~82iXO829HL-Q7H;9g-EPDyghzA+g=VS zMy0}>mb&8#5u>6v>r}OZ)R=lL-Oh_%70{c5NlKEsSIIyv)nCKENI2?0LVBO0br*j1 zdIM90c@wCwdarHjyoY7H`R#k#w6L2_GL%1V>w!bg<4LFGVJdKrJ3k86jfeb884@5& zEDXX{mM|W3Zs8&+H|YEatVNB^6>8?X#M8*di-Fi6 z_3U(rxqP%b$PT0Sy50WpDZ<#swVz*fz;yP!pUDDdi262NU9sWeaLQnvP2IOI z-Pi+6&^XWK;I7Zd;O_0dfCk}Tu4!=qb4e+Dg_`-B*W734Ti$sNuxNl- znf!t|*Iv^rI8wX*KO&H7`AAFXML=xp_ck4={s%5sXx;G6f#5;t12ISaLG4XDNLnKc zP~x+j_faHc3J@ydBjnvVqBcG=z)S!T{rfx-+rqrO*Q&ALr^*te+Ew-Kn8T!^yUd>Q zo!}zY5m^;_j&_A zNg9F=$sB3i?VR~GZRC@-B*Gqo$#bMT^kOab>Z7~uzIJW5F7)wBd6I9+w&VjYFlADt z@aD_XzMuz6NF6I~g$*MO53#)1yg9|Bc{v)-{7N}8PqZ1Mc>8$kT%nmyolkxHFZs^6 zX2t?w6&gniSrKkm^b8)j(^NM4vn``&Rh)Sk$t3RA>haQcR_J-J*`op_r5}R~UYT>M#T{dHh*6DhpHN`v}A{TIXP8gF22zB6QyH!W}kTtcB5c7)czwkUwU8)rS zae;Hn&VLo)Krs}I{KnIAlandGRrG9!QmZ$xl$d}sZ=+ali{X4hX2;K*&6eAT6RGxcc#;_s8QYP?30K~LMM+k${-=8*ND2(V7xxndxB5fBc1 zmCsQn#O_arGcnSW^ony_I}Y}sGF<$koyu*`i4N9ekvBUQp>{qR&UJHjIagq&0xiI$ z3NJce^Q;tqp@Onk$x8BiO%}Piuq`3$w48TWv>#xQIxUOXlRA~{yVLt%qIjldv2)cw zsb!IyJC$`HSXwb7=4;*Cs(VwK%STcRNIBRsD*U5vJ0CD zp3EP1ed(>xT@dkwDgD>cn#u+1BMzP$YfAT10Wc3#L=uBk9x*COIO_^oX+-S3R^nGJ zhy|pY<*){eZ}TTsxGQB%al`T*{kfaoRf-Ex2~#A@4}gxD!6k3Khrw5vH;s=275kl; zv-SJE_R`r8b1&L(q^mlmdY1qm!1A+N&5|p&VLJ*2r~d@PXPnv1rcFK1o3dn0REocp zJ_%ncfa}kbP3jryI*nb(NMGB2YMy?|Uw=5)|hVqM!4O$<|N3N)U8u#gz=_03t|Wz+YNu~ zhadtQcRtKY!ny%$I4?}NQzs-J+;uoj{>$Zcw+L_7XS!9%N$g07?wY2Rybf`|&l@#> z-G^1bRIPpq!}C_njv>))&ti8ZZf}=~(apsZo%!5%EE4GU{vD!Kcdkt2ziUW-%rA)3 z3*@~YbyIuTl+3qz6Szt}{XOgb{Ptb1F-g8)iF`J-sJzztBS7~3&(``a&13MN(}0r0 zUUU1173~G+G#4nWY}g9@xKPcVntA~5ta1~638VK1HuCx$zaW$}upIgM^Jpsg%zhF0X4)Pp(ZEv>f9_(Jd_N5tsK zG=_eatV>UK9Rw-QS6RsWEk@f$Cq|v+p*W%RlJ;3=89=0wQ&HE8bXk29>vd%KZ_%U* zMaz4adp9A!8>YTt$TJO`Bq@oVOH&_-uWA0PBTuB-OM1BzVU1ii={h)ew_GeZC%fpl zsla08CDej@u6@R8`zUWu1&5*nX3Y;2mlqhfsR@tyt00xSBqsxEYW|{{aed(qzb5m9 z+v!9|Cct8TeX4lJH$C-k2?{SJ2oVEn&(6ZquU^FYa<=q`vN_Fdub5rLdp5AQrqOHSLS z*6f?I@ck(TguI7vF6)E}eL zeI*(=ZH({XHO-yoa=l&zm~P6+1`kIO>Y1H2^U-ZzqqX+@d>4J-g-8(C2Zo!X0<(wE z$T)|eIK3U`dYn53Hzn`5NzM*q*Hytm$a*NlU7uWI6QiWcCEfXr!RM#(?BtifG&@2} z>qoZLSHYdRdub)%{(X3b@F(G_D;lQSQ5OT#((|?~GOws05_JVLS{~rh5ng+c@Q_s; z1EXX;@%oEXAtF)3o=_Slv0?PlW#Bbk(j2mX6w!8y2^!vF8VLf~t9k(%tH065m-JD| zeBPYHVnN1nFj}-pt@eje1@PH*dr^_+uH+X0_$|TC!8+L!fk0ip_dquMcD>NWNy7MA z`)sb|N||#jq&VwnQ?a+Av&sQ+t@l9ro`GD^NvE)ZQEB4RAB|x5I26=<12g*`34c;G zEU@mp<8i{Y5l{Oktfn$O|A^S4fD$;5mlik55NNwa;rtJLdlks}iSVn)OEpYR(w z>VXO1MDB~^*{5p{l>2XP3``HgH74P70N4fNq<~J7QneCAm&OeE6}BvnJ`z)&Is3n+ z90yBuO+1@yeR~hz1?Zx`=d#L(k%>8Xb&s9jSM-;pCe+@3oigg^sFam>gZBk*u9-sd z=oFB3yhJAcS_f_BS+cWrE>pRNlqcEfSIDMSbnW6LX`eY=U@lsei>^4bfSqgfnceL% zl}>U&@7iKwy`T)pH|F!O?%dS zR1tbyXODj)S+kz_3_AQ0_V;fEt-B7C(&6O6jNIs+@wVP{}q^NpJJ}q_t{1Vp9Ik22OUP7(Wk6DtW zl5Go7wnl>Gt#Vv$TpEN|h7@{5liKr23s1v3Dwl&+p}{`zP5^g74Fo;*PZhED)HNh9OaF~2f3{x6xaOG%gg+k#m8zd`_{ zyTtKqKeu!knQ=4DalCAaSqo&YUyNZ7 z$_{+Q*(#$Q5zB5tSH^5hzwY7{u-~{1o==|Q{d#1A5O&$Lr}X|uW5_=eU-j~1Zs~#S zC8O4M8WS}2$7gk(j4q6yO*n3C@Z%nj9;qbn<}vO`IX+TjHI#84e6{AN4yqseLvX}V zMR;-WmjzL8J8zOKeY+^91Mx{5`5m(^>y3Fg5YLy`CK04G9GO-##kY0H7S$J|akeU< zPumvQSosQm^WlMflb8{F)WsC1*GbHohqD0xqw=~@Dj-JgcoRm--qsdFa)5U}71e#p ze!&fmYwk75(}-O0aD-%13x2Gc9y(j%a4k@X3ozk};8H?zX{zm1!NX3t zNiW%BUd{!#viS^R^A;y``MeBzJSxq4`r-?2)ysg3lcML66U}gZHL~#oSy{xh(o2^J zOB!l4+j*&Yh+sZvCbtJ}Fa|cNBUVf$-LIDAP((~~sqy8Fn3Se9J|8&Z699Z{s}$Ft z`bD%6LFG+^bv|`|tWw`xB>ZYL;6bpPN<2*clMx&@)4MN8iy_-rCusO6YXO_=*I$=) zxs=iO>omVjuJ+Nx763nD3oeVmjjDcrj>%pXm1FupYpthVyG6Qv*2G2uY?Sk0;9R)CRLB1X*T8At9Mq*p!eY{y#=2@6cw;pEEk^rVMZvOhD=Ma3IxLSe{#7!ro$mda0Le;UKhn^giFNdcX;x5b>x5?#CQpB6(Ahl0Iq zV)z|y1Hq}xC2v%7yyZOuRslj3`H8+^9n@MC#OlSqwW3@T(j2HT#Gp3CRSkC99PO>4 zi|RBH=gYoAY%p{4KsLMTME3wpYIPTil}yeWDuVg^Z2!k7+rn#B1?T;zEeR=hcRM%z zHR#&&%sePVo@JC~SZ6XyLxQyAyV_#69{#v6jR$=_(W8BIsapFkPS~`oM=bg7zNh9V zJ|hxbI`rF=8nZe*^jAa%!ReeY^Z*O9By0K%r=~9g{`WI&ry7-rFO}e3&~+(W#Qjkn zt9hO)yJj1hO$VTF_-KQ*1~gI(sEug@Ha&hjl`=;TZ9guASm2mlA4`t%&QviBP&K5O zc^WPVWEK}~@LDDoAM=17BvEcyXMnmxx4rM=34sc9W^90!N9%kda zO+cci3eQ|L7bLb*5v~N|q4nqWYSs&}>YolwYb22P1!Ffcqe~fdy}K#UP0Sc3%M3g} zmDt?5JH;6gSHp{$9Wo2mkG1?kVqTT`S77Rhh*zFWB4xcSt8S z-)K8h`WaxM?G?Nw%{-;@OD8Om5mV>ug2i%3z7LuNv~|yxJv%1*HQqDzDi=RL27;%4;H#W}!V8dOiSmSbr2ZVq(pFLU5QL;PDrmO}0 z?QA!Nh%psY%ecKWQs6ET0cfRLY}_3kp@? za#^Kl@tDP&lMG_d&M-lh>l{)}q$Z&2Qej=l!mx0*4?vsdLn-MJ_VIM;sRGB?$-UWA zUZtw8U$l7v+otTu zjBplt)KZien!CSM7Qy}+% zi>EhC338Cde5X0RViFNpS5{m)>x!&r%N|>$v?TN^jI`?hyf;Z8JJ}r(PkGhrOrO@v z!>8q%2{qOJlqo)UECte}O||En$Iw|7RLBF(ipQWUZP5Oc%MBJ>&H~R*v=!~UQkTeeABm`mPzD76c-wvPmKs0_6_!c70Mwu{m{E6O#EH2@{`7Hyp*&d9F_ z!I?d0;&O8Jl0R>1bB4Fvqd*pIF6FpouGS9YdmBp3Qa%e;O01JueKGIN@5P}c#$8if zacN$|qJBnjqx{S3>+l6&aUaz z7^Tl~b<%vlZQLiu3SfR4hxqOB5P$BZWKF})E;umZxg^kYZ@S}`g<_9Rz1+Y?J8w?Z zLH3%A=%s~JpF0u)8>Yf4C6Sp-$DEx7wYgVt!SQA;8F0?)!SN4VqVn3$+Bok~i)+_#rg< zC8-1*C23^6=K#GoIqPG*H#mJN>dp5Li23U0N8IjtM(bsRfY{Z)70l1a#DAUND-k%r zWDrPDXM{uoiJ#G%75Ua_^$42ph=FypZddgImsLUxj~1XlY;}d90|6q)Po^HU_}LE& zAbVHA3Pf=y+4)?fdx>{k6Wx8*+4O>GLqVwfll>l@aw_>{By>%D@g4eU=nk{}Hlv?R z=uS#|uW@n@FLRb_Zn3`@E0C!80pdWre^WT1jQBHKERiR)QA<+pP$~adOt;w z97MdaDT~PP3C7oA;;FcxrBDy%nYd<3yFzL4*VQ0C?e+U35e#wq>==;GbPYCc?%mTl zCSttYU>{AD<8^GRdF+8$wfT{(gC{BG>{1ZV;`z<(c_QLJLe{|m&P6D$BZIFzhr~Oz zJsKSCxWebl-bG_9Wn<&m5hSFNl&ehIdL7;g-WSJ-2V`J5UnIvah@45D-U-gsH3u zjgh4_e9cd=b`LHJ@^pdp48Gge+-89P+ROCPfF9?_W$-^103T>vk@!ltc6jsYD=cll ziD%;D;)`JISdgdijk8}kgR1TaibfSXc2p;dx%Td>U{$a%7_zrtezju>E{qktC%SR( zrNMH|U0ToC-+cDD zw!8*198&AIZiy7!_lv8mk7kG;V3deq)e_=Fj#1sy9=cznagw}J5P$HL5VQHFS2FU> zDjqo3U17QTeKn5xA6lq^KzN`jMN@?l;#YRcFsD1 zWvri@yTHweFTOVWx-PhwXCmmv^Xi-AwtV628RA!poizB*g>=mMT%pblZ{pGFKM~!1 zwuUCk@YbEr<3TQ?nS8?GWN9`IAVlEcR>G%fh{4UTyAdC>)=80C>w)M!LifhwU&o;H z<_Y%HBSj1k#?7{Sa^wH<(0N9=3Geo=y(|I1dp=LPbp7M5$d=c%Mla~s_!qE`cQOMHDKa(2oi1}_tmmPQQRjn?`On{tqtq%?0 zNqjS-JVA>4(2&Ki?RN%*nkrw-bsDV!(J#}N+~hc&0KgJEcb^1+jN4=EVpSl&$C+eb zE>789n*FQlY zJ`Qt@-Y^Fy&X8_>Um3up5M&B?Fw!9$vU#y3ou>}%rxzp9m+7W4yWa*KQrB9+_EI{i z5R28S{{KbVdq6dnz5T+@jEV|~6zPzGP!$P;CKAI)N1A|Al%jNy-a#NU(rXAH9U{Gm zVgTuqq4(Y)(wp?&Lh#!-|9QXnuJwL*t?%B&Svle4)P44To@YPh_d9P>nryT-irmgT z20IXV&2KjpwbGh!M#m{C><1^>A6EdrsCkRo#~mfW#I2?U!S?I=e4E@s3lTfx!Zouw z5oV`JL)tW2O0i*y?_+JdhOn1S+^+IgUzT<#{Kk~m=U;^()$+16Hrjf-L@WMs&5i-H ztvF`FbTrdOVN|BLk^#`h=KvGC*F_kot%ENE2H%rjFB3P`I+m8FF+YI4gnzCR_PL!zn$>Wfmh>D#oplQBw{NsbFs^sgg2t3%iRGsL88L|KMs3 z-GmFtX7iBoLUvVxa6>uvi=)>kJ{zduvG4Vb+BN=)7D z7|2$}1#{~;0W~a$E@YGh(pr~kDz$0KqYGqK^stnfPYoFwYC|b?uQbT4fQ-=Vz4SXX zPBEE!PZP8;5euf0j6Dh>n22K^MJQ8Siw^?w>ZMXg`5*o+Ejk*X;~$GJm0CQe6M@=m zwhCp%#kt&&3~jti)5$&;ON_Lq=XfLtcMV<6MJywt{IYqgs4rO8&wgd%tP~{Z=AZxN zi2CCz+1lLO==~kD9T{O^dF9e~)bnBTZgiaOuL4=|iBXK2ond$Lfoyn3EAaHqtyX#! zI!-khF6f3~kE-ft&2`h3Y#)U3yi(&8!DSwMyE#&2%=xX&%%p26rmWeJMT^5HegXZZ_;9#XbJZO#1I%?uMBH@U(P!km}Tpk^xpe zU|IaK($_>XxauW(dQ;29j%C5YJY~F2zSK2xKwzqSm&NuQ)U|GD-bLYrC1un8HLlKY zX^CHKY)Q%4R&^Tc6K(;f_Kr(R)12dVGO6Ko6YDPAo05_q4^9hiH=odyTJ;+}rs2yB z0y3GmnXSW&!!(ebeeOx7dbkvMe)PD+GT=&gCwzwx1 zPUDIYRQ0x`we0YbvOU&Or2TWdid*y+_`eN|3W-N)u4ZWKpleXfaJiL#~` zY5r-Wo%sP1O?ScA0Pt)AejE~=rwWKT?84N-hb+>Pi03Aqv@>TBF_mo

73A8!==coY)45A@9yPt4#&)Z257X&deS3T8Nr# z-LdJRo6RZeMd=lRDT6_Q?p0!Gf%3cRWF#|@&7J+;OEpN}5ATpx0y~XqDeXMM3+lUq zLiL5b+?tf(k7aijRj?pfQL$s#EZDRDJ%{^e@78^F$DTq_78F2u7Q1c%@)zXeC@;c~ zihIav&?Su|Bc-&z`-|s1ULSC)*Sib49AUa0CSz)T zIpFvUNkh|bchgapoE6dgYc#*P_(;NFw`wc}ycA8Ov;yLRpN$KRuOjlmb|9f6o1PCV z&g(wK1m0Cp$Z~69iZ~gnX~^H1O1~;L*LlQMyN{W|5t03o%^)HU!qbQ&eSU_E0xOK4 z@M$8@f#otb;q3dR6bQhXKkmWPl&Z>;KWKU7P|zXop~1^*xH3jyxZX;1b23Gae?ON6a?o&foaFasl2K%XA^BP^QG%SHA}AnEr@ zG-**~E?>Ff?sG{}fYeULBNLnRVzeTl`7+x5HE;7o$kY1R+x9?T5g|4~7IE^FHO|33 zKqzd^8*>&gjfcwk-_&RU)$tcAxWRYh{Aic`MnynhydqMPG9O@apKuSfq;H08m!v5C zGm9<6lF`T7$&hUWZCps&Z1463*^ZnR1{S&lO3FFYth9il_6Rb9iBvd|=`u#&(UHIK zeqF(8dGj=2%_>Ce^?f#Blyh=42pV%x*OZJ{80o7-un78aI40P{`*YNF7#Y|ZR^FBP z+R&1O_zh|X=-s!|bcefJ)wAqspOQ^d1Q<;lJ?)rtVDmOdzD!T<+p>jZJ%iucegRxh zcSJRx+I|Czq(p1y07>mje+HM}n}S+r80>6_uCH$Jyg}ehJ>zLI5Xa7THea}A80!!A z8_r#ET>Yhr)M$pB9cEnMNXKz1Uq?W|sKPDL!DNN9wo-?1~TOQD44j*!h(nuHK8 z*eDRmR@xFARn>`*Lz8koG~5)vurqI;BEK&1BU%(K#9Q1>a;#nquWU?lz}#+>QbBx> zCR*+Jo1LPO_`X89q|!4BwZdqeTDm%&0%>%qXR&2?LJXBOxl`pIM&<~?t`$+3>; ziBXe|;(X7=Hc6#@gMPUM!a7D;tdI-bft}(TsYCUIOMN?2!cw*d*}{0_6)H+XCA>O= zihNJ1Fz_WNc2MgxM%z(Iqia3;oolh>%ROmm72ejtJLSfkeu?De7TmA2S1+^4&7LIu%{#P(e zj61z?rn7kcmJ(~oH#hb#s{GMosePp|7@WxYW(6(tp#)R&*{g*xPG@o|YUujWy8?yN zm z%Q$i7@bD%um^zKOOHox;?~ADrmeiqeWb}7CT^-c67bsJU>+G&2`V&KG@87&kMPLh+ z^M_x!QYctCr-GVOz#!BGr?1kc^@vXMfaxQQn;3oDZAPzwtk{hH8CNVRB(RvmZA86- zJRf|-Cd{jJi%jc#ag-^X#*s&uUg_RW!Z)n`hS<=E2ac3}-WU6>bsnzN_#IO2pqYE3 z_auIer3=`*rpiu4R>F6s^^Ygseo`4PXqSyg==Hbms@)CJtf7rJnXon|*x8x6<)*o? zy2HF=b=33vP)>$~Ki(mxh6d!8^NPBA>E1f-B03tli~69d64iYj&@?6B^rBx;1=iAQ z!u1vX@6q_+jG09C+qKs6tr$HW8=(61!Wqv!8}pph050t1{avR6-mjyg7i%ys>rAAH zK4Q`lgBInYdt>Ouc3{r8a&6W2X-2vpB`P;(($6c4GxW+&Iek3vdRr!pjX0YLhyS#L z8;;uIt~W?xV_vm zPTMdZpJ}6k&OYy0nv$;9#$5)H)%uk6w2tf;8J%OK!VThSMd8J=t86~0d3i8iU%8AoTD`A%`*s_0b-O}DLNe)~ zvmS&jS4i8jL+~{6=KB5zitxzpV)Zo9X!Y%PhpMSrKXshmFkquoMc1#R-BwqqtK}n$Lq;yfy4*WKu=XS2GZXAtov>v^#d%um< z3b{qyx45Rml7hK!*16v`>76PgRh2q8PqQ8~5FK@?Kje(adFfaBR1iAoAj0 z>q@3`a%{f5QmPfU@wgyvWZ3OC7n3@9-RJT=tBn-K<`R1ASw>pE+&PAyy3dzZNrAjt;EmJ;n>W`U2k1mKYD+Hcophzp_zQl>$XvWm>+zql*l}y}C{LbP&MrdBf_Q>m(lU6bHpA+j^ zlH%MXnXJpYTsql?xSYO5+rd2KsWuiOHWQoMkQjFex+DLca4Kx)!ah~6W*Rw!Bm%r?E zf4bNtpKNlzAn zb8gu^^3liM$mcRXooQ~9TMQcXlRGoD>%AXFa&?QJY$}G$TJG|~H!E;U+yZtZ9Ok#RRrhyqFYI)c!RjWoBew^USHo%AwSzW- z%bv`?5RRfIGi%u0vOZO8o4HbOA=f3F%Scnx7!UI%GjII_?L@1ah?6ig(T>{`a-!-c z!fDl{zF{4lwvOO)t4j{g0|}39g0z8+Rv<`t?KV!2elm=$3GaB2wuv?LL0~>h8T+ft z#XwnHE;mZx6(!mbD`!l{&gvTRDk!P{ZLi!E{b7A0x{bhG(A5#L4R9{DUMDk%gZ)?{ z^LD`FDwOU;B7K>W@#L1Poq5@*p>Ee@8V~>l)@3skeHiv`XFTXBX4@ouY2bz<+gU#R zmHW8J(r#eU?Xd#_`}}}ryD>sIx7(rHpuuXKb#vqY;#+1hvJBVXBI;Wxl&?T_yZH?(#H@`FbX#-ihY%hZoy1=e?8Ob{{DzadwrC4_j8hn=DPJdFW0s z2U=sFVz6bP8pYa^+qkTfKGnJZO68 z!^NC(-EoULIi?rTy79d1@`1hZF2_HP*k${%Lk8$~h{;pi;N-a_FC~=&9)7Kz?D#t$ z^*Fo3t~UQ0HtU%G1TO;?);@~=b$x@R>N4g7gj765K9e48VJCpk1~JnZ#&Oec0{ZRg zBQyvPe7>{2j{vN?hoBewF^2L8fq}QBhHxWOPo`ke9UwzOz7SBV zL5a?NsN!4@Zx+S*u=j4hI{-t7?f`0!(wq4i^iH@h)2 z>(C^*#^Q0#inDZhcN@5VO4rmddS52n;_2kfO{(8~(VIfy=c^D;v~BxmaL9m!Xk!{Z zzg6A1w;5%#vq&0)DC(Y|)eM_nq>0g?&kNE3+9W&uGHSMEBeY!x%8Z!~46m#HG9ZZ} zg&s81e{agRxZUCD2)8>CN>UiiBv|86C08}6-YQ>$vngh^j- z$G7$`-cRgd9ixVu?w9v?@3TXKqO^-wBd}sQnb|~fnN89C8jpw*t;^W`_l-@VN#NwE zedt(6XHS6@cMAZEI!zvZu*w24qCs&c`5HP(2ch%R95d%zwdjBWY&@oJxYeBPtr>5p zva9Ebm$PJf*6z8pQ48BwvueTdaCy!aN5GkSoj1a@tg+fQaCTXa?2HU?_3S%8JDCkj znCEz#E^G?Ecmcnf?G$oo(;EIEm`;vdtk71Qt1Vu*eR#f#{45MGTuZ%|-{emtj?(hT zleSvxc|wjWB-wKF977hXE9MYZqYX+e^R_pmnKo(|@!xanF>5Y&SfG5uq&}!nNbA|5 zl`8^q(sAkXmv9KDK|fu~bMo3vA^#aH^v=hR9Xz1uv`G@V88pLVVGYv$Sy3l28V*e4 z7%+9_N<@C$G=R{@>7SEq~ZWJiGR(y_3=8C0n1N!Du*3gwAun(l(zYhG! zU_<}i^0Hh4*WqTW+zwD=%0ldHO&^p@(}nMU%xd=#Fb~@lGxYI@HmnqQ<%=|x7fgWjHvJx+Pgb2Kdp!v`G~TMd zEz24MDNTGJ%%U1n)8QuU&6z5u_uLIKsYX{5iP*7SCO6(`zBS^gfT8H%N;ET0N*UtV z!9&S7MEn&<9Kivyp7=r`!fg*{zV@{PPHO^{<|HHc*btD``Mz`YGxA`gCu~5=CpGE5 zdSb;_d^6bZOpVZ+a&R}US9ToKT`@Kw zPaaC^&OC*;%3>KeF6j*e3E$0JrGI>$qpDP>Z<;Io$nH1?v4|ngHe0Up&t{inW#gk> z((xORMIl)Uc`gR~4aE+1eAZ-9l|9|HPdF;#i8Mg$;6u;#ehQ-M{hU*mPN7eF0aM|! z1%U{pm4LS7sPVI1AVHx}gMg#oXc30K&2COo(nUP0&x-nCCQkAvKc=Hg&|7ATY~=VR zRsn+wF4%q`uc|>`_``W0YN{K>=Ptr=sn3V#60-eW+5GrD|FzRdg_e1-xK62B*I#&Q zpU({;!E``i-wF;c>}@bVPMkCO*Y&WfFC%IMhiaN4Q{5MGNv_O%SDIf@NY>`Xx5Jf> zLIU_en+*sXto2?ad74ap!o{;Et4z+);XP%6NCX!65^&Lyw4ei^^dXz4V9J?2Fm@6S~o4Kg18^mI@N6SJ+% z%0DC{x^F3<8Y$oh>FdL%I=3HZk_J%nWi* zCHX;cJ%tb^48RkxfY{kCTtzPE%o^zxSj((Qqn>j3TPKLMPx<0i8bea}3WQ-RRRmC$ z{Z)2|rc$yog>CbA5`pRcge$g|Fr1cO(>8Dor|io@8l`n1o9WM$Oz;QD;x=3`W7vIU z<122kKKF>@D%Im6Df?FR#Q9CBU^Y9w(P{MKiidMcOC{GP$&wRh=RAJtwm{9abDz`s z5qz~&dABW9Oq;wb{&uYmP02I~FHzEMoxqYIu-VYt(!QWDi8jTSKcaxvGrsf;ClYl+ zSP76_%Nlc?WfYUNdB8pB;~<`f&V6sF>sLhv>zK!Qv4tD#rb=aEtNL>WR~g?oRtEO2 zElX=g*)OQkMh&uRrZ7~h1T+pEf}g(db#t(1#Q(kG;eE906lv>w!=@=hMG4&rT!AZ! zfGP^w5i|^;7|ho^TUV!5rsR`K2oT`M7AB!&uM(y)d6kZ)&m^KQ-ZIy-BpIoX|G|}! zjlw-kW5=XN^BM1iFa}<=?C6sP=Jb0AFDT~bOkjHXIrO!|Lnah&Tx{nrdR&Q7jbZz$ zNqM;=%|onvROpZ~^~U}niRo2>?a(3nwPZvGElkT6*^>DE z62AnEm}CWprpk+(2+lR7a~^ZEJ6VT-v{nw!diMmK%;P;*tKU%;s!j%RUj^JoG3Na$ zLlTq-57M>N;;$DHl$5C9l8W>r$qTz*UqC`7kR;yZ7@hO05Z4kqDw+(cWePfJy9ZP! z0(MAB6ZgIeihu1m>q;%)eup=V8u1I4$bWv(i*Uf(8vTJIG1n-y@U_T!*#VP7bI-PP z%dz!Yo>FaG9P@|9dhmUCTHo8{8)vBnmGdnmU(OCnMZ%_ryZ=eIyK$wR*rUDv3MLh% zCTnr&ⅈI9G2bk(NA3I-GKe3bpRB%_!6sktroE89 z^5QDzL4BxlG}OtLw>cS3Z~tAMV`hD1y(^3cT1_;T7TJ4}v6SgM7Y`hs+ z%oI&Ahe{Dth=T<=A_h%0@H%$v32|TCWD072-8-&555pW_lhlP@!E*!f<|AI#rc=bA z!W@TgUYlK{Lb_kKL4u&hAh#jNEXE&)1kZimNSe(Rb@rnhn4 zHo%eNmRnwNE8+n7FX3))Z*?0kmG3BJ@Fmmcolf+rjbrP5Z~!QX!mve@8> zH)MdK?euy*&CXWWzN8pvbo5S<%wKtS+HT=KZ1VqIPQbMEGOh$aE2@dg(x(k0I%@Bd zvYWX*y+V9oPF3GRr&gOYdRuk; zF^8-Aj1(w>+s6h?x}*(m@tY!cpEEIQl^t5Gx}elPU#R8G6?>jKo>V33EJH9N)vgsx zT*i46dhVisV)--5jkvYCzP-ayUBYQ8>BJT>$JQ)`Z~X$i`mFzmZ`gl)z@_m531yEH z!mF#fPi(!!9;KxtyIIqSpA?kkODxq_sx70-O<-mX2W0eEwMbJJ!y>)IUCD(ix^H=FH)Ni;TfyGktU>YS~cdCB&-n3ELJ zhrRnWDF50X;5Fro=+?)LxK6jrxv}FJfsK;}{Iqj^lR<4UlRTbSuD~vsGRJmyLu5o7 z?ZR~a`*Qh?P>FZIY`RJ7h_sjxQC2xb%B?>RZWf~<5U-;&#g6k`PukV|o7OYa=1NuYbcz@S1$jtRuPF9j*L%HD5ZC{Uo#iHmgo zpd&&WH(xFOc+;6mV6L=W_820O7^cW!g@p?g_y>JTBqf-G@JYTmZ`R4><_AQd7*!vQgrkp-9h8d@PD3-xZYuN}1X#^p2_T!zF0gFE z&(GQl+NCD{rcg^b{00d3(hrx9~xZok8TBc(e)uMO1urPX@;N1ObV2DS7D_Sact=!Cv5 zyGhhp$(QiCBj;+U9nl)GCf(Ln@rxCFI9fCRfpcz)yYu)mwh0^?S|m{ToRC`%t(oO# zF4GYHi!$Z@j&zE7K6qS+LB8Td(D^LeI+av$vo}n;()?2Sx^U|6J!Ys`-Enn>v#Q*U z;2oeE9p`MIM#QN{KYq1LANtqX@kWfIlq-PO8b|QAS>%QW@U$MWHj6s%`n{~_D%qtL zGZ4r-ztvazfm*bcipE^pEu+Na>dO?~MR<$qNUWwKgtV?9>I4_k3p*y78U4omfWKFF zfV)l&0u~i~UBam=!8^5dgb1g72$3O7>9CL$tPthmHd3Tgj@U`egHDuYfQT^;*{O3~ zg(AvAQIqMW7U_zXo^{=&CM_d88#6{O}r(qX4JyvB7TClU(FVhi&+Ud+wS z^bNl2q#%qAH`)U_lXkdL{Tgxgd8)eVnx#7`lpJSOgu@zwjD%C+FWMXm!c;qMZ{uf{Lm_;o+gr@$+Ub{$kh1Hyr%+va6V$bxZ zI{pg>t)NW^A6%9$2-O$C?1%~cuK%pKtrVi(uT!_&fU?b!oh_=S84vnXZTY2pf`4@#0zSiYRu zsQXhG_tIE$`_tb7mtBgRoCULydKDLVATNR5BuM-h*>P#6U{EC7l6t%;ZO(U4(|n(6 zZ9K?WC}7~U#R7UxWmgkZ5IHyY#ZGG*ln|>^_|QwN^K%;}TlN>ZLQ5~*?kmb#yEZG=5JEA~%Xt&igC{+(@mYV3I1p`@h-`k^m!q2c=EF;8D3EL`}w zW$RiK7uT1BH%|2V_e$3|i{A?My>nVS%qM|x%AWyHe_(u|P31|&Qr9eJuk>9eI<#)M zsjoaAxd#v_2@m1TPFOJz-y26uo+uLN!2LX>tOW}wvnDO8lFJl1*3 z!#c|=RXGhfi%dS7?Y-)P-IP(Ou-2$C2yDfFOsf>g&wML4EZuZ?^h`>rlY2r8?6ZH$=5r2WfzC?R+lVHNk^qo*%NiW(oG7 z`}}yenseB>ps7uZItleWz}?27gli{@aOkohU0Q%?%$gBJ(w?zei2!Vzw$+h#am_d$Fs4u@Uac$uS6Ou9 z5b1?4lRKVy9ZNjZr004ACtuB`kqc(yL6i1H$E|hXxJ<-c)bM>Fnw>AN`2qa)1T(A3 z>Tm?4<%~!`&uDTP;kEz}F4>g;O*z;5n2fVK(7x8}a7gtP>KB;tL`kjL0oEFK z?Ko6YAJQV$a-hzw6qI?3)Kua{Mvn8(Eoa5n>^jdonREb3MW*$hA9Rv&F-Z?Bv&E{S z7dq%u5W_CCO#$IEk8a3Yz_KXk?uO2_?(-;M)H*U158?D??BK*Ea7e`=Q@o((NdzF1 zP(`F&bi4&(7$SAN#q$N4QagB7Q;MBNfrE40XQDYVfr?E58aKD{+YQO#DFBnwt>q`j z=W^j*J#wuPjWT3ZK(&!xn(FbCfui#szdisuKs%&@iQ>nyZ0oC@ zQ*;$tN4Q(|IK*^^pknV?*3g?$u%b*;1u6Wqhdi%{uLM0(bDQ7`?dNLK9=+70Ip!sz zL${5exxIWTIazaeIoeU##OGGwgx`MIW@u&VTEo^yh_L;kYc{cto2mJH?|=sxxDH^` z5F8>+mOCLZ^=IeF9G+@an0qk0ie%qNAB;>%d42HqgtbPm`mTFsrn~+r6ly}|)=0Yr zazH$Bwe9k^Nus}_xyZXV9W^EsRX8Se=0Q@R*(QQX_e{G=Hm_2(f6fbE0X+?Bf;f|b zn|Y3W5_OA?RtsK&9PI6SXQv%B;$)UTjldq-l9HDOqN5h3^>a>{#emYBCSyd<2-Cr! zz(xV}NM-FfrWvxYmgjNyM~aWe2j=EjQDc`1UX{VEtR2-SkT(yHPem0L;8UAxTee;Y zO!<<7Ag>mcQtxGvWY~oL669AE{paYM+H^sipuAi~O1|U7sU3n3*pK@(Xvi05J&&anQ0VbP12zp z?giA56=H;L`AHKdvHEw_@UwwTn{&z36Pi8gFo!p$e8l>lD#??TTvW+(rrBN-*QkSQ z1xmyp_zr-IY=~?}^{}6ZUM-L(qnapyXK*1hvYew+k=>NtWNm^1MMR7Kgc^l^0S0;X zM9M$T$}1~LfBs?5oK3^9Ip;e&LZ=P&NdGWkYRE+&CBl=#hnF=>ja~Jf4XMuXN=-cH z&j(_GxYS>mmM%rI+<+Sw{laQ5dTj6t5!gs5mI{eK;c46Pp`Xh3+#_1xs;s`8!~aD| zTz;4EnP4>3FVK@qs4W&s!dGDtHJazgiP6;giS1e`KyMI~tW7?OvHN%r5ib&gU_ZT} zS4n_RrMs*Y$^OZC2~>5jP4LWlqW$jvo~`$8HK6%ei7|?5M2F_g%&4-i2~n+$oolb^ z1)rUBh#`*aQ^lkhPi545=>V?)fqow#I#0JPJ1iI`q>e$EtIB{ub+9Qu0=XY9U;DW% zT~04%2YxKG-lJ-I4y zA7ioH7B;U_zxMnf&!V^tAErYA(1|wgxvWpVa(CG!qUw4jd2g<7)^wR94Zh;PdBrifGVAP^DTz`ijQCUfaqmSh;?sk`q|oK0TMNd1rh1Drr( zzrww829cvku@VRsyS7*;;)X&6im&mhw9E|v6d#upZ+FGYQW?-0n{z5wJXAMUp@M50 z=C(AqXQgcy0J{pjhH=%4ah=sCu;?PK%zC&oxzb;m=WCZgBP$5y6n1$lMBc{#13xP~ z?ef0ik(w^Z09r_@J%hWm+u(y2t6%2O_p|X8SpNIyLSY+&Q!a%1T$QI760fR z_>Rh(pVQp9&YMefFV~&VNYfn1&|Ta7xv;KPrSZD5w5i=i@4d5H!b5vP6yP|Zj>~$- zR<0l8-j>e1Kh##vgZX_Ob*e!1z6{;6(Zg{*2|Kz~d9Wbps>|l$5n2q_q5;nLmQH6b z{+5kiDJ$v-Y2I^Zm4tWh2~s_`Gf?fx6r|a;#zk&J3DFWr=i(988)d~iaXy>*9_krr z4Hl+Z-K5In=eoFYt()F+M@YgwJN%~l;j(ThE-T)-b4@ZU|5f=Lx9hzq?kua%pyS zL20S-fI9rK`>Q3*?)CZpJ3etaw@F+%gn}+PPY4AIRC(yk`KZJP0xn8roRm&Ga*7qV zalrgiFgg6Z{2d-k(hM_2TB*{~borUPx3gkpsb{L#9a4Wy0Zm@m>=mqJ==Q3#TLl`+ z*bf%pt#ry|%*;x_97S@w9aK}L__ac;%(~FIx%{~*v+QL)cI`tK^a>W%^0_Pc)oTQUS1Dmk+x)%oQ~BZ*$!B4r59Bwm`VL@XVTP2{>0}*?>lW zJ2iX>C~4XChRe{f)m3g$tT>rD?i-HNne!3y``r`>cqx@~P%=f7NM$LRM1Yb73Ko-+ z#c&Unh$}0XxiCHUiu{Fz%3CL939fm7riS8!{pP~eaQQVC?zycY7jW3QMtiGI;_l{f z+f9WBDBgX$ibv?+=QJAYJ-K(?c}w9zWq60WS5IB0vNqP|>knstxV5H%aceG31Fc(= z-%;Gi&uQQgc5|8=chuz4Y~Pd@mR5yaxjZAdOli7T<=?$_Oj1&8Mq5k1ew!N$`&v~#e)%a`EQ&mNd6=yb;Xpux%sP zj}gCXYrgFY+Pm6a*xuW!`5X9F9o@jc&Cu}(=K5*pI=%Z=j^}XO?ph<(Xa^%6A!xEf zGuJ5u*k;_y@6c(?;~3x3Xs9i$Q^}W+rm-PkzJ|K|b117B`gw#}QyVq#xYKB;FHCbI z_f4H<)B2Fa!Lp?>l&3%Kjh>vc4sONZ66;zATzx@c0zE^p+DlJ9J1+6<%}%D_95VRp zkVD~Ov01sd6bxVZy8PXLaE3Atrzlm-eeQDO?WkB;szN31&X1dG9%y!JsNl-Ot{o5n z{kMWe!d#hG2Il#A*|AK;(XUzDtClGfD+%*d$hM6k+PpqUYgYLw6mlACF$YaeZO?-`HTbP|Q=5WyF>H(#prxsRwO|BEg8e_Hgayd_F8_Rb;LP{5FSc z5<27Nzw-q^|1A&ZROJLf|E-_`jkqr_d%4!IY=_k^LX30mOMdK;mrPbLC*b}|3p=qJ z`Kf0|!1vyUz3isEKMMW@!^S&;tK+Xnl zH^oYHi932`e0gQ@bqRC>bEsf>aUImJR>DI7yi{OQf~I-P@xJa(HAl5IgU4Qa1*`WE zt?wy++~0mvO%Xj^7Fb@H%bRKQ(B*;o!&ko3V!fuz+R?i7KC;26uhwSnD=1DGMM561 zK`Nbg)6hg0jZ8N4+^yC-eS`6w7lNh0<95gx$Yve6@|FXnLEfrEZmO+X`kL>??ekgT z7FQZvrxu{hdcF2hZb9`kORNg5GgY6E76KG#eqBoPlTyyM`UPzZrxK z@n3$s{LNB*V-K}<>@?n33|Og*5B@+DDgXF`VHzAuilqv6n74tMF9Rz@p#nwFgmH#L zmDfRgcIJ2LUmS?h+5QB9r(V_KrPYQ72X?N%`qqqSPpf!+aO3uxoP|OEV2n=nCFER^ zjz$lyU9BuV@SWE<4Se2*cS{uXoXgwQAQru>Z&m&BU@4;51v;hs1&jKsgVdj>*oSmRcumUY}oJ zym@q1rQt^<4KHE<^!o!Rqtf%5svNX!bKd&l(1|cjgfrylM>nqxQeBN&6e7)AMw!7r)5vs&yj+ZpYy3IO92`i#|9C|Dp*79%vk@AeOiMeg@ABsqcd#OO<7k-D z+=r{YS=zm$M&f}}=OZ*Qo|bl4-R7lL?W$iviTK)~SxO;|CrdY((ww^(ql=>{Ik%;& z*;CNoNR!Msq<*$<4CSn6#wL=|4nSjw>&Ijbbo3Myj@))|TehVt*WN=T2|9TxDecf) z<6!r7w39eJlcUzs4HuU8C$i5@96iz6&T$_3VIm?=v z*)$zI6_YWJvhLoIuhY}#qtrj1QSQW=-CR~xKcEG#9S%!b>$vzkIo}$`&qQgM+fLP~ zCts%!o*QZ4wrtmyP`+;)WmRqG%UKu2Vi|h#cvRXU#Cf}6TUBlh_4dW+!f;xcNw}CR zC@X&_l0tbh1?4&08>7B4Ri2Ip7p?79ZHIC9#-T99(+;Vht?L4$Et+sC@?4HxxEsAvyBFZ6VhIA5ji#-rCV;SVVdHgp>Y?N8-;LCBs@ktcK;Z;+~o^D z%sBGmC*|*}`)BC&lPMW<7}w}a^VZ`s1K)%7W;mjh{u($d$ITttY;9+U;qfF548`f< z6we3qgpn}!y?mD}8%dtxpb)`dD{v&yxe224llI>9-n@3ipIGfKnEtq z6HGe-65q>nGSbW@o#c0z(r}-6{QcC8lWGtU%oaeTEJij1K z(4CRK+0p8iGzX4GsBbtabTS!B@*Ksy!r7>VfsrIlB{+?%FwHCbXL&rQD8b`7Wlb}b zpotjgjcMT!_zoi;0c{uOG}&aTAWc8hjER^-+%=9d-*MtxKF#E8hGN_fu54kNivtOo z;xtfBk8?Zdc!ViV6Xi5MZU=Lk^Oxe%-e|k&slqfkmr1vGZ+~GL%$K0yXz$bKW4U{y z6DbO(oaD)*3eudp5R)_j+FPf|Fi*Up$4`5Y#ORT`t7&*N$$fBI?%_KVVMRdD-nx$r za@!o`eucL4IWp8YkpB+acbNMK_{5vH1?Yz_O-X;kJ>+f5Xm4|xv%PVtQ`O$7T;3+8 zd3-RB_42_O-MgoX$9R^WdVWIg;Tg1DzP$r{MmgGRl1GER=9^*j0YPBBm4$vl_z-y>nVIG8Zn zE+uOOzuzh2?nf_A=GuF5JWl%#&Px4kS|4PZkfoCslXUy8pv)it{QXh6cZvJe46|Dp zt1<5LYnZ3Ny5-clnA8K>8{g^e<9su}f?#g%$qDok#B<*HUapU1xnG&mNMGdk23440 zzFDPF0c|lI=lbFPdlCK0k_O{DGGovlF6RKZ!6D{trzDNh-uyiJ7p&n=a+^=gWazFN zLsE{H-rzpR_lNjC+Rn>qa42vyuP0EaFTXKEBh0&~_D+c_Pdtxx9uy>dk492jUzKC$(^yUt#{O zuGULi*7#`en=`bZ)8YOEzYl4A+)C%UFJio*e#WO#bmBss*B{(=lgxjjkMi?XRal>T zrG7m8;Fb*`;fH?o@)Y+Go*TH2pzUTR)jqN^^w! zFnIh~q~Uh(c-*|sQFA`}1lE+G&Qm-GK(?Xp9XcMSNv2C~zPP~c)x+xo%(+-cUl`>2 zW?CEOIRI;<`dXC+{QjY{yzXbh(#vUdy`hg`45_wDa=%jJ3PHEGhv%nD14x5=kz5*# z)yNcR6rNZ2q`f(BUZx{xZyk?5GQ)iYYnJ#d`c*#7AT|W?cd$Nm^Fp<;UhyN~l}34N z#b9k7Nyt0QX_y=lmyQOdkEnQrX>Qvnr%6W>)Y9yea~AQwXJ4HZI*Ya&8P4YoVTQ|t zH5et5iuRx$IP@`}jJ6YTn4efw5PVQG1F6G~cG-`Y^Z(*Vd2&2s7BMs&N^bsA8dJl6y zMtjdPKcd<@{~fe9XfxzkI$qHPZf~yB*la${$$~UIzWefNbbCwN@j^i880QnNr!gl_ zqyJ*w=#MfT^vPIx?3poX2ee&+zk|H4=?d~UlJxq)8EHF=)#{*Ayf~m84)D9cGotMh z;RGdkEH&|3`T4z5be8KEeFTF8?cKd9#Pm8T^hdY1Bb}!8;K7kM?rX2U3H}^ORGO}i zAVp(odg8fp3P;nq_MYWuTA9Y69~?gumbL@HU+6gvb35u@+B=n`vlmp|_<63txZKP9 zabu&OHgtIAR@pqaUgB0+o^}{nSPB5KSb1`^}+FC#JFGSyadMua5kxJ7D z)6VWrugtqBk8bbCOp?$XxIq71B=GGf<{7+>q@rmHMBBT6+xWHe;0T9})y!4Ek-a}lUw-TeGr}=u zprgXTZ`oKS%;=J^s1nVe2v#S@PR}yq#mrHd8I~F+{qBF*D1yW{ctJMEj5@Pf%x*$x ziN73}$m_pO{zh}#Ci?i#{-g26LWHLd(YZsvDZgKSeT=^OEDv^Oh#`2seNVk8MoJ;q z*O>?}ze1(V3bi~2WzbpU{F%0pgMRT-UGf`vdEW#*#S0h+(r?=qBDkpnP{)7z#Xcr* zJXwT@e)`8cbGw<|cx#fr|LTmKsdCfCfGD+qG}q6cbDC);+ATq%PkpG}5bkD~d7h^4 zyfiJ7;LV$mrcu%WfBEHp8e_(?brLM zeLa;bw7N24JH4(&H0CAhvb6=>zX-m3ZLqzcE04oCar0eE40Q#@M;v#|!Z< ze0NMHmrbos`q=yRA=X*?%D0E;%uq_sVR`?9jX5O*()?de1LD@x;Gj=^q(kCS_y7F( zFdgB=GSe!0&%JfDp+_kcMwuD@+kY7mLMCZGoIfo4TThMBq4Nn*PCR@^ZBB6krt5Rx z7?KICEtH|3`@|}V2fqKKQQChxA!n-Gy(=W{w}2Q=`hW42L7C8S2FlNWqEq65A2LJ# z^0AnlsdD?40Jpbt*@pK1^DhqyW6{86{qgrS%R&n{$xOmGo}Cs(ePfG*KK8ygi3h&% z{b4%MpO!O2e&U0zvfu^YIx<7weI+c64|cR!%|74X+zAEe&Ie?pjqwqTm;$7lz} zgY{P-n!z9TouBfPeATA!djiw5C4G{WM>mZ#_9ihq>(_pt*ZjfNs4}DIjC< z41M+=hmHEl&`*A_C0Eu1M`!7KTvlnj+pB5oM%CUElS%sfZ;eSi;B1?p`ee@>7YggAbA7xGyOcwWzecy6w5 zV;o#DRa$Z(yfIW4cz63T6Kh}qB%*)hC`iNyefOsTYsYHD2M_hh&) zt94f?V8a!Z*k^mA(x;@ZhT~FKc38JMDD{oHLI1SQ^|jR=;X`ztKzIon-Zxmx7XYB! z+GS}e{^4?Ad?G1AO-yC5E=K#ntufXe$P?-USZcno25mF?72ad6+trd7=G+`m=>Iew^03hgJO4)9^MPoNdGB} z)4;pnxdwBM2Ks52F&>4+4it_LD0Q$6;R5s1W`u$sp2yvamo>&cHl>3efVM!s0-9o% zkCtXXug`c+W4<1=s#Jb~)|LQO8~ao7yg6?j?E&%1V68Wg$Hjb_w`ksVxty|L1ML9% zV4lBq8qK4aVa~7l`%qXyaRNX=Xr7as8ht!pJB#9VUjQ#}{{C8HGZx}QL8mBIbUy0q zd`$oB=}FVj5YRGbgp*m?)E1;FM?^Lf zFBH4}zp(LZ? z0Z#WOXg1*xVKwH5tEo@{AcR}2E3kM?6;1YZQOfTVOOUnoT%I-ueP~ZB-M5IIE!6NM#2SPr6^R;Uto#3B7p8vDqIa*t?yRwwgv>6T1cR2 z=|TZvuvW}yKw$`>SyQ8jZrW8%yNr1PLO9T7SkB|jxSMvWdziamiN90<;*|u1!%)^) z=bps^^$4X24whdodIZHT6cMpll)}-tC{!TenT-Z18V^u7;-G;MD3TY?M57Lx8XTff z0nf1*)KujK;#TNB0pXwBT(6;p*yvw#Jqt^Mgz?T&{KMq{gm~C-UKMo9nVS#Y+d#MP zsg-s|--qH}D+;b;zLpB`oCwPSv%nIHT66iaTVCIX@<%Ii0SHdb{GPrKJ{5vX-G?BP zz&-Sjg@(D>;!=NHgu=)NHlvP=CgnGFonLL3H>0#RFRf2O{uF-cYMHNKWfx)w-pkyao6Cn?EIOp4bn=b?cGJA{flm<6@9yudKu(?GvB$D7l@QptQz1LGb7-IBnqxxxwnggjXM zRzh*W?r#9}V7`U3xqn#uh>kPU71TTWoE^~j?DAt5@E$whyH+|j-+RsZHUsiUq}6p` z9vd36Thp{79?yZ6mV{*t;CToWGFcCgZIurQE%4szkc&314NxEu;^!0{f`t!g!0<>y z%Ifp0dr+*P-EjX}K_=@J&jt|w&WBRM76_`e;1%v%YB;Rvg4-nf{;?Q9=mpCI%!hi% ztlOm~5v=jBqZpPVW`TCOz`HNP)z5TNEcpgUN?STvfpHXzr=_o`eg_vg#X@YjT`~*B z^K-ol*Z_!nL_FRDg&u^o=Er1OL;LmQpp+@E(T47&0}DsHq(2AE0mWq5zDH zCxjjYprvqc2B3cpayvq?nB?EsWZl?YL$$R*5k8w~H~JZ1*T(?NH~M)!eg=l3Jnk|S zOEAyG^ESQ*i$l;TyazOMd@3nQVdUWqw~w|?0o_6$(@IZ_SLCg}p<2d(E*r{)@m*^3 z1n9O>F6Wh}4LEOwyBu6<4)XkhK4e}qEEHJ(V+^7XLSbZ8+%5!d{4Vs(3l}4z3<3Y5 zX&LImZ1HY}xgYB`${6mu>gt2k&{Qi*7P&UYRw>tCKr~o}*~b+Cx*d)|fC6QT*#I0w zk7hQCxNsohq7%P8;e;^$ss$qx*BYRRfVmt9K~qPN{`~V7=r8~7yby@>U0J$+Plh)2 zILXfo6}OKGt~W&F3K>=`0Xlc#C>=ZeI1TlFnGV1BC`}AKE$9*Dkubmw(wsMArL|-;n=kb_zH(lY$tQ_ z!748e&N}Gl|Kkbqxmz8~(4H*`+O;7?Fa79`Xm)0xcuq9J^w@qn{pNq7W3T+Q9852Q zx6u?m`G#Wf;i?b^!*&>M09FD@2_VW*tXQ#&`ix`%KH^OMsRp!)WAP*uY%l+F~kry1yb zCKv+Koj0r#~i1I{2USLmsQW^mVvey?4Bq2G1!y3rgo zJvX~p#QGBV;D!%M3wZBD|1~RC#KohbSb@7DvyuZsD%9b8iWNm;-SR%T46_@12s~+P5v_O{+^uz4h%c@vGyOyU| z!SfEjuPnHgV#VIQUb#SCu--EB7%mH-;cTDKh z+qcw6-cT19|M=b1;1&1ws2jLQ+P=Ap9=f-YZojFP_Ux|?ut|ri5a84`S z+|3%U()4-+3Ir%oK+{nt09@FC4#U+t#sJ)B;iP0J!+N>`V*NQd920?k$d{ym7d(S< zXNu>~_C|AxywQn-C_>Qg_^lN*N~s*@e87@K<)x*iis~Awq;KPSD9YiEZR6Sy$0?q9 z*S2br^TF~F^h&#dTfZhK?GwiwGNQ&oy=sVgsamFRvZ@A17$+u$wn(y zT2_VVnZ1+r|9s|{oZ*2Tw(D1A=p8qw>Au}*x@||6ZrtLc-CI3$^G+WI^fY6NPFwd^w+6B(GfiMdU zUNGb#Pfd`1^S_^`FMMr47I+Oc8QQ*Pf=;~hF*^DBzoGMo|4_o21HVnjUilf?|KvS% z>WyEcso@vpeQzF`p+EdwKmG9+M+^MIVpr`-Ln#5o!WAnkn=6E31+Ku#QLIc`4yeD< zU>3nvp`zQWf(n)k5TZkHhVc)D3i=$*DnY;k7Rm|$XFve+ow=l86)53AR0to?e?eEU z;4UQuF9oEB@&oyTFa&wSE_Uqp$C%NI6$qEg0R+VW1Q^IG@&@4n7V)|chDKA=+>k#{ z!i>c#R*=_hI?8{OMx#7vCp@#ZJ5W}DGR- z^y`HHa|1R$VCOyR1{?JKejn37hbZXL@o*l^`ks)`Ez}Vd45;t*JwdUELn~XuN(Igs znVC%rjYwux8>1|!S8U9HV(Pv->ctuZZG%mJun2-o4N9gv_S8z9K@r`?^T(DAAyLSJ z7WVVJg8qziKG4TNLotswH>&SI*@5d`u_R21l0+0V+%KU70l+UHZNQhIfCn@;!|#jA zxnPjf;p`8%U<0j3-`}~VO6KGBYpOVZZkc2IrG3D21!$VbCh~@OoF9dE;TzcWUCU*? z>y|pY@Ai7Ct5zKoZHs=1xdY$4V^5ttvySsV!)f3i4&$q_AtVRFyPQgi35%J&Az1jR z@dJefrcul-z5P-CzSI60{wczwoM^fNWx;p%?y0U z+8TP|^$7jKe>z29{nn5yI)T}V12o?M0|`^ZFHm&mw2Eh@_0|1T^oO78qrdy!G>t`_ zG&`H7SN2U83CC9&=2EQS;PO&oxfhR@8^|tPfq|)=3nxd_f$di-K&Wf&GiW0$G%BcI zIe|qh#=TakV1cUp8g{iqC~*Fg+7$^Ju@q>_1ke?H6Fb=#3M{ITRtr$giWLaMp!5Ns zjh*=O0fHI`?6q5&CwF$qgiXQb-=n?1V_5hpx)*R z5CB0bQLa!P0<>}fAsfnrJe=!|i4bdYGC_m9uIxQMNf*yDpLJoDhKA!bFr<_#TA>Bl zDOOMqI^g;I{ro}WlT#{xxQD#P63V?D>KbDn@#uRfuU4#J9>M|LIzSPs`2;(~3dSME zON8t1Vqbm@i@t-tC4xjAqfk^r_=N-V(VwBLwc{i3PSm}))#3J#!{K?1g?wppJG1oq zfoVwxAtHD)D27Er%=yxNOXs(oHe3oI>?>1`yJ%pHTLDW3tCD+u#Y$cY41Rar>Ojsa zsFY#_0_v%mln9v@642h}ylBOWrd83XYWvpa0M*y|Dd5e@_ydq@u95D??gag=3M zyH8vm0os+))jG|t=~WsBWW79gb1t^jo?ap<+*!re@N2c z9UlI^8RqvRtZnbeePaiw9kcm{em{ag>!Tg(HqavvJW4njzO3brC zZZiPNB7e|N8FDKnBIqdR4Pyr1L3`mFwKX2vx~W>mAS_*AZG)kU`4HzeH`M#&U6(j7 zxCaFi@(un13KN$jNnUqG<^?D&pa6--`P=*qfY$3Dipjg7sDt$z(AEs=VYetlP-jry zBob-zxl^*qVUB}k5G-%?Vf5go;KB^$#6}J9f7qCg`E1|8 z87bf9^;NWPO@P8o!*L&F*{~M<+(lb9Rtqh__!yf=@NZ?|6*J}^%nztL^CpdQknmle z^%Uw1oA<)Zj+m`c(011>uI0SX17kY6PH=@AN-0*VsgV~**q!bVxT&!%KoOqh|JUDL zpb!82e)`E@eT#ngk5AGU{_zrh`I~+8m4EJ|Kl|JB^jm*?ivH*4`|0U@Ve02Wj~xT4 z6#O*ud-%Qcp<u>jMxp09r6- zR;WNg03KH>Q~=ytF6f2*LSYulK@bH22?WSkP?w`fu>!mB0lWwA!+Sut5l}DKaSz1` zgdL@nK$3RIVzC0n0EA(tF$3iS@{f76Zy-TK!_$%u77AELV0=OF(0eH+0!|1su%lK3 zf}0E69uPVpod}wlckp^$MRQEKZ3W>A$_#;YV?A8ccsLGqk(6~!Pq$x$7T8>2_G`Zw zz{mU87&f7){9A#%6ew1>2p0#`Mh>MM$*;2z*T?Ufo|@ow(})O$3WO^B6Nky8&I%PP z@p%J;!4MFYt5`wZK`Ew#9#>{S0El?B9ojV>OVRmb6B5RUA~ZY2Wf_mraNjJQIXp(a zXQpU;9Eu_(WYaJ!R^ZMHJF9gtD+n=uwS`a;W}1vp&`q^90rGPIq{6eF<%a??MrVZ|kvR1}rfk@OSgrz%J`U z$HU^5^~vYPBpqB4Vuv<%rbDTNUEZjFyiW`Bb$;h-!<7us69{xi$5V2y0qRWy0#9`RlChF;EZYOt~~p}kNzgT|Goc)#)kt%-_Y+za5y*6hd=xqv}O0dr!6=BTiVzjlQKXM z4|)OR2Kq4s`#^QIpBkHL$RAMiGVX)ci4v(UNcD}?Vj-gE1+KD&fS9wHXk9wVv z!_Jjh5>`}DkYJ+)&ZvoS-G-wM;agx8q|f@%eH-~gI#}4?-7QT4s^Wg`^Q1)qk>$8> zSSb;kxP9Q!25pG;QC}{638i%);1s3Ch90;|L!MG%{R6s#IScegTle67 zP_}@Vx#Q+K!dYfB;f$R5bn}fhFgTMjdMDFmSkXZ72?Yr@v`_PU0VsJu$G`*Nd@xvH zfhM4Crg$E7@=H=_Wyux{C|8o;MWZ}tW{IE6!b(rM=(7UPm5Xq7wef4|z!a;kQKmUW z`L{9cUPmad@9P1JTZvSV1DLE`TdQf?rs~|}4vlMdgO6Ift0)`v(3z1GJ-vULez13n z9_O(Cbd>s;p_yg^3L*v~146xXTMgZFTVrlvRtlm}>8mJIu1{Q_gyxz@rCF{n%pB}B zge@C_au{TziKhGfZk`|f6nDGna9@U=JCdL$_QmO`H{ z|NnR2TDxKnrY{HAg8-sjlv1orWapmCuQb4$V8Hu0;3gxB~!G-A_ z`lDHRZYRJ7tm$;H=3TqI0JK0F<(9y|v7m=w1ska50@6Z|q3a9jAVfr7%|gYtR%Jne zd}DW|zNh959EPrFFN6_F;F1T{Di9<>C}AEuSYP0s8s;`D2m0}Pp7S7(!gx<-ocvyg zxZ^^cSvj;=K;VOMKi4@T%JRTatY9v3IObHWppD?J3iY4OIwjvZaF)%A6(|wP31~ay zqg=%b{KQ`xjO7BXGR(mDkv}K`&~}lTq$pF8bNHf!g5}K7ahjb`3OzG)KSdwW0dXiJ z>J7imkg>pdXsmNlO(@M}$+xAhQ_yz26YE>Vq0Bl!VSzfaQ>?(UYS==)Nq+zU|MW>j zK~%6r!PvyEa46?O{*=5^=LLQ8Qh$slCe@+Z5MpANy(sJW87P{pz`7bPQ?ZL2!bQ9T ziW7XdrO8J(ZdXDvq=)+-oL7f;11O6gBg?|qa8d|i5w0{KbOap%UH1AR%q~=-n3WX^(~7wiD~kc>k+w{+Q>;J{jr8Fpq&!0sUj4G*QFn%F?^{}kpSFw+ig_W*h=*sTjjbGa1gxyhRgH~r;F*xx;<2F z5n}82Yq)*Y)ZD$zxKauOSheZ%G`!q*(2i3~Khd9Rcxe^zB+2Va@py-|144_DT0ro16F^|E;d}QiI%6YXc~5tqa@$(>b;Y=>% z59iHbV|ZJLAknk56bA#drEGx?RAiuw%&MWmjF&U>s z68*_3?)GH789?1b!GpT2tMQ8B6AGuPDIVWZY(n9@a2?@YI8tGFBqnVIMGfW!Gv8(g z-V4hfjP>T`YO1dBF`ZCKEA(qv$%utk6J)k{H}0jSyjJM5>B>P8TB$_>Rm)k(S)<_Z za$2LHXg0;G;4+~69&_Ddd3r6hwzu3^C#GdsOh9-6V1hCaRtyphY!Fuj5ELjo9=^Ys zna}xmk6u}YN||-DOap&@RLH{0Mx}kOJyhE4asxt!n{TM0-MnbW!rpwKE=VT?Ole-( zr=n!7GhU3 zU@?dV5f))^EihyV^vVSmmUs{NCk^bpgdoi-IIdv%0Skf2(HKpS6^00}21D))wbVdh zVLZ&J4`wCa8WQ2Sq%#YRA+Q=AR`J&0&GKTN({(iEg@Da7iObVOpRo+X5L=3{>e1FDa zsi2`y(3pjaP^<(3A@T&eDeF*zB_*g)a}N$+$32IuLE^N+MBnoU*HFe$Edmm}FP_NC zu22o^J}no>pC1pEm(q#FAJQ(?yPqBi$p-#;6 zveW6KVD&l*gt$)4%Vh3KTCoBJNjagtC9hb45(w)xDApDW?CgbtVSFM*8K!}KXQzxi z5OmsGKLJp>^q!s)#R}TkTuJD=5RB`f`?a}F%z%;sRsk4KP>|y~Cr~#jR$%=Dp9#pOG(=9fuRAGq7S%2YYKQyJF=k0dBI8@0Mmi)$$nfFs;e=1r-*f zSi!jox_tqwVg=Y|K-2rYxB|m}NCFBQf1h+m=ph0LnFr?1CsOI@7 z=u3)V`po%AZY)B!Vm?!-RDk;~xUhqgL6>!Y|ke(_GHI`={xLFHVTtX4DmS z_0NZJBuo!J_@F2{jvhTqANarr=p!Hb2z~H_AEZ}beU-Lu-C{hsc-(s1t#sdg_leR5 zikh2lx=H>%^w2}{7x89%>xq#9LA)q!IDpoiIv3%#WxB_G^v%OFbmT->=0jNP96uAG zt3K6w}Z0#JltJ&b!bwLxlZsueeA zfSLc-K-pnkf_VUa+v`q>)f(Odmu0YC!x=58S0Cc3l#!YK?N0*0qoko<%Sx1$6XELVq*Q8fW%=j zg9W~XTDKfbc>7H?^w7NxV&wuWm1`MT^kQCI+wGq-T#Et9N80?TWuNUzCasf*e z2;w2g#8`xY17o|&I1K!3Z%pos@F!UQn70G!p|#mVUVk(B{Pp~|rGyk=F2#yEj2N!3 zaLBJYPuXln>Lz#Uy#^NrJDJb+M&=DTuonmHLa~DUYS&qd1^N#9JuEDM)`m6oiBEij ze(I-wia!16Pt(Ug{&9Nmd*4ep+;Bs&f`!W*<$4IurfAAgZlRBr3L$@CMTWTU%=c5t zG({sR%BC|Ei(+?op<)H)6$J-`xv{hnl*=i+yN&r8yk~4Io>Q#AMVI*-aG`_q493S3 zxi~21ASBA?ryD`!0{Bw%hZ2dpEkG!}{=(4;J9836!2hL;t6 z&_AHg*Kv!|7D@!rEv!@QHvVRfe`Y|T@#la3=d^L-M!BAunGyNb*w|Qs)yh)w?6c2` zV&$Fhd?(e`){4RgmVVRI)1u5V!z?$`z}aRPzL=}tIx<5C4$nxtLUDw%K-?~;SYW{# z1Bbbzt&zs61OdbXi0cV`0v13=PenxG@y1&-(mydaaA5u66Ja{W_nv!YLX>l`9Jd3! z8`SYV)SI%1RdW^kHQJ&&r0!unBR^=6#se^>L z%Y%j2iacSJm0&O6%XnOhs=wMJua``!*i}TDas5eE}+~o z14;|@LyXPg(YVkfyh~dP!P;e-=K#=hSkL&~aq_xVd-#3D`~%((h0g@{^CKrCQl6LJ zm=eo10R0(ljrQ4pNY%p|2dBll2IaCMxWMJxT!+=8oK|ZTTrZG(lm(QexHOE*@U038 zk>{MRb*!+?f(3p@o1bpnUL#7DTM>5G(QO=V+F2{6a0^+i6e(2rPeq|p3fBhZD8Kb9 zsGt}yU%nE6@PEFQA(%QadRC;e%0-6;b_2!I`FCMq`gQ~sEHIUZ^$HX%=AitUn;Grv zhf+WQQ2^9HE59lf;2LKB%!-w1hZ4F}LOx*E8FrJdT^$gYcCfbE2UdYK*2pb#R}q)2Wwc{9iWy*FSl_<&V)dFV<$b{ zZzoJG4-k|yeKwV~9Aq4=G&?cP^eQE8ovcVEdA*b^j$aHgS6~AQXd37`WI<3CKmqyg z`y1)r+nIK7|Fz41ZMB;^+tfKr>sALvFkdeE`ufB&ObKx3d(zHlij^DUl-GNu%; z4n!ODbOksc0cjHrta5Pgh1VvQ!Mo$R72ms!0+}XBltfD#_?dZH%bSbV{@ykY$LWLm;6(*!Q=JF_1%B-6bk6||vc54Bx zA%`$E8dFU0ddJfgV7l1K3_G;$8YlY_qQPxup1zGIHT`-J*9&85f`Yoe&Z&Gy8aGe# z0vH6V$w;FCVtsBjP2i0?>z(xBN82QRY%)P#|G}vE!EXoN&uP`y7(&Aey_V+LR%Jw2QjjekopOHHP-Uf@MB($xC0v|~evZrNQc z@vpx*NiQ6V%I~&Z8kL6uUSy1M)m3|Wp;w>(4t9*38cd6J8)+VWsD)~Il0*DgzdJ;u zVH|`)YyEWBEy{Q4sk0G!;?-$N@|bK5W(vwP%xOkA zji1xB)^IzRn1WLSyf{ibs5y|Khwp0?w|Kxex!!umv*dMgd635BQsNA!fuOyP>!-6h zKlU;CpBYgzkmSL%3u9cCqQQ?8$$Ru{dC8D0QBV1Mw^v{65qT>Wg} zegwBlfBWqTO2?8#7-_Vn#Zd84tAdI*ji2Beqn~0*aUU(;@DiC-r*F5(=K}S?i%XgKKJ5YCD=gQ zogG!ZtlICOAAh8Q;8x{@0}(oSQuTQVU~n*9*-%~fZHnu^@SD${p-vvN=r60F+muNopo?w07VR}e~~`U%mM`HSd_s7MtqSn?VT#$*5edv0r> zB=@H8K0hrMJdfO2P5qZ5bej1wjeHGpA5XdpHlAQdE)>Q9$_Y107yIJehIRDN-5+AU z&%UiDCMM|Y*|YS_4}VC>1m^&X6|Q`Q4LfQ@LHX{RgLL~%)kca!;NbYrKc-xZb+vlv zG0 z<=5dG5I$<4e{^-&r@`Uu0UrAR1d|#N5~DAc3-#W@%?=PmYvn820rM@OpM{K~!%zS( z1*ju!C4g_5X&rb0&^mMcE7n|NOoGM&lEGM$Ga93f1wcq~sIh1Uvclf#v1kzFk4OYmcHEqx5em zO?7gP3NSU+M?d}3zd(Zn19EML)oWJM=RWrrR8`kTE|-h`;s3jb_MJ{pGL!EsAA7KY zHm*_QXNW!{&+XW`OO#HL>0$clM?OKbvomtv4!7QV3w`Eye~0RuRsH_)@7zY`CzjS1 z%LV!-+TE@`b-%H@2Zb?|k^mGSpa1yQ5$83GIuPGMet&@cUS%E=4u`pa&&uz)fXx!d z4+;d`IVG{rp!;UDx>MxIW~hdnsk?Um3?3e~ub;(3eG}{PP3-}yaztqX$JXSq^Uvn5 zm#c+}Qf2W8uL$N+r~rtyQ>Xyz)+oUOpbx#$yVTs=lc7NmFwriJGV7+qV`inwWy1oS zZ^K%(`wEl7C1$A0flh;o>!QsO)wlz_%>` zU#$9IJu9#S3`_@h#o)kB>w*`|+xi|H$mo%4cy0fu_){_2_MZs`LH;J&;mOO zt$>+1m^t{l2IB*U2tb@>YVZtzcVN*4tnONvwce5%^_s`ETX^&>JO8&<+%$BKx=_MHUM$Cq4J-6fa0Kv}To} z7ZIkVTQ`P;ra;O4#=#j8{9^YdTz+BqrKTX*5eI=1XpL6HRFo>q4+tVxH?N{cKkykN zrVuYY{Xc2niQ_Wf&^EX4x{GeT>!;+N72o*suhB>(TBKBY&%6E=b*o0@57DZS4$TKHr&0x&OR=)C)kzN_>XqerGLXZcg3d&{P_)`wxP7P~ptw6y#xw&b6Av5Yj zk2~VQl)3@I_Be;*Pp&XANuiMkol?<*7kJMAO5%B zB7fZ)xjwu16ZF+5rzjj(bO5kZs&ubjLzz^JW`N{?bW&ccE7Ty%ee#T{Iaf!D;Qh`Fq(uu(#%gE9qk48|VZU{wX( ziyeCN0%HKyAQ+Rd=&NR$YwmNn4gbkF;!u3BxfImUDLH^2E!`K`cpDF5Mq*chufNub_c(gr(tF0V)5 z@wj*mRXkU3x^R}fspM5qsuX_fdRD5qe(Se>>pvU6uQ*2fzC(vjjmW^n4rFdEMgWll;f-<}7|`Mgu*|xd<1q+WArxLo zfUi&hf*JE6pmQOYh8LdFPnQ5p2w=1TEC99t?!}_E#v>E%a?~~6qy5Xm@&*g*r2so% zw6zQbk;vn<0QfQmq`i5J%m>w`d76bbEk{^a3h;HV70VC`YDK6SFdaU}i!tl~!S_#| zjffBh%m~KzFfZ`X&tUTU=HY3Y=Ea_!0=2>D+h`l~N4qvcdEm|vidd`A0t^t|fdvNW z3U>Bkmmq{CRa_@Xi+aR?>i}GAfB}Ut(tH?h1@mFKn42pPoSgxePH6YJ!iMY&)q1n! zb31r(5Ta-#Y`kIdNOE_LGFimmQfLktKjy%2%tgaB_46uJu#o^`A7ii*>;vitN?0Ps!qp&Ht-`CcQY5WQz#rh&0h`3KqRvH=zXTedwyUZ3hC zX3R_v(}`2BQZVGnDeocl40-*ub?3X~+KPd`BXptvjQmE5mii9rS$~^cTXFW(D>Obc zrg$cP82uu~ymoij&D7MQghf`ob>K0kN2)&}?`t=_i|5H=E1MLT^T1n=lZzL}diN#( zD-+Nf2xL(v%%O3=#v-|!Jvy0ah|t14!e;djKFUQZ1qMLalOIs!gvur!k}T` zH(GS;h(o zYcGy6@57A<*Cn-n=3@*csugb?3)6I>IKQw;-nB7kD~N%G(s!O2r+7y3>C@ve+O^q! z(t%+9bYD{3rfSFrIAeT(WdV?HZ&_`z{XWx z$^ExMxycU=hWyiL)wKPRPMb7FE7d)5tK1kbly@y`g|Ck6F zwXojY*07{@h8`hz-Om)HMSucwa(aZu#`|Pv@Ww7L&164lo2MN&ypPWJ9^n2tC2KK! zBh3937K~@kN2RYpsj^UjH^w-?7{YHQ)SSOx#+hDeH#8VG;MX-Up7i`6^M+}z(c=Q+ z#jJ>dU<_jdKwE29W`ItEIz_oP&_6W&RB7^gsHx7=J_yn^L{MwQmkZPn*3IVk11J~b zFqdjsf_@hHL0+**Z!rOVNz*i}XE2vzO=gYi^@36jm~OjGdA#RP0jQ38MaHuid5JZJiu??PFy`8CSrQgu2PWP=H>@iy@o z)$XTfm`$IZI7)*TUZAnQXX({fpQ4tI23ozgfqK^E!`-*G(x*PWk?y^F3+>w8Kw~3E zDLncVxx-%&`ZhS3rZEnhW^7vvcUMmF$`Oe=XnJ%%f8#}(8hnOn=zeNh)j->}HBrZ^ zdRk+A>w^z>(FY#sp?mJ!Ox>&8G(L8W;uDXNbLNY3z6LxoECd)MXmcwN50_qz4Q}a| znEUPKopJ%IAbW<}G~1iAR5KAtXW^J3(Z7!H@$cBNt87GQy!cy97K zQaQ!>LeTo|-!gu!JX{}^DvK_`RV(_uC`X|(K8HfZ4iGR*O(%J=m64L;eV7mspqVYy zCYM<^b3BI0aePwk%DY+sBV~qmM+HU*%$A0^?4{DcM9;inEJynenBRv*tX?4Dz(p`W zK>l5GR4Btb!9xLnwD^Wu*jMfjLv!B1oa>!~V9cV%j$ELevRdn{mdCMX=#e*AO9AE9 z+fp!hEf%7vy$!cq(%$GJ#%*(*f?3v!3osm|ELBieyUERpe7k0ac`&zw-Wd)5pV|x- zhqyu6w`pBSu1}l^i||?@OE+wNZDN ztNHnGI3qhFwI6q@H4EafGaT_)0BVaAGqCW`ObVD!-6s}|g*57QiEFb0u(RE|5Vyl4 znLd-HN(+sT4jFeAkL9#fd7-*%PK64D2v`7NJXTN|;Ax;dfdXXLmMUI6Kro!9Q)isvdhXYD<5uMiG8_|`XQf_WgTrOK{N_cH%b>_RJ@PSL&tUn{Uw zx#`AF$b#I8>8U{epSEmyzw|FFh6WGQ!E=XAdGF%9-zoR3ICkuD8jeg; zS7$!&lcO=(w&8ASs4sT=2jRlrH@;Mm_gyeNM};?(i>l=#+HEasRf%E_&v(? zkSY`A*ZEw5X+U6%-ScztU=UnROlQP5xjtaNT;Q8?S*jqPs3#2wk+I8uuKbjTe0m57 ztvnqpRUUolR*E}{6=V=L|H}{lmg32nyyd}NK3c!+W8`!qR2Jo|r*t30%& zilh1`2s^6H0KMCP_%Q81^t4dwotS&@sRfGH<>OU#&T+Bk*kx}d}cF^s6ln@M-+Bhpr)0)d; zsiM|;P$Fq4OO^bbX5I)^%2EaGr0E~{7oF#FaPDGMcpZETv5cGNqKo%Fsw$@?{70F5_Z}Xlqt(i2!`}^#jwQ$N?>b%N;10;JOHH zX$9P0x79b(U3Y$(e*HiFzVsgeXM^C7^-Gu3xmTU5-PF=noPHrdUi4-VAi;S}@tPL- z)N4Zk^$D5@L4I*7gdd1O8UE= z%i!+16!7j~y*h~BJpav=2AGVO*UvF_VHFCXjbTB7c10gY-?rBhE+gb> zIOoOgy^w)m^Qo0ipkKoM9TZY_eKZey`mz+@?3weIn4a^ickjH7Hm=zv@o;nZgU27I zqeqXEgLw+AP;t4Ke{*}t1;q;g#cx=uxScb!W_3ao`97bU=Y(Q8`jxX(nfu*hsnQmp zDrd$0*RrCbRIx|77AhkPP^dsa3?>lF6eb2R=Fw!#M0y&(24#KERo&;iD7E~Uyk8%4unfkQIk?hAs7ZJVkn0q32}mVzNW z&5I@+fOq4L8etG{)&LY`uxfep(2NLY?!BYFfH?!>kxHe7v8^&O;2O9Og~?KsD$9!N zrlT$f*Jk0hQUyD+n?o594A^1U)F3r`)R`(PO{ubf#7&QpI$KMlqEJ~pKqEoRKs%w( zMZJMOVR45=4HnlpC*_tKY6yqR&PFq`IK+;weQ!-mTVhAD?ny|eg#)>z+6XPu#S7U? zQk~Vdb2pSLS$_5f;d99|Orr@b09E~>UqGqS8my&s($DX$qJ}0l?)rL9@m!XqD2){; zCTcv*lu7gApPyURy`C=ho@UxHK&ecWCezc!N|gZTEzv6d3~3sh+UV5rH|2gRJ3&M7 zR4(uB0Vg@L%5Bun-FHi@E@vz~N;CWtt5T)WS51^rRuQ+}^$0~HGr97HvqJ@W_h%c( z?ef}`Ger~WF;S`@?@E|q;`jNxms7Cc$^#sJX%3n&%te z{WG2i#>9QHrp5Z5*lCYVYfW`7diSkW)X8HZ?WiMv=Vxg1<}FN9q7)uIL+^UuPpSkZ z@XiPCreFKjU!;c4t&~a((XkhPivH;bV>A*|eHjNJV?4ql@|GKwQUxxK;pVBSQMnCU z$x0O~kY8-l(sZK~#BDaur>J|-9IP`otW|vz@vts|3u(CT)Z-Z&QFK4B0?%kq5LVz@ zs5hi7N3k*&Fjk;c!Nv@vUkH%aDxfthR&Xzw%;Yvp!d>(6(_z^RVrThLU)xOYzV9b< zN);Ta{%gPXYqWRoUQw(}Pfst4QpF090dc>@Siu~CjR@emu-O)QpXnDKlwL^t# zf?hm4|k2t>$(L(8O#VkK0MAuZqfsNyq|&1`lHfT!x|jwr{EtuO&m{&0ODU zYOI~0STsRz9GsH&hSv}TO((m=ZM<=@K%k81M{~6i+T5E~fNbk7ogR)T~%}m%6Pydik zoH}PHQIsM@lqk%c!Ce^I6FfvFoub;%F!l5VI4zV`KCYMI{&IPhD)YZj<9b%Ayv^Nz ztvr;gP?^s{1%yJI-yy)lV%N4BVX{DkphN*bkDXCqOd;3+QLf;6hCR_MpA=T00dsGd zg9BikOS%67(+uI@asi8~US3ppw)$lOhJ%`+6oK*tbYhejFtA>MFfq+cLn;k3aJN{Y zIGG9QHqOk^h{dv$&NxJ{VPa8&~9129i_?+(#@chu3gO`)PNc5s+Nu9fNjYarsJQ&eqS84Ex|SXfG-0-6xy zF^Rdg5()!$P(ql3IzzRA_F%z3<52*0fLq0 z*t!1_y3D`z4n!>GMtGqQ#R>#dcJvQGe8v4&9vIKrw1fOEC5VMW1?L|{BWj^D5e<`e zjgA_1WS!)7D#2T8d$%Y(^s|$RFlC&1_cdrE%p=aMm)s5yrIHD%scn?!5wh6~&8A~H z_el7^JA;KJ&wrc`x5uj#Dx5BvNl`eRkj(L7Q5`wDA&^23Vd&J zI`6_o{Pgqp&7T2X#0Cu17XUs2Whvhk7@jHp9Quz{K+^yL_o}<7wzk%YDa0FZ{(xyk zO5WPm&`hnJd$>M}H;BYyVLEW=8RIGsxc}xwK@fYGr&I(>GZ{0{IOx2pSA zYG{OFuecm%&mUx->%4KL1m1dlz%mc@i}FF3J25@RJRQDi&tpQ_5s$~|;Gx6ZuOj?h zhFZEpLTkZ4HUyls|CLv%|J*)0dwegsC_$5>z4ZEv-;!Ra(9tnHr=t zF^|gMY2Z2Y)#sn5f%E(2UMT3LbTUlOKlvrO9*;~=)}bu(F;t=OzT@UPTE8YJbu}^y zcQ{11ZLbocuFu~{Devvn)YQy8u!p>%M*8~K{*lL$+W2IL&D(a-Lyvx#+s8?nbeOU; zkI}wEvlL13oWgYvH*H#>f@>)LTbexFCOEq^C4GMJ?!VBM4jId4L2(_g&zHmfm&}Pw z!?ErMO@Z*6hoIyUZD*$l&_KD77T?FF26e8PdLHcnIfE#FxnFBnVCWO554(VSrGVY} z5axq6K=7>d1{#C@i+SA~KNpnyAVnkX@-bI{!U1ipU9q7y(Kcucd>iity@f&xo&=hB z4FrV{+5&uq6#;*UHmuo2Pd@X4)DJ8Z;MxaPD%w(|rjGMj<)k&;0m9i+5JZ;~V6BUO zW~G0C&M(%2khdX!C`=QltL1)D3Md0yBAGFtLIvpIyl1ko48UBY)|m3m5~!|HeHHID zrr>!IV!DpDM|qaw_Q?)Vz+v7r2h;^fHpUJ50W6@<=k4mvODny2AK117lLZ59I_64+VLB!2KR+ zkQP?$ct7spS;RqskGQ#jZy|5ic~-`qk#Fn0=aFo>**PVG)V(eV&zY4WXu{4CFoM|GWd?+lU}U{EyH=o>IeaWEWxM9HI(_7>tmWajIZBaBbG9S*fyql}F}yJ6tPDm2wm+5HLV+0--@A*as{C z;NAdr2&IS?{s0hCLHGlD1^R`>kKgAI|HIhv2p$nMuN1Jj!#mANmEqB(2#e7+XfG&j z@P4?FfeQr)!0hNW@>Nl)XCJL4x8&WbRe?dv@) zztfHkxr55Lyq=FBz=taZZ#p3Js?NJssw7=0;JnKoRavJ?m z=iQOEo}^bh3DtB$O&4Zw(!I<#9TB=s6ncKS_g^ zj?C6@ZN9J@wc9pyu`wz^xP9)lY1BN~lLeLnxfi?W-wYkdv($Gqj8D;cAB48ke> zepSD^zs?wWX7Wq%=^5@fUhZ#dTzb6f9e5Ufe=enpo8L1t1qGY3E`$Qqte}jf<2j{D zG7{lDVeV982yRgDTrN+kD8+a}hf*Ay1b1u>36C+weIC3g`g&cpi*DH-68<(rRXL>! z07c2Ew2GD7#>doPa_AKiH4jnv%SOt;;38*SLQiMDRvAK;3NibiVybPg6v>rf8Vm6`V9OiP^O1gj6Mm7uKf2mGqfaou8ro87_hR;9`> z{n9VdSHJpIv7!ry!=eP$N)@!lLKNJnGc&C~|H3zP08b>FSGfOy|3QFUXfD*%;cSn5 zy_KU-2?pKLkB28)DUq&X-apLWb>_~Ov4ifb3sI_|ESUS2Td9IEZtX{@w6cttn5m=j z=>QYqu+TeMl|gQP#%n5jMs9$g=bK9 zj3@9h<}~8|%(z$X`>qwZxjdkipl_h0HH9-=VsRyO11W|eW^j}j zu>9Tb4t2n#R+dySH{jL;LKzKMdjx}dmq4)G!0uWdw2%;ht1vA{1#sW|F0=>Y%>6+N zU;!xD%kLRHqBK1@ z#D8NFushtvL9XM4{K{b8S#F2v+_QuI=W@>`IM@MS?7wh`67gv6xpXSd-yBizNfx?< zxo~PP$E#sakN20u``^)&E=4p#=?<%dTTLIdt$ zKK_Bb8tC5J>uKGZ0FCq93Z)NrvtR00Yl~9AGblIC1I6Fk+5ne7DC17j8AZZxoYeuB zi*ton_D#`CuTRQckG0F;6tK|?N*TKVw`5R& zoVj5CeFU6`V;8_XXnJI&y-;=>Jrx!u1J+qhjR6V;)xq!Rk2oZ}9Q@-y{v++)y_=ev zn#A?jasXB3XtZ$0ebKCBshIm=oL2kU2R|;jB`kE zFg*H~m3N;Dx;fJs7dc%4rhjTZy_oqEn=(PapbU*Ad^9!d6&@5oe+1wX3+I`Za*qc< zX@YZg(JrvyhUE+Z{&pr(#ozIWY(Q@cf{d|(l?BkT_7=4X55Pu<=lA}APM$kMvoli^ zotdEU!0eZ4=t-arDJ795mmKP!L+uqRN z;e|QVCVpQq;FRxU$J(to)e2)8=6l#FR$u29-?>=eSpDx-@b-nhrAqNQSm~B3v5uzP zSS&}Of_oTy*qw*5SqX&!yHRz0VsQz%95uBKVj%*z zKc1>W=}dCg!_-8z8{B6Bu=XGqELDmJKKemAtPX01Lg?c8lN5_8TI2L_zx3t>52*yd zIibpld?5e2oK8zQHR53>xw854COI!TWl446CW+XTi#*1z230q+D(^Ps)VLNbR`5-H zU(-jiSmAGBr>yxi7(Y3S6$S)U%3?*i?^_J;F6{0#W0tGbonqRIEt&$ZCzA!yR64Ja zh{T=bbHFW|OZuPL{TwWaBAH^v3X}mco+E@V#WP7tWL4WkL6MGnxXu-g zg0c>I(a*waLs_aQfOj+RJ_jIZhN~%@C!pGSijJRoi|Nw@Ww{O$$vE?V!!$Ho0{ev9N|K^)-@|XzH;NT#wUcFirDp0gw9`IxljW_(#vJ3a_T(yaZY>F&KhYa%#}EI z5du9}{U9CM4zvM6S@7}rjt-C^V6Frm!T5rE9+WS@-Ppsl7WIDM$gC)p@qP`A=~4mb zLxMlVceih@5*Kc$H(1t-)l7|BcBP{Xn5&h=O5RNw@`4Q(aK(nd)_}f_@rdWaJD_Z+ za~)uDW4^WqS-Yi_wIk?}nf6LOaD79*g7F9$yPJy*WenUQW6UCtW}uF00wG$vI&Z1+ zGe7e)bn4V8&Rbd(pi8k-nG5J=C=*vFt*+0~swNk;)HrNIklS-AuKEpJY{B{lKzg{l zYUO#gr`26D?Id?KKhqRgT)h9zEZx2>K(Xn#+_Os)kEO}Wv;pmmeAam~w648${tyz} zcRd*MhNViaJ6$qOwI@sG&rDN)f0XBVE)VwyWfi5`4(;OQwa2<<2esEbZQl`(a{cjK zT~{4rI+GxuN6`XUfZ=?Ku4emhOMS#t{b|5WoQuaT+Ff|pQ z_fUGPLIo4MGD%cnaERZ*j0%LJVA3Zh6LfJPCUuW=?XCU-X1jt4Dku#w(t6hib|h)P z>HwH+FyBj2tbnz17^hv zfI39Lj$>@}0AGT8pt0DQs&{JZfcxN;u<*z8o7V@W-Xk#xi(Mjw!GaP1?SW!N30fQ? zq{5-Uun>lD&TjW6Xlq5Ol83l=iu1geR5ZS=W3?y(v>-O=;)Ngog8&X88F!E~rN;cK z?u~T*%n|twWV{JVXP7n^3w-`5ZIq6=$eD4;d*Meqch-m_OKFcfoHZ9BuvT#z0^v4! z7U?oheveDJeA9ENc1`7o`(*xsaJQ*BFGS9`la$V?Gb<2aIN(m}xl9S-^|L81XBIBT zbl#aAfMO3y6^|n?5Z3Ou~bY{g1>u7j+wQ>wtVmzUd7D^;|0RbF{uvhv7s-VLP+`ccoiZ8S7+L4K#R_DU7x z+?jIalqz`k*1H}Nr2&4Ml`6=KE16fSpuKbL&L~HzqIpaxR^V?QZHaPEO;7N;?kt_V zc!K%{&(Y|_AdeAcov^CIFZ9w3C{;Wrr3&2JMK~W;_g{cjsRCu8c2|csUWif!fTC0@ zO6F6l;2XKNN=2C_aDNw}Xj(Qj$(apqMGwH2qpw342_=QN|1y*+sOQM+B>nOK_#dJ` zfdKo&i4!z1Fd)~k6o8_oy`z(Exp_BveSw@(<>h@dbbctsb4iBACsML;3Fq6W-S0^{ zbSy0WxP|8}w3$+>pk5s-LaB1DH!8A~?o|PyQ*b%s^ZUfA9d!meVOECVJLaH)JYc@8 zm`J)%Cf zVg&%5unR~7{r~~W9&Gx;U`6iAr7WcsE1KSew?JQj8@OYq!qOL9{9TL_&D&@MxsTp^ zQ!{x3Tj|W%3)H=OwVaoL`rWnb22l<|$6i&P;y#|fEJ_tL&HEo{q+4#Nrp+5d%r6xO zYz7(_Xa0=qS6Q~H8pB)xS>29xA$o-0Q7Y}wWQGD<=O}+qJM(Z%qu_PL?s*9MPn?Su zC{;R|{q&J{H`zXq03Pt@nP`DhrHT9F#~y9AeSXK5D%n(s^C&iKtf7upzl349#pd=! zK5;bAr#{dw?gXvrTewdjJ{6&nsf<|rg#!5jfpzx%w=~c_x78M!t{sR4m1Q~v!Ya4dBFOHsg}?@%p=(J<@0k}HTfvSG%{4>q3SvxHM9n) zt*e^qn*6e<0Pf=e&?Rh|m3c&o2j41^V zOl0Aj2#abklUOJ$4J)%r2^^$`Nem!Tix!N;*b;uww(5927_;U8Wd`V(4iJu5pMh`%>2VJNHjtMX(-{bkApnA# zLeLEW%5by`7WwFt=Pt&@H4y}0X2rM}pdl5dN*-{*5@%jAXdK`Umsk+6YC-Je>e>c*UOziFGeu!;D=ienMxdeLIC-k=N;;xdI-v)fEhLfwXp>Av9l3gPvk9-E^xyaPHv(~$^` zO($}B&&D&ka>A9DS-3kHo~7AXI@fO`??Z8NrMOQT2h}4_=JJkAPZ#9flTioN19;Y4 z&QUI>KVWY?1!&>kidU>eEfy=_feI8WP@*fp?^^J@6vYbOVO6RCW~EA1bpy>zPe@$@ zW~B-g4O*!JtXa1`rwA;iQ~}IN6#(zneZ{O)L3yEI&`K33>d>zcfO3>70NN355&^84 ztC&V%;|r<_?TmoUH_gn8;b338^_5krg1#CF&+y!<>!q|(rHAVUK;K6DE<~w z^*^6dr9jb>;ym#uAb5iH^vJlfd^~?KM#oP_nAUS$a$j28!R4+6e_BOJZK;w;P-3c= zzVy|9k$08Cx;5>z=Y~xbsAlps&T%cF8@li zR8e!FL+V7V5By&8d7#i%0$i*iPzG~)0J7JBo7Xs8EFJ2(-*q&5Y3(YX{C@nI5pwbk zoacysX9c4C%-eam59)WoI$?Y)PPgo;q0K#hI(s2PQ7G%3ZfdM^@!ZV)Dd=Vz#pN*S z1WIwt;Q;Cs-$ETC-#Vm?zo>0(&Ay~F5fG}2qOt+L^Q^l21tf203 z$h4Vu!Ce#FFvSyTrZ?P|QGo_f?uYNcfo7u}^fRCSF?!(P_s|3Hd^f%0p@(VLjl1RV zJMX=LPMmq2Y1q_dQ>yIR5TH76b4|R6mLecPk6P@PyYg8#A zRyBEOZMVHt7X5yT+tJ4~2}!k5C6c|B>Q?<2RW;qq-?%Fms+#Vmb(TIt~7IVzx-Bf_{gwn&dv{ebun=&@Ig zx1fI$-Mqb;$6hPf?@iRY_T!dxcTscaeRR{FchZI4BTVlVJ+CNLRwk5UMU5fIRZ>j* z986ZA-1PEzLV&^<^c!+pY#P()TASxqr~nnE%H@Y+c6Qd7Hm*F5y!LbSmB)@y-vG=d zqcVYQ*;rM+;C|6LziLIE6N4i>+0QCw35$3=NCt*u`9*?}bzK4osC0dmQmB{##R_(N zKmZ!#1)F(tP$-=k%-Nc5lMA5*R%4jI-OmeVGqivej18=1G?7>w7MP)H9Sbh5eS+(z z)-FpyO270%Up%J-1+b$>GyfW3yf5`*XKnsD^zqi_LVxOu!SWT?{!M+nI6ZYXB5u99 zI(;Gt0R!2~<;IRL2xQi;4ai~BP>e#53=5W-5JEUlQHfszUI4F?z-kqZEnHr7R7 zDQH1A=plBamxnAb76MCdo6C#kYxyey?BGM2VNw0?twGwl(W=Ezos{tgDtg5}u-O z{Nul;$%N`Fb>1|6?8pCr0-;v9HlzR2Vfya(|CAb=1G1YRfZ(--+w-G8@qgsnihZwq ziC#MJd@k?nTiWT75C5Lrv*MY@|2LiLJ1KJ`fV@wR#%Ry3chT-!KO%8feChxGD$^sy z10(MbzT@A}s@1#X+6+o0uWrH=RuYAP=ogP(TGM>QMti=C1aFwQ zC{|7Nh9m*!*TBjGLVeKezQl;c1CF$l>Krx9@2GXvdN~(oP@a#clQfc=lz1!LF)uY$ z)rhc4DbuQQ?yaVh5t_;56*r!+pV}I$WgUiR0ex=BXndMtq!cUwc&SzMxKl+NqTEoR zp96wSl4m$-bW zL%h2`IYvzlydE{&kDTp|<-P#sKpDS@W_Hg8c)c2uafLF&s!V@pBr!#CL+Rw=`uD{B z)Kst5nrJIn73pXDW8;)@s6LBLKRA0!3)&&<##uyYx{p0rM?GCWN>d$OoVb}{vq~xB zV;*DQp;3yZi~AH@BGuJ~_&th8$vVB%*?5$Ko^krCuME;itgyqPt|7ojKQ?cw0wAc> z^8*C==6=0;Re+%QM0!|xXkbm=*{0H9T*C@RL#IKVn)zA3FYoTsng$2?!`dC#cW_!Z zxL}jPhP5FPbYooMedh6HeFylq`){fep4|+{C-j{C=YMyRrpRtCRPS9?@1#3#Eady3 z5QB2)zB}sW`qe{mI(jKher_LFAnko~O1=RXNnIUz>lc+j6TM?Vu>n_HXa^`3p=3gP zzSgSPq@y}_he3I8VR6nu--6_o2ro7FlNpR&Vhll2b<4! zZOxx81`7pj0Bd79rxg>hRQbi9coz+gZ>QaNJ;LLu@lwONR zzFpDJ&{rW#|KuZ`y_3df z*HPBHhkU+5`h<-VL&JyZ^qI%#f!#s!)O?EjUWj(z@lNu3?P=M!zx5e9d*&s{XAh5? zcRuvfoTi?3+*0>9qTblVySksKscOU-?BNp=_`hQaTU>o<>fBUb0 zPV(NddJ}c`d09fW84)3g&f$+&s#3$2`w~H)v(LqZQ}#Vbg^(_0s$MWg3MIfg_b%ubu-hj zy3I$;wJw`y97S=aPb?Y`L}-Nyc6`8XQD1+I`Um3TR~5>nfuXq%$g7}&l?0gi7cWK% z`!6QDRlFc@V@rtvF#n4=y#7j~vz-@|?S2~Lg~1yKX6S{zQ*``PL>6|tcUH@;uM?*u z^!%%nV){QYm=JU2QVJEIrrODi?!_ro%y2ofyg&`k-m?aeVK#kj zpu!B7i{+{*^p2${R3Ny=VjM!2TLa*fYD}ZM|E?9XHJDm1@>^dAm|1iFAi4WBF=KKdk!I;u@l5$XC7R! z*{880OE`qr=2JIF!jbO60W{o7dvw}yy%Hr_;cKm0Qi+E(8v zL0{L_C}pLW`J?&((XLzGUGVIlyFVts?|S&B<+)Pms?JbzTMyl1q}_JYy9>U9djR-4 zzzeO`eI;W^IlTi?TF<0s@J~nOJ=_(GfH8#r zZKZiD5wLbbJ}0NrOowLZF!(VXv137Hxcfnw894~vjDd+AbnMdoG&bE{RHmk;PHJxMpsG;5&uYX| zA*qjxquVG=h4s8t;fCp_8#iU!Tn{?it=~)^bIBPtWMxVXM0WVqI9S zLZyN$gNmif3c|dWDn_==xtHA{hUxFQ-iYi(Xbd{&jvH&3P}?t9=SE@OjPSze2YaVQ zn~uSovs77N6<*->#jbuZNFyT&aZdyjHZ1-|$KtYhf|)vq2i%!04hziGwT=ZB*FM2@ zQ)`!{AalPIf(smStQk$WqUWvo$wWSJn z&)u?_84G4Q0F=O53J4OkD*_0_O95_B9(!pvw{sCfiN&_bmBaG2{^iE}mMTCtZ>i#Q za6elfOO*((nMRkvQf2>$n;s*zqgbO{g$kb0mJXK#L%hf@*s1GEP=Zoi79iW<+W8rtdJcl>)JrVx*R_s{9<&>3+_lz}y4=T5rs9Y1B< z%>z4ypL*tci4P!|R}_0PVTuKCX*mx_xHwBn^!#7j{57 zmMZ1IZl1V(b33*6{519SD5ZuKU--&rXkv0elq&b%dN0+sJV2eDoyOffGMNnh+2?+- zq@~IYYwD?uzq4h_7P+?K2T%Pi9Y3{KcG2Iv`v$6RemAXMyVkf{h%bKicWG>*P{`WU zpxm2{O(taxY{rJ3{CW~Du(WXfa$}`gs+>Bfgsq@~5SHta1TqL^OZO^2t>K`@n0^=f z_RoB%o6@15qg{I*mV0*iga7`Mbm>x|kXvI-vztElzTK4ce~LD2x!H&<#xMTzZT#K1 zxZA=y3c^JVxa88xVF39%eLgDQH+s4Pv~gWf^JB3l+qtz` z$_v-VuwsF563>A?VLb-7NX?Cf3MI7Bd=@Jja0i!lxOo2XQgtBT4jOQUb;G7jG&;MU z;4;$=d*3)fr!Jk5--VVch2L5ztd=Ti&nGArk8wRtQf*V0@f7zbzn^BO$7rzcFrDf9 z5tp0mri$0JAqTzq+JubpyS4?XuH%>G`E~2o@qAG%vpIj^4SMO-zoR>M1gW|G<1{-P zqP~G4%6jT}zRoMDYiep}sP`xxJM$e1RV8wkDi1#J30_+^@SHV5DGE|eUEcB}7!1<* z;2Ao6;-9IyCYiHTdF0`b(d2X+O-@bIG!K#5`og(2J~K?mPJNF8p=o|DNr#Wm%J_k> z8de|gf9O3l6W=8CY{!lrwmib#*FR4KgZqptg%91^P6vD6FTdN{+o`d!QGS~-Fm#^2 z{I&mLToqyikKcDb_z}tb>};5(!bz&C%PWu3Ceve=Xy1V!()dhX38pPo#=~%h=A?eE zUsteMtbtIkI3p^PPSDio1$yE2Z;;FA+7(NcwUkkwKV&LSpd`1$dfdf{mH46EV97Zn0=vEV1osBWBUXvcQmX7%wIcL zvM$NS|6q`9-6iysJMi+*o zA_Ibusmc|l_Qt8=XTv9Gbodm_B=Tnh$j;(uifa7{a%V3TrAfz6(YfAUilx=qgTSw& zF-r09>7r*N)2FC+V3>lT{JaH!?RCB^)mP0HJ&$nUzyazT3rib=C$06yX;q6&IcHDM zK;J=?cb-E4$$KP4t@S*gr_L9piO(LPiK#xCj;e#6Gl>-4wi7#0i}OA{ypJvpBJZWo zRIy^^ow0&+I$#_*We2wzs55M|3I#Cd8j*~poUwv5)-zSQo7{BEy}w3Vcius()@&~f zJ=^K^{oki_CM7xDyr!FOx$hTf{pLMI&(=1!(}6?JsF#`mR`0gk-a$9s`Vm^aZdXw{ zNV86#Rf4#XJ43hM{bO|FZSSGZHQS1w9Ui?zLnG(qS)kOJDhmbpQtKSi(a=cM4Lhm6 zzIgXFaNy97xL?eQAhx?>BL%9uMObHtSKs)qoH?N_mCa|WwAK14RCfb4Hy0}qfm3Jq z)7W^QSR1TvYa?H1L+LynewLy!2*MSxCT*-&>tKCugc;Zct^r}YRq1lMu+q*{$*sYS zc7c*&%lZ(l?(&PG2^JfO$Gb4bKu?eceA|xA8<=KwQCrt~5jeXnmUPKvlAe41n-mV) zyT+>vIjO7reqK>EQhifnHy0&x3HKwf!YV6BjSU{z z>;P{a*tgcmYm!l>HK1ppe~>ZZj3k`-g6Gm1C;0<7q(3Y5k3;*>Z*g9bRzhpY+Kt-; zG*kCy@D(wxXWRoVN4{Vg8R9(Qj4ZgALtjSy;Y=9NWwgJa>G1l_7|(C#s4m!B7((jr zE3ciWa8l)=u2w5<5S9i#Ht@O|Hh3xP+Cty>=f~+=-+7##f9_e@v3(m|ICqw&rzYty z|MIhR>hu}fvaOo@L9QnrLQs64?TvE1yQ#ayL;V9zI=t^GI>q$x=$lVd|AoUm50B8x zKm12}^VP@b=&?6wY&J&DjDyy8)zH{vHU0h{{RO@H%FE)p;ow^b=NmJuxJNN< z*JrA1TVF-t_$v9%%P+q|LxTe}J~~1_dgf{Q=HGw*AL!D+6b+6?MZu5pq!0RrGl>n| zZFKO>({${>59#cYAJU;Wo|JMqvoU)7Up_144JR&<)14p7z~g4#5mnoVlc1sB~@|fGQHY9of+b?{L9)IE)dUO9i9`n`Icj+QU zW@qTL|L1RLWOR%goAYA_dET>?$8TyY9Xx!DKKD0Yrk7rPfg0-T==+a-j~v+y{mozh z4ZZ%xL27Ds@ie6RQRPgPw3qGhzEY z!ls^x2-hGa!}z^l~cp0ykFm^?shi)H}u}p`cQ~9XJ)*2B42tS710- z5_!QvrYRmzi+i<0$HO$p^cT+|z^xfv)2V93UsEvE_2tHaBU8Bz zyc+xV?V~53e3I)Z-@abBNA{$+F0-`%@U$o)P_H9nF*<+ZHA-6g!lmBRMQ#tLr{i?| zlseByW=5WtKT1?|KZu0>$YpC177%MyjgSPJN8un(E6lRxgKQ1y*14hqMt=Vxe^U zd_*i$urnONyo26~V1N!EK3p6QzQ*g4ygMZT0zbQFj~&s%f3$yLABe}} zBE+*xcj8!~%PLDi$C{s^xMDj>-2yA{7>nRe*eGFPyNKF zBz|Ii{%y@Kzq*fp<=_1defpChm$V4K`pdsaKl{@^NB{K?{;I4w8;X^_0p-dL^aU=6 zL0`a^)mA$x;7!UiuoBU31z|B1Po#w=;aQI}DT)G|Cj+{qy@F_~Lpx~2iZzdobzYHO zKym!~fob~DOXKvy-bv0wnwm^jQUFNP=f2WMfAJ3k9QtiTB)Pb`rCflV95|n14!iI> zus}nA;sSs*4i4dmi!8YP0$ulcRN2pr*pCIfv!{B;nP!g`u7g*tS|tJB!e1*caGOrV z3-bqefU#ICmrpB(XNk^_7WQAf8*~|etuD$imzd{~MA|_YEcpZ)n+nfD!Fa)e{pRq$ zzdT~xEyUR9pz&*N^iQUX@(yg>y0v6^0pxk#Stx)C+hg_W)siM04wp<@K?M~oKjxpo zDp*mlpURdCm*?%;4G$O(C{sqq5@NDlQ>}ca!Za655GFXQ+oTFAxK>b6tXy3bvfve5 z)3^qP0p=__0Umbgmr|&}r~BCp(Ip2cbL?nEMX^%Bl>&sl)&OK3p&SnfmuwEFH+Rqa z{9LYhtk2Fz;PI})VBD}l@v}O%+;Vz>Vi=8HqKwOq5}#Vg*X_#XbY$tS8>;AI4>!=3 zHLcXM^*_@)-v3Sd_22w9{q}$SdwTt~6dl@^Cbxjs@GRUi4Gj*`x4-o*+PrBaoj!fKtaoTY5rXy7ne$OPd}5Z4 zoCwp%Sc2(Gis@OLUV2@*A=9+By2?#nx09x3QuOAL8BuyX@$8rg$YHeuT930e;3jb{ zXvGTL27^YT-q8QRcVY8@xYy!$!CfB?n6}C?AOxR`JLe2DhU>4Z0SNKY764qQ;k;vn za2T%7vJ{P%cApoG%+Q9-HyT%S16CAJbTl)bfHl}*=kB|WUyB1QY|tk7 zyAZtb#v76j=esO4Z3Punuy|ZO>U~vkjWR_mE!zvs56mpVi~u2C=p8;jLnqIKX?!A1 zm-?f0>TH;1nAyP&8tibiPNo%9aIIi*iWN1WDvFf~7KRF)T#3LLCw72BWv-o|I1IST zotDtq+(Gx<^$7{xt(z(23={-k#!q8|PD)2Zv}N;0C9Lath&FWv>47~V+O*0o@4-7O zSU!L@YoP*!z*-pncEjj&hW_U3BlPqC=?wk5|8}1K>T4tP?EVm)?sL$Qv$K>i>Iijp zp@BLtG{=ie)c!d$nWuRasNzb9rW1q({kS&&JU*OsaIww4hv@k$&7=Z zc!~MRi^-zrpLl6n?prZ7la>4Cyg&77oQ|B&(#Z=G6p5)kVXPiH9j6P!Y5LX=qx9Eb zAEuw-eE;%i&dTpndH>ck6LSAo|I2xK{x82WBzgbtvm+EsCgn^TU@DxUCtpV16Y{)% z|F8Ym^Yp{lW;pNi*rKtV7Ap${Hc$0lipx2Vu*kug7uY;C$ovh?JSv6dP^{oA3p)gS zQQKgJhv{bFGqGHl3n718J?}Syk>2kqcEOT=cVY0jiZylf33|(g-nDNJeB%o76Z%ue z=N`PfKF2SkziwJveCYLJ0AV=}iqDdt(o`pLE>D1}S~gNub^d%bJGlMTRM)m%expC3 z|6LD&;s9f7a6}1`>uVhp^rgtfd;(lm;oKv$oq!Bx~l4?RRb`q7V! zn9@MYj!!1&)dTr+aI~QJw%cx_FMs*V@>>IAdTcT&hs*a3#Y9PK6?&r#Q1-&TAm$hx zsQ=c{S$gi32|9ReR^p)aj>XgR9DuX@p!i5JZGyrV@&>Hc5C`RdXM6c>|C$;-)Ya*y zwW|Yiu47A+Pd3uPeOXt#pPC!6wsQ!Ly;kHIIPYlV#*Iam4cH6|7khA(1^LX#M53h9 z|J3m}ZLL+Tfb|FtxZkp6OVRhR(H2!^rS00{1Zm2J*XyOu&Q5yx;fIYFelO31P#7WL zoFbe%gnkq*p%_6fjvRPVT`Uj>_rD;@CIH{VW&^9+wNeO$LZWoK_10S#tQhh6d{R#+ zdj%D&G+Y}LadEgdl`8i1yn+=BFdbknuww*=V)hTl=)mD=@ka{F6-?YXu)ewR`e0rw zc>7|h7Aw}nTq~%cf@>T7Ly01V3h0BGM)+MBdiR~x^vOr-={@&vq8oQTAfctEh3dRj zMWMG_uf-Oo{Cas$uJ9ev9lGz9{8TeqF)KA z3+Xx*&)5ZdHG)+beK`O@QP$_B>6Dw=x@#!w_t9wBL8mSa(7uziG!aXS03Dc`;rT2Q zrPoiy=``OT2|LLZ@=<$tHBBa5PN-(MGycUbej7%WJ!V(QDHSZPsbM-?N*XJ0c=XbNcj!m2>N-#sPPmv0=Lq32$mk~Tm%e=$n``>!v`y~myzqd)q~3-qnW zMLA300LbI_93jrHFkI7Z&%l9dCm+7mhs(%gp~z{oM{SSKgQsZlVPTHIAC4f zP4IYv`zu(KX&MFk5n!4&ohTL+L2!$DvjVR(2LRR=k(9ntKw1cl%|dm2_xz=pgs(8>;ArZ8f4Wf@?J^0>Nsr>Ohzeur&GmzyEu&B+&|kF>X_|Kl)sojS>^q zEl4vsI9Q})z?@?TJojgR_GjX1QCqj5otwA}58l;CyS7%-wvFg3wZgMtGk_JrU{#R| zuyTQPs22eJGZM?tuwltLAK<#{bD#U1oF!Arnx_=reDh8E-uJ#oPd)XN5mP}06O{VkO<27O2ePWrQ0EqR5)dwSclu=E4fN^8t9Z=Sd*nH|b^))7%s|+?zDEhbWoI&%0{|;7 zdFS^aoreB4tUTae1VDM$bonI>c1kxkxO0NxUE4w;jDwU1&p=2FpstV)Yu*z$E zHkH9@WaHY99HhT#eMpqD+c#CwD36&5UK?QyV$J}Kx%q|~>R=iL;4^S5j&#TiltZ#%=q-DKTWT``l={;7lKcI@{^+UY-?*P7+)1!J%pIg zs;hR%-{s)zDp;AgvQ)c*lE8cviR77k^X^AzwJ*W1r73RtQ9Ma5H!$gSwFiVD!a}Z| z7nImBfQ8bAp1dFKh2!$)y@CoBiiIjxv@dr63;qf!m><_Cb9Oyb^v*V>3EXTh-#YRI zJ7qq^!gbrmkSIg!aO+)S|`TF4#P%!_#?Tm#mx3CKBl zp3r7WX6xlSSc{pe}9ptOpBJNY5Xu*zf`8IzyRDTEet7=i) z0L{kVyK-yhxbK0*GS8P;BHCD@$*jbS5ixbl<&<`ar%cRrfr|ydn(EAy0QZT^&IE1fF1l0U}FOS6pPr! zjq?K_eB8RRineSB%9z1?b<@sju@o{ZnXnN6JTKY<&p~KyZqMa{*HG5<4mQxazADbc z!inzq_ym3ABOejLK6bt*lS#RT%bgE@_`}9i|37>00q59poQW55o}BY+&Uv}JB$qjh zN~Ekv$vRoq$#;_Fv(NTPw$GR3yZ@b&oaCTjTRB@2DN>|JF_XJoZq8|DcXFOV&iL2Y z4-Gs34>K4{UgF!W-vEvG`t|ErUDZ{!QZaL#Ltx!hZ^>|#hk0BAV^*zLF&Z=Z5(vbf zfByNDpc=r~&L+&QT8b5^yn-TY=gxE-4y>byM}j#Rdmt$EpyUL91o;5mc_B~qMXMPx zQ1rBAy+h0$co)PmfieIA__5ClgcM~y@>Neccz;ESjdEqv?16I5mb$LzlG-(**6-1I zSkkf0?5Ip|eP+I^-EOD4x;i>~^r-lbdX(1~40@`pa*`z(?0w|AqD-r)Z=-cv4${W$ zcTz*kMyhY#KpkuMitkNrikq%#Yn*Dc^ei%_3fyz4tuWBRAi-tH1<_>SvvJ?6_2Rz7rIuQzu@E)vch{y2T}i8CS) zR!?6*EP5N6dBbUgyePV~OZJ)t0Vl5dc)|s6ItW%9U~+-W-F~qMgNcPk9vct|oGt+q z0(4#Xi<2kSb{#!>f1S9taA?;L+U1`g9}%bPFz7ql?8~q!mv`IFJ7)d5+Be)#wYDHH zGe4Q)M5sK~ECC^h5GttvlWKV?8XE|hq)&(Wd*zkW6MFg-U(i-&CLi4I;LW}x`HO;L z-URLezWk%{lrRI<0}CMxSU4>2_QMHY*=G0ev*)y##D%Y)q*_yqToxU#T{Sd0K9c;U zc=*G-vGVg6GGMMYB zs!kC|jP*Y${_fxn;o25uEsyATQq2B-@%g2v|CK@kWm7diIw<}^p#tdjCc5kG|3Q4l z#>*J`32$JPO)6qH{PR!7g^Q#TibLOENStE4d3QN^c^-$b&}cM}gS)_UuS^KxBLq6j z6)2n53C{V#3$IU#g9GbU*{P=GL6PQnU!sZ8i*)FioA&K2qw=a%XZ7b3K#iXnaI@F8uVjHZ4q_f)FaB{&YOo zqL0{=@(ZEXu)?cgUs3EvAJ4!c5#$X)U?PFj+C-<$d#Rtt6i%_@Bsmn6>a`XMLHT?M zv?=`gt7C#F@1Y2#ARL7-RRVowU^sVPmVkxQ#AH;Qeuv=j;#I$R2Fi;zotlc!o*iWr zVO5B0q3A(B$d2`(h3ZO^I6!vwdQb?io49{sUO`fT9NR$MT`7!c665X1YF5Mv-Wo zI-9*@HYs)4)e{h78*VS(dv^tOazBew1NrU0MH@CKb5JPgqdN~yA3*w{hu==W`}@Dg z@8O_mc$kJy|2n;P%tOb!Gc6vb0|frkG7o%$qNr5R-eTk5bwbz=*J=`W8!T3pv9BD! zN()})Js2CXh~(N6>9E|9^F{Wdt(GP$*_fXKE_LO`51Q$Bj4jNqMuUacx4(z}_n&@I zq~r9z1WwWeci!WqvZNa~0AoffKhf9A9h)f#nR~kj!7X+8bw6Jx9i+L=)u*@`bKdq@Ylg}3su~a%*?bP0EArJF>dV`6q z%ugobF?#*zl#rDurBN&hwOmXUi_1Ju%m-SVZ7D^DR-TZ*6zdWU{S0FRN|g^kR80}n z$Aq#Zp)=6t-FGCfQZPPzonCqANqYLF@6!6!IPhwq7!NVT-T@!mQLQ6$`Nz4AjnvW6 zK~`(-UiISTH|b|j{{wB|@qPDgchk6M6PYa*a@Dj`LvwrbDg~ELyhuNM@{8Q&W8(Y9 zRukQO`#~D@>?E7bMz)GZYH80rKy>BIYxJdW{4MniT&E4I?exf9l{`0Wq+$0yaj?VA z_q29yNM5aAq~{!c>1$u$dAnQm{TQ#^i3Ia>T&FL+I!eF!tM`yEelx#gEN|?VC!hH; zUAS~8`AxyYx9}#y@lmc{o^2W$sG=g5x0#$8rXT<8e~K|~vm}^znxN*SjBag{h2D1e zO_2f>Ye0t zrWI0&SeQ<~`5b-YM}MA7$?Rt(%pag2S>IZmg|Uz4$gY71UAP_=>%u}{{k6+vjz*}A zyIos(GI1K5&J3kBZ@|8MZM~ITh9G6>>kGoRFU;O@Y_U+p>y)q%kUlEKNe!n_C{zN0 z2t^{ine4C&0y975R-39X0TyPgmr%kDi+mOS-84S14GlkY91Smf{scC|F~_?Z{G4rZoa(xN}+v zKroII#aO!n-foJ7#wqCQ7KelYtZ|XxkVp@3I;2_<(k=wDEgGf+gnd?SE0ix5i;#EX zlqf&SE(6I!s2A{DCcozrdB&B~yKvhiPjus*VR3=jA=xM|SK0xGB#;M`HB%$62!Ryb zdqSuW0oT;%Vewno-z`pL12$`Je)9#m+tPFeCagUWry^}J0xK<)zZin06x?M&fd?SHNg9|_YjmwUD zLchhkI-M4>+Z6$RwzU!756VK9%R&`pic2L3VyA;tARyL2q44>m+<#)!SmUL-s!&Ry zQV3#^0EH&HlHc+p5|||4*tO(01rXY2_w(s!q2@USGxxiKplZWxWi*}u#bR%Nh{lGM z1D_K2+;fjO0S|$<1eD)uSCrj7!IaXmrou=aDi>m~2)gaI+k}WF(2&Q;uH#%LJ>|VN|cS; z_E7t(wK>n*vioMLsY@$bqA@*%N%_8R^G;f|W@FAho3`(zrqUlS<8=O#FLlqF zjoWF}+T43uS8brJ+i#)4k&v)v((4q33f5xu6P=-w-?Q-fL?RZq2!+aYfC9_uG?T@I zejd*m!LsbNjqS8`*Z!Qcw{)zf?YnLh*QgOAMS)|s*hD?T+9>1RvI^RB^F2IXaxH91 zm>)oy0?U&votB~xqQET}?uQi%@+&r<5|$Q*&wcK5|1J4>(J|8Z6FPNiM4UJRlMBG_ zuvKM=@m9h36i#O`bIHsE0;rjpIfY3!lqx2k_2D^pR5|W3 z4_HhQ3i*2|7V!vSDmMAiP)wMC5vaIJ-Y8CJOwLEl0d^SPFr3s67sb&vVdW*nz*ppPQqm=HjM7sbi=iZY@^ zw4WlOQE>tt2MTcVUXG)g0O8!oSXd~HAe4u)L%s{zCc)3CPUT}Pn)H)Awmfw9f?o*lYHLiw`T+Hf_1kIBeHPaH{=qQw z_2A$6_xKdggCSw*0s#)(V&OzNPGCpFlOhfd-V;Lpb*pR(y8dYP5r3Tb5pbsiw>>y5 z&b$hzWy#G81{60wU!10R&w_e@kQJ640Qv>$5eiB`>}gbc6|Lu^p5;CVfY3FZ6xc!- zrrr~wPomFf0?*P3g$nXS+y#tRv>`0|;RyhJ6=`=LtP*#i-C%VHs}kJZ!Tk^OJ;r@3 zVc;?=@h7x`8>=D9j=lz0c&HmZ3;jR>;}hl5s&5D})$cbOpuETvd5CiJIt-u;aH9rm zY4ioG(ME2M>Ix&TU09!ZZR0Xtyy6#q5#@%(g3ZEx+n5lC0K2XS1&@k81E4=4R*~I` zKBTyPgK{AsFbAN%VHqRq9`%iSna;WeWx=&pOM=Ujc^%eS^e-Mpw0V_P@N&#~(BLr9 z)pIXWU-uCj9Xdm0IRBfs*r}nWkuG23_8uLlRjb!hPfsuH+_j6s(Fnhj!XG-y zl|uj+zbLnvmk3xp9Xst6?~Q2@b0=Ie!dld1h>JA*j(&r_jQT{qK>=>#zKr<<;}1&o zxy)&W01A*hcDZQBdK+!%u+plQ8fs|y0IgYl8{NGBLE5-}9~r_C3XBer(`ZeRBT4aq zk?wo=_o=mI53T8Fr$)z78XgLz`W?ob+G1}ukYj_VJleL_MG3<;vbnf?&7H|B(two@ zl%|hA@lByv!MY121o|!d$NDxib@g}B)YKGBPEOLmz(59_yYMQVJo5{l69QDnb4q*r zPM#~x)UtXTkBhW&O~PQZ(TS5U(a?~h$gJjmyQ*_5x1)_3+BcEip39`;p6>25G&*u# zeCO^s&JbL74G#}z+OLt62)T^T)r5+ zdD1QF5$ha)_g%eevnYFcZ7WsRDpv7o=nZE6-A}I{`dKmsasr~=TN)`4;Wji_sh!^+ z7AtD#biB@SUH$Tx-xYieP|ocLKDC6o0g8|Z_Bp7fc7A0wb(KbHsy5Q-RGfmU`FyUZ znHnbpPXZQZC(5UHgd#BPOMaMV@D_opndh_UaX=!OI1AK2__^e#<%hS3`>!Q?#exC9 zkYEbD-YC^nTf`|SFa=Pi)KpoRiHe9515k1_H>O9!qPzcUwI_dBPFNo8i%kT8NkY8= zoOjInb+vC;9Q|4boNlKljmB(?u^jBzP=P{vyN6qpv~uXHP?C(Pvj3z+TO ztbF%h!18UwqTGMgRnz3eX!4ihu^iohK~RCy*Z_DQ#gzw98Nd63x0VUl6cA2b9o$U* zkd2~|Ae}z`It`7-Naey_Kx`z}t|w=CJylnjY0IiEvYEz3*&vMg$%~$n`>#0w{T2dm z2z}s=5p5^kG(y1Dk_?gyAs-Yf%LQ7leuSGRF8_Sv%mtrNtYFQ;yoox)h8-@Ru5rJI zYas~hkd85c@v(jL%)xAd<7d3Wf&k-b^LmGHsdWWzYIu5vund6zef)lcuZ7?U0b#do zEG&Px41)KTU|nt77WIO z6$^f=uTx?rAV{zjFiBj!9uW5db=Bq!#e%x*a2KR@j|CTE7^5h^`tUH);pz&3mf;Bi z^CN=iH#eH8w?9bdF8OHB_A+roesGw75cOf={_W-bVzh5pndrY>UQcjf&1Q*mu)EMWJ9uZrB*5Mehw`8#wAxHmSEU#I5dv$u z{@^n#Ng%{OdeS2V*|jxhp@={nsY_P_LST(?jlPcG;OYxJDwI=Diekq z_53UJS6})cG&~j-V-<5T+EVmEe(&ab9<%%#-rvUKs5)sicD*kk)?ydeH(bYIEaE-@ zbIO4|6=FOA!o8p>R?K_@N|ld4(m++^N?rQHm2|fEK`y^Z#GwIBzxfQEJN}&btcCY{ z>`(Ze`Tl4hnL}TsuYPxsMgmIt=ga-qhaPGoebw)X_049@-Dk#PJRhEao?bijQ?dR+ z5ddHg2HnEzn+X!HJKqnGFxzx+D6Jqphc zcUbp5@ar_;Z{s$!a{K1Kv}fu%{qp7S(9lq~_};;D_1ho*RhkH_Co8{`*1-ha^ZJ`V zql=eLq?DOkH#o(74ng)^yR^#(S=_gu7@_fCZl1uq4pz~Y_1gU3Cx7n@>B`V<%6LZ` zSb2_Ys7YUs_kG}j57SggaXDt;cg_aNe)iH~I(hP!$rPo(ed2w)$gTSzw^4-3%W{1> zp)Gs*Pt!Bcd^MR;a{o0SXs$KU!EI6=x-jzz@X|>?^^IgI@ruQAasP$=__`a^{nyG; zsuW$)C40q!F*qDdo@T-6t|;x@Q6Wwj0Ws!$uUzxf$Y_N0ytY(Vrce6Lk5VOn{lM)0 zyU&gb<^@a_POvO5EN$CD*aDMdv>i6e5@6!Q$*$xEbzU*+SJu8kredQwHo?reC(Vqb z{0N+i(-bQL3(^gW&s1)pFlNBK$PG(LsWLZULSP_c&5MtJRq8+h8O1^Fuxw zno!y$JJ!w0!18Uwl2Rp8sRBsB7Siw=VAf;9t6X!_jxsR^NE|xu7Vi?va&-gYkuiDC zo^7s_@ZdVvIZhUa<2rEVxf)?wzJSkqn^uT9Qu?pMp#rN`2@TJlr7o79DtMF5cKC0dKQk{`?VA+ z@bj*IPel+E7k_69)G2r&SVq7a1^rRD(6i|2*_X$K;JLa|3EE#%mEP9?#VS=KvR&Uv zcVw>$f;vaL;Wb;DEFul>2a7OR31FWN;XVZR#hjX-i$VoJ{2Z;Z0!XEb z8f!b#2LXErf+_xcp)ot9iqh8T9}BHi(dt!bgM5k=C{^}tSx{{my+Ky(ORXahaPy04A!l*dDpGU)Li_>PaP0{!7oaox1GzT_PPO=flx?ePQ`i* zeg$38mbNuCHabXl zyP~Ane)F&Jd-01!`^Xvp2Re4fOK)5Xi}em`kQg332xq$7931CcotZ@B722 z$8w$zrOI!Aq?vh&JPpP8`VR)EJ1fq8NvSe7bT*o4-=^v1Gx?Fft@7c}*?@?*GFOz8 zDhrPyUZ;eGfKVjy90&7XOtvo_8mE(IJBJe2V3r{KgW29<0*oOT8Y~3Zh=7q% zd?c5E%@vbm`V^xdO~-7jIsrLIoRrxK+T39+>>%)LRLK0SqWM zpV&P24}}Gx5A+UXZgfg09#En{Kmiw0S_+k7fX!GH&%aQntW1RpP-2jmGqPhULBIlG zom8j*P=EwtdO_Vo(G2oO^*IU^0It2X?iuwYL>lfH9gFb16d|Kg$V|nW1ci%Q$N=R) z8oyIQen8-aI4KZzp&cRcoKB%4EEFaq6b*z^EqQD@)+`xyso-(eMTN2 zSk-9}+`(iA_|A!+!I;+=E9j0%f>0EeB(Ok%LM0eV@cPGfz z9j%HI2!yttEucWbngWFv6gFz>76{Fe4$3DahJX-3y!)7kz`>^3L)AzcQ2Iz(U zXf)G0MOYtL6{W~*32lY(fzMDbp`T8;mG^+v3Y5J-YyqYsv=`=FD5TJSsAnDj8{{zn z0cBmaiOUBUU?li>0D^u9E@3TH=H#on+OF|D4L4yB#^Znh#<$?@=g8ARaEkn)j6{^J zXhIpQ#V9IJHmOhn5cC}<+N;XB9?an96#^hwMXVGkja)9Xcz@Ir1kVtxL%@h}w2H?q z1lFiW2=wdgc>ZI;ZwN|1zX}y7L}pf~0Qtts%7ymWoNwfx1(f~+1@aZ%yJXYhqi!Cv zaWa^-1uj@$yfH8NgEs0Psp9o*CGl?ZU1blFi>rI;#7z%ME^*-)HdlLw0x1Wd%qDqleH z8x5-zC|%T8=$I6 zXK<&G-EKu=9@kGOPas?aP*(UY_xKbc&7?abPV<04#XH!Up(`OjP)FCfE~U!@m`ew^ z{xFWQQN*SNeE{_=Ptt*zQlA=zf=k|yP5iWO5Z~e`v+Jp?ZvL2zp5Z8Y{7T)IFuy1+ zriy*V#8iPY9Zay?DB&-Jh-zRS#dufy^u`I`e1I?#bASZa7I|MjAnu10+Cpdu;S+>b zNMF-w6M`|gy+PhX2+Yjwg3nrR5=zJg>K5%N`5x4*mO=&VKd#u^qNlqLl+otZR@$^- z53Sw!E7Z}xnI?KK^MV^7yU~(EwUv!@??ayu*VR@v(AL%y;(m|^mW!9cc>ra>^Q`0K~HEqPLUwt!$5Lii@GW2dW$jOJ?bUI-=+ zAqYN00PHAR&*d>tB05e1|CDg=f;a&Xrq30KPoTEoT`FMygfa|#7{>O@D4>y&NcRzC zLISUk{aDd`BoELV0wJ8#MH~(i0kA{dM`T>0>_ZZ0dpYNUPbxH~iUjV3;skkP%)$}| ziaIE%09b|KVASagKA{9fbzyACxfA2**lCa0pH@|xMLwt-^lQxdBCZZ!3oACs(`iAL z9nS_2C}XOi&V^rnki|$2E6NNj8N>`y){8=c)81;Jzo6gZa1<1bh^Hc_dGMfRT-OK! zj`%3}4y8MQISy@(c`h4B%lBI$&{n8eMV;bsK_LniobXoj%-KNw+AIdK50gMUNnlSs zU0cm3a$~CC6Y4G<9|i9&EiwRG+NX$kf?zP-*ydG64mKVbVSLx#E*LXe0 zdgT>=$43WKpEvEiTdZvq_mDa9riiIXm7AD`e;27Trc_oS*>IQ=Gz?ycS@ilEj4vIXIP0Zz7k!)_Ave$SvR7I4 zacXb2^L(b{_sdttQ_mID8z8qYPNAgxWdI_;$%zmRk4442fqD6rHzrf}V7{2*d!)8QKCKHrv z%2<5kxLd@eLVbE7+V^3Ohtj33-b5EJ`NZ{FWrqbG>PY>3+=m!gHr_M6aonSM9|%^6 z+0QS;4M?C%r=XjJ(D8z)3~!J9RbYlyF21d7^kG0TMR2YT;G3`!FrQngW8q ze89%k$4gdCr9rsQ!3G#U^5@Iq%V@Asw8$gp3Eq_Ibj5EL78}zkQ~rIM{ zeb{h-;9A80h`2Rs`NR~0?<-rp6UCnpA|!St8nGw^ReAER@F%4hU3*+1Zt zM=dBs*|Oaf&Dj;$ET==12kRjO$i-pah%eI&|Mp|Y$z3S zT!E>8zBJREr3I9IXgER*^=8_%)}HEa6R~E zwS|ZlrgQ&=F^qSID;6l(QC6&#K%smHgr$;iltAAV${yY?;)S3LQTi^F=*l&iCs04Q zcA=49p`y6IETnItF5oV0CP0w{OCpKo;r=VrLQuN$LjQx{Qv&^CuI|6o^E?EvQkZ>N z6;nl>o_$X?z_)$;kviV5v?xrqx6@FL>?$g0%NzWNtfIFwpp3!7m1N5J)lXY5)1l=4t2jJ*d!}3F z#m1y3M$aDgiFKnG+$iq9w*I9j`DyvV@VU=@u4JjQjDTQkPCHJdD2zK!GC|4I(qt1G z5SR|4zHs6In7gIQ^n(-aa{QuS2#G7X9A>joD0r4~Vp$HrNufX>ZH2IR2YfNZ(jY48 z2`2$?Dhj`01A)`c%jrZg`Uy6s0N!Oyhg~ex3I4(5Fo{j1kKYfBh1CpK8<{5sOGpDe z9DK3^P^e(@x@UWt*vuiQCN@UiB*UbRQ3Iw(E!4v1wpdFQ2%vB;gaB%*C~VMu{2P=a zIOSHzCS3vy<(cz-amo?%08S3WO$JVJLg{v`S8;ELO)`W8Q*I^DsrrQdd_!&Zu(rjV z*Xm(5Kph=B&kS(Vy^?SfvW&)R;aHw!F2+*D>9A91nOdq~3}gM1r;Z`43j|`~JuwcU zOu<;h3DPaA%v4>bPf>l9fg-^uMMAMu3>De$0Hi^Pv1N@_Tr2Mz9SxD5*BAT_mtSf) zj7s|Y4l6a)8Z({;g6EClu>}3(DWbt49d)!}bFLFXn=z-)$Gl!&vyo~lb}N4?*UgG3 zRz)4HduVjxY%;gy4Xo$WDO3QoP+P4&705ZJZ>5B3gZPY~ypeE#w(Yu2eBZQnzxZ2L zUd{8ffjZXh72ktFFF6gbi_ZXrzN0?n^f68?W1f$zH*Dmwmdx2=1-D9?C9uw5 zeVfZP3O*D32ZFxqbb97Z0%9%0x&yunhkEeWppWxh5fnk;A-sfezO7kX$X+P46e<|& zaDRmQS}cMP94F7kCYtLKd>bs+A$-Mpu0S@@94ecEK7#&$xeLN}HL|}K3e1yOU#F&G zf`5R!FStFtc-1e;4_7|uBlw$*nJrb6AF)r;vQzHQJ+UVfEn7{5%p7YXVo_G@gELFB`U`7iA50_z(@D~YU!!X4OFV{y z^n)ixXkc8KAIi#Ld6%|2n+?#<(BHIx^&0$y_{@DQ$nBw?i}C?V2)T!aTuN(fVZ4KP zkq}maNkB%0@rkt#eO*0|VJu*tz`Oc<*c<0E@$;!r0hF<%)PtXSDy?Tu2fN*vnzN^? zZ(Ng4p@R2Coryh$2H|if?k`rM0+cLOW)HaFs!ooPVt_dgYXEq;V&hq&-Qm`AU@YBV zW`i5WQlDrw~SCbMD|a!fCwaB&fw^N;30c za^Ra2n_qD{F9t=Bfg=2F*bIRAhB6OUIBy*k-nYQ)LJ$Fl5@Y11o#leL^ZBBJ;jCrG z4|R=26&n}X53oQ=h7^F13sw_gb_!LhxIGa%e#R@@xS<`vpusE~0q_wk2f~Z-2~Hag z3#JqEiu#%PfKC3nOMbB_+_S?)t2=F?4`X8nMh-E9wrzINX5J{l7dK8>3IPLu$PPF= zpD0ABGTTvh<0w^@CyG<5*eDcCpR6nv3!zlOco)KGCj7-IKWzT62^1%tx$9v5givB< zr;#?TvQk5pAw|tK2HMbR5iXssbO$LIOV6t=Q=IPFmoYzL zDVWS=Gna|$lRuA)pGoF6d%%?mcoPWJ7n-E|H;HV83V_)opHii_>l9U0*HAPPrpxD# z3AZ2RyWG#~adLf#C#Sb*n2+dxPK!9I9OAy{uxf~iA6spXPqK9nkG zbGYBN^DsnJNhJt)FBvZq?<|4xU_9VAxLVT^JfVKT3jxw?mKxy2u%|`2Fjv510LIt# zKE(?G;xeIJIH-n$Ssv#3v<|9)hs^h061XPYt<&I8SXi&!yr&|mtkQ|t6qx7n8{WCl zu`pLC3Kheg6)KoVQAdRU?YsC&6;!As1t{-ADOE6z)v-C9}#IG9tMGF6e0;;<6(6ePAJM?xZ3^x&xYx>qi(+6L#HqL zh5M)M10yR9T#a<;vPZmAd8LKty)Zeg7wO2GM`(29EO`U{6fwofU`wRPY)|mo93h>4 zig|%<8XZ1KSG%s#(bHp0UJ;i}y2iquuvp7a^n3I#!LxE6>Tv+KgJ^Tih3E^I`wCI4 z%%oJocyH$ME-^Y57V9g3eE=+_qfy1(B6v}(@#xs&!LMg!(S#885JlFQwGK@g;X(Jjr9H$HG89tuamA4u@#Ge&+MyYR(qVJ$Ir;K}!2j`Q#)Jzt30Rb26N=3%1cb{0Mx&AH%NwcQ z;h+{*EH7mP>nhyjpiVK*E(WQgrBIm( zd?!`bY$A)jMf{%a{tf*w+tr*B_&2l7VX=x+`zm?hvckI6Hfn9Q2q8TF;yVP4ptXn< z)M^#K!9^Hi2T7p50wEj>fs3bP;tVK6p@Ov$u5=cZc+)*JnijTXyK2K43zwrx+?x3X z`Vhv`sy4)7vI(UJg!9D`%8mMKZ8lR2w;$RG!Oo>Z1^h&Qpi@fH2HH%Xs@DQfE!+p9 z)ZIIG*H0M#aNh-Jt@Ti~lJ+Cbv z%-lEU3k&~*{0PT%G#=8Y=;hOXdg+v(-nbabNS_Wj`=b`MVaO?&bqE)n+jdgX(H?Edwz($$1oezlQouenJb= zjbM!TY=w$cAY$%^1>e||od(9LXu_=%&ytE|wL(S971=^4R2Bm>DOBWpV~)n*EiJ-f zsJSRqN|-&iteTzWGuHd>{$!929i0;Gl?}A}#VbDEn~l)RhbDLrk?seDV11kRey@b3 z$8zLUN+@C3Lv94INJ6kYI2__d9x*bMQ&Igxh)EI^r*aBCVYQe*xj+C;r<}j+69T)c zN~72W!<`L;^Ejyj%Q4F|rr%4BWyDWmgO81Ff~Qva@kZN=I7kp$F{E-0!Q*fuNDbj) zjjzWh6nSJTSFl-DpLWB-jV$)aYUDq-# z08lg$7eZB!5Z0s>L`u2AxIzePx9ho|m_%9P37zO8xED-vwplCgf$Omq!t>4uv@et? z$|)q}^e_m*8n{3c0?H+Q*=0OVXTVD8B2b_L39fG_E8$KHH81AWW%MGjPJnwdwao%%yK1c`l?V{Tc?i2LrLv8foN9w3O>FZhob5ci(BAi_c z%toPt0}7H1CW}}Pv`BqjHh%s*0=x!Aj4N!s!@(hnM%?1BL@|mL271-zD) zkVpQO-4AdY7X-I8aG5X@3RS3}PHQYs^2G(+vSTORd+URA^Y%T|TG>S5$taDF#&amd z>G*B`mhE)czB|P|TUV`4Io^Vsr`KF1e;i%ydc|(3<;@2KUhbtklX}R&k;nkd_mL0Oc%} zW}{HSxWhaOD-!%w_vhuOP>};Pf8U%>EZ&o5i{)Fg8yy%rb0sJ^w2-Y>K@81eFr7jL z!1xD2kzlo2$?iyB3w|1FA@;v-MTH915bzn8JGH2gLy_4)dq~eWppuo!?9ka*_&B)K z<)>#~8Y_5j0B<5sK0CrZxb~RT!n#()`n81Rhm!lR6^O}sbN@B-VuW^q`!8H+F)M)% zOHdRMs2kKb%rS9N9q}d*fD?al@+{12CW8CJ{9m@wvH{P>5C(&BLHVVND44s#w7jP; zC{Fj`J>d^EpUa*Su!-ey;*AMr5U%;)gB!u>z{o(<3LoM)t$;oNrG&6j;l8tDvr7m! zy*?hdyyJ$8HJo_&`V{LHxUG==1{-W_KEsh1FQ!P-iIbObZ6NOBc8l_FFkgo0HlBxo z;Ar0nr^785lr}d&0T99>9m0TMNO4nuGGXICI2;keCTyAm zA&do`P^Q4$9r{jZTl%yxT(97n5E5#+_?Ru0GNuZIC>ZAe+HG_^D%`cn6GU;8i^md9 zgG%4*C1keQbnd@K)$YIS%h&xE#sbC=+;qV06cj07aB(6SCxdM^Wt;@vH{ihg=_uk}qW7c2E@ll@&1_*Gg=( zLV(z%P{)O+nL4UY^^Uw;pcc|$bi z3uaI#Fu`;D6m@r9AfLOJT-NJi-UnUm3eZGAQDTD^qv#-o{5?FkW-3JBzCzO#n8QFi z)EEE9XJy`3uEBJ7qw#ilC$Wy&XYS{ypF$NXKu4W{-uL!e+P=v_JMZ`cZQK12t!i7( z*M#ZGXHL-6L?VYq$KZa7==1;M|IyYxZ>P=M@1<3B=V zn2YFt@^A&_BE=P$G7l|RK!}4m4etR`yWGkLjAhw};d&NrDS^B&-m_iVP4QX-;hmbG z+|bZb&IrscnA@OCX<{Be+o}(FV%=8*&#Pko4~JYZM;MGeXIf2UCFWtFh1um4$Nu1({}{3KcCy(p=zjDK03%^GPb!h1^>aP^h%jrq__^0ENm+ zuTLbuDS%b#u5D$sYfBkz+vE~s1M33jW69s(AVL3NklI^q1@T6}m^&uiD9#4UFQ!VY zIK#l`$C8N~w(7#L#+XhUIaQkF}}mJV2`zyM%_hZA@R@Fq4AyfDH=2izmUw13`& z6|=7L>2Ij6R8Gx-s`xWb%U$aU(3Nh#P!3^o$AX|1ER>K7x$y&2c*j`%77q5Jjz zpioAXGjjtZcpa1{MWA@o84TP~%6BLzsHwXqY5S(3^5qyr9C~B)xagp zD{Q=p#Cmw_w3nIa0FClodGTt1E?x5D-#ZMHG`k6jAU*M2%qZ=4HJ-{>ScEH9Ja_e&ZcKTXz(7@5j* z$>0dn+4IlRg^N$po5!CJ_e&a@O3x_}4&t5j5iCyC^E`x=uy9e&OX@a*@(ppc)P(uJ zP+HpgZf?MOIU9vaJ~(Svlf_k={H6`W9CFofAfq|ICKtScx^F8ME9ujzOJT9H*g#!F zc_g76V9ILr4#uGTm>0n#*e%M5Ym7(b;9Ei{ zHY&;uWHrZykQ2xjbQL;BXDc4C=Kzm#>YP^zh(8t*@hlD>_XvR=_>@8jdjMDfO-~_B z>KzD*Jf>5qz``GGEDmm!qplQX4!S;E&lRIknLnWJB`qw}Pg?k=6$-dxQY`0}qo;)u z78u!^#92T+k73@%JfH~Xi#`5tg+Jp@nlw_g$e+LIe^2Ci>Xi%D6*OmCsn$e zoeiN~mx2~bB-z-R(V)X>BC)(ZFRIOG610rYV)V!PG#?BN)Vm30;XkJSdWBEN9*MlfJz~juX zX{plOv6W)x?HSic_`PG{2|9iuKyEJo_=M6QYpP>B9~8EJLMWzod6N%DLp8T?CG&1` zw^RWTz#arNR9wrkRH@}TPXbDW;o%UW+A+=KBh(e#6#@wGUuTU{L%EKs?1>ygJ9xv& zwG#MNZ;j-=$7YO^N9F%K9M=nqlAb1g2^yJ-)6hgre9jk;SKgD4ByiFc^Sh+65gU1@ z+Q~Cjm7+wnHiII;8X6y~q_NQoK|YUiO)Ol^_j3Iw#xoQp>ilOSoTA3MHXBka4we!S zWT;Pf7ot$9b?HPLF~C;yE;3t`N#xAwQ?z;GMyjo?rIC>ly5*Kz=*~Ou6yHHRckZME zw;UAL0)dGaDH`k*bIF)bS>v6&o=9sWDJW1ZRumo+SP2#@C?EQUw6rReP}gvysRrK9 z%Y723_|Lc4?Wj+AKRz8bW3H&zcPFul%zr$xAzcbzee1M6!VCY{b&LCEjVr2#e zrpw9uCvHk8IZmAQ3gLD3ffVqB;KODD`T*)p0(}UF-e9c(w|?Leg~c#mhm++f8-$rN z5w3%xt{8%%Z#snvpq$=UTnvRHaH9-CJ_)zAb5YXc*~M9^psgj%9n)E=R3@!X(67N$ zOF+mf6@{3C7tc~f{qE{?W$dZTD1)VErx$`7(NYDxg44`AgHa*LXWY8ONvnB}QeR=9 zo}K`&uR5w=zRSvUf}~(fM=n!>?A%3V8h8U6=i^YNp_=qO-;{~xC}~jY;yLB2JmKXJ zLG81j6T%*opQFw*#`l`_D0@0hS(0^h+wL;zY%)<@xq*6n^OwDo_m?+qwu_Veo+;iR z@}9Ah`|s_$og&T1opq4szkFrizr{i8+AZSR>(~6E?6ppQ{vH=qI`lL=7!=Pz*>|jW z(B@TE8tB7;zIfiUtDgg&Fkjir`8r-MQ)#I8DjpZN?NZ8aqUp=7RqxxGC)m2iD()W} z36eX2I#1As4hL;pYoUNQLKD1ZpzL+LzP#;@N@}e$5xhLWJIGwhuGMGI#!!wHw2tt+ zIK}e{_W4k#L!OAe{cH&`!X+V|`vBpJd75>5wkR|}y@;QZJRkwQ_Z^Kw7Bn4JwcBZo z?~(H;>aVrgnqw8K1@H%_yQWt}W}{@OvhXOm|5|}q3Z)8|Jv~JZXY~1;xK=8_ zn1b2G=FY&Mp_Bl@)U%L&l_x<#8g9l0tkTbZn){X zdX1T0Y-YKAa6)isBqE*-$agW#QA!GD>(MlC9g$e{_IKh@p217L^;>9af zV!Wt~j$Yxh1O==?RC)3F=f&p_e(-}dH8n*iPMi=*L;MYeLiCPz zJtBSw6s1a^SjVo9#K~$=PKSf@eH!_0+vK2C?Kbfq;PLSpmMn!5 z`X!VS#SjGd`4lPu1W3{)?xdTqP2fQUzlH<5WIL?fz@&lq#6}XMXqWGA@Qv1>+HO_Dlr6a;Z_yefC%1T}L}MI;oy{ zz%E{o(EIMbse&47j8x{()5)_Q<~?+D_udM+`#`z4w)-0I_ku*5J8kr?d#XiRFu-%e zSd1E~EcAhgYebsEqND4)_VMfTa~f#ZW(T!0Uv`=IebKm%9=x@ZZof&%^ZX?*`64l!1s)J611ktLXY0BQitgA~mQnUy%(Feryd2WpythNy>v^s?xXYPS_J8+iJ?-4&%qaVN z?yIE(J6+;_S?{}fU%0-*BJRJ)X=6Ta-wqqye``5aaoWgmFje-)xa_r+yoPg|zxam2 zdwt|xjkKHVC|}u;r-z?&((Dl=g)}rf)bRlr4oQRp6oxvI49f zlHXWqz+3?S0{czOz3Rhl#R7c$CT`D}0531kznZpEx%s9VYUF-h2%uOwbI~WtkE+LE zOnAX51Q&W>eV+VM07^=gg~!}`T?q?@g`L}GmphnIY~UaetEyPK;IPXT*c_-g6e|s2 zVlk0R!UjwNLDjD^BLb@hg#zMK1vWV)C;)>mftV>0*svo=eD-*ODJV8Or_cN7h1bUE zwIh>4Foa#5bi_3i1s*p!6)39z@&8l?sDpAvx_l%{*sT*UG$2*)2^*$ zsZC8G=wPOK|L!t6$V@gAD%b!65I*f>#ue#1w<>-@mlGCpb^_ChjX8wLkr;3OOiGKoP{HZ(^cs*! zIM6W{m`o;$g^tqO51ymD_nf7h)*qrRt-lmh;Vg`^-?Y|2J2pG>(sBk)Y4;7J=ln8L zOjyzsN>09huF%SNI&vE4_Dsx;g%DupwGM(q#7DvWDu2Ugq=Rsc`aTFTaVQ9Dqgu!c zz%m5FZ4j=NDC2x23UT?Rg?;<>iNF8zfBsK8a^#4xP8l2=r2Fo>Pq_ceME-eNY_97v zd51z>f#Cpv7A+mmhIf!uJkX{++%D=i10bXZA5<*ikO<~G%;yqldni4!pQT1h3CEY< zS}4IV*TBMCTK^({Sob1tSU`dI!*AF#;4@;-C3TxAfH#DdZw|7mQLAhajzQ6I+x~K4 z(T7Xhnk^!>7e1qp;J*B%2+Tp~FS*Ll!U%%@d_<98X(iu?$>0RRMr8NH%2re#n`BQ|G z57_v;RiHjmh!e9=W=KE~l&x67M_6}2fr5=W6dh2;VUqxbN}-B52!VEQhti``(0zAQ zr-D|m>9EorH!JCP9jvB3e4RW6SHkRoIS;1<<=-pU0>pb1aSBZ`UT8bC8-#nn(koUL z7dVXx;RpO3OJO^#v2cnf8|jg-@&R`*5cGgx(UpDDD;kSZAmGoSXmoldME3Q8!1Pu- zkqAG-&)2Ca7Aj57W@lkf5^{r|9?@uP~FJ3*L5j zHLYs13fj2VK{xG8TOQ2^c5QVEA-I~_nk;nZPAlEK*&^t^y>@!^PFD`CX;bPOYXa`O zX}gnt?S1u`^!{9W|05geS04K`?cR5GjuN7iqn{ zz4VQ5e1p!OJxkyJ{`WEz`EjpkZHEU(f`2PjI^<8LNl-a}ts4vLi$N?2)74#&=p&siw| z9~BJEZCxl-X#p4M5-rUIxIV~2dy6gk2^NJoG?4r<0}568l(2XxwMYpil%NS{`=zhu zVcsMSj)cTUX^8(`>kSA2BK$>T@xrDD!bJRqOC&4|2zswpF5Jj~Fde660VtDTb)v0U zNhTzLQzh77gQQ>t@j7M;2txCnmPfjJQ(r=HkO6C<$ig^y=@*EK=@OK8MZ&J5Hsxg%*m(gkt?CLa3TtBT+se_XUvs|F$AHJy1kE` z_R#asK9fQ2sr;^%CcUnl>rWg#lKfR0FTB#5a}Sg;v&D1@6$r$whPWo>IY^kHK#`w~ zMr|v+sjz{bI}xF$j)XMn!qD92F!)-A@C5|F*fX8XoGsw`2V*~*TI-C|jJP*U?F~j+ z*JjQkId{u@ke2{nSyB?-ioX%$tNdF!HTVcc&HE{CXc51`ofoWrib2%8kA?#W=%VL0 z$y@%{;u(I|e@XtTKo$jcw{@da914*1?t3cf*WOc`m+<@Qc5B8x3rPqPt`@dsD^}(U za9=k$F;1TGK8lBZXVxQg2pdb#R>rTk5v_Bawgrc=UXQW0p{Nnza|Hq3hE^E2|Nqy4*=d1Jf=>U5Uy}= za=yIGni9S&wQCoY6MQlH>b_lNJRTrKH;dRSat?$GxGUX$vFCv6G+d7W&rpOyS+#zx zBY7G-Oo_OkjE0D~Hn)8=DsKTHpSE~U)WXs}eJ)TdRM6&HiaIsP_C{YSDOPSIEb%1u z76BA0iy@zZ6OTm}#IlnnB)Sp7T}o z(5-jVyB~Z^+_SE^UL5R&yHmVFzO{L9X!><~CYXzmo4~c=Y~jp0>^hyxQ8kJwUkM9~ zH0M}C2`dI~!9{nGUm2Duut)(QK(_P7e*f+Yy8B=??buRA)m0YZ-x}A5fX#eO-yi~) zheR-RSh3)QIu`D?g2f6pgld!B{EC&C&D9~KMcvLs(rRe#6xB#uD9X!!*EiLHG55 zh=Y(1c}utgy2!{#L|B;Jw!eaI*;`JxAE*!tQS=LGP9Ke%C~De9^$m?FYHVsILmtHf z(C^)oaXqM}t}gj&F1(>ia#gL$xE{|i8MBT%p|Uk99D+6oa?!V^vrvIcs<+?j%%J;j zDx;3J2dKVoho-Vbra_^SPnjZtCZCB`DoplOc_|07o$?Nj1wx(*&Mc1d2`)(>=!b$? z5`@u?iZywusj*VT3RB;+kOT_>85c}KOR>^k7Nec*dO`0zV59fm?hqu?HaGI-HOs;V zb0FeYVD1~b@c+^E6TeR<5C0i8R2-v69;~3<`*P{QyUOXm{KqCbck*xO+NnRHp3{Fo zy6{PnAM%+FGbvWydxwKQ^WG{txXF|%x1{#6WqzYJ1P_hF z8r4-M+P|w@#CgF1rKWl_*(`ph0ACjs7C8#EYHDF1pR_nnn-0sP6!}nXjSJe+Zl=3- z+3C)`YiaB1HMFUtlWH9n(k1j1@Fi$+BF21GlrCNhkbgXsB1_Cb)%FT%sp+5^M>QG4 zVX?QA3cMaWl_iEaG=l`MIxBh#& z<*t86x83vWboad<Qx7Jr0(3vYIc<Zh3~C^hFVjGKht6rD-g)SN@(#YyoeN{tJf5z+gy}wn3G;S;-P=~ z&X6YkBh%R{K^mT925mg1d5xs+{%nkr2R)|+;^x4j2*MVpLnq?RG&NWR;nWP`PDv~u z#mf9Z_*mzSuR+5k0l}gH1d&BB<<09Ibl>fjbn~8a;ihAX>qTCpg_X!YV!lKF#c6%; zzX+Ti2qtLTCZ`aJ!6g`=H`US3-Fq@#IFcC+jlqji3*<2(!ss8 zFq1-MG4RF-k9a3g-(Z-|Ud$h>rKW23<%J?KQ-Q3|L~uRTZ~kjds$Tc!H05*9L{bR{ z;VtgL$!smRdD(#5w~H6fQ^czX=Zi%!7^Hz~&(X-pFpqVu=VFx3JW}g6{Z(EvSn88k zEglqMTdraShY}>9e0lKBDnV*@OfoIoY69pPkJC4vnxGd>1nA=ROLV!no1T36oS=)n z12pLw%AuZ-L3;efEA-sq^L+g^x^(>t9X=ltbagnE;@ISY7D*EDnVx+LGTUP1;7t`= z=IRWZt&jD5Kw0GYDTHQp7g$)A%0RYa1$!MR$>4sgSb|_?Xe4uenqIMzOwa(VL~!^5 z{SNn{-$8)^mtRndA$CjlZ?J&Hdx4)otQ9p1sUnmU794SAVq_q5C?QUr^U~Q%e(L7= z{iQ=wLitozW1@{~9KteWbvw`HT-K!k)=Z0q+tPyI^yOS`MX`tj38(|L`&*=;oj0s@ zkjYX<)s6R4OxGwBjZkJuw_p= z8k7SjlV17E3(D;`SMf%OH%Pp>TesRK0&`;Ht$tnn&I1u_g0HMY5Q>@HS zAA_*SZbk51y*N=Tfm1+WWI=G-v1Nlp2#&n|xHu8JYpaW#Tn7+*P50g_Z6x4*6Fe!R z?ZXiz&Q3I{^ktjHOo_OGVo^PXA_khAn8+bV>=hAUHyqK6>m)_^yU!m=UpuLgDfGIy z-s{V}UfdJqXC$vn(Zo3ELg#605+}8k>(s!w8y<;>cUaSDqutvwQrL4gnQQSdOnr;0<6k2h`3t&sgji0NryB2L|dQ9(wVS)_s1cHB$t4G&RU{evm0t$CXuyZr&W z*mX+=AzfZ))$iv`^;YgbAu$dm@LrP|2UMU~IdU?;f^fcog9C`4mnLN_RN!SVF}C2h~~%SAkFlRxp9*M!E4jtU@3_JAcV9l!)anBW+&i6zzgIB_lk3 z7h4D|>(a~h9ghXbJ@y(+jl3wzjWVHa;kr)^@EBNMaeCKaQr0O~d6W2yeuj6$J42bZ zP>}7hcr~Skr7uCTPzM_4o|yc^yi$1!ZP|5mN^lCuzY>Z-bv3yvYLh8xEEmPfNcb*t zJN|$io&STsDbF4ct`}*+ia(;-#!VtE6m`;=>Gwo>+q(Nj8Zeajq)2Pp_^D(H?-T&@q@h3bg;4fCq_&-Z zEWV30-+dyja^3$ThiFS(vh07zW&dL?`ySlPWp^dZ{)e>fz^{rlpf~($A}w8ZU9#+d zNUb~nxA>lo*(g*nSI-w=-zeW(3oe(7_V3>>sHLTaZn@=_)b~xBHqpD^{qE$I3Ldz# zP8{sDJF0m-)`>N+z1b#sq-p{EUpuZ6%#YaYAb`va+6THK&T4AB4VmQ!GaBv`b6l; zLGg<)P*SWEj-EcnXZA`17)2;e(AMfUT%L-R`GLu(kQ&neKLj86j5r2C2sC*@fHeo= zSit3vo+ps$PWY}g$QH*bD4}HH_p{sdZ`|0bypwQR9eOg@q;?bsz>;0Y%dhs=1>N-i^{K`Ly>%aVi zN*Wz&C9A$USz-mSDsnm$*JaI(7M`P$KQPW*^oi5ID+$nNef=k6^!MKy&P$Z6FeSA4Ws6100qdL!nI>gh)>cs1#% z*M>9b@s}s)#HHd~4yloy_fK9Nq@TPnNZ)?Otw}E(^NDp$(wnC|;yvTh%pmMgvLLS{6=rnmgc#*{luqv7|HNB5B&s%*F`dDVPDm;9Hml6<7bm~S-&<7>%aX`7Ku zRwYJIHqfT^H72pns1ab^69RTvHDs@?7?(o$o@y&?6slO6P8kbG#R~*HdDr2lk~=Mj}prZ{KNqFL%(A60*e*&al|~*@n7`E)@F;aFog03YZc~p zqtQTSv(m?4?J?g#jt*lYhbnADdpFtX{+r8bU5l9vx**RB6ZHDgDRDrnwbnom6JM($ zeKbnzTg|ko(@brZJrwbsrl9Afcy}lr(MEMOsyH`I!+lD6IqC#EZVI!{^lnVu7kTTc zmtB`CyTc{()Mb@jnE{}b$xK7Nah_RiiT9ChnNfC;XC>KF&ruXTNXsod@~ljz$m>w{ z%8a&*i1w{amR%{6)^j9gqfo(~05Oi{gVwIHr(%uegTvvZ-rioJTzSVk-a)Oct>Qa) zD7V{9Z@lqF@=67p*DD#8*X*UrnvE2W>Zqmw9zo&0it9dkuuTofql(3(r!e^ytexQ! zSK{?ICklQpT;{`DfCLUC7mAWnW%*%wDpiW%KLm=taamzL-U5Lk8|$qaWD$QQ!+{gX zxz{M9o+N-6kKg{Gpdg%>D~?f|D{hQ7Uhc5j6ebp%Nk4B6;kK!wOi#7dM#vATe;~-4 z#;8!H;6xnK;1?N-n{*K*Hr`4%d&{9v#R^<7;KW5Sv}Rt(wrB)b7;4O;6VotV|1j9rSa!NsGnxsr3U27qkJ^n!>TX>jv{9 z+8i#V{5%gj?aEw-)A}%7UoK>~+qs-d#lsQ;FqslU&^u1@@8T8#>Owr4yLUjC!qTs;TmSY#S zr*)5{VV`yfKY98bJ@C$t&@DIZroaE|zocLP=!fZde)B)l9k<_2@A=?wB(KT@Eaza2 zS185!edY?Se5WI=XW~6?yY)8u?|=AN`orJ<&*EKg-G7rvzk2mr@~VXg=Gffz)*!6t zwBViSqo8jx`7Mpf;cj6~l$2TI0785ScI8~2p;(y%Y@9`d(?yL=J>9p*CTM#*m){Z- z|0~ZONixSNzOMC5E#t`P-YAcN66#n z{Y{xt$EbG*i?Amd9u1M(9Tl$gz_VhGL!1$~g~D%GmwS2L#o?cP$fsCQ_ZtXHwAOA| zWOwxhMNAdJuMCIj>UES$6^kWZg(=9StYm>G&(DXCNBRA@&AIkEZZpP>Dl?exgq6&dvY2P)}f z@2;VpYb~^MorMk`o8meOh_-^V?BEV3J#rUctD@iecTM!^4>j;TRzU;(*SH_}>Bvd9 zcvcm^kNBIVXe$=ewMQWUU(nH-J}`y)on0Nz<>@OE5S*SpdzKCzIz)Yaed7D@@UZv` z;c6~2>t{JAR!Ue*XpIq>R%-KX%vPa-eJ#cm6!3EporIr_W5 z`#XB+rI*Bauh%QARkE$u26=4-!ogu)>mp<^>4f#8R@=+{Pq8Rev9fbZ+S-3;G)gZW z8q1MaWCOg)&z>Dkej_R`w^Cby>{_AaDq(Rkx87F5vIQnZ2zB$31egx3-$7O7nHx|r zEYiIKfs+ys@obV8{G zAw68hU`|li&q@b`RuEu87zDRZFCU(wSC6=h4pKZH-MQIy!M_3h2he$X~Cf%?gn`xZlp^IcSj&WaJnt4qvG%OStb-|cEhprDr z>F9Z$bH>x}qE@VE-6IK#1})&QfyAXtmxQ1Qr*b8>gq~fr46i0*@~69oSHWn zcpY-Bq4Ju0siWg2^7xy{A8Mo4mJRfY4>Ztw9<1i}PF`F979!|rRi%;czO^zh;n0T` z#z*_8|JvCZX`m%IyxFQYxMzG7b7xXvMd zJIKEwrU+c^$v%NK39h(c$$`JH_RvzSWXoj|Sqeow57s2;b8b&m1d5lIF>rke1&e$S z3FMI7GPnndd90flPv%AuA|Woc0*=Krt$3LZ9nswTWQvd$yMe z-V?4!)YCF}sc??hf$0-)P zEY`Bi-F~rtXG0zkE*8BbQdy%#X>4Ba6fsvNx_iR()N><37NCVoU4Htvr-qZ?6x?}B z+Cph249{ROyZn*K58Wup?SUnfkVH6~9<(w> z!{soFcYf*6B%M6x6YfgRUi9-ilAwYDf3L7=KtOu*VlDQx)Bu^$V)QXka0HqucW!5ExM=!kaLh>8Ysjf&)Os5KSjCQRu(Ebgkf~cjg za6ilog-b)}Hi1xV&6+jz{qKK2nL>2BJNG>o8kl28c^#3!{M=BV>COrGv%mT$`oll? zuk^LAewlv!gYOB#=l}61Um(ACQ1Cy~AzQIBU+5XCpyQV}aougBEB$MesksRF-Sqvh z{tFj82}|{(RJHnZnzVJ_r)cX2hfq|25TnTF?xUBV z{ug@X7hlVuqp$u*kUH)7>rW(~qO>9E7yM{#m7c6The1(+G|ai{S387)c*+wKF?--{ zM6?$dcTI;~@UKvE;My%4oWhdB?N$_gt&J8Tlm~wSowQuT!Cw>#lm*tb5b|_gR}PxV zgGPM=I9#MyDhwtSH5dWeqaYBn($yZlP`*Ie0t?7XT>&m@nBOH#W>ZwmKZwJ!bE``z zBETczxu&Gm5|j@%do?8ttzA0mo;lY3ILX z(hh|_`k9wRTV#*LDdTS^ulW&QpGlwlKZmG{+ZNVf;HPje1Zhn?ri+1ATNDfQn?e*S z5L_y!rxAy3e&>sohIov}%E%CX?|a`9f>SA2mDVZpJ7RJL{OPy@aJQp{l4510K&w4U zZM2k7D^xIs780>&lm`2IsIRA+Mu)ER*!EI$Q^T}0KHNvcgMBnIbd6qq?IN8z@8x}_ zmyVpAqL<&85C;t$8VVG=(_GLynt8w?6X>&Px@~_I&rMj1l<%YCF?#%&QTqPl!}QBn zCImr|@|AD((MzvS@HJ`NcA%Q7%C+}hTDWk%bfA4XqVN`6_IPVEC-V)s_Zpv4HWriP zAv%9@g07w!r^~0t=)#FH>c8fpk&zG$4k7q!RBR+lxUnDv#k^U8r3p4NO$}DwG}x)L z%_csVyG&%W8JTIdh~Fo;&s@0d6D}6uQl_@bEH=0J?X8SV#frlC0LPCoEF5%Z}nUv z+%CpAc&s3$dI zrUPWF*sn>B^3`Ow8AP3dVA zgi;j;FQ7OHMfGCL!W9%Ot+5`#`eTacr$AD<3F}s=XfT;{yoMnbOM-%7#p-glRz|P} zfglQ2ASlmm2P*0QJFDs7{t96c2+J6(^KeO~B}DfHtTg7XCcUvjd`Ep@4Moh9Kp@KR z6B6?d6bDvYHP6oup&SBl4XYTq5J9;S%-!Z(O;xpabqwixA3|<8z@hjUyca%U#LPw3i;4yw60kxFz|3v^SZ?# z=pLYp=Z+`8+;$NN-TAwW85TDo@g--(RK$18I{0&y-uF1p?{)k>BeT zY2#yQmqT#hD({zNkH=!Ew9K-Pi?m=+m8Vb1)8k1$I~WY6?pMmrW1HJUriH_4d67(0 z&yAj`DUs&)r^iPy7!Yad=TO|Ax?gRnEz{KX;ZEim45s&EvfkBsMnd7#{d$8^A2DWF zWSW|v8y_7LX`xX1*)mV9vZE~x$vo9>icXR=}^kyHa+g?zGBY2o_qQ z0?#GzI&tmVAdO!63mWhG3p#)359#EK|B1f-wLhZj#wluB6HZY((?{N8rB6O)rH{VX zMUOmWqZeQJ3p)IZ-=vGL{|3b)=r3_`s2l4$cn!##vH@50F2~%)J=|;!C*=_{0c$Si zCbh*1fOWd-dO#53S!S+63eNy**+PL>Dy4WT%M;V@5|#pm@?bY8mdop7qX4*h(i-XY zQGcI@HwQR%#T%DUltza`6!P%E_Q!>=6qDP+ZzkX3onwwDruMMV!leKLj=?`OHmfkX zM;wlpCJTR8m{s^`ZfUYn8()WOp?E3h>+!h+saVNWF3A&&Zxs>(kpdJe(&zcuXqb90 zPf#DvKVbGCyvJ!%A2TQe*SvyJfkFkso~00EX<>OQR^|@00~CUny93nS6BL3jH84lO zbq53tAOy+PGRd9^D|M##c$ObaB@qhi==`P3v3CBlpWZy_p_6C5La}1D=&6Cnq!tj9 zWHOvfzj(t>XRglePz9`PYF*XT=(JO7Su8I}U_MbRRv-vn-@$87gDJ-~mYUSC8{_n$ zw^e4)gSWWIm~^F;5|ZOE-(?msET3itQR$LXUNli#LCDBz_h|LrSev(Id41qD9VQq(b^Hz;+0xd7HCPA4p? z6*pOMHHYefLIG{;;@`?#N*!TuBV9#>BMG5IcDcZxDT!F)3WeZHc>RV#2YKGIuRP$H`2C1cMl72;tJP4=HoeoG?~bW`sISnHwAlZ}yto+9KPIKyp| zxu!(JJ{svt&zrDTQ6E++1es5oAD|BwqfpTjUd~56ruhcuO7&b5Oj>av4f{LwZ_@#a zOi_X_Im zev*#7@TYYA`A?B=M6tYs%edvDSTQCBsK2k5`g?oH=4usbX1$vR`ujwh!BQ{MjQTK* z3=fI4bTIM+xhMI4P78$XDaA%OIGM`RVy_cv7X2^{^eK5dDizn77NeI2`};+jwS03b zZE8YEizKR3g8X=>Tck})2FX#@CeqYpud3f8(r~{lyS;LoNHgjqG%?yE(!#MaGKzBQ zDCkx0_4@T>ww8-)V-dGT*@sejIx06RY5bg_0p;C|_Eo7g_vD~RLwzXE;U`7-*_`L_ z@EDg}sbiE~=2=z0Tcp`d6tKBQoQ127GRv|5_t4ZY<^6|Z#=fq@yT;)ohv8X3i z_R6{~BF$zRO+Cjc%Wm*+S(I|>%}pZD?6O;v^`Vb)e#tzo4y8Wq#@`Pu~i;5mh!eEAAJ_3AZ2&m1145ieXh zW>SFZmq!NZiI)fH*~8cA)sww+_)IUoc6w6e(cD=^P4!l4;x(|P!I~4QKmxL=`9Rk| z;rkn`Ne|s!L;H4>=ftJX1`Y(g_Z{`Lro)j;!TdBGDL8#~d48GcGGfzabW0c-%m~^N8WbCx@xwKw|NK=4h( zGXT2JPf_=EuMlRck>CgE5-~!u!Dt{mGc9&ox-2E!Siq)Lv@w&~M1 zPRrq1Ft1R?l#m7(dz=J+D+2-u;R~D@59#Y2pRoyonh46u|U~c*1 z9r^~t6w7IkT;LtD--D}#DxEx61QIkl9?hX}*BF(-MHSbR!)B#$XzmPtg!lh`9&-4b z54Dn?odyHEVZ20&fNVN=y(V(ns*>N99yl!-i70c<$fV*vW9vqxT_F6000?~&X7h+e zP^?v<#azu)!@S$D)X^g4D{w{-W(>M1w(=HQKj4%6LA0a;)^d* zC=}wk!bpuRX3i^flLV#A&dqkQo@OI#Rjgc4o}r;Zs;a7?zMg9|(A$$U<_dxABNqEq zGNpJ7_9^eVbLUQBk%PZiu3QmmHFbLC6?HT)$a5TjZ>W!nSTL9u@S18`)pi$ERdg0b z4o58oe0@222AQwb^TXsE466d1a18Po7#Y+FcefUcMfBmy%1TjwpsCqJ6_v``0_yuWb!g~9o{7wcko6_qv%DHyKF7ix`^B5USrecMU zlP@0R{RKB%9)QQhz7dBo;0_B46;pEhg2EsCgvqR&u1z$>Zy*DV7v9Pj+^(2J6 zm1Rb<^Y1u$kC<3!H{=Z~6A84pTNM}M60~w&E28)>6poGC+xD;_ZZDh7K@N;?o@psXbCqf9` z51<@)hRYt}-@18!rkrxV|A31eChh~g2wHhg$tGAIX2WHQ^W2zwtt7bc%isGIV7zVY ztfVW~Z1m-S{x&`NQb!pddw~6+X3RJwE+Eo+|;NbW9g0jzEG%@e9-y6t3+5zXktN*|Vs28$wnBc=>Qo+-1k~w;05SntZ|IZQ=fhG6 z^No{vR@5uXl@G(i0kI~6&YeF)SGv3C>a}Zhxx1Ig&oE8;M>)?)9*?6mI5J4XV}m08 z60T9xnG5|iJRTt(zw^LYRPg?4K3Wab9mlT|(x7`CCPSgD7#}`OckGVSsBgW<(`0tg$k1upy*@!vLnnnI7LhhKdYL+S zZ7r*8Azw)0Sv~H4a#=jIrlXuD0!<>%NHj!2PdAs{Lc^X7qU?I3mDj=(bZ|$UCb;ZT zo*$qXK-ssh;=X3DrsY&7m` z6L~r~PxtsK+PBq2W4=yNA9xPRe)IMixx?!y9EA*w^PK9TP3?ZtnL9+;^*SSu5g%3A z$EdxT%kEdo4rN6waGCaP4$!cd>x0)k)aT^rdAe(lm&>ly2cA7KcA0jq=eb+oEb>Iz zQO9ky0p%eX#<`ro8mcO=LkZ4mXL zF1yj%$j{-nyzUxcy8vCV76VWY}#sXHmG4f%fJ&Ovno_xz*cQI?QwBl zf&F;3!$20jA~&2Z>L2)A^3(Fe4Wd*@j1}Id($VWmky58+0A2U>#yzozO zsYwL+_l6o1>3D>KsR8q%K54^qy~qd5Scw*k7Qeo63Lk&fK-*&znSJfN6R)tKNb>Kj zNGrbuB(EU<{#QBIKCXQfGhBX6pkY0OdeB$SvEnSldV+Qz16AkG|5+o5Js(30Wd!EDOR9i+`QT<<}V41 z_k2nfSV73KJu)&l(Uq@`P30m=}S+a}_Jsx*+^l zlqwHA@PH`)xpU`);;WADt*TD1Erlpnsw>uszFCY?B@hVE<~2Urw)zS+*N#(T%@EaB z_ETfk0NJg|oH*u=)8Ke4y@v4AER`zoPri1;PU^mLMqFF0QbkLlqQtMT(3Va!edou0 z^o{R4L8BwXG(0pY=+Nu0(ZBuV3A%9MA{lMW8}j-GA?Bst2n~<&+^#ccC{>_PIeGL& z>R7!cr33=Pycl|7%9uc(hJ`fdC$;bt2PweEdHES|y#;q!P|o8-dTL%+Wf$#q>b#FG zUG-D{P)O{Ta1DU#z&pUY1n&t86JSQAN<~ts!uKHE&t*V4kuQ|0CbNm>EV$$%5m(I4 z^#-M_qF71S|H-pH@lM$D;@)zXg)ELu+`q!qP^-8!!+YS+Qe`>wk)du1`MShBbo7+s z@=ck$5r-}+-Vgme#Cbx1bMs~!ZCY)k)vZ=qyZzJjk&pj5-FeTi(oNeB(qH_|lXSf+ z$YVB^LD#Rxshg>+Y#sgaAO1gj+k5_i?!N!msm}Cc^7|q*G?kcf$Bk)gLmSbRo=SS| zh1Y0sV1Tx5-75a>-Lr>&@Pi-H*!UFBed#*J^0ThhK!c-=^s}G;Qe3-X{dzif^eFAS z=_dN|kAFf#!=tHtrcL#nK6ejoS(D&4G0;>%v9L+RqtsG8MlE$yDdiCa`KIVO+SnPSVefh&$VZ;OiQ}|$ zL!7)>dG1&bRk@v}g2_Wii70h8jC0xbH0D$419_I2E>cT9uhmIq3DOc=_U&suTyJS* zNi^6;JJx#19d1>WC3+)g>7(`S9&Tq{sy@)mn|b|gs-8?KOK`tkf0Z`2Po(M?b(G-w zb@M78m%T~kiR%L1er`*Q9j=e0vcza$o}zA$YRV>3?S}g+t=FidVIo6WVu)O%wQYfn zIu84R4wu}GgGv#b)3g|f+qa!B2SmAj`t^*sG-V3=hS&gY>~NDWQlFuKf$~cWi=j|iO2Fc?P+q4HOz`~HUT+rj-E4q$A69j%+U6l;D155$^(5T2QRO`U6la zRUkxB3-$9MpF#!7NuaaQNN=39P*3luXk(MfBot6kprH<7p;1|55Q=mOU7YJMOQ`}y z%BHRRX=vbDs=Pof5hs6K5l}-A3PmXdWopF+AjcyVoI<$~hzV;Ev>$}tRTU=DPEe>| z3}X#~Qb-N#Ss*mVxRt`{8I>wYOBE<~5R(P<1UFrnBM{>S?+=B_;bU&W_d&1^H%d^P zsD(1aqY=U5ploe8(duXemx!;2|PHi%l6w*+}C|`&C zP!{kRH*KHGKR#Q<%5>0Ds!Rur2UwXc2gM4M zDtos&c}y5-+~24q^4tZXccs&vQbIT!)l^}*NNx2~H0a(e6b2BGQ}86MYiFJeLieyD zbcdzN`VPp%j42Bio=s^(`y{!nV<`(3C>-itm#MbgErk2RV#8iVcKrovtq&=Rjbxr? z8l;XU2=W~%#fCoN=R7?;kA-Q(+adCF*vqK3<~q4-UK;hS5qZM8qRMuWYAXU6$|Hw~ z*V#HB`66{G<&nh@q*YB*Jcp;PK){x*Z5|@4$)8ee*sSH$P~JtgWn(GD2J$So^-)9R zWQMZDX7W&Lokz^|QdxpFT-7i@4)b^_Pm9Gt?R9-rVH-^4iL%!?x~R(K&QO-vjD6Ht z6XLAW$`V*Cw$%tx$nr z4dsQ9aXu*%r2)E7m~Vy3a=_q7SO{9gB%(zOn?)}Ko08OukU{`q4+Po}(nxII>=38u zr$a-vgZAIFi{AJC4^m}S4SoC*pQOQ|5qj{UhiL!4owRjLrjQqy2pj0!0Og@X4h>8$ z{dj4vHj4NBm0x*}I8nZJ+YZ{og!e}Jy*IZoOSy>URJDCJvgcq41lI59=n%>QxM`D6 zUyr_1TVbGGn;cYIZV)cuvPo;B2p3*ZtQ3NtktjX+hM%4|#PqsCPaY14G|+3O11T51 z0F(z3HoGF+N<&sep32C=ObQj?@z?x9$N)h31PiR*-d;gKD6XThDxfdcKlK_Yfgtrz z0%ZrPhad#w3RIR9VqlHXQV8KhDwJodJ8ab1ZcnDBfi-w_hh4-0gaCU!fj6osGYEk# z%7*#j^`mY&a>7H;yf`7;b78H-Z#ZCqzM}>L>Epd1+=9|38lGSpr&xGc^r4D!lMsGG z=@VnVKv>5m0p$@CO#qZTIQ`lPt30j?C|h9Vd+1nZOd~+2H;~cnpfzjP&|{B1Mtk?} zr4N1RL-d~ayhrqZ5I%3-x?NnCf!rq40Nk|bXeyl9R_G(rrJfd`pUl1oV-fe@-sOU& zP^h5)$hKZ8)Kr^uV)Q`qk9841-=0m3mAL|nlELA0z0Wqr3gV+--kc5L{qwzFrR^G- zjY?fqRV(uu;(NGkin}@p;!PGM#zuu>I5n1Je2`k_6&{;PqN`FlR8VEVMg|_QKzUU< zPlrY6OE%8a$axy{5q{2;$P*SUGLA`=y(g8YqhgKtTkE`(&a*~|8B%GxP8O5W?`*C% z(ixnDSRPt=)~U*Ab*&bETgs28^0Zed>t=)NY%0%++AS0(lPG(o9YOZFzo6Xa8u5E; z#qm_0daLs8?Ujd8d78_%i@)kT&5jKejhjWD6*i?lQN~bIIn>lxb~cq~kd&Au>O9GQ zi}=&1$}?`-oX*pp&eIpFGyeDL$}^#> z5>`N{V|9J@PbuwD>%7eUOqmM@yh@&EH(f#zsKWvYdDc2Elid;!dE&j1C(3R!45spI z?@-=TVzCt}*rIn->S#-gF-2QD*U;PVd6eFD|9k1?ZM!Mxx6trlEJdS3F$#@GGw9|m z+v%Y@-zDx@*W92S9^knb@1Z4wMA|4~o2mGixdLvt`bLUZYRm-)mVfl3;?^@8ct=Ii zJUz{4U6i1W8^BWKt=CD4vs5X(o-i4KVZrH}7lXj!sOlGT5Y;2kv zZ5hHbBwbHP({`~fhcO18I`Pipj?Nkvy(qpaQW1~1@qj4st@ACgE1lA z$ze(po{#yo)*jDDm-kpT?ujJtskX(r9IAV`&2W#|kf5rpdvFL08>%XdfXw_-De&RXxgLj3W z>+H6Z?I7z%{aa4`82K-k8T}oCkSa?|c^^&#;nXzT=7{&<{A4-^tt0A(^QhqRseeOV zqaSDABkKUbX;67`6G|3o&4Uwplj9+A;!?RI6FBMp&tLx+vN@Ttftozazrr} zE6WuStf>WCVAP-(n-8j;oLIK*zlMVb>a|s9mRn6Dqk7(0FK_o>&5eZ#c4vdRTB^ii zF`AgTO2Hrmh$iM~a1xRiT*ge6Dgfrd?Hh1fFx@w^;SVOLn>T9`9SufusQNOH&r(Gq z+hV1IG+)9DMa zKG4zDO$NGYvyHTrQgg9Xv6w>CT6aD9O##N{(X(lnY=E4DKYX8yo_Zljer8B$`7Z=ypa(VCBWus2+Kf5>DM7)qyjV3_>e1~MT01uj z3xo2i2EN}$Lz7Cp5(_ijuoA+lb1g#u?io;mo=af9S1VKixXB9o%4u+LjBGX=ZQHg@ z(1i;Z#Cw~$zN%`K^%y6^A%r&R3=|Dy##Awx%p$P9XKIXw2GVV&=ke^SR$O!8{Uoqn zW?QSMf&P#FBm^#8R}g|?Pc)q(d0I;qR5g=y^Cf}6xUwn1cR<;J{Sxv(yWn}q18%}# zxq{Da&6ce3sT0>C4Sf-N;EFOHkI?~&hDXH}$Q!&34v*k7ta7E`7<;ancm|wCUB60E zG=&Verz}-~V{aazr=EI>wr}4~-}~P8XwRNKV$MY@pI`jq7j)~b2Wk6`oyn`Y4u`%Y z4tr=@sw68)P#V=`t5TLK04(*Oc#|#x8&vMUBwFe=r7Tr2UgSMeVTXJ06vzn{+foJX zxD*PN=En58IyfB8X!FIeRFObTP0S6mwOGNP#>PdIROxh5O=Y#%i#d5t@-T0V@q_nr z!~Hn#0~|aD7`dl`YKI;Z)>8$^v8$Y!@wl`Ft|t^r|9;EwL#^}$J%RaI1JIY+RL7z^wm zyR(AqW$jdNKTIY=ki3y5&a+A6S#9s;eH!yi2{Xk_Yek;rc0bpTVqGEgv^%Rso=(dM z=eb?vX|%Obo#Q0$`8}yT#dS91iE?t=n%0Ost>zflb8kkTdQ)Xio@8oGE%*N`iYeb${Ok-$;_L{!F^Tc8T1X&WMoT5o>s#oUFxl(>bka!Jg;2Wk*g}R zoP#4F(%Uv>rZLbmV0Ua=G*A|KX`(AhX;hb0Bb1bVekgomg;a1 ziunkK4(1E66ltk7W$+~njY;M`o;i|^KbDQL@rXFkfrB>F(dxK|$6v`(Wg(&Scs#{( z7<0tgH$G0^eB!Jy`R(Zo2;t$TwN7z5r*JG;@#h_dzDakFV#*HG*IH7HS=V)cieYT5 z&-C+MaPE8=n5ORDfY@Y>3+`F-MIsgY*~w(nmqw+tl%1;A8LO zO`;H#BGRZsgvWU-Sm@J+(MYY zcfFPGQBFnxfBTI-;bR-hmiIkeFHU*^XD@o``@ftLLgt;T%=F;hwIUt(^7jU)ejK~(e)2I-$49}`NX&MF-} z_Go&O^uwQz(3$IDArOD~_KH+{AmHJbel#kS03BS->U)0t%qX4e4hu&0{+r8b^LoWy z1vYqp|GgohjA?Mh>Ej=4Np+#0{c?e--B8XVYYql5bu!6W+dUw>mj2>PLjdH=(;sZG$uD?a+(^KQYsuB#(@ z?>ibqI`F-pjnIYum{4du_OAL=Uq5lyLqC1Z$4oP~L$jXVb-!}D2KeV64pHw!LMRd* zK3LB6qiihQZF_4j4v zQ9nEJu6Oafigr!VKYV+LM*ZA&wkUo41L^m9_T>qB{i5Ohplzi`(ZZU@TZ?vTAfZO|Tzcoa@s8XJG2wReyJG^WEU|OIv$aQ@2 z^f)iT%0>?J4y@#=D|lmLFDD!Ke+WY`Hr8|~<6}7kj32B%bi_zc zPUkrTvi4kJz_QfmQ#j+Z-9zH$Dlb>&twMo%8XX-K zZj!dG`Z-m(ti0jVbH7TvzpJj`b;A^+7hj*ESI%oIgy4GW!|$xl;(0Rh^viC#Je+Qq z^^JPEo99h6Ah7!O&!;kCuV?{+O}O$|-)5v8s}<#s1cW#L$a6NVP4ET>ckZC~|JvUx zKV~5siO|o#^9VhCcsQkK1|X=n@LEtP++G*+1RX*MIa@%1fIiaNsO@_@AD}c>*VE2+ zJ^lLczMA}&i=nf>Nl(0Rmj3QvBV2z(?|ev4@4m&Jb9x_m`smw|pJor2%}ob3y_Eb0 zK=>A?FMV&ACb>)t<#>TE;DbD512Dnw_9nF z>j``v_%+lK0?_9J+<`$jk9GO#b>*25!gREyr4EV^DxJrwHUw)ss47N3DX`Y*pH`YGBC?bqGi%{7Gd;y)&@=I0!LH~r$JF?!=t zMC?BlD?9dO_AOxFmPhFyzWhz`S@ta`JHP+^?~AmZ z$$KCtKzxd9K+vXEbgb!2^M**52X|(R<)BbOAHX40HK1&3N{-R&-&>ljsXlbMD;?Ze zon8z^$HHQasiC$M$+ir+e~(jGbpj*tPf_QZokDr-pSVVU{nuZlAOG}e@moIp%a{I~ z8rnCLtD=@hyS_x<_}W+KqG~P2x-a)0fZBp48^v1GxTg$E39$!3ACmDN%d9%uze8CM zCIW3_txyz^mdJ~wk55o2>ZGXk4$|{jGsdovDSBG`KAE_mELJW@e4MXU)~kugZn8QR zt1MgS$Kvlqpq=yFAwJ_eTpxRD zGxCHIDr$cyC(oYA?Nn3WAwJ7Idq$e6rbV%;ka>|( zfJ}yvm``xPM6Fd2avuNxQKWC)vW58-Wz2rz&;OLZ z^DSl0S3}0-!{4W#eLk5=^qEgRM#1=HYGK|8%3)Zn^$i928M!e}Fwf4ng(`5@E~f}y zztDh%%5z8aD^vij`B)40b04x(R2(92D`2a3I_b7}K4CEE$;0#K+Ikzg^Z{}3cDC61 zm-*e6E;UL@m1Tn2yv0H*Re+(3pvgVtDQ z6;?)Sl$0t8N=lWIQUzGPN)@GHmqMum6MVT51F%^c7*d1>IAzku>q75UH-*EPPj~}q zO_1JfpqeJ9IF*9-!09x&*jfoFM6sgfmS(A8F{iC+)Cv{F9fC-nGj8S$b~Dc#^Qlw` z@ZMpN`B6_u5&tkhmxGd0W$u7dB^s&~Lb}-kC*57VA>6v^DPcVVoIcO|hCfrt)Y~7T zOQUGTToj^I`A432#zN_FR&9yWCq9r~r-4G1DgfrKTX))N*V@dvM@y;ljt~5~@?#dD z(0J)5AEuul8pu$pRPy`0@1d&HyqyohsFPyW19akKFTHVelE>og2P4V=`qU@)kk2zr z<;K%IZ|4_60}xm|{*s%<1L-m!SZAbne)Q+bZ@C!1^gHzQtCto@sq%92n}X?-Do_T! z|D#_edwDw^?>zogN~wZ%@O^ieQCqW>j$YcCRI2D{U|?Y0lqxp+ zBn87qk}28%Und2z@3>_x)pX9UQe`@Y3ZPc1;5}iX0)aV5tyBTPZ|EZia_JlyN|k-L zK199OFNwhVYNZO|z>LNe%PFk$9Z9|mSPG>IPXAw5DOFmVEO~{}YKs;d=bP@|x&0h~ zARKEx#uQHIV-Ez>)tafZEp7c@jAA99QUz9^?|;uDyth-<1TE~`y_^2xFaL_nmL$)c zp;Xa+mu#q&DpEOuaUm^LW>Tu)9uOcEF-xITS*{8dSa)C^!uSHRl?e-_Q~_qASb5ul za@x6B*>4TT|A5-sJA_gt9t+cxPd-JT|L@Z~O!?jqe@M-(ioo67_Z9l;m%o&uQ~_qA zSOH|66^f~`N(%aMzzbs(UO{Hxk4h+ExdIB6=8oz4z6=yNez5#~;?YLl<1(+A$gfm! z*sOwgICbh2ZQZ(6%=`F`xLVjB{KjwoCvh$Cqi_Bebq|~pRy>oF6MS!iuJ;Fp(knZ* zDl8h|9&{nFZX1F z^T?QUF>j8zL$tBUMYgy{b5A}Kma|f2Zma5&V|fTJmOo}+PxUpHlwzWx!Ac$L%Bg*= zl^WX(RN3MrSCvhikO6asYqJ$9^NWRQ=UH-9YRtMwi_upX@EMCy{KdkJ^e!tLP@t$c zKG;Y?(Spq@1RKrGHd?c}iaIv%{IkwQb)Dr@)6DY^Z%QFB!3GZ3uM}XzJyVPoFolal zhJr~;p#p(hO_jFq>0)Rh0Hq$P8q6FN(Kw}5!u;dx#mh7{b%spliz)I1&d~X;qtw-R zoF+V{H3`?m6DPSpy-LR~N9f;P4$wdSc#0l>JxI@=3}?{gJPH*6u0Oy1_!xcZJHvv$ z`?GNxnT)0A%ikTzP+H6fFmIha>(xBOY#ZdlS6u{yQ>tAKLk!q@yxF{eflW+h- zKF7(t4z307fS~pA&>H~7kos`Sbbuf`ICez@f1eJqkdORhmy_QB`5yV-MFQ(B4*RG9 zOBGl#!JU^xwqQH^9w_XfOi{--%D!izu~HN&DA#mKg!x9HF;-A78`o%ClEa0O%ju$b zyyG3Bf824$9U`93XFl^8(dHlg;0MKby>Vt9A9Hecj1?TXLS1SRluCsX4mZg5hXNh$ zNkN$JAn+|wiB>u}oy^a**$SuD!f5>(2k#-p(8;@WG&D5Q(@#Gw4)=WQV;`ect5%75 zAMR5R9Xcd<8#Q)sbCOQad)Vr|zCfWiY-B)%dP_0s|Q zJ@=-!Acaacc5E!C-*~KKrY!baz8F~HN|h4k6C5+#&S z!m`FpiWLYFusOq=)7oUEH63t{+)R`$WLS>SD)(Gz-!3DqS>-2_WsHK65emh|cx-wo#GeO7`Y93{(Ilg3 zj4akMX0%5|zv}0?V01!>uct-%;Eft+B#@@wNgX|ZB9tPexg&)M9cKfaN)M}oN9RMi z^_rjx4O%vs`88&Q*854i+!YXRDF9dx^bUmRxtAw|bx<}zNM9^T)ZdFmg=3WVulY9ZTm7vZN`%fOuS%nZ*Vj*eutAgd zZF5YkPyyP@<0(Zu0L2P~piry;7JVYaeH|=twcObuo(hm1s2=k*EP|F2>is_66^9Gd zfaOX)#Y$c&Odh~W9s(!`$<@jcSgpV%=zJ(vg6@;_`m=vYhoApDx_sd$^!EGL(mnTV zp}X$hD(L?Ex6uG1LEXN)-nD~1_3=IQpFX*l-gaLrT{{1BI`qrGqORkgqtAP{EH>>VhwR*LP?|^%{y1O;+(So{8<_gsF zN>Qk2m206^7KVq1g~F|`uaCyZ$Az^XfEZ0UtzIay6)PAksLQz$_8;o` z4uEn6?oO+!s!CL%6;DowgXb9~9@xARk4b-E`n6+laDZ;V{dQqh|M|~7FHi*Bf1+BvzMFZ1V77b5E>8G!{>2w$Gjd5~M z>h;k5Zp#Te&6!1V5!2=1-nizEPd{wZb zv4B#M0)dKti(@%gK?5@-oo#kz`V}`lFuBI5supH6;9hFpEmY>aGKv_rH{w7qVX07> z;0nQXiWR_UP~1%Te04=|qYe>W+wO2FDI_9+MgL{pZ{%my=qs`~H~h-rvloS|%m3V>kn?|bwC`r_aGKl=Bd`ZWFS=l*~`@R47oFZ|u#(>K5I75b0={zJ(t z6*QLVXwN1^V6Fx%Rp0_F8{#Bmp%cdf02}}80}c?-&a7BLp^Gm#_?v9y2wbKXt61q} zzUqtL7!dTsAN)N%@w0Ey6Hk7Ne)Pn@al4+OQO`vh_g)}h_!5;>UMG{aoA-5np%Nks+q?@FbWuYBbz!ivQ|IY8mC zGOk}cGNJH6lgB9*yv%%9f-YY5i5RQdkaP1w14@-2yf7s!R}cpU^*JMw%Tgcn#xI@n z(YK$Qq^`kmdb!G`e3|^0y=C7^8)acP^2`~TT=x0F(s5x!hGN@G?z`Yh|Z)~Q3Jv0ma|nyA+T7K0Q@Tn z*$NeGn7f#1mIC6rP$uT5UU;t{PQ}PBG?!d);%X++5|k_#pb9`*<(>;c;0nPmgjtBa zW8ksru@8ce;R_)4Rw#?Y8H8~s+XE*zXA6JOLT_BymqFKtmAC~GS_&13 zrnXJAY5QJkY;4M)mX5WwW}^}WSpwqFt6uu)%btwu)P#cxP@H3)%twd? z)7Vf(dUF|-H>O>8Ntmo<)V%Is@>>@4CUP}wO!?cFFq$1y)1D5rpA9HfvSWO}J#{hd zQc|eQ4*3)--OL+;E?m_vVVgsArU6 zK4>}fbtROr65(-A(d5J!`NsQbaG;M|F1Yp1PhP%mY;=UCrl#oVi9tGf)ypEkt3a`7q%9<5V0kE5o;u_amM0f`LLxqjBq(5BI_VR?fBV@<@wsoL03HtW zz7_#mpH*qWF&{<7{i#d(7dR{lI3hJk;J}L2VxmMeoGQzWgr!xgsB5}}1wyHkXNw!H z#!5Xvg;HfKE2sqrK%t5i2=j-S37O(ev>?yQqp|VnUD7N!Xem^#@x~R*ECgl{9?XSs zxMjY9USs4grYQ@b1(Z`<;Tg$doxN~#v0yMHsJ$Xn*8rtIf~zWekfP5Kb9H<6;@$(W#l zapfIB`0V3pPQE9W-z^)%)Yhsks81nZWhS9+1B}h-0+G)I2;hGH!nhzc-ZILKtpv}yq${D#mx8+KPSz3sjKneKn|w`QbU?)^yeu7!uJS@bEj!UO@$ z3sS7`&j^w`--6fqv{;!AYHtH@XNbI}1C%gOINc32TaM!)&-R(kBw2KxDv|Cg`-1f6~912jHznb*TO=c@#0 zM|@{3uQ>*zp7$T~Ki3tCNpDOjQI1{=2<3{T(^rE+iGtr38c}bE&VT7Oy7GgQ)c5@5 zRA6{msw{*HFt|mWZl;Vfb8IzZomhZ}F9R%q7^8&QVA(9w%b_5eWhgN+OO8?#l(0ak zuQiEN;A#}ASiv%sxt*G>gS+s zaJ{&P`{#G22pE}P#Oi$jZHl68?2)Z&DO{MuG2_dwH8?V_C z?hA**8P6z$w3I<}MiG@cS8KmZqdI!CD<&-+sJ^0}}`yD&@?j_ZWt27>JaH&sx~ zVxd<~2L&Cu6s8OPaq1Z-y3Ta^T8uZ2$;?$i{FFjr;~~>vH&DGzPpz(a4!Mk(8`6vX z4oA4GTGSuV7IYd7QQ@;(O(Ua<0tste_WG19#2g$Rr&GsY*Q6`wUrt_?hO?|X`Dqa` z%l-r5Uh@ph;iAo@ZThjRtSMr0v_5R_2D4GOHBkH0iQ z-+g9+zW2-kJ@LXBdg|3Hf}T0lOGEBS^7_4?oUAgjNt}Zm-xj_Q4RpuLd)t*xe*ngW1`Z*tTT&`H5N|m{7 zqDm+sFBYV0&1a_hW}?L!6Q!|N!u$f8zhV_DB`iELssN>YZ=j`?YpPw=7U~ATXsxoUQ^RFB=S)M0@Om^ z5rN2^+^(SZS_5rvHwnULq-g~mPu*iuQ8JHw_be44RD(bi0z+)zC*3g`9EtGQQUve8 zkaEHwaj{@=rzKP@6b6HV9IiD~UiVH~vvwcdad11`ea9|AA9=K%9=^MZtmfQtJR91( zL$NTy+@Q8nx!hAluOAKMC{$XTEW+iJ8nuc4LshXq$)e8-G6a5_yh>tr^?{(Oo7O1- z^Bd}B89Qx`!xCd#Td{&~>CC~mtUSdE%3oXsWh+!*)pDsTKv%Bi5@P)H^$k;7`Sa9L z_Df9)d2?MB>L^5w&Sy2R2W8(=QmEuYOQE8+&{=3j1nQ=v)t2#`SB_57-+yaB(2xG@ zYxLwZKcT07@i_hXsi$dt>Hg`v)h_bUt=&E1gY;qoK;Xh8NS_ai^jCNBMs6)PoL94b_y zg70vRqZQ!3P*Q|e^ACjd0P*Vxpsce61d6NLtTR$$t%)L$NCr8at{lp~X09~dGhl@f zjVgkg?DBTDrUg2{O*>t5>rLf(Nel9xx8GMS+`s`4EWiI%_*nvES>lzZ|~F{f`&p7kZkFX-h%ZhGUmhmN1|(d$P&bmWAWj-B?=3I47QfQ)`G z-}TD%pei39oj&gq>1tpsA>Pb%fY7p?+haO{@&*0ZWZyt0+Zr)%YF$?-ke?QzU0Rzh zn!icH?-EdYz4yKfdhFp!ddDMwM)$wxX}aZ(FOc2wPI~#(7`^d&l#U;cWYFucMa6Hw z@$vsh|LgNl)BpX8!}O_-zmM~%qI+&~l2K)Og#7EQQEG9;1#Mlmfo?nSNkPr!8>vd~ zq;g#*RWLPJtLfbj{idLscix-29|Xlsp}@R{6L^*7CNWRJ&0Qp_6K#P~ioZCmA=Gg8#^lyDn} zahA`8(LzDS3&~Zigff(?z{*jqpp3=$NiBs+KC2cyMLr4RBtK==r38MH$hn8#TLSM` zQmABNCWQ)wSx`hQHYP*5X-NxO*MXish%qKaW)l^nqlYBx6CES>> zTkV?tzff9EC@-7kVT`v3u*4;oIdbPNUvmcBf8|4r`6sZ(28!lYhOKlMKKt3v{zu+bBQQE1rnB84G4V838ffh*he!vGo$-<Vl6Zd~ve!r5if!ypdJR z8`bwz+H|ySQ~I8BSNt?G6(=*l#<~tGRaYvDia!veW9R+i#6SgCv-+M3SN*~dIu^t= zys5y30Kg{T$XOr75;}6460~b;+DG=K?f?x;#6&x^H<+m(h05_L85*JluB11Z~^k zOtm*QCKr1n$#&4u25uvX!%&{qtvNC5T|1oxK6p;4HbHB?{pt|^NdgU zgvY7c^_@0uhjiPWycFa*mGzUZQwWIr$K%2sO>3=D^Ib(da6gqee>FhE+;&QxnlkG2 zjnlql{Um7nMn}%ODs5*;`4kO?_EB7slH~Bg6 z6^|3c>i6lo9;Dteybq7NDgzWBi$mi0&qtN}x79MdZbB&_KgwmC0}UVX-Et zywXo(^pK;>M|(C^(ue;2=jp(~J5scL_g*@<@macKUx)@rM@a7oh-)`&h*C#qgj(Ce zGm_cnC8O2L8+|X`eM>t%`m29T2X5p1leBf`Zn|^J&uGWS5DiU^lYy@Xw9Mouc z-|>f3(Ri=sJt1Dm?dAby_;tcJKWJU2mEY^rR963x<~`6Eoj!A(#*_LC2#?BD{@pPj zWdkmqF84>16cN;eI2j``!MC9Q*H$TWDg=mFkFaLQxd;LIC)_c*KAgT^65MwIjm+C% zZmO;{rUZ6?kJlV2?85lLnrAZUczv9nFjtzbb>ynt$bGGfLV-T+%UD-4uNzmrFO=1? z%m}EhR#aD4nM9sBWT+yGa|`Ks^OK1CHLpRr5zh*+@%(?wZkL$k5fA46tzi?|-P8_U|gA?VFrbQ@4q% zWw(*lR!i3|pQn&_lCLpkkeSKltfIZQK0*~0_0&`wqrDru#r><>ZFGXy{7`Zol2DHi z>`O4`0pLrq=A&+5IbpVxalJ=)p3?C<2E=c`R^~;(N9uK*1fSndXPRdz6mZ7|S7A~a zYPDL)Xym!r5T*9|ZgI_+J5Gb+>2{RR>9{@Px6s(AiN{`fUb@g_7X!UJLvq0RDE@ zhA{I2J=9Wjbw+Yp2Iz8Mm^^-1jVVHJ33cDj2KptGo#27M*I^7N_%brdO!o{h)AH_uYjAWIA&G zoC$bWlpnzQq*knH0oS0#el9$xI!*H_fKX+FPizeFL>NugRdA>UL^x z-%afuyJ^k3JD6^#bsO)Y^_w1`bsO%Xox2|5xxA9jpE)I-BVo7Oxn9$Ku7na+DxA&= zdix`vp^jCzF^{u~YAPFe-`+{BEo(EzN@s(PR@H}c#@6ISnEa~we5rx;SCN&VOpMNm`#~`9R7h(J(+Zh9I6=9-T&F-r{#wgxEd6;NSCm}>gk4U)}?*18-29Q>iur?%D4f5P2o%y zDVN`rA(YV&q-|Vlr}`SR5LDvugam|^ZLL;nX|d%H(qYZva2Q1S z)td|my2d9mof$(|HaZ>=%AagPI)rW@2!~@)4@JV`LZK3m1%$Ha;<+-qe4!#m0e5|h zdaqTd()+GgW&DP;i|5O!r^h7XXdo}3ym~7+oYiD=b%^ho@uU>Weur!zV7b9$rTzQ& z3j#K6+LZc^&pUVSB%{?udP8PEMZbkW5r09QZBW=}t_x~3x2+|co%=5nAV16Ra|PPa z%5&cEXhacM8+=sm(u?|12g!$^Pq@-beqU_By#m}1wzs!aTU*qK`el?tPJxB{Bh04qd74>`G2!N|awMAA{CG#ZJX4=22oc86RO?y5- z+YWprgSPH_j9S**Lp9C2sj_Yp*5RoO`m?YGj_{U4@n`+1zG zXz%V$9!nKDbn8u(yk1&U3eKg*;Bb)q{_H~na@O{rOF2rI14@lpEJ})%rGhr2GaH2pe#7bfVrZcc{K-SZ zi#akQ(Fk3+d?|za`+8|I*qOXy?udnk=*lI|TSbF?edGx@C9fz9!GM=MBi$5_WeUrq zk+4YD#j`gk3Ou8HPb5>wgjfwor>H-fl8LeY3lt0I9)rSj5_#_Nj9sBLo>*4l-Y0;~|#^AI)=5WZ@WmH-Qau6)8VC~P34 z&nBe95&|?l!t;bpuFd!jX`!H<^G*n> z6Xb={@ILoB3I~VCKXpzBZt+_-N$ZS4P*zq(d-v`Yev+ZTwlw zC7c>nHI1}(!%m@KkwDsfp|09QMw2q{NkGA(M*mJGp&U{xcuJTJFjjNNE5>oLiWLadF@MY_u!flpi41}%=D=`RShd$x7-&_K znab@t@!RlNn8$Zaq=Png@;Ksj8LtR`t6a)&ApC~@3&Q919hTH@k&vQL!9B1XlO*q% z4?rNNSXCFEVM(F#)>EiRWGhw*0p?US1%m-$t*48RlUX-J7V0KT;v6~kC&?CjfzBWQ zK0WobFVHJ5{w$e82_@Wkh($c44?IVS;CYG!CxyjqEE>xhFCZ--U_6xe^|h7^#R}%J z3QHm{xlFk`vYGCIM}tCu`Jqs2Ic;FhEQD4Tu*Awz_vdb@=7bDh09CJ|Xf#fi8Tj~> zjurNHa~T}V3pdW2%mbE5WvtvbS*((m8mffFK|aMwcTZ5n?$9LO$d+iX6v`o-7A{nw zf@{E77ekqt|3N+%L1$PfmeO@HIHK)OJ{xAehm5hyxZiuA$Z(PZwKIC=aCz4YQs8TWwjoGVwl=<2ngqA*AjgvD88%E}cI{ zeb+CEG$>TYM+d~`LLgnA<^!xyaN1w(Ru|SQh(80jIyReLxSKtD(U;+-X|{l+%ewYS zx_93Ny62|zw0+eP+Su|ct#5fVd4*yz0HJLz&HUVaLXr8vf(mYt^@3zSeWtTjtjIMI z@cE-cC_WeRs|4g$V}fqqW}|!eI0W6k%`RLXL-AQ*j?Xu}=H+kbEcCsl>cK=(l-?qfN$tL-n z^6hRmS!XxRaeCq^_ilBoOQY$%vUd_BK=k%Mzx&=L9>50>AVCtt!B4tF;Ng|~ZaMdq zd(Qc}obuyu{tLSN#&6TP*Zz=BzWjga#4Dep6R-Xgz46kQ>GC_kK+NnRH>nDDfp8MJ_(z8$fd`|h+cYdrpx4!e-Bn^*7#hR!! ztbjVd=iyfR=O1pPpZRbPz5j#%fj;ojKcL_Iy%*_s|KN4{jbHma8oKVLlds3-%Zb-w z^!$tQobqe`;dAt<-+WqJ)6lqAcxWPx0LsL4oY%mGG#7kWaIW$^@O`B5%ySSiSKp9|0 zam1e#IV9?xN7l8kEa@%=|J>i<~M=UJK0x`S?tNM#tmSH=Y!61{>V!bND!} zxzZb<2)`2YfB5)0b0Ot9V=PSH99438)HC0VwpX4Lr>lJt5z`;nG}L9U!LHLABXQ9M zh&erf4L|Eze}v|k*eScuEHuZ$8IFU2l-D4q3Iuskx0yIy=jY6-IYXMfhzFgbDgF)2 z`^{k<8+;LRd1S9ii2NwXGXmprgWE`PZbb1MzUKN+T!chH&JZZLC8krd*?h;uxAvtNoD4Uc==Y_cwBei1w*d;$`EwXrGY; zk5>cvT$=tC*Tg82RC0zibKT~`DRCSMvR>|QnNvmEK2Uf~bNgV-)jRng296_S%Jo6z zT}3}Ios-wx;A_x#N}GyH#BsFgwLxYWMEmf&dKSJb`p(CF2c`nYN155^<@b>}RT{k7 zeu&a|K-pQ?$aO<3?rENf`0XmUPc&r|IaTU3?*k?Bo(^+!%CxM&0M8Zm$UN? zyZ-ZmISHisexLu+>-6k1Pt&$7o9Tt;o~7Zz0s70&ewJQ*=?!||XggiKaf5;}CH_8& zA(f)P|2(dFmO9(p=+&2BqEIkEfBJv_kGSUOp>`S_ySX5z%9o!yPESAm91C0-I(_m4 z%>`!Z|9s|ui)(gmtEaw!Ugi&!ydx+fUYno#+FSIaA3ZPb-`{&vlxLs*5qk7*OH6<9CP)`Pt6!pH&xAUqUs4CjLm7Asgw?db#=xvikA zEL6}(OqrR^W@tlQnl`tYslDEyTUzUszfE;sYHQv|gTu%@wY2$%UAmnu4%*VyL~V5u z+SHPvcOUc6o*pZu!f}z%J^%S0UL*YB>{#_OFLHRFTdeDjhDStB72xWXEA)lW{}Wxl ze3?$3JV~ccoubjvQ95(x3{6f>lHc#ApZw{M&(}RN^ExFWH^t}6eQ}xzrG+r&W`3`= z!6fD#kfcs#T6T%g{Wnh2#K=uyRDo9&AiS$)r+JQ>XxrXn;#ej*#`EEv_>8_gbt#)u zMJPr!^BHp-Ygj(8R%z!c3}%RD4KF5KAL0JSeA?K#i)Lp7qHW<>R89db#t5Zj*ZAIH zzGsl%EkMCwQ1GUx*YHGgK|UD3U@(%?wt?#F>(wI*QK=jN@TduehnUC8Zgs@`z?jDx zp#}Kcjuz{D7%RO31C;~}`F&$a!NWjMuV+3%qMV#6_00Q#PL-QeB_HVDQgf`}c^DG_ zlsb6!a*Ea)3cTxkA8r(0TP&o^$9#H8WhR^!GND`(L7(s)dWn1X*YUbzBD2*)G4tcR z)>x>erG@{R$z*ZRjhp>~S1g8K{@4GWEH=(jzjuL#Mx)G(un@sD*}cupjPOFiU%{GHwc=RLoAeHZ znNTTrfJIm`bvOINDif0tu?>sGpq|GHHYtRU8(b&AmRA+@HH;uovgglb9LMkZ*8ot8 ziEHvE<6_r|Jq{42vKkuPOOC z3^}%Oe*XOmw-2s?LakW)=+~i~egGEKTm6Ifgb~e_cP{`69PvKfKX>i-h+_y%149+A z5p@$sv%ob_5L$V%9^9+MwujJutv@zTc93^qF`*A(W^kQU@K+D2tv)M*)i9_4J8xd2 zPG_1tHUl;JJQSJ>sJ|=^QD(TOco_ms#jYF}S)eqM!)|wr^0yFRy!~O=M}6cHa|dr; z?47YeWL#Cq?rAsByWamK#T*|N-z8=z&rqlNFX_)eKSutzLdd&2a(6=)gHXzZQeuAH zyUR+4AO2UAupUu=RS+KkA=#tfpuhd*G=-ANeYf@~3N#7yCyeocC6%JL-sZ+(yzhPQ z6Fb)sg6NGm-Vn!r;p6wy)tj$SAdy|H+~yR${Hk(|^gO`d*I$2K9Q&D%-B104uduL| zy~bfm)0=Omm_H!;$VWaRu7Nkh(@#Gwe*e&W?3eR zF%dmK-%H){T714DLGI94oUb>Cd@*8kimGrub#6{5Cb4t99N_G`x0>kw zyS>T*9h|)sre{t@1TB?)s&_v6IAMQCe4d@1rLjp1ZP~t^{=fhBDe`y}x?C=x$bb0p zchR2x2Wf0{gxZ@^yNMqBu6WJ)TYA6mTh<}AH@AtB}h==V>*%S+uY3MbdF<#)(g ze}F<$z4U`0{DA(~XZ}(gFNCK)|L4@yv5lw@7>QPNrXqLKKPXtdMU zI*zJG7Xtj0tX;jvcxW(~$(%VNa;mH}lF1~u)2l3hjFQ%S2L@l{^U$^*`mY#eGw>LC z_?Th{f+yI;DcT;v+Lf47YuyeDf+d*-ES zdgE$BY&`mf4>fZ?DYOyS{QWn^X*z18!&|NN&If(sIPlUNGxYNLnBWb6=6#LS+@Q=i z(8a&{${0=YHTyQ0=>w1DdRqSA%@EBnpH>=*)6beg<<>W-0C-QCaQ?#&*3*`aSdW$Z zymkF2m}XdM%a$$T`^ne7O_8|?)#ETX9u1B?`SZUg=5{7IM4t3t()XU7r1L}i##MN+ z6f%-VQ_cKau71gCWxg&JC9A_nX0u%=d2M!|@|TYRjV&AL>ZQx{y>EU^e3xiyY9bSM zUer*-Ee?m%MUTJt37VZArl9`@g@YrMPR)sVr-dOCC1Yk<{g%ZT%RCbiq*mg9v({(s{0p1pf{?kPO_Xa4XH$mOupg$oyi?0}qm@M^wz@gi+!{`TzI zv-BsQ{VQ=U@Ef1{IkLL?$nC^tQfzWlj4IcAL)7TY(nX2Q8(mx%^~)^{eV!Cvo!~`* zNA9Ypdk-p`Sb-$-q1V1}LhzeffIXX2*%TzJ-=wn-=iIpZp+vx-VzcV&@8_ZkGV=&% z^V$fyK8G>3K%Z4A_Wn_2bOS4aD)UsyP;;ZLfTxQ7V7e8t+&8JHr^*TfIt=Nl0>!kp zNO=qAV6tm}Q-8`iCJP|0$t(Q7K>l$Q0Dtn2;~0Rtq}uo*GiWDTt?yG&-bQ^WOKqSL~*TvSemv zM(onxwu7(n=U#)|=i?*FZg!lHgx4_KAciy0v$>Nd=f=cm331I>Mi^pXRDnTd^XAQh zc1%o6@IBgSHa?}EO-uGv!7eu_z-NOg8Xk?&TqrFKkQ0H=imhWsZ(vGdoWVYCJ zOE?mvfk~#65JFkv*t<#DftQbzWg8`|M=4{hqhQEL(MW_E8XM{5=bv4cr^==++o+|j zokDYSWOucZ#nCLDVNRSOV>-7l0C=AEPbmGqX@i}5+ALHjJdO=CG;W~2YiDU{;tEB1 zoNwuIQBzAJb#H9tan&Nq-renVU|&1kcesOTPl`r{F3@oQDXz?UG8<-vH|E8giq|Uu z?Wo5usHkD@K4wY>Mg3tSHI!4EcOv zUcctZW)F&DGzTaU_Vb+c^H>g%+Y=JU?R?IJf1K|-C)UnFMT@R>n=ssov9ikY&`5r5vKiKF|xEMuWPt2rfjQhpUe1&{ZC}!Ys0^rD6 zc&bPQnJ(n^xAMN)4Qva?#BzbUDFvP?hxfWgC^|s#xLW9`0>Gm@-%|y^HPTb1v%!>O zXvg|Kpn9qt*x?jo3cv8aA{HPX&4S)~ndZ74y}qM_%q?@$aigUYRKP>IG&G(DSQ z{s_Cn&GY4fgVIrC-jrcv6nCCu{)b4)3lH#q6kg&>7huP&_@C%i{?Y*2X94B081 zIV?U)PZi+e`E&HcAAFw<95^60gkV$8E3dpF3@YFH*0<=D3Xqv3%1T{6-#D)i#%e-KfsjIUHZ_`^Jc!z}rybjtM*u?8&DV{1Ir`Y_9!}zUD z+4q`*ay?ZnX0z~C(ZgIcNp&^@*)1k@gYNqDRH?%7Uxkb+HAqySJu>`(4|Pt5LLl)!YNfmaS}k|FNUVlI1v{EChG1yh z5S;o%lhUkwHo7*@c{@vs&sW>kT0b=GL5jrVkjy2@~bFg`(%VKFcCTv%vS z*}c%H60Sa@3Jey~sPa=k^;0}o<06r`%zLqS??#%MQ9ie~SViJ)pVv$mFDToca6Y^x zVDPwf>5@2h_|Rq+a>m7Z+H&=Z!mD6M8UW!*UbA&;C(T6`?$SryP)F1W&w&v^deLm$ z&`R-CHs<+KjVgdtl0r5>XqzT}PXL08^bjrwX!)(1kI|8L{Uv$YKf0heTRu#t@Q-LR z7$rN;#nvVZ9ow%zC{yO1`LTrDJaa*1SMP~8Ut5+@rF%mg_mfSGU67^6@;Yn;dUMOdO;SjHjPibq7*>iw7(;yg9(*}G zeY89R_z%zw*}CN!RV-XjB?MO?lwwrDm_RakZM`JWcUq$g!kD4HptVaaRon8URFbaTh>3FUa+EILh|_FKLtxXvkx%w>2jg-2psb4`rp z#SEol8JhH`#qq1^Z$o2A3iCC|gn@4KE7x4S7NZMSqvDz*-^)LvT!Zr6XJ_c`vtjBV zh|@s95~JafI7Ol0QNzmW6&Wt75NZaM>h@6ahdOCsIK<;0G(bJb*tr+W zJg&kbY~!^{CuwY?pBzrlyywdHz4wc`EsZL`xtk072H4$W7j#q)0eXn6`RgPTs9-R= z^EsJJkcno=kcp7ZFh;|JecX3_bo1JE8XwKwx?MA>)UaNF`L%Vkn_@9|ksHWtHdCF~ z%g1xaw>5c+dA14ln*tc!wMG>HwA??N5MC6!Ho2Mq!G;ihqsot8c%Cxp6t%avi;%G3 zKQXWN?Ab#PKKLL#^UO2!{tson{Ub9k(#7k8ERQgc5jFCo;pjeR?tLD~Ph|1Qs_}w71X$3tb<^`Z&K&Xzz z02+iaUjP(H5H0~2$h12vD}r0A8><4MAIEbA`PK4JLFg$-1Kyn)qHgyJg#St?;lJ=0 zFqUw6#;ORW5-1k_E6nGHyPL^(s7oYef8nf>&q@oSWN~MeY74@DJ+_I$iQI50nRJ-y z9b**>|8@7_?G%aU?jAN}{FF{i(cgY^s$lppC>)W`35drsbm6q3^!fRp|9Rnx56Dnn zKk*X}(B+%2<%|vBsV^)2bmYhp5&8>8mCtKX`Lgc=NgJ271qt+`g2Er|YwYM_H#Z6g00j1jLNpQV^i|HA7b ztQwT_!+^>$B#&r+ySixjFUNccuAXj(kcpNX{tLPP@;4nwfG=&+D7u%68`q=s+A9Id z4^woj!_BmG`|hQ;)9r3h0X8swlk}q+Lw-%p)-z2D(Egp+@R3~yKK71WBd=cguWJ`x z6`%ExAO7pDQ?vBSMSY{nzV5>L6T&gYh?5TkMR=V{lEu7`mLrcU!WsppeH0C6*DjzI z{;P)d0*fg^hxd+%&*7MZ|H7u8 zKl#ib(wD#VC2_nEUU>OcGQktVWTyY~2fswK(JSO~npuA3Ix)M9P331V1x22(d~E4) zGfh~?m#!Bm;lC8xrG)>=-INs^4^cA4@{p_v$6J2g%%iI8BhLaGX9XA|@1x#D5j z;lHpM(x^jx!Ou<4#b{H5h5HYAvv`d(#&qScQc%s|zlw8`RfF|28CLR5uxnNV3>v~$ z=n1$r)UeiAikAw2gqbzeP(x)<*r1{aiYsYQ$wv+^R>5hmy_M8AlzRIhGn|=i|AB5! zzlY|c`Z+PiC*wtTLR*Xh^4f0Z6c|)02`InwpW(L8sK1sE7%BiLPPNE4wqb|51iVI2 zWNs7y{0Gj-FIv6?O57A&P)Y@XFU%12O z76TpIV;ALtJM7||U0qovirti*Dxw(LWfY)93od{Z5`#?vL{N+mkuZmjwyaO9hM& zP+X&|ltCp2YS$Z#3l#!u3GCd=Z?|gP7N3b)>P@t3lbwF< zqpkEWeyTmEeDKkR9D1Lx2+sG&ttKExiMIHhO2T(pmWvzL3LA}XSKN*U6?i-q0@lxJ zGpGPf-WfW$D=iEvSi7KuK)HN9cT8i0!`$4Q*p-elF)_w`K|;4A(iRa;6z8Sl$`1LP z{Sn2(S*N^qDN3(i)Gw!Q4C|JYH~jSG)u1rcN?MlyduxZFH4;#asLf^;kjqjZ-o(?zDAL-LPxOi<-JLf)&}Z1)J~87;(oH&kuZLqU8dpOR8~uZo}{7sY@Eg2Ud=iobB(}nA-7PmKzsZLa|PpY|l;ijk+ zS|CtB5QmZ_Kl}~c8WH9Ozrn>6pItoO7mVi`Rt%sc@Gz06RQN9lfHGEk4XcmE4Jw8e zH>fC~r%Yr_ZlkR-({HY-W5p=i;D|Jt!t-|GOVRQN9_X!L+kI>o|&q5gW| zzuMZ`==AB+B8<@Js1l0n-lLnzU>p+$aa@P7f!rf9r^=I0J}L5>AUxOPqUNu_9$K+^Q+~#V!-o%(!{HFuAWQ(B ziSS#iF zbUbo>96RWy4PEy6d-%AG-#(Y^SKMc2B1oV6hv(=kU-~k=^74=ARW8pz`!xO8pZ*#B z=;;@!xgkNXpYhX_KPke@y?iPx%8AQL?vlkyJX${=va4L6pJpO+G~|!u-gh#uXnvax zBb0-(USr%!U@XZw0cgECv=HN`!Uh$LCp;^Y9HDq@oMPcY5mHF2eAGjJ2rXPw7|Q$R zhW{%49bijDcq$33t5{$2+i~eAKl~RAn)xAY^p52N;lGT=5ndl=1uvi+Qw*)UH`&SK zG?K~M!h*Cbx0qdGC+ykFOd}*+;&}t$n{uQu77zbrQTruTvG8Bo@EY4%P4td?ytI3> zU6j3B?X<1iMxD)OQO@@+bKMGiX>c^K?smYtTt?cx+bKMI^a|Eh%vCM@0B%Qv3X(iG zHCTC_Gv@H#P#Pk{o_5^^x;q`hQ>>ccS81={ALB_8kp!NMD1!r6C^&PGMh9P_Q*V8X zMuVf|YvJ|O&HO=<`HFay8a;8cyUet2pO0ES=c&>03SGJQI-S2VM-x*C3MTa5x6z&< zHD^H>p{;P)d0wfr} z_t;}p=k$=Jj^$Du)O8A zDg6WE3&MYCpH&WO;lBzX8~!UIm=yi+Uu#yq6+tE5W}Jx#5_w9rx7z1p`of?x!put) zGeiX##s#6ks|85f&yZ3Lx90~2pysQ z4FU^XJ0V!K@;Q}7wYHc(DqGv)cY|Q075Zx7zixdjZcu^JJhI{*DoXe-6B!b_=v~HV zsN0<&4?m)@-b3L~1-8yGU{IM>!+$X;5iw;`%zq+m6BHYT!hbQpNt11lk>l9ErvCnZ z>aKr=o_qV!e4B*AX&Rf13tA-s+J(l`hW~p1J99&SX;G>0U-#Xu??n>`rb-U~Wlg8( z&EpDVe(2C4^7(w?v-CXq-T(SHd0nUI`IFIkV;j6Ze*B8UYsk=F+E89U|M3TCbO1_0 zwZ7yP8V+XP3tk*=zM10dNrdr&w+Uh?|NYtFx6`255>_ET5O6}mB%RnSU+cIheB8*M52<)3U-zbSwx!54lwLy?qGD0lDP zYNB`Cr?i8_voHJUjcdv~<6VB@@p@`&$*xBjTc7=6wqJ1{Lnuin&MV_YhCF-hvB&7s zpZ+w@D?9z-#~k$P#o&Ank#Z68_be;?m&rCkR=Z}tl~@fWY*m(qYr}sPGN?fDJ}^?6 zK_!*6P-xb}Ylza8r2upaKs~@?xP94NJ9<#)TJ|0E!+&KPL_1IQ!hdDbMhg1th2S`^ zIn_Yc4?z9U9x(9A9EdQoSe-#KSrq!*)1~n47{kcxQ3$A)*<@aJ_%EQ85Mc0Pn+?86 zCi9S}7uFPs9c@PX@W+0ey0<*49?3;C5~SbwFOSaCrEMxtQ3}>N{MX%EE%f*U`eB5C zKmFSDB8EAj@B}l@HqfhQ`e?m{|7vbA)5GsjLKhZ7zJZ~!!7B38NZc+46_=_U6zj7p zF99>X$0PwVTDmC~5(N8gvvue!DgJtn-HGLT#_bgLk;;{=4<85$HkZy|WS^>ppZCHnf8{z*NepcekChV=r6(?#!l@+T=0QRXey($4Pg z1-zFl`nP0Bomampi1VEMo39KP4FBb|6`ow+muKU-*MUCz)N3MLK1^?3pZ)aYs zam{2XLlM=G0Q#Y~Ar16@(*_scugK(H2UslpmmaQs{%uMGV+1x_ZaUn_X5UA9&#!g6?5E2*}i>f=uvEz-I zGA2BB)glOhajS&_tDzbIVHben0D|g978341+Cca4LeSOj5V=;M>>c9qx@U)*9=L~p zJ5(=n2VrM6gm*C9wXwW_1~m_@vr`^C|~^YSH$tw zmL_#<!)SRk31|X~gU;XM=#b4m`jrfucDwTkRg-(Y#oh_!tOR?Hwm$lZQ zf?agi`@*8!=toY#()uKwGLhBnBaf@K zG8Ls*R9~@L==iM;nQ*-@79USHMk^Z{@>YW6K_s+e8p`zB$)HjVfVYVZ;Z;r<7+%a@6%i&SpAXy9)b3n5}BVIn2m`}gc{QFn(!ERc8X z_E1xUg%a@;Irz6bc6q3^$tK1x1omR#9BQZx{4+_h8%}zb)Nt#g+6*f2utd0~6@`XO zLZMNB|6YI~H`An138Rxt#OSNvAEk@e!qhvMRjlY4R`Qkj@V3h@@V=8_I*S2@0Hq!1p4pB#E7qxeE%$M#B8^v)ly6DB%XLH5|fZw+7+?{hxS9iBK zo-V**?%H=J?bx+9=Nc4TBtNhMCzsbY& zu*ob6KIi|AvRuFeP2Q{3hkBX$ul}=+-oboRi(*VfxWCl|^e^aFpe~P&C!#@$&-Sa| zvWQ1!C^&ve{ZJw_HVg13FnI>ECkI6jyXA~O# zCkl;yorW&{H4R?)Tu$k~c~0mB@=LX$ttB^XWDWYjnj|9_2FkOA=RmBvSfcZm=_E6W zkh#q!<87gOuJZ6->#GYY{WegL4Uh3G5I0uto*N2`^h1F$^Oj>(tSYRpJ}(Ppzk1;d zs<9OzeBbB`i@#9p9zNg|yT%nkCBx&^LR0=YUAh{gqj%K{`?_(aJS!I&Gwz*Eg+L_^&VzH|-9b2+Qp7LILeDGc&0d{tJ0nF3dXUxOtcO z?w^TJ#KN@8q|6D7UF^=5yYclxfdTc_;>KU(6p$fs^22`#g9_6|KoeCBf03k@-oH7f1kenT1dnP9vfG}1r)<-h5rI({b{;+Rk;SnlwG@aiKPA) zE?nR_W~Y63nYq6gD*q%#xxX=g5e5bGwWZ0Tgql-v`b6up!hb#d_`7J&{)03&Izmm& zE##?F!lyVwpCfbPjQFg@OK;B5%NG(tv85OO3t>8?f>6>OjMbfOM%uG|@z4Z7lzN!I zC3^Xdh{&OX9h3+;RgM=0k|BTMqxF$cH7?9)Uu6+sGvVrG(dWv>zR_cOHQ~8PR zQE$|LW-d+NcxjH?D@AV0T_SX!^oUwX_=A_IxoK3;CZ(U1`fcPX)7g2H{_cy%$zU|m z(Ibih5#v1&3^3hI(Vo3Lrb`O{mHQr7i-Z+gjqqRlHnh<0JO34RbaaUCTEJlXzyIu) z#Al3utx~>Jyz*jzCMObfJBI%Pv|*##n2tz!R^c}b_v3mrsDPGg6_%?V{tNAmb_e)1 z76n*G@R6k=-=NYv5EXwVpcI9yCxLgCza#&ym-!+<+drDUq!j@k*V1aI-s^7iYj_f% z7XGV-^@3C?Ob+)=^;`MCJSouuc}0OJKG1{SP6n0bg#QANXH=?*@9tFOVxXMxUk;l^ zgaFGY|FJ}h63n-E`LcYwnb+uA_^%q4h5Uh534jUfVB(>bIZEy3rS<-u@`xqY9+E0zf{M!NEaMO2KR}CFbwp10F7Q!lP4bP`Q=R;4=%O zM1I+_xq&+F_)Sq-_xuKpX8r{=ZvD5^u;Byhl~9@*h0?rSbnN}lWN!JFWN7(!;{NSi zx_1Bc{IeB<3ht|a@BBJzVe9^NzTa<&d(K*ahRm)1lDhBs*XplJN9)#~BG<F9A6xT`(&*Vi$*9s=hrDS>KO)d^4f~Tx#gCn zDjIHg_`H_+_4igcsHoGcs<5riOb;D!6)ZbC%p#ObsVLW=5(wsoeby$QmiedvCW$H1G{NM&k<_t*rq-q3rPoSs9`;zv+E9CuiM4=*PS0lN-0Ly zl|-G#BIxm^4bI!jpi&8F4f4o2x)gvn*Q189M4B8676#@m)lcgURqUy*4LS-sc{8%W8Qk*xuRIUK}CzoHZFD$XEH{Lhj!+9s<QXG+1bUt-BLSkakJ^a4)GeM);(*W(&8r zK`7Z^#2M0fg<G$kBMm>i{mHW23GxY8U>ZqZ<@SObI zm&X@)s{GV@d_}MM+pmr<@Knk7?#RdIzcsnQQ{|H%Zk*?7^zhX8rs&Fe>FvIjo+^Me ztSsiK(mNOvM!S3NsuSaDE}UW7Y2-1N<=vL+sq)Bub=2Cmjbcd;wY7JU)vnNOPy9<{ zH7v~WuvAZ#dv{ss{=1csdRk-*4x01+ckvk>DQ8ceq%GUF)6hU4ed{Y<6vlw10G=wp z`rE%pqr=03-{|O445gOD8R3Par?k)aRJnh*MYqmCp#G25PZ?2XUqd4`wY1Rx{Ow;~ zmZ!?QKlD**<$eeRW~qBak2r2h4Uub3X`_66_Vc4Oq1M@Mwuo_QG&N9n&pX92iP@Qp zG(K^f!aTl#P2E|AFE&viv>|{HXqa^iq*8IgAK)IMpH&)V z;p^KP4$-&2`W@DSXh?L^;E&!Sj^!2(hC8;-}>`ZX>2mn-S;@vZ@B=! zFR@flmF7k(d6}mKv>pu-w~9e!lE*FHwWSH3tA?^YRS@!Xd@?3-4Y*yo1ufJ|lw7d@Vr`5dp8u3x#lAW=Px%x3fQ+PH=qssZ_l z>f_NF9^YP;D{|?RBmPY?r*5d<6hO}S=F=1NiR!yL6rMl}vGyS}Ak$OGGmuvxH$lfx z3243iZ#OL0Qw6|BteADo*6dYf;&MDyTn;S{m&GLCxZPtUmp$9hkZGNU_`F91q$R9F{sp#1F6u|V(A8z%ERY1 z>+ia+AbHEb6_|bOB`EfYsI7sTHttcs6-KEZD+t>JLvW!2fdKbH0&f(=B}d*Uxode~ zBsTvWO1?p*R6zJaT``}bL>-$#e-&Hl@&V8Pu29;_8`b-G5&_!^!Tp7wBNux2fIq7u1;eV^Q=B zDysz;L}C%Y`fce52PasV*H~2r&?~ufv~1{H9_8nR0%b^|1&~SvC>RJ(M!4>l2V*8i zj~;c<{#`9JIy#zD9OelB9v8+CluRa}DcR!&zQ?=ockw+s7u>@_6IAa`vs{rBbW5u| z!FLoR3mvM1u|QW>7acirMEsQie}OzKS%XRi`eYT*Hx%!Qx(>B$qUGWIp5&3iVff0oen`mn;Ml3X_Y8z4d_ll=WkU=SreWr*mzh82v0u# z-)hcV$1>H==PebcPkriBg)-}{I3|a_O=qu82!;d;Cqzob$+XuLrez`{7zr3nf}t#P zhu!@)t4R#2U%*(z;saWXMHV}$q_XVh z01NyqL|}KCSb%w)JyGDx9uJp>c6HO;~N+(2}Z{ z)7VLh_rfu0{D6@XjK7o5fzdd>VBTR}M(e_r9#f;)XQq}$3%U53nVAG-xWarY*E_cl z2x^uJ%S* zz*4TcdNWEdygnS%AGqx-^ib2KK}Js%i5c;~JT zn;2UjZyQ-mbHX5YgX@B^W=J=X%~n{^R1ENp7@wM^b62M5?Q?S_l?i`Rcq(ALdo}9- z#uUc9hu3w~3&0pdyJ8%6H=AgqW{0tafs&M*J4=S}D`bkkM)lSU)L?m;qBCc?kF87I zwI7ei=>tcfC2Q(B-}AhwsES=9LzvWPnCh0`<8+h^zIy-zSF zkKEy=p^17L8dLgLmZSSd==wmAVroc0@K~~n=r{BqfN_0zuZ!>DqoL8RQxp=TIs^Y0r6XNb2HtzaYJ}!#bPnBsp7~HmpX4W4O#-Un{D!e z_QpFwu7Q#kn|PqOg@L*dz*i!~Vlm)exF?WEF?~;i2UXtP;q-93#3?vCEu@%WN-^NM z944^=NDIhZ#p(h~jwLA0^kco{YOvZ2JZ=`g6L|h?9@X6bg?s>+0g!a05TKBka)G2n z5^`Js;BBS%g@o421z0PC3II7C8zHS0Y<$Sf&q=^rXAx_gcCG?wKk(-OWPY>NBCeN; zvZVs;EqR3PU3TG>TL|#-9Gyuid=>YpUcq~74Jruv1uw8fGEG~1U`+9dcZ4zyeKtA~ zqsgg+xK;uo!Sa=;=mS~Lu11r{w~3r|qVSxPpJ&28N<>B|7GgT2mgw9d#Y5N0lFXS~rv$=ki(m~Ae`vtgQeRn#{Iq$w2(DEmnm_By57pBt^qp$X=pA?|Z zaz95si#%{F8P|{Aya1rj7U?RfL5lk&!7`}Ni8jeLijhBC42n#!6tq0?DfLtJp-RJl zWtp4xfR%6H>=VE&W|P+|m=6WU$3!SF{=ND_fvwpvTzf3()%7pB6y5q2);N2&aTXFG^do!*6d&+ZnGN#7$jm~6*C>Ra z(@;7^(>aC{iBb$I-JQ7!xhsxauRAM_mG@AoTqElxs&DYR#SY*~07>cnnvLps_fSGH zw15xan;QX&rou#n+kS?qal3ki=;n>Z~JY$M1;W2X3CD*Pi{n_^gNb{KS7Gm#2Z5`XtSae3Lddy-gRc zgqY4|==9}qPWY|G0M8kOACs7vN{DccivjQ7!`DjO9EcL~U=;(}P=+i+c%4a|UCa1g z@+LwNGnnPe( zD$j6L1CNt(>YPZLc#O6$Iaxdm7hYE{kLP^vn!-r%JVX8@z-da;C*Ipg{gZoXcq%t9 z)V(`@K%f8a)cpHl>}abf722H*CVJu?51s4XwcsA_z4uwVG8m_mS98~w{5Q=c_R>>d zeMNYuAoLf?lTSWLPd)XNFk*c0BVP5)@=)pUUmd(I!T?eX+VEcnUa#Cq*OJ12fj-H) z)bU*KIu?$P*WQY<4433KTACrTTH&iV&;v)ZbaE<0LJ0@OR*%MTy%OQSFfI_L4#@X> zfT9m;p2S)jRPup$(1!V1%S82yh5rJ6@J5hk7BLzEsK3mi(#L!#!oMBbUr*t1g4eb< zw~vKoLkk^0Ju8ezFwz4ssOW8|)7H~tEzWb43+5;UzZjVEQ8b*}$hGiaHLMpPQN6cr z8HwuEc>-+iapow@;f-iw0%fzA$YHD8{EWp?G|lt^_Xhnhh28Sc#Km=X`@;2ksYs;_ z%!8S^1=3`*EKdI_jdH_(1$w7x;D?vgZ&}C?VC^hQY^pCk{1*%=R?EV+jKq_aNvEj8 ztFHTM|CqR=oW@u!{8tU-qq58U;sCR@XecoLy%q|rhFcZ2QMz()s=^-V2ow_#KD{0T zHTe{8w_#QJt0&l0g+Zl;c_pS6)fDn8AE?htV!`csZ7jBf6O84SV?Rw>b{?KD+xFZ; zzQ$bTA`B>6=gIez1=15 zQ_gNIj03GfrP=`R49TZJK?y-(^F{}~^PvWM;3x|dhrGhLqdl)0U~#l8FsJ}lM?HC3 zcd6g>;q{ov<1&ez$#0wt(#vlK=)#q-P^9PPqNr}bV1!&H6A@#{B@kc!Se%Fyf9CV2 zBJ*Wn)-Z2y05F2et@Ctr`Rm(EO#j}6iZrNb0c9T)^V+f)Kyy%FD1(PUI%8XK56BW2 ze=xRc%XnUaH!A?|6ok4%E}|w*g== z>SMPU>1Us8TTq@nvQ<4}eE}Qye)gm7qP*|XCgGuovF6oysjLOGJqn(6sRk7Q#`Q`W zRMsmn_q9psVeo>tE@fbFHG`KvC3%u|W6)i+=cO%t# zv&Q!tYFKX&)6wG68ULjg+|wZYp>fGE7|+l6$m9Qc9J?AMmlpLM6bRzOQ+Az(HkcM zBKb9x@!0JLqYD&$$aMpusAf=Ed#s*8r9=*P5uiTBb`h@xP;ir6(k%+BCi(wu zj{;2rZ{oq>sF;6+N;(oJV@4TY@Kk|O<-&yv!mt8>^u$65aV|nvtR*zlU`fEp*Q3EJ zy;C4_7pA_!i16wvR<3$Zkb`0<7u0-l=VBwm^2^&%%fzi};D^JQiwcwu$oIV_y2eL-o4l!3X{sJ@(FD z&MA*R_Dgi+o=?z`qo1G$9{#tYJofJ26y=Hc|31B&%ZH!*G#z{3-O9sis9_zVuCAHK z`tQ)=@BJOR@4%&T|Z>m_dygNezA@W)CxL!=S#2ceVsz;*U!~q}pQoW0uF=HXN=Q~c2olSH z$5BjwiPJ^aBO9HXE%2nbkzg2-j<<{%ciePO#RF>D+1H&<<1qL!CcCA?WFXky}CU55r$c)^Lv%g*W3(WGd z{+0)bHtkc7D8LTN&8?^CyRVJsw4VeFDcT*+OAQ59?>5rohZLhqDr2L#`?tksg#Q}2 z_NGwYp@c(0ibg`>GumnY(GQW!;}hY(hWg&5oo(L|*8wwgY5LLeg`tF?v_QROon-i~ zP$VPfIN){`pR?Fyj{5+`!hb=TR4g957Py~w_qsOxm$sc@;B9HL(4HMGnhPs+h6g&v zbSZdfznxm@bK8HV!hhjDcO5z)zU!gh-ba7^ommR-4u@i%^QY{>QH=eSFVh5=u2dFZ>tU0im?YK{(&=CEiX2BvMLK1oz+~&P!hgB#z2tNh4s(?cOtbv(UuH`^#qx3hSPatz!+(JeAhaIf z=5hVg?`o>@L#-M@H%+r#7jbkmEpgTj}As+ zEkN63U0Pg3zx1(e_(3^Rp8lGd{`gy$gjdjd!k!&=`t*NlQ@;_taUnuCN7Q&R8mxBs zFXRH+psrg=7?oV!b*pA<7Bi>-n>IMarXTsE+^q4b<8PCIhw;Crs;?~h z&_nSjfLYW{UeCwy8(h6y&T39xe;c5JgJk8$TV;T`E|qOypk*>o>{>)(D+!V8R#i%3 z#}b%c{HjfYTSMg`5^Zz4BdIn1LQus{dY{)Kc7h|U2N;>7cX?^&Hdl^^%GgAV`!QD` zwdx)!w;|b*ic2l3IpmiFjBgnv1y48UB&v7Vt(2@#qI&EZ(A#w*_Y$;ebkTm6CpJ9h zr54{1HP;QymnKg?GlFrt)Q_-I>d6`)JQMPl$YiNFXR+k<=rbg3)XojN)j(T16lGe5 z%#^Y|EItQj#_8gz7ifBNl*UK;$v-tJ5+ma~{%+fIjI1^XKR3$+ps>QEM@Tn3qg1w~r;UZMJOd2wUx`HZn`dW=;(d#qJuj#bmY)Rx{KT8t~*-j z?!6gqE6;**>RfK3`u*FT+~z5AJK{M7bM@@iNWnz)3Oyz=8~7eOoILmV9!|biEgmkA z7tUVcd!&>LLF4keEyWjm`dh|UXrAHrsC+$CYr}+Ee{YPlewibHh_%kAG z2mk{_si<_KdeGne`I`^WYS4F}yWU7!_q>mG?z@+|Hti#ey^f1leD3PmOBb)dCC&qH zn{VI+ZIg9zS(z@njN*M{fl}zHr^je;EXH$eeaOKQ^>s$-={AY?yl{DrUOzJ@=p^KU z)l5{6`7R9w0BD&s#%L4%O2C^2Ks1N^oL^A*YwH9a8S5bA8@!hUJSdhx3dB3$T_j3L zR9{JG*V{Q>&JY^4P(gkiO_P@l%)dk;Eh1^a*o6%hlhbkWo^7Jtkoejv=2I!y-D4L@ zJ3WLl`^jX8Q6?3dFX?26Lcs}M%LB}DO_J3xMt0)})md*+CVrjHoO+ecUwVx$p1Z>9 zWA5&pTB7d_zSK_SQ}>oF45FLel1bE5j1QDvP20&R60R!W%Z zHLNQv$EX6-j4CS+D1m+TW});2jleGS6fd?$rUzh-?mt>DmPer&=9LkGB*GnBxE!WB zPnK@fLVm40*4Ci1y!Am*yz3ZMY*t=}Dq~aulc;A@!EunAW|zWD0%HjaHSEvsrqu%Z zERJ7_(lpZ|gvQDbQ?(q!%H(uX36C+EARDErqs_X&s4{r-toW>lVn&tMPtDQw;e=3H zpdhrL+?fvrsMfFoJ^=Ma7>>mZDgczUr5IHNomUlJi=kAb3XWl2myquz3@uEJ_ZRNH|QP zU{LIoJ^uPDWgAr_U{vYe&_+(TkJ}?gF1LIBUY5iOU84#h4U90VC<^RspJANmhlk5~ zuRLT74hq%%S4voqP~3c&F5fUxebYAP72!*7z&xS-E)oY_3rSu6TWeQIUthrp~*;;h0c- zOb5~njVfI5rczOhaSf>&p?b6h-e>*8Oau8I34Tv_kwGDiai1*~dgu_pfBi9P?l~sz zr-jMlAgim9o`3f5Z%w00OEYcR^&aZlu$8>N)&=GDJMpLs>6!2## zndkXeGpf|EUXVycXmt2E_4l5m!QQuN;Kplo@$?TD%$JjAh8N7MQy1oh_kUE~Xd&qx z=qwD;B3vlbL(o>pPT?ri73MF%BQAw57D8O`_UYTsuu>_b3INp{0Jn#W2FYlWIo z<<#v4DQ)>ag)bu7m*-VRyJc5RL~l1i~!@%bG!D<*~K~6^W&<4{K>u zL6g8G+UFo<{+Kc4$KA*{sdG=GdPXh~s;qY`CDwKr8SC5&InJdTRzMH&9ig8#wwQ$X z7j}w``|Ct_)Tzk{8XLaG=Y}W{ic=_>Tda;cerAlO{XsHhg4FD}qTHPE@>>C#2xf%9 zff5LnQ#tVn|fcC6=n(dc0bv6nLggl(d*Nn` z&fmzE8zTv!=#>Eu5jySKP@G~JBMnR>>9x~g8lFlCqYHrL>gI4_{`xcv7dUS^#CKqc zK^m)YpZRl4W}#HXc`u&~)5YEx%|wW%f_yID)586-rNb;jpD1%n79OvOY089-lOg;H z*%EJ&*K(HHY~Q2jUW4*{=|+{^-Ir;5+i`LlE|JS{ij0w0#WPH)UKV_m{?+2bl@Oi2 z8WY|^L&FNc+t`pj4`TvzL_2t3boz0Xq?k^Z_uW#T-;ykRu`MYr?ZNt$t_fsmbSXfTGaXm_*P5gRupIlZDF9zHf?lKcZWmduW4lJOL!V z8)jY{n=K({VU6Fr(?h$qxkT7^u>pf+D9~Pb$S<{E(>Q3hr1!U@VWpBr6*L(PWI!oK z73hX6EcfK!J{(Jt+sd+~j;;>R5S}VaB%Rf4RH@}uSs|=^qn7am^;9sD!{gDMOV>Wf z%9;(o>Ok4AzwiPu@DYt503I)YmuNL%IXPAE_Bbxb?DA2(12AXg8Q4XYzw>Y{Q1*~n z6pPk7ZVZOcMsH`-1r?QMM81AA<=d;7xJ z`0!MjHh)t2%;WFIwJRdjRB-A#edpkwJ=4F&IaQQrgElReQ$>sSA8Vz{{Ts<*U3g8KZ-SmV zp7j#U2WTwjyaZ^Lmfmh;`uXB>Gc-1qSh69pTH&rU($2jL*Gw4qWlj^IT63yspD*tR z-l}gPOE(MURLRdVP%7{aYnfAJXe2tnX=2G(R4S*61j0F@73xaZr-ghe zR_sd5!z2sdU0x$OtP6hwt#=yYVl(4XP|Z12YDSe6!pb*l8Bfrh3dXRy3@d9k{MH^z zdiCr@kw{X6qQS1`d_YKUV#X4GSEk>Vj4eyYn-8=n zl1n4R)mpXdl7>xDEPh9Lu=Nc@g`$3BG)8qSyzbuN61&_1gc?ErA!trpt5rA2@~Wcp zjZ{?-0)ExyP$|FBSHq|h;ATR}2lL?~iG3%_*a!i3W18qG(?+3W)B;```MaYRGpYbf zHLR>AN-?aIieg5UJ zg|1OWvy|YY2;o!)h6mcXt(Vp=P!KjXN67BXjg!3?;;NScj4BW|H}xzus%QaY(V;CC z+Oegu0$tM#0#|xX^!%F*D`r#yDs5P)gi+<4$EK;XC9C*d4BvZUTGyz8-TSRg%IU^0EjIcL^ob9(sNWU>Yu6Wl;9n!7N^YN&YgGA(M;0n& zwfNF=r3w6?wb;e0#U`e8&p)$1jVjG8W_tJ?#oG?38C9~tJ5-BNrO4ijdEiX&o(l+h z0f6pk4JycwpryrHAhf4c92Ucacev^PyS?hST+|ZP*HD8#Dw(KW0>%!k#jQ-ow{LdR zEYDwT-Y_$<@_8#uu=ETomBhwwCn0r6KJAroI82Mmge!&Yx|OMjQ6QnsapzxV1flx#9&w25DY(D(_vsiUkL9N?n5kK5Ufk@la&YNx>UARTlg=u zBa|#?Hvqe^VO){!m8dsNV0E3gPgqZu*Y5EjTklccLRBVsW}to3QXk`JJz$s&wo zQV_18@({v()frTP^5+5=L2dXiwQm#Zp3ntu~5<0xP#ppb>?_e=P@v z!hfw6&~M5*iX`|3p@h};s|3~t&_0W`j%lQeLbDer77OQuhXIhQO1=-~vRrGlkRftP zEoN(+9Ilus4UGxfxG_U5t;zXfutdmekItW?Ep}IwjMkV?i0R$CPzm!G!Mi!^32JIY zxFYa=O8xa=pvl?Pd>FJ+O79T(&$=Zmm=XSq%>Ma&LV5-D*7m`2LxEKy{8#_jI9=+W z<2HzvR1nJ?eUcB1Q89KMJa$1u`F}UlrTlj(G*9&nDtM0aEVSRK#`8j=-eKT2V?KfT zHoXF4V*i*DY7amTCkqI%1~B}@RV6Fv650}<5u3dba8BXyU)g$V0b?lIq!>_N7<6G^ zkIuzu%SL@8-#30RA#x4jJk&+c7zH{3x~uhA0a}`@;{5d*{>$Yu(x%OeYiVwk@L#we z)`s;Q{tLPp8UAZmhnaS5w9$qZOSZITKfA14r@6FPNAls~CWHb_Tk72oI<$WSHPm@{ zekLgtR6+$opMa8zCYg?=M6s9~m=AQ2%kCmWDkQGg?7z!FPpg$ScIxxGfy{$s%?p!> zaFcVvfS|jn6t`)H*F%~khiQ^b89xmV_0jlvFWtO$oyJFV4fM6}Up1^3fTr!*Zl_2D zYm|~F)mvZB$8*QGHF=un#f17z0qC7JQN4sB^Q4%DgT`9OZnu(&c{!0+(3qhYUz-;6 z1vG!D#b#6FDDV%s?^0x!QUDqYSu~&aO5pi2r{ZcOyKWh1Q-?zh|E2IdX%=$J3I8Pl zeQqh?zhF>72rw-YDf9vIRw^D#`M~DeTKKOOz$1yi{cj};`o1X4U{ zru=bTg+ObQtwiFo@-0=>Skmi*Sx?Z|q#}5P!buup;X5=N7bMikgxz2@likToE(?m- z=>=EJ*5=%umurcoda6i+OXWOOayvlGi7`dcg|TpWFhu_G2u1m`ff;8TFA&~FX6)5= zg%H=l4E$=hYvpH6X?Mg%Xv9cG-$AK3Gn)_wSpZ`Uf+PAxhRRt}RKAg_0@Z6!(W3Om z*LtcnCx^(FmlWI1q~Wq*7xg#-^wEYB>e14H_JEfP+?n&ia)1a6#-x%OokVZAI%wMN zrn=_)Sn#f+;MCg`kB*5o4nl(#@LrH!T8rUU_E;$gXb-KI5Bj!TMqUr_RFOcP@(o-| z!BW~9^nOdXbzaGbdW>>?w8}Fp57^e`tY-j}L`hf%H9$;h2$>KqkpE>wUCYZsp*06{ z9qXeOqZ6^B%E)qo9c+WVhRaPi7|#%lu?93XWR-iej!PTY%C(7@ol?<`WqGQ&8v4|4 z3WWbs07ZOfTX8-PZ6))v+`Y|0kKC(- z13_SD085(0gwC1T&^Hjk*REwv|dyabP z;9l&2<`>ayvo!F?{_p($~5@`L1ZH`10ZTg3O1uYH@YU3gV|*29xO z|9hg%W8ndc`~OTl>&m!3E!fs<6l;+l3WX!Im=-EYB?fqn4ra{E5BkVItsYcS^Hix} zy})9M(%!9u>bLUe3g$_^rwTAU8Wp)&!IyS*WWBUO=f|1ewlLjZF4|kI%;PBa&G%Sg za!gH*jG*(yFc?tsT58c?&yY(s)W7%fcCuTsNhM9+`eD|%Ivvgk&ko4o$c4EU(5_qh zo+`)7@>Bt9A7VOQil>Uhh7AL`{T_-X$!bVbOM!e?Fv2*D>(f)EW>l##R;Mw`cuJ8| z!6cSzSjh*hk=S*Gb6|Z0@x)Hf_7-~yhLtrNdTWm*y*fMv(!w(Un4O7H-_==~nu_J@ zu5!A#59_%7n=HZ;1Pcz7s%x6#LW62Fs$c=W-lw!{D3qidm;5v}iFVD7eK6`qGYf7! zw!QThp>RR{%Sp0Y2~>X8lzvATRuCgK8Uq88dmZLIjCWOm$~V%QLkRU%Z%~matpl`1 zm16LkBJ^)sUr@i54zx)jqYB6ge#1G)sq#wac5&R{J4#Mx1Nldvr*x_^ip^Wmuu|2~ zQRYY-XOvm!IKX=u;d!&HmB*X zgS%+&zJp}8duZ3@1jT25AbxxPwHbQta_L4D?R+lJOA2RpkVI3pAs{>spuz~bGOdj^au$z>W<+)FU3$Wa0M*}?Nv8q%Pkzt&rvCS=kk znweO>QN>cGQDw1_48uxuqeajj0RO&yCMdiC@;6&U$?sK_`~VCp{gBbP9}((P=}+Z8 zxE8z-_@MmP1&ueShMwLu*h&-9k(U-q9QqZVUX@D+m=ycGf^NyNPrG|Bj zL^4cfXRrFLa+nJysQ1dO&_#Xv*LG69$4HTck3RRsC~eu)N^R|(!s~2!;1Z1uUsbPS z-picJ(d@tb{X$p^hy8Tz%Cj^T%_XRX3@b3I{PIWIm^Up&~bGKxRfL?#1A=FVy+?xj~wE*{pNu)5i5|RH=gSU*p2XR4~wdY(0eksv6`G zh{7+fH87r1!4E+w-=#l`MJiW=F2LkMAcLTI_3RW)Ok_h< zNhA_U3WwsGiy+%4$t zQVPQKfwuz>vTvtbC_J%l!oZFM+X#7tbs8byFpgw+Jk$Z}J#wma*JWsDw}rYIjCsYR zmh7=MpO5d;K@;3Q%L)H=>_9zr_$<`j7^g1ozr{*~1;R*5;V)85Pw(7hqQ{PSXxBz7 zZR<2sig|$iYh-Du_fnI$nQ1Z4?J~oEC6h^BUyV!~($w9QpeS>DTJ}1A#xXxj< z&V_(YE67U#8B5mc%!N78HyBsis=_#?7%`wARtze@&3?r&aOb`{I!Zuo{wks4aP)RRrwpdQ?Pb{AB0y33?dk7CL`pEw73@co|ue_ zJc8iOU;x4RLkKePA*e6fI~)EhEjH|+zS7I25Wqu&Hp>uy5<+>+?+m^WG7#Cg3l-txCZZ!YbK@=${IZ!74HgO61>y~rX}bPNzkB(A0CWzJMny}h5xFB z|KfMhhMHNu@Lyb6t}t{lPHtC}qryw2IIa!FDavy?AA2|F@}a}id&Kx|XlM}MM+dJ^ zLt_(lZP>=`oS=rLcG|RM4|%+e{HuXB?Kq;$%XE-zbV4XIr$PGG9b)KPDuMwdai zG`OAA;IifvkKIL$b@kNjYo?Zl4r*`irjFLl)Y-nB?!EgEx#|y+)z(4%H*=NFweVjx ztQXj<7P|lbN2%WF;W^=bdB&Cs_p}SKAlm_YU z4(U#jM!Fkm5TrWkNoV`E$V3IgR&gOk@2M-r_%r2k?t6hH? z>RwlVd)F&axx?RMSwAz_do#VSB2wOJMfi8g<%_V$_XO^Y{2p6Qp>b_E+tBL8S-ZG` z!(W4n_J%-?Y~Mhs$W@y_frD^FBqwt-Z?BL$;z5yYyUL2-s(*4kdPfI8HX(Db4UkN1 zir!hOW}|&Ls{LBf_=S{_bBXe=&>{+hV`i-9$Zxx186S5)q@MTE?T&WGSjBp`IpTuZ z4b<-umLMq3JTcOB+VsafCYc7ATp%GA6O!>eT#l;Zmvk7)(h2@h^t#$>);`0z^$E$!?+Du9$^ z;FG6moZS6^txtXJcFnpylTJ}EWe1cV)m1P>(h6#&jrfi{Dkm7$qG4TVdu2N!jIFU-=NIY+CP?Kd^AXHQf){d@r$(5c_Do0)s4(hHi_o~uFXX1J& z0f{OBh6~SK-*&yTjuoYoG+fwIm|D~hLx2BOB5qgw(a}-Fo!uv_gpKo?ZoqLmi-arA z7>8yp$NbT#^*i8~QKZoHSs=P@G}tGOEdh;9?xb7Hi)0pl#`QXgRqus`g}&j<>830U z+$u-EM4UpYn(GRw5+n{NEP#E&mmt$@eVO#~bJ-%NAY z#UM~#J{~!}P{%scWY~r+uMqWDFngu`nW>4My1Tucil0r%yrODqr}6b;^eAhR8F~78 zREA~L=9)~Ii#+87_huT(L#;NQyMmcKdO?# z_FuQ`@Kt3xp8bffGNjwxX^KT&(q1(eJE|*aTeC0=#ib%Yt)MaG^MGuh-k;g{ z#B^PhI3FGJAC;&oLU#Bi{t?bPJ!ohO!!M1GZ39E?_0I<4>wsoLEd2Z>NV>-#_h>h) zV{*S_p?BmIY_2y5gF6Tm7n8=|$XJtKOz+K^eeL5rKd2E$`oyOm_w7iYPYyneoP?OS zXL#w1=A|KaFgVNSf5ZLr=`wM(j!vwFGZ#a{R6y%e(`;T;OZ$h0>^H+i;r-89hh`PI zEWSD$g$3&k^S|ch63-|@TS2#e*Ru-VQ^U{Ewl2Rbf+q6(A4|@&#nXTeL`^~1MIAxp z5yF{o-Xn~HpC5XoQ1Z=ndkAg7rs|VHvmm*wc_mw$Uv=vEzzX;r7;@%4N~w5Zcg(*1xI|A1lW~ z4vr(SX5rtVkt6y8Lh7lK99gbU3}seny{T1$X!e#4*z`GCS1?n*O zD}|w{w`9a)U^X7}0?E;x2pj7idJ_;wP>?LR!9LU{7!0#b#tpG^XyI`vuPD)P#zc_f zC29}wXBpc`!zD`Oz^m^&*piLrlx!!_FxGmjZLOT&PW!R&5JQ|l1(j}OBMFr_|BP}> z9%@&7tbyA0CTWI!DsPenIwo5%6TYmF>olnzl;?s1LWFFVu$sCelcSgp{C^h zU{~UgGYuCKh2DpmD?wWviNQzB13^Mefvt#iRj^-q>gRwrPD4j0{q~Wy`-1iAmj!@3 zWspBSoGB_~Lo3f($VWs%i6IRgn+SY2!#`@TG80biknbV33YE%8)&J_A9;C(#vri0 zC-os!k`B_1(M||5XPKm^k-VKo`YeZ`Yh5ifDJaTvl^ksD8GeO3Z0Ezm+}9jv!kPAH zg!ssC%MX#-MByQP2hZjV4p`shpSlrRppU@~!3%~X^@%(G>`f*vs0K~HUPW71+0nq@ zmJ@In8t@MLo=3mMIRw-}^I|;H^oc;}iy{Xg444mJ$1HxRur7W??T{!Y$o!EqNpXC$qJUoShF_mQx`R!o-kt9ss$q51qtbv0a%A zZcP0l9sk06Zj>hVk(+&5YH7OeBYP~eHIyWqHkn%`(sO~9JyCTKm^f&4TO~%64Y;Mm zX|U9t3Dc(Pw)wQpaPL#)=lB6x02tt6WQkJ_%V=k%dhq{w^*N#l5Zy6Q0kq_nNai2Oxk?4hX?QPE`D zAY}rF#JV603?wV8S9E`*Z--SgMVGj6kG&LA14_EO_S=Xs6Y(TIp`%Q&ds;lp+uJI9 z9SUj+19)?N9Rijqd>_zDYKQvm#%O-DR%cVS?;&z`X!O0nR~%b|Tg%GA<7s!(y-kVX zRGoSdm^-b|<+U+MDQaOMR_uV?@>HL~M2k9!qeF01h$Qr9tv!UvpY*UYf21}URbR>c zlT)Cg88-km(aDAJgaJt<5t4>6PVE*HJqP2T40U=Irm zJG@>rAT^CoHN)l9Y=_BqQ&(xtUz58T6DqU=av*efK8hZgR+Z@Le!*D>2%EMMA(@^^tTDyo!Mm}l4uy)woW%Y)%gft zb3+%Gp&hO3gdtbCpMmh^H-gM83qMPI6!}PL5_?W5Zqr~*D55uryx`0@pE&7;1r;LH zb1Cr(6n}cH+hQt6AMZbL;wp-H0G!5KiKaf>kl05oCJ!(cFINlgE{Rlt6%V?X+_s?M zYcaxCC{sOdJ3+$R8C>fit^wL`I8O;<$&fyJW+->WfrT{AKJUKp5hjwVP#7`fGgotQ zAi6Pg_{kYM1CHl$@Mp0`hlXSyLz+Z+XbmlLE`hiT!b$K=TCN%Tn&tLn#Mdo#JgLed znxD1xJ-RzV3a_HP%h4Ns0*ui=vVV7QjvPU1eGKsa_9ZJ7#TJp?tOp54&O*rlRhhZ# zy$`H;_04se>q+WMh6YE+bN9%`gCO7BLm3hIqeT?XlbT}ev$)mJiwN1Pmw-~IM||H) zioDY14Iksx?*I15Y@}UO{4K7&;Xbi3GY?)@ZRp*7aEc@+ez@WBySImq) ztbgo(iO|^779Wcr@dicp!r_7*T2X$aBNS%p-i1?!SbP;|oPk$f~(yBViVT)O1ij$6f4nFnO@vQWDSlKA0^+$`f zcXT8v!2TdW;pXZ#H8KKb5Ioi}a6lJQhOjEmR-Yu3I?2yM;iN$htkruhLJ-`zk-^ZPjMEL#!N z_Imnyzx`q8p8iVSsh~S2?XG84aC5LZYX0{0HiA_ug z{n4teh~)QQyjQcIES7|{7;81IOs6R3x4Rfm?BcpOfGEuT$)h-@Rc)8!=GMtAOS5$x zGcEi=q(@JSqUdq!U9})?S%vRMAE6i9_O*rjlQ1eAi~Y#tsR$7Z`P1vxA4UcF46_+`JL}$5k?>GLA=ut|UTJuA^+v=+k`!N{N>>~9q}$=#WNVhsH|?m{o~#&ZVl zuQ=Z7!!Wilz#8wyG>kAdAt~~srf4^hx;Xm4xCAp@bE5J+Xzi z28p|9J-_35gMh>lpA`|DCc?k$wrb)lAOE@jpE^IKK$W>>5TmYq*1a&>;6yjmy&wOia~qCE>cuLc`sXpv3)~q zX4VI((eIhipZSQr9zgnsK6m*$3Eia;Ot}&S#CWP?yo6e=sR>Ju*y92q$&2hSUA@pa zJ);Z~CZD}oRpqPv&do$b+T6R8w@R-iHtGx}##~W?m?8P(U<)xaO;AW$;$1?1fRRIy zVoEyCK=Mx{YW5fwHptWh`^kx+0zeg$Kr0BSmI(|*J@%TYEyRV6jB!_)?h(lm4>WoF z#gj|*nvSb2ba6&49|Ng7UeMi|1d~UP#tF;{aGNk)8#f+)f2Ro%nMf_`vPFRexQpSeGKjKq3q*5|# zgJx=|BX~xXQUNUfJ@GjHyG-ubP8m|+(;1d&C%G10=7y;PW|2Z&p)AmpCMp8IMaLzS zy=&97jb-6Y#Jcl(nn|0IJ~IhZcm}2rW$Rd2xxQpt0*i9 z8huw#>v?_a$de5T+AfP=_#gOc^mLEwN`C}pH+Y)O`-BxVyDwsOhX`3l_KG~#x0{8w;*aW|KW#g3_W28Pv%G5X#co$OpXQceM?tPZJP5|2x{ zCnZdujaXRhVBBY8EfqgFkkiI!n+fqw5Wr~YCyN}nc9zH%d7W1K;;Oz5VrnacsAg?#xaS9{Un`yc%*YD6d95>LjHZK=I?#DR_Z7FpK5+g; zERfvi1en6W3gfIIyx$)LGk#Ou+(EO~<++#DigrE;yF5M+oyA8Zdq*mtw48Y#{XVO^ z(MaZ3cBt{w7tHs*zMc^?IentEmJY)GME<~T0pQyUq@s8k!;iaL~Y$B;F8a0j3N zMQ5tB(oSGW>7WkEN-FQlt#ZRn=zZW#iMX}f+_$rgpSV9J8-F%=uyXune;A1zeI zUo2B|_X-R6Wk?LHc3dqSB&o%hQf7O=e#(x1h-yeo5hMWWkoz^`M;d6-C#;*kR~Vkv z0fNWxnR z4vNuzVJO3pBPZDX!LN>ZY>qbN;OW792j?-bW*`$gD#g}I!xi$D3em6a0;~pR}Z)Eke{{RM&Ac_m{JFq$U+zz#cGWSf3_dTH2QjYjpYKO zeIA0JH6XQbF>8I7GUiJ0N>%Xz^mFVv|A>+H#jj-1{w-kCh(Of$r7+U?xi-ePZ*bR4 z${0+b8)$PciJ|~jM}wK1itJT#D;KVjlBP+&cerukeOj6v&pz2rP90}56EopY8@oSP zHDyydhLBRs$n6ae<)zwxLy=@#KLvP}didDbZyPd}K(Uiy%&FtEmeWa&d68_|uh;z5 z&|aF(ea-nqM1DL_nnMjSX&kSnx0uwStaQtmj71v$A z#d-l&cC=-;W8>1;&&}GU)PyF!N>3@6OUKn6jMu+J$s%6aG2G3&xQ32=T9_Z;z=lBrd|LKA46eH0@%zFEPVdQPO#v82wnG*;P6B_)Cr z5;%9Ex;YD#`fR_i8%WL2U>jV#$3C{^JaW>4h^eDYVV}eK8E2=#GC1 zxzXil`bOXD&#?Y2nAHH_GYKpBcyYy>v1`tq={8^V1e1F|>{y6Cw;GAXy_uL~vh82+ zHrwsxFbZ)F;A+;_ojqfY+S|Zyzb+04rz%5F4fF$&h}yYhUoqr#6A=WF03HE{g}XI> z)~GSTg(xZXzsKW1yjCoW8fD7VH za0z~Hqr573sF#ZoR7D*yOlav_jIpa`9xT7O*~ppH)6rQezvw(DJzT9-55%Tga?|6k zWUCHfMXM-IjGpBjnV}<|B7ohRNy~8S{%vjF_<_<9v}qM66fB5B6Rd6<2#wb@$6*X2;$IxX~OGvOkR&5GX}&B%I2$uTaZTK*UUMd+%;lCe=L0fW8>A zrzq~7(#3G7OluhN-e2dyGeh01t-*zX>tRm_Wn`pFyVv8f7)5R%*A+-VH2j1ApK^JP zHmWF{gsXpuleuxzY*S0uK*Cdl;15;{^a}URAV6jZCeu2L+qy$wjbTA?N99EGwAnKI zf(GHVM$~I-)0ZQL&`BnriB7XjTS0yC!P90s_YZ)zFT?t9F1YuqCfQ)PoQFsBOGD{? z5g=hO>y(}k)NFLkr!egH^t~@xWiKM}(7ulYx2k@D zRd6PJ4fi*6?$!Mn6As(e_Qv1ggEUNFQs5JzZ#ya z1Uea-MY#Jq0#}FWAG!|tXQ#n{ejy(mqk`j}=*_R>F4PL1mD z3I3XOoeB)~>gc-cgmikDSp$-O0e8K_jVJTu``AMtlNh(mbfwk8#9NMh9Ft!uF? zs#1=Kd!A{iH7W2Cyp)?C3-*B4epd-G9y35Y#TnZY4ADMWE&Jo6R)QV$ilLcs-x^TP z+|XQ-d^r9+Uxc|&+(9edi=p_6U^m3W^i|)DQo<;n&3#_J&N_KI1x(xYoeM&Lkn!u6%@iJ{C{U zb_maZAieg<h6BaZ;r@I6%le^tIwqCJWtnS`AV z6SLS+*D^3ix!?tmoa2I(t6peHvt+ID1%?th#K0I> z2!O{|*IiZKeJSy>*-l&MPC)186Dg9mc}z~tw>r42JuJ|J@m>LQ*IeQq%VR0k4&HuG zJgqC%f(x{}U8Fv!Rw}vyth381sheXFevC4KGW2T4^<z1s<+i-h137a)KTfL7; zGsVwZ`~sT=B=wniovj47vD2`5ldP!I_<`b{&cr=nOAZkg595q%#3f1D($>6~FCWe~AyR1=Q4!9BgU|9}cU4Fh6Hz(T~k)(;A>_mVNkuc`B5vvS$u+n%rE1 z9^6EH__x}jHSApso#Dg3jDQ3YZ%<<#0*IWhF``D-|C0y-kXy(2E*mN4FMC37@-Hkm z8}e}nOwRg31!&m9%;kuCPL`E>CEn^OV|rZyU$_Sl=^ZlA+@U|kzns4vxKRhB-4hd6 zBMkA=OAR)%lQIyk6R&A@�yzeTWv@_%t27lVr{X<9!Wp!d&KOQOwX<3&S_9Q-D$* z4BRWs#7yE=6W;Zjn!YGHBud^-eWbD(btv5IjV`#6L^@34NvP;6pg_aI1W6P`o6q*z z8E_!&5Ca`c!|zYAVT%EQNMR4-NCNWLSSIX(!t!w{AZ`AWl{1SZ`kmV_^-ae%f>6Mu z2@b{%k*H5?um(%HHf5?)ZPd0qcRA=%E>$9=Fbr+fv|F0;?fKZE9ZSV@#cu^BEJ%kI zOxb!kib89;vB783R)be%@nOEGSwQBtQj`-jKNFj^t|ibeB=JZzqAAq#xHl5~Jem!}>mMr-qN$^4~ zPd?C-sRpc)%xHsHtibUwQC^5E4i_Um&F9b6EP@XX_Fw6U&j_iZ;U{6X#?RWZs-OzO zlk`Xa!bMYf3{Oe(o(j(%<$br#(Igg+V1@|84hsP91z8_Q7f73_nN_bn{qFZX#@ zm^(tEcy;dWt-kqbKxyZ1{d}q&%iQ?a zPP0m*lh4ZvXbUqamZ%^;}> zQ9+L)e`UuG)#+wih72`HN|Qik712MV_Iy9}{J)nzMc~6-SEwX~uMee&ZB!seqdl2i z>UZ4du3LNOd5x#7Jc7KhD8QtRr|u$FXNYj2>a~*WPo0leb;XOEK8cS^xjh_6Op+~E zm7s;bavmNp^X(Cz~0f^>;u0KFoc&&W=LQ+g~OOc85`hQZ!uu*141j5&03cXtt~+-~Y|w zXvTo1ImwI(!Z%y;bxa>_l2p0;8|q)0tt003)JEMN%Q z%jJl)oa1O48QA>|5N91xB;V(iWIhNi#hkTS?igvS#S;A$MA`d+VSd(R|KQL?q2xzK;PBQDl@SG%2JQn&UYw+F;N{36+F*fWQVB&PfVpWBF zU+AeVOrJVC!=YHK^EHEZIr-43_+JMf1M!K7ew%1DsJ8U5Y=IzZd*a>W#qz$lM~}Hq zfUYlwMS^Xskk|JVKX1)Z(9OdmdJ4Vidfw!P^t{#3XLIKzwo1UwD5g`{amVG#!-Tqc zv1TB|hQ1Gs=;2T|7bu3=e}q6-@p|<4xY27~yAd`QfarR@_+iU$p0T=S?|&6=mIf1b zMuDemSZ0=(XpIXQrNOopPni?IfHk%FL3wFn^I*}(Y9)|h`pl*xUX!|A$0z1fCVyC_ znu8h9(Ib}}+aW%U1;ovB4tg!+WFEeLnU83pv1M`&{`J>-xk;sH)F1R-l}P_>hFW24ogt0?HiM*=j-wk;C`@<1JB1Q~VSQ4GUvSYcVeh4x z+moUavN{qJO2T2v71UHa$=oE?M1jOp8y#@7xTYX*z(&3+XDF1DO6e$~Qew~ExK#uP zXP9{`nq_-2+OnR`>V`80{%#1oC*@J55;LeJo$7uK>o<4zy4B}siqUgffJ^AjYshPIRpCPs1ld~?&HxaS+K`Xusva{kwe=qKIUVyW zzlsBUg;!DJLOy++c^I*qp_wtt&ujDm9mF^cCq$B%S{$>dzMB%9p~Siiz$}l&$lf64_4IcC|0>5~)r?fe-OYI`uH`q?@`gvFpEA0n(j?%MEHdC{9;zM+>6E2hgE zS7_A$%Cji{TNCz(`flCwKs$X?VL)i>(<_MNOwBuiYHTGGiQaC4sJkXaQJ*U;#Ghfn zfxSG#a&Y^eT>A>JYYRAE}e7o(fR)pebp55 zQqIR6r@1eR&x+jt6A3dXJVF;IWK13wa7T8|69-QKG!sXn5{i|(chG)er)A@0xd*NH zZngJv!w#(qD(>_pXV=gvasE)6>N!PqsN}0RBK^lpM0$o#z^+eHqo&esn5AJUj3grC zVOy!NKQjm3x7r}!7Gs8f#lAR7cnU6tYB61MfTy$_djC_&wN%$b_G= z6eW?NlCNiH8%p*KF8kTgUQ^Px93JaTHY~fQ-5B|``GrIpSffiKIPpWwlzQbU0cI#z z!{sFGg3JJ<9Sc1E zHeN(!<@-SB%b^r%<~Pf+V?_v z3+Ol+nfje_l^(30YMMr#Dt(Ynd3kb*CHkN-d_O@IEvtQ^{of~4FZifSb@`;ur-kt2 z2-X?T)PJ8;y>33G4GpqLi83l9v~=mHhXg*pKj0>>V^)4<-%!BL{4c zNJmrB(P(3-76Q2)=ZKcZ>7KJlgvhZn(3z6)y^nYCP&`{=u+Lk_Mp+C4|Eoc-5x+92 z(A=5g4kmH%WEv8wEy67{8uD}W=S#X&1?F1r*)btney*alhlZkd`>nYoH?F+jd=}xS zqP~@YdC}hFo)4%A@4M=^AeuDo{$oGDpxc3n(_+3`wU=>hdx8O4Qg@sKy~ z$%#)ibAkb}Xl(!QTj>HJLN^b$ggGO%35tK^-7J6t;c86Dq~KKi(&KocyzupqkVEUE z0&NmwO{~{YN32}vCSO^Is;LmL{w_YUQfO(H&5U`DWnPwa~|wk4=C%!v|$l(MSo>jPpJ)$nbt_f49%1Z-sXPmhCvo@@CT;r|vBr?RvhJH36h zp=ya!+ndJm-YGKZQG%-DU}N;VP75wHlk0U(mKUn*)AZOnWQ6qGqb9j z`Rb$#?|WtrOO+*wC6<~fPm<*)*UAHgY1~IU+z9(;`f-lcF6a}xiEdBtl3;C1J%_A8%Lq9eM^J%OZIz~nT`{{pvi-UZL;2!{5%1W_xiv268_XD(NK ze((*7>n}G)e_`@{0B&;|aiBH#Z|w=J8@Q&?{;OGGq>$vKPm_iB z8z^-{X63f_br_-SM2&dlWuiXDmo7A08>Gard=|s6x90mA zp?``>ya|9vXiGUSDj(mt#2^-T|ELQ~mE?jH&t%|VOj#0>h%^t5?2MXxR+7NjK^=31 z{-kcL30zc6n@O@$JU4O5Q5aY8d_#MF_a5|!f+Y$Yzx#4JxGH~$90EI3C%)PPQM^j{ zQHfWJy7N5PpG52=6A~93M5!p_>Hf}QS|4;pr06=0IWUjbx!OJlNDMz6QAB{%7#l}d zY=Y=Tk3MkG0oW0ilE!aoZ-0MihBFq1JRv$IpH2{gS&e&VYwJPp8w&rzZANj4kzy$D z<{NIl;+e4_K%!wJ2S~Y+n?I-j1v4x)Dbp<7)8Ak_FM}2zbl2y+UL1(ItXalRt7bbO zMEy}J5YGjGczEw}UzJ+x<+qZCER>Ux377rPY~{-J78MC2CeFI+dr9w@eY&$z9NbFR zLUXC51zzG0^J@OS@IhCuLmF6zhSv|H@9kf`ToJz_cv2Fm?8&dU8kTJHyJKAYbnw*Z zaFE0I%inE10x=lewX;gBwGS@gavoS0nTbls8;!rzM zdX0c7sW0*$Dj%obHV0->q_j4Cfulr(9E8kh`JqyKy>#Qd`c%lJmS3medY4{jd2p$W zIX2F0hmv+lY&<=iRBR9xjeQsE9=I?=^73V$UjpE@^!Sm;zq?=JGQ}+_JXbL zz=&U$jS1Owpt-|YOs0sC8=rxq9Xm^#wn|zSKqd(rYG3WMMx|EVeOsYsDi|}y1*;H& zqUs%U!$FYgYg-sX!XL8srvOKd6!8ymcNzuFU^vt0byh4vXKHJ*T!ogHe*b%r9C3Ja zp5s3~C?)r7Y3!%1L3NTb2q!GA_hIuaQ21g&&og$sHbLw4g&hdiVm91vSffqQ`2?@K zBs1m(^(jpt6VMZp9ZDNuNRe01ED(>`@8UC~LI-+Z?~==a1?h=`%5iOz7ED1!QJPW< z1`WAnZr9-z6<*EvDw6bxrq0=7Wss^g!?tky@cZu3)6o#b4gOZEGaS6b#2=V{&u)Wb z=?AvaZ@6O?dg4uPFv&542|EIMrcx21pUx+7*LMgvW)@&Q$3~nnOpnU*2y$goiu1zp zk;mE0bG7wjts@X%DxLd*hsABJbB(>D{H!Y-$iJ8+Ln?7LmbIgi?X7qO0~T zFX{Gw%Zd=KfD0_vR|QybQEeiNsrL}=Vo9cwed0hJYAjaYMJfKGsHh{rCCHHpB@jf< z7_?KGYc$z97I2X9@&8?s#Q%=NS~Cz|j4K^qjvOtSjjRBC3UiPn2AY%F!>Hg1<1G)S zSUA&z4=_@3Ja0{aqXf(p*Hx%MRqH6IP*W>L;o=M8FDnZ3$fphA_ z>A9w59G~mw7O<~d>>)JK919;b=ixEQG@7nW6rog`3G+^#m1pX)lY95^$(@}Ts4%I4 zztJ4J15}y8CHa-CWzm2DJw$KRl@mkheNZ21s<#OGH*|JHhoBV){9KlFrx4l4(O4rK zx;NV7z-wyE%<8@0@pt*r@4H&i@G4vV{Uda2~ z$Tit}zKFjH)l`!#o4mv!E0vO!$%4!R*%<4WN_aK}EZ~xWnaJP`szhKIo~rXiQotFA z0gIz{nO2vrlVFoO!PW@kA!?n8**_vVzspOk)w3tEwJUj zLj+?S3xKa2QXkx>dnyt97R+f%@(!m$B35}nXa-$GOv&v1a2Fj1>Q1w&lA$W%JGgF*C0 zm}258_rX`_v>CX#nW183QPC&e25&p2k_dk;di}ot`9B;TXIgSOH8r#UL#i3M$>A@S z81m2Ybwey4NKZucQE`Uqe5@{o+W#{1%La_cy`ZqQ}c}T)SMhbfSqaLe~&mdI&VImp9 z`^2gnTGJ^ea?1RQXhUUz66NQvX3#xakvU-xl;~S8(Zoba6pKX^0+<Rmp& z)#4dP5fDvDma{{IrfXofQf2`=he(hkH2Fdl|MqoKe1FUjEo>O!IP()gu?%^4W&{^L zR#P0%9u|Vm<|B?+ux7NQI~Y|aNrxo{(}4@NreANm4E{3HhqD#0tAjX+#Rj&c<3q_8 zNPd-v-SG|VAlU=ywo%Os&IoNaKsOf>9F4G^Cb1#$B}|UK57s&hi;;tyxppmN@!zk4 z13tZNrd_qxXDk(*!6KWTv*eFS?tdfUc*##r_^9242- zN#M>s-#!X8jGrR?(q)QIP1A6ELbyW-HT{vvS^^p#42U7#YUB5`GVU z4doVJv3dS}MZL3bM&?G_UpPRCruZw zMqFy9fnRDDeV7gxVXUN46qvTpU>NHq*G4(hZ2eWXyCnIG(GU# zOi|1leeYIFOHrKl1b@yYG3FZt4RRl%*OF7S5^5-VqKU1x&b&MIE{6L&pJy--17TY( z$6qgVS^RHeBZG2Tq9m2Ck>M*ya<3^lhb?4TaGL+U3BB0ZKeXHuk;u?YF!q_?Oi3Rp z$VbU7Q2A058aW)9`s3`2`JrUhr{92WW7*Gu+0;Q2!XeZZjd0z2iz>kPX=7c7GY03* zrOt^<&cxSU?pkwnFzpr6)73Eb>vWx^*vxndT8WMOby8bf#ovVAwq$YTl7lI8#rTd- znHtR0#q=rrHnl>jS)a)m)(-g(AW0sMYSUPAC5h*@6B?m#hg_DVLCqXvZN4NZ^~~gP_af43#w@EL;!-iU$Vw5jm$gto$J|Yv06% zMJ0Lr(9^kpXG*d&F8YMK=ec2;QoW9@!AH)}y`eU&h9+CJZ!gF||EY^_;D~q?_Y|S3 zaTtt6fX79r*=LU?SAx&cFpk7Fj3h;$$};h*4wC;!2_$TFCI3a(0mr59)FD#i?Y+Xh z;Bub0MT2sQ^gj{e`En4q=x>spL1$PGZLWwrGd2+G&^}9};$~xbwxi zobx{%)KRPcOL%+7aq-$Ydge*I{;L=I6<*21$lO2fwb|uMNi)rqDLpKK1JwFuijl=e zC9(Q9L{{>41&%s%7K1u@r4wQbrAXj!fs!SY{lm-eg*q!yza+t^D^Tk34>!U%&}t~e zgKU8i_OOBpikdGnbfgzdVV;OJR&<~ zw%PHidIZeV-*z8;XGiwYN$vOGf1vA9qQA`t-~sO3=K|zz!DKL+nm;Dz zOR9d7giD`-@nyZG0;wnE)!}bV^<7N`4Yv#0pAmeVsL)@bQQZF1i@g6ybfH7VKFPR{1jlD((TA%NE?JGxQ}8N|fB+~y zaDq8hO5AqKH4{318b`^3B+Y$vAl}z5)f#uM!C~Es19U$HF^BM$iQPg2hkkQKbqI$J zC6J7yhkI{Q)n;kfC-mME>;-LbQCsr%W z{VZrqsShv85R$aWhC1%$nb`X<-fuy9#eQ*KwAJxlLbQS*4FWaF4hkqiXeJ=s5E?6lCc3J<7SkB|N%8N_={ zFvYvUu=TY$O>_fHrnyTw?9^YRC!|u*J*%oOT$?oAm6zInb@<$teZ!kYkP@YqFx<?FC4~+0_0108xr-Wl{z4eq1&Ox}lI0B<=r{05ct z@2@2p5qJJ1X0N2|A;I#QbNVIasOHPNA1-{vV@zKRGL<_>^ve5f^kL*j`V|coiOb|i z2TH7@c`Nd<#xza*-!(p8qQ2kj&T+^p|LRNO=5bOQn-!nX+!c-L{V-n!{rKjKny$@d zW7rCzz}HY}pH1$IR?+#xPZ~-&sluMsje-{)wj*ioc{#$q7`bZu*-7S-IL_HJbZhWB z#9RuWKR#P-2CSIj40e)fy>FYEevM3Yn-SJgJD~U@2P_PG{dKVWKDVCZ_^EmmJ7eEM z8gIcSdZ@q89DZf+OE;9OCjZ-m`{z4ftZiXskFC}*9%N4?uh=;|lGBddX&$ixzcEA= z2NI4S;3T|kuexjJtV366N!=JS9v9|=OrI|qxq_hPnfMhTox+n__XzT?V73J(uiCdy{UfSPDKq+$~Fi>y|`{_XDWxME8ylk}SCP7A? z&XOP?Jdxft;{O0dLA$=H^vwtEgYYScMT^A;Om@C-zohVAdEqoFi(97;^-%fR-`ed_ zGOFk`RB{tL#GsW7j7CFtxDd@hpJznD2j z0m@BgT7y2y3F%Y_2><2q_S1qsd;aOoCQD`N`3yc8Z$q?TfkiSU}3yfbVo3Q}~h9$43IKK}b zub=s2pwW?``ycohv~km2;(I>+@eBWrCj6u7w=A|a8|cwTf0>`@BzMy$^{9emEI^YZ zSLnyD{VmNUl)7x$Sc!EHZ>|rtbt!o&0O9$y%ury`Q%u$f{o!yd%+~~dT+ZERe(0w$ z9s|V;khdb*I<3^*Q=V+Us^P!*Iq<-n3FI1Xwr*0w&rI+&7q8CI;e%drzp3fCP{uX- ztRiQ?@F{ym3$)W&oN z=;L-k)C7r%P)6`$Hk(Q0p8~Y=shMew46Os~-r=Dgn-ydIbFWMZMW_S}Srd`mXRl_W z`dav}8rBO+PE;S$NmS4C@Nd67OyeqfZfUX!eq<$Kw6s&eKOhV%g#fy86JZkhT|k3d zn#?pb9HtEa*WBn3JkI$`L7^uDq|OW1AzT>Niq>X3ZQBgPIrD0vB(L9QKHo-XF9d}H z0M@7WR^-cDU+XoX7yb(yschK!s3Oe7+-BnTEYc5pK=>~ts$b5^RgK}lYDSe3v3iYE z;*-j(P$H2ME^v}@!0tN`6bxt^3&#-ZKo}}#SXr}SRWeF7s6c>5xU6DIje=NGGZen4 zl-r?S@h(WP8V)DO%ECK#s$RJf7V&@~6vD95r0%qY@Btx2i(&>92|NeNlt3^+$z)pW z^hRP*?7&4^)r=~YMdfRMYqv+qsG`@L@+ZWObpUhpb~38inelpJTZZ;du3k=+a*Qf) zrkRZry_vp~MyVEpWic$~c~C0W%BXT+uZNm^R^iU?bk>pCI48nz-5iM0!^eE{Mirdf z%g3O&y89q@tSRq|`@p*dc`;;IpsXssuy1bN#j??q6`sdG= zVaTvC0_!1^+E4&C_zLfWgW&{gF}fnxu##R-7Z_{`-KQ9?^+v?|j`IC>Z+B5^i&YpT zVsYa2-b5$Q2C3Daq<{a*O6>e_*TQ1G0l$Y$He}gEljFU@8_c=L5`!^? z80M&~*P5m_-wy6XrA`e^ZQ}3rN%Y2QAuetxAhqiVq3TRyO)n`U15I0b# z&qVKiAiF-Exe}n`m*>Q$1PN{3kxR&1U)sFS$BG+O_}+?9Mfpw1sZzkG!oOX-GDmmq z_X^L(m^x;i_6%LV2BS)xj^0(jWTVPb3@VB;Z)KI2dQjdkw=P=9IRb!=K<><^o7jmC z?=JwqVa?M6JcSz6@gwP9F;vQ^0{+Hih>?*?nrw98+y#2+xfj%571WF>HLMrFsPeA& zzlZ6XGAH4IwN#@Da?ODbt`sb`W^&i>r@`LWnHJB9h&y_aMitQiO&c9TuN98L5MpHd z!~APBLFX^cQDcLJd2;BVu-;?@t%WRrwE_krIAYTn6%JHffiF^=ee9h5xE5=ra||1(-`D*aOo5j{-0_5V&D92(cs- z;P^&nY%wOm0G3twTHWJCi^6E?6|2rMy@D9O5ZVy_0Sqme zRb}Uol6Vvf3;d3A5gtPEILVH^e1i&%9wL7Fcw7i05DxGR5Lab~Btlo1#Isr|M3M_vpVMc|zQh4s`-f@!l73JdcY>nVguC~mcY;vUb!yhcc` z`i5>wC&qbQjPrZP#W;nr14%hik8lL*HVjM_k@rQcvwW>y!Lt$e2G2m5cvjK6l<;5q$mc_q@Lx*kvD24A zMZ}1A9C| z@s2jaxWaLan;l!6Ja!$TpHOf71}`bBFHH?rvYA6H5F>1ndeb6+u@3JI@KB;TKhF(H zQz9NEPo0nZ+)1OuH^ui*Dxync4XHH0M+4pH9i!IPR^~Zvq5v?gK=FZMR zsw@Pq%^fSnfOY}zEBVf1!2DloC@^@7V-DVX$S10Y5K-8i1D>?2Q)j1n{+jDBmRU`7#}*qMIqaUl267KP3A}E;=0P8A*kBRIeGLY>(yLsvtH(yi zj(Yew>VVup2^!;ZV&nIb_0-ngz62w#1n8cY3{)iiR|0YIx$o8cf?gxU3xIi|l?wqG z{!1~K$AmoH)L`Lp1YQlaJ<03FoY=(H*{0+@0lx#jM`E$?U$>G$1;~HDe87VT;~RjS zh%kx>NvM@GVeGyuPSW7DXEo(H8od4- z&5r(Lm(Iy-JhAZ_rz(U!F zCnanvHW*17hc#k7k^#N&UuNdv<+=n!xQ%@dC0yJ5qFMqF`U}x3O21+usxkc6(z%`6 z2*sE1H9(ma0@EiM%rRyP_w4Y{L&qBFk^7rz?=CM33l{SG6N30aaj<+;U5n+Q9D|DX z_^k#5&+c&4z=E0*a}vrNi~|rv2#XN5ulI&?cK$%{)*4i9^o8ltwU7uo0go~iBx=PD zPXIzp1206_1#ozO9W^&uDa}kTlo&PCP!(9ts$C&K;e~KMTF70MHLNU3r9>De*zr_H z*-#ZVEJP&@Dr*HONTFnxn4C_~YsY7WQuEF`vO8I^j==x}B@s6Kz!MX@+@at?O#OPV zN$?3$*#>Bpq!RmfxrLVqAYwCz`&bB#(AkS2UXyc2XeMKzy81S1@4iDlvN*(!`WBlI z2C?};uIW%l$z8s{V!M0`0Xzegy#RJ>!{G#mA>=s0P>{l?ME*Nf1k1Q3gy5wluZL1R zp0rUazbi@Xj- zl&-EW;i2;S>#vJrDIV)l_1gS9pl=i-Mz(0jZ}xa{zTlct3Lw497K2cxvpj&cp`7IP zXnPo5z>jOO66wf0d-|M0n&A8PJDgfwW3y=Lm1?`~)&WC{- zMr5>+UeSa2jsN0$Sr)tI@>q&qy%=3kUg2{5N`GGIqqq6*+t()P&8q=XUcDH}DJQN+ zg#i|FZ4EW7SA>~Ic;!M^loQvd>GaJJdh1f(f+Ek!FVaf|z@`p(3&OK-IR!=!Ex@y2 z9SnzOX=dUDvKR|{E&|~5K_@YH!Q&&eFT#2uR|-5-uwfYI05E(@U|ohD41eKqin@RX z&ju3I+aIR4PtVRrVX;_E!ccR&0O7wRWRiLqR1}sU|J>emvgWB$HCVZU2n9Hpc!UG+ zdMv`#ITTWq0I;xv;e&vH?@%6SmFnvaOEswAc;8?|5aW`|%-R&x6UGlHS?b(Ip;*B? z!wnLN7_qw*{j7(!7VM}}h$h1JU>5=y{Db@I#O_^;AM7~7Z(!`9Jc-3pEJUP5tVs~o znLttqe(-py9#56qo6y&=cF;4Z2yZZrG6srDRVOP1Pq_nTJz%XpRl}Cs;suB3V<~cb4(gGPoA5jBzHd6zwUM@$FLb8L#NKqQHHB>$8NV! z3ZXRkEP|)P8rRfl5dsB1*YVm2r5nb&b{8*{t}V>hO1yb0AiP{a6R>V#=RC$KcI-mH ztLHjdcoM|IgJRvhcr_$K0}2BVua)@)Ypm8Y1&U_ybI6~9_rSezOhWG1E(bE{CwO)L zOi~Dx#>_aSli7SQdpBj@@#*IWXgXk_2+#Fka8{JL;1tcwjL?*SlJ7B5uml6+6b>QW zSdfM1fG8HDpTo$(||_OYvBNXMww}joLa6P&9l~v@wKpDECu*K7`8r zFchXWTUW<*?j|G6 z@YphloIvn0!u_!pf#1S&Ts;1Zc@bbtgO`&qr?@_R+`n_;doUR(I8W{7 zChF@OqdKnF0}nhvyLa!Vp`jrP1OmcP*WAYAR6Q4SOJaCb3C)J~kOg6vkc$Bi123=r z4F&I3YANJlqKBn;tf1d8Hqa-S&&Z*Jz5?llF$M-&2}N(i232V$=a@vPo+_A=s0-#9 zl!i022{9&MkX2+I)4c2~64$Ha0kT%TdjEXfiUt(`?FqVBtY8g9SRj19?+!QJyVpf~ zH`~b&XFAo;LLIGl(VhDrqutw&P*=wu8t=VARWtycSWfcMFpjIb@P^O^W zpe>-&FtT7BEhLU8{J6@?@VU4S8%mH53)f>4u;88fow2z_yVhX6gggjd0oOrB$EI|A z2R)ZEIy{H-jmYZ-dY&p46GEUV@0(y*hou*)%i|-n?O3>7)~lyV&8Tu40E7rc1;l7$ z7nlGe#aUKLXAFWl#{_}U4&fWjnq)B78VObnH%UpjUBg1Gs!^pv<3JB^ z>4!2Kz=jei#Go|C8ich7n+Kr4hoJ>A;;~MJc&&q?9Vx<*F98M+*= z7r-V3gwn$JhS1i=_x06dH=U7!p|seAhqW`2h>5VAm#&7yx{Yu%P~0kog_-%!P_*ZU z{DJ})bO+uecn^Hn8dYGl!SQkco(N&Du%2Uc&e%jk@COiRrGoE#Z(Nku&qe6u}zG!7I~u&)Hl zHLO4(jskhBk>5*%8C07a<4vMeg9=c{sFEZjeeB&$Ipb`3Miql z1l`)!ZKpby5|(=NMkl4M$H-vaPMf#vp@zl|rjafhxcny53d?*k8!T08He_O82V=g#~1J?wPp{8{xW3Tj4`8rBP(u6nxvu}@HA z+d*pIc(0fXM<4oG+I#3p+H=>3=gZxD=eWe^E}l=az!Mv}!escbe89+wwM(y9c&?{1 z;E_yBv$M1p*Vvh+-nqw3P0Y)p1Om*L@H4DNrs2F6gVzSnR7@N}SVjPR7&eiBSHt>^ z>p=UlmTu?--4&cK?CzvLj_UBk_3H*lOn{Tyn3XD+W}IM zr3LsQcw$0fn&dSNoRmmtZ}yPOr3hOxR(wZS5jMC_`hzDY||&PX5UZxouY3-0r4Uhl39Cc{q1hR}Xc2((|R+t|U+|75T~Q zO99qxl};#Zgr-p+nb^L_Sort_qyrfyY|w7?FU6^^VE|$W6miyGE*b- zpsh~F{CV5j+r&Lk8hOqv1yFRC8VamQDB}%utv95E%$?952c;TRB#_q$VN6815faBh zqoh&@hBW+!zj~0@0FVoCKLwzHSvrW&D00J-7SU*uWyfs$!RTz|xwNK`RTo;Em9Go> z9m+Vpb)yulcY_K5V+!U2jQ)sbuoxUp_k5Aa|DMIl_puh$vwGD~!>t7qPu0inX{3+6 zyG4|bKG8{s5B&_?d(Xe3hadjW^b0@t$Mmm1`N#C=k&jZF**9O@86P>4UV8hLj3}FT z{0@ESL;s6D{;^*rcaCSs;6&l9EY9p@*I9(i5c8z&-UYAD0AR`?yVUI$8h;n`?2@I2UPa_q2I&~k{F zct^aqf?5|l7ZW!wVCM$zcONYBh;4kE+_`chhaQ|568W=yYodHZ>|se54;w< zkhg7eig&=21fK_<{`}>TSc707>S)W&%>tm`VL&PdZJVPfENL@2tjaZA8@AKbmhoy;n|Nrd$2b^Qqbsvr&^o{|h&rWZAhgkJAUVTA0F_4 z0cL<1Oy&EMX9swA_mx}DJ@>RbAf^AZ*=%A@6+n(uX=swhAfBmEqzaTWPn~knnbXx& z$Lp4OvYHl>KTCV|JxU#2$7$^Db<)S^n8O`9cDbG_FQ!r|v z?ICA}`Fa=+8gAtNp)lPXkm%l6l)`bAo0$*I`I2;hJVxJpb)IhA57R;@CH8SKao{&9aiN;mkLbKZn__Isld3i5d)(=i&Dh|=ZTK@pud z!Q=Vx{sK#D?9iSMA#R1)aVN*0w9se@l%K?OjxwLC|3HA|5yGUoiP6plHmrlyA9Tg!D7qIh^gq!rW~ zO!UxW&x>})_m1v;q|x&n=&BcG4T;xzUJlR@ui1I1ErQD|MTDWRbp6M-m`_1pt*$Y3QD;KWw*w5t|YNU#a?E;fN zK&@3jrD)(5g?#rZ>c2^$h3nE7QILQB29Kp+&bXSMiHVf(g(6kJ)*e3Q7EU=*WV4Z` zyoY#vLuSzm9svG4KQls8WBp>!jzYBe$dlrHy)H;sFTXQO_uw&Gx8%<&1Q@(Z@^$cA-q2dvJZQi6x!7Dq9I3IN^- z3qQuAl?7Gg_r`+c-awFiTt8T}pg&E`Muj&f7V+pu%}r80szwzR??tTCpwhZyZ4D|I zyO?L8tiqUEYl3I4Y)}C8L%u_d!C_LMcO^ z_&jj?JOu+D@i`wxqlJ3+JtRIyBMW5Lofn^htG9!+5Ya3$sz8~CcLd;EQ7OX;BJGq$ z2jJG7kXUF!@fT$N7mi9ssJa@RNSOsDP>xb?t&J)`j$wrt%}W_p02o!^h_tiYO8%gh z`=+#~N`0+Cq}YPe7Rpgy(8B#DB#bC7r;Y}O!{S|*+P_4GyvI*5qY8j$MFcSndLTHk zpe>;g7JX2s5rp5+CX3rw>MP5&hqBI{MqWHSYN@)mjjVQ;*dqsf5aF}cUd23io+9zZ z?Ne_}uzcA_H*QY|qY5Ha>gwvaZuDZ~dTj98-l7wm+2c90Miq@1`}m7_V}Fl1BOAsN z778Q|lGQ4ut-5>TEJea{`mu zwwmZ?9&s-+s_bkxlgp;1fpI8_HNp`Ab0_LwlFtod9JjE1;Nm*4^7WMDLOK%eUjZI> z9)6CQdFEw&9S|bPcQl&CZ=hkmN06Ue?$tOa%Fl|;cJVvX9m0@|abe_lfe|Oh^C8L@ z_!%I#MEJL{sR&KNSjuYye8>Iqu2>7;x%p#Re5Du`8C95n3N1{5OK%0EO6dlb>`QL7 z6f=lQ%y0X)2JXkp7*$5@U#5Y(*SNk+bm!JZVO+t!O`}8o)Y#gWV^n$Rl?i(Lil0(^ zAG9A7pE588WTRs~-5VO@K0c63g99`;I!Xhh6ErwBN%u#l>F)46-5d4L{V^Z&wgknK z35o>Gs!>J7wnaD+p~0zP9tSftJT@k1(O6-+HQ?j16w0A~mT^MN8Vjwnz}k-Nc8Dlj zAeGY5`1~&M8Dpoqx>|gmof_hCEE!V411wfY4t4H2De;w*pPFm0(Odxg&KZQ9mB((D z08U(vRLEFlRN=39QHsm@r{g;Y0KmjgPVL;$@Iax5|-V1@h ziWg)U9N2IV8(2bMYicx6OIjJea;*Kkl!Mh9R5sW9R2oYeRDg~)i&(?~5R_kk$3t&0 zO+d-S|3L|i6c;eWH8}Xip)4yCaxAh9@?K_V0?+L1@ZB3_5+q^)(%A^A0 z_Jmvveud+3D1lO133=_<*nE(>dXA^-Q#vRsMw?srQd`G9GArsD#+Qu;o=XW|Mc(ai@*K3^qDfU&j@8R(yQ&??VwKnTntDLbn^5EGh+s0MIJXT{CBMY z1$d!UU^tGxQ!0esDPF`PLE`QF)u5LT+Xp|y}C5OIjy+T|nufDC3bnr!Jis8F#zVYAo@?t4-SVVo34 zY4Q)|Yil~?-^tS-5XWk28^vEGVCcpi2`WdQUmE1erWn0f>pHl+F+FrgfMgs=~w`kHo%0S28Fp4%BB}- zXCR<&7pM^`OJg~M3i3$G{Q-I9FJJeG#TE8cf!Cc)} zMnf6J$9e*3f8cElegR%%WXXHLtEC%J3*CuX=|%=b<|L25Q5XUvC6qrqw;Rc0se z^MH+uv`X=qB!gfq-o2UN!A%2DgIk`S%S)dfGN2H33OvH*a8?h3Jq(mRUJ0VgEz&VHl z!f}IUno2=cD1qN&MAM9xo4ULgDwZMHQDfT@?^LVn+n{Rzv5vj6R{)2IdPs>o1AtXM2s5wU`Z3H0^+b~AI+9zWm^{3IVZ z_trp|eB8f+++TXTY@%JU&kn8$UI;lG;|%=_;{kJ&NG6#cb%c5$DSp(yFuNkUd6VB&F-QPJpUWi((y30b)KS@_7imS)HAg2 z;QMIr0Uj%9I@TAWW4q%#o*Wt4*JGzU_X0)Jf0Y`ka{kTl(p);N=$)Gvg+UeH@psSR zGh%!rQYGMdoBBsE-$_dSLUZccL7Iz-)Am7rq>6#(O1ZAXEF;=@YBVoxO)Cl*zYQ!` zuB65e{LX9S-t{mUtJ~5?HV;-WRjOD8au+UZjcS*Uy4$VPSSM}R1VXM>99z9XWqsde zDX0dOrGZ6HIR=%Xk+3klb@0NgtIbky;j3cpuz5z-7RDOOI-A*`0)>kVEaIVXS!-g^ zODIK89jg+XR`1(ollFkvZ6{CCKr=csO&e@9VydD6vx{!&U36XNqPMA<-b`jGu329Z z1>FRT0INogR9Oy{j97tkQU;VL&{M!*fiVI_*+xe^Al(uo8I-y4D-C$&_VYp#-nk%r zzkK1<%;Iu66pKt*>xdQb6c_`L6#zzr8~s5V9P!h+OFot@BFqP*{Z}?KpqQJRj|<+F z&Tg;>=mP*0@>g&A>HgrnP%1-~f>Vj?5Q3<{`$K+u?QM^!d!!6ot9^l%2kyK0-rs&P zMfV1!_MZ1h#+4hll5~GKEEE-m5DAXc^u)W1Xlm>o3iu|{XGu`rQNz66R=s#*dcDy` zCP!WR+hU+U&U<2FPnv12=VHLvz_`J90pUBwjqK^Z)__7BsqSP2`BE63Jwns5&(m!D z3pr$K{JYfN^^mB0?8gHG29(Nnp*S{)Yojl{dUl@MEkpyuxr8-Oxds&gd=-j&C`zX1 zqT~-G$sbG#86SNXZv;6a#>FK$f}hQx7te_Z8~lFhx-Vm-fKdYd{rKT3@eTpxgee!e zD3kOK=`ULtsFUqtP)QL|KNeDpN`I{5;?)3l#!YQgU zze6qV@6xyb`v0PD{?*^3@Bie#(F`r*P~5aYRkeOH*yHr(YyX|T_{CqLKmA|7E~Tj( z3ed$X;J*>tyUQ*N*0O93gC^Fig~(*vK^8}A4w;$s<_0oZ+@#Z+1*uT+UIxYh#)HMt zvS_^6?DoZDYYo!#E`@LXV2TEZS68$ShG&9ub$5?Vc)+d~%I)b$=VDdUf0YCnRw@B)j&P36 z&^0_pG@}0^QlJzse-#^LSdljT#GZUGfMHLD{(B*@!8XP_Qp;{uAPP<vtq$ld{_tAxm^Arom#d+P#SCI}5pNFCFdv~6uCPP$Pg^l7( zB6qa%ULbUN^lIg?YKK-3;IL@L^_0KMIjEJ#>fce|N-J1z9oV>NWR=PY%&zqW|9p|7S(6jmK1l0KRkey1Rf-G428)?y%)me?3Q zyvnXOG^$|Gl0Gml53FwS9~oSDZyPDCz;w4WjRjK~&#O z`i%KSPO0dLXz1>Ag5J6rq;I|Mp_eaA(Q8+yY1|i}$skdzKsWJlwV({n0qMCv&GL2r z<~0xf_}vhh?N+iN#EyY}k3I(^;z4s&QmIUm6E|rqzS!4#@HLA z3I3Gyp_j-K`yRQqe?!+V{}G*g>wD4-RH)d7(4<17@qL}*-Zv=byFgL@4f0N3v=rue9*10rxdG55$7yur9!*bNr|VbWptEnkM3=6-P18KiWr`-k6o|&j zR%KznQ%CdDeDAr}Xkq58xW?9ma-z$p%@5h8BJ)~AuB;S=XOOKA&BDUMhP~U3cYcMw z{N3w>4bz3E4Y$;uUVCOAhmFGeR7e?j*%G~P;~%oJ5h`1v(pLo8aDv6uy}@jbc+?AW zLj#pCs5I5{;vnsz3hz2uVFMu>xv~K$Td`;c#PPP`xwBV}t=*Pu^Yq)de;36Xyz2!W@NK?TN+^#&H-NT-8^ww0ejP6dK`yLC4p(&^~+NS!3@^OcWZuO26tZUx@1 zX<(Dx8D??tBrX-GHgA~dd&ws$Mru^vTEpk_k;yqo?_QC3|E_MLBL_4h4I3f?uxWE` zjiKV3)g$Tzkrn__-9#0d9n3@Mk3#9C7~je=*tA(Wu8~3q3Pz-tK{_ZIVji^W#JC(7 z3Q%98R;2&x?X;5KU?)$oj_1HA4Gxab*!VongmT9LhK0+Jpzhw?gpIs=It)~89~GOU z`&f3law|x~zFb9lJ`Wlmi-_kcc3cMdL{q(_2rCCrcuvm5#2gQ0EdJseP!g{Mcm}0n z5!XXns!C<}reA0MC20%m4V=3}NHr&puy6gWN9=!2)1ko!isgH>!zRS%yM?!G0HL z-~af(C#Z?}>nGmtqKj93!UzCwf4NMnGnJG626E54{UHj)HFUJwDDDmH-DMNM{nxM0 z(en>GXXI{(A=U6fvwE*a!I->A9>e(gsd@hW`zlaW0Svfr1#KSzNW(n@HAF^cO%6Ycogn|XTLKL%%oO9YP0=)4#9(QU#!`$-tdbygOk>=gH>cU=_oAP zk>`4T*Na!Y6kz_@SX)Ha$$k6`3K>)+f3gpFjys)5z z)MjS0lN|1&6p74JaN&~Zm&)@)EX&CV++`-|}omb!hi1dv6 zciTn(h;lQ*xQD3LnYk#<&c%d$>8P;Cc3`iQCKuv#@cLa(W^}ZXWl)_{r8xipKx;CqqJ>#lDG!$~jovFdB69@B{Aj z5u$gmdTDk(nscwtHk;r9+ZWk+Y`wAX&h_*sX}UIZdjQBL5Muh8?|)cGf7*Od_f*Nl#&zGVjE%1~)u2*3kgfuu`IwlHdsqe(3G$)@o(IYe zdsl+Zv8ReUqE)O7RD;U$fC3?wfYhX6VLB^4NnWo8n)k*<{(l%(3hnD~(&8txw(vr~ z6hN0Old|MHmQ_$}we`a`#k0*Y*cfH04dw-SIfhhcq-a6{4}38R{RNqQNOY z32wrd*YGqf6TV~nhl%+a@&xB;A?TsoBQbjOYLIU6Utd(ieKvR8KmoX(d#vF7svJ@p zArV=`vV`4`qGo4`T57aZ@6b?NV>|VBo}i8$-DFC}C>aiuCZ#9ke-^Ed-28mcJoQ1^ z*SnMUbUNu^r=NDU7|1&tqG%*R;e_<;l|YkQOOKy&3&RKuyR)7cy>m4n>R@NPSsa%M z`@>B6Qq)kTr4Kw_BMfh7TgWdLZUjXi>fB)vMjHHvGBC=Fds0;A(9-)JuFhNw%IPb& zgA`9{=z#+^k-`SYQEy0_HaMLiZ6ZOtd#sr<=wI*N42b+cdZr?~j3R zh)B9|KP;Y03B2R8kGaU0F|6Tl?m4Ktt9N+5DzK-DydOg{rJ?b;B;6T}3A)d7>Xc`W zCg)~pV$Mr3bh-j#Cdhr+6AVx!;T2=-_HdN0+zHe98zKIU!*unXAJUC?e?$wjLo_?lPp`i8XLSAIkH{AsBs=#lgH9{tZ^-5__CoQFeOBb* z7~#H&s57xqtVvR8ti+%K;5otHkopV#7j1d%mS04+K`9PH3!-YVMu)6}=YcZ>eiyBY zhvNU?pamXn;^s5(d*XbYhrLQ)m1Jg56=1y$ zDtJHaX@Ykxg)omH)gB_l&>!*%bz-w{pNq|j{j%^LgTrCb-{o__C-BZ7)VG}S5q&|9 zdP3x~nfoe$K7;;NDqtkTd-?dDaBhHHfGHbuF0PAy136Nh%f~B4V^a~*^Zd3jZ=`UZ z4M^QnMa6bOf@Lzj(Nk~?ltK_8(_&->;49cuub$VRhYwZLJdfR5_k%R;iBofnl?KNm zq~rNTp4*hb8jM+qkPW8h$8{Z9JR=7Sokl85!Fj56-BVXadRHufPaYfu5UM5V77 zr9`U80`_VEML;=`D##^`G#Zt~#@NkdDL+pOZ^Vz#gt}S%ngfw4 zd-hM$*S;+^lGPF+r!yoLO7Lo3E6?5aid2EJ9v->?t|fczDpPRH@glR76h}~0%lFTZ zGAV@hj#vTi3`m+Mt1d||JmJd7TwyvvNy~@C=ht5R-!wjaLwwGM&EcjGe*7Pb&xz0_ za*&i>3d*|w`B#(ViB_&Z>}%H0^G{{>^?(uNYd?~_;6C}ZWNeY~jqgv>)v=_AH2UZV zvt`Cve)-Gq&kG*&u_s+3+C|29U!I{00}1M`)zBxOt4|-5HYWe`Z_kM6jt@WT%tXro zav2z;e(|G?>7x=){gc0*5|Jt&de|v=s{{@G@YOjwdpkzerX>C9XPVN-r8@h=uTJJf zssI-*87ZMKv;b`_G3sce9D~aAY)mNU9fl-1ExG3_zfCibjVi7u`e~h!o;YkJBUaC8 zymEG4qykZ5mdl3IWktVCE2ia0mDNCsLddp9A!T+YP)eiO(+PoPMK9ElR(BiI-oJOt^$;D893U71R>RD+5PTnqO>-2k`` z*5J60473BH0q|^4V&nZ_coxUGkHiv5!KY#PgAyI<2SgR@Xh`=Z>2;SxsRk7oIb;LL zz;H05u;1876^$?!WFu9gq8?Zcp~|bFwU12%f~l+)mlC0$^Xb1#gu3 zw=uJyir!$!*;~cttfirW5&GUYzn(rKL5);Vv0Y%X+UWhyJWUI8W0Z)8nIb#~NGS`I zFeI*#E;*L|CLtP4(QD^CG!@M9Tma)9a}k{7`+9856Jx^Ii*%8gW6ob%5c{zdOYaMV zcV}BxHUj@u8pMI^AE{C>h# z_YyX?)+%pMQK4dW5Z=v!7z_VvtGKQdFn*xu0Kr32xfoTk7!VZK!=QqNBa|JJym$pc zI4#yTo5`R8K3jQ?w8P+31u+Z1zx>rS{l8zGrYnQ-oN^%9paPVu3|97iW&hobzfKVbsHWVNUApveA(PPVw8$ZYw=_+$B;Wt;V1NNOFQn7==MFJ}3<;0GX|mT{oXNS`=UE$H+fEA44%q)&YCef0i^ zUZ67%e1xoqUW$0MWKNkfRI4{peVR@mdXk>t^Bz9(G#%|UQKwrgQu;O2nP><1L-ad5 zGg8i>kI3^B`Vhtm3}J<+vFiiWvg<=R)V%XKs^0Mc)$TY#?)p7~9PUoCI+`+Mchr#C zTxo|t6)H9tOlG&}`>wj(JRS~H%g$$+p39-GuI9yKt1D~xSOi|2B28c{mL#jyNDik} z`~|Q^UWwz5ilv~Omz156M?Kk2{rxKW=8qz+4mII#-OtOE4`HTUr=yD zv9cPhB>h+Q21cn>3gJkK!rZ+e=VQUTS%I+wt#@Z z(sN>3@@kh;D!@YzZ6hmFWo$NsiVXB0E6?Q^mnO=(EgZ*pqPTPMwy~SSq2_+NC^X=4E8w?S0CW!c^K(xa6HDx@;&gBXsk1e^g42S8^B@HiS%7cLfS5P>4J~T^DVBso~gi` zJZ?dKofhh8&GNlCHB-vaCq5_RK?(=Gbl}J%yuh|oOWRJ;8<>w))sRN3rOutl#d)dt zB$?=%_>AYea6PbW`ma<{PugTHX;QXjDH*qsKfaUhPqxs&L?ew&B$)4_-EDjwJB@hu z^6>^igF`+FMQr@=Rz;Zx8X7Zl8Ll@zUq`uRMn?SP4_W!4Y!paj%ZyH%SO!gqGQ>3Q zU0f!auu(AHO#@S{;`rc1mDubRWi%<2*_SCZIOr8+@J`WW8{elxy4F+`jquzM=W8k7 zoA~{>F+}Q&##$RS)m2e*eKkcRCNf(hIR+Iamg@ysg9^^nWW3Z%1^Tx9#@Ae~Wq zU+@HZ{9%0z&)x%j9AXb8DCOh)3K*|SIbbCQ6(w*_&`N;uj^{y2PwWq5<2opnWvs@a zf~XQi+ym>E{!8lH`G8!OP5%WxpS_Mr(XW;1uyB4QQy$};AtNG62!=86ZpdKEQ7kUW z{xS~r*y!WWG}7?{RZLDnHHaGJ>w7%=6*g7+FP?CrJjO3LzFpFPg(4ajC{jETr4OtSYxVR{VvmeT z#sMhfy)4{du?ZfG{KQCEBZcrAM7wMYtg#$3h#*VUG`s;}p3Z(q`7T?+0mQG(rvaQVw=G&C+whdt^(koDU%{ zFVcUdSx?D;KIDG5n%+#EOdnCPRzUhMOVtovxGeGhhWa?q*=rj`T4PGknFp$6 zAA7cr$Ec2Fj0An}$Fp>MMnf(x^Uy&X9op*5nW{yYSqH zfn|Pvh8}`u*sTw3$@W8YY`7_dd8DWON-Xow3$}f#JX|tB5Ko1z&w> zj&5@~84vbZ>CEZs^ta`4_JW6Ax#Sn}7Vyv>D?NTpon=s6O_+pn65QRL3&AB2+?|WN zL(l|wcXtTx?h+)pySux)+r{>NTl-`GQbkd9m^o*r-|nXYIv>3qNB__n8yt@mZr&G@ zHBN5Vwy<*$cSLhuN=!Ml=&*CBB~QC%yWXDOom^?8wJ)EJU-4d1s^{K1q2~`HIwO^S z3d-B5OgR4aG}pyKIoMQ`|12_YgOC`|eli5n*LW4n_RVNHEX{hy=awl0UQ^*bO4dnoR)v5yQVxAxB$csC+W+|R;ZOotAc|F&S+Wr;fXc{;w z0TqxfFaOzCz8%gF&!Uf3H|J9@ETW8{9+Q(o+Czgj5})Pg$j#PBBop?(5(wDa~O@nyw6rHmLGvE zs1=5FyW9bQmJ@%2mS6uAqh>oy_rX^N=zrhSzV}S*6@rpeC^-%ll%IW(rH`O@+ELGj zxBmzwtr^w5+JWZcbsX~x8^DIXRklHx}>=L&dMjY8kYKd}1h8)P! z@9qrMOhni>8Np$<1SZW&-`2jU_*7jFG+`|s5~sA~FPx$&MX)d$8|2{%JY?*8I_lKq zdUe-*SwVihte^YfM?rsq-YcDbW;O|Fn<7&DA^x>1MHsPsRA|5x!k$FNac4fllAPE- z3w7MU_X<((-c@jket%YMR_MJT^tgXSvef+O>uTHQS6+{2qz7kWs^*zLzSU~JE}oyp=}+jA>IB?u}5Lp$i!2J08jSPzJQ z;Lr^$fHiWKmR|g=23B~A`UQW%x(6l*r){kL${SK_JDI-$c-;3`=@0AB^_+PYnxtoJ zxtYC5m~JfLA!TD1AcSAk0^MJ zJS>N~#z9-$a|AmbValEjrofTgbFaV%KMpw@a-x~Ip^|TDz3ADFDj`T6pyC)l68;U+ zd3(~y_is8eQ|L*aRmMT)+KAok>>X1Te&Ao;MD!|)L%*FCD3O|R+H>){M1mOzxp95D zBD`{wvYn3L@C){9!SO7-chY81)UzDr$xbo%#b0fQOQy(jj-5Yj5qDv}{&+`G@L>kEZKFzIR|3x~Q0iVdM;qC34^v)^x* zO-;`vDi-EQ1V>!JN3O`kW`AH2pZ^el^@y1kCP78LUjE+tBPHgEb8bX$QC!tpOECMT zbI2-KiKMXjL)(*1hYJ9%GPJNJ->N|xZS4O^89lVOQmZyL;VAX#9LUA{z64Se3U^(_ zI2(TO9d3*Tu3%tyS=prD8@yph6gA3zHa@I5e%ln9?1&D7Zy1>gL_r9Sd*YD(8L3~W z;`UT-KzHN9k^ZlW?4M1d_|G)#)@(4mnkiN?8_v>+Pv$zp)`}&970N6sc?~XNV$C&h z-{}};WceHp8=wBt_Sibl$(vk}Cu!r@l)@T10Ka#E~>EE zb;g!NT@8^Ips6L$mJLf5&G{O=A;koV$N1t=nswXR-IObe1)W>Y%p3`(Jz(T)+dmwT zjz``bl(-O{>|j>kGmCA3b{O^Wr6cYQy6)>d;+f#aknn`M?k{-aKh8{JvnMlMWMT2Z zPsE6Ye%AN>E%cO4iH=3p_r&(67^nvRc9aZuMX_3Zpc8+YFt@Fbf}$nlS&s#`Pil6? zYR6t*A5a}F1skHX@T1XGPHIM&Hdd9@fMZsqd;E$=(#OE>EuQY>-(?burHZPp>`Wl- zT4~*6zjGGZUsk$me}|_*6Dv>+rx-=rHg6{xD6PGDLD>((5qx0YyJMbL&ibKYNk~Fa zwDoz`Dc?-nGv)hT=wf1p=cvoeEaK38ohev(7CfJ!x2irX02O<~I>sBcJ)y{tBSqBz zlMpZzyD6qr1`;?(U{0k4KgOcLC1b4Bnqqa#pI+4|2ac{5evT${8?rz(8H1Q3u66{> zr~_w4tm|x&Oj(hlG7DOQbtvAK$}sizzc$4&YsxM(P87~CeS?P;ktV?R3_YsQI1ZNF zFcyTxuK*vay)Kg7XEswk*O^QvKa6Gew{*he_pcH*;*-DniBTwEniPoqrh^NelYRo( z&KdX~OwCFD-`Q2OlFQ?{+=U4ove25s=H!QSh>J!CIUI~?x zBwZOp1kgb&hmu}ne+GJ)!w%COG~A$qqGIf`*XyY@mM$J-kg~0Z|V4PDMZif z`JsMxCF4wvyie&Z4|y3<#QsEuh@c})3H=r$%>m={Hp&b0FYW`SDbH1*M?HstXesz6 z0z-T=^Ow%3A~`tE5AUW6ZbEephKd1<#AOeocM>Da_H&$&^jqs!5n}u^ME9!jdnL_o z6IS$S;pLeKSO5-HZV^|wH}ik`?28a#zq?+x97Svyl{?5N?($-YH3z?2 z#P{NwA%MsNy8q6DEF83rU0Z8(IqP%bzod4fe^#n(_r~MRf8TD0p_z7){N$sI@XD*W zA~@WE<-N7qD2qRg2b5k}7C1U`_~HQsh^H1bzjLqJi3@A)D4vV%_MFT;{AqgaZ%Y~q zjnvBv=}_C_bN}eKafxqvdPa4=fT+9=h6F&X6+T9V+LO8Y`QOpr3*L0T9Fqg@)n{{+ zky2{Tf`zH^kP?>8ih_fKkxPJdVuJ2#4L@f9#BC&b&_kPwuZTcz(UR|y-wCk8Gd>Diqa_1^|pxr5fgrkVBEb)7_nujv_C`7bY)>3F2lpXDM0k79hM2b{D-b}~6b zh>(u4e7HTiHh+_uN0yJ^a~I+?fgZU7M_rZqp={d}C<| z8NQbssk%aP(Sl>k%1=qZuJi;HAX&C9u|Sf*q9`G5X~lFp2r<}1XP#zs+nX}{$Oe*?EK$J5Kk@Jr&~f&Au})i za;wO$TbA{T#e4fD2e((7{H>X`xNNiDf!Zyo!pH?S9v~Dp)=9!6L^+=+kZ=4Acp`;; zUDMNMPl8(^95>MPLbpfAk!*!D= ziHWs6z{K_1PtjN*-+JhPPAQ|xW(<2W4=w-@Xy8RuTi|CDcs<%G(lnLv`a{lF7V3aq z8ti9*hZhL*j7^PtelP}URX92uhfT8@;LeVb#I`Qy%Y;HF`-iPG*8uRE#-@DGTZE<8 zVOjX9qHcK(4!PWC^!0JzL@H5XKAyx_-4Id}tXMT!_Q&F{s|WzjIgK0Mz~M#ABWTGAdv%O1`>8DINh)=eAR4JbiR42@x_qvVu1e8UaEs-pRMW5kDp=}nnuiXxt{Y%WoLyn^-QjC`Q+;G1)gvz2iFCec)Y zkzOG#z-lcw=)awTz|ut){ev##rnz8&@ez-;7KUx`7bhP9I{jbXRhE$E7%=RGyL|Y& z_w8~zfm+;0#qdE23@Tt?M91z{|7JvcMuV~u84)GA` z!3b|rAw?yO6RB{X=cgKHf@!p4H@$3FZWHkXZV*9}@=$B|L6eqTnTDjY$W6bn5S(VN z(?g4dm$oIA^3}lymu~u*f|t5GOL=D3T~wTKcZ%!9Ds{|O`x`*d=je6Uk-YsH@l$zx ztn8W2`+}iM5wiy?mLIv1Q|E>EBvDlrt6piKbPl0~X}EnUUr{LIqtb@?4P5AV#jXr+;vD(aE-Mk z11?ZaRXS+)y}OEAG0g|l&88&+lVwuK7Cv89@b zs^A*D?AJNcLjXrJZ+FI7h7*>;K)*gKO`_tL(qa1w&gGcohMq| z>}Dmig=&ijblEe`)9Yjt7I<{>hok&$wIrkE_bfb?5X>pJFWBAcU-p|bBsl>IkRjGC zY9-;CM&I>^yIhJHzQv`DQ0=-Cx-a4U3vFg6(^GjA;9)@>bcyP<>(+>PvR_Y(>q(-z z#AP;nH=G&^OP4xYMOmaIKF+VpJ=#)&mD@q)SOAWDl@_mR+I?8MSdEPSQbMAi*ya2Q z2zD}+Kp*jNrIYq_T^YG(N*t(*{8{{}HQXF$yD9U|eN`wc1&js&nh=#o$cUE>#36IA z^fG1Kf)$G62B0i&Zu7WL>55s}1E!eVOpFDmCs%d(rC3aN$7Gg*DSMIxH8zKiFG^<; zHw_C*NNh2VC`1l>5Af?Iv$7-29&Jx-{?-vu3jC(;hR{bU{p(-~Y7`j+lL8|;YtdwY zS@NPynH>8Jo(c=4^>E8l1>i5Y(|=#?KXmYCcX4Ot|BamoG?2=b%zmNA6k7D;?1zU9 z>owl4_*`rX$uO`_?okm*hl$hU{CKXEJrWT&hyzLA42=8{kB``}08cIGME1QA4NbND zjDn9O+v^RhW5&H@dIHY)8N7p5 z1Ql>C-3z#}fI&u|j!@CAnr#&3WC39U)fKJ~wplHu5ISplXpjsmk@rp^;*8XI6DN=G zs#6Yg4>}TwiWm8gCo)aoc_#<=X`bpbLGP*c`Qkhnme-ZP^tY-37?fR_uS!zzIRcmL z#pm7IG+es-^g8mpxnxSyx1qUt&h~xLHk=0@E?Mw7P%zi=XfnJGCt3oLKyCN!sJCdn zMI&S+H9znbV4^Ba3>cyrgsRp;AuBP=#2pxnfW{}gEz48TPE3j{iU#Z!Kwt^2ZIlLZ z;+PIe>nr9lkqD@ZKEXda7|bfm%STK7Z6*pCnwlAZyD$THFS>pFy-&pLl7Wxm6EQa! z`~4lYKt`1i+Z$YxFps}1%zlS>Z`A!4tt74G_Q z`pv|-zylkAkb56}+SOoD;L+XZ_3&!$9$+rT*Yv%H5qnzFsY&_`7cU2iIeo4POyp=s zLwCsoidQDnX#zAMk0zjkFLUFa>b@0o0@ebXzG#@EvR~7v$kH+ z@SjKkAr7m;5qkE!qT~9Ep(E(_!s)|@;Oab8g+GYr^7a-vqI4@9tpu}au1d0NkcTD< zri(hmMjS_R3x?zjpFf>1agK_eR^FpfuC|Djkk?>?=X|S(ULt+y&`o73^HHm?O~F(@ zDQvGH1EI(KiO}p4v(S#~v2zPKUri`|gD5`4mPwiCYQ7LBiMWX*=daXAnVF+`UI&;- zJaL#fZ=>)p= z83sOzo&pM3$(7HHGE-zm3g=O0Nb5*tSffxLBEKX9fo!dG{tqyq2&t{%?xX;YK8G&0 z8;}LH-wiUtU=b1k0QS*p{#WR`K%PlS+vjxT;|CWSxchf#%#j}x>9VwhXxGG!4J8DP zKGKF(8Ub#PgPYW>lLR9MO6ua@AL|>DxE4;LALI#iHfK=VXBf6af@e><8Q51NQppdV zJ8YK?)S%r}!F>>+>VK~ptPD2gVBg-GQL%EHST4P`W=$`%6-TIFwN`sPiAm`E@8>Ow0{Oopw=)16H#Q}fF` z2a8%UiBg%xHwB|CK%5kKG=J-s0$xz53c%T0aK(Bf?k6|%v|CTA0%@QV8%~8N-H8nf zH~+_YP52$gj_f|z2QmeG{)nxS1Dj8l@1@zyx)Az}aS+5j=C)L^ph2pgH$nx{abwwM z!KaZ{4ipg);^kp4WzxJ%R~KZWn<{4P;^l7x25;gZ6`ZcSA6=r*(9r9l#`8_08Z7U) zTxDG=U2d5j*Od)E^f+b43nf9WG}rTcjl0aJR~r@jH!GxbVaHNyFQ{Tu!zU&>X zhCF49wf2B{*AZK@dn%myo=E4|&?WKUIEal@$%^(@r_PT%;qxmPvVrLiVL?lJ3C{5v zD_#0ly9wF8yRWxXD+~N;sx~@!PDUQbnsEvAlvAP-vuDVrY_e~1U-cZ?4M8<_j9@8X zOmvR#&{;eC2P1}mS2dOnt1_&Y?Ib4lT>?=RJoMK?Q}^oLARU`Wm@&~sobehKV4oJO zFBqg*pJdc{EY>*&`J|An(BLf(we7*3{Lfi5mu!A1?v zp<3;NIOk~F>Q+vHXbW@3g~f+VY~M)=<9z*lv(Z5y?yf13x|rbS0Sz zW`(Q9-$?r2OYSm1s+BodoE&%3bvS+#+Og1fGfS1DC!uB0wh$*+2x*1kza_&WNf3ec zloGm3j*etAOpTzL?avu9-{a_Ud_bBS`%VMK{9t{@iMYx9Gh~mnhw7VLn1l|oj;Unr zhBAHtJl%G$tqx&N#v<;WH_FRaAOtfsb^fNg)Y{C<8{$~o@^5jc#m&Y9z;|C0nDY={ zpcrQpE{1kPH zz#zF|iB*dI7ekXr{Yw|LVLa(vY-zbBjXU`fr;zDQ&W)0}rKI@&#b;hDX)$vt}QvG{pVTuX=aL%gTNbPC`lP>h+VusPJsH_!ht za9=VJihLPy7Q4Rl?+@Lc!r2or1E*a0fFG&xvtk*-Mm=zJ+Cu7!5!)zhsZdXxp;1K! zEXNmS#&y6$(MPON>O zVZ6_n1*ErLGq#GSJ}Q$1p6L1c-S`yRP>UUow~h33o8@M$J5TPh7g6IL$ey*N4^-;khN2o?Sj^;pI4VUCFbT<+z+07uAXLd z{)8@!-px(Y5%c5iJV<2@<*v)7gsSC&sLO`12#!U#$Nw}1h`7Q9 z;ESRR4vtW&-QQz2-cNtUz1aGNdq8li*=c{QRUAiDVfZBw5^KngRLqQM^QusVcKv=H z)7j~*R<@Aiwq=!zn&kk-8=L_LkEMjR!j3Ih*lwR>dhf~_hOr??O6T1*NvI&myY zJ}r-`DQ+dv8xP12AgoObp8_zU>Uqgt$JTYD8pc0!6_?kJawQej<}gdFkB|KUVEbTr znErUntS%!DVAPTI&;?I@``*qXM`iw?Z14B#fb-YRC{MCg)H7c^brxJvQZjKNbr+@> zLS*H63Pr{`(}?jRf+07O04C7{;C0PCJ!x?4?_cdlv%XbZV}I;RzRmnyyd>wI%&n&e zbnY%YopjAw#@Km1oOCrQW>jxvv~$0D!@YqrmU1x^2vrNY07JP@V5B82$;K5L;+YT~ zJraPap@9GR));L0sqw$S>LQnt*wRuCu$ETknc#C> zUl>)VO=0>M{!4~FGc4UJS}?V!C9vgr@zJ57TeIpng~xqETtTk#6#u#=RZxvc_jBKKw|226h#A6>RoN5&n|$HSl9JsH!AZlc51!2Mojo}j zEV#`{X=vL$HPN0++26@k8=N@OQoz8(x_6)#x=%5ydsh|^|ckCI>S6=i#V z%Psy)@H-M|KuG$vpayqp@`AiK&+RMnrmp~EZu8c~lX$zMPbdD9%`W(kO99sEyO|B# z)V$!FCh_ozUrfYBOHh}~ikM!r-}g`xXlnyKJUz7(7819(B@0|95&AsjzbSijDu3TU zx^nG*T0QKTpRLnKYV7~`meuxMyhi^PTkbPB`c#o*awAHAQ1e^^(MB~VH$431p4$h$ zV?IQtlyIS9`Eq!xG&@1x%4W5PkN?Ldr0n@xBv-j4)t(5Mu;31B+P3)Iv#HeeLWl=q z8WI8Mx?tgi9o^n07tu8bJBQW9!^5NhXidYQ;QuMYX|e2-icxb0A1htC;ko@=+<#agdanj^TjobO=rz@$??(x~Ko9UL6cA zr8&pNm*eZ%&zCnd!N`Xm|_MI_%U4Q4G~<#AEZf5FBE;Fw%2 z_pY)N)u2XBm6Fk&9Ki1X6z-%zU)BY;MH~>QLVQubc5C^8w>to+vn#@c!=@wIpQzkm zq9?|iRS@#eUEg2z8{j}3y7ptmkEfBl)f9^m2+|X!Zy+G!pHYUPb{E+Bml)h1?Zpr|KmHLv{5MC@NW5I!b>(LS5gzyl_v8%>Wl-5KkU9kHwbsE9!=}B!5{32yU1psK@OBt7wdi9P9Bu05jxFKZQWzk}5cje8846Yo#Jy^_cr#HW(Fu3bK0GXokMaULZ!w&e!tRUHp;YBP0=4i|z>zjpFd{>wpdw*VV$+SDqZ-XS z`~e{08DQp~GA6^-X4G21`}`zAwjHVz&iBSrL4rj8mLt1zf<`&gLl@i3d>Ca?YUiS4f8Y` z0FdckMe>X0EVX$TMur3P{DWy9g?jb_;yw-_YRcprOJsOaX=5rp%Wb|1<%J|EhdE&@AY@(N~o1jhyzSxb*cxk`uqn#ad=8TX>YOaBtSL(V8jKCT51 z(HyS09G2O4W-eu*t)q$5T}#~z1{)sM{so^i6H?sAAJ&8;#K1wSE(cV+^N9d&yxJc9 zmLPdq*MYyAK}AsUG(8Kj>q<#0a~rCXpo|C^XitWQ1~_)l^5X}4E33FcJ#w-GjVclM z@4bj$4%}dAB${#@YN~}5)tEYfnFKEnR#Ku@r+eJ1@?5{S}=N{4t0;F;374Dbi)U(8U< z!srgb@olo>{h&K(htH-gZVjx(WJ)2#9r-YFt`wa@N)0^Q6U0WVbEt7R!3`2%6q<{o z!{dx3tL+?&F~UKA^`@HhEGJ9QB1zF~IFe)+{nPihqcoh{{c~N#jGhtv+{wFDu=b$O zmW@5jA@Fp<=;o{nSqX2p4o!CV5`?Ir260Sb#4<%T1BiT0yHw8OmHEv1V`^+Vncx}( zDH3WGaxx>r!qmkEdhg7lE8!iGzV1qge^L_sLLc!r3I{nRqArh! zc_+A{{pbBbRK=?(Il)1T;VdTZ9rVA9_yfW5ughzewE66Fp7w>xyaYL0)B+~wWUGj& zSp>!(mbjKigz2j%-SLuc6Zkt*zZwb}Lr>E^ig>6GN+yZ9UkL1bY&G(Z4A8gv{M<>- ztcQnxCdO#Hq*^>Fz>gt?IB%rjSd)tl7@~+eQ5_Ot3ZiD}b$_ywV(CaG2mDh|M23uA zE+nA{*-&k973EB8u*;PtrGw6JS4@7A1Jyiuj(`O&BTfS*z-KNYXku`|HZ?KjZI$j(!C2e16ZDd zjwGTVND^iwsjC^1NxrQJW+{!bP5zR+?)k?G81L^IJWb2Id1H&*+;bzUkoR4vty|Oo zHM?ye^MbzQK}5?f?`L*+2I5p&&SeQvcWyxIy_?A!$pALyfZx4=fn7{-S29ZBXS!Z6 zCEMoO)Y7x|IrIr70Duhs+5Kj5i+l64z6xbGSdb3%bqYe>!!Z7Ornq`I^wHJv)hgn~G{|=mPZh483+Cclj z(&i!+bm_Za;8=O?s;dPD#eU{NoB>yIZ5-E1)<!aLzo$AbQ5#tuq(M*KO&C5D@|8@BuzQEn!ACo4| z`d+NJB#MEUuZX;#YCgVwD*x-s`~b0krStBy0~4;ATOTMaS{0t-crfK^vkmw1 zvZ|21TCV=@gBj-8_Xm_epncG9Ga7pvEW=R}Ule)65i>?<$vL87Uq+16{Kp1u0bA`vCeK zRRU0$J=`u^u(`RZ1wbFQDBm6#+8Cz^TWzfZB5VGHzUM;WxP$T(IZ zEia+;ypZD(_I-a(E)rN7e~zBwm>vMqy8LZ*Av}NzzJpj#Z6^{0MSc zUN9>P^duI^3yE%w|AVCeB8!ey7iq33KLUrH!Yb{l{V=aoQ}Tx(i>zcoiXE}~9v?93 zFOirJ@4{?)ih)J@tz|>&!=PFiHdRmR%dMN%B*G82cmS~6Mgku(9>8}uo#_k4dRZnB zltBso?p+29xC807-EI7rU^Nv&^7p}{7}h}qXy+Cu?_GRoVSUHHa&Rk1n^kebwRM*= z?KZ57JsDs#*k5B*uJJUfG5Ebv?WP)V;uNt`Yu|Nf6TmB<@m*h`P==0zzOsS-o8_*u z_aRtAH&&|4LCBXvQ=*{EjEW!hQ~eIg^x(2m;b6ziYl9XR4h$^dV08(;eCU#BuI>=4 z$?=T;`RuW25jH+ag>Pfe>(DLK_A1v@u+BL-Rk&$Ksf{8L5*ao@$fa0WJ)V=yi2~5;dMF`Jc3emGMY|YErk~MG3QF>PTzc z%0>4s17hrd9(nsj5JIr?R{a4pD>-S< zKYRP%7YAtj^d?Mg2DcGtJ9!Vr&r}o2E`PD5GOT z-TL&J8TLUwBNv%78IH4T9t*CYu=wiRUo3F5SWC_?wA(l&XYj>H)JFAFR*Rbc`t}7v z-ks_tA1e?6YaV!sBf?l*(AI1P-Z#%}D^UQ4!ie}IqAE)=ZzsznOz^(p@kc&O2^ilq z)D%9IZ`P4{f~D*>#;Wdf6Ortx4gPtwi=}uP^cE7`Qm29b5z@DO&IJ&FjwAfWSVBGu zLsEV4y}LWi>1H&5N_HMESOlK!UR$EFG#(J??>e;pv~2{x(dMg4Bw8p#U-k%<=SnXP zecxN~yVd=N$kx06er6nLS-`!)@>yX~6|H%JhgdmPGz+853Alw#hR4FPKCCr~ym4uk z58hku5yy9jmHX+bw>9A8S#sEFEILNkVJj!cJbNhlkCgPCIT>*tWkF}2zeK3yiRadv z2Ph1tc}-8bqa0Yb;vapQ<8f$t`+7)Ef|#gJSah1MJ$o38k!oC%DB#ZgE)Rt?yya{5 z=TdG^(?vFnhnS6$=!He^{Z=v^N4(rHTRdsCS}(!>;PBwT_=&8oDl^xFV$@7Z*F7^f z;ew940v72KQoS(j9W)V5ZS}8TOo|%V+egGXNKEO35s(j|FL?FhjTuKO*&4F2P9jUc zUj{r#Q4+dkDAaX@Nu3p=r$y+btC%LrA5}--Taz6LCCV$eottp#jgup8l~z_&C{+Q_ zBOqHWgcUcDF<(w_9)ekIM=4#v_OEe44k{uFIOXc^y@^T7{=`!V@E3;KLeoP-xU=-{*jML9SMYQC>tUS ze*ey5vz@we6$eaHLr4~?3~lr>sBd)$w^je&-?w;Ac;< zI4~>1@jo}Mm*6}x;7d(F_aX2N-=W7)iIuk|<7(-7^Z7a>SlL)j1vo@I6xo)*fs?O6}Mhz8gg;L^lR7ZciUFacUh;`(VS_G zkKM@o&$phMIah-hc7m@Hhy;jJi9LsuZ45$F0!R6=?LbBPE8pU?t2Yymm)B1L?}Z29 z#as-`_ywsptr%gmMU%pva6tOQV!T9i;3?rMxEex#wb7c^+1XiHR`xH8$B#^uL)I`3 zX#|nN^>eQvCf&zrRD-nL7B}_rfg%Y1uVBZ|K&y<)zpTuWgZQFutQ0m`GPRW7$e9LB z1**9+|FA{zH}?4H41SXYjxN@CX&&U|O1P0B0qTO1ifM5aBi_|Cxzy`mYV9ffS_5t` zmxW7~t#_yO;j;uTF?fV`r2lQphru3t6eN+H9*x*rNqBIHF$oK!)bNXuj35#)asV1r zzx@OX&#RDk>+odHBLwsF;qH|E+e9f7M+Tg5XmlTPmsWPpn(o0tke?ka9Uecp@;Mz8 z8|=po9^P3L$WUzMCZJYLN=V3l<2eI8<0k~52}6gjc$M3pl6yL9w3@mLc@)CEo|dji z-`nU3zRPT!1^9G=oOw<7WF;F@$|QBtY5ztX#9jDaJE+{^n|WYew*c`34<9we)O%I5 zi!Z`PUTRZg>#?R-1%APp4sjNOW*peH7*S;Uy_2GFCtaiGa2*Lw!mNNRUjKfeXy z>_6jsaSuXIf{A$`^B zIF0IfN0ihQ6*NRc;4U|c2{oqX_WLy_?JIu$nq}&>M|y*|P7f~&TP7m(RuO<}9q>YU zNAlz`6aa{g9OH?<1-4+}QF&VhA<4D&qor}Wj-;N`Ry>B}hVM8!-3=<1el8Z>&;5sd zjYlw`HaSH(Nf0%z6oVEu_M)RF$*m{KlAbAJW;g!q5HUm zbl+`(+;Ba2_w5C-KK$qP8pEISSUYxMbx`A?tWhuQTz(LQv zs8YAG8a|~>0nbnic1Cy+hSnJgWi6p5aQ;dSSg@su1rbs>Q`3ghoLbo8Ix>G5x}8Ii zalG*w8B7ic!OrgUUZ!&Tx-0_e;LfkQmsSM$AT;-}+LpYzZndU~qhcPz)|N?FYv&b# zL%_3cB5ZO7Ux2;q*e;ulIQ5wTcey6(o&MWDSxO;vif<#K5R*sJO2P196W9nNw-n)? zO9z>s9jUD$0LiS~Bax)>|lbn~uav9D4c1~`&0yM)zoZxYU}&1jUp zRI63V!BjZRHga|`*}WS^9_n)wa9L9Gisp;GAzAAKk3) zK}YL35<4d`_MMY+qwx24Q>A~^`K-k9ldD=y(_r>SPWpm1LmY;Uk54uYE$x6gMD}o- zdvuHwl`JIN3E|avB$i?H$-P0Gc#kCDKU{+G@JZL>MP+f>$osCQx3{;nWqEJ>D^_?H z!>sQFtjp~6xG*b8Yg?Nv!1r<&^|;E>H|wK`?c9Rp2z-ehs3qYf;3z!eL|H^#p5B)}eS zL$_s(6(1+5__vhb8%O(j->vFYg0mZtqB3Li79bt_)MuAQK5F%v4uTRou(+^BqP6o& zE6M(JFrN(-VXz?^E|~@K4lSL0S_IswM5ap73R$Sy3l-+lZNJXEr5!tr{=%(wT?11K z6wdAkL+S2MwKS`#({bosIAjS_xd;e1-t&%wg~k0y;RwZzZ-T>e#6-p}=)bu+^V!!p z<%dk89&qAtv-tSe;-=VWvNpfx1#(7 z?&ubp7M>r^q*Zu=7jfE2P;?U|8^H2ub73GG3~A3LAxT!QpvUb>{~}H5l30X=%}c$d8#YVt=AxOGbg7c0z$&z-i@=n;wjZSJ);SQ zcjL<8(HG_INNd~~7qPgb5|OJ`F5L#FZeeIgv(I-jz1G8$v8DIjtM6mBacbS3fASZ^ zN?_bJKQ1#miFjTA+9gFr9H1XIJzo;)##*+z(E=XNly>)L0KD#0DPU9Gbt3m6Ze!U> zX&#_WVOkw38@J4e0Y%l)-;&sY;uM9AgwNzJIzSwO48O41E!v>Q7uXV~ ze7X7fGz&k^DWo>!gixRGC(f`sqMFkhkx&G}%5rVe4va{AR5F2T96MShIv!hY!+^O> zIxKY1K61(h_OY!LCX_$vQ7;JDHpT1tSsUoIOLVT~Z!LoEXDwnG#$x)yEha#=fu0lw zETlX~IT9T~v{j&My@MT0hKj_Y`^>u^q(I6xygt;MWWe&A{^MZ8lzq2np<9S&sai z32PGh6pav^Gt@0;Bp3fmpC3Hkbl@;*9hG& z*#!l&_z2KFGn|xZCkUI_yk6xgkLT9^>3&U>Z;cX$eY&z~{L&fpo?TwyqpOifK~rb?$d$iJwqB&BtYfZpv9b&i?~hp*DozfBWr zFU`s6M@#*@DS*nbV86mu!fi6%6rve%1{sfG8_^CUj;|5|@3(AEzmypffD5zy%*oWa zQwhoV=Z4DfOf75g)+S52+7?h`AkV+OJP{vcd{y`*7c4br@IMliRdkpf( z-`7x(i4n>ypfbQ6%kd|lb3709&qU1qkYMI*=wnk{ zRe7k>AP8z+NYJM$N91Om=RGC6reG-chlP1tvc4cZ&obR0|HtnpDQvP4;(sl|id~Oi zDfQa%4e^WZJ`?>rBR*oCgZaNb;mC>7)p3w}=0{<~6|uMsYWn!=?Jws6SaW285lozB zCGtv>6ilm5(d+BR4lw9@xA!5$+ma-x6dE~cSU(UUt+Bql%U`#+p}ySgM>{e=iY5Ck zLD=eg%8 zSsO_TE^eF3ncMvY>~#2f=tfbz%!`|BvDFn^b8nSt?VDtG=7GnQ$4jzG96r%CB>DWr zIF}ln4QMu4OXbzo`i1ihK`Sks;f1L zzT~QZf}h(;@#vJOlY}oqPd((O4qm6^l9_7i4pV1)54ARTWNAk`ucPXzuBMY3YTE=g zH|?aRhAu%ncI>6L&J#QaT4;D+F#S{#FeXZ=7ZoZtJ4{9cJ^b+dc%4>Hwbf13R98=3 z9lg}n+?g|8FqXO+qj_V?L<>CM1u7gMj(O6ZH%|hy3l^5~Ow70AESsheRuGtj;Q$Lh zT~looQI18}tpMbsX-^GBV`~$&hV?PBIYc87zDI5)k55W#`qx>p zlpFBg)9H9|h2O?PV)Jf12hQI}tb6(|u8(^|QaC>94GS$f%@-Ca>y`cshA;3M8Mqhj z31E`JV#|kq!~GBE*0}Y;JE5HLeDnb*_R*)HB*((a#0vlzSzvI1G9CR4sSwbo3ZdAW z#N$bdL=wC>(g{TeB0y{wE%kO;xxe#bj|-x2!GM8~c^F=r`1!He!(Ti{slfOs*PsH0 z0>+(4Eu|<}=zU}*8pfOQnybNj8C1}=v-5G$UjQs{YpZ$D%JnPvCnd%vA|frCjFlTy ziuH_KY=l7tXm7Cy_0ItFT>#GkMepn9{i2^f_qdZD+HWSa>w%o~U#CwV6Y0L>XceUY zf^kL03m^Ykdg1AZ)%0K66j0QSFWe%Jr&@e(sE<=yOLp!NV>s>MUMT%nAzXYbmk(@p zfS*44gq<21D!Y;qJad)lzm@`I49Q_CB^GlgUc}|^`37FqmXAz@T;yX@qwImK%$UYAe5 zA);EIIaMXnAxp@8=8?qjklm4+E;131)5Q3wsIy{luv~ht|2F;gSN=SGM1q?BOT~79 z#cHExKl(`ug`{~4^Gb7TEA#AJ9%GCA85t7S)87E>VU(gj`RXW51(z5^D?onwFBy@T zj>0U8I&6tW^5kj(o{M<}JjdxY(9Uj~Sicqn3@Veewfwij4^jj(GczT z`}b5WITxS5v>@gw$lRC{v1XUkfT`)fDueau1?!B;4r>*w0Ssk@Fg06PVJ{2F)on$gW$qJ7*gAnME z`!En(PI0<@QGUyoiqfvEOb3TaMOJ`g@q?5VufOe~OV@oO2c^TVlf0nHFz~{FA}^Mp zByZqF)cYT;p+_IArbixdi^U`+U@Y2Jl9nqNPEjHW1C8|j7L%6zEC4`pg+6Vu=tZb1 zlvhp%HXoPRJI0ipR-zQF#Grz_qj)bU6C?uz-Fmg5qnnf`G#WoHpR_GCL=2 zGz^8J>|_IgS1AoDFrJ_sqJEY00(eOw!hDlYWILHIrD7#e)@7l{YE3Fmv9Om?$y}a} z?>N2^Jo3mR)ZX4+GX4JV|33Za|NNin3tuR1+}Utoyp%X*AfG`#^|MUnbm}*)K?UgO z=*Xl4gB*L|vZtug6WF)gp{4;V12Fo)I0vH~`UTb}BV%EfJ40fVcF2^F>`YPNO4y&Jbwhhs)_F-zRyUlc~C^;?nX?}i?*8sEP*(yOw zfDgqYQxpkJ@VZ2Dtnl($J{}8^Z|-gK&YmY7vnoVIN$Y^Zb+Hr>siV_Gn7@St8FfBE zp};IHc*baEdU=JT3Kd%!n&ce!{V6#ywYTU%Sx-?BjT=#}dW>2HOxtH&;6 z4CsuY-$?j)dMW!N<7zhtFSrP6<`56Tb>w~P!~*$0*L_yJg?Aq*N&9>>CQ9A^=7aZ1(Q+MTD2R+hwE>l%F9Ms&rh= zAf>W^F{YarHvvA5y*9wSp|FPMKL~(QTVm=Op&*dbh)Jn3f*~lu5rLr<%2Y&u;F_q1 zjr7i2_w-+kOgKJMvG!ITUkl)Uvtj~#LfuM$MXASGEioT4b#1$a6PDkiRTL`dOx zDB3Yr1wY_>$!)O`;Qs4jP(eLopBmH+lnM9_1Du=!5Op8n_d*1cJiZY@B;Oajp>0R5 zM|ODzm8E&cMjKRIPJ?(t+0zqIdNB6kV0XKT>Z_R_Xn4UKiO|I8Wttj(g?#hxQnhoQ z4(+ipqfC*5d3bfLAw%_bdOEs?Xh+pBY46?;*WGBS>Axxqqyai`AWk=KOW%`;7}eFL zGGj>QWk4zEzc4;0M$3~SwgNgjjbyLzo)qBsN?u+t{TJi~=G~}QSuwgCzz?ASMCvdY z(h-Ra-apGS5axRvM@k^2K?UcZy|5r6jInSYn+OY;4bCWt@+?GkPA$3YS}`BWmNaDV|yfT&k*y?Lg~K-2M6i5e(SgB;~)PxJ^AF5bnxIox^(H1NLwTm@`{g-kJBeU z@d?_qXOD<-`Mux!JrPw>X+XhR<DxzwaHRAcWHsnU-yfw40!(45*}DtFHqLbc_Nfb zO8pITfRMYnz4Th_lNqJE10i9w_wjkR?goT|Tt3~u@m;!g>92FB|H?OM{Qi$=V(=$4 zcK@d|KJcobk$bNT8oc`k4UL|q`~Bk-&I^=P(|@VhE{H`I$UF62nizVG#s^=e$)Q*1 z_T_K#82LsHUA=a1(YU&L%TH&S2LzZ$f;YjT6Z#a4W#}91X01pYRfxc53fb5Z5rMKj z?N*_W0R>nl4F!3=WIjAIkNt`hB0X58rb0M}!Z-o`jP)#>8x*W{5s>mLkzD`r555EW zDU5I(1u!4L85mBrg#ft(d=v8=<`3xKz-L9;cs2c3MNpxxxOq@uY^rz<0D>@>AB-P< z7JMKm3r|L77zkemus@CkklE^l>$+ZLM%O2yG>7j=x@;@4?Rf#{Ga>|{nl^%ZTjV3_&Ivy^dsW< zO7Ta3^haVpE#N==hyOsQPoEZs6Pc!`r^Oyy$BrG#oFkvVDIhbjvVh2C$OKo0{^k^8{;9&svTvL$?7*v$9IX=T_4@R9QPS?;Q z4_4Eu<1RX|$03}OWTTB-r}=<0;MIGfk_hK+X23ZNj!clf@xGA9LDT&G(lwtT$eUPq zd6QZi@+2xov*FD-$Er|KNnoS;p?U7}E1+BBQPNrsRO2$zsbke5i_3|_E;_i^Nec@x zdT^hEKKyu1hK?QhAe}h$Je@xIX?phQzb$Bg&na?}B|}vjE4j5+iq7dNIAx+k`#(#M zp8h;N`_!k&ZO)%)%bs`(0_%Dh9N+}oyaNW6;$t71(#PV(=jycvqE(Q7Fdvt%dzn`j z-;)}f)+05%tapLzp`vowc*(4SSl_9yjJs`_IeBXe4=|J<6c}DTNXNCKUN08p07Cen zlz|}w%9`VcT;e#GW|H*M-(*TKQg{Q&Ge^^@RA%}ERo%AdSiS!5KD^}ER3sj(cp^ea9DHf z(S}7b7QgX?WK2QY6QLMPKL?C$tAXSVq7mt|kjEQ~FFAZwMq|Bkkzr+Oy09`1UM0#j z4y71W0F=OD28*0n9A3^EzP>bm(D!jqoD+#^C=`*#p^Vk&2G+}<0?5V>2q0L@K6=V6 zqS&AqJi6aO9j(|;M8kEMC|F1NK%K12prWX}G&Z9_MFtkS*iUJAEG#@B{V{D(3a9h- zE790srg2Y-ZV#(UnC*;0{0Ih>+z3HkB|hQq=j z3vb;*DF-(Luwgy+&;v~NUDVR`6lsl3!fBzo(X7aMFU>peUh|3h=CM=N)Y)#Kwib){ zjEEMzcd>WG(Lev@6#eo4naI$OU;482ql&T-VHxF*zdD|ww=ZF1a_KiXaMahCc;3yr zYa z_I8%>BzX(U97OyV1B|NSi1fZt>L6Qy3JLiJ6-2gxf9~tE)4@GRYpr2fH^j1gL^$!l z@P-tL0325e0rFNM146NkWs%7#1 zXcx=n1?XUBJss|8%BAim+S}fep}y9x9O`Z9qQ<6u)VQNJ{WL06Y(F3Z;o!~#+~+%a z95f3$+}*fnyd3Fq)6s4oPYSBiCaJwfPhA~$5sf%G6{PWr06AV_x4k3Qx`dm<_sCMCekF0G(MK3>8ThQEIX;8X)m?3^rW9S zAIizN5G@VJq0j?De}kynswJYrLlF~&qvh)nWMKZS#2gI63LH-Ifw@?z%TWRmm2lp` zTnxaeV>7NHwkp*0UnmsrW3pDH#1Yq2up5P?yY z(j^kKJFz)7r$ck9>Axxmgt5D8gLLPf)GzdUY*eoiV+>fzpaMQs2-mM}9>Zd#kkBx{ z;m(J-S)^59o-d5nd@Mf-u2g`hDfzlc|Hb1I*OZS-@}jrTbc^L1L_C{VKg^V z|A9Zq^ZQD%)zg11cy%;5oD@cAL%L}pKSHjvTJ)kX;kt2VyBaO_IO4v=Yd4(l<#)HS z+>GC=6zN{%HC?r9<<14|4Nw~LTvH@@>(tk*=|s`vBUz9727`^#W%{W%@73 zkI@*`7B=oT*z*z_{F_*wHZapV!&JNDNDkFEAEAz}2l(D*x_RwN`iUf{>AzHL7g%jBdg#n&sH$!s zRW}|JV`0y+7pQ&LQ#s?MuYHbobp)xmlgCt=9y(D?`}!O-GM#pS(dfx!HZpJ0QX{XI z5AJ2gb!`Ellh#vF>rqGYk!Y3II&C0QZmC%fq~%>|Rp z|D-gs3K3!n;H2UN2kPm$D6gk=Lg#0*7M}~J=4;cRN&{q_0MESvKNHWnp%C;RS%OR> z&!tLvs1$$)Ei5c>y=Eso@KLk_cw`|!K7l?;*0sYxT}3f9{Z|E0o&>dtk?l_Ffimv4 zz7MtvY?%iw2q=?ls!c+`hR3)Jb8Axy&qNC}jyNek2&@TIZ9 z1R0Il`^bt@5x$>RX3Kye4ut@egb;vLtQR(}Ph%m51s^|82};nOGRJcx={4px)US^%T9Kyl#Bh|U|3A<7+V0=9#~Mmb$&q@Tk#!>V0qD6 zDk@@7Sp|f^!d)vC)9^x1QZ_;m!e1yOA=A5c*tgsP?3SULR}zr8u}0n zZ1}8Hc;v&VO_5obqK+LbR5QN>Z$(|I*uKzlo6Eo)DferjP8a(t-8-gS)sMGi0RRHZ#GX zB10()w6wGcLx{X_c{wQNr3ppaqEL8A-m!wxV+zNDp%Be`Jc6L$DF@g%S55T3lS@ltVts32m4P!*2D(U zm8jG2pIs=6?o7r>4m`qMEa2tk(sD4G8_8s;=Uyv~0~nNadOKO2yUF3&DV$v3*dsem zs!*X~{UIDbnO7Nk7-EmMa&X|tBh=E?OVzbabn^5E$!c?o&p4(;XPZ^XhM+QS5Cs9= z30WGv6UJQV60?(i?hX8*;`4Mq;IJ^w^X~%B!x5f;6De#vAkDloVGo)p&$*t31)86q z7iG!;=H5bSzy^k4yeX`=5f1LW#*(60G{U(U!`q6>*bFH}d#A*r0c8wAnVP*8D3(qoQS4ofe4oXAq;MJZ0jW+? zV5fd?5S611nA-;>+AmdC^lw?npmlH!^&p&051@6+07 z;Cpe~*>yBJnr^!SWdyilExgz>@%JNpxLvu-RYYga#K^`%4>lz|zRyNZtCq&5kPa#= z1Q(<%!+r>|cV8*kD1%A}o9?sV1qDCyTqETgt_#9~aBLz%bMuH?Neb_4c&S1_gK#N( zp5Sw(B2_k{K_x#@1&jV^?gMydD8XU0M*Tqv03jC7pRO9wm#R%ksxl_U*g${&@RM%Z z-EJT&^NXRuARRONrIR-p{0eHMN(BKguIu+kDH4_xb8Z*$q9&D5s0**(Sen-`N-?Nx z$4HglohH&Sv$tB1?orQt5JnYv)JrKw!C%S+jGjs*IZ~^DUn!5TBvJ*Q#xS&lFTubL zBRZmdv9T}=_DY_QNI&ol@P)>DmOWy#6bTNn3=$Gv&q(iv2x64Wr$f7}^!NiV>T0uO zC{gp<>PGb|gqi2@Pd~2_8?<({+r-}~PcoAp2x*EaWv9V`>|Qo7sMOWf(e>-s#rLL` z#q)WgNEImW^CML@17u^5)2@*sRj#KaRhD>6c-o^_sgWv5OiV_(pKEDXk3D^4F{b9L zxSmRvlaLa`Y&HuIR$)jhGQ$t&jt(wB?n`w0>W>9|^BaFdXU~6|`mf(%=8)T0)kqZ;+Xb4W zkBqVJk!SK8d8f|O{NzO%yZ;Ie-+4KQMh9;!8dukD`{=trnx-k{RaoQ6yb76P-o5Ij z!+nlSH1$%ED%UUll)MXbG&eIrljDP=H%JE5P|#1EyG}~{EafLn{36{Rs+^2JI~Nsl zDy1}3UuPzlLZ2W3d{m-o&+<{wkRf1536*LfNzYX%7mY?J7LSQJwN(D?a5#kXgeob0r*aF&D>JtgqEa$sJyPjjcwiERAhpR9W1O))HmhZG9hX6aj_>WZQ2(H$_(hqgPrIqB*(|OX4aMlza6~YI-7Q9X_;?i` zHwe0QFGyPcp~_WGS_eW$rnzM)0m z01KU52xXpmyqek@jnrJL=SeS0GhV68iQQH@dB9FBbq1=oYw2=-P$=2ab{}~P_u*$_ zit++`(vuKn4t5*q34SL$LvJhJ=e}g5sj(#KqwlYg?!(uc=Sgd9E+LE{yIT$P*vTq! zyxy&&OE-f;(eL7SJ@bH*>&Gsx2V>WrQE6e?Tt)n@+}`3{Ey5daK9Caa@PUV`=;&TN zn}r;_Ah|yg=Q>SMXRU^QhTl~#Gr<#xm*+Sbrd-QQ~#zeRabHsMK%zJ0RKOs5Xn z`96A4=E`m9UB&yHacA!1WBxbegMlbrr(6#>-q&fSTU@7d{XFxii+Z@8alKeLF5VUG zaE$Ns=yB=U@cS)pZ?uD5m*DYGMQsfRYIO1B$z?`nrA?tbYlz>KpP`4Jf$9Emn1V5G zJ6@=u?b;d*;y$y}VX?0T6yLp#I(qtHmpFeUtJcHe&VZlrC27%DkqDV2e95ymS1xiII8L@E2UwB{xk!V5~XOW%=3qlAg z)m8lVJl2p-4F(t(jvyRW%BZq{GFbRV-1K&y6X8v+P1z`! z$bB!>sG?%KAQFqxgl~!_=7WMTCdOxZeB@D~aRq(Q)B@9Nl-I@)x;GRQMq$i>wahj4C4o*F?H60Doajk!jE2GZHUL`ROme`fVEGc?8!-WLl{yrHcW^A6(03 z)l*ZwIWv#s15qlG=+Y6RFl@lUkxUeyE0#kt!E0xhLolzFnvxST3nEjMzzwk$AP8>lSrE-^6M*%ZP>3vKHkXZ6vpDkLNUN=UcR1k zF#ttiC4t3;d>;s(G9Zx3$3YNIWk9IUl*tQiZmKtC%cK=0z*1$Pi~ukZDenUTT*jhy zNM8$tMTiV6Am!swm@1)cZ{_Eu+FRKU%HI~%kK!4W$8*Z?J(a&Hk@IYdHdgkl{4%+9 zn!Cs-)(%Q2>lcvE&o6_Nb*KkWeSS(h#j`5k75z#sqwH5oAXhW$Q3jqzE(21cSlcPf z;GLDQn6lSK9#sH_n5LTSb2e1#h2aRm0;<$h1siEl0dOrW^3eBT_)o-%Zr%;hagXI85U?`w42;m`*)R4;o<2B3O z7Xz(=DNIR-%x&9Yrrr(<^)fHSo+-*SQpz%jMsYiJDKgNW#b7Y&>GL0&r9S6Xva-B@R2NX-=cJ|D zAOc`~fMMlBPlo6hKb)(eC=W|if&xJv!x|n44cJ|~2>ij)(~TfP1%?zQ_U+v(NDt*N z-ZP&vK;uf02cT#)F7m*aiiU=U^e1T#zG46$M_r6rRImOwVRzI>?+m znoJ_q74(UaKe6U|;HZn9dc00h9oHv}(ej>&G7#+oPvn)R151&P+-@tG%!~V`#bTr? zmzB)?Hy_G1Wu*XP7t#>pJzF`;m==MptI*a!no8`ucvyeW*O2dD0_Tz z&`;s{Fzx1bLtAYlHM;i-XST+ACt0nFH-uK9V!Hs2$IUJq)!TS1tblg%m}zb_3%wGY zaKHzU4qvH1kdcT7C?4}M`N`*-r+Lp5kLPKM#N!##>R8^;>jW9iW{QLtC>fs>R7t=Y z3mGOb=YfALW#spV3P)fnF*`Sx{v-qZFil|Mc_h!b`2@a=y~cF960C=Re4psWJ4DxbIReLH6%v-7-M0W% zCN8WLW!!CjA8Zv^&j;Nim9oTR23b&5p+ZGzV6j0g0%bTHdeUjK15C>4ximJ~pdtf? zA{dn*cr`W{scnZv7?<#VFmScEn8iX?c-*m|f+!p;iv4Mi@6}?lK_$0NHXC3lL_M&4 zND&sg!clB`Ed7Q*NtV=Xh9o_F!X=C;OTk^mZOzgiA{f_;u<`1sm*~<2(eMJ%yRjbn zVe&D0BXyD{D62qHv3d-TEpHrj=0zmP5d1;0=MKi_b_DitON6db$ajnG4u*sh&2C#P z!rS!8Woc|YoZ-F8)mQe{;^(8D)u^hq0?-fI$(jrWH`V(*n=^qn8hEIKxR~R=YqQYag6xi+dj8bQ0JXBP+gL4uTMR2eH4_m3ye`^7}Q{taiYm)1! z@H;!~i^mRRJ{X8JlCJ@BMN55DjB=%b(g6Z-fs^Egq^FaF$9^tn&*c*>(sKi@=q zcRA?5ZijG;gDpS~viLvWouL2rXTyU2$6wr|i|79ry?f!0>7BFxo&L{X{SN)^aiB@4v|Pbi--$E zAMCvZwGlQ0Hl`KSw%;z;ECv-BFsw8;Nhyfrln%Hb{sJ%_ z#FJ1)q=dH)%SU3txmpxAs8rzMYXm5PXXawU%h2W22|}HW@gg4!) z5lv8@qHTFT^Y8;M5upb<{=ido{J~Gqu?IgxMr{>Uo19c<&Lx|nidvfYi}OGap4dfa zPFK@sKGH}ZI8&Rx>e2|rHS~>FygBsF^~vu*o?6Ks$Zr zlOLwf{_-zVYey%2>}NkgRn;~0i=X{Pal90mY$kf>0Md|#d0tBjV@s)|(WWw_*QZ2k z9+{NC6)L+F;W-@Em@uf657g1}V>LuSSvNGpig36R%RwpLU~+{nuk)d*!img zj7d$6CLwzxvQlhP?a+(QI0jNiL8?%pVq;KWYhwOp6Fdui#}`P@Y$#Qfus>x!z^d@u zq%T3QUh-vV%p+Z^P??n?5=jW>1|9QPWGX3!aCB*%f)sI^$jqBdlQh4|bFh-IH?;EH zL?R&^K1u;ne&$2$wN+$pKo*-wUW8*I9BCqYyp!meof18}OQPrcvh+v?&qKT%nea=7 zmh00J-IyVIdz9$*EYU(#E7sPSBIGr?lJJy>f|1wYJ%9gII`AJoIn?*B2BnAEq)<1i zFB#&aa8KAQD)QvYBTg+pUBG#L^DsjclX3a1Xzl&6j6JQ2Er zJS&@+Tk!ngrhw0u}Sd{7NlFH0@J7{tyPPgw*@F0}RxEr3~GM#jP ztd=6dak@7i5QDg*{XvS*5m9D(HbHlX#wpAU#lZ`KhSulBeFi7$Dd?Z#`}l-Xt+V|o z#dIgcZ=(|_x{oqE+U;DXZpZWF33buPR3ilg)6_q_z)X;+rExE%Ob>}N10y;bn;aoO z7EjEt8(LnVg-|z*&FtVhn4w#P9#KCn4ZWnbJW6w1W@ya7lhGJ01mmJibNfd{nTfd; z3h{kza~ZT;y}N~sRZr4fpqmEA9W*^NOmjSrpa^Vje~!G-T{N}OPJaI!mzfh2RgJTj z%&w<1WoBoGxjtfqj5}=|Pmw>iSCqjfTekk4xE-3wq#LHo{eJGR8ft6aM@i#D zqRjZTmWD@%L}(*6Z*S?8%1q3+QZhD5H}3nmPBq-#y<~Je&SiRNWYWyv;+$c5|I}kS;Yvmv7ArB}I+1jx6pEh%#f-R<6?lJ|`*qc6;XsD3sh!(_BWwWv<+o z%2aWk*6w&tlo{tTsn`hJ9!a-D>*IW%LtH0aqA%VWm>2Ef<}y_c&(d6wpKZ#;Cu1Y4gyvWrEW5URIRPaG809U%F%JLB^ zD|m?t1JCEKl9VO#dm&vBgw@&kxOhTo^VKl(_&D>VIPL2+(8UL9G((< z1T@d%*};OGu}B{R&qMe!%gqE89=}w?f)&+S~{@DA<~#;$eR6(y;5!sMajb z4oXpP&Ymig=V7r_hS=BZ$X=mCiv1??| zNU6=R9=MU-OKd5CEn=TGi63ahUrkESJbC%eL{%&X_M)>GXT)4D6PyIN=>;H<9y$B~ zJ@VK`>G(ru=;*QIw0GZrI&$sW>@lK#*auuwd)ygY*_mFDK=^ta+bGzs#qBl<*E?g&K=|6NSd z?*RTFE!uLBJZpX8vxV33HSWUiH8ms2MKCC#u8QTbUk;mZPZgZ2DX^zXc8?ITzmyJ9 zhL9VSqH z(`L*GG9gVJB8%`l9A)MgV&XWWuw#feN>_GMqd7AN;9haaUHr^4;TO42<^PU)!99RN zd#Ws*?owP?kc;_Dg5MYKkWZfZIr2_lBG1&j3c5u8xoZ^i+@SfX>oj=x9RIyShQuxM z&0e9wdl%{arPt}!wSHcI=X!msd#b3|E->m7qAfi>l*ctd8=dBc& zr)Qb4c5kT9uC?>w4cJ(&EI!udRGGPRXsMJnv=pL5BFQ|l@LZ|{=4kBak`Kry%8Vg0 z&^|~Zj;$4{C`wJK!l}X<(orhVoq>=dOb}O9J|TJ~%;G*jwjcm&aLA6>Q`ZP*7(P$_ zO$n^eac&j!a0B<3`Vamy(i$X3jjaNHwXKQVVYSvM<8JHwU|R-8laqX*dO>qucWyoD zc91_@PYc0X3Wl=_2$aEb(45zmJ}MzW)j4GnNvSLAbf$Ef263N+Vo{z*)rjLhCX|8l z6VT~Vra@6AJ1pcfpkUaXDFZ~4jpF#czb2=Q&QO;r6Hwd-h$frFaSxYK9w)6MQ)a=R z8)v616NzRg7^Asri89i&NoBIk*l5a@@dX{}qY|PC=|0|I9mV2V25eH4LH#6^iVo3s zi_7SA=4=@s$|&lTvUQqMMxR?o37w%f^P94d0RAxEwUIo5T<=z$5$z!ThPG2es?)_~ z#Ir@X3{(DnL>WGwUq;kvrcB-hpl>d}jINmieB8@pMOi;6gX17yFuRdAfM+XI27S9& z8N4fw;~DbXK`t}r%T-P#s5bMPvJ4PS?I==4x=*1p#jx2TR0;v!fe_}f_=5m&?vj@m zh7itRNQlvu8v)@_xKwJ7<**e}eu;YDA@$+One6ky!M2Lq3&Ink39y#~yq1viV`qod zPNnSUpoGh+rJ)5xok)a5d8sHM!>QOLfN@eria$b$QYx@V7xv^)QXzqTtE1j7&GCrt z`t2{YiKvbbJW)e^JvPB7WP0>e3ptuTkxPwPqO`GNy>Q^jBUD}6M9pozbn^5E#orw* zJ>qjQ;2p7-680`ziu&43^qFUCnd;JiYw3x{PN%P;qFi7P!Jm7sE<=wTv6Gz_xKJ2_ zEG8|>AttidbuUsT>WwyW9NwPt`5-Yr^561M+WDRBP^LpRAZlqUp$tyhB)kDU4txp@ z8pTj*>aXRZRFvrI>f-yBW>Ap{hVN3~bVA0IDtRfR5@ZHM^8%qz8I$;?MtL2};YiYv zgAw}p^IAIdh+-{R1lU&vvJ*C}hl2{XIx+HcaBw&zjL`W;%Y2{=6r9VEXCWq(m!soh z8k-0U!yk-I^6%Ii&+C)U!Dkp)0C=b?_iTih`rvRdhrGUQTMvzfa(*jk&d&~HnXqxF&8olj10vPi4|X~#^W&Jr*h`Zwjw^ zSAbNZV!L507*qhEFtSL`R9j;dN&*;Ge)7h=_`ARhPn%7f$^Bd|$}^~J3|~+hR7QCL zj zaFPC-7t^1J&c60t3I+Wl#lhUnc>3sK)VK^{V|#e;FGYL%?7|zq#%;)u(fxS(Dk@e2 zc;?G=c)yeO?y`%v06p<=HR%l+3I|4u()%B)$(#>rYB15rbc}8fN9f%3AiaGxunc9- zK^d8D42EfZHdj%9fy>xr&X9`8uh8H3Amxdo3 z5go-)suK$KrYRLry0~0bOBhsg(~-#MC6RA)89=Ec8{6__0VVLxvJxFp6e^YnjFsT; zFl@Z>&OE*T_8h(Z>I~h!7m$8SN9j}oxDRA*@Yq7pFK9oU16Zv(YHziQh{m-A#<)zy z0Z(dpMX!YPEJyklViXO<#b*pn3(v1ARJ<2p<~40;lsj$`2rq~y$ztIz49^1A=Wz-I z<03_^md8?lM1ztFLH^Cfd_^V)95j|FQ!cR1kTl=Ek)lt0fd zMTk}@1(<{L;q@0c$RJv@QgiUQpYIjn)i_@c>vUv!KonxNg~(|_if$=gB@8EpmUvj# z*IK2$T<~|~k3UWC{_BV7@*n-$BKyH+r3!V;^~L&%U}fBGeIHDP3Kc506}E~&MMgs% z!fK_>>yg(P-g*eNb-N7I)?z8R=Rql0S%k{^F8)NlFJVwo0zx4SDfkP>0u?+j%R$r^ z5k?Z^Zgp~#8~A!Gn-&NEhM!@>0pa#BmjAH^z}_mJ;(Pe1SWjTlf`&>H43;XE2U5&H zIg6ahGWq;b3VTK=naEW@Clk`~6heU%$gOF)5h{mJ&?gKiqeK1TyZl*cY*{(fezM*$ z#(qfi{l8I^3gPPg2)+2Gm%jhT0=@W_cNxMt3-t0iFI~7D%Fx@_gEXlys=&LH*RTZ< z1z+a6FQ4-*`dvxbXJ#z`g$@)eOL@oQ_vHX1M!6}7kb7OJ+>t2j zIg4?X|9c`?Vnj)rg}?*27?g^7)qq|)8tY9|?J{zoLG(~kq}9POq;1?Nz@W2SB%0f# z5!Bmkq?3E?f|{yynd5~Zp9k94X~~?sR2g7jw~c=Bg{Fe^Gtd8h`q-!cSq{DMiGM*6LdFbL>rGT+FjI}*NcNPA zP8@umj_!Y+&OG!K)mWD1H|0R2CFILtjw_a;Y`G2UVepXVNoDlOa)f({8w-->*wPl9vd z{D^hFCb~eu(JK_19gTLh~3RS9h8T2y<83Kbb_q2aLA3@S3PdA)1^fq@0y z(#R*PTxjBVJC9FUm2f6oM>lO-yZUsEGU=DmE4ldsY-hIf5zuR06eedO2x^*uo_9~L;r*DkX`FGx=cQ0O~i|5bh5RUr; z*}Tb>SWd}?(p*Rl0M9L?E|518Urge(G;$jaDI?&`z7!!XjdJe-K$jRxe^RkpOiV>+ zY%)S~^D#mF+}D;fgx}~7WX_ifsenq|L#$Mw{joO(_EiF5PlgQ8B`eXn*Bbnc#rC1k zNwd2ItX6CKQ|UmOuEmNQejLU3OeLnjV;q+PqhWbD2hmO$hE~Z)qQ_6Tsk6yMp3ui=|G~da zAOGZk6!gH}r>Iur%#hJ@8lA~&e_>1o#tD}irRkdU`XJrxOg}oNoGTW|4K65o}CUlw699g{ynu+U4N8n8jewQ-Co*%;7K}u zWY!6Ux-xJig`vGyyN<+-UMcCSMkt%Rh%Fdzr zl$}!xQu;qWb20JnAe;wTx+G+aNyLY8BT;Z9OS%dCyb4JvEj$yaMo0TL{vMiUykc-5aiqT;;_ z7zkt_%1Z_|ONZioDGYhF^wynt4sAzV9Z4*D&#U99MVq-#&G_jb{_gM7um9Sw(ocT$ zBK_C@|9=wn8-M5Th~x4e2CL;1*bAb!(@Nd#7Lg+A+drD4uYZ4r0?ZHM3tyu9SN;+G z)t~=uO6o>wCO$)B(b*gd&@_#XzDQsB(yt2oKi~Kfed+6yg8uaXOwgqpei|AL=TRhw zUVeR^zVfYU`qJ09T$+CR;vc1-P(`_j#FAWx6B+u!D|2E$EbNZ~x^*{5U-_G^KKB1>h6C`teqLFm4HVJd7etPqyDH1>mpGG#4* z6ks`uoec3~DT&`-D~?N48u(oCFVdH7hlO#e?_F8IWA}rP)zGhea>t6vQp5}S^idc8 z-n?RJsV~hzNQTv-6UtZFfEZ8c#eR?2=pAG-7?|`qluBU}e~IMtELNwu&QgfSlZ*I| zOhL~znx8nAOOxj*;=4)7&{Yb|Un1|!yW+DZcAqFZL?id#q?*k;lmS99ozgTr{p0ym2y{v^)IFZH>iZ%qT(>N!Y2%&cD_5aocKzCzMtjCSNGYLcg0DYTL=oWpG?KQg+P+~nwx6f zO=M4(!F>$6AO)iqa^gOSTPuEJDUgDp2#!xM(-45>bOo(2G3^H`?*eaqD-}u+rgP_heX0p zNsW`+fy;26X4}C_^M0);BibQd2JL|Bc|#DQxlSAQWXkBd9elwQKZBd^Q%_D;SLQx? zjfVo!Dz4KSZtrZ{iD&bt$Y81weXg3{6~|FOR?`Aad*FS6cIYO(!6AOrao-7q_`S^B z2HbY;>Yd`aXa}yJSs%)9U2~n9^7{HD$^q6A`XgKP5EM`!w+T z$Yrc156yTCqKuo{yULwy2a~~1^8s!Leztl=JD}d?eR@#`qVB3|NvCsDAm|X^Wol}u zryBlE<|RS?UC-^UJjY_LrfAGr7I}R}767$O8lilg^TaDc#hgeA8C2#MAc!tj{8lbP zW$gs0N*GjRz_6m>ae?#^vZvEhn3;>w{qs{)txt$Nz6PC!c{1L$xMYA|;0+If4|!ZO zPSz}-;yZHlV!xGQKwelMH^W@YMU$zz^idU+1bBT)=V3WeYKWR@;_**H5epA=8CXE& z14frZi?)f8wNc`3B&zFlJZGe}QcEDj^3&LuR3|MhE#hx?cQ;+XeqDTaRvRf8i}GA! zAiWOr3}vDSUx$+HqD7V17r1OxzXGepHjMgqP+uF$Eo23M?_ zi_rav2#xcY^+q&etmh+=(9lAd$5%8d2%lv_nYf}1_#vJN3r*$XQoe?g{9yyngpfT| zl#dj7qBEJgg!iE`ny65H=Tn%^sRYp0NTn$Q>As3?c#B(>cw4M7mAnMerMOR)jG50^ zuaq*!N#}BX@$*6H3vYQSo0bBM#pu&5Jf9+sQ$7%>5(qEebT%I*lS!oWDhGJ4iHQj@ zmX;)Owp6)Vt+u2zV}8G%A`$Ry4ejbK{QOw+&(6nq4WZ|2ayvU$mc9yn3;YYPS#?6O z2Y^p0Wio!1Oq;{_rZn>5{#EJwqfL~KJ3zHtO5qxdrGyuDG3c2`%KM7o`pO78lSwC@ z55T)Cop9XTchJ{8-dN^c02oye;ep@rj4PoFSG?rU>xQU{J)Kr+sy7uZQwrU>H2Ly&H4+EOL)s)zU41ScW%E!w{E_bL;bhjrlG;hG;sea{qV{m}Q=wurA`)Jp@v+xwaPT?}4_y&s z;`Yt6i^j{9n=^~X)wMeTvO5hFVBQJdhrLw5E5U<<{CRh$P2zt%d{U%ixez)I@ZKyB zn4KD8d6cNJsa=f!14kZVp38D-RgIw5uEP=!NcpM3#m_h$Hc9Gdz0c|7}u;MTd%(U-q>Lnvq9g$6-yPp@4FsD-e;4_e0EHmnA7 z(X!(?UhM8je_LB%@T*XvLd90X$jFEgfV}=u8e#!*Em6#%GCN;*Vcydr32jkcykkCG zJt{jfRnnj$!(~j6MW3QGr`^=nT->?=gUYvFnxSt0EOncsBCUnh03i)w(Z!!b2xTnj zA8^Wqw5pH>4r8@wQ8kM}t9Ml-iDQY;FkyD>>Eb?|J?%A*SbGu<2O zNPkmN4m6qs9qzrG{>Ec75T}9Jq=+h9FJNiWTc;5l+&_F$Qn&;njr=TnI(u<}rl*E! z%9oxW(~pHe)yzKhdIQzgOKq>$`be9a5uc~$V>INE`j8X>TTF?c`<_q`jZZE=7h|Jt zjE~{bkl5n_isn1_1L4L9wS1 z-(u;zplQf)Ar{>078S?&6n5L#<)Kg~`?^PTcdhwMR zT8L(^36T)WtWyV^VtkbYgHc0{2C06(`TYsHGAz|$L!F5n_G05n!Y7`rNq>^?PX9*; z8!E%t4-EFdLwByfDL%Kf_42K%U@w=+Ou1NOC%TG#C5p(;t?=;DY3Y1EBe_)`mgE z!R*l{NJBPe&N_+DWaE zy~K#t8mdu6g$fm04PLL81u5j?_wk%FoIYB4lxt7{l%ABnfWqZt#aJDW#&f_s6R`4} zTxo*}5Kd@GuSwDHNJymffwC5xu;vT4-}wHF@LqRELR4o|BUQE&M0BXxOB0il!a|Nz z35KM7Gh`^e%Vj7dRiK!}{zll7<@(i17$r9sN{v)WFzc9}km~JIpZZj0AvQfNEtp!` ztz2gjp)|rKl`DxI?eC9*T=$U<&cJ3aaA-xKF` zw(4k4_oR4_o7m?iDDeq+%$iL3;|TAU`;Oo}P=J?$l}4(>ctUEbH)kR&l)%)s;Fr>L zEd@jd*VmVz^-v%isUp>P;XB}HmS9vtw90ZA85tFSp~xxb9ScJ#c*$xbRg_V}tBX{T ze%ox3D*JnFBF&~1pUjJf~lrKRxo@*r1XXwdeRkWAKd|$_6YHWQU_3b)HJ>7dV)YZA08tPi9wYi5nT6?Ia zrCWU7(b!FO^?kIXc|YylcY?=Q8;uMOiszM~MyjaTE-)Dlbo%uBsHLfi`#+C?mLA&K zv!A-Vc8f70)7~yU?deERUnh^LG<7wbX=*Y;f%JM2V^yBFFpnMC?ac7MR7zhoQsw%k zpNjF0Xf^y*e$McKl%M|ctKXrasi@em4ZIutGjF5rtn%!>5c1oZp|mmw-V`?@9KEHyZro%D3uVh$)q>K2idLq zMfwOCZ~)*_)JT;IVfhx?1VH7kFUq*%`ahfs6)IGySOu^sYiclNslKvQu0drp0gGYm zUjrJOh|s(zE)jF6c$WVB>yz}yUm2(CwQ3fFJt5`dXj*g1xyh;N+0t#f`+`HtPeTy{77|l(GDIShdXQM$-lUqkteM*o) zyI4@hG5L2;BcK21Q3vg8F;Zuffn4@nWmO_sn&LI3S>BsZ#d`}#FNr8N5S0B{Xh^4b z=0r6B=--GsDFsl%7;>&z8W14?T})W1iO7S7N;66#C2u*H_jveUJad}T%9mUchci@) zK?M;oG7#NX3@|LfpbHe#VU>X4(eR>n+s?RqCqh5^(*#|gpQO*7Y7i~Ao=AjJH1Jx8 zrU$c8K1%^nKiDS`ba$Y#p4^BYa@q|F(r2ibf5Y#EsIl{DYT5Z*4mI~YLsgBBkh4Le z&RtK^oK8YHd-M=DSx5)pF-C>D#0h>3hkY4n1SVFKsjZ$*GPjpra3)iDnvx+V^*HXcz) z483mYc^D1{dIKUk;ecci5jaZH3o>#Y7bc^L34b$W;$uqU^Z44OARLMEe2uhdFsevo zMM{PufYBRHQz|Nh&6WO(2hg6Ki_?Ft?*o=`w@oI`sp-E|s8FGzIOOzSiR1*u67Qss zGS-lnmugUv(;LBCa%}SdWA8uUB)zWtK=f43-PJjFPft(kiI^D-1{h!vi9mt`6DU#? zgG@@6tY>RwYi-G4y|TT}-reW7KYO3o@2yu)Vh}}23=j#Cga`s4G6tA{$*E_$r*o|C z%DHOq|K7S)UsZoqUDaJ3=lcV9`l~P8?|wI&d+s^+oKxPywLFynaS$fKwFEZb!CeN( zJYpvR7p?@zZeLyI%b-hVcd@j#TFJ(kLAYdqs}KlK?u$=Tzaz@sf7vqbzZm0?d3rI} zBbxiK4Gi!RupX<1`!AQ%KrI;;E8qVfgoaxO%XRLGgd%`pj2sT?WX=ikMrL+fcMX{ZENbDI9} z>$&>9IT)fBezmaX?!P{A*iOffxcTp7+C;ZKU!%6RHvap)SO1c%79k{nTadZg3HH~? z*d8;m7FXKYZQGk8{vbO~VNu@69uPn)D>DSE^9i)+NS_bnDd4 z<}C!~UdsI!HYZF?N2#yZ&RsyMVRE*HeSh&CvJy?rP1M{}zO~BG&=Aed&1HTq4bW-C zZdnRY?%W(0;Kv=T9uD+7`EemW_|Qx6g^EgRYW*VljlCe19w=|4QzLq>%rs`l{5$-V1-s;N_VwYCx@ zg9|iu@mDl^@m10#1y8EC>FA2imvR54%eenqJTGAvxoo57AFI!9%mFS99;R5_KxV7h zrGEN@SIIXo+uk})-y`6U3Wyl?#V7)^(AG+6@fzv`^&;}O6xn~$W)=`=E0%y>^& zs7I4j&*%(j>c>8ko7dic-@|FEdM}6 zQYn%7mH#IL_ACDc$D(@_e-em2$t_|^RjrAj3hDyyed0m}P8C{!RAz4wrd3q8ObVQ25{ zI}sWj4pVcJ*zvm-fWSq%1<{l$TN9d6r95CUO*Q%C#Cl`0bTmK6QgueERiCE(Y8h4kiKyxc$ji+@Y;n7S}> z+s-3&>|r4U*N6X#Z2C+57(uMR@#9%avc)~ze$_TV#`=np0`nhIFfc`TMkBoJz0C%? zZ-2g!Y;>lXUO%M?x|RbdRi1x(f*)JhA{g;OUOf|}E4M;ikda`k9CU*@2rAk9%E4x=mdyjsU-&b6zk{dfxsj@J8hD{a= zD^{o=wgiOCI9|$i7{(L&G3xk0zq;FIU%*QKu&9SpfE$&aJ9qNG<>1U2_PrGVyKT$K zdvUNIuU6p_^1(Z6&2j%R^tJ zj>At-O-&8|y;`{W#t&)i&F}GJp;Yk~#8g?_exTRsw5Wq#Hir~qU?{}v3CQwg3fR?U zn^~wm12o!;&yCB06yW-1-4qGu^S+u=MZ;D>Iu&9xdHFF_BC#|LFrE>#4OWQY&)}L1 zf0sgMyNwVlFUImPvNaiKG-xrW+X@$wpufQam$EBWsvyt7J0b4A5%YO7qi1TE^VYJp zhWa(YfP$;ZMI}j>msFSHswX-46~;%W6jq?c0N3U>ZYy0BikBYQXQ8?p^*Q$4GxOBM z=Hj(cs_4l;$t|r^S-Q8c6;%3E@ou(SsNjujU$_+m0*q=U4H`6PST1H~XR~QxVSy(I zSCImN05=U@O+aDb42LLlQXfh6e?gql>XPFjIqRT2wkd&@@O{VAZ+ik^7;ue z<`}L?P(G)VF++@Tl`&S93zVW%QUi7!cD9;%{FG8mn1;=cQoTS!V~vH!D1ke^QfRQ} z#wdhs2nH+z)&qNc*jUn4leR1k2)&Uc3V#=Zf2TLWX(*J;a509Ih|O?8G_FCJc6%aD z-~Z)8UV7v7>cz_1>WIWr^!=ATJpIK_=jbPIcxlQLr^W^|wKSQz@VXKK__9%Ajp3P{ z;OW#`KclhXoBSAmFPwdo|5d{~rx&;|8?K13(E)-VC|dlU_gOl{6)F&#ua!atz_VCO z`Gbj~bG^kJXY=pUV-;>u<~-$Do=i_qXV-D%B)I)5S6L$i)B|cUumIFMzFo%HSRCJ` zIF_SO!Ml1gN)w>EeAQZ@_`GOp*|q8l6`=dL2rOMLT=mDuVBJfJq-fhgHtq`3Jmb3| zcq^tHk=Kf)Vwepv{yAK|5rzlU+qA3O|?=loBKqwqxYh;5+h{KYJ$x=+Af*4_I=lbjJprac{siI+3 z0p?hP1`QfE0-!jNNh(!59uH4Yw5+yL1p>LLnb@kPa)LBNUNSu!qXlnnl?WjUgoZd@ zU6eNmfVl+w6OQV5!qkC;vaWv^cs1x>ywNz1#>FW z0;>bJLr+iLYo#xLw3)v6bPLtHS6_gjVZEX8Dr)H8?ci1_pj{9Y7E9Z=x#|D-PyZAB z`8U5wpZL^g=@0(!pYgwc_UC`b&$l+O?HKCp-brxNgufsC)Ys_Xk&{&4*v3;SAmBad z&Xt=X8XjGs$!QN=V+(iCMp)0`ThUXnNl}^9;Hc&nw)re9we79;TD+DFb?^dc%k$_SFf+!?4Sj^xd z$`h!}OwW`RTcw;BOBg}m0>F#FUwk=$V#nw6^J9EhF&9j*5go}}wKZtiihykW=)S{wegA%pk9!X0r3Vjov9aXJOFeZ)I>z|Z z{rxUFabG{ zq=uDYW4QlfOelB%#TYp0{%h?ERlytAt;R~Dl>0ADsiHxHhK&OF^e%a%h8V9SBqPW0q42W{K+Fg5i3ONs=26!(qLM?dvdKKB>H zM;?2K{^>vceR4MT(L4X~c`}Z_tGWN$0+2jO&i$8IObPd2Y0dqY0vI2UJnp2HR(0W4 zj=R&*7oKRMy59dp7H1P%Q{{x;sbq{|K@Yw4i~pYf_RRrmZL{$Os%5SU@A-G1DL78z3xXmg0^pkb`SYpz*mwx`s z!uS~)$^qPeeen~y*alEWymL8Bp_sHVAg)wF8%(fku9`zm2o9PKF9zv#GXMv>grIxPl;+NRMgssyPnBd%WO>dUn0-1|Nf0d?!VeT{jX{F z-UIx2H38+w8~@?+{J0$VUk0O-k|}mB<>j$ejPV4Im+^TI>qubhB`?!0Kw(t#2DwjiviCJ z4&0y@{^~oKGXk3XFAZA-h^g|4=YO5TVG)lC{CP)L7o(r~W7`q?4w;g|m8=pAj8}i@ z)B?fUV|qHo)~yC=Y7&+v4t6|vCrH7t`j~BQwy^t66py9ZUvUo46k=pN%;ro%pW&7d zSgHFj;M&aqr`feGBU^tsxs{C?X6M}$jh7zp@pznXFsKGF_m)dv;*5?BjpoOt0`A#k zBDYJue$HI*au=Mq+Gh;Yf#~Arf$F&bLNbs+r@8;qph1HM4H`658BnTpw3^9c(eXui zFqB{nB2ibHg)cq>)eu@OLUB&U#TYE?n*HEIAB|5&xI2`0&v=$HXdvgg6rj^ z?cFwNZO$=>CaZ%SjeVJ4#nH8W57}!wGQTuvSQ_I*~gvP z^yEo9wYTf}wf(z|dDrk8=R4T-Cr>)^p24|Fo_Xd`XZD#R`^|aJAgPtRquWG#5B72w zd}_#zW^tr9){wQPHBX@e=nZCmeyxE(;&9O<6)J#q;j|QB5wX3;#$8WAaM#8b-}mfu zQeTgir;k3~z|Sd@ss3Y`r!_1G%DOy!poaQ)I=SGxt;I~(cn)PsRV-G}T~($cEXZ$6 zr|9fpESql6OwzTnVY+x{oMxhFO6&4dlF~HnOVRMWCwt$;VNdq?jigYq+l}PT_?pLt z3DjvR>j}FxPU%#>!k`!+&>0ySQ5EV`s!)M~rd)*zAQdV=F@*{+GZ*7ZTA-W_BTFk( z;#Epn@t`x7u17nx%>c4H`BBG)onM$>|tv z@3wNGq1T_{LME3(&zZY(7yWz(j@;o`eW*`nk!YIlE|j||aTnit+9?DXg#wIn(a4y) z6Z@@MOBIQ~|M$K^{r&y)gCG1L8~Xvj;R>$3y`8r2*hSAgD|~uumMU8Zt7)mC2E+>j zp9wTrlJvV@%(00u@y}249;>0kZv|CaxN2zb$ zQ^Im+*%m9gCfzismO=%)cRMo*0TD1gM&nZvO0mIl{D_-uHgzS{__UMKy7KuUSgN#l zbg(uP0r0P1zh1UN1$4O*3l#t~{LZi#yFH9g=-(*>YK6e}UcBO`j&>_|`_;qhw3wSP zptM3or)pWUT!ji~pqhKC4QHwHiJq*>w2f-1g0?|j$+r9CLv>s^EAhe2PxC$ot195! zyD!qfm3R2D8lL~!zZd*Ma-5v$Z_xK&oS^HI>I$%)dP8=;Ed=BEGDrD<+a8HzO0*5P zc4L@gdkOwjkf^Y3UfD8_6x zELA-7F;4$OjK+gbBc6+#KMGNfwF&??Uvc=cE@c8&1fVJ9#xaw)aeHwr!TvrYwKf&x zlPS(9n}^^f!(r2tf$?{TYopXTt?n9Bvs5V`hClw}KmL=<@tR|9{6)GnFw2<_xp+oE zL@=IfhYC7;KVuX`>Z8di zAslb0hrkv=7gKoxHMPLUzCe;I9RLV;oh5e8qYp?v({4=Dy$5o<5-i3p4MZrJ)=_tp zkqZVTZrl#hlrK#-Lz<54b7mKCh|zHVMws;}9d$P7xh0mwz+i|bylEas=$<_eKCS_L z&xPwDuDsdaYRn2)F%+?*_w4luR}vvXspRux+#n7>lrCKhaiL_2(Oi5B>L-_SK*>J|VUKrl=8S{~0t4Mu&M&Rz=8 z-@Q3cZ=Lqhm1}3|#`Ra}+SOMnk_yv&B1VB!ltS4QV=Jl%&CK4Wt5;s->Eg8s`tWLy zr=hVZMUt#+tUZ82g$n8g^>1V&yuHbkx2T>Abg}o|$^6n#35;y`oH&vb9An{q@m838 zK_Mi8OD=uh5Yt;pL zhf;Y`$HouJi*LzPAqRv`2X;EBCgbYxCqJK~5Tkh?+3n7LpR4~7YHVVYCRg} z;Kw?Xj%IW*n)ZqL0W?AEau)3(5)}VNP8*OOJC@s|0E~P3xzMn_UTj2|9KFG4iIw#~ zLF0S-_E7_O5h?Q8wg05(lW9Mh=|j45Bf#jqqOuh5hSM~|%BG&8s%h3A%ci+NoG1B= z+=vqmSy{V@@<`Zhwu*(H8Z>M~B$BM(hv%~Wf0iwLW_*lCTa*gN6ypWh81XVb6np^; zq|Ign=V32h^K;9@WBY43{RYx$15J2Dd?FTs+F)QbA)>CFRYGsjv-K(Co7ubqo}Cq3Tqps= zFT?y>$%Y1Ca(a%{H#8dZJ#4+gNNN8L6&VWZilwVJ{CvK`&w96o>hv+H2`;vF0b11e zNaVrGUaySvkF_?YRBR4l-64};5tQb!4>5(6YBziZp2s>}@9w6K6JHb;HaIq%Ql)9l zl`2~Y)mEx_8B-2{B}~e-q$MqBNi9M7Q7L_?mQqD3RKnpfU-&Jxz>!K7w(KRHeu4`X zv&pD9&Lr%3i^bBbrdUCMJTGHP=e=>NuQl**7@3IDoskHu+cdQ{=kLs}K8m*+7VfQ0 z7IJ3Ryhy3?`fIQ79g8zFGqi8tKAM}Gqk{(z@}0GN_Us`m>kBJV zs<3}FrOL*Gq#1X;QYAA4FI)-GrNJ2gZX_&FVFdu?%7Pcd*EFje6BkyMLc3efT{nSd zsU^fHxji1Qs#0ZQEU450#=Qbog7fu7>D zqbp5ryNMc|jMsEx43(GK8%&HBi&2;j5AdqfGg0o+5>Pi5MZh`|8yv9?0G-GD#1#%| zbFm@CXuFB=N=uJ>JdgPo7C922rAPqgUnE?IG6nTf$@~t4!ePb}&m!ZzbYKrG%+=>t zw9P!@q3s#VSj0E8#Uh$gr3z55@w*0SwlYz{ty=|P$gx{kg9Z&6HX^{VfGLqef^q?Y z=+FoPWfr8-T!OU-fH)wfgtaSyi7ikeTtL9ucTRih?GF~XKsLe_E)MSrf+@gTXgEwDf;F& zzsZ#=xNkiG{*-kuO6b%DMH-feN*4}W7A2~|Zo|%OOE&d%S-FxIz*s9x5(DFL`tuj2 zi>9|e3~=R9wE!XE{6d`5fd`Md>CqE)+>I}U?NHi4D5y-u7J6z>Q>aK~53mr^(@nOX zRHjM4*0+`m(7T&6>1-NaP$;4qU?~MlMF_b|##liU$h1j;F|~4qir6@zrceP8!wmVu zA{5pt*wtGMEsZfY50)PjMG5do5TIMFR=!~cu2mfl2Nw!UVa{@ZO)5xOAG;hzt`sVU zTa2%PQVxO~e6v&*6hd90lFN536)IZ^u>OVRFYqUS@+X|fT1|jXz^x7v_{UQ4%udqS z@Xc(xaQ02QdF>oOR>tCzDCXV^*s;w)pMS1hH9h$3|4vVT;Tw7BBhUXS?SJs!(7qG- z>A-{kf~N*?hAIEcyHh>na zHc(c0r@$sHtj95j6ob3QPkLQtG6yJ5ME|`RM%8qUJqPsX(4>_q%DTNARt0)yJNVva^)sYlxl!HjnN1@qU znP0^*JaC1=-m%QD>Y&_GA{GmF*vzFHGG{bwRAA@4QW&=s5EDfLJJgg=?lOjThlKLJ zlF!7H&*V0yq!ahn@>ooW7o|*4k|6d?IjNLF1#p{Fw5y3|e}_JscC~5Cn&kq5|NWhY zY}(bVWArb-vy@bXHJY0B4;5;<20P=*3AOO$cerRQp zpUhuggT@xmqMS-)PO1Emmn`3E=O@cvDnD5EDC+{+>80|+wNOZy&jY3M!~NJ<2EgS} zvHS|(1?@OcD!)qFO6FHs7t76WIc>Gl{0i#=<^@RPY!6a-}OJpou+$^AKo25v9hA!WB|~mk1)NH;A@PGbS(?6#f6&ohbQY z`N9?m^!i$K)Y@D_Iz405FW;a}LnIfdo->A`d}=^3U_KmUMO6l>M?VfT#NoWHz3vv*9UJ=Fp%#OxW%QXL{iLqJ$(oH z-`2(??dzN3$KQTwmL?U!@Fn^?%+y?DhkT5BSYOGXOR>g@#d7PmLV&;UCk!+>nxg3m z(8e6JK=m573ZMkJ=RlIJ$rLomnxnrGhSUU`=@!$$s{=tw+f5=Cse;BD7}@=;PqkB1 zgP0!>sQ&bgkMd*8VQ}#bT)XfFU3mXz{8$aof9>D1v8!kN^f-O@JO4Hps6InKtAPb? zoJPjOe4`K)|FC+isVP3MdHqfbgww~2C32R0r>eww0c4dAP0oKa%nQp;Is%oHmyP2)ww|JoXyHu%C!6&a< z?NpAXlq!Hym{AA_cc-VPGr!71dwaXaRA|tkp<+k{hZ;7LQU$nM6f5}(6$qilcXHu{ zLZO1#1=xWIrWwq5o!i9ysbl9Yo>5b*VCrEkapu=zq!_CXW=x5~XO6~ZsNWH-no^~P z<iqyV}Syt0^+cs|8pVf zc$B{nJNVmMGVfuZeELHl&3fWozy_CIcuoljp+H~cI6!`QrxY40fgO5sF)5S|`Lqla=RxHGF?RsCoje6Vi$L1x^Kcb)f^>;JBG*kkiRLK`^zIrA=(+dgSPbM=KDH6@B|7H~{ zY>c6gtiDoZZIEQ&0wMR(3YEouxm<;c1n30DKE|QZKy>V|n~$ktfMR8K0ZQEB<9oFb ziG=C)?Loe&2Dp!vwUj~yRto1Y`?<9*=m`3YR4_ zQhwhl_S{N<^7&@n6ba{Nt|?VCY!$>4A+oscWPU9V_4O96Q~_Xh2|A1M*jAH2m&M|_ z-$}N@^F}e(<`kPC>Fu=!e&3@f8u^+O3YEWkX_8-$vwP>lf>u^jsRDpLk4}Us9!pbW zgNf6BC?ASp-d97R$lA`sw+9Ean-P^bajcHduf+hGJI21P!7XT3cb9|Ag;V#%LB?P# zR;+Z^5FPIno*UGF_4Q4UIM$RZ>jWrO{_^Knc_+r?i-ypYD$9qaRMDV8!)C#HDpkUv zQJSB5Gjo2Rk5L7sB)z10;fixnzjp^6>IN`=bV3x4tk6Wr|=6e_4E z2&-#c20D7MrlewJrD#co$z@C-{&j{aLz}6;V`|z(E%mjWIYWY#IG8*DPvO|fniJor zL@34>Io2)xpD&f=_ zA0J0hE+9@yp%8j(A~*H`T$e&iEKnhE^aqpFwfz|i%%7%sbe@Jr!+8QZ0M9|NyA)Qc zRDog%Zp~n+qEr&S@$NhY!{R&8Zg>yMhWm1wg$*u>iLtP_Q(ycOKg3Dmg}=Seco3kk#ra zxvr}w5R>E9?VJVL@g)>0_^wyqoMUTxBQ?~)vRo)aa?oW3?-CnHp#rR@Qsu}_J9nuA z{GZ>LCLb%qN|Y*7Q&U{A0t=NVpM0`x9$TqYNf^@fet3b#{GzN%rHbBQrJ9BZDBz!? zu7pRrdPQdAetMMYVD;OaiOKRv~OXAFwltnCtHCB}70%?}7 zk(wGU)W_CC{fGWBU#sJO1FJu=W>53DBVbudwHkU3x)1u5v95>ecRwgDY;fF#N|g#e zcin1cdC-(98Z>CwELcyaN?XG$-PeDSpM&7`Pk-d0NK(*7DNv2Dg%tdND;dMBs#qzm zP=SStB~u?Mx;7AGi{u0yKkUj|)Ly+Aq?y?`b+nmj*LFLmVPRJS;|_IKfW$ zJv$v-z#0mtsIB`E3V7b7+d~1maXU!uTuEeLi?)2L8tnL2ezy`(0zn~xG1$B7BNPqX zAir;vTiO%?W$9E1CyN1AIH)^dIZBnRpq(v7Q9d*K79mIz!KjZMbY<%muGAoSmxB0m zp;V~gJ;P(7Y>27y*{AFI;!O6ck(n0y#hc~ltsw^}Res|W!o3cFG4syl5Sgq-(O#^Q zmF+E2X?vCr*{bUYb%DKlxt60)kq|=rXvPg#ih8?k+)Y*~K(R74XCu4aRdQ`t4b0BY z()f7JxBc-Wr4=ebq1&(SP8(M=%lg~s3Kd|zlqx{x6B%@L>4P8z*!;Czr3w@(NCyuJ zS6VN>{4!Uplmn$w#h*yhFMM7u@B%P**=z>R58CZDGJ!1T)&{~4K*S2Di@5Kr(M-yh4m{{l9vQU&nL$JjbJ!rg$u zT{Y(7`Z}SECnsPw-l6azYIn_pF^v~G6aK3 zx^~mgt^He?EwsJIPR|^#r4vuVx}>^ov(aJr<3Il6Kgk@gIcCRSq)P*{ocX}Q4#2|J z$`~sRl>#wO>ezxOLGhT6Y8?@>TSH_q1@lrYQCv`omx$3 z8LOobh{aOLVg)f_u!{rvxgE1)HU?BvDltnoOPK0iUTUlrJ94q8KYKMyiL{vf>uQah zp~T`3i+m_fpzsIcjA@9*(&S={7MLvrq*l5O+Q$I1t5AWE)$2=8 z1G~Sg-O7aws5`N!Hgfk!P(uPt9Or(tbSDEvbl zDx1?!;}fC}Hq;Y297$U6<}2htDxjQza9s+OlyKS&nf6y7k8_?l7kI+oI{L28;9|U{ zlLCPt-5C|T(&XYz(f|m#pcursX@_8+EnNJ;G+FJ9luk@B-W5T3Kk`ZEIiEKEduvKAcQdpVH|>F0{ALep@7b)0pks2Ls{d|DMruc zd0uMwL$I`zpd0x?aV!DrGx^=pOtp*-VOP5{HPi`O0-(H7p#q>xmv2SbIwC?BGwIfy zAnPlv6KSXziDZhd4Gq)9n<1WtCSnv|)g25c`Fx0eD%%@^e;Fi}&js-mMcFwhE~}HO znb-0Y=CvHquNTuEU?mC_0DWA}r<~@ngn6x$8!)Sd@k-VNqm>a>{}}UvZdDWD(*_3z zc?>+DzRpY!9BaA_+9`s77C(bfQuMOZ!sPu z9|BkyjhF2Rd52PYQdcYD(cxPQ+2J&+E0Kt1#^Y@Lo~DoNc4xoe)&B@JHkG$=1e=sv zT3UFZdbj}V>+8#0SsIw%?!5H_ejH=$jgX%8uMSb zTTeSWEcD!?4RoN-PTShIu?Jn`v@}q&yOBcd*?2TYI>v*`)NIpH9h5Z|Cv~^?Pz$@S zr^QJ<&2ciZiW;3`f7zH(Zb$(3ZnI@KOXPsxI`XDJLMDrw(mGos zAv6UQF)=z`{Ju&7*~ZAo2u)1n2kQqq+H7?EDB`P?e&6{^K1wjU4SoXX zV)LU^ZdU`C8?liJR{T)hz#aIGPAhfweUV+Qa^q}ptgEHUwbQ>%-~IVD&J?YUrAh^# zx^A_yT%@_X2@ryM8_{QcS*mEzpkb|0ZA%sGqy#?s&};l} zxhQ6-BC**mRC>vBNdl@+0=a z8}BV}!Rr$z#qL<}u(*t|Fvo*k8tJ|xHI!n-FyxdA8+8t;Q3(vp~M1T6hlb4w55vDA_Z8ErOINkF*qY) zL_Gay1L;(~WmJ@H)c!p~cS(15OGt+bNGLJDP|_iwq;z+OGIS$dGjw-%NJ@%;bW6i~ z-OuyqEM_fW&TG!S_i_A=9rGFT3!XD4m+DjNV0m0h4bWO$KR#%giYhVN+b8OF zbg2guy{lQOvWlaC8pqXm3KU2T*D7h$LYJ0@iVc)2AbE^|;;=7W{0n9mz0<+!S-uZ7X7p#$x3e`mp)hWOJS_|EE>VD;!Z->j!@Wk7cRLn;s_~p*$>aU3qrOG~IsU6-|iB zayjWxLe^c|9JG~9uwBdfzV%1dKe*%hH-M55KO&!Kog;mqcCzI5aX$HeI{n?yqXJk> zf9t!yjvPYqOr@G?WVuilLHl~%k4Sj7sJNfUko5HW;CuwL!m$M~{4wvmkHOkKD(<-kB zS<22y-~lo?{h~|Uu;o!u)9zx%#e-#vTidxQI*F6SXQyRu$e97lP_^`%YT6LpmmOtT zVl&f2CZ*8-7&zv!$_pW49oIw#edeN#car%97;}rxu3vyc8lFbN#ZI-te+c*|vAqvj zJB5iE-D4wLB>Jc|;^a|Nv&^yebc7Z0TgYcI$&}v+%kRkcZV9BPVrlgf@yh97+r*Rp z^JN!BIiSm~o=xJUB2eMb)=ww;Ij1Ks((6pjMW88?N&fWr`M(PjBnVi-erB{ zs^wYUssPUKw_BI;v6Ea+u`tS}xA~TQ{geM;Hf5QUUb7|(C1ueY`|MT-h&i_ZH_4!l z$_sbgI&#NCv_>1{jrUE@cYWpr_QSi-RuAvJ;_5$K#zINxz;_u}{4L8|JcLxMbMQ5} zUy35R=a{{1|DX&}$zud>O4-056()w%D+in^h@izY^(qf!QXSfEWQH!jn>^<{*0De{ z)7^h#Z#q$a$fG6~L?|L-G#Ur#R2R#mevN*R`@oMMs9>i18R3Znl_(tf-2??5kWwVt zTfV2?e1F~juibA?l#{rC@?3Na?8hDW50Xstd3l9-=iLT29bpEDxvUhz5h8psVGDkw zSe>hK$SWb$dfQ8iYF4&r7xog^4|%hj-eRZm0GbU1a~;GR>O-1@CZXCaA5 z4A?4G(qt*M!(buGwIKfMo>g52PK_c^BUHV|y^ zA|tO`F)oji-a^NaJJhLG)5YI)I8r?u;r!>f1I$h&U9TXsk7P+bT@}^QJFnY`m5&)5 ze#DdZ{JJ1=OAwmFIrj#0V_dBG3k;MdfP)CgaMU<-P2e{HcG`ZI;D!OQwrG~cZ$$s4U(?-3)hGI-N$uW+fzbx=;_O0)@YP+@ncj4brTyi zvk-AeyH(?c*bKZd-|BmFO;c6)q>4j~d0IsN^6xc4n;e*H1*y=3!m+Y+tuN;q(Pp>b zpus8q`V5-XI!UyxI`hXh6MYT65^T)s9wof^RZ<5#L22oowRggW)>9})I%Vrb+*R49 z_02&FUt-Txt&?wZd?>2qqc5-z+hdZQuDuV93PEzIt{14>gO9p+&2F+rz2o#1UsrhN z6JWB75PDT_Zqr-I@WI8N&j#V4 z@$MZc2-ryPnA!{$zfnB>(`a;ksX)%*p>{rZrY4Uq7W#(D?FCn8J z9vPR*`yL)7b&I;jF>D06HQi1eXQb}!ZreWMnM}K1StU%a1BKh$aEN|Iqr9cFxU!c* zhDqLEIMpzn>Zusmm%?|smSA_pqv=?F9gU_u?w(J|pDsY`ZE3(z^E1)GwHe^BtTuk! z*S$Qfopja}T%7uI=26nwDdSQvlyuy=vBbKZaI%a}Wjb9|!US61wLHSOmQ2mLc9@LE z6*}It{%V(d=e1cheLzv1o=$0NW6$(ILM-mjUybql%U(k^HR=ohdh<_;9xaOS_eNqt zKTfjpz)HZkQPL3(}tud)uN5I^Wq9va)2mrTGc!by@yBfPZv%ou&Iq4ome6I`Z z;gHge7Ymgl$(|cNpD4c~r zf9A8ou`jaQC(0JUNX~pW$_6~_;JlDJdaqmIVyn`c?p)TNz4`ftE}0+w6;BDbp=C-C zTLh7nIS4z}Ly|2a&}=6Weg9^$>%BvHf1k%R3fV(1uC6J+6@?-ak|+it0uzI`qpPz> zuYoi=u4)a(X_JDulAc6UEFv^@r5*dw{zpt9Rsl~WnzHz_fJ}$)BXU%@m5nPDrKoNx zix>~J#{Yx##V?D7#ir9)is$v3WX`Vj4yqsYR0Z3)Udf!%zes}K9@gp3jL5snzU#3; z|2>rZaVnc&ryP8xzc?{?|M};yuz$nt&-uG_GasJrTGNavIl8wIoL^PYNVWSzxw8`!+iboP@{+nd9-7=`4F^Z$(+qz0bFzSH4r&RuLoG$ zl{2?CbbO|s@+%i1^gMT+6D+r;D>I*T%c5>m>U{KIM~pXi+B`n7^9m#!xRtRmFyS32J{Cv90y^sl2IftY*&&R7V zy}-E!h{hN3-T?tyvGu!pGXGDmNxBS<8H-H~{&g#Rx(@SE-(~ z=eRaj4#=M5>udfExdS!@M0nX^AFsWQwgnKRJ?cO2dO#_9ie&Rri-x1-Vt7IH6i>`NKJ z121qs{bd_) z`od2S0S`|gR~16xAc&CKfEIPH(O~(r*3_X*I`H2!*Uap^0e{G8xLNSws`*y_@S;?4U|#t z_>)kA5BfhqqqPu?V%W_`6xx19;;WF=$V)|2~STavxDa7~oh=-s73S=V;z&PMa-OzHBT;bvg4+=iQbvPD@BvssxW+JkY z*tBMhMp=-Qyir_S_^kjjyV6EV*Fs=iFl~=AhCc#ZcZ@As;#Q#%(#`v~stN#EexvMG z64rgxkK#rxEL3Jr%)iJsN!EScJ|vBthP(sWzTV8PvU>6SK2lxcz5}u<936wf^qKwPU4Iy3Ykn+7zTLj_E(0`ayygWc-;quk; z`_h`ibW>JLGU*(|U}0kaGkU*yq%b}t-XZxNr`D^^KJh44_i1%CXa(M~`yZyH`2~dE zx~hU5cD?H{lee1tnn!8vYOemh&)N-=)bnXnyjqOGsODRwb&O~d`-Z*&?x|N$u^^n_ z!R@+I)vi0#3wwj|*cOSSy2@X2zQ5k|2<+4*TX8kp36SZE3?PoBT>JtV?T-WR-x6cn z(dMahbjHBsS2g<;jC?yMs;bt!MHw4Do)}|_;FufpiWmh7|JUAX_1aErct<-X)=z`c z$a<9e+~KK_`c$re;CnZ`t{9&-S}eu7c322Q=99G7%o%XIhiBe3sd2&78#o$l!W@4f z)|8GZF>KY>qi1ni@kbbv(5og0xX_#|gjQ%|JA<(~E_sBzhB_fk$GNND5OC zYqVTPf9ubHrP2JMS}ymP$CE(VC7If3PBPG zN(obwxSjP?Sm(GJV}t+*o4njbRP5lG#rm=RVMVh`6gT!wlOx66A+TZna8BJ z@_vjwA7HRK`C`oE6(>sdqET(-OBwd(xXvz-G%JrUx6P11e;1Vo?ID5g!jE;xjLvVm*3JlA*UHWXl!+KF6aWVO=YePlWAOzJ|) zpV_#Ipa^WDyLXoWPH8~>u(!3ZkD}9ul!&(>PT#`EtYcy#=~sbZEK?REpS;O02O}KD zn;H}WAS_F;a`UtJ#e6*AnwP#U^sn51vipoY$Mgnwj~c+o?|RfG(>V2Rn8wd)n^1#rPWO`zL-5cnK&5qxC+wx;kMTkQ|!8p!lI! zAWGbpU}xGD>;-l4pkE|oB)#S_x+ZqJ1>v^M{iwf1y9JTI=&}|w2@TnN;&1cuI^nE*W`QaxHxs8*Pn#?s_J1_HobjR&lwZcQ< z`f-8J-66$K=0@LWUonbsJ)G*glpPQ3SLA<*GK(AyHCYWg6t<$Iah_^R&8~r-$X-vKCAz#;NJ6zWe4h;h`I3f`6Wnf7mik_DqNQ)A-9dvOJ=19hG)bs=}Gi@GTp zgiB3}dx5J6K(sw11XP0aRu{!B_k5yR9{X&E`^)o#Uazqsou3e?x17Mau3}h;1EwbH zlm2AEKo$WYCD?^tIX-J!OR3;iodF{u?k2M4XU<^4Zh7+7X*ui7GA!`HsG5oE=|@Zq zXHzFI7zKqeciZG!LiGdMVS|Gs6M3yywk@Vrvj;U2_|OdfA~;k6g~4`SL|qkBh^)zn zHZnhu${}IS%cWNG8d|K>S);s>i6LF>ike(5n#0$fwrKS0D06rlY&Ffxi;RnFAard^ zg=4Es!j7h@vtF~}&jHrdjO5}6$%|n$ZLs1az7f1e4NRVnf5UHX8u_ibM8g92fL$!? z^z%$V*?@*YbXrcYcBwj;|G1DIPS5_QSYUwL8i(s0+aoAR@TqR)^boge+g0)1R@C~nrI_r;F_g8&m))j|82_A%;Z~t>l9oTu(+2dhvOPma% zVv$QkGL@_#{n2Gs8F&^x9+qpY?rgdi0;1d^G)KE&4!N5lGOq{ed+yl=pktv+1zb^Z zzn+#s8L!>p*fgm}UqgfPg<=KVf_OE2I+)#8qr{MWkU}&>9hiz@N{owFhZI0};ssl* zG_lsi^l&81W73fOGwioZM2O=vi;aFW(8S&r)=tQd3&)(e?C(uvy$Xe9 z@GU%&Z8*NNIazCeIOz^XAKgK~jyu0qgqi(A@$9|5GCCRXVcQ}0DImJ2khX%Ze&A)^ zyK@XdV|x%f!qv>|5fYdBptJCPO`6p_VmrHt!0sA!F#A#GI?y9%XHnlYxo~q2WJHcJ zMI&NdFxd?CHJ8>tk8_kEx7N~CW&J0?$59PS%!Ql@c#-2l*=a|wKAW^7&-L1(Mv;7K z&zI|UPBihcT5jsPlcZW7RU&88$q-OUY2@re?t;;?$_|wwss=KDTe=ABNK9Fcef_3T zO*+8F4cXuO#*0T@y0dZ{_isdhfEiJbP4e+^BAKM*=s}?36EqY7Q(4jNZ278W|#p9 z=-8*ufhXU4(3%`MSH7}$yRVi&E0nM^&98qZ3}*b1$853=CfXsZ78g>1;f9#u_|0zN7ihQQ$uHdPuPSo9&?%To)7exFH4 zzLupxsVJ0xi}{I#4a`7nHfFkoc9Z((ZF`uHVX^$h{SVB()sWC9^s2+CpaYig$`KVZtJe!_tl? zcoGNEw0HxhehNm{XD87Um9r3aJcA{1{p!);1JYg`ibZjKO#3Ja|G5;hl8<7nqo^Xd#7N54 z&3YiaCHVkpGX2>qk{@$eHrdwF6C``N?>15pVO>4}&B`;SFr=%Ol9a!BIc^oO2DZ#! ze5;^C&&V+0(5$?MVUKIFg!9+}$5^(?eyp172fQrx9FbZ$A`cG^vpU`#EX@5sX$ejX zG@$aA_cpwNrA8D!qiGnb3OSDArtGKtvx5C_r(O6UFJq<1FSoT$Wj9(a?% z(@4SL0n5;h*FfH4QSFzH0m?kuNmwL(0)atT>)Ky}%5gimk_1BG6{SDTP~~MXk_m*! zJ%3={{(U7QApT_zXkZDVVoQM+<+{F+dCg56V|0k5vxECh6VZ>=N|xct|3se<5}>Yc z?8F^RtwaTrXXnw@jM>ROT-+ox-A)`H?cf<3D55-7-E`3q5%G~z_(0t2cEzootU-a= z1?(Ni@I91Zs8jT%&t)aefS z?OlLY-|vLmPUWRhyGImy_JEVGITfl8wu*k4?5lvRILfHkpX!6mr?|!i4cDBRX)gnNLX_OGVIBWIn_=oVWS1jh&R1k6$Tni~i}r zwIm%W%q)!3&-FsQ|7c%owzH1Q^8Fi)m6{3wOV#+SfAEu5WEgnKv!ID8pncqa{n6|3 zYQeMX?xpp_>H0RP1|7g$&A*BkM9cLu!lPx zgK=8e$)=oC2F706a`dkeMzSo4%bo5gP~?4Jl=5qfQ@8QYP&C}pzx~|KA=%I4x}2L!J%60jYNDX* zFR-drR64H$>huYf)uf7LprgTIrm;u|?(B=bG1;c+J(7_%I)bVKlUs z$aG=2#Hl&w68txu<3EDi1kwZ7hBcEFw!Gj5XauK5|ST+fu(UOtKOtx{q+eMC{Fs*@njR_8RC_);P|8}|`i_@}mY z%9B1jgt^Pzal3gmRlCLfJ0>wVFjakcLdg-OB(H{~%k&qiF-E62Ikv?T@B$L_ORigu;`_m6*SR$sF|w%7UZ77$-gYA$XSb{VGo)P52y zCa<=w*Zf`?M#=NO<@xjlw{HloxL0Pjn14tl71yP&G%11_eAC-d8aSBq}XhJGFI3cRt9WV^dYTqanT}vx4ZkJL# z@!|hqJ>k9gU@1Um+)A;rMd@g))IG*Bdhh4Pv>{*IzOlm)tj z7B(rZIeO1XoJl|);~_IX4_o%Q4uRtyH?g?XHwF;UcsjOPnA3!)B=n7@ z{#~9CT%`JkZ&dTMW_I{CI&oQ-Ef+*5>cN2^d76mb_|vs<&pzRL_({^=qXw5J=lWIu zZcS9)uH(*Uzq<+dj$ZS!%vVl~fc8V$`iwQzpXj42NpKkWzNCJ$7T5&4`6!%b{DyAj zfjEWg@(QytaCgl&5v{7NH-7H)Vd1HLgYMglKR^B-zuxl*-OOCqE0M&T3Jess0RFpjbuaQf|21=;;yk!km`W|Eu1C5~lr^0O29!%9e7}in-?d z>eQVlyXfX;eQ#E~N)Q=`xD*mwPprz01-Q$V{HkvjD~ zUQN$PIN}c3_k1Q6tnUKhjxYv7v(E1kwLMS9xPe70`bt(sl0R_jN?K{Emf^zIgn;;ZC#|0FZ zz3nEXmlUBA_!uE@ExPTVxV&4>R^T^Amix?&Y9g3l@PgiL2^R;<_L*lGk+_)XG z>yBms?+S*7VtAHW#W;6^f*=L|NrYc@o?yUxlZu{p5}T~RdMXiEz!zl(oZq<{C;5GU z@eRW_q?`By;b<-be>o-?{7|`HV~0wptP?>GpSW}q@2icB8ZxtY>a`n(9v)1>j{_^uEFDmid7U$e5ujEn^QTOFslXnJ^qX&s{C~Rjaep ziyJ3-9S^EQ#a_I%P(t8{1l{vt4mrS&IR>mhO{rsHKu$hP)OJkHn~f?-56l8O%yNhr zYR}gpXKQkYrw2uYy}x<-Use}?Z57GxfB)lrQW&=5{WtIXYJ)?0)R zFWpH7cC0G&)McQ>`G+HYlL)&d&(!g~R60aQ{jZn@J?IaWMq?^ey=&tbWW4 zicDZ_C6O-~`#=&v5z6Yi#)ZWCY3jfD#F;K68lmqe%%<;n7q8HySZ2)>A8chg-*vGE zy5&fp6x@cAo2zcQJ}Czn)O2a0MY*oj>VeR7If0nP0rxISD+_9lp6?GlsEv!b_}#;r zRbB8}il?>BayJw9G1T8*>mz(kcY<6dVn{LOg)3yr+NbctwCu-z44a+o;7Ag`==Y$- z@Z|i88rGqA=qJp*eQfuViC}E*wYQ4Xwa+Nn_UKsO`Lj<~`&ywLn3p^&BYrwOw4tXIu~zKxIcyNMR2KV=ecytM3g zFmXpwb$jO1nlciOq(qLR-n3x$K17^lsNC=naq~OkucUVEgId)JbN`}av)^;gV|Csx_v50B^*eHL?3hWE<4ed4up$YN@x8xcH4F{}@0hXY zdx;;djFS-yr_Z>W10E*Z9}eCi(DUWHH*%0N2!ERWv?qEGXH!yYHqNYw2)O`1xLofh z1^-R@?YbGzoc!PYuR>C6`K{$(ow0zSag;#*A!Yq+wvBIiC!cv(_KLr?-hg7VL0J;V zEzg8Z>PDH`JY{mxB4mKAz|b=wi#W z-c(Uz6f$In1>l|pz;Q>IR^lDddLwDFX2c6q`>{fH;i_^8@~PV9itJUB6aAiI8I++L zsMiH+%)qcAHdqrI3@t;+&$iF?DjAu%hDJ`p00+Sk){q+z-%;L3Hg4uJ+Oc6E8 z7TUECJ+NzwQ0SJHp%ZR2@nxU|QIs!J!QOUb>g8>$)9%&wjy@v8|IE;;p)O&~q`<}| zrj=n@T`Hi%Y$)ja|%~Jvj71+_L8)bIn_LXs3ws%FO+qKvy>uPfiXV+(yWyJH=&-RO9d)pJ= zq_GKK$by&5T%(liaWZ;sY5gv*;8SjAgtiJjDYAZ|3Q#a-&Hk$vV+UGd=S*2d6gxN+K@d$Ud8*&-B3Pkg5jjZhD% zyfyjcF-BC`5thZY@IFqqixEGv42?jDRK%RF^0N!?$g18 zE3TIT(E!!x5fging8Yz?P~DKd(gLcD>j>%4FdiLH!6v1_>?o%tHB#ZAr9b4bMfBX^ zno;u9KqD*|KnUwxi*L}<{wNVuQC@y@2L5KljbJM-63)d7v|C5S z542m=SZ&4j&sNzurOe~+Lx(F=G=v=ENQ;b%A@Y51XW{7tNp@Sgl71GSZ<1qmMBVYf ze3TdrEmcylFno1y^)K_kuqu2U1*YZ$qd#R|1#R`kq(Va}D;7ZPx`{&e(j~)>jb1aJ zlG$Hpl?-Jbugi%`I)Xkx8>@{lN4SLC&Sf3d9aLrk+wa6N&buO2A%0KicPb=2>h1rl zLlKtH%4c*WYeCFMr^TQO4}0;F#BvYBVMkK)l7YYV$0*?Z0OTZ@%N<}8zbMR$+^CDJ zuFU+c4|%h@kqhK*4Untxi+phA#J@J7pBl1vu^B{?7#}65mmc6RuI?%c#sOypBj#6J zFpr@}Ud$HYo8UlMaU2h65d(zJ*1N+MEVS!fKa;c|`fYfa=Z&8zUv$k%;}>DuzVS-6 zID7BlQ{HlN_>HH@<=y(J^~zz|lkc^b=K92BF(b0;?TlwsEr*$6e1@%l_Qr1DUU$wE zza1AlA0Bl}{LBEapELzcAs5*PLZ&oNSt>4=ner&R;8;ZGTR4!2$QD<+aFT}ou|;TP zz#%-g6IuC6f{9`O^VDqb;6YO~2m2=wv=>FMoA=|@?D!sYBWMcI43fAOt{~O%zT7To zlf4o@UPDRUb``J&2dS~;UIm<|?H9CpeX?#-+mpQtiu*AB=AuG4H`5T%m$>Bg0{6XN z2JSDV>fl2B>B;^BY^@iejkCZ`liQQplcx|g-p)~=7iq5EMK6>2>K3@xTvlbjv_5`w zJ?6yl`xCTp`!6lJIr(PcYsR#RU8bHG<14mHA+c}ydy%(*6(^Rsgm(Teom-*T8QkHq ze$2dOu4yra`D9Qjvp0JY(>X%7-Zd`4kd9ec(m+~O&K;B7?W{a_gAkH(>Kp$g2J-x~ z6c~SI?g3kD)`C{9G+mNr$y{mqRfO$!CKrGmI_~K9^uq>(MD?0bBf_qbZxriguka;r z&E2k!f$eU&kkZ_ngMWowa)5+e1kuBAo2o4R{?J7H|GdWsc@Xeei|PJ}2g`+>IlJ~e z(vwLP5(CP`eBv*b4hLbt1?;A(s`zOVPhzPOt>KlL^A6d(=OM}-HTB1!jOKu$i{{_^a(ft|jdQ3iTk z8aHFMy`l$2O6)ntj;*Uc?Fd4UXc<)@H>C*O???g)n%*?yZAMWvfnz57&uIEPW|w$A zVmFaz2>!=w|7tde@7KyO&h`7z=SbFvlkV+YF_@EKQ0dKxP`K`MOM~ z!a5wfb(#`)!=)6F)3X|CnQDo#O>lsuoV2&}sEpQvnN9b}cv0G|XS(_B?_m%RO4}c71o1yj_TO8Rs^jC|Q?hiW zU&KZ~oUXL-xzq0UXq>H7{7#pYd70zgC@DG_hdo*cIY(``m$tT)rO=aa)*!9-PRz%2 zIvJCHl4`>dp!3x8b3t8*k_v|0JZTOGTSIRdopji+FNCDGOxGnRFH)~-#YcXa{G7Z? z$mSUd>B?`$R7Nw6WPX97qtvY)^*k^@b*X*xn-3C0&q^5LVsbg{p4-+X|G|@P2rnLC z#zkb#GE0VSULo718;eSP_pA_6iX@vF>xIPso-hSN`Nfp1vLR5?S=MFmS2 zS@>&%ulqiND2Ualorl{U@377qwWX^*kY4S6=I7s;*)<^X6>a}uCP01X_@LHu>orIe z{k0Gx;de48`oBLSn7JK%YZwTz@Dl$FZKy*o2KTVFZN;1L>*hXW90E>158)vm?SGfh zQiQaq%o;7;?4sc}`vD;uiPT?&aenKIHVnqhYVQ?N7%pXFh(Sj~JWo)GeEgot#&a)$ zx}TIb?#9RWFapaDyiuhye}B$OhZ=unQU9lB9A$84a#UQGI}O*g5T6q_Efmn^f3i@8 z^^mi2^`7q+wxx2K*;l?(g-PLSnP2QXP=j-%D`HCXU18WnlCb156E##5&PxeWMdf*z4IBkSbpF7 z4%pV8UkxaLmX*Hu1Ig)^z?ED?KUX7d>?dgPJv8>7e~X4F1|NkE?8!WzoSTN$AloKP z{CnQFG2BN;Tu}DHMRZug|NFoo-^{HY-PF{g@OcP%tV%!ox46XBbov6Zckxm)vhBad zA-m~CR10gxT)OXTg>%A@DEwZuxoj43;M!sH6e;6ntY{Vn6q`v|ugnqrXAVRr zc=GFLh|>?ALDxOnT`P4LKp@0E>U-C_a_j&E>$KiQ#8Gpv-R8Q!mH~J5jhdSTU2!!L z@0+yY|CX1PML$61K24`m^9d|QX@q{#XhPx&NbirDc{}fnNaWTA#VE2@Fo*OV^i)y)={MI9pPrx_PK47pGKvcc06x!Zk*NALS%%3OD!%4IW^zr%;7c@@!@D_o>g?n9 zL{xu&&QEv8xk%D(MEHiQ4wt7HBdOE-U)-Au!8RFKXpsGlD9$}W_W%AK4Oecl7BNP9 zr~+KrW1z@1w>FASgP@@TX(;9K@(9@#x?B)274FTW)~$gDU)-c#T#lF-NuXfOAcdt z5&mkZHNIWzcCF*H7&!R6jp&?$xe2G$Ng|cxjqKv$$g)01Q|8W5s@5sV#|8KjoI+t$ zpUENjGcX=}&aBGvi*|^3ldv)u;O~~n>-X$G{=gYfp_9yiZKf5R`7-ykM5q#y_YME; zrUz%3P~nUftqLkfWvvGH-Uw^-oSJaG+8@WA3N%s5T=E%WPD-69;yJ{V!}eBgDp{na zjhUnvw@o*?GIsBX`YS8!d)G||prIfYDJ@hEefzNyNVDVQa}`j5L3`w;n}Y8Jxh)a- z|4+BoPv&I9&teN+lSSj`<_lONpsy7m`=bf8(NZcTfABX&E8hPEb#rrr0k<%yiQKM2 z^vr{@Hv853BPN)E^jIe~XCc*tqJilZhh44NHYt)D199>Ripem))QbWSd2aeY1wPje zvqPQ8>%o#|StF}If76~B6}*_1Y-E`kK})r`?R`r?e}E=yNYPvn-C10D8K;Qx3~Q~! zs^oU8oJyC)q-xLG63wNnH-NIzPR?A)k*G2eV#isJuJ}+O-BjK$3j> zuc2RF(@k8+j=Dmxh)hpZ&dH_m*Nq3=pYo;lGw{?IeL|~nLp<(3A81ni!s+MMv3MXZ z+>Yo|=GGAb5`*95)nkq{7)HZJ44jWP8@Oq?x?imf{ovTDWW&eS$l8Ay;SyxDk55fJ z&!k@0_Ao##Lz}HK^G7M*DO_f8;(iII!2BfVLNi9&MY6D`fsWF z9U(4s8MP0RKfCs5D&DV29k65sp4|dQILGP?WB-#eq}6oQgwZ4`7djajs;kgVQ6abH zd3CKPV#ve)Pp;G?ERARs0SPRe{IK@V>Dt(l2F0s38&s)~U{s*dL=EA5vgBqf?}z_g zzBAv7ZMtfNlzz#oC@vgvH%=}3Wv%53UsW=?vZ}FMNdU*~&?YXKXPK;nx#Dp6 z6{xQD|7Mv^=BIKJr5+R>nu>ww1jqNQi9)fCW36tg!~eBL9h2f6;PE&oqHYQ#O%A(O zjj7itZDeSnVXrm|zfO^EOA_OP6LM=aCJvPuaDH063n&~(EXYcV7^J{wm^b;#zt2gZ z2iN4lfyBqs(`8<3MhU3ZQ;8 zq>--=6`+=_?<>Q;-nYO^JpZfK69b&Lf1k1mc9OmZ(kT98TjBc3un*Fgl+OmdKxMtp zsom5?Dc7xyGG&qC3sB(813UQUD0A@K6G=+XmO|+n!=sc@XJ=?7C^6sEE{^z-L zUf4Kg3GL;xh=B~lB5wyS4@hRSgsKTAWQujjhLqSKpe@X(+1Gx;Q2A3^OG(VfDwcVb z(x7IVEsPPYI*I{hVR*JOiHX~*w+@f&%GE2hMeE)_vc_}l7XFdvNaVPD>#iuE>lD(1 zl-4Y>LrO5bQn{iFN2&re4}0@c*CGP<3DL;}jD)yIaJk+JQZQ!NF<+EBn`AZ}@IcBp zf=7DI{1h?E&C$1xA{o2OEgJb)sOI6c{{eQ8@L8x<5^aEI$;Nza@HSaX<30Oo?ekWh z`2w5G%00UgwNJwP^;cG|X&M`Upu>~a6MEcV5%Ag`BW&^TR@^BS z%&XK(#>K!QQ2(g5q1#mMCEQJdS1V7B!@!>;3{SAB5UpvRRR(4bbuO*3Tpu0%gh@Cf z?gap)r{^ompu&=JbKbWEEIiDQjZwQloPVU6nOUe}Xk;vkF3hLj2%vKXdG$8*6Sq{BLlOS#~{S%7H(dq|#QS`O@MXClo3Q6jf9 z|AcFAKr`T*+PqBAN908s&Q&*X1Ve~OcRRsK+0j14a9*ov@I&RVN(%?!Zw0GKDVeCBcwxB+sE$ zX1twf2-9n+erA->O$PX0j@|DwP;3wKbU7_&sUV0Ycq`4z!BP0VV~*O(LM1(K@% zhlcAP%)pDMRlH+=3W*FL(b*-BnV1x}qSCUn4COCXTm0DIr)(H5f+u~+{nB-*#?z>c zazma1Lp0hz}an zPKCr&IKfOvtY`V{B#gz%0DbS$3JZOZ0~X_WZIMfb`<1n3(HmO0&p}GN^~Ie(PEJ&g z?Dj!NaNxBt!@gaC`4PAF8(&$0h^7&vBattwp@S`m%E#t)CcRaA_}9M?|uHbK}Nh-j|t*pP|-B zghVS~qIl+HrR_Ylk5uio*p#I_5lV3s{uNX!{>(A%yG`G!Aau{+X3bB9?jo(IUY3 z`CAw7Oe}~$!2CNRhQ7mtlA^jp9`#l}FR1PP+DXwMZN(O;ApA!FJ&kIq^Ps-~_ktN} z&`RkZxe*=4*}Bn@Rn?GE4X_X$xsd}{%|f-V-2u>mv5Jj*im2uLp_l)Vnx{rJ+w zz?`j)2nMYf`pC-7Fy-G*fpH1*vQH+!~nJL``%ukMFzju?cT!&+cZc}KaIeEgV5My3osJ#A7h`qbFQiSkvIaO9>T`D7Q;7`+co?8TT;aTcF7n} z^+Gq}pZ>-_F}t+wq*D1O^5Tx2 zX8jl!enTL2{Z5P$X+az7+;@+UVhG7(Y!Lv#kAZoGkggc8!`i?W!cY<@0}MjojK!_= zYc2s{otnR0ybHU8T@C{m+(Ni60iio~hGI9d((0uUb+w|+$|*O1I2%=d>h;kq3x4wyvX3Nc_=b; za4(+Ux5vrL9F4+Pxs|oCScJiH1C}x<7XW{L;m51*fR|5nx=qC}@Zm`-x z{XtN}cbBvB00(r|mgfUcT zosIgC0(!`rAiQ4>nxxjp(1x%^L3z-}EUb?qo*#DY!<`%G0hDAi{sdxDDC>4Bpr}Fx zO_XUSSYV*ZaBn<1N4|v-P7gria6f3Io%M50<1+mnW1z^C$omNT3TT&HFG*azA*`@a z*RYE51$2B|K>-MBJ1AF_>nhM5xcb8V5Qvy;J861)lAL(nsOQ2Aeyq~>%K==b(0eFzp#V&$!<0+}DV+-Q>lmjH-0*AcTr%NjYfPaW zM_aZuS*Weq!d*Fu_0x)f&f3;LhgY~TuaY+6u`+2x?vHvpJ-WIQ7D8z?0uFb6ppO#~qCP|mBc zbi(`v3mxUyXTy-Dry_Lzif`E|%H9(ys5a0f-$INoUS;ag?wX_V*Eus z7NBI@%Tp{G;lFuGMrnFtk_HC`GH(+=fOy0-SuJ3#0>vQe8?L^vzF7}GK*QFD$z-OE zj(UoQy?iVr<32L!eQb$p#?O_cfJ8Jw5pz_D6>cn`{j{E#oMp$_p3{-SRH%Jaw*_lCp53>??MWFjBr zt9%cDciJ2IEQ!1XOI`J%Xi8A@UGh0THaT2UM5__GxD2o4sDP7ksJ<3w$6}Hw|E8# zrtq?jWFM%jtK<2oVLjb{1%qQWJN;(nETer1Ha62@oECNe1#HT>r8vOIu9f>QFsEJZ zi+9+qwfnD1v22BkP0)84#{?K2jnM8Lc4}qc8VCwyhtnw-_%k2+xiSDsmu+2(cRiP%VWEri-m|ZUE6D(y$F9Jw09ZoF?*d@a zrtIeuIEMv01jakrc#;YVxS@lh0oDyTw^H|Cz`$UL(~V>I)KX2uqck=44x59+T>1CX ztFyekD7OUKW0<|GZ@Ytb_STTu-cNJWAF}yV$L91Dz5BsDwJU<-R|@I=3p5AoJGJ`B zA=jrN^v0N7Z7}wP&rRTEK&RmX?KZemPi6 z_g|}q6?Uh#mi$;`)r8c~mIemsDKKK`#MMoVOny#TZ&?bxBf7Q_gPyP+Ny21%(lVR&ARo3lmR)XpjdMTv} z1f5950AZsP@B$Dl<2M!_cut-NBqM=q5X|B)AO-jU&f$3p2s|Nt1(26ilmHMw<9_)r zSxzZv1`6|2zN^~#;eMsScdhaR%BkDJ@0E31Nq)+*m&y;4@r5gSowfr`N^`Yx%TTiwI#8;ukVT%=@dCUZrgT*V6F12|Y+ zAKLFEi|byp*@dzquyBnnG@u|AJF@XClqv|`3?`Wk??u2pY6=&LR9eK;P<}sz!EpVx zyDzs;f->dYB|ob(1FH*jUY!FvgNrQIW{L!FWzMKTFuw_|RuH!Uf0Yezbs$JX!(l#l@7eF-b%MIOt*EQb3}u|2VhR-r&;%iP zcW}XKBAKQ$=Y4#PK?n;}L#cwgg)sl2`|H>{EEJ1|**o-H@%P3%^V}Lvx#JT`0px*Q z@<$KVa77B<%B{VkN&4`jkIn1C+N2O>*2RmDdLqb+h2lxP5AO>3V@2F)i2OlTF=nAu zhLzk}02X|pYiNg?gCV{S?dh~}O9zRoH-lWr3+&(H;&YM2g)4qOC*l6Cb}Ro*uu2%G znPtujQI$;A71dR$h>cyvfN{a&->|v&@c!B?Ek?V%b!v`VLo~Qo*0(mTQe^{oCD63i zmfVH}!K>sHD}CD>d^`!dC*}|+JrOqt!2J-mN?2H3;{L)1frBo#3>#Z zYd^5K9c(RRFqrAd$J*I?1{*zf^uf6W#;XL`dMiMane|qsN)^!FTa0$YG9NtA?wv07 zzBHo?2|m|AK??8_h90BOZ5F9>u zUma^V6FK3cEjCY)zzur$%mQDuKFk(Yun5|6N)?m3azhPJq+o|U`Wxy20(_-=sA?!x zFb3ex3T|@t>~!$^00pebsIWWE>lL@HLA8NUJH9NY=v@3DK_tUVcz&&Ji|>wf->QmIl{*GKyt zv~O4b+5vP3ZRblIreIhoRwUBt6a|9;M(+gOLa=%Sst3}kI1RFPS>To`78)G5!_P}- zN)-)T1tvp;o_wO69i=Im0*|RDr^~fSc8DPLhSX%{R}MZ#hyU)>Jhy-iG5Urv4SpD# z#D4qJ?b&%fnKIGYfsgWIY{cBLV+TLJcHs@W@cz&Eu^K-2_5UEslANIL{pJ62*-916 z_cw1t0g$GSb}Myv*vRXRvb6|X|CsdTuC>y;A9$!KL$5(+KyTDhWqQ3yp(#~z*x)f$ zD(JAAwr^Lj;C1djjF74C3}22?1um7~E=Yq04H}98mMWFf7g(y4!fMA<`zz9H|+dJJr~y1W`o_x`Y!9TNd4Pw)Kq68 zn^{M5vr%GQgC`l2O9JPt21dVFx9RJ)QX8WgZbmy0Cjr+mSTL?RZDVZ@6vkBH@6F`j zzunH>%V>tmdqGD)59a3MG&mTdJ-s&SX}6G@^~t%}7}c=+<^2HOi~fqXgfeFEPKXPw zkq^#82#G$gmL53h%QZYQQjXRa7P_r4T^8? zfY7{VKjQ%`tQ}ZeBs^Rhh&c^PBD;%SGngnI^RvDX;7Tw_!?XD@T8bU8%Nw3+Kc-g` zN`-gjF;#SY?vQj^`HX}=n4syo7+02{Pon>TMj}W(<_63e?piZfTCP-~0<2|Bm1P5; zDN_Z&+zy3#Jf0#0`xa$=q0EShhPFb+*l1bK{BwA_gC0FrNBf}YV98Z;KWnEww5{tP z8*4i#TR#1?j|33Ju#YQG!k`P zTcoacciHH`-WoP{nzBjG-7~4LkfZ((IqLRilf|`*B8f&a+P3qgx9lK;ZI?*)J=EBG zfcETpkgQfGUAugd=OY1+6R_;ppkcGaVymSC_x&0r4cl1X@8zkr=Qug*_vMY3M&}UK zyB6}s7ZT|7G@AoK&zcyo1KJIDjG)CQ?r~@5^>o@m6P}&?7>b*Qh6aA@nHiy}v74N( zsHMG!pWuHf9U$NQXnAR)ZXF;I=pgpZ-9naIuj*+7>6$1Iq zuy0JWZ^Z6qB(?@B`OHdC&NnU>SPaS?&j12_qKymN4=9Y)0%0L6Y1Hnm24r6;1m3F@ zB+7**gz`p1l5XF4g{DSd6X$T>>Q&#G0v1w-c39|hPu27E$Pp(U-)p0X4%)Nl_H-?t zd(4J3J#nmtU2mYrkGj}1c6wmHga7{MgSA{?QVOWv{oC-~2A;%w?d-iG52U?4mh2)9 zV+_LML^MH1cG)ubI_c}5ZOPtW_}(tow=n*o&<1UQTRLoTtF&+Ft#xFp@5%fs4wI{m z?C#dguZ;s4n3fCm12-ug9Hv-kFiZOp-w3ocF|MCI&!d<_Uv@hu099jcSOvjr2yqWEa7CbyLM4?>s~s1^hr8$@5kua zp@*s2>Ex;2>L43gX>y#k>r{e#v-AAEnubRxZGM0YX;%t^KF+ErlAqEMMnhwa-io9_ zg9h*)F*Yuus^g^;AXLZZC-5Wp9jT+Ej4qdJeR}Z7N!q#RFxl)*{dsY!|_KggV| z5Swb~LRdfRN#wZzk>GJK?82I*lq;~+Lb(bR2;i_28iGk>6~g6| zau+s~6Y@9m!Z#HIc4ijFS;76X3`+se7rFu)8IRJ!LLys_uxP;!BM3rpFJh`dAp}Jh z%87GI2y2@BP6C#pFhISmH(1EPvH`!p@=-V6wGX`Z&OCX8jVwPCg+qRdM?Ewd(DU8& zO4ON?)X~vF?QJgF)@haUWCig3 z)pY*_KuC*S`pP!DpyE#vU5D%!S z!OE2cw}(Ugd^Hs+8_xY#6+R7$)P1{Myo{9q-++29oD-CI>`)C?cuAZc_!#L8_N>dF z8yDZA^Y8zZAFJW{ul;)=yGTxulfFqmd1;a^j6}F#w3z#^Ci~*`$fGA3s7?`2=an~S zvffdOLsV{pO}X=okBtUe$?M7Y+@ZPu(y&#KPK6omtURU)EZAV_x^t(K>RN0Ri9k`o z=mH}P%}ow+GJ5%mhjKJP>HZ5=UORURg~^ReZ&5n#=W74}%9PRJn`E~OIl!S4pUct$ zUHH%G#kW2D{Bi&qJUkZSR;5@IVZMjl88iXG>O~w$SRNwAqp*mpJ}RX38yHw0XzsrR zDwl?>2`cDpo3>wW{DMPRswFLHNlT^DU5C4iM_3a;SPY94EYKV48G~E1n2{~VVr8{Z zu0kak7RnKeSx1KtxY%O8jt=c}Q4M3-VM!8&(8rpjj+zvm+;5?$kJ)*;Z>Nc$Yj>&h z1zol2?7cGWZq@T=kd^|3HA;&W2oI&z489F@2@`GzsTNoQU{M04L@}Tp@SHNCE(+VG z&|O&J?-M5;rKg_zxAg31{s;E#elk)MbvhfU+m)Z{UETEbC;u%SxbL4*(*BziOE|b9 z<1tpp5QG+ou!7lWfPl78DY70GD^R2ijYP5v6##t&N}CrM)eqq>orNiy(Ts;+<*W5{I|#B z;lE#b1-)r9+5%{GpH0!6OgzW1L$KW8YPl;GiWRk; zun?$7mtc1<#7zcKBOff{Qx| zxQ23@Q#_@kahhV|4efFaLp%3xv(oW?8&93}20msGn*s~!ot;MR zD(mPjD|d&rp&>hqN{30MP1L>rU$FEqRg=LiEH?__4>!})eAlAnkEmOe7b2auP}{CQ zWbeSc7bmMjU8xd`)T+NX+D-;jzQtQL(b?Had-v|;3KUqVz_P5Zt&J;Lpj_D~P@7xe zCJJ;OuA`ttlx{yDT#?oiskDfF)WB#ZtQM5xRzfZBd=%+qcO}ZH2le_w`y?6Nn`3hv z6uU;&L?)w9nB5r(@%eVsxcw@(nCexrY(N=>d0zs;&rmqQ_?Vm}jYK>FYgRMkAu=Zz zR;pA92Lt>scBEs6I{rci)X>CopkY-|iDCto77*&LcH&9~#w{w{ zZ50bj5A$ap%+{!5_d>}c0_K8wH=A^e78f>qJr_RK*0{)SH5E;D_2NFHQn7;|jE6f6 zya!wclsFK&qrR2`$_#;FB`&O%i#Ja#WR4aCyH&A!RVL|M*=BcT?$}zWhGGSZ5x63Q zI~K&Tf%~m;lT@^s^=W$gei!}y&$rO;u=MQ7S~8|nxiF(^adiJE78eO7njn)+1f55@d@9weC{_f=l?_On~Ol6cS5erf(xmX#9 z^XZiO_zEOWkfZtQi&A~p?`7^-8mUCM_)--#me|pgs$HT@;Mkv7PujqWOU8W=CVzJrK&+z)yk?% z6@~rS3Vy?GWjw}WS74}bY_hP~a@XSUjkQ8xH+nb};0ebU&c4ZarsMbOAy=Uo?}#mx zOE%SnK-?NMY*j!BUD)U0K2gRlDVDI_si`q?EB%|d!gS%Xk8kLLd&INnydrJ}B;6K4HSf{Q5eh5LU7T*Ke>$L5zb1MSyw;jcaR!FpjOmsk<|0 z`Or{r%3871ICH!G0R%(eaHycVLUTiujOQ=Np-jQ~baHVFD30YfM;4*^5lTdapK&F4 zc@m|A#;O59TC0s%V2&cbiOjF!z&)|R@_nIK3m9jxOsO`CyGukzs6uDZkO#PM!RCrP zqak|t0}s9N?i`IyMtIP5SR8F?tVx&2pIa=f`yyDgNo8ml82JY6H!7-ism&VTd%%-K zGCRX#F(~nKrY?9ptYwNP_D=@LM;W`Xe3Y(8^dE~EuFPc0cWEk<+`+Cv!&XIMpNG;F z8?8zuxLU+UgNAxD8_y!%*zKVpO-@Cqu8#48ET2nb5grRkrlGkhx-~USS4XeW`=qPY|d(7PAkqjxU6OJ{Fhq{+-$Y&GGTU%6}D)q$jErRkc6 z^+ENyYYiI`O6Ej^1`Qh46ZQ4=)ZE-m?d|Q<-Q7*wwr%5o@w>IPb>k~lG^{GhQLI3a zyjDr><}ayGVL)*2U?|1or_|Nzsl6Es6CI6=iXh|I(Nzr68Uu=y-}tS6!O!j3bC~}w z2lL(p7wVyms6TEYQ){Gc-BvCTK)E&pil5-5-s=Z+{H5DVQjYbT?OSu9H3`D`Bi%4;YaD8{Qm!g{^Vc%bNaQBYfBT=%qmMmBzxA76&b}ANc<;NX&Svh+ z$K3R=>U)v;`-BUti}hR=MKe)88}V&n7wL!W%cMu+dWX48=e ztn~3u*V4ECOD}!z|F@l5UEif|{O{G{}-MQEa}!`d7@^CvQoem%3^G` zfw5jdJylj$u&zYFa=06WaIdieE<3F}7LFP~M`Q66j}KA^c@2tyRYAF*S9vv56@~GJ ziUIKqlqlTk4O|)s(l>uJPH&u9puzD7wYdM5E?xLP=$qg8J)VC4_FvF=Vm>d0joxhf z_P73_xcA%tj^{I_Q0^CptU#Gc15;}>!{o#RA zT-q2t#<_B=-Z91y(`0xwOyi8EVC=!-f4u>Bha+R5O+W(*>D|&aPs8eAb1GFf?L4=> z1&3m#oTNd61`VqTxG}QZ?Ob_sR|dP+uq4V+tgIzUDO4cb<~trO!vFsH%K>`#w3mj* zgx~?Y{UOAI`HQmDS^qKc4wTG%=T8ymRJ929VpH|L}eK;Ef;fv@m^(#)r;le*chPUkc}M z=3HfA&cu5UAI@291sRPj%m(`3ix*C3--~zR-SW5B7v^p|maAA9^%GqlOVH_o82#{d zFHbnex#5LeC7=)YcH6jM<;AzX^!?Z7=|6vOir=S9%4bqribUm)sJj>C)Wgc^34IK^ zrE6VAJ`by5W)7C8aFH0{F2g2gqFlKGx{7o1+So*xre>o&e$HAzDtKBDAh}4{*AuX? zRVG-(4vmDk(m|rJ-a^}Z?Cfv;W+()CM;aK9(5Wkao@N5c?0GfFYsHc}WFIS4f9m%@ zh>IZANN9iTv`2!{2sa&D(`C=&i#Cs9r4UM5mrw6BtS)pOk7wO_ z%k|TLpT7Ijwd~{t9;Sbnqv$RZj?LD$vsnFtcea0$5vuY6V3q>hm1xkQLBm!9g5|>f zKr%H+@#F`Yvn#-+osR^dxEPzvxwP4_&Bp&CKEqNng`Q3;XQrVzP`YL4Xcfu_8Nm%F%LZL5{j&wgCYJGXluse zue4AZ{a5+@Pe7iCLJpe1HmL@R{3Nfr=HFb2Gfj;^~W9C;r zUikS8T^<+rU$|mpZIq&eeNp=CCx3&SwcGi5uje|w_|v~8e_Tg<+8y-RGyj;M2i|!3 zztZIq4-ahr+{Zpcb&dP@`H+8C>c!R9S|ax6K_ck=}rn1-zayCX&W4ymsRRs$G=ko{s47!=Aqoi@Hk+6XA*i%e_^ z>guqo^4^;h)tz5ZSBPa6XEe2it&@7Y?exs?I(p#AzhPImN}ZJl!yo<8AN@(@c+D|4 z{vur(nBl=xA%p;$*y6%kY+<@Ke8#3ljcX4Z{9+-sTxbdv4H`6TRX`AxVyozMIzXxP zc;@Wg3kdKq|4Lx-3&54sQh+cJZlxe7Pb$`@@MR8V3-VP82(g0{J4p+nd>4Wqq6`o! zgV_d<2Li7{sEj=D&Z;HkS4N(4UM!|i0T4d|LU@!H7Ap|oKv3gy8YmtYJ3f(%%ar17 zM&{=eRNvS|y3`CMW8*Y<>k=hWF$yM<6iX%YQb$KCHMrS=Cpk?MqaV`r)F2O>k2F3N zqq&fd^G=9w0il4yt|PlmM+>ZOKfL7U0eqoIKv`s*3(taj8{<0eL;Fc3mONK3LSf-f z1CZ^mJQqsp$rIM`G#iM})cg!hFU-*JY?wwpahjQrQJjs_B;`^do}g)V-^AQB-5i;v zo1<}>_Ob5>5qYCJRrU~l25kX&6s|)cFj*?_?Begw@4KjHW#5J148cCD0gN9AfncQ~ z6^>9G#aV(dsgO@YUqfGPYA|t^Z%7}1*j>aO5pnknGk)P7?)H$LECvUq5_NR?>=3>4 z?m3>$d^k*jpo?M=7md$YvgeV;ri}c2Fyx}M=SQ>WKR9zM`^>b*nfJ_lXX7+CYo*@Q*$A7~ONvJycs;OSf*_;^!J$3|u%|2vgcb zw#+Wj`o=a&#AD?5dU%@#QbK?M!KMtV4U4uyYmJ3DBSj)nZlQwrSu7TcMx%T#t7|ln zm5uX47?K8Zm<3(JdjY%`n2(0YnHkII(-@QJSCs;NT`DZ02v_ET@$Se7!yzah9*t!C zaVcO-N+J4c1Lc)*veaO+8Tc5)7{@rmw-$b9A+W=?n5D$sh&-ALzJSj?jP5JWqi&@Y zD&|kj^%Cd{l1?k1sRYOq?FK>o!M!z{KdE<{skPZkW0Rs^Ztro>o*hnpt+~-c?piY! z)}t+zg1+20EH00cjsF^a2Wx%^nUr)5bC4Vl5Z-eaW0`J(@s2X0zgaCTS@rz+a>mO_ z0fkPDtN12XF-D5>f>46Cx7yfzBz`OJx3l_ivbM9acWm#l(LK9e)Y)VqpEt(M>F|Ap zn;?|WEKYj%jEp($QRy$$6Df#z8z6kUs5R7wLxi!W;zCoE*2GkR$ z!>kUStnRSx-O*{IuD&m@t6QPI%Evles{D4wQU$?a%dk{gx00?DYg6!QSgL4@f(8v5 zwkoP_sRFDrdB?&|3U?uFt>$hSEEYGCr3zw#Ai#BkG1AzvsZ?OB_b#Er-J?o{ibSFH zhqUleT74LFvMu$rdq-}U=(U?6E^JAr7k_7Cosre6*y(v^G|B}tO4uDnZpDChc6Ofh_Xn5#Clq)6avB>>};37uJ*zm`+%|>;2V|wOAVXVQbhvaSBb@n5+8l= z7%fDPXMW|7WUJJA^H1reQ^WlCPyS9vPK$%;UB!1SR|`5_lCIpD=awo*4vKT->@;36 zR!BOOmMVMq?&Ve^P-qk|CAE@i0#cRdiigJ#&-cr#ms>qVSHUO_fy zaUOI>UQ+|UxB8YUu=-lu9(OD9EmhR5JXYIM1#Z7E4<0?}=6neP5GRr;MnmmvP6+UK z9=oTG-I-?Zj&izM@3zvpOJ0I&u7-?-1yIsbh2@>KRGBGZsWPFkR8e3(ELN6lseZ7#2nQ9pgi$>!#H91HB=eJ(wt_qc~v8KMKzlI-g z@9pMs7F})^8^cNRPXCHdUklJAqcZ|JRf`i?6@TH$X2x^m=$o-%vqK`0{|wxuzVOBz z7wpP;RnlSnduJp>>4cT)YV&CmHUk^k9Sn44Ao=lNn@^iD{edMa&%a1ML@AJQTc_z+~K7N~`2?vD@ zk1{&W@=Q&TG5Qw2F7wo-BV>-e$j>SBw8nl)>12q;=jy4U^9g>=lsL=syhZ-7jgr>K zMV@JvXXGuu`DY>hw8)cKo?)5iewJrHKbCn8P1aFc???DKndh9>N`{&zGI>t2Jm2Kk zXIMFF3i7-$v5R`PAL7SF^Gw{LJL5*GZF`z*Y+mJgM%kRo`b5m~G}YBNh&|g644*ZmhHqIx)(5k0CxB2Rb&ZhPiUe6x1)yY8g}yIP$)!Z z-5na42@%#i9qs$cV6ZSoEJX&IqT9n$jI&9yg}#NFTK4m2B9RE$O}FV5>n9+wZ7n<4 zf~l5YOT?yWYIdAriN(*D*n5Vj0{ofghAy%>n)x+6Gc!9z5yo6u4U7ToxR;-g#bRu- z8fMRU`R~?(XC|j7D4t4?MW3ejPQ^1cM#Gb0k*s_s9P&^wFhc%F{xcBl8fk_+yP z*5;krc1Xp?X>1ZqUB4q1 zy{(O?(-wY=XT07?n)9=^GotN|@$+a06AjSNgjmQapGicg$>$qob;=gwtTS|V&c~ z_FSF1EJJi-&_gjcN7uP(vh5I$`6wQ~MN+fsSA}WhA3jy0U^;G8)t=rV+i43 zHBb%V%|=zK0BVYrjRO8H1qu~>!>ysEl`0a2iiE*oVG3V}!gq~xVSkFa6qaVF=j}bh*Sn;F5<+0S z`IIUU)z#3fdOCV9c%{-KwLr7ptgLVPhN?FhDV-3b59Sl}eNYiH=IU;hJstr$N2+|%^+-})NW zx9w#4&d~JrKcG{W18n^w%A=-G0kAgs(nnhu&r#WY_Pt*Uq4VTakWU#+O+t8z`oDcA zl;Okj^F%wF8R7b!FLd&IuTMWoHBCqPwfgj*u{HlRP5O3G+VvTJ&YpUcY7K95rO0UX z>s--dObt_$;V=31i_>4H#-=8I+@|}V`Cnz8jk-T)YuqWGXVSsucSiVJ^cFdFZ{_7_ zqG@)om?M^xr-M#YjqVk;_I1-l{L6|w|C~Q_ar$eDJpUK|_sY~qsjgYB9)~&8=o}eQE>+exZODlgKd7|v+N1vnZJH^^v=J|K;@1y=hPcxcn z%I5j@xf*KP{-wM;PhSX=vFUfSdA|P2AM(E&3Ha_wMq6N^w{yFLt!YgZ<#V}?TPMDM zcAi`Qt+nN+rdTP&((@1MM<`X&tk0S6YNg8Ra(~sr>hTm?3Jcx~jDdW6Wob4)`2+9J z;GNg$>WyE~mFut3&D+1?>BcSb8)YgnONYoc;?2dj8UA*Tp`BTjnLq2@t)D)w=-vj;F+T0nXBv>zgGw= z0P&3Yp26F%X3mOd42iRJnca_P7CgCN#F5YhTL6o)4c*E;17US4a-QFhYszP!@R=AB z&kV5ok%LA&bCIsG^Osqgo4Ux)19)b9^bLM~fYnbTA(&OvX*zb5uCe#vnrAxq43q{_ z<8P}zqf1=nb%tw&?JzSbp1E=J6|OV_&<+;;6@CuaCdP7>15o(rqv9E)Xr_+<`qUuH z|5yC{=pC^`2SA-BLvQi(S6DfeZHH$@?ufhw242aW70);g@33!ug@122uf2!q&X9O! z=$6I2qKMY;3(NOYLh*X#WJb(W{H9o*Kl*>6?0LpnZ6(-W`p^EcQt$~tu# z&(lqn`hk)t70k5Vz%TQj(Z|p6cjMY*!886@QE%uc(P*w6+|~)k+njux*AKoY6v)+&nJ)8lcm`>D<_(tKR80%Mx7cFlS9J9z z=nNb8w?KbhW0N=g=D}Z)XZ|g=2v>i$Sc)aCQ7S#jTBS+~l~n=+sfdw*zeo@|f}w}Y z2_yt?--ybFYQkt>3yhZ45mc`PP-qn@R8|v8w_9-M1%(RG(v)E3i1T#M{xluvPx0gK zE|xlsyzbxg32lL4OMsgocgPrAh)q)5XE-K@*m8hf}=W zb=hm{(>EkdlLA91h+y4NbyVr|Y^;w-K#>CF26$2lY-EAZQ3=Qba9#GaGqdfGXmv@APT#CvwQ$+KPcj)`|RZc);|b74&gBp1lADhV|;q%W7+da zXoq4-fwcn41?2=3YH*zgrDQw-1xYHgY(H8`V6N z(G1aa7lp%Nnx7k|kbjJyn+fjY=a6RDdK;MZ?qdB<$Is1^uF3vU%FmtW2y9=OTNud72XJ+u6C9 zz_x6j>4=c~AWyxyjh~B0rnpi8h!`Hq=IJD{{`Z7;XY;hA#72ieVlP>3HhxYYzs%1e zPp7MSQJ#9o{nz50(fif+HwQsYHgfiIrb;hRdx0`>^VG)BJTHT$tqB}e17;}I3 z5Eu;_G^_=%GpwV{!s!oor_0pSW#vL`M-h6o=BP3cfnB-MdIY=svB(C)31I<*>Vp{p z(e&)rr@Ihz!0lCchm~8gAdvlfCA=T~4g%n%;4r4B-jbxQI--XTSZP}$@!#f*kQH5~ z*`DIpWNLM#$!*RFgk&E5ordf^x=1vehr^blU2RdGe*I|+edcj9Ki<(A<%))lf;RSD z4;`>kU$dU-+4spLVQ1ed>cW;y?KNp`K`McIsJEn8ed_r2lPuv_qNh2|zCD&rU;Vg^ zzV<0Q?cXVA#K?F~cnoYbMcq^HVaPOcWP+Hu$^cwxmxBm@Kw=cg&Z~pwh@#CL= z|3A{?#00-b3QpGppkb@3Sg8_S#=3q_S8mM1QUpqkUAu&(DbVa({4!Y4+EkPT5(x5N z3V83q-kkCliX13(;BrhVRcg)YMT~Ytwg5s|LP>`Takf6}Oc$Vi-ekf630RjaFcYDL? z28x#DC{{4`kPj?AAlyP8u+9T*fYO4$gRSqtf5>aF48b+-9!CYDtWlm;3-hc@=#tyI z9CY${19$E9#K|UZf#_L?5n_l*h!}5rR^~7l)*(g?zUl1`JOuYLDb}^F4Fu@M?I8IA zNghZZ*C5a%9oiyZ#K`FiJY=Q<{9*jQzDb6 zFD~410kabs7h{2bE^r4%23}_W>R35DxxgKmofLV(A|+eSxm&DJ#n|=5_wc`fZ&nEB z$9)I0d5#VIE&mIpNH))j)4Z~L(Izrm-TWNNo=%H-#-GTQGvXDBo(V;sf$5j{Unq&3 zE@5rypUEkntX82g3(Q|-Z58G95lM@=7|t$~8NUIsDN>nd+$-u>w3~w; z#{$>*U*wt4ZR5w0&^$Tx!p-N%!qIG=)`Zybs?5_E6ACUU&0ygI=o4b|t7tdr^<;ru zMq$yZ%(F(9Q)W4wqCQ=Ep(sI~@;z3ah~*~QP2{Oh`?7iZ69=<-4iEm6|6K_%2SJ%G z=cQ`!jZlQcjVP@1W;}6v@60^C`qnJH@$MW~XyY1Sw;5?iucM*_UScIQQ&X&z0_s&J z4TUJ=$2C+9TWheH*;=Qu9zmKiCo%w0@%!W1on#s|Cf2?;-i?!uhSdOQ4;UJmw%*SB zd`Nc|a9|F0|HSudQ{pM$ysJkU6RJ0gG9uME^ z%HD%~91nNOSQpuC?1RObmhW36w4e31M~F5*L(!GyGRf! zt~Ef{hQ}jx{dSPxUI~kKplXVhDo+t8)2Bc2G(G?PXQ-~Bkq#WXhqmwBMW6rmFY@z! zy~4d^A&#B=b$aeM{uNJ0Pkx>!`MVrA91eQ&@ssq~&wP@4dbiVW{m$>wgC`&63Gdyr zTL^v%apZwdWZ$#*=(Dt~|B>u(?0{9Gv|j$zvx0bNuR~FLd+`!y^^0O2Dyn0V@@6y#%3tQO1d4C z5z-O`Z2~?3!hghbz&ZTJ8VhT%hI%u1i-qq2FMwEFxJMZry&MR4bFktNN)jkn@OOMt zxK@M$~u0_m{^}cQ0Z*T zxigH!+~o1K(6pz4CTHtPCSSnL$}e~?)Him^7Xk{}Qh)+O3bL>R!!$J|gywm9UVEMYg>YRye~q6LiV`Wrmw6^rW{ReTE9+p;!<9O~ zOmHtFlcFzOz4QzI7eaiQ=iqIjwm4&eexJH#L5V643=-c4eM( z<5HQmC#xX4b3K=*tj{|)q2S8T6N)D&MwAL2cm|QmET!^gZsceD@6g=gY@XwTLUAON zFJjZhyyq%Oj}*%V#xv$1PSZ1+`!K$74t(5lfwdHPjg}^1Q4byq3h+8NHn55IfNMz5 zzDj{Hyiz`Yvnp1U%CB=GgfR7 zKOUu-xfnOU)}UdlLnBQZ@=!&d0y`-IEKm`r0TvR1_NJ-3!@`(5GwF3Y?*AJ?7Yzm2 zvOM0}e3TT-tzCQ>-kre=UXI{hhDU@BiaJpuhK9zs=M0zxH|h{Xh5v zcK$cHKXWy}eTc>CSd^?bu`{+DeEEyd(?9y}exLrkfAWX?op?8n@!lsM?&JQevEY|! z&rSz5Hds~Pi=+m1#me&9;M7|`%Lc~3aP|%U8?j_gy(t7i3JfSx9=^Yx#{fBTtd5QycJrX?*nlDPDHjl=ppKw`#dpDF z(%}O&w5!iSMw5;UXP`tu^`MX88k87#AIgGfVL6NPN(C+20&ce8RtsrjIzrLt5|y@0 z9uq1j_}KCtv&8*XV^8UZ5ZT@P~Bk)-C$VSH42?^Ye7% z$dRlyUO6aKr~pG#d+FBXaT=a`h~nnYk-6?Si>8F_cj(E-{tfNf@u|$yl|!k(2nK`@ ze=aQIYyeUz0tJQ?;@`fN6WB||09U@SW>#7@AkP3xxS+Ihxt&pf%!T^0Li}sj7F)TD zjtE7I(jsMgYJl;2BIc3OB4sf1ex(rq;ss$nGU?lywV)6R9a(lUujCXurmXb{%07~L zztVa{mJ`YbsVKR4;qUlgu58G>N9Kw8Nb1Cf0OX1C1LOYtvU#38^8){?R1(Q@DlI)^ zTcAFa3LPW>iV~?LlHU&HOSYUB7hBWFJW+O;C(0NO%`Z~E3}qB-$~@1VMf{2UJTEBg zBcpsleMG_{PpN!CxuxO??Ix{$?%ZCPl?oIph;fC#gTo;jW%CinIA{`F<$*q}M6m)T z1$Yg(?Sy3t6xpD40C>Re4tw#n#45vNsHN!{BY78CUk+J$s&l#7c_-=8tXwQ5;&#>^ zy6knNc+|mol=AtzN&v-gB4K3jEuQ>-9qSMJMJW<7ahk1`uz8}oSl@YSJ+X0>D(kf9 zs}44G;Z*?!dNSj~8;ch(oDQ3TYm{pc)Jey#GX@-H*@e4=G^`djYCqeE<=T2O5O4RAGc+Bxz+zL2-Zf%B3VV9*Oy=msW9K62F4q% zQObp?@Mi^|u$)J+$wMh*gb)sHq zY{g2IhY89f%j9a=#p3}eq0<}qd7VLhSG(EB>O3{Cl7#T495|Z#$ZQvGRFuGbn_Jvm zFriEkP?!ucm3N91&$x>z1jcy2V#UJqTWvs50$L;M8Ne}Uh!mVl-|7fJ57;azvfJ_l zv_l9D;2NyDpwI%a+ZDi1q$DF_Hk*;prGT0nJ*6TB0wlPP0^~c2VYxzYDWrxX19_nC z5nLbN%Pl`x9pOA&n?S)dH;+whQErh5MUmW5i?x}u9!mj=5l$c3?Y-SL+P%X;PS)Pw zIgTEz<%$Lad*^}v8tU6-=Y65O!^W@S6%eQcs1qpQ(T>xsOh9u3b|16yvm3F|uG&Hy z^as2TN*u@!b?hT779B4K+Dqw+UzT%QmyP!AcJbZN*clDCa|kYv@7%TBnf=DLRtw$7 zu3-}k+N3D(isdzT+1QAR6}X$jPIaUyw&q9q&`0z8UGd6Er;-#4&T=<~fA(i0m^zM; zzV)qd(e>-s=`a4`FKB*lnu5Mre!Udb6e>!f9ihZPyppAo31;!j02CNmp?5}s0HL?e z*vOA(riJARfLI+8Tw%bfNokRCBWvZ-nN^Bhx+sL}zDRS{B4vCu7jrh0?Bjo7*&vk- zut<@4Ub-ZnS1KE%LIwhRDa4o7G|_}TPoX1~4W39&p>sW>6q)kv&MJwr3LU?SLMK|6 zRW{7ek7e^zDjVecp=^+ffitHUD;t!`mqLXO%C1y4a3v9gQb{DssjLr~r&9SM^3>(E zCGwn~7gj$gyUg><8Bxw*&yj4N7c%XZuYAF~VO^9{zVP}8czD^B^^q;RLitjvK4$zm zH*8$_5@B=xGJ%Z;UN%2~kA{K?t~YtiGB)1k*xVs#dPezN=A5Gj(A+LIuOPu~7ZQ~C zuwYq^LIt!EN+6}Bq>a&dJL3b2C0qxL1{*cI4^w~dr>NGppXwY3DdgKu3v=7D$)ej$ z4pVeuFp+(vD8E36FOdwYNVMN8$|-U*@W;A`91r{Grfx@MtW#+blak2)$LVH z#w6?O#x}l5LYY<%tD5(Y=S_`kHyR=*tnjWPFC7ud&aN-5O;J7;!C`h>%%7$*;McbBw{y zG3LqmY&Ji)Gnl=WNaC4^>@!xgqAY2D-ZOede#&R;*4)BUSMZE18=!o~WzQ{C3!hPz zTRwwtb=k!(5dcB-*#okyy7 z6+EL;Jmbg-V3LX4Gj7LR=B$8xkJB=lS8u#*>>QHYkrPAOmZ8MH$ll+P&MqbyskGhc9(K;O6nl@d9SWb>Qm8Ty0fvXWs9=A?Q9UKodNx*s#UKRWQfPG71J$slt72_F4nh(L zOqw$>V-UNj#$}>ePn^4g!7kNhFP@h53Dy1XyH}wCVM~BKvm(gtdIPO$Fq+6-dx&h# zcKW~B`wuX=lI%PXJz42ZdGD*>O~C_g(SEw8$B{k5v78|_^hP4J`z@cOCq2CtwUTz9 zw4$V4u1JdFa70n$_!&-*>+WecKpV7yZ`dlJP~MyLKHvExGBR)8x|x+(l~pJJ^>-g+ zW#qkapSY;q9a-TEVzDUe5V-8w(w+USrAhj0SBenqT_6a8 z3=D!+bt2YCQId84W6BY%tJp3^Sm|=CTyH?30{`)_K!G*I;eA!~@O`yH2_OL_lSwFp z91g1p#t%L~y$67IK|aOK)3QEL*V2Lq^Ss|57kfD<9#9W(#{z4UP>6pE#6){I?1)v9 zTNg9)QBjr$j?~fqJ-jz$I)1EP9J*WdE!`8Y29>-nVVqvO;b)%6BwT^v6VFHdPi>t* z(SkO|0YF&C;bb-51An(RImA0Q;_ym5Nx@K@78j%9{Sn`1BOF}WNQxCv7R3AG?uGsV ztEP@NC+~AoG&2kS09R?thQCd`KkMso^8y9u zFUh%%_l!nZPN7mxV9v+~Z={>cZzrqOMk6<5@N@{xE32wS+T@6I3l)gglE+gi(q_ia zh&0qs%+w>&5-}eIgHqWLh;I>Tpz*W|Du1MzTyBp@8@`!+PE~b{NSmFMF+t)9E7@GF zA}tb}7B0nrFm2D|sbaazg|=}$Iz`&Z4H**zF11viBR6G$dRTRMJo4EK)ABh$yrNg6 zq3pBMQlaCE^ewU{Iw~!&IK+9%H87a$6KN(>f^H4U`tU}&GG)Jb_WL3Y%9onjI+1q$ zvV6{*Xx}Q4HZzG>CcM@pZ9*A^v_#BLQ)xGDXv=J#e<#wAr>c)Dm(peDJZtOfMcSXNZ|BaPMbp+T+xb0OL^)PVl&U6=eLtm=HIzt5j}=fjc6D`$ zI8?>b-o1Ni_x8u=fn7E9DDxJ59S)&T+C+J=F_kLC@q?RKN2rYj7*qs~#wOV3!%3&8 zU|7NE;dEGLBGAFl3)zm=mjykr_Y5<@*+w>nU!@%_FVmim*J)eF7&DCWw@`43(|;;{ zdtlF*OgcJ9GI&z_wx{DY+S)Om5sX8?-Ch48ZRg*P?Rqaq36kJ@kiN6+6~1RIBg~KR zJ*|~5h~JLvc!wG4>;@p}dxy3+|5VVf?%_Scs`-gX-`^t{H3i??Tbg@D(y0<|`aY+>!1qXBtqO_IS&Dp-A7^_A)`q zs1V|I=&boMZEgGs?d>_wDcJ?lW8!hZ={vbjwTcVWDblm|WD%T~_n@ET+!I;I+_S$| zGHVL)z|S(jHB@JPwL)1}Ykgj%AKEIJV+CvS-ON3$^~Rf{O=O`20uHB{ZVrcq5~a1l zL=81KotdDULt!BRsPwGfZ|oh94a^gUX*Y#ThcgsO%9DQzDRSog?oS;^|B}UWd5~%O zJcMswe07WJO2%7l{i z2H`%01Q5zY5%<)i_0-d0qN&Tj%k(>jl!#8Hb65%TzktaUrrB%1$IrmCm(t5GpP-9Z ze8TmPqBq`|7pF^$L9UQimIG~2NU?HbHc6*%Ml*Eg+I#fEiSG!yF*iv;p0%RpC^>2p zf;`(HSUa(Qfomryl8qo^s7Qs1)@lWUrhHf~-by~; z8Q52$4cd6_g~9^wJuwv$iUKH+P(Kjzz!LxtR$w1uB|fkpiTY zIE`$zn#tvYkP*DKY?nkLDSorr%w)IYB)>^of@r#JIFjIdOw`hd!*vz3uo&e&B>m0r z*y<6=39aC5wMqdfn$W)JBYMTh_FngrIYZPR{{y$Fc87&rZo8;E^raM+QMmcSZ~T7v z%}_yxwAB@R#n>o{74%D+wSuZBHDEb~%8kpf(R(MqOBdh&DP6m8g07x_ZCM%}xewv&Nh;gBX_TBV= zbwFKRogk&OuBb3)(x4nrXlQ5+Y} zzZ#pGL|QZ~_g9IOO$dXLmW*YutE{XNX?9z7%)p{V<>_CP`{W8Umpz>p4rJH1#^z>` zh5+#jHMLw$PP1qZ8amzbUXTi;Z?Hp> z#gHb;F4OD|M3a%7opOaJe<`#LK zUs|rf?OA=M?Ae$?aAk)yZCg5>&P<*Gue={nWry+yfRag-JsHooWlfDNX9YpNBm1Vd z?7oGpoTOA>ockq8((nv~V?A#5xPITBX$*=7E(RU@Xu4Y%&@1zbMm6sJ&w= z_4f7%tJh7G9~)Dta>pY7qI<_f^J-w4p~Q_uP0UPVgPde$)SNjnwk+=AYT6Lc)bILM z^+s*jJGsMc4wgF#W#FUgY9tc{b8F^-=^#P43F_ph|( z{Qg(pj?(e7;`Ms^>+f>;()3r~j?$?M*)mRYUH#~F zcg{8c?Hh}nF5eS$;d))p@5tl*OW8bReLHim`Ri}{XiAgEWp1Nj@ZL~DVrY0Q*|tK^ zaF9Z+Jy#I9-blv%bgTb$T9}bad&G^vTnFS+tU!pkgvi`6OEBcuUPewb~w;y1fPDxXz=c?Ha0i2VU8 zq+7!wp-eV{iYEgXTa|Ec%s`z$xSbEyV)s7=NFRz7?*Lh@h2Oif(k_%4==(^6h03)X zK@r2mY_7;Cd(eJI4^}T}zvUDw*ssCD19g6DB*b$@it8NK9@4r8ia7*>W+N>{f9sv1Jr7&Aa1EmWGee;TDF z6Nz+Mwo;NwnHGy>6)h0(;=48tP-)ux6S$w#@RG;N--m@E%Y z%qu|Ys!z+!Qw|^~F7;`EN|OS5nTEVXnx>N^P{*96ExXACi@9RUo_>xt&ve=2an1Xr zp950Be5+3bV)1mI+IlZgcJ2L8=IYY`m9|{jMgQQm<;uQNpgGVQSl3M4b`@qT)iqR; z%Ol;o32Tyc7ZytC+X%fv1#>&r0OeL}TW|J2(T$O6np$WVG&bEtw?-=|W$L6V=QeH= zthHDN9n{g0d$6liV10&_=4uIRbUAVL))tzYuTOuI&?}HPv2tuYrOF-Kws&`@RE#ku zSj0{NLtuAW$l-wgfo%+s%oGMog2#H{Y zf_W4!7V2xQ%p_tnloBU2adH)#YFHH9b3om$vVO~nP_UAM0k~Oc7F1Q)D#+<>qv?sU z9EvBaxn1S&phUu&^ZUZ=G+FG~-3*(ahv{hUTWH$ZXC2?!tRcF63MjidJ&@d#tfUh6ROV@6NC@W@>K$U&-$5Zsm zsRi+D&{w~W=Z^7nrwyMgg|xOMg87vyRv-W#(zx>ia4*`ikRTX!2!#xU_*nlC^8#~{ zx@Cgb+CkSm|vGeZPMe&J%#ILmpqJ z%Q@XdUSIYQ#d^a?q0-&q5_3Nk8z6P?Vm$%A0WK$3OW;M<8sHUFT((WD4i(T)-7eb1 zodcIkPD(hvgA*zUDr!pcL|YN3p^+dn+d=a4z^r5@eWja=<#D_F%tq+5%alR$^ZJx_ zBh<+zHgR{Mxxq#?)fTbo$7vO8p5b2}zQ4gFLZO0FqxTFp_iJkk2xzbw!RhTvPX)C# zA>efdP0z&07f6uPDf^oG+{DI&c8GNJ9->E{`Fl&~_|w01+sD%AMAq#R1Wj=N1y@a4 z=oKqDScme@Ob^r4*t;U0;47#7DEpxGom4m%@+S+I~q|WN>y-Kly7>th} z^w1|Bs;19>sE!`o?bO|apz`UP7-(}?)Id;=_#SWxhJ6RtJ-ENRbj?rU;21^2({%BQ zUj$rNF2JCan4cXapKp=QUi1npgi@_J8|r00gg<$uM1q0^%AP_{mJy`_^^SMLCoHxA zSOY+)4?sEBP@7gNb~yzPfH)^8=j=jMv=LCMVg-B!o{PZrP>|qSSZ)jsg~T4Nt;HdP zIuJ-9P(I?9K(SI?X%&Y(wCL${Q5~020m=@PANSnkH3iRFOGwvoc@!)BY?K!YB)sFm zO}t}JycgW9;Wr_4(^XNqPY9O_>#tZr-ZFoM0^@+gsm|kJ2c>4Szc{J-CjAami z4r?_O^H`_XL&=g)p`snD>Ttv+a)G%P>$Jio*JHUAD@JnvyPb4P+9pnU^0(^s%N+}xKpZWbN;=Hu)4;)y=JYO9r2Du8TK0uwN~2F zQ03)|rz;XcY=5E{y)0^)u3gOxt{Q3R`uc&`0`LI!0 z?xf{<+)od=u*22A{)+H}Lc){*_jF6tlzg}WvQ<^_4vq`sG#pg_PWc5K8eQlpeg z`h}oS#omDB#B#tmfuPgo>?C*1Vc|AKcipz zwLhXSeDM$Ikw^X>UBBs}+3_q*4!h~<2R8cSzX;L){gp6{%sfVqJpKpt%fJ2~=~ut} zdCsGCiNz%ZAZT+ac%dXw{RHbElmJLWY!lQoJ|QfJk9PnH7g!^J&`+RH!8;WTxRX+V z@Tj3)mThqvD-{S~S3C8g&lp((Aq@vC6fjR?%-|E&BoMHpjet@VE4ZeG-`8$43*`w; z|0C!)VrD|YiQiGjElm!gVCiUe3V}CbZE1nu^a=>H;cIWr2umT96Q_37*k3CcDpt4} zlwt+@R=BrB91y%CzQg(l?}%%P8QU8L>#tamz*vKluYWK^m#_I~p65)=jc>g>&tpKk zlheYUOG#+b9|0riz)!VKS3FSwWpu zcIvFDrESgabZEx`dT9SH`uOoy`ngBy>F_d26=1;!7hC!HqWXr`9Cw%sV-sOI@%9|^ zKy&oY>3JF$42V7jC=0f`8|Xu8-;Xx2@qzKv$m^e#$2G?JnTuX}^PPD*f5|828fC$$ zfCCJ$Y6-$s-+WA1I0lwGIkE~Yr%=HJ86lv@00G3QkrJ5T+mHMU_uU3JGgRR) ze4(ZUqYuHJO$0Wq5KK52E->9{QiH5#KD`<7Fh2su{`$?JAe>ZO2&IIHxH*-iTO(nS z4qwMJ-UML}>gIcJ`bFLokQ(ryG%L4PXzm#d()2ttQArculcI%%So)rzI9WBv_we2$ z=N{1HoV>@y_uxdFO2=jn_h7C;e%gERoJhjN%%Tj=wS9~9FNulhTz^@IVPc5Qcy zlRT)eQ|G)C=6f7`kC!J}X!Ma6PK3?)W&f$dv%B(={8a@Aod1bLy7_sCOZvwRQk za+#AfKBel1-)AO9fvAaik3`Y1x+h2jH~D=62*$|os=H?*eGe4YsdyrD4?bsn+}3=L zhwA_?7Suhs->>e8B{KB`6Z#o%lH%!m;;~f5OnZ1dO1CCukWEV}dk@-smY;)ma9UCn z(6+;fYzLr{^FuIBxI)5W|Mpq0D7TC6!G>4egFb?LL_2VMx3}5J#gz!A;PeN63dLpp zn3CLfy|V4jUG~!umo3HRMtj%sGb+>8Ru`{_$jklI!EGAkvf&+-KWxhg z6@Bfy6TF#RASX8{`l*}Cw`-epJ2T7u?E>c~`W&}IcL#*yGC=QJ?|Vg^3Ts+!has*X zJZFG6FWUO?E=EN<2!e;X5ZZzJ1Gj@J8wleB?SSWF45{>q$tW#EAkspeCdElo_1o-X zg8OL&zfV$(Rh5o@waE8i3^`0m+PhP3Y8LqV3)g~TJfMEu4pXMRFL0fX%p}AZLVIVQ z!}XSaAE34d?jq#hn=l5H+1RXtv?oi-0c_5({wk>W0T?gK0Rk(Sh{M0S#?`N2wjta> zzSt;O8Pu8nB)a5pvUP~l*l;DYmVlsGx!T6OpclfTJW9vb@j;QAh&U4Fd*)V@Pm zaH4$ZJNO$#0>6zp3h$2hL#)SQfxMNq1zdfhju0mT7@IT>Xs;mFwmd>t)EnwPAEC@D zm_Eh>;!|jWSUB2X`$m8;3-5}$K-=IHF_c2u_Jj2g-ch?&;99sB!Po;Iina%#UqHcx zdX4b2k<k-bkT>d_K756J@EZkybE3Ri#x}909ZQ(rp=lwp0RZj6v8tby3Cdgm^9r$Om(IESeJUk+WXnPbORgrJVwlQTn(<=>O^+^yR_67w-t@??wHp zv50oj@FZnU_LZ!C_8Td7`cGE>UhHtVP%-V60$FDg~q# zR<7$0Khlt~{tAR@DUf)Wwro2_2M#_?d;1=x=^N*HuZI1IgDeT&-v!MyF_EMR-rq!G zjkNp7uaL!gh*C)(SxgfY;PG-Zt>i9*-~#V6BC_BPJFLF5Z41|5@mQ34w(h0Dfe+HD zJXRCjHWdlcXDcDJU|?(`hK$!|;xUAnJ0e*C^^M+r{6LtTbdKi7PtukC2_e6DXn%^T zZI{UuIz{iD=_h|AN{4pvxT+Z>d*WSs_nkAmmk(1%qn-BljFBVt9$h;31`SUxQWZb{ zq5TVFPo1ODn{V*mRtAfITMntd46#2eHxwdQ4_CShjz@0wEjzP(an(=vhi4d>_|jBN0j~gq~PTrK9J(}xJ)tc z+jQpKjcnO#Z_2WtIzv;7e(GvM*~dkmXWu4c=<~ioUee)vE;r`b%Wq<5&JX7}5 zXRnH~-^XRIb6rW7{k$mq-X05eHx7wB&!0X;Bhy}L;ko?a_8G3@)0wh6c&t8lB#;{8n7d(!p(-l?}}e9lL0-1qlym1Vzr;b)n$KXNF*Y3FJ3 z)(N_Jc~Fe8$BsZYkX!acJ8aZeHz1$$`YD?A`Dt6bgLZVtdN(Tjz@=AtU7aQm&)=o) zuQ5-8|G~NhU|z)B1-=I30_&4@&YzqPi}+iZcj2uD^B(32xCTQS=BIM=#p$w*>XHjZ$mFJYPFV)827jvub&+Kt2|lo15cx6Nfh} zR9RUm@+k##i=$l5SuszqhRhXia@m_jo+wK=EayI#%f)kX=`O%~+Qw*m=Qyup3FgJ) z3g+XrIr6z(VdjCc=LpNu6wqS&LFLiY?nMpr07!_&2 zRL(sy8kmut1w!1blPQq~I?WV}%Yi!`tPtN7^-s%t5a8|_-=qC4zzh;F8`9mAeh%+< z=-L$DbCc84v>285%tcJ%``2Dx6!g*=DYU}GG&oQ6t=GIF{hP0Qg%BIS=f#mkCa+85 zaw1drsB{qAH2`>C_MSN314W1YZ7g6GX^JNO@;QEfuZtteOgipSLhO9^p#HS?oFC@J zk?R?lU?x|4&$#BEYs_<~^s~1hl$XCv@;xUnMd<4hDo)Hy7b{NT-AP zXGF5V;DU)>IUA<0zv88DzUs@Adp2x*kEm0==Z9|x`5qsA?__}H_*ww%e)d*Uq=VkR z8WrV|?M?LkH{?B_DZjXd+o6Ikj-r0h774CX-k_!H^ulnGPF;_Q>o4#%ezFP$Ssd-+jX`>IJ~( zsq68~Z|`&Yp^%HF?@@W-eFEwCx$7aDU=y2IGa#5{J|)6R03jL_qg%RNg5VkkLa5Gm zdyc?q3DDO|+`N?=P%fF_%)bE2AKoAPxh7_r(eKVt_t|cMAG%P&_tI(aqhB!vJxTiE~Frm zr{9-atiZhoVs7YRb2pHqszv;*0=!mLN$Vr^eb1gf;u>7L8erd{#xYz`0pRx_P?LKS ziy$K;laSOL)Q+goK&Ul1%ekO$^` zB@ovmpF#z~EF5IQ!6b~E^#+83!z1}!f#sk;@o;^?HE#m|<6w0bEBb5kT@e)D6`~%r zc|u{?+G3|Ro)7T}nLwS+b>r;@+8&1<^I>GDUwmG_az=bAK!Jz31AA4lGdMWZ-RYuJ z@A3ZgM2cQ`B}wxO>5Db6R(Q#roS;NxES&;jXiTJ;Qxg=6X6H>^E@ zr>5-DblDk&%5MA|&d3ih1vi@I1oD-Zv$E2lG%BP}0p9<>M}PDEaYK6Hq+4r+rOfHw z4h!?pIL!?IzFT`-g0^pQXPEGN3Hr^Jo{3*qY{0Gvp^5Sl4Rp4_KXYNB*PRBO*1~DS z{d?p|hMn8o)Z6VAOo;v@_$KZ_+*?!PCe|5Hs({J?xRz^fk}hZKKasa|)vM!u^#3teu;9Kcj#^ z>%{=BNcwLEatKP3)uOuETC{M#7{v+#4CeyB=dVDc<)x59<+kpF(pXlpV(`jd-%{lk z>aWDqUUm7y4H+di^D7{3Vl?^MfWG z;6K!Nk(T*G1I-1QpEYSYNT=m2O6s~|(lnpqL-RZS)O;0CY1(w7>k0sK2M$ai7Ru0Q zP!QHLX~AGTjv)7dz#o>52l}dcpWx(7D}`JTUReMfD2c+fr%cegB1IMBnM$F8 zdH>Yu1)5_13l?^A3NVp3lA;CXHHT-TG{Ecot*Ho2@;Zn#k%y#E+oyS>#y$M?IbsW$f%JzSm|U9ZSUmZ`mGYqM44 zdwjo#I_oM#TB$MvrC3oyi{&srKF)K7n|}3If0gU5f<{Kz?$rS?@OR28X0?Dfp?ZfYFM%zFpi28Ly{&e7;z$*J=9xzBCpN=-^vJJR zk%Y0IeMaGSg}W5wr^QBBs3;UvtnfZe56nXoQ%l`S-93txY#&g7OSodrWaLwM5+@kK%x`$p3P$unqjOS<-Dko3P2`d|~pUb@% zqcL93!_14}9?T1HYlgu4^9ynQEg}xPj8B30gqt(7uyid1xKl1@Gdv5$%^h*-pRl`A$P}@LUUP&thE8;<<&&WpwZk^)e%T>sbA5R99<5XcyzQ!70C-iMdRQmDmOg_No|n1QCryQd~Y0`GeA*C>AKJqlinO z048K?B9htg<^wkM4WgfH3|itcp+rc3%f@-%Gg!(~-Mc_tY}QBF;BYt$ndUXe25iG} zx+=-iU>9^iVB5_Fz5pDRp$@K(&}xqD(o>!X#o=3C)Szd)S>$s;R3Yhs!Cx#}lbc ziUu&FG^=ISCA&`k|7Yo1P9rmTmk8!-G5xU*-Ae?d59u08N1gAHmkJud+}ro zUwe#ReCq-F$s704U;o_}a@QQEz1tt7TK9GlM+JF1xsH`vRV`4aV#}q)redZ1D2)T% z#3o9?^1RJ5FwS7r*{%REg9N~^Az12BUTm;|3x%M?mm3!Z!ivX|VxqpgQTYAb&I)Sb z&3w+pyapC4w;Ny-@QMhm2?ir1;)}>B75;o7=hPnXK;Sko0yrtST;S17Y~rp&d3fth z=&t3@<8PvM18di(9S>Am;f z6KPPWfG%CSB+_4e@kI)ICn)5d6u++qcAI=3Onc}G1_s3~>2uUs6?{Lao3!K)+ssF-QyS`CYpqPpj za?@xuOjcuPjBh`!M`n%3(KLkC>47glq|9G28gl zBJ#oWY&M%XM3)cxash=bSb(xBRyK$Brc$MJl%FBED{+@qlk(4sMFfl!5DY!- z!@&=&Kox%@O-sw2&Ra_uDprI$2Dt`0xO|l!^STjSEkJ0FGFcqkc_nsJz#kBnD%fbk zDj2*?eXVtgpupy?r<#^s;v}K6%D|`gWFfx0YP+bau_v993kX7yzu4F|tn_p|7Mi7t z4T8*~+{hd4zEZ$t(5;b>r2g0G%7q`()eAqN@sanaqt#4xjZ3Mm#Y|het>m4(Nd1>z z5%&!AUlw_k8psx9hvfzO2zbhB=Bt3^EP%BzQmAybI|WaN@A(ueJs^EI$>)h^Atc^@*i89KPW|ReSX@xb$6R*6O`` z9Q*;eK3f~b%C~+vPJjMCh6H`>yJzV9nZKm>-uZ9z>dSvhFTV6AG_*KM)A0aV8xmw| zOi*oSiXM2_Dd@m~Fa_toCMe`TPYb@dAT9L$5bIfAhm+d5jQIeUV=_p6;diLu%(^;l zbm(9O_hF*;HWNMZXztvJz1?eX%+kqIvs~BkYGI`|9`9Ix;g0C!+jDgGqL*$C1v7^; zfy>te;?Uj9T#Q~hF)L_-*FFGkr_vCcN#Vp>^CIn?)7hXd=P&s(*D4^`xJpCNZ~%L6 zeE-Vd4Ab9!cZ~W612i?Wbncztv7hy@V4@gKU~n~E?f26wCpk|htN{S#UzG+A9_XKg zL)m_W@2Xu+a6P=GU2+fcJAAtQm@Ynqnt{0W2%8rA#D(%uWo{Z9X z<6UlFPScj%2yoY>?nk`?!B8@jHnf6RUO4ax!wKQm18i*eES;AXZey)L`>{&Fg%4IvZ|CSId3|D|}`^8Cv0A>}Ssu})z9si;VC zJs}RRJU9SrMeuQQUQMoOy@b+2S&D2#6jQD>u~;c?dARFf{>T6LAODN=-|LRq@#pDc z{|x#33G${J3+{s)t6{#@6r~TiO{^5gb$z>90G0(JXcw=?`0QwNP=FV)V5EXPF2t5$ zMwS^O2nDKn0}jRt3IiyrwSghAX-E2kTOqM1K{*752a7Zo^DW&j!CWDKMee_aT%G?*RXw3aZQ-1+wn4 zn*sD~0Plo0P(Yh1g(I#<9RS+&dmbBX=%bBt+BQ8Vz#K0J#KbW((^5BO0+&!0%3f+jxK}c!fDeR=eC} zL2#^u!E>5=*QOT*gMOSySje}y)HHpg0I_Fk>w?_B^3Ug5p#Ng-15h`5cQJC_&ekCW z@5`MYUo94RtyG8KaN^Fz<3$UUN3Dqv@H92p#9FC<>rqZEUB6)>n}x5lFE4ysEmF)t z&3eOBUxzq8G7WPA_yV!ca=*fyf%Q?Y^|x=r^Z>>{Ilud+Xl`~?)F0-q=0>Or(AM;~%Ha&Q991XOH;4YtLTl?vYBB zcx05qi*Jg*N2g;HOPWOfpeK%1XWU!p0m1*xiP#cu%w;jrvHiwl5Pf0F%lsFw$NGM= z92EZx1j8x1d?O_2;-&ZK%$c9jxr^`6$iz*msWX$i#w)+f^>{~xO>Cl7k@A=c$n?I?i?Wl z%7C%99H9?m{@B^$qFNqrKqR%D>YMj-ezJYvdHXHezki=_m4?1^?AS4S;)y53{QZef zd_v^&?8iPXt_1=!KcI0P=w~Nh!*kN#0+=(g9ZRs3(*M>y0c=w#@-y zCC`NCfj86EcRoO%7>y& zO!W;`s<5PpS2&tnj0hT@UZk6&V}b@o{nS4irt#UVBEYC0Vu(I_yn$w>6Ers`-`iow z{xaL&n_IhSa(sw-w(iYwGZsm5ox0?n1wj9*FeP~}N3>@b_v4Oi9Rs2-a~+J#M7gX{ zE^~~ACn6Mzrf6h3LZ>hL>FhN>p&MX7=w|-<8khI-V2~~`p`F6qH*h~_f%C$vgt)J$ zv?(5okac35kMg@CZJftKg!>oTc7p#_*P?z=6En<{t27@!9C>;<@AtTG-{d(i&aao` z{?fv8=>+#Fl;uVB%;!28)jeuw_i5DiX*DaFmbz7 zq-)FW4JUa$i1TMcv>D2ImD>dKA@Wi8t3DIpc~hm~ck~&!^IDFF!X6$n49sz`0L2^z zYci7w-*EsmCM;R>a#>uD-!T3$ci?aY=4i|{n77q_0@iYB4qq+gJS_PT#3@nnMldHL z#&H$zV=&e+7h0`2_+k=@ER0j|QrO=@;bLO4+b|~(UE@BEcEa@8P~E}Txp;1~@jFXp zCX^DDmHFd5!HPs{p`w6v(3Z|Qx^#6$^am{vsQ&)_)tr9?T^r;*q^U;agSrm}gUrh$ zGHr)^TrQWeLV*$oWmDhtL2o&uFfnt9pOIS@0CN%Q(dn#UewXKWgE?Nv@3_4BJv!Dg zc_3P@Ip}xWI-Jz8<#YUNdD{L?!O|Mv#3ojY^Z;Brj5Anuwk2R>oap9Imiz%J%*W{y zOdL2-5|3M`y$Ol~6Ag`og}?*T2R2?abJ>Z+=Qs0ri=bO0rc9pt0C-X6(Y4Ri(~^LB zE2t2>7oKB;(Q%w?OMlTpdtV@k^58v;iT8RLU{eR-&Md#XqDxnkd`(u6dtgr`?c7>P z^|duzziyt`?KC=J7T2Qg6mZf8gl9}lnt8+G5Z6S7+pR1jQ3!N%8Gu4aB;eK~TfVW$ z3h}O}UZvbXp4w{^EiPhF=f%xt7mOC}0V4t?0t-42j&PlYu<*zYz zMJ><&7IL_^rc*YtiS@?aJ8=k$70pHshf@&bz5ix#T?r>FfAY!Ja;- zw0eg%3WVb-F#G7}sBnRWw6(?B^bZKwr_+MW0B^8wPDBKa&BbUD2aDnmqGibl`fK!5 z4D<>Wd_vI$K!C0Fx1JBhC{!Sj7MY)8jZmvmC+VLo4vj2lN@Z zM}y++nP;A%zP>*C*0;Vzt*x!}#v5;>uPO$s?*r<+0SHyfsZc@P>EqNiH5dzq(AG*Y zrxI)~_1AD9J;JzxMh=MC&oKP