From 839f5bbb125eef41e154f2c251cc13b281a70eef Mon Sep 17 00:00:00 2001 From: Eric Katzfey Date: Mon, 13 May 2024 15:01:43 -0700 Subject: [PATCH 01/34] Removed obsolete voxl 2 board default parameter setting --- boards/modalai/voxl2/scripts/install-voxl.sh | 1 - boards/modalai/voxl2/target/voxl-px4 | 6 - .../voxl-px4-set-default-parameters.config | 192 ------------------ 3 files changed, 199 deletions(-) delete mode 100755 boards/modalai/voxl2/target/voxl-px4-set-default-parameters.config diff --git a/boards/modalai/voxl2/scripts/install-voxl.sh b/boards/modalai/voxl2/scripts/install-voxl.sh index 4a88a7a56f80..a908b0a83576 100755 --- a/boards/modalai/voxl2/scripts/install-voxl.sh +++ b/boards/modalai/voxl2/scripts/install-voxl.sh @@ -20,7 +20,6 @@ adb shell chmod a+x /usr/bin/voxl-px4-hitl-start # Push configuration file adb shell mkdir -p /etc/modalai -adb push boards/modalai/voxl2/target/voxl-px4-set-default-parameters.config /etc/modalai adb push boards/modalai/voxl2/target/voxl-px4-fake-imu-calibration.config /etc/modalai adb push boards/modalai/voxl2/target/voxl-px4-hitl-set-default-parameters.config /etc/modalai diff --git a/boards/modalai/voxl2/target/voxl-px4 b/boards/modalai/voxl2/target/voxl-px4 index 3ce4309ee2ba..bf1b62e981aa 100755 --- a/boards/modalai/voxl2/target/voxl-px4 +++ b/boards/modalai/voxl2/target/voxl-px4 @@ -129,12 +129,6 @@ else DAEMON="-d" fi -if [ ! -f /data/px4/param/parameters ]; then - echo "[INFO] Setting default parameters for PX4 on voxl" - px4 $DAEMON -s /etc/modalai/voxl-px4-set-default-parameters.config - /bin/sync -fi - if [ $SENSOR_CAL == "FAKE" ]; then /bin/echo "[INFO] Setting up fake sensor calibration values" px4 $DAEMON -s /etc/modalai/voxl-px4-fake-imu-calibration.config diff --git a/boards/modalai/voxl2/target/voxl-px4-set-default-parameters.config b/boards/modalai/voxl2/target/voxl-px4-set-default-parameters.config deleted file mode 100755 index bb4045b39734..000000000000 --- a/boards/modalai/voxl2/target/voxl-px4-set-default-parameters.config +++ /dev/null @@ -1,192 +0,0 @@ -#!/bin/sh -# PX4 commands need the 'px4-' prefix in bash. -# (px4-alias.sh is expected to be in the PATH) -. px4-alias.sh - -param select /data/px4/param/parameters - -# Make sure we are running at 800Hz on IMU -param set IMU_GYRO_RATEMAX 800 - -# EKF2 Parameters -param set EKF2_IMU_POS_X 0.027 -param set EKF2_IMU_POS_Y 0.009 -param set EKF2_IMU_POS_Z -0.019 -param set EKF2_EV_DELAY 5 -param set EKF2_AID_MASK 280 -param set EKF2_ABL_LIM 0.8 -param set EKF2_TAU_POS 0.25 -param set EKF2_TAU_VEL 0.25 - -param set MC_AIRMODE 0 - -param set MC_YAW_P 2.0 -param set MC_YAWRATE_P 0.15 -param set MC_YAWRATE_I 0.1 -param set MC_YAWRATE_D 0.0 -param set MC_YAWRATE_K 1.0 - -param set MC_PITCH_P 5.5 -param set MC_PITCHRATE_P 0.08 -param set MC_PITCHRATE_I 0.2 -param set MC_PITCHRATE_D 0.0013 -param set MC_PITCHRATE_K 1.0 - -param set MC_ROLL_P 5.5 -param set MC_ROLLRATE_P 0.08 -param set MC_ROLLRATE_I 0.2 -param set MC_ROLLRATE_D 0.0013 -param set MC_ROLLRATE_K 1.0 - -param set MPC_VELD_LP 5.0 - -# tweak MPC_THR_MIN to prevent roll/pitch losing control -# authority under rapid downward acceleration -param set MPC_THR_MAX 0.75 -param set MPC_THR_MIN 0.08 -param set MPC_THR_HOVER 0.42 -param set MPC_MANTHR_MIN 0.05 - -# default position mode with a little expo, smooth mode is terrible -param set MPC_POS_MODE 0 -param set MPC_YAW_EXPO 0.20 -param set MPC_XY_MAN_EXPO 0.20 -param set MPC_Z_MAN_EXPO 0.20 - -# max velocities -param set MPC_VEL_MANUAL 5.0 -param set MPC_XY_VEL_MAX 5.0 -param set MPC_XY_CRUISE 5.0 -param set MPC_Z_VEL_MAX_DN 1.5 -param set MPC_Z_VEL_MAX_UP 4.0 -param set MPC_LAND_SPEED 1.0 - -# Horizontal position PID -param set MPC_XY_P 0.95 -param set MPC_XY_VEL_P_ACC 3.00 -param set MPC_XY_VEL_I_ACC 0.10 -param set MPC_XY_VEL_D_ACC 0.00 - -# Vertical position PID -# PX4 Defaults -param set MPC_Z_P 1.0 -param set MPC_Z_VEL_P_ACC 8.0 -param set MPC_Z_VEL_I_ACC 2.0 -param set MPC_Z_VEL_D_ACC 0.0 - -param set MPC_TKO_RAMP_T 1.50 -param set MPC_TKO_SPEED 1.50 - -# Set the ESC outputs to function as motors -param set VOXL_ESC_FUNC1 101 -param set VOXL_ESC_FUNC2 103 -param set VOXL_ESC_FUNC3 104 -param set VOXL_ESC_FUNC4 102 - -param set VOXL_ESC_SDIR1 0 -param set VOXL_ESC_SDIR2 0 -param set VOXL_ESC_SDIR3 0 -param set VOXL_ESC_SDIR4 0 - -param set VOXL_ESC_CONFIG 1 -param set VOXL_ESC_REV 0 -param set VOXL_ESC_MODE 0 -param set VOXL_ESC_BAUD 2000000 -param set VOXL_ESC_RPM_MAX 10500 -param set VOXL_ESC_RPM_MIN 1000 - -# Set the Voxl2 IO outputs to function as motors -param set VOXL2_IO_FUNC1 101 -param set VOXL2_IO_FUNC2 102 -param set VOXL2_IO_FUNC3 103 -param set VOXL2_IO_FUNC4 104 - -param set VOXL2_IO_BAUD 921600 -param set VOXL2_IO_MIN 1000 -param set VOXL2_IO_MAX 2000 - -# Some parameters for control allocation -param set CA_ROTOR_COUNT 4 -param set CA_R_REV 0 -param set CA_AIRFRAME 0 -param set CA_ROTOR_COUNT 4 -param set CA_ROTOR0_PX 0.15 -param set CA_ROTOR0_PY 0.15 -param set CA_ROTOR1_PX -0.15 -param set CA_ROTOR1_PY -0.15 -param set CA_ROTOR2_PX 0.15 -param set CA_ROTOR2_PY -0.15 -param set CA_ROTOR2_KM -0.05 -param set CA_ROTOR3_PX -0.15 -param set CA_ROTOR3_PY 0.15 -param set CA_ROTOR3_KM -0.05 - -# Some parameter settings to disable / ignore certain preflight checks - -# No GPS driver yet so disable it -param set SYS_HAS_GPS 0 - -# Allow arming wihtout a magnetometer (Need magnetometer driver) -param set SYS_HAS_MAG 0 -param set EKF2_MAG_TYPE 5 - -# Allow arming without battery check (Need voxlpm driver) -param set CBRK_SUPPLY_CHK 894281 - -# Allow arming without an SD card -param set COM_ARM_SDCARD 0 - -# Allow arming wihtout CPU load information -param set COM_CPU_MAX 0.0 - -# Disable auto disarm. This is number of seconds to wait for takeoff -# after arming. If no takeoff happens then it will disarm. A negative -# value disables this. -param set COM_DISARM_PRFLT -1 - -# This parameter doesn't exist anymore. Need to see what the new method is. -# param set MAV_BROADCAST 0 - -# Doesn't work without setting this to Quadcopter -param set MAV_TYPE 2 - -# Parameters that we don't use but QGC complains about if they aren't there -param set SYS_AUTOSTART 4001 - -# Default RC channel mappings -param set RC_MAP_ACRO_SW 0 -param set RC_MAP_ARM_SW 0 -param set RC_MAP_AUX1 0 -param set RC_MAP_AUX2 0 -param set RC_MAP_AUX3 0 -param set RC_MAP_AUX4 0 -param set RC_MAP_AUX5 0 -param set RC_MAP_AUX6 0 -param set RC_MAP_FAILSAFE 0 -param set RC_MAP_FLAPS 0 -param set RC_MAP_FLTMODE 6 -param set RC_MAP_GEAR_SW 0 -param set RC_MAP_KILL_SW 7 -param set RC_MAP_LOITER_SW 0 -param set RC_MAP_MAN_SW 0 -param set RC_MAP_MODE_SW 0 -param set RC_MAP_OFFB_SW 0 -param set RC_MAP_PARAM1 0 -param set RC_MAP_PARAM2 0 -param set RC_MAP_PARAM3 0 -param set RC_MAP_PITCH 2 -param set RC_MAP_POSCTL_SW 0 -param set RC_MAP_RATT_SW 0 -param set RC_MAP_RETURN_SW 0 -param set RC_MAP_ROLL 1 -param set RC_MAP_STAB_SW 0 -param set RC_MAP_THROTTLE 3 -param set RC_MAP_TRANS_SW 0 -param set RC_MAP_YAW 4 - -param save - -sleep 2 - -# Need px4-shutdown otherwise Linux system shutdown is called -px4-shutdown From 293389abf3f531300cdb7315bf686e5eff323150 Mon Sep 17 00:00:00 2001 From: Eric Katzfey Date: Mon, 13 May 2024 11:48:08 -0700 Subject: [PATCH 02/34] Minor updates to the VOXL 2 board README file --- boards/modalai/voxl2/README.md | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/boards/modalai/voxl2/README.md b/boards/modalai/voxl2/README.md index 02d7f6fc5ab4..ac6bd1f5f15c 100644 --- a/boards/modalai/voxl2/README.md +++ b/boards/modalai/voxl2/README.md @@ -9,7 +9,7 @@ When running PX4 directly on the QRB5165 SoC it runs partially on the Sensor Low The portion running on the DSP hosts the flight critical portions of PX4 such as the IMU, barometer, magnetometer, GPS, ESC, and power management drivers, and the state estimation. The DSP acts as the real time portion of the system. Non flight -critical applications such as Mavlink, logging, and commander are running on the +critical applications such as Mavlink, and logging are running on the ARM CPU cluster (aka apps proc). The DSP and ARM CPU cluster communicate via a Qualcomm proprietary shared memory interface. @@ -27,6 +27,7 @@ The full instructions are available here: ``` px4$ boards/modalai/voxl2/scripts/run-docker.sh root@9373fa1401b8:/usr/local/workspace# boards/modalai/voxl2/scripts/clean.sh +root@9373fa1401b8:/usr/local/workspace# boards/modalai/voxl2/scripts/build-deps.sh root@9373fa1401b8:/usr/local/workspace# boards/modalai/voxl2/scripts/build-apps.sh root@9373fa1401b8:/usr/local/workspace# boards/modalai/voxl2/scripts/build-slpi.sh root@9373fa1401b8:/usr/local/workspace# exit @@ -69,16 +70,15 @@ pxh> ## Notes You cannot cleanly shutdown PX4 with the shutdown command on VOXL 2. You have -to power cycle the board and restart everything. +to power cycle the board and restart everything. Starting with SDK 1.3.0 it is possible +to cleanly shutdown PX4 on VOXL 2. ## Tips -Start with a VOXL 2 that only has the system image installed, not the SDK - -Run the command ```voxl-px4 -s``` on target to run the self-test +Always use the latest SDK release In order to see DSP specific debug messages the mini-dm tool in the Hexagon SDK -can be used: +can be used (Most messages are passed to the apps proc but certain low level messages are not): ``` modalai@modalai-XPS-15-9570:/local/mnt/workspace/Qualcomm/Hexagon_SDK/4.1.0.4/tools/debug/mini-dm/Ubuntu18$ sudo ./mini-dm [sudo] password for modalai: From 17916b7fdc91822f7414f1f2da748ab8bd622cad Mon Sep 17 00:00:00 2001 From: Konrad Date: Tue, 14 May 2024 13:37:54 +0200 Subject: [PATCH 03/34] uxcre_dds_client: use topic name as defined in the dds_topics.yaml to register stream --- src/modules/uxrce_dds_client/dds_topics.h.em | 6 ++++-- src/modules/uxrce_dds_client/utilities.hpp | 18 +++++++++++------- 2 files changed, 15 insertions(+), 9 deletions(-) diff --git a/src/modules/uxrce_dds_client/dds_topics.h.em b/src/modules/uxrce_dds_client/dds_topics.h.em index cade47b5fdce..3c4311e6c333 100644 --- a/src/modules/uxrce_dds_client/dds_topics.h.em +++ b/src/modules/uxrce_dds_client/dds_topics.h.em @@ -43,6 +43,7 @@ struct SendSubscription { const struct orb_metadata *orb_meta; uxrObjectId data_writer; const char* dds_type_name; + const char* topic; uint32_t topic_size; UcdrSerializeMethod ucdr_serialize_method; }; @@ -54,6 +55,7 @@ struct SendTopicsSubs { { ORB_ID(@(pub['topic_simple'])), uxr_object_id(0, UXR_INVALID_ID), "@(pub['dds_type'])", + "@(pub['topic'])", ucdr_topic_size_@(pub['simple_base_type'])(), &ucdr_serialize_@(pub['simple_base_type']), }, @@ -96,7 +98,7 @@ void SendTopicsSubs::update(uxrSession *session, uxrStreamId reliable_out_stream orb_copy(send_subscriptions[idx].orb_meta, fds[idx].fd, &topic_data); if (send_subscriptions[idx].data_writer.id == UXR_INVALID_ID) { // data writer not created yet - create_data_writer(session, reliable_out_stream_id, participant_id, static_cast(send_subscriptions[idx].orb_meta->o_id), client_namespace, send_subscriptions[idx].orb_meta->o_name, + create_data_writer(session, reliable_out_stream_id, participant_id, static_cast(send_subscriptions[idx].orb_meta->o_id), client_namespace, send_subscriptions[idx].topic, send_subscriptions[idx].dds_type_name, send_subscriptions[idx].data_writer); } @@ -169,7 +171,7 @@ bool RcvTopicsPubs::init(uxrSession *session, uxrStreamId reliable_out_stream_id @[ for idx, sub in enumerate(subscriptions + subscriptions_multi)]@ { uint16_t queue_depth = orb_get_queue_size(ORB_ID(@(sub['simple_base_type']))) * 2; // use a bit larger queue size than internal - create_data_reader(session, reliable_out_stream_id, best_effort_in_stream_id, participant_id, @(idx), client_namespace, "@(sub['topic_simple'])", "@(sub['dds_type'])", queue_depth); + create_data_reader(session, reliable_out_stream_id, best_effort_in_stream_id, participant_id, @(idx), client_namespace, "@(sub['topic'])", "@(sub['dds_type'])", queue_depth); } @[ end for]@ diff --git a/src/modules/uxrce_dds_client/utilities.hpp b/src/modules/uxrce_dds_client/utilities.hpp index 5c7fb2e9dc2d..70886ec795ff 100644 --- a/src/modules/uxrce_dds_client/utilities.hpp +++ b/src/modules/uxrce_dds_client/utilities.hpp @@ -23,25 +23,29 @@ uxrObjectId topic_id_from_orb(ORB_ID orb_id, uint8_t instance = 0) return uxrObjectId{}; } -static bool generate_topic_name(char *topic, const char *client_namespace, const char *direction, const char *name) +static bool generate_topic_name(char *topic_name, const char *client_namespace, const char *topic) { + if (topic[0] == '/') { + topic++; + } + if (client_namespace != nullptr) { - int ret = snprintf(topic, TOPIC_NAME_SIZE, "rt/%s/fmu/%s/%s", client_namespace, direction, name); + int ret = snprintf(topic_name, TOPIC_NAME_SIZE, "rt/%s/%s", client_namespace, topic); return (ret > 0 && ret < TOPIC_NAME_SIZE); } - int ret = snprintf(topic, TOPIC_NAME_SIZE, "rt/fmu/%s/%s", direction, name); + int ret = snprintf(topic_name, TOPIC_NAME_SIZE, "rt/%s", topic); return (ret > 0 && ret < TOPIC_NAME_SIZE); } static bool create_data_writer(uxrSession *session, uxrStreamId reliable_out_stream_id, uxrObjectId participant_id, - ORB_ID orb_id, const char *client_namespace, const char *topic_name_simple, const char *type_name, + ORB_ID orb_id, const char *client_namespace, const char *topic, const char *type_name, uxrObjectId &datawriter_id) { // topic char topic_name[TOPIC_NAME_SIZE]; - if (!generate_topic_name(topic_name, client_namespace, "out", topic_name_simple)) { + if (!generate_topic_name(topic_name, client_namespace, topic)) { PX4_ERR("topic path too long"); return false; } @@ -87,13 +91,13 @@ static bool create_data_writer(uxrSession *session, uxrStreamId reliable_out_str } static bool create_data_reader(uxrSession *session, uxrStreamId reliable_out_stream_id, uxrStreamId input_stream_id, - uxrObjectId participant_id, uint16_t index, const char *client_namespace, const char *topic_name_simple, + uxrObjectId participant_id, uint16_t index, const char *client_namespace, const char *topic, const char *type_name, uint16_t queue_depth) { // topic char topic_name[TOPIC_NAME_SIZE]; - if (!generate_topic_name(topic_name, client_namespace, "in", topic_name_simple)) { + if (!generate_topic_name(topic_name, client_namespace, topic)) { PX4_ERR("topic path too long"); return false; } From 2e7a99ac410a680a78512048b216fabe29a2aa3b Mon Sep 17 00:00:00 2001 From: Hamish Willee Date: Wed, 15 May 2024 10:52:26 +1000 Subject: [PATCH 04/34] VectorNav.cpp - fix docs link to usage guide --- src/drivers/ins/vectornav/VectorNav.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/ins/vectornav/VectorNav.cpp b/src/drivers/ins/vectornav/VectorNav.cpp index 991b1262958f..cbe7ab535257 100644 --- a/src/drivers/ins/vectornav/VectorNav.cpp +++ b/src/drivers/ins/vectornav/VectorNav.cpp @@ -832,7 +832,7 @@ Serial bus driver for the VectorNav VN-100, VN-200, VN-300. Most boards are configured to enable/start the driver on a specified UART using the SENS_VN_CFG parameter. -Setup/usage information: https://docs.px4.io/master/en/sensor/vectornav.html +Setup/usage information: https://docs.px4.io/main/en/sensor/vectornav.html ### Examples From ee2a8c9bda06425c4c78e72455059692309431b1 Mon Sep 17 00:00:00 2001 From: dirksavage88 Date: Wed, 8 May 2024 10:58:06 -0400 Subject: [PATCH 05/34] increase lp default stack to 2000 Signed-off-by: dirksavage88 --- .../px4_platform_common/px4_work_queue/WorkQueueManager.hpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp b/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp index 5310701eebda..761041fa0e83 100644 --- a/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp +++ b/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp @@ -89,7 +89,7 @@ static constexpr wq_config_t ttyS9{"wq:ttyS9", 1728, -30}; static constexpr wq_config_t ttyACM0{"wq:ttyACM0", 1728, -31}; static constexpr wq_config_t ttyUnknown{"wq:ttyUnknown", 1728, -32}; -static constexpr wq_config_t lp_default{"wq:lp_default", 1920, -50}; +static constexpr wq_config_t lp_default{"wq:lp_default", 2000, -50}; static constexpr wq_config_t test1{"wq:test1", 2000, 0}; static constexpr wq_config_t test2{"wq:test2", 2000, 0}; From 9fd1c54570f406fe1ea7e2d33d81a83f19422ab7 Mon Sep 17 00:00:00 2001 From: Thomas Frans Date: Mon, 13 May 2024 09:15:46 +0200 Subject: [PATCH 06/34] style(editorconfig): update newline setting The setting wasn't consistent with the one used in the Visual Studio Code settings, which caused different newline formatting depending on whether the user uses Visual Studio Code or another editor that uses EditorConfig. --- .editorconfig | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.editorconfig b/.editorconfig index 50a87fd83923..683f0fdc5159 100644 --- a/.editorconfig +++ b/.editorconfig @@ -1,7 +1,7 @@ root = true [*] -insert_final_newline = false +insert_final_newline = true [{*.{c,cpp,cc,h,hpp},CMakeLists.txt,Kconfig}] indent_style = tab From ecf4af7cf769358709ecd61bd7d0a4224868f031 Mon Sep 17 00:00:00 2001 From: alexklimaj Date: Wed, 15 May 2024 18:12:16 -0600 Subject: [PATCH 07/34] boards: ark cannode add ADIS16507 driver --- boards/ark/cannode/default.px4board | 1 + 1 file changed, 1 insertion(+) diff --git a/boards/ark/cannode/default.px4board b/boards/ark/cannode/default.px4board index 3141d40b3089..d875f6b8211f 100644 --- a/boards/ark/cannode/default.px4board +++ b/boards/ark/cannode/default.px4board @@ -14,6 +14,7 @@ CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_COMMON_HYGROMETERS=y CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=y +CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16507=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y CONFIG_DRIVERS_IRLOCK=y From 5fe955c24354808e05e81378784265b3f0ebc62c Mon Sep 17 00:00:00 2001 From: Alexis Guijarro Date: Thu, 2 May 2024 19:22:19 +0000 Subject: [PATCH 08/34] mRo Control Zero Classic: Definition for GPS2 by default added --- boards/mro/ctrl-zero-classic/init/rc.board_defaults | 1 + 1 file changed, 1 insertion(+) diff --git a/boards/mro/ctrl-zero-classic/init/rc.board_defaults b/boards/mro/ctrl-zero-classic/init/rc.board_defaults index 110c240ee8a0..0495329e1a47 100644 --- a/boards/mro/ctrl-zero-classic/init/rc.board_defaults +++ b/boards/mro/ctrl-zero-classic/init/rc.board_defaults @@ -6,4 +6,5 @@ param set-default BAT1_V_DIV 10.1 param set-default BAT1_A_PER_V 17 +param set-default GPS_2_CONFIG 202 param set-default TEL_FRSKY_CONFIG 103 From 6a966ab065d9d60d203ce0567bc18e3f24462cab Mon Sep 17 00:00:00 2001 From: fury1895 Date: Thu, 16 May 2024 15:17:35 +0200 Subject: [PATCH 09/34] px4/fmu-v6x: set mavlink dialect to development --- boards/px4/fmu-v6x/default.px4board | 1 + 1 file changed, 1 insertion(+) diff --git a/boards/px4/fmu-v6x/default.px4board b/boards/px4/fmu-v6x/default.px4board index 4e21f0fd0870..f197a254a09a 100644 --- a/boards/px4/fmu-v6x/default.px4board +++ b/boards/px4/fmu-v6x/default.px4board @@ -66,6 +66,7 @@ CONFIG_MODULES_LOGGER=y CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y CONFIG_MODULES_MANUAL_CONTROL=y CONFIG_MODULES_MAVLINK=y +CONFIG_MAVLINK_DIALECT="development" CONFIG_MODULES_MC_ATT_CONTROL=y CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y From 440465702e3a6fc6afc93f2d424cb1a4e6ab838d Mon Sep 17 00:00:00 2001 From: bresch Date: Thu, 16 May 2024 17:21:50 +0200 Subject: [PATCH 10/34] wind_est_replay: fix cov matrix format and data indexing --- src/lib/wind_estimator/python/wind_estimator_replay.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/lib/wind_estimator/python/wind_estimator_replay.py b/src/lib/wind_estimator/python/wind_estimator_replay.py index efa19eaf0e71..a44d62db4fd1 100644 --- a/src/lib/wind_estimator/python/wind_estimator_replay.py +++ b/src/lib/wind_estimator/python/wind_estimator_replay.py @@ -103,12 +103,12 @@ def run(logfile, use_gnss): P += Q * dt - if t_true_airspeed[i_airspeed] < t_now: + if i_airspeed < len(t_true_airspeed) and t_true_airspeed[i_airspeed] < t_now: while i_airspeed < len(t_true_airspeed) and t_true_airspeed[i_airspeed] < t_now: i_airspeed += 1 i_airspeed -= 1 - (H, K, innov_var, innov) = fuse_airspeed(np.asarray(v_local[:,i]), state, P.flatten(), true_airspeed[i_airspeed], R, epsilon) + (H, K, innov_var, innov) = fuse_airspeed(np.asarray(v_local[:,i]), state, P, true_airspeed[i_airspeed], R, epsilon) state += np.array(K) * innov P -= K * H * P i_airspeed += 1 From b42799fac2868f5f33dd8312eb45509da1721ccd Mon Sep 17 00:00:00 2001 From: bresch Date: Thu, 16 May 2024 17:21:22 +0200 Subject: [PATCH 11/34] wind_est_replay: allow setting the initial scale factor --- src/lib/wind_estimator/python/wind_estimator_replay.py | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/src/lib/wind_estimator/python/wind_estimator_replay.py b/src/lib/wind_estimator/python/wind_estimator_replay.py index a44d62db4fd1..0a165dfe8df4 100644 --- a/src/lib/wind_estimator/python/wind_estimator_replay.py +++ b/src/lib/wind_estimator/python/wind_estimator_replay.py @@ -54,7 +54,7 @@ def getData(log, topic_name, variable_name, instance=0): def us2s(time_ms): return time_ms * 1e-6 -def run(logfile, use_gnss): +def run(logfile, use_gnss, scale_init): log = ULog(logfile) if use_gnss: @@ -75,7 +75,10 @@ def run(logfile, use_gnss): dist_bottom = getData(log, 'vehicle_local_position', 'dist_bottom') t_dist_bottom = us2s(getData(log, 'vehicle_local_position', 'timestamp')) - state = np.array([0.0, 0.0, 1.0]) + if scale_init is None: + scale_init = 1.0 + + state = np.array([0.0, 0.0, scale_init]) P = np.diag([1.0, 1.0, 1e-4]) wind_nsd = 1e-2 scale_nsd = 1e-4 @@ -145,8 +148,9 @@ def run(logfile, use_gnss): parser.add_argument('logfile', help='Full ulog file path, name and extension', type=str) parser.add_argument('--gnss', help='Use GNSS velocity instead of local velocity estimate', action='store_true') + parser.add_argument('--scale_init', help='Initial airsped scale factor (1.0 if not specified)', type=float) args = parser.parse_args() logfile = os.path.abspath(args.logfile) # Convert to absolute path - run(logfile, args.gnss) + run(logfile, args.gnss, args.scale_init) From 95ae5a657d900d80ed07772ff711ed5909d6140b Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 29 Apr 2024 11:37:16 -0400 Subject: [PATCH 12/34] ekf2: merge mag_3d_control + mag_control --- src/modules/ekf2/CMakeLists.txt | 1 - src/modules/ekf2/EKF/CMakeLists.txt | 1 - .../magnetometer/mag_3d_control.cpp | 225 ------------------ .../aid_sources/magnetometer/mag_control.cpp | 205 +++++++++++++++- src/modules/ekf2/EKF/ekf.h | 1 - 5 files changed, 196 insertions(+), 237 deletions(-) delete mode 100644 src/modules/ekf2/EKF/aid_sources/magnetometer/mag_3d_control.cpp diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index 7e9fcb7abf88..f21ce26d1142 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -187,7 +187,6 @@ endif() if(CONFIG_EKF2_MAGNETOMETER) list(APPEND EKF_SRCS - EKF/aid_sources/magnetometer/mag_3d_control.cpp EKF/aid_sources/magnetometer/mag_control.cpp EKF/aid_sources/magnetometer/mag_fusion.cpp ) diff --git a/src/modules/ekf2/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt index 03c9a481667b..fa57df04c735 100644 --- a/src/modules/ekf2/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -109,7 +109,6 @@ endif() if(CONFIG_EKF2_MAGNETOMETER) list(APPEND EKF_SRCS - aid_sources/magnetometer/mag_3d_control.cpp aid_sources/magnetometer/mag_control.cpp aid_sources/magnetometer/mag_fusion.cpp ) diff --git a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_3d_control.cpp b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_3d_control.cpp deleted file mode 100644 index 41192f2cbf64..000000000000 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_3d_control.cpp +++ /dev/null @@ -1,225 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2023 PX4 Development Team. 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. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "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 - * COPYRIGHT OWNER OR CONTRIBUTORS 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. - * - ****************************************************************************/ - -/** - * @file mag_3d_control.cpp - * Control functions for ekf mag 3D fusion - */ - -#include "ekf.h" - -void Ekf::controlMag3DFusion(const magSample &mag_sample, const bool common_starting_conditions_passing, - estimator_aid_source3d_s &aid_src) -{ - static constexpr const char *AID_SRC_NAME = "mag"; - - resetEstimatorAidStatus(aid_src); - - const bool wmm_updated = (_wmm_gps_time_last_set >= aid_src.time_last_fuse); // WMM update can occur on the last epoch, just after mag fusion - - // determine if we should use mag fusion - bool continuing_conditions_passing = (_params.mag_fusion_type != MagFuseType::NONE) - && _control_status.flags.tilt_align - && (_control_status.flags.yaw_align || (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align)) - && mag_sample.mag.longerThan(0.f) - && mag_sample.mag.isAllFinite(); - - const bool starting_conditions_passing = common_starting_conditions_passing - && continuing_conditions_passing; - - // For the first few seconds after in-flight alignment we allow the magnetic field state estimates to stabilise - // before they are used to constrain heading drift - _control_status.flags.mag_3D = (_params.mag_fusion_type == MagFuseType::AUTO) - && _control_status.flags.mag - && _control_status.flags.mag_aligned_in_flight - && (_control_status.flags.mag_heading_consistent || !_control_status.flags.gps) - && !_control_status.flags.mag_fault - && !_control_status.flags.ev_yaw - && !_control_status.flags.gps_yaw; - - const bool mag_consistent_or_no_gnss = _control_status.flags.mag_heading_consistent || !_control_status.flags.gps; - - _control_status.flags.mag_hdg = ((_params.mag_fusion_type == MagFuseType::HEADING) - || (_params.mag_fusion_type == MagFuseType::AUTO && !_control_status.flags.mag_3D)) - && _control_status.flags.tilt_align - && ((_control_status.flags.yaw_align && mag_consistent_or_no_gnss) - || (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align)) - && !_control_status.flags.mag_fault - && !_control_status.flags.mag_field_disturbed - && !_control_status.flags.ev_yaw - && !_control_status.flags.gps_yaw; - - // TODO: allow clearing mag_fault if mag_3d is good? - - if (_control_status.flags.mag_3D && !_control_status_prev.flags.mag_3D) { - ECL_INFO("starting mag 3D fusion"); - - } else if (!_control_status.flags.mag_3D && _control_status_prev.flags.mag_3D) { - ECL_INFO("stopping mag 3D fusion"); - } - - // if we are using 3-axis magnetometer fusion, but without external NE aiding, - // then the declination must be fused as an observation to prevent long term heading drift - // fusing declination when gps aiding is available is optional. - const bool not_using_ne_aiding = !_control_status.flags.gps && !_control_status.flags.aux_gpos; - _control_status.flags.mag_dec = (_control_status.flags.mag && (not_using_ne_aiding || !_control_status.flags.mag_aligned_in_flight)); - - if (_control_status.flags.mag) { - aid_src.timestamp_sample = mag_sample.time_us; - - if (continuing_conditions_passing && _control_status.flags.yaw_align) { - - if (mag_sample.reset || checkHaglYawResetReq() || wmm_updated) { - ECL_INFO("reset to %s", AID_SRC_NAME); - resetMagStates(_mag_lpf.getState(), _control_status.flags.mag_hdg || _control_status.flags.mag_3D); - aid_src.time_last_fuse = _time_delayed_us; - - } else { - if (!_mag_decl_cov_reset) { - // After any magnetic field covariance reset event the earth field state - // covariances need to be corrected to incorporate knowledge of the declination - // before fusing magnetometer data to prevent rapid rotation of the earth field - // states for the first few observations. - fuseDeclination(0.02f); - _mag_decl_cov_reset = true; - fuseMag(mag_sample.mag, aid_src, false); - - } else { - // The normal sequence is to fuse the magnetometer data first before fusing - // declination angle at a higher uncertainty to allow some learning of - // declination angle over time. - const bool update_all_states = _control_status.flags.mag_3D || _control_status.flags.mag_hdg; - const bool update_tilt = _control_status.flags.mag_3D; - fuseMag(mag_sample.mag, aid_src, update_all_states, update_tilt); - - if (_control_status.flags.mag_dec) { - fuseDeclination(0.5f); - } - } - } - - const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.reset_timeout_max); - - if (is_fusion_failing) { - if (_nb_mag_3d_reset_available > 0) { - // Data seems good, attempt a reset (mag states only unless mag_3D currently active) - ECL_WARN("%s fusion failing, resetting", AID_SRC_NAME); - resetMagStates(_mag_lpf.getState(), _control_status.flags.mag_hdg || _control_status.flags.mag_3D); - aid_src.time_last_fuse = _time_delayed_us; - - if (_control_status.flags.in_air) { - _nb_mag_3d_reset_available--; - } - - } else if (starting_conditions_passing) { - // Data seems good, but previous reset did not fix the issue - // something else must be wrong, declare the sensor faulty and stop the fusion - //_control_status.flags.mag_fault = true; - ECL_WARN("stopping %s fusion, starting conditions failing", AID_SRC_NAME); - stopMagFusion(); - - } else { - // A reset did not fix the issue but all the starting checks are not passing - // This could be a temporary issue, stop the fusion without declaring the sensor faulty - ECL_WARN("stopping %s, fusion failing", AID_SRC_NAME); - stopMagFusion(); - } - } - - } else { - // Stop fusion but do not declare it faulty - ECL_DEBUG("stopping %s fusion, continuing conditions no longer passing", AID_SRC_NAME); - stopMagFusion(); - } - - } else { - if (starting_conditions_passing) { - - _control_status.flags.mag = true; - - // activate fusion, reset mag states and initialize variance if first init or in flight reset - if (!_control_status.flags.yaw_align - || wmm_updated - || !_mag_decl_cov_reset - || !_state.mag_I.longerThan(0.f) - || (getStateVariance().min() < kMagVarianceMin) - || (getStateVariance().min() < kMagVarianceMin) - ) { - ECL_INFO("starting %s fusion, resetting states", AID_SRC_NAME); - - bool reset_heading = !_control_status.flags.yaw_align; - - resetMagStates(_mag_lpf.getState(), reset_heading); - - if (reset_heading) { - _control_status.flags.yaw_align = true; - } - - } else { - ECL_INFO("starting %s fusion", AID_SRC_NAME); - fuseMag(mag_sample.mag, aid_src, false); - } - - aid_src.time_last_fuse = _time_delayed_us; - - _nb_mag_3d_reset_available = 2; - } - } -} - -void Ekf::stopMagFusion() -{ - if (_control_status.flags.mag) { - ECL_INFO("stopping mag fusion"); - - _control_status.flags.mag = false; - _control_status.flags.mag_dec = false; - - if (_control_status.flags.mag_3D) { - ECL_INFO("stopping mag 3D fusion"); - _control_status.flags.mag_3D = false; - } - - if (_control_status.flags.mag_hdg) { - ECL_INFO("stopping mag heading fusion"); - _control_status.flags.mag_hdg = false; - _fault_status.flags.bad_hdg = false; - } - - _fault_status.flags.bad_mag_x = false; - _fault_status.flags.bad_mag_y = false; - _fault_status.flags.bad_mag_z = false; - - _fault_status.flags.bad_mag_decl = false; - } -} diff --git a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp index 5497d427f49f..936d141eb054 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -41,6 +41,9 @@ void Ekf::controlMagFusion() { + static constexpr const char *AID_SRC_NAME = "mag"; + estimator_aid_source3d_s &aid_src = _aid_src_mag; + // reset the flight alignment flag so that the mag fields will be // re-initialised next time we achieve flight altitude if (!_control_status_prev.flags.in_air && _control_status.flags.in_air) { @@ -65,8 +68,10 @@ void Ekf::controlMagFusion() if (_mag_buffer && _mag_buffer->pop_first_older_than(_time_delayed_us, &mag_sample)) { + resetEstimatorAidStatus(aid_src); + if (mag_sample.reset || (_mag_counter == 0)) { - // sensor or calibration has changed, reset low pass filter (reset handled by controlMag3DFusion/controlMagHeadingFusion) + // sensor or calibration has changed, reset low pass filter _control_status.flags.mag_fault = false; _state.mag_B.zero(); @@ -80,13 +85,6 @@ void Ekf::controlMagFusion() _mag_counter++; } - const bool starting_conditions_passing = (_params.mag_fusion_type != MagFuseType::NONE) - && checkMagField(mag_sample.mag) - && (_mag_counter > 5) // wait until we have more than a few samples through the filter - && (_control_status.flags.yaw_align == _control_status_prev.flags.yaw_align) // no yaw alignment change this frame - && (_state_reset_status.reset_count.quat == _state_reset_count_prev.quat) // don't allow starting on same frame as yaw reset - && isNewestSampleRecent(_time_last_mag_buffer_push, MAG_MAX_INTERVAL); - // if enabled, use knowledge of theoretical magnetic field vector to calculate a synthetic magnetomter Z component value. // this is useful if there is a lot of interference on the sensor measurement. if (_params.synthesize_mag_z && (_params.mag_declination_source & GeoDeclinationMask::USE_GEO_DECL) @@ -103,8 +101,166 @@ void Ekf::controlMagFusion() _control_status.flags.synthetic_mag_z = false; } + // determine if we should use mag fusion + bool continuing_conditions_passing = (_params.mag_fusion_type != MagFuseType::NONE) + && _control_status.flags.tilt_align + && (_control_status.flags.yaw_align || (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align)) + && mag_sample.mag.longerThan(0.f) + && mag_sample.mag.isAllFinite(); + + const bool starting_conditions_passing = continuing_conditions_passing + && checkMagField(mag_sample.mag) + && (_mag_counter > 5) // wait until we have more than a few samples through the filter + && (_control_status.flags.yaw_align == _control_status_prev.flags.yaw_align) // no yaw alignment change this frame + && (_state_reset_status.reset_count.quat == _state_reset_count_prev.quat) // don't allow starting on same frame as yaw reset + && isNewestSampleRecent(_time_last_mag_buffer_push, MAG_MAX_INTERVAL); + + checkMagHeadingConsistency(mag_sample); - controlMag3DFusion(mag_sample, starting_conditions_passing, _aid_src_mag); + + // WMM update can occur on the last epoch, just after mag fusion + const bool wmm_updated = (_wmm_gps_time_last_set >= aid_src.time_last_fuse); + + + // For the first few seconds after in-flight alignment we allow the magnetic field state estimates to stabilise + // before they are used to constrain heading drift + _control_status.flags.mag_3D = (_params.mag_fusion_type == MagFuseType::AUTO) + && _control_status.flags.mag + && _control_status.flags.mag_aligned_in_flight + && (_control_status.flags.mag_heading_consistent || !_control_status.flags.gps) + && !_control_status.flags.mag_fault + && !_control_status.flags.ev_yaw + && !_control_status.flags.gps_yaw; + + const bool mag_consistent_or_no_gnss = _control_status.flags.mag_heading_consistent || !_control_status.flags.gps; + + _control_status.flags.mag_hdg = ((_params.mag_fusion_type == MagFuseType::HEADING) + || (_params.mag_fusion_type == MagFuseType::AUTO && !_control_status.flags.mag_3D)) + && _control_status.flags.tilt_align + && ((_control_status.flags.yaw_align && mag_consistent_or_no_gnss) + || (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align)) + && !_control_status.flags.mag_fault + && !_control_status.flags.mag_field_disturbed + && !_control_status.flags.ev_yaw + && !_control_status.flags.gps_yaw; + + // TODO: allow clearing mag_fault if mag_3d is good? + + if (_control_status.flags.mag_3D && !_control_status_prev.flags.mag_3D) { + ECL_INFO("starting mag 3D fusion"); + + } else if (!_control_status.flags.mag_3D && _control_status_prev.flags.mag_3D) { + ECL_INFO("stopping mag 3D fusion"); + } + + // if we are using 3-axis magnetometer fusion, but without external NE aiding, + // then the declination must be fused as an observation to prevent long term heading drift + // fusing declination when gps aiding is available is optional. + const bool not_using_ne_aiding = !_control_status.flags.gps && !_control_status.flags.aux_gpos; + _control_status.flags.mag_dec = _control_status.flags.mag + && (not_using_ne_aiding || !_control_status.flags.mag_aligned_in_flight); + + if (_control_status.flags.mag) { + aid_src.timestamp_sample = mag_sample.time_us; + + if (continuing_conditions_passing && _control_status.flags.yaw_align) { + + if (mag_sample.reset || checkHaglYawResetReq() || wmm_updated) { + ECL_INFO("reset to %s", AID_SRC_NAME); + resetMagStates(_mag_lpf.getState(), _control_status.flags.mag_hdg || _control_status.flags.mag_3D); + aid_src.time_last_fuse = _time_delayed_us; + + } else { + if (!_mag_decl_cov_reset) { + // After any magnetic field covariance reset event the earth field state + // covariances need to be corrected to incorporate knowledge of the declination + // before fusing magnetometer data to prevent rapid rotation of the earth field + // states for the first few observations. + fuseDeclination(0.02f); + _mag_decl_cov_reset = true; + fuseMag(mag_sample.mag, aid_src, false); + + } else { + // The normal sequence is to fuse the magnetometer data first before fusing + // declination angle at a higher uncertainty to allow some learning of + // declination angle over time. + const bool update_all_states = _control_status.flags.mag_3D || _control_status.flags.mag_hdg; + const bool update_tilt = _control_status.flags.mag_3D; + fuseMag(mag_sample.mag, aid_src, update_all_states, update_tilt); + + if (_control_status.flags.mag_dec) { + fuseDeclination(0.5f); + } + } + } + + const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.reset_timeout_max); + + if (is_fusion_failing) { + if (_nb_mag_3d_reset_available > 0) { + // Data seems good, attempt a reset (mag states only unless mag_3D currently active) + ECL_WARN("%s fusion failing, resetting", AID_SRC_NAME); + resetMagStates(_mag_lpf.getState(), _control_status.flags.mag_hdg || _control_status.flags.mag_3D); + aid_src.time_last_fuse = _time_delayed_us; + + if (_control_status.flags.in_air) { + _nb_mag_3d_reset_available--; + } + + } else if (starting_conditions_passing) { + // Data seems good, but previous reset did not fix the issue + // something else must be wrong, declare the sensor faulty and stop the fusion + //_control_status.flags.mag_fault = true; + ECL_WARN("stopping %s fusion, starting conditions failing", AID_SRC_NAME); + stopMagFusion(); + + } else { + // A reset did not fix the issue but all the starting checks are not passing + // This could be a temporary issue, stop the fusion without declaring the sensor faulty + ECL_WARN("stopping %s, fusion failing", AID_SRC_NAME); + stopMagFusion(); + } + } + + } else { + // Stop fusion but do not declare it faulty + ECL_DEBUG("stopping %s fusion, continuing conditions no longer passing", AID_SRC_NAME); + stopMagFusion(); + } + + } else { + if (starting_conditions_passing) { + + _control_status.flags.mag = true; + + // activate fusion, reset mag states and initialize variance if first init or in flight reset + if (!_control_status.flags.yaw_align + || wmm_updated + || !_mag_decl_cov_reset + || !_state.mag_I.longerThan(0.f) + || (getStateVariance().min() < kMagVarianceMin) + || (getStateVariance().min() < kMagVarianceMin) + ) { + ECL_INFO("starting %s fusion, resetting states", AID_SRC_NAME); + + bool reset_heading = !_control_status.flags.yaw_align; + + resetMagStates(_mag_lpf.getState(), reset_heading); + + if (reset_heading) { + _control_status.flags.yaw_align = true; + } + + } else { + ECL_INFO("starting %s fusion", AID_SRC_NAME); + fuseMag(mag_sample.mag, aid_src, false); + } + + aid_src.time_last_fuse = _time_delayed_us; + + _nb_mag_3d_reset_available = 2; + } + } } else if (!isNewestSampleRecent(_time_last_mag_buffer_push, 2 * MAG_MAX_INTERVAL)) { // No data anymore. Stop until it comes back. @@ -112,9 +268,37 @@ void Ekf::controlMagFusion() } } +void Ekf::stopMagFusion() +{ + if (_control_status.flags.mag) { + ECL_INFO("stopping mag fusion"); + + _control_status.flags.mag = false; + _control_status.flags.mag_dec = false; + + if (_control_status.flags.mag_3D) { + ECL_INFO("stopping mag 3D fusion"); + _control_status.flags.mag_3D = false; + } + + if (_control_status.flags.mag_hdg) { + ECL_INFO("stopping mag heading fusion"); + _control_status.flags.mag_hdg = false; + _fault_status.flags.bad_hdg = false; + } + + _fault_status.flags.bad_mag_x = false; + _fault_status.flags.bad_mag_y = false; + _fault_status.flags.bad_mag_z = false; + + _fault_status.flags.bad_mag_decl = false; + } +} + bool Ekf::checkHaglYawResetReq() const { #if defined(CONFIG_EKF2_TERRAIN) + // We need to reset the yaw angle after climbing away from the ground to enable // recovery from ground level magnetic interference. if (_control_status.flags.in_air && _control_status.flags.yaw_align && !_control_status.flags.mag_aligned_in_flight) { @@ -124,6 +308,7 @@ bool Ekf::checkHaglYawResetReq() const const bool above_mag_anomalies = (getTerrainVPos() - _state.pos(2)) > mag_anomalies_max_hagl; return above_mag_anomalies; } + #endif // CONFIG_EKF2_TERRAIN return false; @@ -147,6 +332,7 @@ void Ekf::resetMagStates(const Vector3f &mag, bool reset_heading) // mag_B: reset #if defined(CONFIG_EKF2_GNSS) + if (isYawEmergencyEstimateAvailable()) { const Dcmf R_to_earth = updateYawInRotMat(_yawEstimator.getYaw(), _R_to_earth); @@ -159,6 +345,7 @@ void Ekf::resetMagStates(const Vector3f &mag, bool reset_heading) } else if (!reset_heading && _control_status.flags.yaw_align) { #else + if (!reset_heading && _control_status.flags.yaw_align) { #endif // mag_B: reset using WMM diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 77ddfc721422..91b4682d8262 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -1025,7 +1025,6 @@ class Ekf final : public EstimatorInterface #if defined(CONFIG_EKF2_MAGNETOMETER) // control fusion of magnetometer observations void controlMagFusion(); - void controlMag3DFusion(const magSample &mag_sample, const bool common_starting_conditions_passing, estimator_aid_source3d_s &aid_src); bool checkHaglYawResetReq() const; From bfc39cf3419aaf2b6cc21ae2b44d2f866866cbb5 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 29 Apr 2024 12:15:19 -0400 Subject: [PATCH 13/34] ekf2: mag control always populate estimator aid src --- .../aid_sources/magnetometer/mag_control.cpp | 44 +++++-- .../aid_sources/magnetometer/mag_fusion.cpp | 119 +++++------------- src/modules/ekf2/EKF/ekf.h | 2 +- 3 files changed, 71 insertions(+), 94 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp index 936d141eb054..f6da31311229 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -39,6 +39,8 @@ #include "ekf.h" #include +#include + void Ekf::controlMagFusion() { static constexpr const char *AID_SRC_NAME = "mag"; @@ -68,8 +70,6 @@ void Ekf::controlMagFusion() if (_mag_buffer && _mag_buffer->pop_first_older_than(_time_delayed_us, &mag_sample)) { - resetEstimatorAidStatus(aid_src); - if (mag_sample.reset || (_mag_counter == 0)) { // sensor or calibration has changed, reset low pass filter _control_status.flags.mag_fault = false; @@ -101,6 +101,37 @@ void Ekf::controlMagFusion() _control_status.flags.synthetic_mag_z = false; } + + resetEstimatorAidStatus(aid_src); + aid_src.timestamp_sample = mag_sample.time_us; + + // XYZ Measurement uncertainty. Need to consider timing errors for fast rotations + const float R_MAG = math::max(sq(_params.mag_noise), sq(0.01f)); + + // calculate intermediate variables used for X axis innovation variance, observation Jacobians and Kalman gains + Vector3f mag_innov; + Vector3f innov_var; + + // Observation jacobian and Kalman gain vectors + VectorState H; + sym::ComputeMagInnovInnovVarAndHx(_state.vector(), P, mag_sample.mag, R_MAG, FLT_EPSILON, &mag_innov, &innov_var, &H); + + // do not use the synthesized measurement for the magnetomter Z component for 3D fusion + if (_control_status.flags.synthetic_mag_z) { + mag_innov(2) = 0.0f; + } + + for (int i = 0; i < 3; i++) { + aid_src.observation[i] = mag_sample.mag(i); + aid_src.observation_variance[i] = R_MAG; + aid_src.innovation[i] = mag_innov(i); + aid_src.innovation_variance[i] = innov_var(i); + } + + const float innov_gate = math::max(_params.mag_innov_gate, 1.f); + setEstimatorAidStatusTestRatio(aid_src, innov_gate); + + // determine if we should use mag fusion bool continuing_conditions_passing = (_params.mag_fusion_type != MagFuseType::NONE) && _control_status.flags.tilt_align @@ -136,7 +167,7 @@ void Ekf::controlMagFusion() _control_status.flags.mag_hdg = ((_params.mag_fusion_type == MagFuseType::HEADING) || (_params.mag_fusion_type == MagFuseType::AUTO && !_control_status.flags.mag_3D)) - && _control_status.flags.tilt_align + && _control_status.flags.mag && ((_control_status.flags.yaw_align && mag_consistent_or_no_gnss) || (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align)) && !_control_status.flags.mag_fault @@ -161,7 +192,6 @@ void Ekf::controlMagFusion() && (not_using_ne_aiding || !_control_status.flags.mag_aligned_in_flight); if (_control_status.flags.mag) { - aid_src.timestamp_sample = mag_sample.time_us; if (continuing_conditions_passing && _control_status.flags.yaw_align) { @@ -178,7 +208,7 @@ void Ekf::controlMagFusion() // states for the first few observations. fuseDeclination(0.02f); _mag_decl_cov_reset = true; - fuseMag(mag_sample.mag, aid_src, false); + fuseMag(mag_sample.mag, H, aid_src, false); } else { // The normal sequence is to fuse the magnetometer data first before fusing @@ -186,7 +216,7 @@ void Ekf::controlMagFusion() // declination angle over time. const bool update_all_states = _control_status.flags.mag_3D || _control_status.flags.mag_hdg; const bool update_tilt = _control_status.flags.mag_3D; - fuseMag(mag_sample.mag, aid_src, update_all_states, update_tilt); + fuseMag(mag_sample.mag, H, aid_src, update_all_states, update_tilt); if (_control_status.flags.mag_dec) { fuseDeclination(0.5f); @@ -253,7 +283,7 @@ void Ekf::controlMagFusion() } else { ECL_INFO("starting %s fusion", AID_SRC_NAME); - fuseMag(mag_sample.mag, aid_src, false); + fuseMag(mag_sample.mag, H, aid_src, false); } aid_src.time_last_fuse = _time_delayed_us; diff --git a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp index 1dbff8874c0f..0b79edb77fd2 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp @@ -43,7 +43,6 @@ #include "ekf.h" -#include #include #include @@ -51,39 +50,17 @@ #include -bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bool update_all_states, bool update_tilt) +bool Ekf::fuseMag(const Vector3f &mag, VectorState &H, estimator_aid_source3d_s &aid_src, bool update_all_states, bool update_tilt) { // XYZ Measurement uncertainty. Need to consider timing errors for fast rotations const float R_MAG = math::max(sq(_params.mag_noise), sq(0.01f)); - // calculate intermediate variables used for X axis innovation variance, observation Jacobians and Kalman gains - Vector3f mag_innov; - Vector3f innov_var; - - // Observation jacobian and Kalman gain vectors - VectorState H; const auto state_vector = _state.vector(); - sym::ComputeMagInnovInnovVarAndHx(state_vector, P, mag, R_MAG, FLT_EPSILON, &mag_innov, &innov_var, &H); - - // do not use the synthesized measurement for the magnetomter Z component for 3D fusion - if (_control_status.flags.synthetic_mag_z) { - mag_innov(2) = 0.0f; - } - - for (int i = 0; i < 3; i++) { - aid_src_mag.observation[i] = mag(i) - _state.mag_B(i); - aid_src_mag.observation_variance[i] = R_MAG; - aid_src_mag.innovation[i] = mag_innov(i); - aid_src_mag.innovation_variance[i] = innov_var(i); - } - - const float innov_gate = math::max(_params.mag_innov_gate, 1.f); - setEstimatorAidStatusTestRatio(aid_src_mag, innov_gate); if (update_all_states) { - _fault_status.flags.bad_mag_x = (aid_src_mag.innovation_variance[0] < aid_src_mag.observation_variance[0]); - _fault_status.flags.bad_mag_y = (aid_src_mag.innovation_variance[1] < aid_src_mag.observation_variance[1]); - _fault_status.flags.bad_mag_z = (aid_src_mag.innovation_variance[2] < aid_src_mag.observation_variance[2]); + _fault_status.flags.bad_mag_x = (aid_src.innovation_variance[0] < aid_src.observation_variance[0]); + _fault_status.flags.bad_mag_y = (aid_src.innovation_variance[1] < aid_src.observation_variance[1]); + _fault_status.flags.bad_mag_z = (aid_src.innovation_variance[2] < aid_src.observation_variance[2]); } else { _fault_status.flags.bad_mag_x = false; @@ -92,28 +69,12 @@ bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bo } // Perform an innovation consistency check and report the result - _innov_check_fail_status.flags.reject_mag_x = (aid_src_mag.test_ratio[0] > 1.f); - _innov_check_fail_status.flags.reject_mag_y = (aid_src_mag.test_ratio[1] > 1.f); - _innov_check_fail_status.flags.reject_mag_z = (aid_src_mag.test_ratio[2] > 1.f); - - const char *numerical_error_covariance_reset_string = "numerical error - covariance reset"; - - // check innovation variances for being badly conditioned - if (innov_var.min() < R_MAG) { - // the innovation variance contribution from the state covariances is negative which means the covariance matrix is badly conditioned - // we need to re-initialise covariances and abort this fusion step - if (update_all_states) { - resetQuatCov(_params.mag_heading_noise); - } - - resetMagCov(); - - ECL_ERR("mag %s", numerical_error_covariance_reset_string); - return false; - } + _innov_check_fail_status.flags.reject_mag_x = (aid_src.test_ratio[0] > 1.f); + _innov_check_fail_status.flags.reject_mag_y = (aid_src.test_ratio[1] > 1.f); + _innov_check_fail_status.flags.reject_mag_z = (aid_src.test_ratio[2] > 1.f); // if any axis fails, abort the mag fusion - if (aid_src_mag.innovation_rejected) { + if (aid_src.innovation_rejected) { return false; } @@ -127,25 +88,10 @@ bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bo } else if (index == 1) { // recalculate innovation variance because state covariances have changed due to previous fusion (linearise using the same initial state for all axes) - sym::ComputeMagYInnovVarAndH(state_vector, P, R_MAG, FLT_EPSILON, &aid_src_mag.innovation_variance[index], &H); + sym::ComputeMagYInnovVarAndH(state_vector, P, R_MAG, FLT_EPSILON, &aid_src.innovation_variance[index], &H); // recalculate innovation using the updated state - aid_src_mag.innovation[index] = _state.quat_nominal.rotateVectorInverse(_state.mag_I)(index) + _state.mag_B(index) - mag(index); - - if (aid_src_mag.innovation_variance[index] < R_MAG) { - // the innovation variance contribution from the state covariances is negative which means the covariance matrix is badly conditioned - _fault_status.flags.bad_mag_y = true; - - // we need to re-initialise covariances and abort this fusion step - if (update_all_states) { - resetQuatCov(_params.mag_heading_noise); - } - - resetMagCov(); - - ECL_ERR("magY %s", numerical_error_covariance_reset_string); - return false; - } + aid_src.innovation[index] = _state.quat_nominal.rotateVectorInverse(_state.mag_I)(index) + _state.mag_B(index) - mag(index); } else if (index == 2) { // we do not fuse synthesized magnetomter measurements when doing 3D fusion @@ -155,28 +101,33 @@ bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bo } // recalculate innovation variance because state covariances have changed due to previous fusion (linearise using the same initial state for all axes) - sym::ComputeMagZInnovVarAndH(state_vector, P, R_MAG, FLT_EPSILON, &aid_src_mag.innovation_variance[index], &H); + sym::ComputeMagZInnovVarAndH(state_vector, P, R_MAG, FLT_EPSILON, &aid_src.innovation_variance[index], &H); // recalculate innovation using the updated state - aid_src_mag.innovation[index] = _state.quat_nominal.rotateVectorInverse(_state.mag_I)(index) + _state.mag_B(index) - mag(index); - - if (aid_src_mag.innovation_variance[index] < R_MAG) { - // the innovation variance contribution from the state covariances is negative which means the covariance matrix is badly conditioned - _fault_status.flags.bad_mag_z = true; + aid_src.innovation[index] = _state.quat_nominal.rotateVectorInverse(_state.mag_I)(index) + _state.mag_B(index) - mag(index); + } - // we need to re-initialise covariances and abort this fusion step - if (update_all_states) { - resetQuatCov(_params.mag_heading_noise); - } + if (aid_src.innovation_variance[index] < R_MAG) { + // the innovation variance contribution from the state covariances is negative which means the covariance matrix is badly conditioned + if (update_all_states) { + _fault_status.flags.bad_mag_x = (aid_src.innovation_variance[0] < aid_src.observation_variance[0]); + _fault_status.flags.bad_mag_y = (aid_src.innovation_variance[1] < aid_src.observation_variance[1]); + _fault_status.flags.bad_mag_z = (aid_src.innovation_variance[2] < aid_src.observation_variance[2]); + } - resetMagCov(); + ECL_ERR("mag numerical error covariance reset"); - ECL_ERR("magZ %s", numerical_error_covariance_reset_string); - return false; + // we need to re-initialise covariances and abort this fusion step + if (update_all_states) { + resetQuatCov(_params.mag_heading_noise); } + + resetMagCov(); + + return false; } - VectorState Kfusion = P * H / aid_src_mag.innovation_variance[index]; + VectorState Kfusion = P * H / aid_src.innovation_variance[index]; if (!update_all_states) { // zero non-mag Kalman gains if not updating all states @@ -192,16 +143,13 @@ bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bo } if (!update_tilt) { - Kfusion(State::quat_nominal.idx) = 0.f; + Kfusion(State::quat_nominal.idx + 0) = 0.f; Kfusion(State::quat_nominal.idx + 1) = 0.f; } - if (measurementUpdate(Kfusion, H, aid_src_mag.observation_variance[index], aid_src_mag.innovation[index])) { + if (measurementUpdate(Kfusion, H, aid_src.observation_variance[index], aid_src.innovation[index])) { fused[index] = true; limitDeclination(); - - } else { - fused[index] = false; } } @@ -212,8 +160,8 @@ bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bo } if (fused[0] && fused[1] && fused[2]) { - aid_src_mag.fused = true; - aid_src_mag.time_last_fuse = _time_delayed_us; + aid_src.fused = true; + aid_src.time_last_fuse = _time_delayed_us; if (update_all_states) { _time_last_heading_fuse = _time_delayed_us; @@ -222,7 +170,6 @@ bool Ekf::fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bo return true; } - aid_src_mag.fused = false; return false; } diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 91b4682d8262..b326382d83a1 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -758,7 +758,7 @@ class Ekf final : public EstimatorInterface #if defined(CONFIG_EKF2_MAGNETOMETER) // ekf sequential fusion of magnetometer measurements - bool fuseMag(const Vector3f &mag, estimator_aid_source3d_s &aid_src_mag, bool update_all_states = true, bool update_tilt = true); + bool fuseMag(const Vector3f &mag, VectorState &H, estimator_aid_source3d_s &aid_src, bool update_all_states = true, bool update_tilt = true); // fuse magnetometer declination measurement // argument passed in is the declination uncertainty in radians From 5173830718f0a2a337263f786a0e0c63a1135e71 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 29 Apr 2024 12:47:55 -0400 Subject: [PATCH 14/34] ekf2: mag fusion don't update all states or tilt by default - cleanup some of the legacy mag flags --- .../aid_sources/magnetometer/mag_control.cpp | 32 ++++++++++++----- .../aid_sources/magnetometer/mag_fusion.cpp | 36 +++---------------- src/modules/ekf2/EKF/ekf.h | 2 +- 3 files changed, 30 insertions(+), 40 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp index f6da31311229..a919032d8f12 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -101,6 +101,11 @@ void Ekf::controlMagFusion() _control_status.flags.synthetic_mag_z = false; } + // reset flags + _fault_status.flags.bad_mag_x = false; + _fault_status.flags.bad_mag_y = false; + _fault_status.flags.bad_mag_z = false; + resetEstimatorAidStatus(aid_src); aid_src.timestamp_sample = mag_sample.time_us; @@ -131,6 +136,10 @@ void Ekf::controlMagFusion() const float innov_gate = math::max(_params.mag_innov_gate, 1.f); setEstimatorAidStatusTestRatio(aid_src, innov_gate); + // Perform an innovation consistency check and report the result + _innov_check_fail_status.flags.reject_mag_x = (aid_src.test_ratio[0] > 1.f); + _innov_check_fail_status.flags.reject_mag_y = (aid_src.test_ratio[1] > 1.f); + _innov_check_fail_status.flags.reject_mag_z = (aid_src.test_ratio[2] > 1.f); // determine if we should use mag fusion bool continuing_conditions_passing = (_params.mag_fusion_type != MagFuseType::NONE) @@ -208,7 +217,7 @@ void Ekf::controlMagFusion() // states for the first few observations. fuseDeclination(0.02f); _mag_decl_cov_reset = true; - fuseMag(mag_sample.mag, H, aid_src, false); + fuseMag(mag_sample.mag, R_MAG, H, aid_src); } else { // The normal sequence is to fuse the magnetometer data first before fusing @@ -216,7 +225,14 @@ void Ekf::controlMagFusion() // declination angle over time. const bool update_all_states = _control_status.flags.mag_3D || _control_status.flags.mag_hdg; const bool update_tilt = _control_status.flags.mag_3D; - fuseMag(mag_sample.mag, H, aid_src, update_all_states, update_tilt); + fuseMag(mag_sample.mag, R_MAG, H, aid_src, update_all_states, update_tilt); + + // the innovation variance contribution from the state covariances is negative which means the covariance matrix is badly conditioned + if (update_all_states && update_tilt) { + _fault_status.flags.bad_mag_x = (aid_src.innovation_variance[0] < aid_src.observation_variance[0]); + _fault_status.flags.bad_mag_y = (aid_src.innovation_variance[1] < aid_src.observation_variance[1]); + _fault_status.flags.bad_mag_z = (aid_src.innovation_variance[2] < aid_src.observation_variance[2]); + } if (_control_status.flags.mag_dec) { fuseDeclination(0.5f); @@ -276,19 +292,19 @@ void Ekf::controlMagFusion() bool reset_heading = !_control_status.flags.yaw_align; resetMagStates(_mag_lpf.getState(), reset_heading); + aid_src.time_last_fuse = _time_delayed_us; + _nb_mag_3d_reset_available = 2; if (reset_heading) { _control_status.flags.yaw_align = true; } } else { - ECL_INFO("starting %s fusion", AID_SRC_NAME); - fuseMag(mag_sample.mag, H, aid_src, false); + if (fuseMag(mag_sample.mag, R_MAG, H, aid_src)) { + ECL_INFO("starting %s fusion", AID_SRC_NAME); + _nb_mag_3d_reset_available = 2; + } } - - aid_src.time_last_fuse = _time_delayed_us; - - _nb_mag_3d_reset_available = 2; } } diff --git a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp index 0b79edb77fd2..ad03b8533147 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp @@ -50,41 +50,22 @@ #include -bool Ekf::fuseMag(const Vector3f &mag, VectorState &H, estimator_aid_source3d_s &aid_src, bool update_all_states, bool update_tilt) +bool Ekf::fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estimator_aid_source3d_s &aid_src, bool update_all_states, bool update_tilt) { - // XYZ Measurement uncertainty. Need to consider timing errors for fast rotations - const float R_MAG = math::max(sq(_params.mag_noise), sq(0.01f)); - - const auto state_vector = _state.vector(); - - if (update_all_states) { - _fault_status.flags.bad_mag_x = (aid_src.innovation_variance[0] < aid_src.observation_variance[0]); - _fault_status.flags.bad_mag_y = (aid_src.innovation_variance[1] < aid_src.observation_variance[1]); - _fault_status.flags.bad_mag_z = (aid_src.innovation_variance[2] < aid_src.observation_variance[2]); - - } else { - _fault_status.flags.bad_mag_x = false; - _fault_status.flags.bad_mag_y = false; - _fault_status.flags.bad_mag_z = false; - } - - // Perform an innovation consistency check and report the result - _innov_check_fail_status.flags.reject_mag_x = (aid_src.test_ratio[0] > 1.f); - _innov_check_fail_status.flags.reject_mag_y = (aid_src.test_ratio[1] > 1.f); - _innov_check_fail_status.flags.reject_mag_z = (aid_src.test_ratio[2] > 1.f); - - // if any axis fails, abort the mag fusion + // if any axis failed, abort the mag fusion if (aid_src.innovation_rejected) { return false; } + const auto state_vector = _state.vector(); + bool fused[3] {false, false, false}; // update the states and covariance using sequential fusion of the magnetometer components for (uint8_t index = 0; index <= 2; index++) { // Calculate Kalman gains and observation jacobians if (index == 0) { - // everything was already computed above + // everything was already computed } else if (index == 1) { // recalculate innovation variance because state covariances have changed due to previous fusion (linearise using the same initial state for all axes) @@ -108,13 +89,6 @@ bool Ekf::fuseMag(const Vector3f &mag, VectorState &H, estimator_aid_source3d_s } if (aid_src.innovation_variance[index] < R_MAG) { - // the innovation variance contribution from the state covariances is negative which means the covariance matrix is badly conditioned - if (update_all_states) { - _fault_status.flags.bad_mag_x = (aid_src.innovation_variance[0] < aid_src.observation_variance[0]); - _fault_status.flags.bad_mag_y = (aid_src.innovation_variance[1] < aid_src.observation_variance[1]); - _fault_status.flags.bad_mag_z = (aid_src.innovation_variance[2] < aid_src.observation_variance[2]); - } - ECL_ERR("mag numerical error covariance reset"); // we need to re-initialise covariances and abort this fusion step diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index b326382d83a1..95add3dec9ce 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -758,7 +758,7 @@ class Ekf final : public EstimatorInterface #if defined(CONFIG_EKF2_MAGNETOMETER) // ekf sequential fusion of magnetometer measurements - bool fuseMag(const Vector3f &mag, VectorState &H, estimator_aid_source3d_s &aid_src, bool update_all_states = true, bool update_tilt = true); + bool fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estimator_aid_source3d_s &aid_src, bool update_all_states = false, bool update_tilt = false); // fuse magnetometer declination measurement // argument passed in is the declination uncertainty in radians From bb5dfc7d519fa4259253a2d46c4a66936e63a571 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Tue, 30 Apr 2024 10:12:58 -0400 Subject: [PATCH 15/34] integrationtests: mavros/mission_test.py bump yaw_error_std threshold (heading init is delayed, but not wrong) --- integrationtests/python_src/px4_it/mavros/mission_test.py | 2 +- src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/integrationtests/python_src/px4_it/mavros/mission_test.py b/integrationtests/python_src/px4_it/mavros/mission_test.py index 8d7f6e647828..a9dccf728430 100755 --- a/integrationtests/python_src/px4_it/mavros/mission_test.py +++ b/integrationtests/python_src/px4_it/mavros/mission_test.py @@ -308,7 +308,7 @@ def test_mission(self): self.assertTrue(res['pitch_error_std'] < 5.0, str(res)) # TODO: fix by excluding initial heading init and reset preflight - self.assertTrue(res['yaw_error_std'] < 10.0, str(res)) + self.assertTrue(res['yaw_error_std'] < 13.0, str(res)) if __name__ == '__main__': diff --git a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp index a919032d8f12..5bf99650402c 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -150,7 +150,7 @@ void Ekf::controlMagFusion() const bool starting_conditions_passing = continuing_conditions_passing && checkMagField(mag_sample.mag) - && (_mag_counter > 5) // wait until we have more than a few samples through the filter + && (_mag_counter > 3) // wait until we have more than a few samples through the filter && (_control_status.flags.yaw_align == _control_status_prev.flags.yaw_align) // no yaw alignment change this frame && (_state_reset_status.reset_count.quat == _state_reset_count_prev.quat) // don't allow starting on same frame as yaw reset && isNewestSampleRecent(_time_last_mag_buffer_push, MAG_MAX_INTERVAL); From d7960093024a31db0c97730a4fa26bb974464e7e Mon Sep 17 00:00:00 2001 From: bresch Date: Thu, 16 May 2024 16:32:22 +0200 Subject: [PATCH 16/34] mag_ctrl: do not fuse synthetic mag but do not zero the innovation --- .../ekf2/EKF/aid_sources/magnetometer/mag_control.cpp | 5 ----- 1 file changed, 5 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp index 5bf99650402c..90ed1f670458 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -121,11 +121,6 @@ void Ekf::controlMagFusion() VectorState H; sym::ComputeMagInnovInnovVarAndHx(_state.vector(), P, mag_sample.mag, R_MAG, FLT_EPSILON, &mag_innov, &innov_var, &H); - // do not use the synthesized measurement for the magnetomter Z component for 3D fusion - if (_control_status.flags.synthetic_mag_z) { - mag_innov(2) = 0.0f; - } - for (int i = 0; i < 3; i++) { aid_src.observation[i] = mag_sample.mag(i); aid_src.observation_variance[i] = R_MAG; From ea39032b45daaa5155df159f672c189aa627f8cc Mon Sep 17 00:00:00 2001 From: bresch Date: Thu, 16 May 2024 16:33:38 +0200 Subject: [PATCH 17/34] mag_ctrl: combine common conditions for mag_hdg and mag_3d --- .../aid_sources/magnetometer/mag_control.cpp | 39 ++++++++----------- 1 file changed, 17 insertions(+), 22 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp index 90ed1f670458..1601178cd296 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -150,34 +150,29 @@ void Ekf::controlMagFusion() && (_state_reset_status.reset_count.quat == _state_reset_count_prev.quat) // don't allow starting on same frame as yaw reset && isNewestSampleRecent(_time_last_mag_buffer_push, MAG_MAX_INTERVAL); - checkMagHeadingConsistency(mag_sample); // WMM update can occur on the last epoch, just after mag fusion const bool wmm_updated = (_wmm_gps_time_last_set >= aid_src.time_last_fuse); - - // For the first few seconds after in-flight alignment we allow the magnetic field state estimates to stabilise - // before they are used to constrain heading drift - _control_status.flags.mag_3D = (_params.mag_fusion_type == MagFuseType::AUTO) - && _control_status.flags.mag - && _control_status.flags.mag_aligned_in_flight - && (_control_status.flags.mag_heading_consistent || !_control_status.flags.gps) - && !_control_status.flags.mag_fault - && !_control_status.flags.ev_yaw - && !_control_status.flags.gps_yaw; - + { const bool mag_consistent_or_no_gnss = _control_status.flags.mag_heading_consistent || !_control_status.flags.gps; - - _control_status.flags.mag_hdg = ((_params.mag_fusion_type == MagFuseType::HEADING) - || (_params.mag_fusion_type == MagFuseType::AUTO && !_control_status.flags.mag_3D)) - && _control_status.flags.mag - && ((_control_status.flags.yaw_align && mag_consistent_or_no_gnss) - || (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align)) - && !_control_status.flags.mag_fault - && !_control_status.flags.mag_field_disturbed - && !_control_status.flags.ev_yaw - && !_control_status.flags.gps_yaw; + const bool common_conditions_passing = _control_status.flags.mag + && ((_control_status.flags.yaw_align && mag_consistent_or_no_gnss) + || (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align)) + && !_control_status.flags.mag_fault + && !_control_status.flags.mag_field_disturbed + && !_control_status.flags.ev_yaw + && !_control_status.flags.gps_yaw; + + _control_status.flags.mag_3D = common_conditions_passing + && (_params.mag_fusion_type == MagFuseType::AUTO) + && _control_status.flags.mag_aligned_in_flight; + + _control_status.flags.mag_hdg = common_conditions_passing + && ((_params.mag_fusion_type == MagFuseType::HEADING) + || (_params.mag_fusion_type == MagFuseType::AUTO && !_control_status.flags.mag_3D)); + } // TODO: allow clearing mag_fault if mag_3d is good? From d359f6236e483bea635b76c45560160bcfe0abbf Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 17 May 2024 05:20:30 -0400 Subject: [PATCH 18/34] ekf2: symforce zero more efficiently (#23133) - increase symforce CppConfig zero_initialization_sparsity_threshold so that a Matrix setZero() call is performed instead of individually zeroing Co-authored-by: bresch --- .../generated/predict_covariance.h | 255 +----------------- .../ekf_derivation/utils/derivation_utils.py | 2 +- .../ekf2/EKF/yaw_estimator/EKFGSF_yaw.cpp | 3 +- .../derivation/derivation_yaw_estimator.py | 2 +- .../yaw_est_compute_measurement_update.h | 5 +- .../generated/yaw_est_predict_covariance.h | 35 ++- 6 files changed, 24 insertions(+), 278 deletions(-) diff --git a/src/modules/ekf2/EKF/python/ekf_derivation/generated/predict_covariance.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/predict_covariance.h index 5fa0ad1772d1..1ff79d8c7e61 100644 --- a/src/modules/ekf2/EKF/python/ekf_derivation/generated/predict_covariance.h +++ b/src/modules/ekf2/EKF/python/ekf_derivation/generated/predict_covariance.h @@ -236,57 +236,16 @@ matrix::Matrix PredictCovariance(const matrix::Matrix _res; + _res.setZero(); + _res(0, 0) = std::pow(_tmp15, Scalar(2)) * gyro_var + _tmp15 * _tmp27 + _tmp18 * _tmp26 + std::pow(_tmp23, Scalar(2)) * gyro_var + _tmp23 * _tmp25 + _tmp24 * _tmp6 + std::pow(_tmp6, Scalar(2)) * gyro_var; - _res(1, 0) = 0; - _res(2, 0) = 0; - _res(3, 0) = 0; - _res(4, 0) = 0; - _res(5, 0) = 0; - _res(6, 0) = 0; - _res(7, 0) = 0; - _res(8, 0) = 0; - _res(9, 0) = 0; - _res(10, 0) = 0; - _res(11, 0) = 0; - _res(12, 0) = 0; - _res(13, 0) = 0; - _res(14, 0) = 0; - _res(15, 0) = 0; - _res(16, 0) = 0; - _res(17, 0) = 0; - _res(18, 0) = 0; - _res(19, 0) = 0; - _res(20, 0) = 0; - _res(21, 0) = 0; - _res(22, 0) = 0; _res(0, 1) = _tmp15 * _tmp38 + _tmp18 * _tmp35 + _tmp24 * _tmp34 + _tmp25 * _tmp29 + _tmp27 * _tmp36 + _tmp29 * _tmp37 + _tmp34 * _tmp39; _res(1, 1) = _tmp18 * _tmp43 + std::pow(_tmp29, Scalar(2)) * gyro_var + _tmp29 * _tmp40 + std::pow(_tmp34, Scalar(2)) * gyro_var + _tmp34 * _tmp41 + std::pow(_tmp36, Scalar(2)) * gyro_var + _tmp36 * _tmp42; - _res(2, 1) = 0; - _res(3, 1) = 0; - _res(4, 1) = 0; - _res(5, 1) = 0; - _res(6, 1) = 0; - _res(7, 1) = 0; - _res(8, 1) = 0; - _res(9, 1) = 0; - _res(10, 1) = 0; - _res(11, 1) = 0; - _res(12, 1) = 0; - _res(13, 1) = 0; - _res(14, 1) = 0; - _res(15, 1) = 0; - _res(16, 1) = 0; - _res(17, 1) = 0; - _res(18, 1) = 0; - _res(19, 1) = 0; - _res(20, 1) = 0; - _res(21, 1) = 0; - _res(22, 1) = 0; _res(0, 2) = _tmp15 * _tmp47 * gyro_var + _tmp18 * _tmp46 + _tmp24 * _tmp44 + _tmp25 * _tmp45 + _tmp27 * _tmp47 + _tmp37 * _tmp45 + _tmp39 * _tmp44; _res(1, 2) = _tmp18 * _tmp48 + _tmp29 * _tmp45 * gyro_var + _tmp34 * _tmp44 * gyro_var + @@ -294,26 +253,6 @@ matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix PredictCovariance(const matrix::Matrix& P, const if (P_new != nullptr) { matrix::Matrix& _p_new = (*P_new); + _p_new.setZero(); + _p_new(0, 0) = -P(0, 0) * _tmp9 + P(0, 0) - P(1, 0) * _tmp12; - _p_new(1, 0) = 0; - _p_new(2, 0) = 0; _p_new(0, 1) = -P(0, 1) * _tmp9 + P(0, 1) - P(1, 1) * _tmp12; _p_new(1, 1) = -P(0, 1) * _tmp10 - P(1, 1) * _tmp13 + P(1, 1); - _p_new(2, 1) = 0; _p_new(0, 2) = -P(0, 2) * _tmp9 + P(0, 2) - P(1, 2) * _tmp12; _p_new(1, 2) = -P(0, 2) * _tmp10 - P(1, 2) * _tmp13 + P(1, 2); _p_new(2, 2) = -P(0, 2) * _tmp11 - P(1, 2) * _tmp14 + P(2, 2); diff --git a/src/modules/ekf2/EKF/yaw_estimator/derivation/generated/yaw_est_predict_covariance.h b/src/modules/ekf2/EKF/yaw_estimator/derivation/generated/yaw_est_predict_covariance.h index 5d2c4327a55a..d3fefb61d848 100644 --- a/src/modules/ekf2/EKF/yaw_estimator/derivation/generated/yaw_est_predict_covariance.h +++ b/src/modules/ekf2/EKF/yaw_estimator/derivation/generated/yaw_est_predict_covariance.h @@ -24,14 +24,14 @@ namespace sym { * d_ang_var: Scalar * * Outputs: - * P_new: Matrix33 + * res: Matrix33 */ template -void YawEstPredictCovariance(const matrix::Matrix& state, - const matrix::Matrix& P, - const matrix::Matrix& d_vel, const Scalar d_vel_var, - const Scalar d_ang, const Scalar d_ang_var, - matrix::Matrix* const P_new = nullptr) { +matrix::Matrix YawEstPredictCovariance(const matrix::Matrix& state, + const matrix::Matrix& P, + const matrix::Matrix& d_vel, + const Scalar d_vel_var, const Scalar d_ang, + const Scalar d_ang_var) { // Total ops: 39 // Input arrays @@ -48,19 +48,18 @@ void YawEstPredictCovariance(const matrix::Matrix& state, const Scalar _tmp7 = std::pow(d_ang, Scalar(2)) + 1; // Output terms (1) - if (P_new != nullptr) { - matrix::Matrix& _p_new = (*P_new); + matrix::Matrix _res; - _p_new(0, 0) = P(0, 0) + P(2, 0) * _tmp2 + _tmp2 * _tmp3 + _tmp4; - _p_new(1, 0) = 0; - _p_new(2, 0) = 0; - _p_new(0, 1) = P(0, 1) + P(2, 1) * _tmp2 + _tmp3 * _tmp5; - _p_new(1, 1) = P(1, 1) + P(2, 1) * _tmp5 + _tmp4 + _tmp5 * _tmp6; - _p_new(2, 1) = 0; - _p_new(0, 2) = _tmp3 * _tmp7; - _p_new(1, 2) = _tmp6 * _tmp7; - _p_new(2, 2) = P(2, 2) * std::pow(_tmp7, Scalar(2)) + d_ang_var; - } + _res.setZero(); + + _res(0, 0) = P(0, 0) + P(2, 0) * _tmp2 + _tmp2 * _tmp3 + _tmp4; + _res(0, 1) = P(0, 1) + P(2, 1) * _tmp2 + _tmp3 * _tmp5; + _res(1, 1) = P(1, 1) + P(2, 1) * _tmp5 + _tmp4 + _tmp5 * _tmp6; + _res(0, 2) = _tmp3 * _tmp7; + _res(1, 2) = _tmp6 * _tmp7; + _res(2, 2) = P(2, 2) * std::pow(_tmp7, Scalar(2)) + d_ang_var; + + return _res; } // NOLINT(readability/fn_size) // NOLINTNEXTLINE(readability/fn_size) From 470bea9ba84ac6202a707b263bbc2ddee4305b93 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Fri, 17 May 2024 14:30:14 +0200 Subject: [PATCH 19/34] Update NuttX Fixes imxrt1170 mpu config for extra checks --- platforms/nuttx/NuttX/nuttx | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platforms/nuttx/NuttX/nuttx b/platforms/nuttx/NuttX/nuttx index 4be592dd2114..0f401a606265 160000 --- a/platforms/nuttx/NuttX/nuttx +++ b/platforms/nuttx/NuttX/nuttx @@ -1 +1 @@ -Subproject commit 4be592dd2114d2c07505b143493a3cfa6dc9c239 +Subproject commit 0f401a6062653795b6355c420ea8b0e72578c204 From ebfa53286f10776308971424402e9bbb5cca3b42 Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Fri, 17 May 2024 12:00:55 +0200 Subject: [PATCH 20/34] dronecan: SocketCAN driver check size before copying Avoids memory corruption if we get packets to big --- .../uavcan_drivers/socketcan/driver/src/socketcan.cpp | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/src/drivers/uavcan/uavcan_drivers/socketcan/driver/src/socketcan.cpp b/src/drivers/uavcan/uavcan_drivers/socketcan/driver/src/socketcan.cpp index b3a8ce183625..8df5c21b5e12 100644 --- a/src/drivers/uavcan/uavcan_drivers/socketcan/driver/src/socketcan.cpp +++ b/src/drivers/uavcan/uavcan_drivers/socketcan/driver/src/socketcan.cpp @@ -218,12 +218,22 @@ uavcan::int16_t CanIface::receive(uavcan::CanFrame &out_frame, uavcan::Monotonic if (_can_fd) { struct canfd_frame *recv_frame = (struct canfd_frame *)&_recv_frame; out_frame.id = recv_frame->can_id; + + if (recv_frame->len > CANFD_MAX_DLEN) { + return -EFAULT; + } + out_frame.dlc = recv_frame->len; memcpy(out_frame.data, &recv_frame->data, recv_frame->len); } else { struct can_frame *recv_frame = (struct can_frame *)&_recv_frame; out_frame.id = recv_frame->can_id; + + if (recv_frame->can_dlc > CAN_MAX_DLEN) { + return -EFAULT; + } + out_frame.dlc = recv_frame->can_dlc; memcpy(out_frame.data, &recv_frame->data, recv_frame->can_dlc); } From 6b0ac49daf5c49aeb625ed684359fdd59b1a287d Mon Sep 17 00:00:00 2001 From: Peter van der Perk Date: Fri, 17 May 2024 14:27:40 +0200 Subject: [PATCH 21/34] hardfault_log: Add jump to 0x0 & write 0x0 faults --- src/systemcmds/hardfault_log/hardfault_log.c | 18 +++++++++++++++++- 1 file changed, 17 insertions(+), 1 deletion(-) diff --git a/src/systemcmds/hardfault_log/hardfault_log.c b/src/systemcmds/hardfault_log/hardfault_log.c index 0978fc653601..f8ff269ec6b8 100644 --- a/src/systemcmds/hardfault_log/hardfault_log.c +++ b/src/systemcmds/hardfault_log/hardfault_log.c @@ -141,6 +141,21 @@ static int genfault(int fault) /* This is not going to happen */ break; + case 2: + asm("BX %0" : : "r"(0x0)); + /* This is not going to happen */ + break; + + case 3: { + char buffer[128] = {0}; + void *dest = (void *)0x0; + + memcpy(dest, &buffer, 128); + /* This is not going to happen */ + } + break; + + default: break; @@ -1270,7 +1285,8 @@ static void print_usage(void) PRINT_MODULE_USAGE_COMMAND_DESCR("rearm", "Drop an uncommitted hardfault"); PRINT_MODULE_USAGE_COMMAND_DESCR("fault", "Generate a hardfault (this command crashes the system :)"); - PRINT_MODULE_USAGE_ARG("0|1", "Hardfault type: 0=divide by 0, 1=Assertion (default=0)", true); + PRINT_MODULE_USAGE_ARG("0|1|2|3", + "Hardfault type: 0=divide by 0, 1=Assertion, 2=jump to 0x0, 3=write to 0x0 (default=0)", true); PRINT_MODULE_USAGE_COMMAND_DESCR("commit", "Write uncommitted hardfault to /fs/microsd/fault_%i.txt (and rearm, but don't reset)"); From 70304fe7155a47132a4dc2a755a5a24358efb59a Mon Sep 17 00:00:00 2001 From: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Date: Mon, 20 May 2024 12:35:29 -0600 Subject: [PATCH 22/34] [mavlink] Parameter to always start on USB (#22234) * usb: Added parameter to enable always starting mavlink on USB. Refactored cdcacm_init into a module and added a paramter to allow always starting mavlink on USB, also added a paramter to choose the mode. The current default behavior is to wait and listen for data on USB and auto-detect the protocol (mavlink, nsh, ublox). This results in the mavlink stream not starting until something else on the mavlink network sends a packet first. The new default behavior is to always start mavlink. Added parameters MAV_USB_ENABLE -- default 1 (always start mavlink on USB) MAV_USE_MODE -- default 3 (onboard) * added 3 retries for opening serial port in mavlink, removed sleep before sercon * added DRIVERS_CDCACM_AUTOSTART to ark-v6x default.px4board * added CONFIG_DRIVERS_CDCACM_AUTOSTART=y to default.px4board for boards with CONFIG_CDCACM in their nsh/defconfig * format * remove PGA460 from COMMON_DISTANCE_SENSOR to save flash * remove LIS2MDL from COMMON_MAGNETOMETER to save flash * disable CONFIG_DRIVERS_CDCACM_AUTOSTART for fmu-v5 protected.px4board * moved and renamed parameters, removed mode logic in mavlink * changed parameter names, added mode none * remove parameters from mavlink --- ROMFS/px4fmu_common/init.d/rcS | 8 + boards/airmind/mindpx-v2/default.px4board | 1 + boards/ark/fmu-v6x/default.px4board | 2 + boards/atl/mantis-edu/default.px4board | 1 + boards/bitcraze/crazyflie/default.px4board | 1 + boards/bitcraze/crazyflie21/default.px4board | 1 + boards/cuav/nora/default.px4board | 1 + boards/cuav/x7pro/default.px4board | 1 + boards/cubepilot/cubeorange/default.px4board | 1 + .../cubepilot/cubeorangeplus/default.px4board | 1 + boards/cubepilot/cubeyellow/default.px4board | 1 + .../diatone/mamba-f405-mk2/default.px4board | 1 + boards/flywoo/gn-f405/default.px4board | 1 + boards/hkust/nxt-dual/default.px4board | 1 + boards/hkust/nxt-v1/default.px4board | 1 + boards/holybro/durandal-v1/default.px4board | 1 + boards/holybro/kakutef7/default.px4board | 1 + boards/holybro/kakuteh7/default.px4board | 1 + boards/holybro/kakuteh7mini/default.px4board | 1 + boards/holybro/kakuteh7v2/default.px4board | 1 + boards/holybro/pix32v5/default.px4board | 1 + boards/matek/h743-mini/default.px4board | 1 + boards/matek/h743-slim/default.px4board | 1 + boards/matek/h743/default.px4board | 1 + boards/modalai/fc-v1/default.px4board | 1 + boards/modalai/fc-v2/default.px4board | 1 + boards/mro/ctrl-zero-classic/default.px4board | 1 + boards/mro/ctrl-zero-f7-oem/default.px4board | 1 + boards/mro/ctrl-zero-f7/default.px4board | 1 + boards/mro/ctrl-zero-h7-oem/default.px4board | 1 + boards/mro/ctrl-zero-h7/default.px4board | 1 + boards/mro/pixracerpro/default.px4board | 1 + boards/mro/x21-777/default.px4board | 1 + boards/mro/x21/default.px4board | 1 + boards/nxp/fmuk66-e/default.px4board | 1 + boards/nxp/fmuk66-v3/default.px4board | 1 + boards/omnibus/f4sd/default.px4board | 1 + boards/px4/fmu-v2/default.px4board | 1 + boards/px4/fmu-v3/default.px4board | 1 + boards/px4/fmu-v4/default.px4board | 1 + boards/px4/fmu-v4pro/default.px4board | 1 + boards/px4/fmu-v5/default.px4board | 1 + boards/px4/fmu-v5/protected.px4board | 1 + boards/px4/fmu-v5x/default.px4board | 1 + boards/px4/fmu-v6c/default.px4board | 1 + boards/px4/fmu-v6u/default.px4board | 1 + boards/px4/fmu-v6x/default.px4board | 1 + boards/px4/fmu-v6xrt/default.px4board | 1 + boards/raspberrypi/pico/default.px4board | 1 + boards/siyi/n7/default.px4board | 1 + .../smartap-airlink/default.px4board | 1 + boards/spracing/h7extreme/default.px4board | 1 + boards/thepeach/k1/default.px4board | 1 + boards/thepeach/r1/default.px4board | 1 + boards/uvify/core/default.px4board | 1 + platforms/nuttx/src/px4/common/CMakeLists.txt | 1 - platforms/nuttx/src/px4/common/px4_init.cpp | 6 - .../nuttx/src/px4/common/px4_layer.cmake | 1 - .../src/px4/common/px4_protected_layers.cmake | 1 - .../src/px4/common/px4_userspace_init.cpp | 6 - src/drivers/cdcacm_autostart/CMakeLists.txt | 40 ++ src/drivers/cdcacm_autostart/Kconfig | 6 + .../cdcacm_autostart/cdcacm_autostart.cpp | 663 ++++++++++++++++++ .../cdcacm_autostart/cdcacm_autostart.h | 124 ++++ .../cdcacm_autostart_params.c | 68 ++ src/modules/mavlink/mavlink_main.cpp | 26 +- src/systemcmds/serial_passthru/Kconfig | 2 +- 67 files changed, 982 insertions(+), 25 deletions(-) create mode 100644 src/drivers/cdcacm_autostart/CMakeLists.txt create mode 100644 src/drivers/cdcacm_autostart/Kconfig create mode 100644 src/drivers/cdcacm_autostart/cdcacm_autostart.cpp create mode 100644 src/drivers/cdcacm_autostart/cdcacm_autostart.h create mode 100644 src/drivers/cdcacm_autostart/cdcacm_autostart_params.c diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index b9d46ce27dc7..c0b895a8fe8a 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -439,6 +439,14 @@ else # Must be started after the serial config is read rc_input start $RC_INPUT_ARGS + # Manages USB interface + if ! cdcacm_autostart start + then + sercon + echo "Starting MAVLink on /dev/ttyACM0" + mavlink start -d /dev/ttyACM0 + fi + # # Play the startup tune (if not disabled or there is an error) # diff --git a/boards/airmind/mindpx-v2/default.px4board b/boards/airmind/mindpx-v2/default.px4board index cb56388c36fc..5f4bcd2b0cfd 100644 --- a/boards/airmind/mindpx-v2/default.px4board +++ b/boards/airmind/mindpx-v2/default.px4board @@ -12,6 +12,7 @@ CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y diff --git a/boards/ark/fmu-v6x/default.px4board b/boards/ark/fmu-v6x/default.px4board index 4018e493a2ad..1209adb9dcc4 100644 --- a/boards/ark/fmu-v6x/default.px4board +++ b/boards/ark/fmu-v6x/default.px4board @@ -8,12 +8,14 @@ CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS4" CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS1" CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS3" CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_BAROMETER_BMP388=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_HEATER=y diff --git a/boards/atl/mantis-edu/default.px4board b/boards/atl/mantis-edu/default.px4board index 58fcec76d7e8..fd76e4d6ca56 100644 --- a/boards/atl/mantis-edu/default.px4board +++ b/boards/atl/mantis-edu/default.px4board @@ -2,6 +2,7 @@ CONFIG_BOARD_TOOLCHAIN="arm-none-eabi" CONFIG_BOARD_ARCHITECTURE="cortex-m7" CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_BAROMETER_MAIERTEK_MPC2520=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8310=y diff --git a/boards/bitcraze/crazyflie/default.px4board b/boards/bitcraze/crazyflie/default.px4board index e7e9705f2dc1..02b70b58c35d 100644 --- a/boards/bitcraze/crazyflie/default.px4board +++ b/boards/bitcraze/crazyflie/default.px4board @@ -3,6 +3,7 @@ CONFIG_BOARD_ARCHITECTURE="cortex-m4" CONFIG_BOARD_CONSTRAINED_FLASH=y CONFIG_BOARD_CONSTRAINED_MEMORY=y CONFIG_BOARD_COMPILE_DEFINITIONS="-Wno-narrowing" +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_BAROMETER_LPS25H=y CONFIG_DRIVERS_DISTANCE_SENSOR_VL53L0X=y CONFIG_DRIVERS_GPS=y diff --git a/boards/bitcraze/crazyflie21/default.px4board b/boards/bitcraze/crazyflie21/default.px4board index aa55b50621e8..0c268b6983a6 100644 --- a/boards/bitcraze/crazyflie21/default.px4board +++ b/boards/bitcraze/crazyflie21/default.px4board @@ -4,6 +4,7 @@ CONFIG_BOARD_CONSTRAINED_FLASH=y CONFIG_BOARD_CONSTRAINED_MEMORY=y CONFIG_BOARD_COMPILE_DEFINITIONS="-Wno-narrowing" CONFIG_DRIVERS_BAROMETER_BMP388=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_DISTANCE_SENSOR_VL53L1X=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_BOSCH_BMI088_I2C=y diff --git a/boards/cuav/nora/default.px4board b/boards/cuav/nora/default.px4board index f312504ee5e4..2a0e40e37efe 100644 --- a/boards/cuav/nora/default.px4board +++ b/boards/cuav/nora/default.px4board @@ -7,6 +7,7 @@ CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3" CONFIG_DRIVERS_ADC_ADS1115=y CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_COMMON_BAROMETERS=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y diff --git a/boards/cuav/x7pro/default.px4board b/boards/cuav/x7pro/default.px4board index 99e831c12938..b2212d5f15f6 100644 --- a/boards/cuav/x7pro/default.px4board +++ b/boards/cuav/x7pro/default.px4board @@ -6,6 +6,7 @@ CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1" CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3" CONFIG_DRIVERS_ADC_ADS1115=y CONFIG_DRIVERS_ADC_BOARD_ADC=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y diff --git a/boards/cubepilot/cubeorange/default.px4board b/boards/cubepilot/cubeorange/default.px4board index 91ddcda596bc..e3c84b183895 100644 --- a/boards/cubepilot/cubeorange/default.px4board +++ b/boards/cubepilot/cubeorange/default.px4board @@ -11,6 +11,7 @@ CONFIG_DRIVERS_BAROMETER_MS5611=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/cubepilot/cubeorangeplus/default.px4board b/boards/cubepilot/cubeorangeplus/default.px4board index 837876ee7d41..d755eea8d814 100644 --- a/boards/cubepilot/cubeorangeplus/default.px4board +++ b/boards/cubepilot/cubeorangeplus/default.px4board @@ -11,6 +11,7 @@ CONFIG_DRIVERS_BAROMETER_MS5611=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/cubepilot/cubeyellow/default.px4board b/boards/cubepilot/cubeyellow/default.px4board index 45cf93a38d95..62cf898af96c 100644 --- a/boards/cubepilot/cubeyellow/default.px4board +++ b/boards/cubepilot/cubeyellow/default.px4board @@ -12,6 +12,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/diatone/mamba-f405-mk2/default.px4board b/boards/diatone/mamba-f405-mk2/default.px4board index 32ec4fd47b45..e8ee5ec656c8 100644 --- a/boards/diatone/mamba-f405-mk2/default.px4board +++ b/boards/diatone/mamba-f405-mk2/default.px4board @@ -8,6 +8,7 @@ CONFIG_BOARD_SERIAL_URT6="/dev/ttyS2" CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1" CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_BAROMETER_BMP280=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y diff --git a/boards/flywoo/gn-f405/default.px4board b/boards/flywoo/gn-f405/default.px4board index b016b0db9a6a..54d17325bc92 100644 --- a/boards/flywoo/gn-f405/default.px4board +++ b/boards/flywoo/gn-f405/default.px4board @@ -7,6 +7,7 @@ CONFIG_BOARD_SERIAL_URT6="/dev/ttyS2" CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1" CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_BAROMETER_BMP280=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y diff --git a/boards/hkust/nxt-dual/default.px4board b/boards/hkust/nxt-dual/default.px4board index 884487955590..cab44e781293 100644 --- a/boards/hkust/nxt-dual/default.px4board +++ b/boards/hkust/nxt-dual/default.px4board @@ -12,6 +12,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/hkust/nxt-v1/default.px4board b/boards/hkust/nxt-v1/default.px4board index bc04f1ce9491..6261079e0d9d 100644 --- a/boards/hkust/nxt-v1/default.px4board +++ b/boards/hkust/nxt-v1/default.px4board @@ -11,6 +11,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/holybro/durandal-v1/default.px4board b/boards/holybro/durandal-v1/default.px4board index 362eaff74250..ecc1bc81013b 100644 --- a/boards/holybro/durandal-v1/default.px4board +++ b/boards/holybro/durandal-v1/default.px4board @@ -11,6 +11,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/holybro/kakutef7/default.px4board b/boards/holybro/kakutef7/default.px4board index bcaedd9cf281..8aaa037cc55a 100644 --- a/boards/holybro/kakutef7/default.px4board +++ b/boards/holybro/kakutef7/default.px4board @@ -9,6 +9,7 @@ CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1" CONFIG_BOARD_SERIAL_RC="/dev/ttyS4" CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_BAROMETER_BMP280=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20689=y diff --git a/boards/holybro/kakuteh7/default.px4board b/boards/holybro/kakuteh7/default.px4board index 270caa7b6510..dbf8aeb7f217 100644 --- a/boards/holybro/kakuteh7/default.px4board +++ b/boards/holybro/kakuteh7/default.px4board @@ -9,6 +9,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/holybro/kakuteh7mini/default.px4board b/boards/holybro/kakuteh7mini/default.px4board index b49f1cfa012f..eb465e00275c 100644 --- a/boards/holybro/kakuteh7mini/default.px4board +++ b/boards/holybro/kakuteh7mini/default.px4board @@ -9,6 +9,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/holybro/kakuteh7v2/default.px4board b/boards/holybro/kakuteh7v2/default.px4board index d9d432beec13..45fd6e11eb79 100644 --- a/boards/holybro/kakuteh7v2/default.px4board +++ b/boards/holybro/kakuteh7v2/default.px4board @@ -9,6 +9,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/holybro/pix32v5/default.px4board b/boards/holybro/pix32v5/default.px4board index 45bd43ee4f4d..0093ee2dcfd0 100644 --- a/boards/holybro/pix32v5/default.px4board +++ b/boards/holybro/pix32v5/default.px4board @@ -11,6 +11,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/matek/h743-mini/default.px4board b/boards/matek/h743-mini/default.px4board index 64e472d77048..22efafcfdb38 100644 --- a/boards/matek/h743-mini/default.px4board +++ b/boards/matek/h743-mini/default.px4board @@ -7,6 +7,7 @@ CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS5" CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS6" CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_BAROMETER_DPS310=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y diff --git a/boards/matek/h743-slim/default.px4board b/boards/matek/h743-slim/default.px4board index ce5f2222296e..71024fea5ceb 100644 --- a/boards/matek/h743-slim/default.px4board +++ b/boards/matek/h743-slim/default.px4board @@ -7,6 +7,7 @@ CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS5" CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS6" CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_BAROMETER_DPS310=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y diff --git a/boards/matek/h743/default.px4board b/boards/matek/h743/default.px4board index ce5f2222296e..dcd9fad5aef1 100644 --- a/boards/matek/h743/default.px4board +++ b/boards/matek/h743/default.px4board @@ -8,6 +8,7 @@ CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS6" CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_BAROMETER_DPS310=y CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y diff --git a/boards/modalai/fc-v1/default.px4board b/boards/modalai/fc-v1/default.px4board index 2a33d1ddb875..e9104cfaeec1 100644 --- a/boards/modalai/fc-v1/default.px4board +++ b/boards/modalai/fc-v1/default.px4board @@ -12,6 +12,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/modalai/fc-v2/default.px4board b/boards/modalai/fc-v2/default.px4board index 6fa7ebabaf02..15b94d5dc8c2 100644 --- a/boards/modalai/fc-v2/default.px4board +++ b/boards/modalai/fc-v2/default.px4board @@ -12,6 +12,7 @@ CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y diff --git a/boards/mro/ctrl-zero-classic/default.px4board b/boards/mro/ctrl-zero-classic/default.px4board index d07a7c1fc9d4..665fbc8626f4 100644 --- a/boards/mro/ctrl-zero-classic/default.px4board +++ b/boards/mro/ctrl-zero-classic/default.px4board @@ -12,6 +12,7 @@ CONFIG_DRIVERS_BAROMETER_DPS310=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/mro/ctrl-zero-f7-oem/default.px4board b/boards/mro/ctrl-zero-f7-oem/default.px4board index b0701855bf22..9fe340b87f1b 100644 --- a/boards/mro/ctrl-zero-f7-oem/default.px4board +++ b/boards/mro/ctrl-zero-f7-oem/default.px4board @@ -10,6 +10,7 @@ CONFIG_DRIVERS_BAROMETER_DPS310=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/mro/ctrl-zero-f7/default.px4board b/boards/mro/ctrl-zero-f7/default.px4board index 074a4f2ca052..d09ca8a5b50f 100644 --- a/boards/mro/ctrl-zero-f7/default.px4board +++ b/boards/mro/ctrl-zero-f7/default.px4board @@ -9,6 +9,7 @@ CONFIG_DRIVERS_BAROMETER_DPS310=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/mro/ctrl-zero-h7-oem/default.px4board b/boards/mro/ctrl-zero-h7-oem/default.px4board index 549ba99b7331..ec6c59888db5 100644 --- a/boards/mro/ctrl-zero-h7-oem/default.px4board +++ b/boards/mro/ctrl-zero-h7-oem/default.px4board @@ -10,6 +10,7 @@ CONFIG_DRIVERS_BAROMETER_DPS310=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/mro/ctrl-zero-h7/default.px4board b/boards/mro/ctrl-zero-h7/default.px4board index c32ae10fc056..7bb96d3aca08 100644 --- a/boards/mro/ctrl-zero-h7/default.px4board +++ b/boards/mro/ctrl-zero-h7/default.px4board @@ -10,6 +10,7 @@ CONFIG_DRIVERS_BAROMETER_DPS310=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/mro/pixracerpro/default.px4board b/boards/mro/pixracerpro/default.px4board index d4b1d29370aa..40301136e26a 100644 --- a/boards/mro/pixracerpro/default.px4board +++ b/boards/mro/pixracerpro/default.px4board @@ -9,6 +9,7 @@ CONFIG_DRIVERS_BAROMETER_DPS310=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/mro/x21-777/default.px4board b/boards/mro/x21-777/default.px4board index 5a51a776dde0..361aca448471 100644 --- a/boards/mro/x21-777/default.px4board +++ b/boards/mro/x21-777/default.px4board @@ -9,6 +9,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/mro/x21/default.px4board b/boards/mro/x21/default.px4board index 7c206260016f..8640bff623b0 100644 --- a/boards/mro/x21/default.px4board +++ b/boards/mro/x21/default.px4board @@ -10,6 +10,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/nxp/fmuk66-e/default.px4board b/boards/nxp/fmuk66-e/default.px4board index b8bc5cc7f424..749e62e5d54f 100644 --- a/boards/nxp/fmuk66-e/default.px4board +++ b/boards/nxp/fmuk66-e/default.px4board @@ -11,6 +11,7 @@ CONFIG_DRIVERS_BAROMETER_MPL3115A2=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DISTANCE_SENSOR_SRF05=y diff --git a/boards/nxp/fmuk66-v3/default.px4board b/boards/nxp/fmuk66-v3/default.px4board index e53ae83c880f..268e89c70fd8 100644 --- a/boards/nxp/fmuk66-v3/default.px4board +++ b/boards/nxp/fmuk66-v3/default.px4board @@ -11,6 +11,7 @@ CONFIG_DRIVERS_BAROMETER_MPL3115A2=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DISTANCE_SENSOR_SRF05=y diff --git a/boards/omnibus/f4sd/default.px4board b/boards/omnibus/f4sd/default.px4board index 287d99165930..8d3c58a7f0f5 100644 --- a/boards/omnibus/f4sd/default.px4board +++ b/boards/omnibus/f4sd/default.px4board @@ -7,6 +7,7 @@ CONFIG_BOARD_SERIAL_URT6="/dev/ttyS2" CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1" CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_BAROMETER_BMP280=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y diff --git a/boards/px4/fmu-v2/default.px4board b/boards/px4/fmu-v2/default.px4board index 59d1c02a7331..f0753941e03d 100644 --- a/boards/px4/fmu-v2/default.px4board +++ b/boards/px4/fmu-v2/default.px4board @@ -9,6 +9,7 @@ CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS2" CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS6" CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_BAROMETER_MS5611=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y CONFIG_DRIVERS_IMU_ST_L3GD20=y diff --git a/boards/px4/fmu-v3/default.px4board b/boards/px4/fmu-v3/default.px4board index 1ced5b78737e..5c24d0e731fb 100644 --- a/boards/px4/fmu-v3/default.px4board +++ b/boards/px4/fmu-v3/default.px4board @@ -11,6 +11,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/px4/fmu-v4/default.px4board b/boards/px4/fmu-v4/default.px4board index 0e1bb8f54774..ab106bdb7b90 100644 --- a/boards/px4/fmu-v4/default.px4board +++ b/boards/px4/fmu-v4/default.px4board @@ -11,6 +11,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/px4/fmu-v4pro/default.px4board b/boards/px4/fmu-v4pro/default.px4board index f722e649efae..ff8455c28588 100644 --- a/boards/px4/fmu-v4pro/default.px4board +++ b/boards/px4/fmu-v4pro/default.px4board @@ -12,6 +12,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/px4/fmu-v5/default.px4board b/boards/px4/fmu-v5/default.px4board index bfb8b6af4645..beb865832145 100644 --- a/boards/px4/fmu-v5/default.px4board +++ b/boards/px4/fmu-v5/default.px4board @@ -10,6 +10,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/px4/fmu-v5/protected.px4board b/boards/px4/fmu-v5/protected.px4board index e5371b2a7dfe..fd3b7bb5222f 100644 --- a/boards/px4/fmu-v5/protected.px4board +++ b/boards/px4/fmu-v5/protected.px4board @@ -6,6 +6,7 @@ CONFIG_COMMON_OPTICAL_FLOW=n CONFIG_COMMON_TELEMETRY=n CONFIG_DRIVERS_CAMERA_CAPTURE=n CONFIG_DRIVERS_CAMERA_TRIGGER=n +CONFIG_DRIVERS_CDCACM_AUTOSTART=n CONFIG_DRIVERS_IRLOCK=n CONFIG_DRIVERS_PCA9685_PWM_OUT=n CONFIG_DRIVERS_PWM_INPUT=n diff --git a/boards/px4/fmu-v5x/default.px4board b/boards/px4/fmu-v5x/default.px4board index 2bede96763c0..46d04d8cc2eb 100644 --- a/boards/px4/fmu-v5x/default.px4board +++ b/boards/px4/fmu-v5x/default.px4board @@ -14,6 +14,7 @@ CONFIG_DRIVERS_BAROMETER_MS5611=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/px4/fmu-v6c/default.px4board b/boards/px4/fmu-v6c/default.px4board index 148e6326fb26..51484f7903db 100644 --- a/boards/px4/fmu-v6c/default.px4board +++ b/boards/px4/fmu-v6c/default.px4board @@ -10,6 +10,7 @@ CONFIG_DRIVERS_BAROMETER_MS5611=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/px4/fmu-v6u/default.px4board b/boards/px4/fmu-v6u/default.px4board index 50b4f6ba3d1d..e733dccc35fc 100644 --- a/boards/px4/fmu-v6u/default.px4board +++ b/boards/px4/fmu-v6u/default.px4board @@ -11,6 +11,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/px4/fmu-v6x/default.px4board b/boards/px4/fmu-v6x/default.px4board index f197a254a09a..7b9488933fb4 100644 --- a/boards/px4/fmu-v6x/default.px4board +++ b/boards/px4/fmu-v6x/default.px4board @@ -14,6 +14,7 @@ CONFIG_DRIVERS_BAROMETER_INVENSENSE_ICP201XX=y CONFIG_DRIVERS_BAROMETER_MS5611=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/px4/fmu-v6xrt/default.px4board b/boards/px4/fmu-v6xrt/default.px4board index 029462aa4806..17434ed18d3c 100644 --- a/boards/px4/fmu-v6xrt/default.px4board +++ b/boards/px4/fmu-v6xrt/default.px4board @@ -13,6 +13,7 @@ CONFIG_DRIVERS_BAROMETER_INVENSENSE_ICP201XX=y CONFIG_DRIVERS_BAROMETER_MS5611=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/raspberrypi/pico/default.px4board b/boards/raspberrypi/pico/default.px4board index a5727267a1fa..410f8d4788a9 100644 --- a/boards/raspberrypi/pico/default.px4board +++ b/boards/raspberrypi/pico/default.px4board @@ -6,6 +6,7 @@ CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS2" CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS1" CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_BAROMETER_BMP280=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_IMU_INVENSENSE_MPU9250=y CONFIG_DRIVERS_MAGNETOMETER_HMC5883=y diff --git a/boards/siyi/n7/default.px4board b/boards/siyi/n7/default.px4board index cb42f3530c8a..3364cf55f7be 100644 --- a/boards/siyi/n7/default.px4board +++ b/boards/siyi/n7/default.px4board @@ -10,6 +10,7 @@ CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_HEATER=y diff --git a/boards/sky-drones/smartap-airlink/default.px4board b/boards/sky-drones/smartap-airlink/default.px4board index 4bb3c7cc406c..7613792e2ce7 100644 --- a/boards/sky-drones/smartap-airlink/default.px4board +++ b/boards/sky-drones/smartap-airlink/default.px4board @@ -11,6 +11,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/spracing/h7extreme/default.px4board b/boards/spracing/h7extreme/default.px4board index c6c28729a73c..aa9790560907 100644 --- a/boards/spracing/h7extreme/default.px4board +++ b/boards/spracing/h7extreme/default.px4board @@ -4,6 +4,7 @@ CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y diff --git a/boards/thepeach/k1/default.px4board b/boards/thepeach/k1/default.px4board index 39fefb9b68a8..d760279546c7 100644 --- a/boards/thepeach/k1/default.px4board +++ b/boards/thepeach/k1/default.px4board @@ -11,6 +11,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/thepeach/r1/default.px4board b/boards/thepeach/r1/default.px4board index 39fefb9b68a8..d760279546c7 100644 --- a/boards/thepeach/r1/default.px4board +++ b/boards/thepeach/r1/default.px4board @@ -11,6 +11,7 @@ CONFIG_COMMON_BAROMETERS=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y diff --git a/boards/uvify/core/default.px4board b/boards/uvify/core/default.px4board index bdc591a2810d..8c144aa6062e 100644 --- a/boards/uvify/core/default.px4board +++ b/boards/uvify/core/default.px4board @@ -10,6 +10,7 @@ CONFIG_DRIVERS_BAROMETER_MS5611=y CONFIG_DRIVERS_BATT_SMBUS=y CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_COMMON_DISTANCE_SENSOR=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y diff --git a/platforms/nuttx/src/px4/common/CMakeLists.txt b/platforms/nuttx/src/px4/common/CMakeLists.txt index ab16e77a0e30..c74810b03a88 100644 --- a/platforms/nuttx/src/px4/common/CMakeLists.txt +++ b/platforms/nuttx/src/px4/common/CMakeLists.txt @@ -38,7 +38,6 @@ if(NOT PX4_BOARD MATCHES "io-v2") board_crashdump.c board_dma_alloc.c board_fat_dma_alloc.c - cdc_acm_check.cpp console_buffer.cpp cpuload.cpp gpio.c diff --git a/platforms/nuttx/src/px4/common/px4_init.cpp b/platforms/nuttx/src/px4/common/px4_init.cpp index ceeb79bd7240..aa11b1cf703c 100644 --- a/platforms/nuttx/src/px4/common/px4_init.cpp +++ b/platforms/nuttx/src/px4/common/px4_init.cpp @@ -62,8 +62,6 @@ #include #endif -extern void cdcacm_init(void); - #if !defined(CONFIG_BUILD_FLAT) typedef CODE void (*initializer_t)(void); extern initializer_t _sinit; @@ -196,10 +194,6 @@ int px4_platform_init() px4_log_initialize(); -#if defined(CONFIG_SYSTEM_CDCACM) && defined(CONFIG_BUILD_FLAT) - cdcacm_init(); -#endif - return PX4_OK; } diff --git a/platforms/nuttx/src/px4/common/px4_layer.cmake b/platforms/nuttx/src/px4/common/px4_layer.cmake index 9199a9528997..de8fe5a0c683 100644 --- a/platforms/nuttx/src/px4/common/px4_layer.cmake +++ b/platforms/nuttx/src/px4/common/px4_layer.cmake @@ -2,7 +2,6 @@ add_library(px4_layer ${KERNEL_SRCS} - cdc_acm_check.cpp ${PX4_SOURCE_DIR}/platforms/common/Serial.cpp SerialImpl.cpp ) diff --git a/platforms/nuttx/src/px4/common/px4_protected_layers.cmake b/platforms/nuttx/src/px4/common/px4_protected_layers.cmake index c55fe568d390..5fbbef164457 100644 --- a/platforms/nuttx/src/px4/common/px4_protected_layers.cmake +++ b/platforms/nuttx/src/px4/common/px4_protected_layers.cmake @@ -6,7 +6,6 @@ add_library(px4_layer board_fat_dma_alloc.c tasks.cpp console_buffer_usr.cpp - cdc_acm_check.cpp ${PX4_SOURCE_DIR}/platforms/posix/src/px4/common/print_load.cpp ${PX4_SOURCE_DIR}/platforms/posix/src/px4/common/cpuload.cpp px4_userspace_init.cpp diff --git a/platforms/nuttx/src/px4/common/px4_userspace_init.cpp b/platforms/nuttx/src/px4/common/px4_userspace_init.cpp index f5d9882ca23a..82cace9e4d24 100644 --- a/platforms/nuttx/src/px4/common/px4_userspace_init.cpp +++ b/platforms/nuttx/src/px4/common/px4_userspace_init.cpp @@ -44,8 +44,6 @@ #include #include -extern void cdcacm_init(void); - extern "C" void px4_userspace_init(void) { hrt_init(); @@ -55,8 +53,4 @@ extern "C" void px4_userspace_init(void) px4::WorkQueueManagerStart(); uorb_start(); - -#if defined(CONFIG_SYSTEM_CDCACM) - cdcacm_init(); -#endif } diff --git a/src/drivers/cdcacm_autostart/CMakeLists.txt b/src/drivers/cdcacm_autostart/CMakeLists.txt new file mode 100644 index 000000000000..8e78ba1cd24c --- /dev/null +++ b/src/drivers/cdcacm_autostart/CMakeLists.txt @@ -0,0 +1,40 @@ +############################################################################ +# +# Copyright (c) 2023 PX4 Development Team. 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. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "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 +# COPYRIGHT OWNER OR CONTRIBUTORS 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. +# +############################################################################ +px4_add_module( + MODULE drivers__cdcacm_autostart + MAIN cdcacm_autostart + COMPILE_FLAGS + # -DDEBUG_BUILD + SRCS + cdcacm_autostart.cpp + ) diff --git a/src/drivers/cdcacm_autostart/Kconfig b/src/drivers/cdcacm_autostart/Kconfig new file mode 100644 index 000000000000..aabfaad4838e --- /dev/null +++ b/src/drivers/cdcacm_autostart/Kconfig @@ -0,0 +1,6 @@ +menuconfig DRIVERS_CDCACM_AUTOSTART + bool "cdcacm_autostart" + default n + depends on MODULES_MAVLINK + ---help--- + Enable support for cdcacm_autostart \ No newline at end of file diff --git a/src/drivers/cdcacm_autostart/cdcacm_autostart.cpp b/src/drivers/cdcacm_autostart/cdcacm_autostart.cpp new file mode 100644 index 000000000000..d7ebbddd6b0f --- /dev/null +++ b/src/drivers/cdcacm_autostart/cdcacm_autostart.cpp @@ -0,0 +1,663 @@ +/**************************************************************************** + * + * Copyright (c) 2023 PX4 Development Team. 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. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "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 + * COPYRIGHT OWNER OR CONTRIBUTORS 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. + * + ****************************************************************************/ + +#if defined(CONFIG_SYSTEM_CDCACM) + +#include "cdcacm_autostart.h" + +__BEGIN_DECLS +#include +#include + +extern int sercon_main(int c, char **argv); +extern int serdis_main(int c, char **argv); +__END_DECLS + +#include + +#define USB_DEVICE_PATH "/dev/ttyACM0" + +#if defined(CONFIG_SERIAL_PASSTHRU_UBLOX) +# undef SERIAL_PASSTHRU_UBLOX_DEV +# if defined(CONFIG_SERIAL_PASSTHRU_GPS1) && defined(CONFIG_BOARD_SERIAL_GPS1) +# define SERIAL_PASSTHRU_UBLOX_DEV CONFIG_BOARD_SERIAL_GPS1 +# elif defined(CONFIG_SERIAL_PASSTHRU_GPS2)&& defined(CONFIG_BOARD_SERIAL_GPS2) +# define SERIAL_PASSTHRU_UBLOX_DEV CONFIG_BOARD_SERIAL_GPS2 +# elif defined(CONFIG_SERIAL_PASSTHRU_GPS3)&& defined(CONFIG_BOARD_SERIAL_GPS3) +# define SERIAL_PASSTHRU_UBLOX_DEV CONFIG_BOARD_SERIAL_GPS3 +# elif defined(CONFIG_SERIAL_PASSTHRU_GPS4)&& defined(CONFIG_BOARD_SERIAL_GPS4) +# define SERIAL_PASSTHRU_UBLOX_DEV CONFIG_BOARD_SERIAL_GPS4 +# elif defined(CONFIG_SERIAL_PASSTHRU_GPS5) && defined(CONFIG_BOARD_SERIAL_GPS5) +# define SERIAL_PASSTHRU_UBLOX_DEV CONFIG_BOARD_SERIAL_GPS5 +# endif +# if !defined(SERIAL_PASSTHRU_UBLOX_DEV) +# error "CONFIG_SERIAL_PASSTHRU_GPSn and CONFIG_BOARD_SERIAL_GPSn must be defined" +# endif +#endif + +CdcAcmAutostart::CdcAcmAutostart() : + ModuleParams(nullptr), + ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::lp_default) +{} + +CdcAcmAutostart::~CdcAcmAutostart() +{ + PX4_INFO("Stopping CDC/ACM autostart"); + + if (_ttyacm_fd >= 0) { + px4_close(_ttyacm_fd); + } + + ScheduleClear(); +} + +int CdcAcmAutostart::Start() +{ + PX4_INFO("Starting CDC/ACM autostart"); + UpdateParams(true); + + ScheduleNow(); + + return PX4_OK; +} + +void CdcAcmAutostart::Run() +{ + if (should_exit()) { + exit_and_cleanup(); + return; + } + + UpdateParams(); + + run_state_machine(); +} + +void CdcAcmAutostart::run_state_machine() +{ + _reschedule_time = 500_ms; + _vbus_present = (board_read_VBUS_state() == PX4_OK); + + // If the hardware supports RESET lockout that has nArmed ANDed with VBUS + // vbus_sense may drop during a param save which uses + // BOARD_INDICATE_EXTERNAL_LOCKOUT_STATE to prevent external resets + // while writing the params. If we are not armed and nARMRED is low + // we are in such a lock out so ignore changes on VBUS_SENSE during this + // time. +#if defined(BOARD_GET_EXTERNAL_LOCKOUT_STATE) + + if (BOARD_GET_EXTERNAL_LOCKOUT_STATE() == 0) { + _vbus_present = _vbus_present_prev; + ScheduleDelayed(500_ms); + return; + } + +#endif + + // Do not reconfigure USB while flying + actuator_armed_s report; + _actuator_armed_sub.copy(&report); + + if (report.armed) { + _vbus_present_prev = _vbus_present; + + } else { + + switch (_state) { + case UsbAutoStartState::disconnected: + state_disconnected(); + break; + + case UsbAutoStartState::connecting: + state_connecting(); + break; + + case UsbAutoStartState::connected: + state_connected(); + break; + + case UsbAutoStartState::disconnecting: + state_disconnecting(); + break; + } + } + + _vbus_present_prev = _vbus_present; + ScheduleDelayed(_reschedule_time); +} + +void CdcAcmAutostart::state_connected() +{ + if (!_vbus_present && !_vbus_present_prev && (_active_protocol == UsbProtocol::mavlink)) { + PX4_DEBUG("lost vbus!"); + sched_lock(); + static const char app[] {"mavlink"}; + static const char *stop_argv[] {"mavlink", "stop", "-d", USB_DEVICE_PATH, NULL}; + exec_builtin(app, (char **)stop_argv, NULL, 0); + sched_unlock(); + _state = UsbAutoStartState::disconnecting; + } +} + +void CdcAcmAutostart::state_disconnected() +{ + if (_vbus_present && _vbus_present_prev) { + PX4_DEBUG("starting sercon"); + + if (sercon_main(0, nullptr) == EXIT_SUCCESS) { + _state = UsbAutoStartState::connecting; + PX4_DEBUG("state connecting"); + _reschedule_time = 1_s; + } + + } else if (_vbus_present && !_vbus_present_prev) { + // USB just connected, try again soon + _reschedule_time = 100_ms; + } +} + +void CdcAcmAutostart::state_connecting() +{ + int bytes_available = 0; +#if defined(CONFIG_SERIAL_PASSTHRU_UBLOX) + struct termios uart_config; + speed_t baudrate; +#endif + + if (!_vbus_present) { + PX4_DEBUG("No VBUS"); + goto fail; + } + + if (_ttyacm_fd < 0) { + PX4_DEBUG("opening port"); + _ttyacm_fd = px4_open(USB_DEVICE_PATH, O_RDONLY | O_NONBLOCK); + } + + if (_ttyacm_fd < 0) { + PX4_DEBUG("can't open port"); + goto fail; + } + + if (_sys_usb_auto.get() == 2) { + PX4_INFO("Starting mavlink on %s (SYS_USB_AUTO=2)", USB_DEVICE_PATH); + + if (start_mavlink()) { + _state = UsbAutoStartState::connected; + _active_protocol = UsbProtocol::mavlink; + + } else { + _state = UsbAutoStartState::disconnecting; + _reschedule_time = 100_ms; + } + + return; + + } else if (_sys_usb_auto.get() == 0) { + // Do nothing + _state = UsbAutoStartState::connected; + _active_protocol = UsbProtocol::none; + return; + } + + // Otherwise autodetect + + if ((px4_ioctl(_ttyacm_fd, FIONREAD, &bytes_available) != PX4_OK) || + (bytes_available < 3)) { + PX4_DEBUG("bytes_available: %d", bytes_available); + // Return back to connecting state to check again soon + return; + } + + // Non-blocking read + _bytes_read = px4_read(_ttyacm_fd, _buffer, sizeof(_buffer)); + +#if defined(DEBUG_BUILD) + + if (_bytes_read > 0) { + fprintf(stderr, "%d bytes\n", _bytes_read); + + for (int i = 0; i < _bytes_read; i++) { + fprintf(stderr, "|%X", _buffer[i]); + } + + fprintf(stderr, "\n"); + } + +#endif // DEBUG_BUILD + + if (_bytes_read <= 0) { + PX4_DEBUG("no _bytes_read"); + // Return back to connecting state to check again soon + return; + } + +#if defined(CONFIG_SERIAL_PASSTHRU_UBLOX) + // Get the baudrate for serial passthru before closing the port. + tcgetattr(_ttyacm_fd, &uart_config); + baudrate = cfgetspeed(&uart_config); +#endif + PX4_DEBUG("_bytes_read %d", _bytes_read); + px4_close(_ttyacm_fd); + _ttyacm_fd = -1; + + // Parse for mavlink reboot command + if (scan_buffer_for_mavlink_reboot()) { + // Reboot incoming. Return without rescheduling. + return; + } + + // Parse for mavlink heartbeats (v1 and v2). + if (scan_buffer_for_mavlink_heartbeat()) { + if (start_mavlink()) { + _state = UsbAutoStartState::connected; + _active_protocol = UsbProtocol::mavlink; + + } else { + _state = UsbAutoStartState::disconnecting; + _reschedule_time = 100_ms; + } + + return; + } + + // Parse for carriage returns indicating someone is trying to use the nsh. + if (scan_buffer_for_carriage_returns()) { + if (start_nsh()) { + _state = UsbAutoStartState::connected; + _active_protocol = UsbProtocol::nsh; + + } else { + _state = UsbAutoStartState::disconnecting; + _reschedule_time = 100_ms; + } + + return; + } + +#if defined(CONFIG_SERIAL_PASSTHRU_UBLOX) + + // Parse for ublox start of packet byte sequence. + if (scan_buffer_for_ublox_bytes()) { + if (start_ublox_serial_passthru(baudrate)) { + _state = UsbAutoStartState::connected; + _active_protocol = UsbProtocol::ublox; + + } else { + _state = UsbAutoStartState::disconnecting; + _reschedule_time = 100_ms; + } + + return; + } + +#endif + + return; + +fail: + PX4_DEBUG("fail..."); + + // VBUS not present, open failed + if (_ttyacm_fd >= 0) { + px4_close(_ttyacm_fd); + _ttyacm_fd = -1; + } + + _state = UsbAutoStartState::disconnecting; +} + +void CdcAcmAutostart::state_disconnecting() +{ + PX4_DEBUG("state_disconnecting"); + + if (_ttyacm_fd > 0) { + px4_close(_ttyacm_fd); + } + + // Disconnect serial + serdis_main(0, NULL); + _state = UsbAutoStartState::disconnected; + _active_protocol = UsbProtocol::none; +} + +bool CdcAcmAutostart::scan_buffer_for_mavlink_reboot() +{ + bool rebooting = false; + + // Mavlink reboot/shutdown command + // COMMAND_LONG (#76) with command MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN (246) + static constexpr int MAVLINK_COMMAND_LONG_MIN_LENGTH = 41; + + if (_bytes_read < MAVLINK_COMMAND_LONG_MIN_LENGTH) { + return rebooting; + } + + // scan buffer for mavlink COMMAND_LONG + for (int i = 0; i < _bytes_read - MAVLINK_COMMAND_LONG_MIN_LENGTH; i++) { + if ((_buffer[i] == 0xFE) // Mavlink v1 start byte + && (_buffer[i + 5] == 76) // 76=0x4C COMMAND_LONG + && (_buffer[i + 34] == 246) // 246=0xF6 MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN + ) { + // mavlink v1 COMMAND_LONG + // buffer[0]: start byte (0xFE for mavlink v1) + // buffer[3]: SYSID + // buffer[4]: COMPID + // buffer[5]: message id (COMMAND_LONG 76=0x4C) + // buffer[6-10]: COMMAND_LONG param 1 (little endian float) + // buffer[34]: COMMAND_LONG command MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN (246/0xF6) + float param1_raw = 0; + memcpy(¶m1_raw, &_buffer[i + 6], 4); + int param1 = roundf(param1_raw); + + PX4_INFO("%s: Mavlink MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN param 1: %d (SYSID:%d COMPID:%d)", + USB_DEVICE_PATH, param1, _buffer[i + 3], _buffer[i + 4]); + + if (param1 == 1) { + // 1: Reboot autopilot + rebooting = true; + px4_reboot_request(REBOOT_REQUEST, 0); + + } else if (param1 == 2) { + // 2: Shutdown autopilot +#if defined(BOARD_HAS_POWER_CONTROL) + rebooting = true; + px4_shutdown_request(0); +#endif // BOARD_HAS_POWER_CONTROL + + } else if (param1 == 3) { + // 3: Reboot autopilot and keep it in the bootloader until upgraded. + rebooting = true; + px4_reboot_request(REBOOT_TO_BOOTLOADER, 0); + } + } + } + + return rebooting; +} + +bool CdcAcmAutostart::scan_buffer_for_mavlink_heartbeat() +{ + static constexpr int MAVLINK_HEARTBEAT_MIN_LENGTH = 9; + bool start_mavlink = false; + + if (_bytes_read < MAVLINK_HEARTBEAT_MIN_LENGTH) { + return start_mavlink; + } + + // scan buffer for mavlink HEARTBEAT (v1 & v2) + for (int i = 0; i < _bytes_read - MAVLINK_HEARTBEAT_MIN_LENGTH; i++) { + if ((_buffer[i] == 0xFE) && (_buffer[i + 1] == 9) && (_buffer[i + 5] == 0)) { + // mavlink v1 HEARTBEAT + // buffer[0]: start byte (0xFE for mavlink v1) + // buffer[1]: length (9 for HEARTBEAT) + // buffer[3]: SYSID + // buffer[4]: COMPID + // buffer[5]: mavlink message id (0 for HEARTBEAT) + PX4_INFO("%s: launching mavlink (HEARTBEAT v1 from SYSID:%d COMPID:%d)", + USB_DEVICE_PATH, _buffer[i + 3], _buffer[i + 4]); + start_mavlink = true; + + } else if ((_buffer[i] == 0xFD) && (_buffer[i + 1] == 9) + && (_buffer[i + 7] == 0) && (_buffer[i + 8] == 0) && (_buffer[i + 9] == 0)) { + // mavlink v2 HEARTBEAT + // buffer[0]: start byte (0xFD for mavlink v2) + // buffer[1]: length (9 for HEARTBEAT) + // buffer[5]: SYSID + // buffer[6]: COMPID + // buffer[7:9]: mavlink message id (0 for HEARTBEAT) + PX4_INFO("%s: launching mavlink (HEARTBEAT v2 from SYSID:%d COMPID:%d)", + USB_DEVICE_PATH, _buffer[i + 5], _buffer[i + 6]); + start_mavlink = true; + } + } + + return start_mavlink; +} + +bool CdcAcmAutostart::scan_buffer_for_carriage_returns() +{ + bool start_nsh = false; + + if (_bytes_read < 3) { + return start_nsh; + } + + // nshterm (3 carriage returns) + // scan buffer looking for 3 consecutive carriage returns (0xD) + for (int i = 1; i < _bytes_read - 1; i++) { + if (_buffer[i - 1] == 0xD && _buffer[i] == 0xD && _buffer[i + 1] == 0xD) { + PX4_INFO("%s: launching nshterm", USB_DEVICE_PATH); + start_nsh = true; + break; + } + } + + return start_nsh; +} + +bool CdcAcmAutostart::scan_buffer_for_ublox_bytes() +{ + bool success = false; + + if (_bytes_read < 4) { + return success; + } + + // scan buffer looking for 0xb5 0x62 which indicates the start of a packet + for (int i = 0; i < _bytes_read; i++) { + bool ub = _buffer[i] == 0xb5 && _buffer[i + 1] == 0x62; + + if (ub && ((_buffer[i + 2 ] == 0x6 && (_buffer[i + 3 ] == 0xb8 || _buffer[i + 3 ] == 0x13)) || + (_buffer[i + 2 ] == 0xa && _buffer[i + 3 ] == 0x4))) { + PX4_INFO("%s: launching ublox serial passthru", USB_DEVICE_PATH); + success = true; + break; + } + } + + return success; +} + +bool CdcAcmAutostart::start_mavlink() +{ + bool success = false; + char mavlink_mode_string[3]; + snprintf(mavlink_mode_string, sizeof(mavlink_mode_string), "%ld", _usb_mav_mode.get()); + static const char *argv[] {"mavlink", "start", "-d", USB_DEVICE_PATH, "-m", mavlink_mode_string, nullptr}; + + if (execute_process((char **)argv) > 0) { + success = true; + } + + return success; +} + +bool CdcAcmAutostart::start_nsh() +{ + bool success = false; + static const char *argv[] {"nshterm", USB_DEVICE_PATH, nullptr}; + + if (execute_process((char **)argv) > 0) { + success = true; + } + + return success; +} + +#if defined(CONFIG_SERIAL_PASSTHRU_UBLOX) +bool CdcAcmAutostart::start_ublox_serial_passthru(speed_t baudrate) +{ + bool success = false; + char baudstring[16]; + snprintf(baudstring, sizeof(baudstring), "%ld", baudrate); + + // Stop the GPS driver first + static const char *gps_argv[] {"gps", "stop", nullptr}; + static const char *passthru_argv[] {"serial_passthru", "start", "-t", "-b", baudstring, "-e", USB_DEVICE_PATH, "-d", SERIAL_PASSTHRU_UBLOX_DEV, nullptr}; + + if (execute_process((char **)gps_argv) > 0) { + if (execute_process((char **)passthru_argv) > 0) { + success = true; + } + } + + return success; +} +#endif + +int CdcAcmAutostart::execute_process(char **argv) +{ + int pid = -1; + sched_lock(); + + pid = exec_builtin(argv[0], argv, nullptr, 0); + + sched_unlock(); + return pid; +} + +int CdcAcmAutostart::task_spawn(int argc, char *argv[]) +{ + CdcAcmAutostart *instance = new CdcAcmAutostart(); + + if (!instance) { + PX4_ERR("alloc failed"); + return -1; + } + + int ret = instance->Start(); + + if (ret != PX4_OK) { + delete instance; + return ret; + } + + _object.store(instance); + _task_id = task_id_is_work_queue; + + return ret; +} + +void CdcAcmAutostart::UpdateParams(const bool force) +{ + if (_parameter_update_sub.updated() || force) { + parameter_update_s param_update; + _parameter_update_sub.copy(¶m_update); + ModuleParams::updateParams(); + } +} + +int CdcAcmAutostart::custom_command(int argc, char *argv[]) +{ + return print_usage("unknown command"); +} + +int CdcAcmAutostart::print_status() +{ + const char *state = ""; + const char *protocol = ""; + + switch (_state) { + case UsbAutoStartState::disconnected: + state = "disconnected"; + break; + + case UsbAutoStartState::connecting: + state = "connecting"; + break; + + case UsbAutoStartState::connected: + state = "connected"; + break; + + case UsbAutoStartState::disconnecting: + state = "disconnecting"; + break; + } + + switch (_active_protocol) { + case UsbProtocol::none: + protocol = "none"; + break; + + case UsbProtocol::mavlink: + protocol = "mavlink"; + break; + + case UsbProtocol::nsh: + protocol = "nsh"; + break; + + case UsbProtocol::ublox: + protocol = "ublox"; + break; + } + + PX4_INFO("Running"); + PX4_INFO("State: %s", state); + PX4_INFO("Protocol: %s", protocol); + return PX4_OK; +} + +int CdcAcmAutostart::print_usage(const char *reason) +{ + if (reason) { + printf("%s\n\n", reason); + } + + PRINT_MODULE_DESCRIPTION( + R"DESCR_STR( +### Description +This module listens on USB and auto-configures the protocol depending on the bytes received. +The supported protocols are: MAVLink, nsh, and ublox serial passthrough. If the parameter SYS_USB_AUTO=2 +the module will only try to start mavlink as long as the USB VBUS is detected. Otherwise it will spin +and continue to check for VBUS and start mavlink once it is detected. +)DESCR_STR"); + + PRINT_MODULE_USAGE_NAME("cdcacm_autostart", "system"); + PRINT_MODULE_USAGE_COMMAND("start"); + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); + + return 0; +} + +#endif + +extern "C" __EXPORT int cdcacm_autostart_main(int argc, char *argv[]) +{ +#if defined(CONFIG_SYSTEM_CDCACM) + return CdcAcmAutostart::main(argc, argv); +#endif + return 1; +} diff --git a/src/drivers/cdcacm_autostart/cdcacm_autostart.h b/src/drivers/cdcacm_autostart/cdcacm_autostart.h new file mode 100644 index 000000000000..a0e12715151b --- /dev/null +++ b/src/drivers/cdcacm_autostart/cdcacm_autostart.h @@ -0,0 +1,124 @@ +/**************************************************************************** + * + * Copyright (c) 2023 PX4 Development Team. 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. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "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 + * COPYRIGHT OWNER OR CONTRIBUTORS 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. + * + ****************************************************************************/ + +#pragma once + +#include +#include +#include +#include +#include +#include + +#include + +using namespace time_literals; + +class CdcAcmAutostart : public ModuleBase, public ModuleParams, public px4::ScheduledWorkItem +{ +public: + CdcAcmAutostart(); + ~CdcAcmAutostart() override; + + /** @see ModuleBase */ + static int task_spawn(int argc, char *argv[]); + + /** @see ModuleBase */ + static int custom_command(int argc, char *argv[]); + + /** @see ModuleBase */ + static int print_usage(const char *reason = nullptr); + + /** @see ModuleBase */ + int print_status() override; + + int Start(); + +private: + + enum class UsbAutoStartState { + disconnected, + connecting, + connected, + disconnecting, + }; + + enum class UsbProtocol { + none, + mavlink, + nsh, + ublox, + }; + + void Run() override; + + void UpdateParams(const bool force = false); + + void run_state_machine(); + + void state_disconnected(); + void state_connecting(); + void state_connected(); + void state_disconnecting(); + + bool scan_buffer_for_mavlink_reboot(); + bool scan_buffer_for_mavlink_heartbeat(); + bool scan_buffer_for_carriage_returns(); + bool scan_buffer_for_ublox_bytes(); + + bool start_mavlink(); + bool start_nsh(); +#if defined(CONFIG_SERIAL_PASSTHRU_UBLOX) + bool start_ublox_serial_passthru(speed_t baudrate); +#endif + int execute_process(char **argv); + + uORB::Subscription _actuator_armed_sub{ORB_ID(actuator_armed)}; + uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 500_ms}; + + UsbAutoStartState _state{UsbAutoStartState::disconnected}; + UsbProtocol _active_protocol{UsbProtocol::none}; + bool _vbus_present = false; + bool _vbus_present_prev = false; + int _ttyacm_fd = -1; + + char _buffer[80] = {}; + int _bytes_read = 0; + + uint32_t _reschedule_time = 0; + + DEFINE_PARAMETERS( + (ParamInt) _sys_usb_auto, + (ParamInt) _usb_mav_mode + ) +}; diff --git a/src/drivers/cdcacm_autostart/cdcacm_autostart_params.c b/src/drivers/cdcacm_autostart/cdcacm_autostart_params.c new file mode 100644 index 000000000000..3dcc16ad2f4f --- /dev/null +++ b/src/drivers/cdcacm_autostart/cdcacm_autostart_params.c @@ -0,0 +1,68 @@ +/**************************************************************************** + * + * Copyright (c) 2024 PX4 Development Team. 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. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "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 + * COPYRIGHT OWNER OR CONTRIBUTORS 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. + * + ****************************************************************************/ + +/** + * Enable USB autostart + * + * @value 0 Disabled + * @value 1 Auto-detect + * @value 2 MAVLink + * + * @reboot_required true + * + * @group CDCACM + */ +PARAM_DEFINE_INT32(SYS_USB_AUTO, 2); + +/** + * Specify USB MAVLink mode + * + * @value 0 normal + * @value 1 custom + * @value 2 onboard + * @value 3 osd + * @value 4 magic + * @value 5 config + * @value 6 iridium + * @value 7 minimal + * @value 8 extvision + * @value 9 extvisionmin + * @value 10 gimbal + * @value 11 onboard_low_bandwidth + * @value 12 uavionix + * + * @reboot_required true + * + * @group CDCACM + */ +PARAM_DEFINE_INT32(USB_MAV_MODE, 2); \ No newline at end of file diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 722c1254f65c..186bfe793631 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -2094,11 +2094,6 @@ Mavlink::task_main(int argc, char *argv[]) /* USB has no baudrate, but use a magic number for 'fast' */ _baudrate = 2000000; - - if (_mode == MAVLINK_MODE_COUNT) { - _mode = MAVLINK_MODE_CONFIG; - } - _ftp_on = true; _is_usb_uart = true; @@ -2223,11 +2218,24 @@ Mavlink::task_main(int argc, char *argv[]) /* open the UART device after setting the instance, as it might block */ if (get_protocol() == Protocol::SERIAL) { - _uart_fd = mavlink_open_uart(_baudrate, _device_name, _flow_control); - if (_uart_fd < 0) { - PX4_ERR("could not open %s", _device_name); - return PX4_ERROR; + // NOTE: we attempt to open the port multiple times due to sercon returning before + // the port is ready to be opened. This avoids needing to sleep() after sercon_main. + int attempts = 0; + static const int max_attempts = 3; + + while (_uart_fd < 0) { + _uart_fd = mavlink_open_uart(_baudrate, _device_name, _flow_control); + attempts++; + + if (_uart_fd < 0 && attempts < max_attempts) { + PX4_ERR("could not open %s, retrying", _device_name); + px4_usleep(1_s); + + } else if (_uart_fd < 0) { + PX4_ERR("failed to open %s after %d attempts, exiting!", _device_name, attempts); + return PX4_ERROR; + } } } diff --git a/src/systemcmds/serial_passthru/Kconfig b/src/systemcmds/serial_passthru/Kconfig index 4c4cb107d8ac..aabd8c59fe27 100644 --- a/src/systemcmds/serial_passthru/Kconfig +++ b/src/systemcmds/serial_passthru/Kconfig @@ -11,7 +11,7 @@ config SERIAL_PASSTHRU_UBLOX bool "Detect and Auto Connect on U-Center messages" default n ---help--- - This option will enable the cdc_acm_check to launch + This option will enable the cdcacm_autostart to launch The passthru driver. # From e72ecdbefb2aaddc5ad7fd6c9171996edf7d0bcb Mon Sep 17 00:00:00 2001 From: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Date: Mon, 20 May 2024 12:38:19 -0600 Subject: [PATCH 23/34] drivers/imu: new Murata SCH16T IMU driver (#22914) --------- Co-authored-by: alexklimaj --- ROMFS/px4fmu_common/init.d/rc.sensors | 6 + boards/ark/fmu-v6x/default.px4board | 1 + src/drivers/drv_sensor.h | 2 + src/drivers/imu/Kconfig | 1 + src/drivers/imu/murata/Kconfig | 3 + src/drivers/imu/murata/sch16t/CMakeLists.txt | 47 ++ src/drivers/imu/murata/sch16t/Kconfig | 5 + .../murata/sch16t/Murata_SCH16T_registers.hpp | 115 ++++ src/drivers/imu/murata/sch16t/SCH16T.cpp | 516 ++++++++++++++++++ src/drivers/imu/murata/sch16t/SCH16T.hpp | 149 +++++ src/drivers/imu/murata/sch16t/parameters.c | 44 ++ src/drivers/imu/murata/sch16t/sch16t_main.cpp | 87 +++ 12 files changed, 976 insertions(+) create mode 100644 src/drivers/imu/murata/Kconfig create mode 100644 src/drivers/imu/murata/sch16t/CMakeLists.txt create mode 100644 src/drivers/imu/murata/sch16t/Kconfig create mode 100644 src/drivers/imu/murata/sch16t/Murata_SCH16T_registers.hpp create mode 100644 src/drivers/imu/murata/sch16t/SCH16T.cpp create mode 100644 src/drivers/imu/murata/sch16t/SCH16T.hpp create mode 100644 src/drivers/imu/murata/sch16t/parameters.c create mode 100644 src/drivers/imu/murata/sch16t/sch16t_main.cpp diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors index 490038c608fe..5410d28beeb1 100644 --- a/ROMFS/px4fmu_common/init.d/rc.sensors +++ b/ROMFS/px4fmu_common/init.d/rc.sensors @@ -138,6 +138,12 @@ then adis16507 -S start fi +# SCH16T spi external IMU +if param compare -s SENS_EN_SCH16T 1 +then + sch16t -S start +fi + # Eagle Tree airspeed sensor external I2C if param compare -s SENS_EN_ETSASPD 1 then diff --git a/boards/ark/fmu-v6x/default.px4board b/boards/ark/fmu-v6x/default.px4board index 1209adb9dcc4..168b17cdfaa9 100644 --- a/boards/ark/fmu-v6x/default.px4board +++ b/boards/ark/fmu-v6x/default.px4board @@ -20,6 +20,7 @@ CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_HEATER=y CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16507=y +CONFIG_DRIVERS_IMU_MURATA_SCH16T=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y CONFIG_DRIVERS_IMU_INVENSENSE_IIM42652=y CONFIG_DRIVERS_IMU_INVENSENSE_IIM42653=y diff --git a/src/drivers/drv_sensor.h b/src/drivers/drv_sensor.h index 4b1d18e76ba0..604ab4946b29 100644 --- a/src/drivers/drv_sensor.h +++ b/src/drivers/drv_sensor.h @@ -133,6 +133,8 @@ #define DRV_IMU_DEVTYPE_ADIS16477 0x59 #define DRV_IMU_DEVTYPE_ADIS16507 0x5A +#define DRV_IMU_DEVTYPE_SCH16T 0x5B + #define DRV_BARO_DEVTYPE_MPC2520 0x5F #define DRV_BARO_DEVTYPE_LPS22HB 0x60 diff --git a/src/drivers/imu/Kconfig b/src/drivers/imu/Kconfig index 3b084a580169..ee0978d39cd9 100644 --- a/src/drivers/imu/Kconfig +++ b/src/drivers/imu/Kconfig @@ -8,6 +8,7 @@ menu "IMU" select DRIVERS_IMU_ANALOG_DEVICES_ADIS16470 select DRIVERS_IMU_BOSCH_BMI055 select DRIVERS_IMU_BOSCH_BMI088 + select DRIVERS_IMU_MURATA_SCH16T select DRIVERS_IMU_NXP_FXAS21002C select DRIVERS_IMU_NXP_FXOS8701CQ select DRIVERS_IMU_INVENSENSE_ICM20602 diff --git a/src/drivers/imu/murata/Kconfig b/src/drivers/imu/murata/Kconfig new file mode 100644 index 000000000000..36d4534078aa --- /dev/null +++ b/src/drivers/imu/murata/Kconfig @@ -0,0 +1,3 @@ +menu "Murata" +rsource "*/Kconfig" +endmenu #Murata diff --git a/src/drivers/imu/murata/sch16t/CMakeLists.txt b/src/drivers/imu/murata/sch16t/CMakeLists.txt new file mode 100644 index 000000000000..73b90a12fb45 --- /dev/null +++ b/src/drivers/imu/murata/sch16t/CMakeLists.txt @@ -0,0 +1,47 @@ +############################################################################ +# +# Copyright (c) 2022 PX4 Development Team. 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. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "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 +# COPYRIGHT OWNER OR CONTRIBUTORS 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. +# +############################################################################ + +px4_add_module( + MODULE drivers__imu__murata__sch16t + MAIN sch16t + COMPILE_FLAGS + SRCS + SCH16T.cpp + SCH16T.hpp + sch16t_main.cpp + Murata_SCH16T_registers.hpp + DEPENDS + drivers_accelerometer + drivers_gyroscope + px4_work_queue + ) diff --git a/src/drivers/imu/murata/sch16t/Kconfig b/src/drivers/imu/murata/sch16t/Kconfig new file mode 100644 index 000000000000..ef0e906edd25 --- /dev/null +++ b/src/drivers/imu/murata/sch16t/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_IMU_MURATA_SCH16T + bool "SCH16T" + default n + ---help--- + Enable support for murata SCH16T diff --git a/src/drivers/imu/murata/sch16t/Murata_SCH16T_registers.hpp b/src/drivers/imu/murata/sch16t/Murata_SCH16T_registers.hpp new file mode 100644 index 000000000000..07d84dcb36e7 --- /dev/null +++ b/src/drivers/imu/murata/sch16t/Murata_SCH16T_registers.hpp @@ -0,0 +1,115 @@ +/**************************************************************************** + * + * Copyright (c) 2024 PX4 Development Team. 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. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "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 + * COPYRIGHT OWNER OR CONTRIBUTORS 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. + * + ****************************************************************************/ + +#pragma once + +#include + +namespace Murata_SCH16T +{ +static constexpr uint32_t SPI_SPEED = 5 * 1000 * 1000; // 5 MHz SPI serial interface +static constexpr uint32_t SAMPLE_INTERVAL_US = 678; // 1500 Hz -- decimation factor 8, F_PRIM/16, 1.475 kHz +static constexpr uint16_t EOI = (1 << 1); // End of Initialization +static constexpr uint16_t EN_SENSOR = (1 << 0); // Enable RATE and ACC measurement +static constexpr uint16_t DRY_DRV_EN = (1 << 5); // Enables Data ready function +static constexpr uint16_t FILTER_BYPASS = (0b111); // Bypass filter +static constexpr uint16_t RATE_300DPS_1475HZ = 0b0'001'001'011'011'011; // Gyro XYZ range 300 deg/s @ 1475Hz +static constexpr uint16_t ACC12_8G_1475HZ = 0b0'001'001'011'011'011; // Acc XYZ range 8 G and 1475 update rate +static constexpr uint16_t ACC3_26G = (0b000 << 0); +static constexpr uint16_t SPI_SOFT_RESET = (0b1010); + +// Data registers +#define RATE_X1 0x01 // 20 bit +#define RATE_Y1 0x02 // 20 bit +#define RATE_Z1 0x03 // 20 bit +#define ACC_X1 0x04 // 20 bit +#define ACC_Y1 0x05 // 20 bit +#define ACC_Z1 0x06 // 20 bit +#define ACC_X3 0x07 // 20 bit +#define ACC_Y3 0x08 // 20 bit +#define ACC_Z3 0x09 // 20 bit +#define RATE_X2 0x0A // 20 bit +#define RATE_Y2 0x0B // 20 bit +#define RATE_Z2 0x0C // 20 bit +#define ACC_X2 0x0D // 20 bit +#define ACC_Y2 0x0E // 20 bit +#define ACC_Z2 0x0F // 20 bit +#define TEMP 0x10 // 16 bit +// Status registers +#define STAT_SUM 0x14 // 16 bit +#define STAT_SUM_SAT 0x15 // 16 bit +#define STAT_COM 0x16 // 16 bit +#define STAT_RATE_COM 0x17 // 16 bit +#define STAT_RATE_X 0x18 // 16 bit +#define STAT_RATE_Y 0x19 // 16 bit +#define STAT_RATE_Z 0x1A // 16 bit +#define STAT_ACC_X 0x1B // 16 bit +#define STAT_ACC_Y 0x1C // 16 bit +#define STAT_ACC_Z 0x1D // 16 bit +// Control registers +#define CTRL_FILT_RATE 0x25 // 9 bit +#define CTRL_FILT_ACC12 0x26 // 9 bit +#define CTRL_FILT_ACC3 0x27 // 9 bit +#define CTRL_RATE 0x28 // 15 bit +#define CTRL_ACC12 0x29 // 15 bit +#define CTRL_ACC3 0x2A // 3 bit +#define CTRL_USER_IF 0x33 // 16 bit +#define CTRL_ST 0x34 // 13 bit +#define CTRL_MODE 0x35 // 4 bit +#define CTRL_RESET 0x36 // 4 bit +// Misc registers +#define ASIC_ID 0x3B // 12 bit +#define COMP_ID 0x3C // 16 bit +#define SN_ID1 0x3D // 16 bit +#define SN_ID2 0x3E // 16 bit +#define SN_ID3 0x3F // 16 bit + +// STAT_SUM_SAT bits +#define STAT_SUM_SAT_RSVD (1 << 15) +#define STAT_SUM_SAT_RATE_X1 (1 << 14) +#define STAT_SUM_SAT_RATE_Y1 (1 << 13) +#define STAT_SUM_SAT_RATE_Z1 (1 << 12) +#define STAT_SUM_SAT_ACC_X1 (1 << 11) +#define STAT_SUM_SAT_ACC_Y1 (1 << 10) +#define STAT_SUM_SAT_ACC_Z1 (1 << 9) +#define STAT_SUM_SAT_ACC_X3 (1 << 8) +#define STAT_SUM_SAT_ACC_Y3 (1 << 7) +#define STAT_SUM_SAT_ACC_Z3 (1 << 6) +#define STAT_SUM_SAT_RATE_X2 (1 << 5) +#define STAT_SUM_SAT_RATE_Y2 (1 << 4) +#define STAT_SUM_SAT_RATE_Z2 (1 << 3) +#define STAT_SUM_SAT_ACC_X2 (1 << 2) +#define STAT_SUM_SAT_ACC_Y2 (1 << 1) +#define STAT_SUM_SAT_ACC_Z2 (1 << 0) + +} // namespace Murata_SCH16T diff --git a/src/drivers/imu/murata/sch16t/SCH16T.cpp b/src/drivers/imu/murata/sch16t/SCH16T.cpp new file mode 100644 index 000000000000..5a682bfe23bd --- /dev/null +++ b/src/drivers/imu/murata/sch16t/SCH16T.cpp @@ -0,0 +1,516 @@ +/**************************************************************************** + * + * Copyright (c) 2024 PX4 Development Team. 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. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "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 + * COPYRIGHT OWNER OR CONTRIBUTORS 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. + * + ****************************************************************************/ + +#include "SCH16T.hpp" + +using namespace time_literals; + +#define SPI48_DATA_INT32(a) (((int32_t)(((a) << 4) & 0xfffff000UL)) >> 12) +#define SPI48_DATA_UINT32(a) ((uint32_t)(((a) >> 8) & 0x000fffffUL)) +#define SPI48_DATA_UINT16(a) ((uint16_t)(((a) >> 8) & 0x0000ffffUL)) + +static constexpr uint32_t POWER_ON_TIME = 250_ms; + +SCH16T::SCH16T(const I2CSPIDriverConfig &config) : + SPI(config), + I2CSPIDriver(config), + _px4_accel(get_device_id(), config.rotation), + _px4_gyro(get_device_id(), config.rotation), + _drdy_gpio(config.drdy_gpio) +{ + if (_drdy_gpio != 0) { + _drdy_missed_perf = perf_alloc(PC_COUNT, MODULE_NAME": DRDY missed"); + } + +#if defined(SPI6_nRESET_EXTERNAL1) + _hardware_reset_available = true; +#endif +} + +SCH16T::~SCH16T() +{ + perf_free(_reset_perf); + perf_free(_bad_transfer_perf); + perf_free(_perf_crc_bad); + perf_free(_perf_frame_bad); + perf_free(_drdy_missed_perf); +} + +int SCH16T::init() +{ + px4_usleep(POWER_ON_TIME); + + int ret = SPI::init(); + + if (ret != PX4_OK) { + DEVICE_DEBUG("SPI::init failed (%i)", ret); + return ret; + } + + Reset(); + + return PX4_OK; +} + +int SCH16T::probe() +{ + if (hrt_absolute_time() < POWER_ON_TIME) { + PX4_WARN("Required Power-On Start-Up Time %" PRIu32 " ms", POWER_ON_TIME); + } + + RegisterRead(COMP_ID); + uint16_t comp_id = SPI48_DATA_UINT16(RegisterRead(ASIC_ID)); + uint16_t asic_id = SPI48_DATA_UINT16(RegisterRead(ASIC_ID)); + + RegisterRead(SN_ID1); + uint16_t sn_id1 = SPI48_DATA_UINT16(RegisterRead(SN_ID2)); + uint16_t sn_id2 = SPI48_DATA_UINT16(RegisterRead(SN_ID3)); + uint16_t sn_id3 = SPI48_DATA_UINT16(RegisterRead(SN_ID3)); + + char serial_str[14]; + snprintf(serial_str, 14, "%05d%01X%04X", sn_id2, sn_id1 & 0x000F, sn_id3); + + PX4_INFO("Serial:\t %s", serial_str); + PX4_INFO("COMP_ID:\t 0x%0x", comp_id); + PX4_INFO("ASIC_ID:\t 0x%0x", asic_id); + + // SCH16T-K01 - ID hex = 0x0020 + // SCH1633-B13 - ID hex = 0x0017 + bool success = asic_id == 0x20 && comp_id == 0x17; + + return success ? PX4_OK : PX4_ERROR; +} + +void SCH16T::Reset() +{ + if (_drdy_gpio) { + DataReadyInterruptDisable(); + } + + ScheduleClear(); + + _state = STATE::RESET_INIT; + ScheduleNow(); +} + +void SCH16T::ResetSpi6(bool reset) +{ +#if defined(SPI6_RESET) + SPI6_RESET(reset); +#endif +} + +void SCH16T::exit_and_cleanup() +{ + if (_drdy_gpio) { + DataReadyInterruptDisable(); + } + + I2CSPIDriverBase::exit_and_cleanup(); +} + +void SCH16T::print_status() +{ + I2CSPIDriverBase::print_status(); + perf_print_counter(_reset_perf); + perf_print_counter(_bad_transfer_perf); + perf_print_counter(_perf_crc_bad); + perf_print_counter(_perf_frame_bad); + perf_print_counter(_drdy_missed_perf); +} + +void SCH16T::RunImpl() +{ + const hrt_abstime now = hrt_absolute_time(); + + switch (_state) { + case STATE::RESET_INIT: { + perf_count(_reset_perf); + + _failure_count = 0; + + if (_hardware_reset_available) { + PX4_INFO("Resetting (hard)"); + ResetSpi6(true); + _state = STATE::RESET_HARD; + ScheduleDelayed(2_ms); + + } else { + PX4_INFO("Resetting (soft)"); + SoftwareReset(); + _state = STATE::CONFIGURE; + ScheduleDelayed(POWER_ON_TIME); + } + + break; + } + + case STATE::RESET_HARD: { + if (_hardware_reset_available) { + ResetSpi6(false); + } + + _state = STATE::CONFIGURE; + ScheduleDelayed(POWER_ON_TIME); + break; + } + + case STATE::CONFIGURE: { + Configure(); + + _state = STATE::LOCK_CONFIGURATION; + ScheduleDelayed(POWER_ON_TIME); + break; + } + + case STATE::LOCK_CONFIGURATION: { + ReadStatusRegisters(); // Read all status registers once + RegisterWrite(CTRL_MODE, (EOI | EN_SENSOR)); // Write EOI and EN_SENSOR + + _state = STATE::VALIDATE; + ScheduleDelayed(5_ms); + break; + } + + case STATE::VALIDATE: { + ReadStatusRegisters(); // Read all status registers twice + ReadStatusRegisters(); + + // Check that registers are configured properly and that the sensor status is OK + if (ValidateSensorStatus() && ValidateRegisterConfiguration()) { + _state = STATE::READ; + + if (_drdy_gpio) { + DataReadyInterruptConfigure(); + ScheduleDelayed(100_ms); // backup schedule as a watchdog timeout + + } else { + ScheduleOnInterval(SAMPLE_INTERVAL_US, SAMPLE_INTERVAL_US); + } + + } else { + _state = STATE::RESET_INIT; + ScheduleDelayed(100_ms); + } + + break; + } + + case STATE::READ: { + hrt_abstime timestamp_sample = now; + + if (_drdy_gpio) { + // scheduled from interrupt if _drdy_timestamp_sample was set as expected + const hrt_abstime drdy_timestamp_sample = _drdy_timestamp_sample.fetch_and(0); + + if ((now - drdy_timestamp_sample) < SAMPLE_INTERVAL_US) { + timestamp_sample = drdy_timestamp_sample; + + } else { + perf_count(_drdy_missed_perf); + } + + // push backup schedule back + ScheduleDelayed(SAMPLE_INTERVAL_US * 2); + } + + // Collect the data + SensorData data = {}; + + if (ReadData(&data)) { + _px4_accel.set_temperature(float(data.temp) / 100.f); // Temperature signal sensitivity is 100 LSB/°C + _px4_gyro.set_temperature(float(data.temp) / 100.f); + _px4_accel.update(timestamp_sample, data.acc_x, data.acc_y, data.acc_z); + _px4_gyro.update(timestamp_sample, data.gyro_x, data.gyro_y, data.gyro_z); + + if (_failure_count > 0) { + _failure_count--; + } + + } else { + perf_count(_bad_transfer_perf); + _failure_count++; + } + + // Reset if successive failures + if (_failure_count > 10) { + PX4_INFO("Failure count high, resetting"); + Reset(); + return; + } + + break; + } + + default: + break; + } // end switch/case +} + +bool SCH16T::ReadData(SensorData *data) +{ + uint64_t temp = 0; + uint64_t gyro_x = 0; + uint64_t gyro_y = 0; + uint64_t gyro_z = 0; + uint64_t acc_x = 0; + uint64_t acc_y = 0; + uint64_t acc_z = 0; + + // Data registers are 20bit 2s complement + RegisterRead(TEMP); + temp = RegisterRead(STAT_SUM_SAT); + _sensor_status.saturation = SPI48_DATA_UINT16(RegisterRead(RATE_X2)); + gyro_x = RegisterRead(RATE_Y2); + gyro_y = RegisterRead(RATE_Z2); + + // Check if ACC2 is saturated, if so, use ACC3 + if ((_sensor_status.saturation & STAT_SUM_SAT_ACC_X2) || (_sensor_status.saturation & STAT_SUM_SAT_ACC_Y2) + || (_sensor_status.saturation & STAT_SUM_SAT_ACC_Z2)) { + gyro_z = RegisterRead(ACC_X3); + acc_x = RegisterRead(ACC_Y3); + acc_y = RegisterRead(ACC_Z3); + acc_z = RegisterRead(TEMP); + _px4_accel.set_scale(1.f / 1600.f); + _px4_accel.set_range(260.f); + + } else { + gyro_z = RegisterRead(ACC_X2); + acc_x = RegisterRead(ACC_Y2); + acc_y = RegisterRead(ACC_Z2); + acc_z = RegisterRead(TEMP); + _px4_accel.set_scale(1.f / 3200.f); + _px4_accel.set_range(163.4f); + } + + static constexpr uint64_t MASK48_ERROR = 0x001E00000000UL; + uint64_t values[] = { gyro_x, gyro_y, gyro_z, acc_x, acc_y, acc_z, temp }; + + for (auto v : values) { + // Check for frame errors + if (v & MASK48_ERROR) { + perf_count(_perf_frame_bad); + return false; + } + + // Validate the CRC + if (uint8_t(v & 0xff) != CalculateCRC8(v)) { + perf_count(_perf_crc_bad); + return false; + } + } + + // Data registers are 20bit 2s complement + data->acc_x = SPI48_DATA_INT32(acc_x); + data->acc_y = SPI48_DATA_INT32(acc_y); + data->acc_z = SPI48_DATA_INT32(acc_z); + data->gyro_x = SPI48_DATA_INT32(gyro_x); + data->gyro_y = SPI48_DATA_INT32(gyro_y); + data->gyro_z = SPI48_DATA_INT32(gyro_z); + // Temperature data is always 16 bits wide. Drop 4 LSBs as they are not used. + data->temp = SPI48_DATA_INT32(temp) >> 4; + + // Conver to PX4 coordinate system (FLU to FRD) + data->acc_x = data->acc_x; + data->acc_y = -data->acc_y; + data->acc_z = -data->acc_z; + data->gyro_x = data->gyro_x; + data->gyro_y = -data->gyro_y; + data->gyro_z = -data->gyro_z; + + return true; +} + +void SCH16T::Configure() +{ + for (auto &r : _registers) { + RegisterWrite(r.addr, r.value); + } + + RegisterWrite(CTRL_USER_IF, DRY_DRV_EN); // Enable data ready + RegisterWrite(CTRL_MODE, EN_SENSOR); // Enable the sensor + + // NOTE: we use ACC3 for the higher range. The DRDY frequency adjusts to whichever register bank is + // being sampled from (decimated vs interpolated outputs). RATE_XYZ2 is decimated and RATE_XYZ1 is interpolated. + _px4_gyro.set_range(math::radians(327.68f)); // +-/ 300°/sec calibrated range, 327.68°/sec electrical headroom (20bit) + _px4_gyro.set_scale(math::radians(1.f / 1600.f)); // scaling 1600 LSB/°/sec -> rad/s per LSB + + // ACC12 range is 163.4 m/s^2, 3200 LSB/(m/s^2), ACC3 range is 260 m/s^2, 1600 LSB/(m/s^2) + _px4_accel.set_range(163.4f); + _px4_accel.set_scale(1.f / 3200.f); +} + +bool SCH16T::ValidateRegisterConfiguration() +{ + bool success = true; + + for (auto &r : _registers) { + RegisterRead(r.addr); // double read, wasteful but makes the code cleaner, not high rate so doesn't matter anyway + auto value = SPI48_DATA_UINT16(RegisterRead(r.addr)); + + if (value != r.value) { + PX4_INFO("Register 0x%0x misconfigured: 0x%0x", r.addr, value); + success = false; + } + } + + return success; +} + +void SCH16T::ReadStatusRegisters() +{ + RegisterRead(STAT_SUM); + _sensor_status.summary = SPI48_DATA_UINT16(RegisterRead(STAT_SUM_SAT)); + _sensor_status.saturation = SPI48_DATA_UINT16(RegisterRead(STAT_COM)); + _sensor_status.common = SPI48_DATA_UINT16(RegisterRead(STAT_RATE_COM)); + _sensor_status.rate_common = SPI48_DATA_UINT16(RegisterRead(STAT_RATE_X)); + _sensor_status.rate_x = SPI48_DATA_UINT16(RegisterRead(STAT_RATE_Y)); + _sensor_status.rate_y = SPI48_DATA_UINT16(RegisterRead(STAT_RATE_Z)); + _sensor_status.rate_z = SPI48_DATA_UINT16(RegisterRead(STAT_ACC_X)); + _sensor_status.acc_x = SPI48_DATA_UINT16(RegisterRead(STAT_ACC_Y)); + _sensor_status.acc_y = SPI48_DATA_UINT16(RegisterRead(STAT_ACC_Z)); + _sensor_status.acc_z = SPI48_DATA_UINT16(RegisterRead(STAT_ACC_Z)); +} + +bool SCH16T::ValidateSensorStatus() +{ + auto &s = _sensor_status; + uint16_t values[] = { s.summary, s.saturation, s.common, s.rate_common, s.rate_x, s.rate_y, s.rate_z, s.acc_x, s.acc_y, s.acc_z }; + + for (auto v : values) { + if (v != 0xFFFF) { + PX4_INFO("Sensor status failed"); + return false; + } + } + + return true; +} + +void SCH16T::SoftwareReset() +{ + RegisterWrite(CTRL_RESET, SPI_SOFT_RESET); +} + +uint64_t SCH16T::RegisterRead(uint8_t addr) +{ + uint64_t frame = {}; + frame |= uint64_t(addr) << 38; // Target address offset + frame |= uint64_t(1) << 35; // FrameType: SPI48BF + frame |= uint64_t(CalculateCRC8(frame)); + + return TransferSpiFrame(frame); +} + +// Non-data registers are the only writable ones and are 16 bit or less +void SCH16T::RegisterWrite(uint8_t addr, uint16_t value) +{ + uint64_t frame = {}; + frame |= uint64_t(1) << 37; // Write bit + frame |= uint64_t(addr) << 38; // Target address offset + frame |= uint64_t(1) << 35; // FrameType: SPI48BF + frame |= uint64_t(value) << 8; + frame |= uint64_t(CalculateCRC8(frame)); + + // We don't care about the return frame on a write + (void)TransferSpiFrame(frame); +} + +// The SPI protocol (SafeSPI) is 48bit out-of-frame. This means read return frames will be received on the next transfer. +uint64_t SCH16T::TransferSpiFrame(uint64_t frame) +{ + set_frequency(SPI_SPEED); + + uint16_t buf[3]; + + for (int index = 0; index < 3; index++) { + buf[3 - index - 1] = (frame >> (index << 4)) & 0xFFFF; + } + + transferhword(buf, buf, 3); + +#if defined(DEBUG_BUILD) + PX4_INFO("TransferSpiFrame: 0x%llx", frame); + + PX4_INFO("RECEIVED"); + + for (auto r : buf) { + PX4_INFO("%u", r); + } + +#endif + + uint64_t value = {}; + + for (int index = 0; index < 3; index++) { + value |= (uint64_t)buf[index] << ((3 - index - 1) << 4); + } + + return value; +} + +int SCH16T::DataReadyInterruptCallback(int irq, void *context, void *arg) +{ + static_cast(arg)->DataReady(); + return 0; +} + +void SCH16T::DataReady() +{ + _drdy_timestamp_sample.store(hrt_absolute_time()); + ScheduleNow(); +} + +bool SCH16T::DataReadyInterruptConfigure() +{ + // Setup data ready on falling edge + return px4_arch_gpiosetevent(_drdy_gpio, true, false, false, &DataReadyInterruptCallback, this) == 0; +} + +bool SCH16T::DataReadyInterruptDisable() +{ + return px4_arch_gpiosetevent(_drdy_gpio, false, false, false, nullptr, nullptr) == 0; +} + +uint8_t SCH16T::CalculateCRC8(uint64_t frame) +{ + uint64_t data = frame & 0xFFFFFFFFFF00LL; + uint8_t crc = 0xFF; + + for (int i = 47; i >= 0; i--) { + uint8_t data_bit = data >> i & 0x01; + crc = crc & 0x80 ? (uint8_t)((crc << 1) ^ 0x2F) ^ data_bit : (uint8_t)(crc << 1) | data_bit; + } + + return crc; +} diff --git a/src/drivers/imu/murata/sch16t/SCH16T.hpp b/src/drivers/imu/murata/sch16t/SCH16T.hpp new file mode 100644 index 000000000000..6e390d70b7d8 --- /dev/null +++ b/src/drivers/imu/murata/sch16t/SCH16T.hpp @@ -0,0 +1,149 @@ +/**************************************************************************** + * + * Copyright (c) 2024 PX4 Development Team. 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. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "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 + * COPYRIGHT OWNER OR CONTRIBUTORS 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. + * + ****************************************************************************/ + +#pragma once + +#include "Murata_SCH16T_registers.hpp" + +#include +#include +#include + +using namespace Murata_SCH16T; + +class SCH16T : public device::SPI, public I2CSPIDriver +{ +public: + SCH16T(const I2CSPIDriverConfig &config); + ~SCH16T() override; + + static void print_usage(); + + void RunImpl(); + + int init() override; + void print_status() override; + +private: + struct SensorData { + int32_t acc_x; + int32_t acc_y; + int32_t acc_z; + int32_t gyro_x; + int32_t gyro_y; + int32_t gyro_z; + int32_t temp; + }; + + struct SensorStatus { + uint16_t summary; + uint16_t saturation; + uint16_t common; + uint16_t rate_common; + uint16_t rate_x; + uint16_t rate_y; + uint16_t rate_z; + uint16_t acc_x; + uint16_t acc_y; + uint16_t acc_z; + }; + + struct RegisterConfig { + RegisterConfig(uint16_t a, uint16_t v) + : addr(a) + , value(v) + {}; + uint8_t addr; + uint16_t value; + }; + + int probe() override; + void exit_and_cleanup() override; + + bool ValidateSensorStatus(); + bool ValidateRegisterConfiguration(); + void Reset(); + void ResetSpi6(bool reset); + uint8_t CalculateCRC8(uint64_t frame); + + bool ReadData(SensorData *data); + void ReadStatusRegisters(); + + void Configure(); + void SoftwareReset(); + + void RegisterWrite(uint8_t addr, uint16_t value); + uint64_t RegisterRead(uint8_t addr); + uint64_t TransferSpiFrame(uint64_t frame); + + static int DataReadyInterruptCallback(int irq, void *context, void *arg); + void DataReady(); + bool DataReadyInterruptConfigure(); + bool DataReadyInterruptDisable(); +private: + PX4Accelerometer _px4_accel; + PX4Gyroscope _px4_gyro; + + SensorStatus _sensor_status{}; + + int _failure_count{0}; + + px4::atomic _drdy_timestamp_sample{0}; + const spi_drdy_gpio_t _drdy_gpio; + bool _hardware_reset_available{false}; + + enum class STATE : uint8_t { + RESET_INIT, + RESET_HARD, + CONFIGURE, + LOCK_CONFIGURATION, + VALIDATE, + READ, + } _state{STATE::RESET_INIT}; + + RegisterConfig _registers[6] = { + RegisterConfig(CTRL_FILT_RATE, FILTER_BYPASS), // Bypass filter + RegisterConfig(CTRL_FILT_ACC12, FILTER_BYPASS), // Bypass filter + RegisterConfig(CTRL_FILT_ACC3, FILTER_BYPASS), // Bypass filter + RegisterConfig(CTRL_RATE, RATE_300DPS_1475HZ), // +/- 300 deg/s, 1600 LSB/(deg/s) -- default, Decimation 8, 1475Hz + RegisterConfig(CTRL_ACC12, ACC12_8G_1475HZ), // +/- 80 m/s^2, 3200 LSB/(m/s^2) -- default, Decimation 8, 1475Hz + RegisterConfig(CTRL_ACC3, ACC3_26G) // +/- 260 m/s^2, 1600 LSB/(m/s^2) -- default + }; + + perf_counter_t _reset_perf{perf_alloc(PC_COUNT, MODULE_NAME": reset")}; + perf_counter_t _bad_transfer_perf{perf_alloc(PC_COUNT, MODULE_NAME": bad transfer")}; + perf_counter_t _perf_crc_bad{perf_counter_t(perf_alloc(PC_COUNT, MODULE_NAME": CRC8 bad"))}; + perf_counter_t _perf_frame_bad{perf_counter_t(perf_alloc(PC_COUNT, MODULE_NAME": Frame bad"))}; + perf_counter_t _drdy_missed_perf{nullptr}; + +}; diff --git a/src/drivers/imu/murata/sch16t/parameters.c b/src/drivers/imu/murata/sch16t/parameters.c new file mode 100644 index 000000000000..205b2f020e08 --- /dev/null +++ b/src/drivers/imu/murata/sch16t/parameters.c @@ -0,0 +1,44 @@ +/**************************************************************************** + * + * Copyright (c) 2024 PX4 Development Team. 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. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "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 + * COPYRIGHT OWNER OR CONTRIBUTORS 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. + * + ****************************************************************************/ + +/** + * Murata SCH16T IMU (external SPI) + * + * @reboot_required true + * @min 0 + * @max 1 + * @group Sensors + * @value 0 Disabled + * @value 1 Enabled + */ +PARAM_DEFINE_INT32(SENS_EN_SCH16T, 0); diff --git a/src/drivers/imu/murata/sch16t/sch16t_main.cpp b/src/drivers/imu/murata/sch16t/sch16t_main.cpp new file mode 100644 index 000000000000..a5ae892c9973 --- /dev/null +++ b/src/drivers/imu/murata/sch16t/sch16t_main.cpp @@ -0,0 +1,87 @@ +/**************************************************************************** + * + * Copyright (c) 2024 PX4 Development Team. 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. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "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 + * COPYRIGHT OWNER OR CONTRIBUTORS 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. + * + ****************************************************************************/ + +#include "SCH16T.hpp" + +#include + +void SCH16T::print_usage() +{ + PRINT_MODULE_USAGE_NAME("sch16t", "driver"); + PRINT_MODULE_USAGE_SUBCATEGORY("imu"); + PRINT_MODULE_USAGE_COMMAND("start"); + PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(false, true); + PRINT_MODULE_USAGE_PARAM_INT('R', 0, 0, 35, "Rotation", true); + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); +} + +extern "C" int sch16t_main(int argc, char *argv[]) +{ + int ch; + using ThisDriver = SCH16T; + BusCLIArguments cli{false, true}; + cli.default_spi_frequency = SPI_SPEED; + cli.spi_mode = SPIDEV_MODE0; + + while ((ch = cli.getOpt(argc, argv, "R:")) != EOF) { + switch (ch) { + case 'R': + cli.rotation = (enum Rotation)atoi(cli.optArg()); + break; + } + } + + const char *verb = cli.optArg(); + + if (!verb) { + ThisDriver::print_usage(); + return -1; + } + + BusInstanceIterator iterator(MODULE_NAME, cli, DRV_IMU_DEVTYPE_SCH16T); + + if (!strcmp(verb, "start")) { + return ThisDriver::module_start(cli, iterator); + } + + if (!strcmp(verb, "stop")) { + return ThisDriver::module_stop(iterator); + } + + if (!strcmp(verb, "status")) { + return ThisDriver::module_status(iterator); + } + + ThisDriver::print_usage(); + return -1; +} From 1c213fa76058b96d7b90b93cf63e88b83cd54ec3 Mon Sep 17 00:00:00 2001 From: alexklimaj Date: Sun, 19 May 2024 12:42:58 -0600 Subject: [PATCH 24/34] boards: arkv6x ark_pi6x change mavlink dialect to development --- boards/ark/fmu-v6x/default.px4board | 1 + boards/ark/pi6x/default.px4board | 1 + 2 files changed, 2 insertions(+) diff --git a/boards/ark/fmu-v6x/default.px4board b/boards/ark/fmu-v6x/default.px4board index 168b17cdfaa9..1d1cc6f53d3f 100644 --- a/boards/ark/fmu-v6x/default.px4board +++ b/boards/ark/fmu-v6x/default.px4board @@ -60,6 +60,7 @@ CONFIG_MODULES_LOGGER=y CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y CONFIG_MODULES_MANUAL_CONTROL=y CONFIG_MODULES_MAVLINK=y +CONFIG_MAVLINK_DIALECT="development" CONFIG_MODULES_MC_ATT_CONTROL=y CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y diff --git a/boards/ark/pi6x/default.px4board b/boards/ark/pi6x/default.px4board index 45f992d69eed..49de557ae4bd 100644 --- a/boards/ark/pi6x/default.px4board +++ b/boards/ark/pi6x/default.px4board @@ -39,6 +39,7 @@ CONFIG_MODULES_LOGGER=y CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y CONFIG_MODULES_MANUAL_CONTROL=y CONFIG_MODULES_MAVLINK=y +CONFIG_MAVLINK_DIALECT="development" CONFIG_MODULES_MC_ATT_CONTROL=y CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y From 664a0f2cda1a5379c554fecef811ac127d9e0320 Mon Sep 17 00:00:00 2001 From: Konrad Date: Wed, 17 Apr 2024 13:42:25 +0200 Subject: [PATCH 25/34] HomePosition: Add minimum position change needed to be recognised as new home position --- src/modules/commander/HomePosition.cpp | 5 ++++- src/modules/commander/HomePosition.hpp | 2 ++ 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/src/modules/commander/HomePosition.cpp b/src/modules/commander/HomePosition.cpp index ea3955e27fe2..4aa341dbcf1c 100644 --- a/src/modules/commander/HomePosition.cpp +++ b/src/modules/commander/HomePosition.cpp @@ -34,6 +34,8 @@ #include "HomePosition.hpp" +#include + #include #include "commander_helper.h" @@ -83,7 +85,8 @@ bool HomePosition::hasMovedFromCurrentHomeLocation() } } - return (home_dist_xy > eph * 2.f) || (home_dist_z > epv * 2.f); + return (home_dist_xy > fmaxf(eph * 2.f, kMinHomePositionChangeEPH)) + || (home_dist_z > fmaxf(epv * 2.f, kMinHomePositionChangeEPV)); } bool HomePosition::setHomePosition(bool force) diff --git a/src/modules/commander/HomePosition.hpp b/src/modules/commander/HomePosition.hpp index 6346dac42e4f..07d6b1a63239 100644 --- a/src/modules/commander/HomePosition.hpp +++ b/src/modules/commander/HomePosition.hpp @@ -45,6 +45,8 @@ static constexpr int kHomePositionGPSRequiredFixType = 2; static constexpr float kHomePositionGPSRequiredEPH = 5.f; static constexpr float kHomePositionGPSRequiredEPV = 10.f; static constexpr float kHomePositionGPSRequiredEVH = 1.f; +static constexpr float kMinHomePositionChangeEPH = 1.f; +static constexpr float kMinHomePositionChangeEPV = 1.5f; class HomePosition { From 4a13e495d7b7dfc743314009e3a22d828260f49c Mon Sep 17 00:00:00 2001 From: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Date: Tue, 21 May 2024 19:49:40 -0600 Subject: [PATCH 26/34] boards: ark: pi6x: CONFIG_DRIVERS_CDCACM_AUTOSTART=y (#23163) --- boards/ark/fmu-v6x/default.px4board | 1 - boards/ark/pi6x/default.px4board | 1 + 2 files changed, 1 insertion(+), 1 deletion(-) diff --git a/boards/ark/fmu-v6x/default.px4board b/boards/ark/fmu-v6x/default.px4board index 1d1cc6f53d3f..3433f245acc1 100644 --- a/boards/ark/fmu-v6x/default.px4board +++ b/boards/ark/fmu-v6x/default.px4board @@ -15,7 +15,6 @@ CONFIG_DRIVERS_CAMERA_CAPTURE=y CONFIG_DRIVERS_CAMERA_TRIGGER=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y CONFIG_COMMON_DISTANCE_SENSOR=y -CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y CONFIG_DRIVERS_HEATER=y diff --git a/boards/ark/pi6x/default.px4board b/boards/ark/pi6x/default.px4board index 49de557ae4bd..7d381c9f0730 100644 --- a/boards/ark/pi6x/default.px4board +++ b/boards/ark/pi6x/default.px4board @@ -8,6 +8,7 @@ CONFIG_BOARD_SERIAL_RC="/dev/ttyS4" CONFIG_DRIVERS_ADC_BOARD_ADC=y CONFIG_DRIVERS_BAROMETER_BMP388=y CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y +CONFIG_DRIVERS_CDCACM_AUTOSTART=y CONFIG_DRIVERS_DISTANCE_SENSOR_BROADCOM_AFBRS50=y CONFIG_DRIVERS_DSHOT=y CONFIG_DRIVERS_GPS=y From 21e550fdba7a6af3990ef308851db0222fd25eb1 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Tue, 20 Feb 2024 11:52:08 +1300 Subject: [PATCH 27/34] tools/bootloader: add force-erase option If the STM32H7 fails to program or erase a full chunk of 256 bytes, the ECC check will trigger a busfault when trying to read from it. To speed up erasing and optimize wear, we read before erasing to check if it actually needs erasing. That's when a busfault happens and the erase time outs. The workaround is to add an option to do a full erase without check. Credit goes to: https://github.com/ArduPilot/ardupilot/pull/22090 And the protocol option added to the bootloader is the same as for ArduPilot, so compatible. Signed-off-by: Julian Oes --- Tools/px_uploader.py | 25 ++++++++--- platforms/nuttx/src/bootloader/common/bl.c | 12 +++++- platforms/nuttx/src/bootloader/common/bl.h | 4 +- .../src/bootloader/nxp/imxrt_common/main.c | 42 +++++++++---------- .../src/bootloader/stm/stm32_common/main.c | 9 +--- 5 files changed, 56 insertions(+), 36 deletions(-) diff --git a/Tools/px_uploader.py b/Tools/px_uploader.py index d479be314837..6328b914990d 100755 --- a/Tools/px_uploader.py +++ b/Tools/px_uploader.py @@ -195,6 +195,7 @@ class uploader(object): GET_CHIP = b'\x2c' # rev5+ , get chip version SET_BOOT_DELAY = b'\x2d' # rev5+ , set boot delay GET_CHIP_DES = b'\x2e' # rev5+ , get chip description in ASCII + CHIP_FULL_ERASE = b'\x40' # full erase of flash, rev6+ MAX_DES_LENGTH = 20 REBOOT = b'\x30' @@ -235,6 +236,7 @@ def __init__(self, portname, baudrate_bootloader, baudrate_flightstack): self.baudrate_bootloader = baudrate_bootloader self.baudrate_flightstack = baudrate_flightstack self.baudrate_flightstack_idx = -1 + self.force_erase = False def close(self): if self.port is not None: @@ -423,8 +425,14 @@ def __drawProgressBar(self, label, progress, maxVal): def __erase(self, label): print("Windowed mode: %s" % self.ackWindowedMode) print("\n", end='') - self.__send(uploader.CHIP_ERASE + - uploader.EOC) + + if self.force_erase: + print("Trying force erase of full chip...\n") + self.__send(uploader.CHIP_FULL_ERASE + + uploader.EOC) + else: + self.__send(uploader.CHIP_ERASE + + uploader.EOC) # erase is very slow, give it 30s deadline = _time() + 30.0 @@ -441,9 +449,14 @@ def __erase(self, label): if self.__trySync(): self.__drawProgressBar(label, 10.0, 10.0) + if self.force_erase: + print("\nForce erase done.\n") return - raise RuntimeError("timed out waiting for erase") + if self.force_erase: + raise RuntimeError("timed out waiting for erase, force erase is likely not supported by bootloader!") + else: + raise RuntimeError("timed out waiting for erase") # send a PROG_MULTI command to write a collection of bytes def __program_multi(self, data, windowMode): @@ -582,7 +595,8 @@ def identify(self): self.fw_maxsize = self.__getInfo(uploader.INFO_FLASH_SIZE) # upload the firmware - def upload(self, fw_list, force=False, boot_delay=None, boot_check=False): + def upload(self, fw_list, force=False, boot_delay=None, boot_check=False, force_erase=False): + self.force_erase = force_erase # select correct binary found_suitable_firmware = False for file in fw_list: @@ -790,6 +804,7 @@ def main(): parser.add_argument('--baud-bootloader', action="store", type=int, default=115200, help="Baud rate of the serial port (default is 115200) when communicating with bootloader, only required for true serial ports.") parser.add_argument('--baud-flightstack', action="store", default="57600", help="Comma-separated list of baud rate of the serial port (default is 57600) when communicating with flight stack (Mavlink or NSH), only required for true serial ports.") parser.add_argument('--force', action='store_true', default=False, help='Override board type check, or silicon errata checks and continue loading') + parser.add_argument('--force-erase', action="store_true", help="Do not perform the blank check, always erase every sector of the application space") parser.add_argument('--boot-delay', type=int, default=None, help='minimum boot delay to store in flash') parser.add_argument('--use-protocol-splitter-format', action='store_true', help='use protocol splitter format for reboot') parser.add_argument('firmware', action="store", nargs='+', help="Firmware file(s)") @@ -907,7 +922,7 @@ def main(): try: # ok, we have a bootloader, try flashing it - up.upload(args.firmware, force=args.force, boot_delay=args.boot_delay) + up.upload(args.firmware, force=args.force, boot_delay=args.boot_delay, force_erase=args.force_erase) # if we made this far without raising exceptions, the upload was successful successful = True diff --git a/platforms/nuttx/src/bootloader/common/bl.c b/platforms/nuttx/src/bootloader/common/bl.c index 61f3881d6f9e..e1dcfe8c5b8f 100644 --- a/platforms/nuttx/src/bootloader/common/bl.c +++ b/platforms/nuttx/src/bootloader/common/bl.c @@ -114,6 +114,7 @@ #define PROTO_RESERVED_0X37 0x37 // Reserved #define PROTO_RESERVED_0X38 0x38 // Reserved #define PROTO_RESERVED_0X39 0x39 // Reserved +#define PROTO_CHIP_FULL_ERASE 0x40 // Full erase, without any flash wear optimization #define PROTO_PROG_MULTI_MAX 64 // maximum PROG_MULTI size #define PROTO_READ_MULTI_MAX 255 // size of the size field @@ -649,6 +650,8 @@ bootloader(unsigned timeout) led_on(LED_ACTIVITY); + bool full_erase = false; + // handle the command byte switch (c) { @@ -728,6 +731,10 @@ bootloader(unsigned timeout) // success reply: INSYNC/OK // erase failure: INSYNC/FAILURE // + case PROTO_CHIP_FULL_ERASE: + full_erase = true; + + // Fallthrough case PROTO_CHIP_ERASE: /* expect EOC */ @@ -755,17 +762,18 @@ bootloader(unsigned timeout) arch_flash_unlock(); for (int i = 0; flash_func_sector_size(i) != 0; i++) { - flash_func_erase_sector(i); + flash_func_erase_sector(i, full_erase); } // disable the LED while verifying the erase led_set(LED_OFF); // verify the erase - for (address = 0; address < board_info.fw_size; address += 4) + for (address = 0; address < board_info.fw_size; address += 4) { if (flash_func_read_word(address) != 0xffffffff) { goto cmd_fail; } + } address = 0; SET_BL_STATE(STATE_PROTO_CHIP_ERASE); diff --git a/platforms/nuttx/src/bootloader/common/bl.h b/platforms/nuttx/src/bootloader/common/bl.h index 4115200db3bb..a39e7ce9086f 100644 --- a/platforms/nuttx/src/bootloader/common/bl.h +++ b/platforms/nuttx/src/bootloader/common/bl.h @@ -39,6 +39,8 @@ #pragma once +#include + /***************************************************************************** * Generic bootloader functions. */ @@ -105,7 +107,7 @@ extern void board_deinit(void); extern uint32_t board_get_devices(void); extern void clock_deinit(void); extern uint32_t flash_func_sector_size(unsigned sector); -extern void flash_func_erase_sector(unsigned sector); +extern void flash_func_erase_sector(unsigned sector, bool force); extern void flash_func_write_word(uintptr_t address, uint32_t word); extern uint32_t flash_func_read_word(uintptr_t address); extern uint32_t flash_func_read_otp(uintptr_t address); diff --git a/platforms/nuttx/src/bootloader/nxp/imxrt_common/main.c b/platforms/nuttx/src/bootloader/nxp/imxrt_common/main.c index 1197427a942c..fd0578f885c0 100644 --- a/platforms/nuttx/src/bootloader/nxp/imxrt_common/main.c +++ b/platforms/nuttx/src/bootloader/nxp/imxrt_common/main.c @@ -395,6 +395,24 @@ flash_func_sector_size(unsigned sector) return 0; } +/* imxRT uses Flash lib, not up_progmem so let's stub it here */ +up_progmem_ispageerased(unsigned sector) +{ + const uint32_t bytes_per_sector = flash_func_sector_size(sector); + uint32_t *address = (uint32_t *)(IMXRT_FLEXSPI1_CIPHER_BASE + (sector * bytes_per_sector)); + const uint32_t uint32_per_sector = bytes_per_sector / sizeof(*address); + + int blank = 0; /* Assume it is Bank */ + + for (uint32_t i = 0; i < uint32_per_sector; i++) { + if (address[i] != 0xffffffff) { + blank = -1; /* It is not blank */ + break; + } + } + + return blank; +} /*! * @name Configuration Option @@ -407,31 +425,15 @@ flash_func_sector_size(unsigned sector) * */ locate_code(".ramfunc") void -flash_func_erase_sector(unsigned sector) +flash_func_erase_sector(unsigned sector, bool force) { - if (sector > BOARD_FLASH_SECTORS || (int)sector < BOARD_FIRST_FLASH_SECTOR_TO_ERASE) { return; } - /* blank-check the sector */ - const uint32_t bytes_per_sector = flash_func_sector_size(sector); - uint32_t *address = (uint32_t *)(IMXRT_FLEXSPI1_CIPHER_BASE + (sector * bytes_per_sector)); - const uint32_t uint32_per_sector = bytes_per_sector / sizeof(*address); - bool blank = true; - - for (uint32_t i = 0; i < uint32_per_sector; i++) { - if (address[i] != 0xffffffff) { - blank = false; - break; - } - } + if (force || flash_func_is_sector_blank(sector) != 0) { + struct flexspi_nor_config_s *pConfig = &g_bootConfig; - - struct flexspi_nor_config_s *pConfig = &g_bootConfig; - - /* erase the sector if it failed the blank check */ - if (!blank) { uintptr_t offset = ((uintptr_t) address) - IMXRT_FLEXSPI1_CIPHER_BASE; irqstate_t flags; flags = enter_critical_section(); @@ -439,8 +441,6 @@ flash_func_erase_sector(unsigned sector) leave_critical_section(flags); UNUSED(status); } - - } void diff --git a/platforms/nuttx/src/bootloader/stm/stm32_common/main.c b/platforms/nuttx/src/bootloader/stm/stm32_common/main.c index 859d861b2094..cccfd41bea4c 100644 --- a/platforms/nuttx/src/bootloader/stm/stm32_common/main.c +++ b/platforms/nuttx/src/bootloader/stm/stm32_common/main.c @@ -466,18 +466,13 @@ flash_func_sector_size(unsigned sector) } void -flash_func_erase_sector(unsigned sector) +flash_func_erase_sector(unsigned sector, bool force) { if (sector > BOARD_FLASH_SECTORS || (int)sector < BOARD_FIRST_FLASH_SECTOR_TO_ERASE) { return; } - /* blank-check the sector */ - - bool blank = up_progmem_ispageerased(sector) == 0; - - /* erase the sector if it failed the blank check */ - if (!blank) { + if (force || (up_progmem_ispageerased(sector) != 0)) { up_progmem_eraseblock(sector); } } From 7c4507b6d6491aa446908495da20d964079295f3 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 10 May 2024 10:54:14 +1200 Subject: [PATCH 28/34] bootloader: add bootloader version This adds a new protocol extension which allows to get the bootloader version. The bootloader version is different from the bootloader protocol revision which has stabilized at 5 and is not easy to update unless a bootloader is actually breaking the protocol. The reason being that both the Python script as well as the uploader used in QGC will not attempt to load firmware if they don't know the bootloader version, so it could basically be considered a "breaking" protocol revision. Signed-off-by: Julian Oes --- CMakeLists.txt | 6 ++- Tools/px_uploader.py | 20 ++++++++- .../src/bootloader/common/CMakeLists.txt | 4 ++ platforms/nuttx/src/bootloader/common/bl.c | 43 ++++++++++++++++--- platforms/nuttx/src/bootloader/common/bl.h | 5 ++- platforms/nuttx/src/px4/common/CMakeLists.txt | 2 +- 6 files changed, 70 insertions(+), 10 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 82771613c9ba..fc57b95efc79 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,6 +1,6 @@ ############################################################################ # -# Copyright (c) 2017 - 2022 PX4 Development Team. All rights reserved. +# Copyright (c) 2017 - 2024 PX4 Development Team. All rights reserved. # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions @@ -132,7 +132,9 @@ list(GET VERSION_LIST 2 PX4_VERSION_PATCH) string(REPLACE "-" ";" PX4_VERSION_PATCH ${PX4_VERSION_PATCH}) list(GET PX4_VERSION_PATCH 0 PX4_VERSION_PATCH) -message(STATUS "PX4 version: ${PX4_GIT_TAG} (${PX4_VERSION_MAJOR}.${PX4_VERSION_MINOR}.${PX4_VERSION_PATCH})") +# # Capture only the hash part after 'g' +string(REGEX MATCH "g([a-f0-9]+)$" GIT_HASH "${PX4_GIT_TAG}") +set(PX4_GIT_HASH ${CMAKE_MATCH_1}) define_property(GLOBAL PROPERTY PX4_MODULE_LIBRARIES BRIEF_DOCS "PX4 module libs" diff --git a/Tools/px_uploader.py b/Tools/px_uploader.py index 6328b914990d..ce1b3cda5c0b 100755 --- a/Tools/px_uploader.py +++ b/Tools/px_uploader.py @@ -1,7 +1,7 @@ #!/usr/bin/env python3 ############################################################################ # -# Copyright (c) 2012-2017 PX4 Development Team. All rights reserved. +# Copyright (c) 2012-2024 PX4 Development Team. All rights reserved. # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions @@ -195,6 +195,7 @@ class uploader(object): GET_CHIP = b'\x2c' # rev5+ , get chip version SET_BOOT_DELAY = b'\x2d' # rev5+ , set boot delay GET_CHIP_DES = b'\x2e' # rev5+ , get chip description in ASCII + GET_VERSION = b'\x2f' # rev5+ , get chip description in ASCII CHIP_FULL_ERASE = b'\x40' # full erase of flash, rev6+ MAX_DES_LENGTH = 20 @@ -206,6 +207,7 @@ class uploader(object): INFO_BOARD_ID = b'\x02' # board type INFO_BOARD_REV = b'\x03' # board revision INFO_FLASH_SIZE = b'\x04' # max firmware size in bytes + BL_VERSION = b'\x07' # get bootloader version, e.g. major.minor.patch.githash (up to 20 chars) PROG_MULTI_MAX = 252 # protocol max is 255, must be multiple of 4 READ_MULTI_MAX = 252 # protocol max is 255 @@ -412,6 +414,18 @@ def __getCHIPDes(self): pieces = value.split(b",") return pieces + def __getVersion(self): + self.__send(uploader.GET_VERSION + uploader.EOC) + try: + length = self.__recv_int() + value = self.__recv(length) + self.__getSync() + except RuntimeError: + # Bootloader doesn't support version call + return "unknown" + pieces = value.split(b".") + return pieces + def __drawProgressBar(self, label, progress, maxVal): if maxVal < progress: progress = maxVal @@ -594,6 +608,8 @@ def identify(self): self.board_rev = self.__getInfo(uploader.INFO_BOARD_REV) self.fw_maxsize = self.__getInfo(uploader.INFO_FLASH_SIZE) + self.version = self.__getVersion() + # upload the firmware def upload(self, fw_list, force=False, boot_delay=None, boot_check=False, force_erase=False): self.force_erase = force_erase @@ -625,6 +641,8 @@ def upload(self, fw_list, force=False, boot_delay=None, boot_check=False, force_ print("Loaded firmware for board id: %s,%s size: %d bytes (%.2f%%) " % (fw.property('board_id'), fw.property('board_revision'), fw.property('image_size'), percent)) print() + print(f"Bootloader version: {self.version}") + # Make sure we are doing the right thing start = _time() if self.board_type != fw.property('board_id'): diff --git a/platforms/nuttx/src/bootloader/common/CMakeLists.txt b/platforms/nuttx/src/bootloader/common/CMakeLists.txt index 7ba4af38266d..e61fb88b8979 100644 --- a/platforms/nuttx/src/bootloader/common/CMakeLists.txt +++ b/platforms/nuttx/src/bootloader/common/CMakeLists.txt @@ -37,6 +37,10 @@ add_library(bootloader crypto.c ) +target_compile_definitions(bootloader + PRIVATE BOOTLOADER_VERSION="PX4BLv${PX4_VERSION_MAJOR}.${PX4_VERSION_MINOR}.${PX4_VERSION_PATCH}g${PX4_GIT_HASH}" +) + target_link_libraries(bootloader PRIVATE arch_bootloader diff --git a/platforms/nuttx/src/bootloader/common/bl.c b/platforms/nuttx/src/bootloader/common/bl.c index e1dcfe8c5b8f..4b4162d4b124 100644 --- a/platforms/nuttx/src/bootloader/common/bl.c +++ b/platforms/nuttx/src/bootloader/common/bl.c @@ -80,7 +80,7 @@ // RESET finalise flash programming, reset chip and starts application // -#define BL_PROTOCOL_VERSION 5 // The revision of the bootloader protocol +#define BL_PROTOCOL_REVISION 5 // The revision of the bootloader protocol //* Next revision needs to update // protocol bytes @@ -106,6 +106,7 @@ #define PROTO_GET_CHIP 0x2c // read chip version (MCU IDCODE) #define PROTO_SET_DELAY 0x2d // set minimum boot delay #define PROTO_GET_CHIP_DES 0x2e // read chip version In ASCII +#define PROTO_GET_VERSION 0x2f // read version #define PROTO_BOOT 0x30 // boot the application #define PROTO_DEBUG 0x31 // emit debug information - format not defined #define PROTO_SET_BAUD 0x33 // set baud rate on uart @@ -143,7 +144,8 @@ #define STATE_PROTO_GET_SN 0x40 // Have Seen read a word from UDID area ( Serial) at the given address #define STATE_PROTO_GET_CHIP 0x80 // Have Seen read chip version (MCU IDCODE) #define STATE_PROTO_GET_CHIP_DES 0x100 // Have Seen read chip version In ASCII -#define STATE_PROTO_BOOT 0x200 // Have Seen boot the application +#define STATE_PROTO_GET_VERSION 0x200 // Have Seen get version +#define STATE_PROTO_BOOT 0x400 // Have Seen boot the application #if defined(TARGET_HW_PX4_PIO_V1) #define STATE_ALLOWS_ERASE (STATE_PROTO_GET_SYNC) @@ -158,6 +160,18 @@ static uint8_t bl_type; static uint8_t last_input; +int get_version(int n, uint8_t *version_str) +{ + int len = strlen(BOOTLOADER_VERSION); + + if (len > n) { + len = n; + } + + strncpy((char *)version_str, BOOTLOADER_VERSION, n); + return len; +} + inline void cinit(void *config, uint8_t interface) { #if INTERFACE_USB @@ -258,7 +272,7 @@ inline void cout(uint8_t *buf, unsigned len) #endif -static const uint32_t bl_proto_rev = BL_PROTOCOL_VERSION; // value returned by PROTO_DEVICE_BL_REV +static const uint32_t bl_proto_rev = BL_PROTOCOL_REVISION; // value returned by PROTO_DEVICE_BL_REV static unsigned head, tail; static uint8_t rx_buf[256] USB_DATA_ALIGN; @@ -973,7 +987,7 @@ bootloader(unsigned timeout) // read the chip description // // command: GET_CHIP_DES/EOC - // reply: /INSYNC/OK + // reply: /INSYNC/OK case PROTO_GET_CHIP_DES: { uint8_t buffer[MAX_DES_LENGTH]; unsigned len = MAX_DES_LENGTH; @@ -990,6 +1004,25 @@ bootloader(unsigned timeout) } break; + // read the bootloader version (not to be confused with protocol revision) + // + // command: GET_VERSION/EOC + // reply: /INSYNC/OK + case PROTO_GET_VERSION: { + uint8_t buffer[MAX_VERSION_LENGTH]; + + // expect EOC + if (!wait_for_eoc(2)) { + goto cmd_bad; + } + + int len = get_version(sizeof(buffer), buffer); + cout_word(len); + cout(buffer, len); + SET_BL_STATE(STATE_PROTO_GET_VERSION); + } + break; + #ifdef BOOT_DELAY_ADDRESS case PROTO_SET_DELAY: { @@ -1107,4 +1140,4 @@ bootloader(unsigned timeout) continue; #endif } -} +} \ No newline at end of file diff --git a/platforms/nuttx/src/bootloader/common/bl.h b/platforms/nuttx/src/bootloader/common/bl.h index a39e7ce9086f..377164a28ec9 100644 --- a/platforms/nuttx/src/bootloader/common/bl.h +++ b/platforms/nuttx/src/bootloader/common/bl.h @@ -96,6 +96,7 @@ extern int buf_get(void); #endif #define MAX_DES_LENGTH 20 +#define MAX_VERSION_LENGTH 32 #define arraySize(a) (sizeof((a))/sizeof(((a)[0]))) extern void led_on(unsigned led); @@ -123,6 +124,8 @@ extern uint32_t get_mcu_id(void); int get_mcu_desc(int max, uint8_t *revstr); extern int check_silicon(void); +int get_version(int max, uint8_t *version_str); + /***************************************************************************** * Interface in/output. */ @@ -135,4 +138,4 @@ extern void cout(uint8_t *buf, unsigned len); #if !defined(APP_VECTOR_OFFSET) # define APP_VECTOR_OFFSET 0 #endif -#define APP_VECTOR_OFFSET_WORDS (APP_VECTOR_OFFSET/sizeof(uint32_t)) +#define APP_VECTOR_OFFSET_WORDS (APP_VECTOR_OFFSET/sizeof(uint32_t)) \ No newline at end of file diff --git a/platforms/nuttx/src/px4/common/CMakeLists.txt b/platforms/nuttx/src/px4/common/CMakeLists.txt index c74810b03a88..f6c25c26f320 100644 --- a/platforms/nuttx/src/px4/common/CMakeLists.txt +++ b/platforms/nuttx/src/px4/common/CMakeLists.txt @@ -83,4 +83,4 @@ add_subdirectory(srgbled) if (DEFINED PX4_CRYPTO) add_library(px4_random nuttx_random.c) target_link_libraries(px4_random PRIVATE nuttx_crypto) -endif() +endif() \ No newline at end of file From 8fe8f2fcb3e522e06a7ca4b21be3b5067c1b5b90 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 10 May 2024 12:25:01 +1200 Subject: [PATCH 29/34] px_uploader.py: clean up various tidbits Includes: - Remove some of the outdated Python2 checks and compatibility. - Try not catch all exceptions but only the expected ones. Otherwise, this makes it really hard to debug if anything unexpected actually goes wrong. - Make use of fstrings. - Make output slightly prettier. Signed-off-by: Julian Oes --- Tools/px_uploader.py | 86 +++++++++++++++++++++----------------------- 1 file changed, 40 insertions(+), 46 deletions(-) diff --git a/Tools/px_uploader.py b/Tools/px_uploader.py index ce1b3cda5c0b..b46ea178cf2d 100755 --- a/Tools/px_uploader.py +++ b/Tools/px_uploader.py @@ -50,9 +50,6 @@ # Currently only used for informational purposes. # -# for python2.7 compatibility -from __future__ import print_function - import sys import argparse import binascii @@ -70,35 +67,32 @@ try: import serial except ImportError as e: - print("Failed to import serial: " + str(e)) + print(f"Failed to import serial: {e}") print("") print("You may need to install it using:") - print(" pip3 install --user pyserial") + print(" python -m pip install pyserial") print("") sys.exit(1) -# Define time to use time.time() by default -def _time(): - return time.time() - # Detect python version if sys.version_info[0] < 3: - runningPython3 = False -else: - runningPython3 = True - if sys.version_info[1] >=3: - # redefine to use monotonic time when available - def _time(): - try: - return time.monotonic() - except Exception: - return time.time() + raise RuntimeError("Python 2 is not supported. Please try again using Python 3.") + sys.exit(1) + + +# Use monotonic time where available +def _time(): + try: + return time.monotonic() + except Exception: + return time.time() class FirmwareNotSuitableException(Exception): def __init__(self, message): super(FirmwareNotSuitableException, self).__init__(message) + class firmware(object): '''Loads a firmware file''' @@ -163,13 +157,13 @@ def __crc32(self, bytes, state): def crc(self, padlen): state = self.__crc32(self.image, int(0)) - for i in range(len(self.image), (padlen - 1), 4): + for _ in range(len(self.image), (padlen - 1), 4): state = self.__crc32(self.crcpad, state) return state -class uploader(object): - '''Uploads a firmware file to the PX FMU bootloader''' +class uploader: + '''Uploads a firmware file to the PX4 bootloader''' # protocol bytes INSYNC = b'\x12' @@ -361,19 +355,22 @@ def __determineInterface(self): self.port.baudrate = self.baudrate_bootloader * 2.33 except NotImplementedError as e: # This error can occur because pySerial on Windows does not support odd baudrates - print(str(e) + " -> could not check for FTDI device, assuming USB connection") + print(f"{e} -> could not check for FTDI device, assuming USB connection") return self.__send(uploader.GET_SYNC + uploader.EOC) try: self.__getSync(False) - except: + except RuntimeError: # if it fails we are on a real serial port - only leave this enabled on Windows if sys.platform.startswith('win'): self.ackWindowedMode = True finally: - self.port.baudrate = self.baudrate_bootloader + try: + self.port.baudrate = self.baudrate_bootloader + except Exception: + pass # send the GET_DEVICE command and wait for an info parameter def __getInfo(self, param): @@ -423,8 +420,7 @@ def __getVersion(self): except RuntimeError: # Bootloader doesn't support version call return "unknown" - pieces = value.split(b".") - return pieces + return value.decode() def __drawProgressBar(self, label, progress, maxVal): if maxVal < progress: @@ -437,7 +433,7 @@ def __drawProgressBar(self, label, progress, maxVal): # send the CHIP_ERASE command and wait for the bootloader to become ready def __erase(self, label): - print("Windowed mode: %s" % self.ackWindowedMode) + print(f"Windowed mode: {self.ackWindowedMode}") print("\n", end='') if self.force_erase: @@ -672,14 +668,14 @@ def upload(self, fw_list, force=False, boot_delay=None, boot_check=False, force_ self.otp_coa = self.otp[32:160] # show user: try: - print("sn: ", end='') + print("Sn: ", end='') for byte in range(0, 12, 4): x = self.__getSN(byte) x = x[::-1] # reverse the bytes self.sn = self.sn + x print(binascii.hexlify(x).decode('Latin-1'), end='') # show user print('') - print("chip: %08x" % self.__getCHIP()) + print("Chip: %08x" % self.__getCHIP()) otp_id = self.otp_id.decode('Latin-1') if ("PX4" in otp_id): @@ -689,17 +685,19 @@ def upload(self, fw_list, force=False, boot_delay=None, boot_check=False, force_ print("OTP pid: " + binascii.hexlify(self.otp_pid).decode('Latin-1')) print("OTP coa: " + binascii.b2a_base64(self.otp_coa).decode('Latin-1')) - except Exception: + except Exception as e: # ignore bad character encodings + print(f"Exception ignored: {e}") pass # Silicon errata check was added in v5 if (self.bl_rev >= 5): des = self.__getCHIPDes() if (len(des) == 2): - print("family: %s" % des[0]) - print("revision: %s" % des[1]) - print("flash: %d bytes" % self.fw_maxsize) + family, revision = des + print(f"Family: {family.decode()}") + print(f"Revision: {revision.decode()}") + print(f"Flash: {self.fw_maxsize} bytes") # Prevent uploads where the maximum image size of the board config is smaller than the flash # of the board. This is a hint the user chose the wrong config and will lack features @@ -710,8 +708,7 @@ def upload(self, fw_list, force=False, boot_delay=None, boot_check=False, force_ # https://github.com/PX4/Firmware/blob/master/src/drivers/boards/common/stm32/board_mcu_version.c#L125-L144 if self.fw_maxsize > fw.property('image_maxsize') and not force: - raise RuntimeError("Board can accept larger flash images (%u bytes) than board config (%u bytes). Please use the correct board configuration to avoid lacking critical functionality." - % (self.fw_maxsize, fw.property('image_maxsize'))) + raise RuntimeError(f"Board can accept larger flash images ({self.fw_maxsize} bytes) than board config ({fw.property('image_maxsize')} bytes). Please use the correct board configuration to avoid lacking critical functionality.") else: # If we're still on bootloader v4 on a Pixhawk, we don't know if we # have the silicon errata and therefore need to flash px4_fmu-v2 @@ -812,10 +809,6 @@ def send_reboot(self, use_protocol_splitter_format=False): def main(): - # Python2 is EOL - if not runningPython3: - raise RuntimeError("Python 2 is not supported. Please try again using Python 3.") - # Parse commandline arguments parser = argparse.ArgumentParser(description="Firmware uploader for the PX autopilot system.") parser.add_argument('--port', action="store", required=True, help="Comma-separated list of serial port(s) to which the FMU may be attached") @@ -900,9 +893,10 @@ def main(): # Windows, don't open POSIX ports if "/" not in port: up = uploader(port, args.baud_bootloader, baud_flightstack) - except Exception: + except Exception as e: # open failed, rate-limit our attempts time.sleep(0.05) + print(f"Exception ignored: {e}") # and loop to the next port continue @@ -917,10 +911,10 @@ def main(): up.identify() found_bootloader = True print() - print("Found board id: %s,%s bootloader version: %s on %s" % (up.board_type, up.board_rev, up.bl_rev, port)) + print(f"Found board id: {up.board_type},{up.board_rev} bootloader protocol revision {up.bl_rev} on {port}") break - except Exception: + except RuntimeError or serial.SerialException: if not up.send_reboot(args.use_protocol_splitter_format): break @@ -945,9 +939,9 @@ def main(): # if we made this far without raising exceptions, the upload was successful successful = True - except RuntimeError as ex: + except RuntimeError as e: # print the error - print("\nERROR: %s" % ex.args) + print(f"\n\nError: {e}") except FirmwareNotSuitableException: unsuitable_board = True @@ -986,4 +980,4 @@ def main(): if __name__ == '__main__': main() -# vim: tabstop=4 expandtab shiftwidth=4 softtabstop=4 +# vim: tabstop=4 expandtab shiftwidth=4 softtabstop=4 \ No newline at end of file From 6ebb2b33dfcb2fc8dd6cfd6e900f1a6618245980 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 17 May 2024 15:18:44 +1200 Subject: [PATCH 30/34] bootloader: track ArduPilot protocol Just so we don't conflict on these commands in the future. --- platforms/nuttx/src/bootloader/common/bl.c | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/platforms/nuttx/src/bootloader/common/bl.c b/platforms/nuttx/src/bootloader/common/bl.c index 4b4162d4b124..65f1e0f0417d 100644 --- a/platforms/nuttx/src/bootloader/common/bl.c +++ b/platforms/nuttx/src/bootloader/common/bl.c @@ -111,8 +111,12 @@ #define PROTO_DEBUG 0x31 // emit debug information - format not defined #define PROTO_SET_BAUD 0x33 // set baud rate on uart -#define PROTO_RESERVED_0X36 0x36 // Reserved -#define PROTO_RESERVED_0X37 0x37 // Reserved +// Reserved for external flash programming +// #define PROTO_EXTF_ERASE 0x34 // Erase sectors from external flash +// #define PROTO_EXTF_PROG_MULTI 0x35 // write bytes at external flash program address and increment +// #define PROTO_EXTF_READ_MULTI 0x36 // read bytes at address and increment +// #define PROTO_EXTF_GET_CRC 0x37 // compute & return a CRC of data in external flash + #define PROTO_RESERVED_0X38 0x38 // Reserved #define PROTO_RESERVED_0X39 0x39 // Reserved #define PROTO_CHIP_FULL_ERASE 0x40 // Full erase, without any flash wear optimization From e4fd80b6ef0993fa9a7ad73308dc5c9c55b14a2f Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 17 May 2024 15:19:12 +1200 Subject: [PATCH 31/34] bootloader: remove unused/duplicate defines --- platforms/nuttx/src/bootloader/common/bl.c | 7 ------- 1 file changed, 7 deletions(-) diff --git a/platforms/nuttx/src/bootloader/common/bl.c b/platforms/nuttx/src/bootloader/common/bl.c index 65f1e0f0417d..1b86adbde350 100644 --- a/platforms/nuttx/src/bootloader/common/bl.c +++ b/platforms/nuttx/src/bootloader/common/bl.c @@ -131,13 +131,6 @@ #define PROTO_DEVICE_FW_SIZE 4 // size of flashable area #define PROTO_DEVICE_VEC_AREA 5 // contents of reserved vectors 7-10 -#define STATE_PROTO_OK 0x10 // INSYNC/OK - 'ok' response -#define STATE_PROTO_FAILED 0x11 // INSYNC/FAILED - 'fail' response -#define STATE_PROTO_INVALID 0x13 // INSYNC/INVALID - 'invalid' response for bad commands -#define STATE_PROTO_BAD_SILICON_REV 0x14 // On the F4 series there is an issue with < Rev 3 silicon -#define STATE_PROTO_RESERVED_0X15 0x15 // Reserved - - // State #define STATE_PROTO_GET_SYNC 0x1 // Have Seen NOP for re-establishing sync #define STATE_PROTO_GET_DEVICE 0x2 // Have Seen get device ID bytes From 5bace785e02d3ce3fa151676f6b175e3a2acb670 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 17 May 2024 15:41:12 +1200 Subject: [PATCH 32/34] px_uploader: catch serial exception correctly Signed-off-by: Julian Oes --- Tools/px_uploader.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Tools/px_uploader.py b/Tools/px_uploader.py index b46ea178cf2d..0ab3a6ff258d 100755 --- a/Tools/px_uploader.py +++ b/Tools/px_uploader.py @@ -914,7 +914,7 @@ def main(): print(f"Found board id: {up.board_type},{up.board_rev} bootloader protocol revision {up.bl_rev} on {port}") break - except RuntimeError or serial.SerialException: + except (RuntimeError, serial.SerialException): if not up.send_reboot(args.use_protocol_splitter_format): break @@ -980,4 +980,4 @@ def main(): if __name__ == '__main__': main() -# vim: tabstop=4 expandtab shiftwidth=4 softtabstop=4 \ No newline at end of file +# vim: tabstop=4 expandtab shiftwidth=4 softtabstop=4 From a9962dc44dabf7c35fd0364b45bb9ece672d9068 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 10 May 2024 13:29:12 +1200 Subject: [PATCH 33/34] boards: update all bootloaders --- .../fmu-v6x/extras/ark_fmu-v6x_bootloader.bin | Bin 46204 -> 46360 bytes .../cuav/nora/extras/cuav_nora_bootloader.bin | Bin 43248 -> 43264 bytes .../x7pro/extras/cuav_x7pro_bootloader.bin | Bin 43248 -> 43264 bytes .../cubepilot_cubeorange_bootloader.bin | Bin 43176 -> 43200 bytes .../extras/holybro_durandal-v1_bootloader.bin | Bin 43260 -> 43284 bytes .../extras/holybro_kakuteh7_bootloader.bin | Bin 41868 -> 41876 bytes .../extras/matek_h743-mini_bootloader.bin | Bin 42640 -> 42672 bytes .../extras/matek_h743-slim_bootloader.bin | Bin 43224 -> 43264 bytes .../h743/extras/matek_h743_bootloader.bin | Bin 42640 -> 42672 bytes .../fc-v2/extras/modalai_fc-v2_bootloader.bin | Bin 43252 -> 43284 bytes .../mro_ctrl-zero-classic_bootloader.bin | Bin 43204 -> 43244 bytes .../mro_ctrl-zero-h7-oem_bootloader.bin | Bin 43200 -> 43232 bytes .../extras/mro_ctrl-zero-h7_bootloader.bin | Bin 43180 -> 43212 bytes .../extras/mro_pixracerpro_bootloader.bin | Bin 43180 -> 43196 bytes .../fmu-v6c/extras/px4_fmu-v6c_bootloader.bin | Bin 46040 -> 46100 bytes .../fmu-v6u/extras/px4_fmu-v6u_bootloader.bin | Bin 43232 -> 43264 bytes .../fmu-v6x/extras/px4_fmu-v6x_bootloader.bin | Bin 46688 -> 46764 bytes 17 files changed, 0 insertions(+), 0 deletions(-) diff --git a/boards/ark/fmu-v6x/extras/ark_fmu-v6x_bootloader.bin b/boards/ark/fmu-v6x/extras/ark_fmu-v6x_bootloader.bin index f4ec9666cc17bc27660ae6490a108594c5085fa5..62ef9238b1061e35a5c6535077ed20491e59bab0 100755 GIT binary patch delta 8641 zcmb7pd0Z67ws2MV%+PEyfXEIr3?qXhI&6wD=&&^)Cg2WH!x%M=3Q9CavfKx_8)H;T zuPFMi32HFW2#nk(F^DFb#N_4%3|<%FRi81V(Zoj4?pgagJ(#@r$M?^h-|x(+uCw&1 zQ>Ustd!H*GxR8{#%&9Im&`CQJ$ zk=_1TV{hBj3svj{lZ^XbNG-xg%xvn5Q6@^Gufklh^ZGr6X|B^P)1;bG%~+pz-C(Xo zG9$l)Prk;bQQWiL>pow5SNWja+X)uQY~U9C-sIY^!W z^9d3ja2$7$3jwR~5t5~xhJPTtl;>J1TF|upmeohc|Y*nYMe@S!247@ zp3V1|R1`PYEn`b1s+>v)eKBE`iVaJXIPQptfWrtJlb>-Id?( zB*li}FG*hP3wRMBvFStF#hV?B3xx?P{Ge_6n8*e2h*nO2m`$ri5Qzo zO%_Q@@Tdfe+YJ%-xgUx@2awS&V^RNPxeg4OEtYi1`lox^GstF@);C+!b*R#$Awzhm zX5p_$pn5dENwU-v@n1-tIx%3j_*PT!Nm(*%~x`@-5bl;J`_8^s9 zij1{4VPZ1cu!?RmbOwMK$>fFMp-JU73{h2>?FButu3xMQ zz>zK$``=d7bysrsQN+v!*Z^>z>=+)3H<2U56DV}da&h=)7%+KXH^v(sLk!cd;9AM| zy0J?N-7+p8AkXbz6lMuPis#!EY~Txc$7r*H3v}W=;D1)+hk;hm*Q($mon%=ei+R$X zSccyr0V76ha$SfkaZ0K%H=*kQY@82IAN%)(G-(=rCTl^_2V~xe@%U}Bf5cKM#9{H# z2VuO)5h&=p6mEgI0#zp4rPamm2odP z{)mjK_Pk{f(Ze^iT#`6yxEqec3oZ%U4fu%Ep-aW2X(>fC6>{QL^!+`04C2}xsq6?= zR_GDnIvk3YDwt%WED&{$LdCrL8D*6 z*<{t|!m>>JIbj{r!St+g_gdEp|DpU9_O=jo#Hwu1UA9x$gk1b7CyJ9=fvmLlUHq0V z@j(U*UQsxL-R0p}Bg)vYj=}ax*u643_mB`nVv;l+PWvCz5f%~Fg;mNEHC>O^leuK zn>Cz29c=0qb|R6lck~JkfZqqa4>7GGzZqK1hH2nE$%aypk?;_^6aYsJy}|(xO`6zA zK$9>cjmi4N%%Z*7vYukDHhX-5i?0Kkr2jR*lKx7-gZjD!+1x28{v zmL!!Ya;l@^Y0itHi)0Qeb*>;QYBY!CzeChxB17H*DWJyzot~D1C;eC|QKpOu#qU@a zkNJf1IckHWs8f7U)h;Clmb7s!#wFzK=hS$jW&d+}jE`6@j9*IQ$CmVozBu_cBVzPf zh^Yg-_8C@ZBWB?M!lfq@lB9R^&-ZR-jtmS&5& zD8FpM6p7hvlRNH<*Qr$~&d)&&jY@raLHI&hf3 zw`MWY<360p_h=U9aG2K2n^`nta@^vJUicCoZ||X1NbBJDxSN(LhN^M~YEvzb3d3+L z+l7o&sqaw+`2qNR>Wx|;xKx2Cekb6oB(Z1_{s-An)QJN~@#He!u_Ds>_36M%7l~!E z7B^Y0PVU40Ke-1pQl{O(vzD_jhF~}nFBix9jt_@O&~jR&W4x}3`~$*I)o7;+ns>2&2uvQ(k!Fpg^R~&!*MjMCFi;5w zenTcsiwtabVFTTL+l+yp(FyM(OQ$7!kDZ2?(EvY^L(^8{6cRl>2ltYB)5j0l)QT7h z;64GEd^~*=erUNmU4!vl;+iqrx4F)TyFpLW8@UT){!Fzz%~{Jfkj*m_a4Kn?xf!3d zjGy%Z_U`=@G5-MQCU;5`a3=9DORP!m*)PN!t}2o)ecO+GlGJ*$j%~;{s6XrX4$%HI z_#_*nH~aJ(@P}5sSI6QplkzrodG}{fQf9of%b;G8TW;TM+td{#1V=UGe{H>~z`c0P zSJqK#NcYAxJDc0-LS{YclgzR`J5uYQcUWyIf-}{QZ@sdV9qs#dCOfoncKdY>Mu5vNil#~fkys>k39k>BFHNOsIl4L*5?(Oj_Rve{M*`z<>Q z{%4TOvnNi8>(-kM9@`@ZYKxUUc+6S$gS^C_n(xcdfxMGlNTtY~dgBO4ZdK*`KXhj}&youXMl-vT#m<<{#GiF+)Dqu~Y49AN|y(HwOt} z;M)tIo?OI=AM_yIA4MIyc`pLTSWZ^zcRLjMfH1FpE#sp z1pFP%T_#yC7yC3HN6bwK1JiM`_hlnaCVej_WKg-{Hez zw#rO#AG&2RcdtFNN@w<2n*nCvML}AR5~q~j{fm^BC*yLmqg)+)9w-CXz6Vb|$ErQj z<>Y*MtTx^CcyUqg<9WY(7NMcT&71#t8zf{oiyy#Jm+AO%dK@ts~>S9=`@An8gj`L8}rbCbWi)JA{_U- zH6$3tM}@)Z)Xq#c!3{f5AVKq%1W$3KR%5-qClPjp&bw8h;3U~LPd{45MG7=$6-9oP zNOS!F?V^-|j1VL~r4iDVlaN6oiV;Q3q>+2`k{}BWeMMVyv}juk(t5EsgqAhYRrIba z0s|M#cf}jRi4Ox>zZFmwQ0l>HW4;xblFb4t!73TILP%)6CLjaSBW}?eq!RfoQMO&y zi1d&8B>GfA)~FsItG{~%e>hdpaHuO}J{)`i0SgdQ{>qIm@}gT3r|272nYz5-sptPO{J&hlS);T% zR+dh46{1Y7*sf?6`Md6sNdrB1tXM1QKJU?eu8wY`Ihv;R#v1N)9o7_c$d^)qa}7|w zfXRy%OX03PO3G4CdHSJl@|g%zV`$1&U!fZzC*fo?@Ed6Y(_(ynQgC%}$Hbz@>foxZ zM?o~DRy3o8V?r35C(Z5zE7G2^ma>VgZ$I{>IY#^eVwL71L~N)ra#QMLX+72yux_5m z3vbkga5QD)R@CXk;gw2AM;=wwwLht?L66LJH-vpHW$een6w-%*XAD04(XBn#L$zil8?W?hk``j;D#t^K)N%Ja_Ru@!8LoafPHbwzpQ-% zQc6~R3kNODeea$v$n@K@jT{B$U9n2e(|KN&P=~amS>sJOU9opA9*-x z>5U$absmnjwTdG{VMKbUugKK$?Q#e?;!0$t(Ay^Q57e$)?%}Th{-xcjxXi*(t)kh@ ze+7DBSi402Z4ZBq$glPYpp~FX{ClM6RWwuTL59(;1*!n4KvFF78#|>%6G=zvy?c^b1Y_Oc?$0NNh3SxnSBZS<1HNyLx&A(7(qPcEDFVYSZJ2E=Y zLD3-%LdFlm$pF|%kqL{2QGjMH8Zq}r8;~_Nz97h31sx`l8TDTWwUM znl-bUfs-q9I0H=)H~*b$2_%F%GtI4q!;1kYR2kj;x{l(3TWRta`e04nf@OiaB-FETNUvpV?6n2iZr);-Jv%LFE|~P27e@UKw=|{` zX^IE>R#1f$RAzqv40XkW((o3tV(|goMuL}2!JEm#C9AQXTwijF`pHhtES)JGAr<*} z2`R5w>i-`$4BJ2TlWMVpA4M)#MB^;-q(YBp6Ln>5yqy=s0@lvw+y8s3=KTUTs4cQ> zZ+1-AN*ExfqjT*1U6CxPG|24yKSk0|nH~I3n=B@x?|wDSiFk{p1Z11YZi zsc@5YkIP5>Dn`Z*VU0k|A^pp;V7#fzHCRbzEw5SN;(rnctCb_6D)6so?J#I}izqIG zmGws{0$CS-0iF!3)H?T!CkA*SfiJn5s`af>LLG&gs_Zed|TAO!L7K8$7`w#V6EEHzoMAJ z49QxRPhGZ?cUP6*H%Q;AN~l{GzVQ+D#6}*y@gd%0*|pjiQ#b77!|D{D_Em_vT!WZ# zb>!dGzu?Q3^KXh6uO;W-UXAle<~v35kL*XRKa#EQ+`+>vEB}%};a5mw%|jeRw$v_y z`^w|mv3N1j*J-E$Cn>3m1F4mD%gsO7rRa0>H(~#mO24oI_y*^v);YNMYTm4Ap#^}%ykm^bIE5-=kIfcj5b+7=t{K#t?L#Z1! z^6thla058IaTest;hWatg=GJx-3n=`D_hBPoBtC&4_w{c33ly%HwOqyR) z#kiOp+p;)1!Zx_XrOHI>ldKx1{Y$gFr_8JbA6App_g=tdr0%^V!`v`eRh?kFf#A`d8ye@lmEuz z)t}~5!V3H}n>>bw;BoN7-T$^;7F5Z!CCXI7el4i71U?SZQ76CO^5p%c7|$p3wok#& z5zF@Ez#=FZA(d1;R=~$38!Y1|+mm4#C+s*B^MlRCmkW}Yc>W{s&s8mAs-Q~l$MSr! zDAil)>xU*5ijZb^qLGiURVUQDCy<$V64^x(A%40@5qv@N-8njOj>}*yw{H^g_5-cBndkS47*ckg z&lRIvbIf|vTJutq;!U16k@-6_lNLKQ((y5=0A9BXCPksP@ga8Ui4k`SbCgIEo7l7< z@Ja@Fw~c(iGm>)H$gewN!sqUk3eGY%FHBXweyJsF)i&BlLC)VmVALO&1caPTKd z@vhM5QpZez+4o(Z-xb-#mmn21LKGhs(f~X7Wn}HH9Z(z$`DGAav1r_r=bf|{F|IvQ4dULONO>hZ z{Ybp`Rt8o%vBAMlgU?#ZR=mf-=UO)IZNd>&rz}R%H-b%OaRcN?&la$Qw+ke9U#Wiv zY)aCX7(W>2EX$F7Ub31VJLKo{^Pmi0nFS5L zLg-C_4B%-G`R0Rf!2dfw)Zh-%{-N|`>C%U>q1)`W97bo`6!5W(fe7ExAukYMsrxn+ zr@mzy1?|gQTYKULzelG3#7$!{c&N=_eTSd@~UoSvTiO6tNiM9jzIQw}W#d4NGn z5IXj(y|Mx^nJW>~u>{_~Y>6pY2FXv7kvbJIS@3aiE8rOb>j5Mt>G%Jmk^UB~?_-{J6{cWx$lo}f4`dQ?W*ps zuCA`GuCDos>b_6at)m0pr%@t8C{d`hZ>1-xF>8O|zl#pzjv^Lul?6!4@>nQ2s}cs0 z?ZMe29=V4Var_@FjPMUB!;Ftu`HUB1ER@briG||s+Yb)lG%M5 zv4cc~%?Q5ZWjZ)M(c0;xg}Y=;SPI@uPK2f7cJh5#1fEV@VLCjP#D=HgVZDRxXsqkq7EktUyJ!owYxX;Sb&mVOrV?JYl@=zFP5mQqI62h66tl$BKM9+OHX;QNw3{Qc zG5(Njj9dxR42&9v4J12iN?^LTkY6jkZ=!`nawsZ2B+$$7b$LZR&MblHb`WP&G8Rb4 zfTYCR-PJta!SVi`*q;^}y2s{Sb1oKMMs4s7MAx0ApCXpn#zd0J0cCg#xjaBiVGsFv z!2V%j62qUXN5V*tDvr4Y$`{4^BW@rZWJcBwC0gm!k87 z=k-u@9;MAW5)rcyuP19_oVXuZ80)}=#1Qw%>_t8mUs#ViEq^?c;8bl{cb6FFjw zg`F~p93Ppfa5&`yz+nQ87oTyMR47^VV)7D>*Yt4w^LLKXBrQGy zUn2SOMEEDsu+w;3nhi zBvd;DPbJyfF);sXZA!>I`IiR8VmLkvdYwv|w9$A0Y13*A*)q;#hXtno)PgvbVi>EZ z!n$NNs`xArsim9YjrEG2DM29Ggm}f+6UCDvMt-FnyZiL(Uc$s!|?lJO}rBWZlX?QXZT1H6ICOjT(bOQoS2 z1~hQL8|ie*l+D_4lw40*6rAhD99?I0gn$^M$+&?LX(=uYW>u8q2Q>!ok4`n|^B(Y)5o>G=6&D0~BH9}<;uu^T09lh&co9;JB2 zZOvJr6m`)c{zItsitoz|AKBDf{tLLCEXNv>VoXU>L|}gxA#y-uGv+i7P2*PSq%oY& zsMo*5y0mx$B2 zxV+U3dg8*YIw6=2v$RUvkSy+ov1$O<0N#z*dRZh;I%X`b?^VYfXrst9z^zQa&e$sL z>7gmhItgeB4k9Pg4F$R8ojFWPv0%%|F7%2UfTr~SCSaxiWq^D8e;rDjxowh7Q)<<9 ztt|Dg&+S5`r4~J})MpUwP%SPaxkI&8hwEYWRY;iaQryTzWp&};zUo6-1$%tJk8D6; zjb3pC^m+_M+L18U1@%UhgpVX&d5@^AXF3rU+d{Y)#U?by(M_`+M?(k13eAFH~axMlpx$HSD9&O+8oB`uQ_DiGY z)40=~J|+;SFEt@{NH${E0ABkHC*>fv;u*XKcoRS{&=uHdUug2D!Pzd$O~#0Pk~|6VyEUuT=nv1)- zUPszU;5zPlr-Ch{T&~(C ztuW;Y8fHP|-y3lHDru@|j!?z;rL2+)O$(MUeu9CrPkN#9ZVO6?Nj6m_wKQCi5@%kJ zj5sD^wZw(4mV!e4JQT)5w@9P2{RSybs-aXX^%;L38qF$N%5{rp+(=K~a@?0pvY6gH zeXLD4eO#^Ot~FOM(RVF0=MfM4bQQ>e+wo|z1?zM(Cz&UXO{lo;huiQdcMHv-B#-!! zPhH$)%LwP}zZON}_`GIhqRIk~u_y>2;4^=edK^N;P?V?ve48Yh=Rwr5(d>Zp(LA<1 zaF~qrLG60b(lv5oY!cpUZyVc=gKznIBTTl@Bj(v1FZRQRKl(Te;*`@GUD-KmOil_N9Dwz&Z?D>)tcno=Md>GzD){I{mcL&B) zCeFgdCw$2|vKny$_;qcjQ5Gd1(M-sKL!fBFs3|ME?>aRw0LOd8HfZE-*EqVxlMc2K zX^RCp11GRXT%Bu?K~w+jvdh6bDxno4q)RIPuC*qo?=_~ARU4s~2APiYyCsW1kUJA} z1%hb7+PgHKnhY?n(kj*ir4~xyJTbOGCYu|Cg$Q2QZ#W?pZj%)RRC@gfXUX0 zgYiTA`H4D=%gMc$rUV|W4iN6pr3RDmH)5WoRT;Z&{72-qNy&H!*)eH7K55rY-i!T9 zK0|CFz*us%EE!_q-^x;AhqQbwB^qz44Q*FCQ9zp3VAb^tTk-I(oP)suQp0NsE;tR^RwqtB+8GdVx#1hK zrCb})_#+-;uyVjrQ*bJO|3g3Z({CO*yU68oo!_z+`)}OhS>#FinB?;|_E-S8JS1ee znCO2uM0MG!@HQlTVM`HkKwf^l`#rbqv7MB^9IrZV>vJ@LRK1*nFOVZI$4C6Rb(U&( zn@;sov+2pXbbwIQU}_-b&db#p0){Ek^atH-q-sh=*qM8*?y@tF&vokfD|{JzCy`52 z#uRI>8LY-083%OPibGoP@bmoMeEoNaA2Mi9{;6ifsq^yA;9YTf%kS;s|KJ?Zg=VNb zDYd~G-dv_#-qZ4)GyAcc9`F+#(m`IDnykC(oE_KasGgtTUj6vH27|S)6d6-faK+iH z4g7pfK@Rz3YC2eW%hVZo8%dvbiJ^rHGI39fi`pflPGe9xU&5oUJNSSEq+=!gH7#r+ z>C=k?xD$vigN3~D8F_EI3GP*2Pfy3+67Te=kym7Y9c=-F%#7?Ptr*o5z+=ABN(pm( zOx*ojkDbbaeaU46J-;X+eef-XQ;ExNk>VNY5Ij`R(1u+GO4qHcpr_|}ZBJ`0X`B(C zl;(X>Va|Ip^VgouWo+_^v;H$0L?F2pPvE$Ig}7#<`7d&HI63I`RWigf3Lhf#EwM?H zPARutDh0P7L3alC;MHd;3t&?U`5t9g!*!D!w?yD)`OSMNdkr|py(C;aN{7lsmJ zBEc6mvSTe4TDU9|YUZn9VV;cT*q~}jft~KSUkM$&L8@jNhS0({GA(=}%i>bNM*tQ= z#6}B0z_&Lj+0ncjsAkJ}YG zE77~Oqcn#5H}Jj*l1@O)4`v}&2ADS+v5NsegDTebtYZ5d#J)5av8w?t0EE5*jsdX3 z_$HK_fscZLbl~2Q;H;*0z@-ioWBlVzes@pE{NA6ZpPWC^%!1^gJ_+7ECguRc%%smPNIk zn%32FS%Z}6W;I1Izn0!`E4f%a8n9ZI4&(2bE6-Ur?P=F@}j)evE_XL{-pEo_!S zv&Pz-*c;R?h!zBf27VJ&ML?~lDKCUA4{Mrkj$R&CnfoiDvKe9`0D#6pIUF#YMu!<9i%;MbG6^Sa%KF@cG7^s1m>ODm&i9`ceCmyL{)hWJ zg}X|q>0$q$9`>!kzRJ%ed|+e2UN+ch;q~8}-t;OWn&@3WD&2n${BK;N1{yl^RE0cEqZfJ&hssIq}_E2NB&QNf#smJQ{G)jybUZH+TOmK^0V5-u?l(v`QRqq@wP{|$?%i>=g zidjd~(FXsPbRNMR-h-?FEo}6@n{)Ttb@2CnGydE4ILHG~89Q%)|7lln z5oe)=zmmoCk_L}Bo#ik=K%NOJwg6Vt2pGX?LaZ{Dvtr?jtV9wz3;3pHM3cYF8$<=V z$*=SJPgA%QZlxtgpzcVY0j)OTEkN1P*_$hqG_*9nfa2U6~8 zYahNJKedACjAKo_TU{m+<^9n%V|Nz8|)>}_NM&6sieZl>x-^O&6amNl^jUg z1EBzQaxBC5;gvyGkZFsv@o@6VVjZMAE-bE^;}gTB-ppSrBo+ERD@Q_^l~6(!&veG9 zLwTQw;h&KY<-KCJ+{+&aSN5ke(q;iQQ9@cHU{2EUde|b03c-G}v9Pvz{|R!iG7i_0 zOO^4M*zZ-UsL;*c+U16NC3KBJwUush9r3(AKD1ue!BMKd2|;V65u}}LpSGl!!a?Nt z(gG^PL!K@z!Jm6fH&U{3^s=wUHNA z{D|k<)8CLWZX)S#ErXoRk+;mM+wLRIdBpYBJzQqLvoe{&JBgp|5uQXu+dTX$nNd9g ze?qob>!?&OIa{58-z0ac7aK3RwY(Lk*a5CxNu#1fxOQ}Z=A4?x!3D(OR`G|yGF!o3 zeg?RBg1o(||LA>gD?~Y;f?Muk>D-TCktOBEapu)<67wp4UAHa|iXn!X~x5-l=C85eDJi2!I$2qE7 zS zMqno?Uz_H?8+@hTt#0w}WYgLxcnCPMHa5ZnA(V0-VNEdUGk6qT4ZEyaLvF8)pd#Gl z>Du9tQcqhq8Ftp1b*tgV<-dNrTG`;0b>!gsKSQ!V|2+rX>gf%+kjO9CFb|(4CpJ{z zwIu5Oir5LR-hB*dV@LgO*;Q=g1*@v1+^PXBoF<>VKMwCAzr25>|8R)9AQ53@ArW2% zX*mRYE>$MSHvSlu=(Ada3;+6ng0#vP5*(ngVT0fTdzO6qffmP*s~^nFcmuN3U)lXS zGXqL^NnGzz#nE5_9&x(wU(RnOE}gc=SW5W6NnExhmcdZn;vM_UP4h8~es%MB{5px> zk{((O`4q${=~Oj5uDD<`&fJoYvk2L8AWr3Wi62UemPGM3=;vmVVi+nuh!@2*vhpxN z7Hkam)Pkzpq#aC`;75rV;u5;ks>C=L@z{LaNd2UE!9 zt@H3)l1@hb;Q{2Je`(lLPgMn(l`OAE%<(C?Y^3G*q0r;Ep6@qskV>Ml;(R4hJgZO_ z3lyq!Ko0mQnS|dbcv}i~6T>z${u5cYZAi*iuhBHay-vcL_tfLVqIgZl5Dkms8**%Y zuGL^!ZJlpXuMowL$UnA?PMguKQ_hYT3SqdfVQZ+hF462({{2DTCQa2KU3^OIoX{It zpx`bt^22B<-AyKa7#Gz^lq4*}=SOnO+4^HSs3psRGhL!gHh!2qs`zZ*CXXn1B0H$g z2wEqE1iqY)9yi$bcCspuxY;vFVt0R?A9RDc{xY8e-Vg}~rA)vc@gRBh;TF(O^+%&4 zc#l#u%5ySj>$M}DES26fk%y%1qmj}5J=z}rKYQTDuOHK8J(12UJfe7>q--CDemnc!Ub9NlRMc^V^AsYIwZWBX+`qSn4s4ce00(AW8I2$hRH#i1Wy_ z8Z#~;M`~iJ=RD-AnhBJ~Lt=K6z|LB@<2ar`qIc%|AK!u4l>m21#m;EeFFmF8I~RtY z?Z!qA*bl>N>hTVktle){EgsO>&BUqO2l44Vu93w}G83nQ!_Ol=?;;m>mj%~=J5in{ zf?&e6_LPtPn5s}uv4CdhLq6A*DTx7|JWdk*JW86=mU&USk=YXzK#qoOWH=<8cBvs# z^+sj8wJaBs$}S{)>*~EjIhs(j5-KY9sy3*1K=Kd?`{3J4-_j)i9Af@PLWwy7rY-rixW}C) zWA}XpiK2eBI(PybSsRZZlJeU4h!(dE(uU_7)bMn~f@y!#q$-rezmiS0#TjQ^gQ48i z^Mx~8GoE5Pqtnx@x#;1;6L z7rKJYp)aJuAvgedUU6Y=FO&lOT9omx%|ShjRm&P#Nmz zjL#xF_Q$Jt!pa=0BVX?CUu6L;QgJG?sxYXT)na%#VyGw!qkSrxniQI*19d3pF)n;6 zjsUGI|4{fyQs50|3YO5QxU6xOu!;A_}IW*=ICmy+9uuEM$S>EW-T=VeFI@JRcC zBcIY$$I}t}z=+u2h9LGPKp4Pncv!iahS-r%9|aH!{~@W>^YcLc_W%z8et8Do5r|!w zh1dfCu_F=N2>3jJ(%?AI@F>L6Q16Ahp937kAa)>!nyW;91q6!j?Xlhuyu(; zM^+$qG(hiI2xUJj`z=6h%j<|8_bT+Tu$R8F5+qqbrq}g+m9@Dk}E(cf-pztZb|Bptt)F;_j o+9R-PY8|`~k{u`GspWO#^vSqBO;9lgnw2mJ{k4w#cyj3f0ytK_ZU6uP diff --git a/boards/cuav/nora/extras/cuav_nora_bootloader.bin b/boards/cuav/nora/extras/cuav_nora_bootloader.bin index 015f8e3c8523e81e2e2a1b90cf967a63b072369c..dbfe7cc7b3e85daa97f337810b5e5d1041cff223 100755 GIT binary patch delta 22154 zcmagG33yY*`Zzpu&Pj68HC=#oKS^3>n-Bn8y6 zsKCMd11idcogt;-2*$!XFy|94Wj_kREH_dQ>pXEJln zytBRY&dj^b5uKF%JayzUg{y^jN^eUnODw(||9N6$tX8C{9j4kAq(vGezSkd97W@Co z8D4_KwLT=q^&xS#7m3gHwRD%i+0woA&2q6rcR|`bMk`|K48#|tZFke##@vHJ;+cLV zhCsRR`%z25FqF*NFiK`1AcT_pKR|4C>6#z*V^32jRQfl%H_%{Up^OC7vlzm1rCYQsz3@Ct-P2zzWXCNl&&DhsU;s}UM&?S_- z6_Ga~sU}elO@yREH&abLMiVp_NN;9*t>XcbN!5BR9@4^&sfnEa+S% zd43k2pFIQV3sMEajLFnvhy03r&srP2$R2tD1w;T42>>Y&s4x;Li2Sb#0rqZXq7mRK zlBpxrMP$P2=qbI~hjAUAnC3z)$VgQdpVFX6qY+J{XvG)`<65=_Ar8$@HKt8P9M)ch zQf8Zo>9deXDLW&vnzNFMNiKto-2tcA+`p7#OE!cO^t!h6e$EJ37& zNrA-|oe2{MlNFtLFSokL|J(S+plKnz-WuE#&!<`NW+e7XX;!=)iED(73Jo{3h;w1# z5`xWzdTODbYM{5;Oj2I>PI1h}HWDzdq+IkH=2>YmoSqv`yYqDObLvpO!~}0N`J4no zT>?{@P%hfDfc6t$`9a_kX5y$)+HEn@y$j7IiHQ>cT2+R$s*+$X)`G+%UZf2xp*bWT z^g=D#^HTg|ooF+g#SZfqkQPVl$nY2ZjcvC7ggRi~V9_tABLpz^yArX@5TY9GI{eXM zp5gtTa$&kMN|>aK#uFix5Hd8vjLZvC>SWDN|#DN&!l?)Z(nRZ>QJUqS}q8&1_*2;77zL`^p%k?$2KAnN#x(=6LO2! znw>G#xC5p8oYh4HdAJyh^G=`^We5f9047?)@>rx!Fk)Eqq^VdpY1$?&AiXjVOnhMV{|!|94por zUNuyrhFPLSk* z_^^b~jlW?@d) zQv9*-byyPqQn(eC7QS0b<>g1Jn>qehD-xdq$>G;^oB+4Kci7!G<)a8fjN&5XhO-D9AJpgeL-v4p=;1Z;FJF)_ArU;k96H<0d zOk#VW~E^5WatMgzcKtzZ-)6vVLU+}Kopht{ zG0uNT$mnnQ)$$G0NZ@hZorYbKft$nA+{hIaoEVRHt3t{^A#NNJYyI4c?+Y>(N?PQCHFN~l(0;P9 z*7G}f1&@-4@g=-kTWz4l7ktJ1Yf`O|7N7F*@zYLb@KkOdFYj81vG_`#oG&s!g~3=PA0 z8>?qaz-&xSbvS4-&xZ{!Es+m_;tOcsU-W(Bh|pCvr;eyYNJdM+wP^8wR^vNZfuBiGMxm{|)JwQl`Wt z<*0DZ`+Bd_@8M6}gw|mBJQ-yQeF#>X-*d=M3YH5^Q3<#}_*Yau&Jkjw)5e4iJoOZz z{GR?_%#4xVmfYm`L=SMh?1-V6K7hn($sCV)l>=|4576RxVOg{e_X=-CPYkvBnGTLm zwz^%ExK_9tokkV-1un@D^Cm3nydabeJ7;oUqm0MN8o&@Gwh7aRB}_K>E1DShEE#!| z?$2w2(=#{mjetkDDgZUYpW39(CEbq{4i3}cox=CSGKa18 zTk7>zj=#QWiB!W8ug{I>9rdS>~m0a;!9-2?vgfB~u<=G*Ne$A_#;)fjK}d%h;qFGlt?-&7g> zp7SRN0kMr#8Rp_3_kq5lXSX;P(bHaE=GWwk#C( z#KhrugytAc)batG%Z?4s=!A76BfVR@P;kd2;J1YE*zpgmVTBp$F^C3~s2D)pZ_}C(7kWSG^@pv=VsA0El@!_3FC)Z$3E;jj)4)2s} zC`cdm343E-Oql0obije|RqK$L?;Yx7Ub6xuk=s6xFnx3kjl?Elc3dXa?-SO=J%yJD z?zpTZtyjhu*CV$@k?~wAuO6EP4iUAgEF7e?hz;?24Z-;b9-)>&WS(1|lZ=`Y^ttG$~cV0}Fg4 zjBl6N-OQz>;xII{-{dz<;41((p9m2NBf|d}K&ihwZ@4D#m9X-z3gZ*T+Bybg{3}f; z!{OlgAh!xbpJ8M0dv^N&?n2rj$bSs{?z-6YXLrO}V5WkRfV6*htJXaGw~f%3HQlOO z4v0F;hw2!9h;l0GNlgma_pf^wS(aP(S&mw-Ti$h500#KJ=n{rMT~BI*T1@MQs#y=! zAa@1D@zJ^8-$FV{{K|`V29<0x;kq8@P_?885};7+P?=gtvHa(PIdNjr7+C`AS;2Hq8Vn^x z>*ZprBs{3&@iJkTZVq*&PmpxkNzeM4Z?Z-#p7@LfQTfkPAO8q!FUo5SnwkQ&%o9qI zCsMrw!mG)nnL*Fba_bCehs{-+~M7q#FwmvA7B6T;FH zhvC7FXMl0^aZCN4$9$HhY`xzzPsmT7fFBTEN}rDX!uRPhiXuJ5^SBVC#7Z-jg4XfRcUJsF0sN1{DP36kBPGP=Kw3gX1JXUFpo!IvOg0_ z^v_2W9F5`^;$h{#&Kb=NyZ8wmB{=n&Qr@?FTu<*wMIIQlE}~puBVHh~_zZX2ivVbc8S=BWs+zbgdC_AnT}uiIkJq(TtR& zTuwhJXI{Obwq5@9N-WYCx58=E;`hAX0^->2j9JC6s(V*`T`y15w!vZL#qKntvmWc- z=0m)+XM*VzoY5(rVX|KudRLIe7OyEYYwImJ>H@Jjjlbohd$%qJRwYNF7ba!$u@@wk zJ>4Bjq!VbDUNyfvpQcw3X+_|M4=-km9TJn5U#}A>`ZT15L{XA$hBv)rxKNCUH6=~J z)Nojw2K%YHUJd8Qfamfc?6=MS->Mr0)rjE*^s3A9h}Ph#7bP~YT@liHQDQ1(TpB=^-=FeKle& zDxIt}YQC&2V)55<+=?f9oisP#v7IFC8$)Si6gea-m6xgJM=W0dUl7lnggS(T(FwzU z_UjhMHRUz?J>UELTxmSn)W07PDn@4vuWmH2X80fFlUnK3_m|AW^C}aV+*ZMoG+bb^ zRmC}_^y)d7>M}>Et#(C!>&D988wh$gR&cBB*zXbi+-iLZ)&jldtub=Eu9Kn(%`Fw5 zhTOmU$?*3zm0H zFI>&6mWi}%A;y{e=CIC47zA4>RE|k6r>=<2IQa+Hbcr)!L%gNer6TR!ZBqs8p~c|$ z9Q8BWs#OcR6;V|yhWMmYr;s)Rrr?hjsWEJ^0?6mlrr^~Ep?=JSc?UnMTK#eC((YHI zP-fL%g05b#J!n!~Q9E;9Xjjm!RjbXSk*@lSW_3(iDL!A>6~DEip=)1w(B3kM&L@@<^&uk&zpc{Uut!njL`G*((b{9kHKyQTyvgXsm-%bq*^d>^IU3D<*2oauI_HFg`UHbW72xuxvn)iBh#a zg9~8Uq#Cul4Z5D{DxJvCx;2ze_pIMDuHOhNUQz7#_~7Ugi~OF0a3m9|aD;*Y5C$A8 z;GidLK9K|>r!oBh7mcrup-7 zd=VsAVSLVHTSWhmLJl?`Ppe;Y0cP{fs~9+DM4HnZ#Wi-+yY;!HB9F-__tXGMF>VX; zdmbOy1_)W&eTH5K@isu$Q2GS}3>s!7P8Jtx?lI2Pt*LrBO0Vsui~0mky(JThGeFLv=?&-IFIchpL{?_P&ZM^(J7~GJ!yw+W2W30 zdAMp7(R5P!DLvd_ZRt-h1H%t`*}*DvCypZO+{7~NhA5-5-rTchxo(Zk)edz8AO8M^ zW>q=VDnI-qJky6C?L<(g{}T-T@Bie~4ehGwkn8z`wAf?&WT;8;lY2xo*oRVWJ->aT z+2C(blm;1->PKF*yXPrxh5THXqTdm?UI@U(?bpr z=yIJg+Ncw6Rq1*89!>kTT!}E%&38P0J*ueu7N;C)}V~Y%Nt9vX45pX zd!_RCb}tHayEm;|J!PG-IH*32-&~}T1+}g%ITzT`;uh1k`t6_;wE;u^w)bcGoYoi1 z5}uTa;mRhrJbcC#S&tam(2K@^a-*i9*9h@$i0xwvonLkb4MUmvj%(8Cn)s1&pYqjz zO1aC>7^C=9&0nQSdrp9k%qT9X`KM%9_7Y5^NUNZub8C#52YH1%0Uc;57mdM5UfV`D z-s1P%@xIp;3~T=v?_XifQ`$WK$?i4utB`&vaHPDn0`K@hdQ=6+%s{-3_9<)0_PG>b z$mUs57H>l0;u^o_a{paH`pq^4ZdF+$Eb~|{yV8Y5@zc5$`Cu<9?<|U$Bheg8Rvy(! z+gP=T!;?ViFtKz5Z0RKuWmvMx1WQPyE&3>DtCXvmd-5%4WC1kx3dAHGB{EnB%AHTW zOMqQdL@imN7O8OBLFv*x( zY}g-4q*AVgjCl{NO41CRAKtHBL-g-(#&gIQB+9x_&}HaQQ19C>W;gAWWCqfy4G_1u z$ZAHK)B?QO@2QbU9^OvyLo{Lp!td$rJLI~mK&?YK`Q-*nST-A+59C}RX9QB&Q4gFG z*Q9ebpmbDTlg{or;I_zcU7O1rzgDcBCk0hgUghm<6SY;{0>=fN zWE=q$P78Sss_rrG`rGlEk)5>skuvO~rh{d}iglK(GARh~i_#wmV7NkW3k@J=uJ0|_ zA@89z^xtSrU$q7J)v3ixy9*-^t^!6_4HyYq+D+3~tj77BVG+O*tJ7B;TydX*YGrk# zdLM{2`7mm~XN*r3c#|g&Yo+VTny5PRo^&b?OkcU6x=A$n>;Vv5M^ufhJD#1#V&PTi zoEt-^zYyqNuv%(0GARv@65g7WnQ(Ies0W7lsKoNO zEJSPp&cB6_MRlWIxHgHiX|zD9`O4R(ps*rgDS!beBqoUPL2e1)ErSOcluQrPsHPNc0WA=C4|AEnZl zhXm%_mdB>rb&pNkXR%$k5<<9cp#kKIPq!H9aXX&uaq1Qan2`Aomd&23U3?z)y&>5N zrSyBw`SvY|CVX4YzA7YsBnztnPDe8dmv}Hs<(BwUx_3smI_nfX#?AOI(OqQax;z)bWBzbf$oj($6KA z!~>MDdP=NqL|Jt4&iRDY=33?~jxE)QwtP*`DhwfCBl>ZW8ENLuA6B|^evNjgWzh4} zAV}?f&v68q{hk${5kqhAAr^%|2>L{cGWH{u(6|cXmx0+M6h&ms4k9j)0DEKygrNQ- zuC8sivn1F1JYudZ&KrB?IhJ$r!=6Zl_Z>E6A6>Gw<-5RCb`lXf)ue^Zr> z2lcazpIVPUgxTxE+fnMp7O>-UM8C#}6MZN(1k7KIIM<6(ff~5mptB#8gd_RtB;iDL z5iy|>wLfbO0gdP|$rLZ^q9WlK8FuifD?bV6O#nV_tV7`*Axja%Wrs~;+K6T>)8E)@ z56?bN_Je2q@-C!Wx46GvYu#u4$dq>BXRBZljOLNk#`>$QEO-K7x+Al*Z$o#IEvqpA1w5 zNZbIHOC=zdZ5;5t0SF~)kOigHrc-QlUL)3m8AOu-^-+YT$AYQHZ9t2v&fY4_LE9!t&CoDNUp8LskY~f5xW$EeimX)i4hW>NJ)4K z()WS+o#s`ITkC@gSWr)6!)8!QBQ3|rRx3MH5}ry+xD0`^&lrpIfC6}UHxcQ5&O0ue zkL7Vr#7dOrb*f^ki&TwN0mGLiZZ@%wCs3IN{C=*E>$w+=lQjXMu+ zxP_-(C*0}b;m!`(9KagYs_VSI5;QIP4_Zi%llaF>1!67pF+hzDzYI{w{m5EqcEx^p z^HjLfxldNy0^M9lsw6d{75@V{R>-mZI|r>GIrfDcAg4N5^i>orlMOI9j!ZQ3c0LNe9%QJloyYK&kqMI)%K#}Zp=!~`wP%0 z0?9b^))HVt@wn|pq?ltBya8|dJDh;D+n?7C zokVP#>t}g!3(mRWBG_Pr%|#42tfgC#{tn*X0dpj-by5e?M3-663e!3FCwL7 zJ8cT*(RfmYY%8f4SnHiQn||jMj5LeA?y7hXvBeOkLO`eeerQ0I%4ek|wvYyN;9d7R z#H8GD7?IvO`6@LIG=0jUPMs^%TQ!%Xd(dNKLZe#>HH$Rci^w!F?OA~?Ub4wETfcFm zpiIrsoEtPJ+{*BjD??8V^gGCHzUh=Uq7KBX>~H*9}hBx3Fd~8|vniu%afuE^!8%RuSF` zw8=~@40ZAaM{nRM_o%$6aDSIVey8nE*Jm-3i*zUk=ohpLV{SU|lpC;$7lt!ETonb| z$>Q*p&ZE8D(kdrec(CY{-}09vMl}y42iOzlptLkmrIcSbno8hlepfzDf{w?)Qntw* z1a-8tq7#F4`U^XIC`hM;gKBIa6ZcC40m0jlc-)>Q;-G@UB-jV-w~yHiZmTHR0lSr* z6o_cFGfj+8LY3ZFm~$`{+Zn*plLe7dOojpUEAQCTdrp_8i>e?}J{FdyQT*5*3yK10 z{-nu%`>fp;OLsA>uVG)8TuG3+z2jScpA66xT;AESY}dsFvbt8CY<7#W`*aqB2-IL~ z*y+O?>~Hh0Ikd7_E%t`f4ZW^paX1sCOY*J@pi36O7Dcc{WjNSFPr9hOxRnp; zgPasFsgz*0##$9yF-(@@+*Gb%}<5~(PMHqCD&V{TPigx18e*j(kva@Nrzu^#DaQ8?#6+9y@u03#gD05 zGBush8PXKlKeiWr=c-B!`zV#4;az+C3hb(pAckx&`ubjnCv7iUaR09cK0M$@l6gxq zNA;i=;(0kA&d0at;1nZkc^G(2{j$;kzHM6G3>@0?eaiG>{KNp1@`@pQf1ymm`sH0L z{TndYAegKryBl_l&vv^W%Kp8yT6;49Q%WRDe(R(Io*G9z5BZn-hCB-eWcY` z!s^0PF!%27lZ1$w6Cw;{bk|q3@H=|R@P{J!-QUxNc{Af|yTM&<_mSzpse&2NCoKg- z!+IWVZjU2w;b!pO+In>cKaWS-OJIng?rPS4YsJf8!~u&ac)k><8aJ4tc-j%a5@(|f z$*GQ2HIuor!z>NwP2f|7C1LX{^@JY3Qb${WE67!M%v?ONiHK{}R!Zz2U=nX$zU@-M znrQ4J?m!QK$tCnMfh0oCH^NV|vhYzMYPKe-337Tae-Gq;AFm0NZW4-SCyiY1?Ot3~ z&^`Z;0CR6>8uV%4gmY~g+kE^zOcgV2a^*2 z1nKZjJ2)w6|8RW?%IW8eos3{1d4V%RxaUS zCbQQGUjLlV0`hIZdaQha$OJhnDLv`XbYIR&td}{7iM9D=HOM%}PZFgJX-3r;F;xfh zLV{y~HN0%=L&N#tK1Tc(XmOtNGvZGYBfban7bC_3>rUhkMr?0VfsvVF{eH|IfjbGR zMx+a#I!n@V+IsSj?<;_R!SYaa(C)r$-98I|w+O2qinkpqd-DiNQShLBUz1QxzttwO zP~VHvHR;&i@OtpftcIMeFmdC)k=Tm$;3|nZMqJQ0svi76K@W$-C)OYsd%mC9%m8C? z8$@VEH1#ocnu$sJn{9aS3<=aEEl*b>b}fV_<{ect-R;OYQN|Dpe*t9 zZK;L;b%WFc?prn1L?#v8{-fsFO(fF6VG+@Y(JTP{oqv!Nr|4@gM)O$loxp!L{6AVO zy5duSKO4)44@-hz_b`Al}4?MYMN3O zw=$|a|8^uzY2*jcsE;Kzh}s7RN4ZeSX;&qm#s|A`FfB^{A7HsKVvvLlHlsMbhRJoh zvY~hL16cS=%`ou1HHy#H=wqNs)kYJ#{ZtL8Gi>O#wdR`i_K`XKN2X}!IVkaHU_6i1 zBsXaSw%0^!tR)3Z;3)-%Ov9W6Pb@vvMQ{x6S&@E^VGyVUR4}J+n`^O-VBT~ zHkT9drX_+j&VI?rq_;Ormvn};og+r|IGM2o{|8OqwZYULkpGY0(=$K@sG=|4ARe<1 z`{kR@xR6eEKqi2LBRI{0EM+JCJ_~8MLu8k22bW*}J;G=mh`$SM^LtJPz#9VK9|yn> z0r(n)Q9NL0fePQV)8fW|7d;+m*hp``L8^Z%0KW|&QvVI{K>)%|zZQU47l2r6mwy-y zgOBsect#`JECcEk2GV%B4H9pX0-zXQ8Yu7-6jNfdjI)K>bb% z0Q~a-c(nYX8)W0VAK+)Uf7y_jSr99OXTZYH0reHIwxfN5|=v&MY3mnAZ=I|4oChnyx#}15*>3^Pid{ zhYcVdExh^b5L5CU(2W)7N~nG~wtTNQw1l(J;wRpaGE}c7M_qRCG_yu+O}9|63xWoy zJ=MZliI!^6qdSq;TnuhkzX18IgDN^8UK!YpnW>x=i^;;Jhc&thP>Lo;p@C@blx3Vn zZ5{M@`mi?Ct-u@{p9_S9M>Muqn@HKjvg$^Z%C@Na+9R}hzc;Q#4!9}>|Ixgo>Jl=l z07yo&-HyDqMn@ z?=|o&@M6`_`vXnoJwN5jrh&`}aT`!)3mFU<$SUZ_s}O^lEijP%!lg$vRJSDbKa!2Z zgfWj!jLC(qmEn^vFEkB${^@1zG6l3q32PtKgwFH*8hH_yi1QMi$OR zq$}@ff0intz<$cZHIuiYnJt3su{!*iu;;OIJYH}=X2$b`v6j#AF~MV*4qksH^ULr- z;jQ`e_51tC%{uA|x0n)Fcn_OyI_V=~fLB>-4daLL4=-liiL4Q@k|byr=&6-l}_YdlBi5Bnj0EN3$pTCR+D(DQV&Tg~e5ao)C#R zFEj28@J0l-B9K-?8c7H&yo@_u9s%Z~KJa5S@FdmaAA(5)kHtUyNRtOOH})fq0pj|8 z9Z2Fs=!QPzV=&(&S#ZfR9lq0BMiwU?T;7iwnwu8AEypq<_j#vmd z%k2t+_X-HYcI!AiQ~1I968PYjEiO#_d4Nc`az{SD8wf52P87dK?hjmUsR94PLyO~u z%ZrV8tq}L5E_BB!aG}%Kt$xq8Qb*gs;Mr7a^Pup|vm>c@eZpU#%}yLxjM!h71H1DaV#fo% zhw&_Ea~JbShs5js!i{G~FT>H@!3*%22hMpU%ne8frzm{cP~ zOUSI+Hfd$W=GuSOzT}*_Qa(|pN4LMT6M>liCVxUz=>=d%lO42P@4%q@Yq4iokvOMc zh+bi`Edx7%3-sG!O`3J{N+fps?zm8zQGCPxQ-cu@I^F+=%MQ=4+Cdv5&EjIKG53QD zr@iciCj-{M;B1q28@8J$P7eHsY#lo(BAPTrGNbhn5Z;zv0Jrw0b)xU_)VY2Pj_ zr{-+A#mJglaTscyzRIHaodX;AuIlFakY~XX{JrG8fv9VBWPhAnEM^_ zL+<9Y5LuaF6dRJKSQ5+F=^)sDGrl#x~cnR8-4e?pWGWVZjA-nx~CU>xFrR zn}xE-n7xmql%;S75s5DQMey*7vK*5Z7zFz^X`w+_Cc>3eBwmK6O31kdt6-fp2keu1 zM!#ptXTqUp9;6TZ8U@)>P5OQZ(yQCINplQ46_FQ-AvOREY%$jlb_gBE@0aGnlY3C8 zSUQ@*{epd|L)iLMx@z9wJ?A^S^oUAw2_v6M=O6cB-8z^pm@$;s3@L7G(|=d`V89Pd zKlle+k^Rm2-#H~dfUfu%d?w>h3EwR-*z|#WOla`lMS*S7gMqE$K|?QG!6H+3b3g=_ zKXM0;Tw#Da6hT-(x*=-XaF?1KQnmfKBsW;}c`X(l5-v)cs+S)9m&6eATo|VhrRe>yZBB{Y`tH9M`b*5!0-_n~wF3wBYQ>hQFHjuA{Di zOhfNmhqJzNG44&M-*bWNhTI(9$m9FgNx8E*tUV~nE#FG2>WvaZ?h|s6i#Hdc)LoA6 zUHSE=mzXxK-86JIV+SyvEwIm@dpeov_t^Y`_;kGOp_c0A>LTJh_U4gftpaW;$_^k+ zpQp-KE>bK5LKO|}rC4dcUCDhfsqAv$`&;aX-`@(_(C;}l!0>rZa1%%-ug?Xijv?01 ze0!>%oNI5(=JI`>DZWs*DrBAXQ1xdw!%_H`L;r8zq|q0;#L`!6kXR=@W?*$HjTIKqN4LbO=fM>zLC$5JJIPkHU?vwEcfG7J67$gP^YQo!p zQQHjtR#2`S1P}E90N78xp2q%Ec$zdo?z~+A;OfQ@o=Mfi;zDA4DxEwM4V#t<8$m)J z0<~`p|Hs2P$5~BfZ#NCEmad@G@=hb&)G~O?dLYmAg!`%X!dyMgLN9I11``2y*&8s9z|4A%6CqW(f|& zS61T5it`q0zvmXLHsY1w^*qsZ7*&s~vbN1J6sYb;Vxo7rTLtD0@}}R@>iZQIl2m?G zO5I({kKhwPkqEco25R8{1EJ}KO#Hs!dSND<$`fB)GOThy&WrUZGpT*;%EqoU;c=Id zI8r$Iq7J7E*IrCwGvMkI67irQe<>AH!kCxRY<-?BVE0DitpPF{*?qr&$_m^{{ctB2 z_~Cxf3;jd1zg%Aky|0=qNg)U5}5YmTla4{rQ|9tead#pQm_qy5Or zr1m;CrFJ`vCX@=-Gj)qBx|%LmEwJN6iFI-?sF+@l6Z9cqoTkCy%%5YnAn_NdfEcD( z@Yk61nIOFc##|w0)p%SiOked7HQg(Gv}z5$C1k$*KQhAMuM)m~ISCgDw_bh(>xH7# z8jAJ_Pp)2t8wJ*)(`S_|TR{J>V5C+IXBV z#Mw1ej90kdZp7h&%|0sem%jfDyuLRd?%U^MpKF$W181IEUvNXBd{J5oRzHY&OsbKTjTXJ0poHe|GG#l+eDbTDD#5y5 zbp93B)MUmdUt!3-1}l)29ftp4*&$aUIP;5*uN)y8Vgg*=_Iob)n8e6-`Xjs}4?3OQ z&m=0_i4N)VdaWo(Yr||Eu#jYcC*tP<{uBTXQZ4j;3CNUwj}vn9Addn3fjTLGm3`}R z&OVr>Gd|)FC*yr^iH?-r0cC@rEa+mPnLRB}S_Oa<0P>SSEkuGi2erHcidA3xvAz&P zS<`iPeY-pu?g#A>USAgn9Q=ptbXX&Nzb=l-927d&RVbKKWZgU=xn~tqyv}T=fRymr8jVKS!|4&hPbGy)W~!zJxXVdYtmV&EMjw{ zwV_^+RHq|WZ7P&5O}B#L{q&hzNHd`cb2BZ&pVwQGo{#0LK;<56nQ2LUUUJQ}`hP?% zxt0y)IE47WzEn0p*fsn_#ZZ!G8$P*N%m2 zZ6DV@G`R#w^Y@0`^^`57jNBUZd8oimU~*1p0~)SMKW!v8vuR9(dC9Y-ncSyYDpIJr z`KFM+ex_}jFR29QK4S^9ekq066Pr?jC>IZ8bQt&?xZ}OUIzx?HW2{+Cdri?-VytOR z`(vX@esih$U|w|9TB(AeR9I;m5Js_A)j@Xs$c`P>cT9V`FtxvnV)k?~c!%Y8r>uk! zkHLG$GV~b$1iYCzxyBf{KphI2ZFBujD@wul?X>8uQT25o*`cds@AJW`hna%h8f#F& zPK()EXgLj*-Y%CgYr`bCnY?8~8s+U1KHH$i*M!y$S++{x0Q|pAD9gOnU8Df*`c^*P z`oHtta=6>l=eg5oFcRh(Z{A&x4@jQB3=m#R@^AwQ^=7Nyvevr9B7Z@G)042@AT$S- z8%X2}i48f&aT%B&Sggv#2QG~O{kQG(J2COa38jSB$#*0Cn-9$=){eh}q>XuXX)!E> zt8h5Wfi21GFNO}>@7*RntU|h^w0#RB+VWt?(F68+cxOSGUplTot+(i&Sz%l@!*(Pit)irAemJ*x zzT}zMr_hCSy7@#J_jrz<^3PD9-i?H3XZS)jx00$ku^Qk*1_Xt`ih6m3rM7JC4d)%zd=lO^C zL5Y3)+rp4G=KNgHI~xHf?@PH5`@lavaB9E#pu~VHoia!xVocDwIQFul*gCZZjhZbf ztIsGDpahxK!dgMaRWPq`*@fe#gYbquzuh$B{Jt&}O!GNSwt0Lmuj_c%DG5mu?6WC{Uu-Qhw6hB>DE$9kyRmL#YD5&W+BDb zdCC6^-eab%jt|`|l?5c_@yr|CNSrr<4}tAd*+o-J!1ol>>6Rs=1K<&Z;d>U)0mJ7m zb3pMFYc^RfyGTv5yqW-}uE6b6lscuydN_+G^?E#6gISPccA?})T;j11s}TLh{Z#4+ zVb&YP*eC3IBW`S^x!6L~C4@Ti8qMIeD6_Jqmqz^Rqq5YzqD)bGT78dN;Q;b-0G%iN z{>B{qxKQ+FW@!0<0^BiFaBlcKy+X~KBk*Kl$D3u`G_N*b=|jdBtjmsUi8oms_5Wcon{E;q~l*BUDw7clbPW1@qRI;Y9d+YntN4<7}hPQzf{!YT_P0 zj@0cU)|I&HBm_Vpm_t03$GD$0vfP?+=c7@c*3y ze`LHJGMxj@6qM>{Z-yf%$Nn8TLDAQ)uw&0RDn7;^&X$-Z=&eD|qi~$b+u>pykGF%4 z{4PW1^GuWk`L+ks_5+j4Hp<}hGN2F#>)bUjVY)n?`EYT1>?>r2k*(hc*L+{uHh$Q( zrjOlh$kVr&f1osFJJQFtBk^g$xh)1;gsyEGTrPyZ6$e~Y+FNO{+x`P9j+CxSOvlw* zln$=-775jF72Dq6k$#$UgJ~PT_)>#+&FvZW*h_VP;pQ+0S7}4MRDXUa9k$I_-Wgx4 z2|4AH?j(6Pd05}@>+s$z_bJ>vOhK38yJ%YO_8aVCQq2yN@pgO-b$?aCyx9E>M|~1} zct@2}&`B2{pThG&0GeTt+n-|>gEDG90B}Xk!U8JK*eN&u5{E`6)L%3r-IuqJIV+&x z+-Oo>LYd&(C;af&BwL?-UF>{l4s-ADD6_)>a1UH{QBD3IN%v8@QQT_Z(-nfD!$r{5 zK|GQRsrPxh6~3qlV<*lJ^U-3h2|mEng)#AqqR!WXRq9*2nO8!00a8@>R1pQ8xB$K= zF!+8Ufedsvi#q>)A+p^*X=nNUU15x|lQzEX`pV5IjvBRIMgP=JI)w8odazgC9dGU< z7%M@LuJ`qUBQ@!Y(x(n|f%Sz!7bvg%c5t8@tlNK|U97d&0xDjyA8=Fb{DPs*^oh!$ z&g3Is*x(z`85`+0ATRf+^KTSBd5OxKUtsKHjk|r+wmn^8c#r8E|33fVg_({=>W_A@ z)O>h{y$X*OI^s4anE_kN(8wXY!X(peMl!`3FWtSxh|TwKc60~})v=5!9Wvv!_RLtMPH)s zpI`8GEZ>RvJlAOA#pROo*KeqK=|)-Mhv%ERD0X32NEpuB=i>QJ(8Fwl{mbcc@GrTj ziSrAxT?St1B1B>{xyV8%x>{AEl2cBVJRkJKHdOT*2mZdfl4p1StDNN71$-2FJ_}z* z1CB57IX3uS0f)rT`s8rk;Kk~8Yo!^9AHrw+F2R>Xz`0y(X@XDm+?9v^1@Bw>5Ww$; z|Dk*VoWR3va085d0grs+Z|DnnGvGQg`RJGmz8Ht#3vvf$XnR!f4C2ARznG`(u?OBj z*TLtVd`XRbLkwAvm1vQLl$_%l#CkR0`YfVQ#4tVKhLvp^P|%UH8HpuOARD}J%fZm6yoV8w$c*D7Sr|2$tmNy?J| zALoMaHxSGs6?#}#CN{=e8D3lVMR%|~G9;I5FJ`d7hdyyq1`u=mg|?lX4N##a_%5A2kM6Za(Y>o@)=`2*@>KXnL(yr0|56|3?s&e0FSukp zeaG|pKziBRCX*8-leZ@ZM#6!cvFMJcaUi7_KGX<`l4OWkpAHO-Va^oMPif0`nv}xQ zx{!Gz3(bd2c`X^d5(sVpKrKy=!v68m0I6!rKxkP+X$DYwEL68)0BfR(eV(KNN)rij z91%%D==@~>)EEO2m=SAp@yO3X^MQ=05_Jgwtkc@whcn?*2n>7}qtZ+!pA&7y%K2oL z+JH`}L|K`vIHZNuVE85tL&aDa%^lCeW|F7sKpn(ATl za3Dblk(j<4%P~TG;8_9BB!-Wipj{9L-OX3RGl37j`y6sN4h_UdPwmxWn=>7;i}Z*s zgg6bt;xzacU@Bt&1t9{`hv8iU#3>LSxf^z6f|JZ>CR+-(XN?_gcp`gj z*4VLG3vw3aBBA>IWSjp{81-XAEs&CmyXmLrL+`AJ4Yxp#s)q8vUWC~E1w-jE3m5%m z%!(B+@oUBdC5Pv}7Qbh^0fG2Gsr%BuV-%0V_-}ir>?|HsF&t&GD z+1`0)=ACz&V?RfUPU_fY3YQ42RJtv?1Zkr!f=PRRh$Xrtx_GN8@jMcPdXPBLi^K&z z&0VECn!A?mh$xBV^&+Mttuq4g4C`MxNaTBw=!F_9dd(6Od(kyrVnQGla?zC^g_2l| zk`O{kw?9BE1L^8NQQK_G`eQM?uG?Wj8b{kEB za!l`qhl+#wYKTWcY!WFd*qR$iVMswskdtN6>0+z~sHYPZlu4v1QkN3*D0Q0GnO>Ap zLc<`8GtAv+25lpdcN=?XYdEhJ;k{^|7H-8* z#uz@S8--)?zT21;4jt%3Jrlw#2vZ@j4H^s9A`L+vhH=H0 zghNn47|I75}i(KG_w(|`82Bjm>!kiH1v3WPQY zeg#t9gjj^|I|RWX*UX8s3@M4_!>j0S`*W-7a8|fIqUyQ2Q*}sB*7EQ58@s}*KB{9h zhJPZlatGW@fm5CAF?K9R@8$&1PA zw66@YA}wPXYCm7U0UGps4wC}y@47SEv2I05MQinh~;V6MRVe4cb(ZpDhxWtQe%3@lB#HYM^*lRYkS!^@wt)iZccj2ch zm?NeQwb_3~X>BZw1a?0gN8;a6TPTB)-U&kNQV5X^c0E2^&M}@p)3O{ERi_xS zs%iXWtRFvRn~rf;$kQt}G$5^pqs7iX!7xZ|%k3Xktl=KE(&8Oojs<_nb2*R1St)&b z1s0>dS8pLqi+}bo`W$NxkJAgT8hAURMaG+EQNtU?swsNMhQwgsK|Z0Vm7j0L;xoOm zFv2cx4E)Ezdzmg~1=1y2VyrZ@io_O4E{65TSwiZNm^;=N3kiidyf-HBV!a=WhkLMC z<&%k5Bt{=pM5@I3WPz$9(s0x{s>L(j z>R}Sbw!(XnmLu^pJcYKtQa7C&!==DE;|>mg%kx+%Vbn#V*SHuILJl;Og-v$v35cx2HK z+cgQj1EKOfcUeMHk>;X=RCrV#Y_L71L9Hsj1*R`W$}N#`D1~$S>tBI&zDx{3W7}|M zB!99QC*yJH#%Yqi8h306Yjh)}!TF3@X?+wK}nk!Xk}_ zttwj(Y{s_QV(zI`2N(RdfpOEhMwZj@sC*tMrG{8Lm!oZWk_*2Xz^_yHoUk*p8u9< z$T^%lxxnpQCd$z*mqlVqAC;Iy*s?omahuQ1;k_D;bz_zm7x?n?9j;~K9CQKxL(n3*cigH1)yPp~dEL~}zeaxRpM=lvd&aD4D2oF&{F zoH{bJ@7ZU`l1F{Nn;9d$JE_s{iRjaCvSWrO`VbN;By$|*R1RECAEL!+!jvdI?h=+q zjT^Mr&$MZ{B;M_!#C<|zR4RT_xE_@?^aJQOFBl~mAmla3IGm&fG*DuvkU1oNLWzHB zBjcVaBX9Ekd5v&>WPf=poIop{>V*SQ{70|o%4=XabrW%*MY)wyI;8Nw?=wD^SZ z;gHOzeST|QIz%Cj!N=Zr6P^?o21=Y4Y6e;E!VUvwOa{}%ogZH_GI*TLq1 zmi>YH!~C9oLcBT?pA;pFXW-e+YYdc_AY2$a67zyAW+J{I6vU(|kN4fF z-vk5KaAYy?!b>r+0Q%k-ZRGYooXd_1$!LcyA|vo_;Dxg>@%Wg~5i@#_0XCDN4(pJX z61Bp}*hE9{=_CUZm!Cp}%gqlgDX=*-IDV_hU#a0#xugX_SQ9^H!QXv^4I>AR8rEm#EwMC;d#ofeWz(^95;~>;vfV1N`35^oNEp8lg8fiLRD81Vm0*9~L;rHC>Ln(KhH(X=5S+M`E2;m8% zY}fi^+@?m9;c#fUV7Cgx+J(*Q_w4om%Y}3UCC~QVaoukGvnzb7U5E64cBwY3_;fwM zwxLT^H4N5oDonzB@76BD_1JaSq^e_h*StE?nuZ&`iV}Ogi>)j9gVy8xb?ck1sep+& zJq-6v9ke)W1FnGvHxD$p85%_Hsg#DB%?-{ydyCRjVyl;`p=)=Wx}5{-4=Qb-1Y8TX zs#bhTx~ziKEI`{0FICHM1Erb;MdG-`3BDx06Sn9e;H->w{hk~Cr1HUa`n4aKXlK9Y zPhmk~bl3;pwnkMES+$h-&M9GPS#(6v@AZ_p%S+G?8ydj5L1IF5>7&RY&3_Bw>HgNU61fdN*Kww`gT zX3+PLJ|w{4ekp9%4#!o;8?>iEf)SSMM<-W7QMQ2*=ldA(2?%q2gDh%Z-53hhWBHYh zNTU$13TO3+_^fb8A3bDL58eyA2qt}e{~%JPPA*RD5n_@!{F1OBX*R`qg?}bxC$91} z-DHheJn~N>$^QA-$NvU?7UeYrPfq6Lusa4NkE3wEP?9`?fdjWkSeyJ113OO=K23gz zsR0~EQkpT z?H1;yE`dt1lJH$>{v1k-mf9Al0Hjy@e{pS;9#eI|xfX?vxKs^aF4-+vQJ?2$Khlv@ zI7jBR-!u4BUc*;QyQgB@BPne?ppW zh>^=LoRFp(V&&8Ya+FQ+BaNylQVdi6=?K$DF1#(AO-qa#)8FltD}4w4Mx^pVAd-;sR|4fPL3wpu(@hD8<@wW66B>+- zL`JhUgcS2|?4A>@rVow$x;F>-1UAF%WPn*b0TbII1Z6xQo_jo!TZ9Lf{xN$56ZP{a zbcC=oBXb;EOuJPS)`#+fQEv{hicMNh&;0_c35BpmBz5`YSk~CqP%WujA|EMjpB&vZ zJDrLC`6F5-^krl{BrDlqM4AEVv#kjQkvciOq>g1x@S1N|o7!oec^%=`TIKkH-}7a& z-}7p-uqbn8(JSiywcpmsQ*{^Nu<~MemeE;r(_3&X4{HyT|6bp}itMU5 z{SvdT&YGjn7n`!UTQ2(Eu9d)pj8bIo8o}Ard`s6LB8D`x&^5hwLDwXjUPS~G*!y;* zx9k2-5~Kk3bWELIqyWKZ0%sH{Yli3hFmwjmU>l602FWe*5;Z6jHUsc@tk+3v`aDZ} zk%nzjA=YRdL?e}sZIH)-uptLA{@edmY)+sUYE}u84Dsq8{QC0P#=IuKr`6x%O63T> zwDorf&I#dFLxhfqPjn-2P#P>MfYhn$)Nn#!@uyxO@lF2Q6%9hgGed0j+RO5=3&F7E zS{1<;f*z4+a`}8v3M7e`$+2RwLCUoboJBAopd$nwWH@q*q69P?Zma2>baO0q|EA6? zGUfq+R|PYzMyyqAkgd~{F2x0RlCITvj+da;#82GEQCroLnd;s7EGIseQu3BV%x=Fngpy z5!eK(5TPVz4%gRj;JSdL+Tm{p0-{8~%{3#m+0TG}#ng>f5JgplqW1z>gaqSx4d!)l zw8+O^px5OV&&6|R#WUF#$Rr9s7*zSGCG@)4nCdV`s(Cw9+d7M^zO7R=>+BeKp*~>E z)?tuJ)*JQh6dht+CN71e(eLSa!1WLoIItr8o)7%gy2#>S&2&6tmcAQ-Mxoj~V``sA zp z@6G2F?k|x(pX4Ryvu+JLXLa0Yoj94AQ{ngcdY7zGjL?gd=_SiAgJy{E{zyBxD8^bU z;)prc5Pc-5y+9{4e!4VxyuQ1?%mlGfr{6N5rDbUSdP;B8ukd?*@fl(7vqiv=!}%!| z`aM~IF@h~JIzt#rQbT$$glSNlC5_wJS^ zWIgrLvaT~U-ZMnBDmTLOZfT8yyx9mbfB|Hr)YeYVC~c1f1*>s}e!a}WxT6Bg&gjc; zJGgGQ6xX&}if$RcZo#_W)=h3#44>3aYj;aSs!i=-I;Hm&DWqQMUEkm64ppXHRCY4K zbEH&p%_zhcKZMvF5Wn*vHjhT^rUzj=#2-PxkZ&V@Z$Q{BsaoPhMkxa=73~}%+Lg$W zcwE1hXh8L=^lMucLoV!=RvS{dU9h?4%z`Z#F=r|n5m{qoM1Id3{ePABdv*c`|E~0; zVL+E57Zc@pM3#dZG01^NoOhyBr}Kv{6!}A3mofC6=O?$DLpMtCEm3W>XrtxnXD*)U zI70^u`ySHU{GMgK|J?_E&tttGx}JXigXcw;W~~YUe#?Q<-gJ@|Svc zrP+$RmmM8wJOUbj*g4Sj*Z_cG^3wJV=zlkz((iOVbsCSPokmfGG^@UIQ6rO_;i6xu zbqcFT>u`%uJ6dbQ3fsNmNB@1JQ*P_lADz)2M%%g*kJ?5~ydQV8Y%S4!Qt1=BhaAXyXm-+EQqyQ zpz60nHy3UUP;uZ{jXu%u_dplwj?eDUo~%H$YlI;`ZL;HFXp}y*#)sm8&k)%7QN}Fa9P#Zeq*nx;>yBT?%~q z&)(nU^DZp0#Pc#y$)0q}m5*MLb&HY5ZTHYfB(ADFe$NQ;OAy;f7CFD_3XVdV`Hm+o zal_<3_MyGpFH-JuG}0)RRK6~af9Dh+-Y6O?e~~hlzX+2g(kcKluhN*A&MDmS=uop! zpXlA-L&9vJ2giJ<_GXOV^NsIy*!h(18K9moL+Zt~A4s+*j}fZ=;wsXJCY^HTL4{BH z;`FqS-LnS@5mH+P@xzul6A}w5{hr}{2qY7tNV}-O7gT(>buO#Pp5sEpu1PKSYtqI2 zKwgjisTh5sw4EC|TVg9fJ7`EWN{ZMESU*Jcqhg6Q)JoxobSG_tZmsD`=Ww8SzxLKb zN0B0f6;7b%UQ%QM0Jjz5Mg?_&(vyl~6(JW$&R+l%;q0N}x{!NAAafcr59_a2i7StX|*Ir#`#{fp#kARnphh>%-C zc1uNTNU4a}yNZ<;mX?&Z7sV{Kz_@qD@r12{o8d_d_JwAtxjAdCS!6?%Iw?`4rly4f4$8fcTLfv1 zCIWCGhi930hGhr;8GLfZ1yd2~2mwxGtXHMCk(YVESK?YrBdQ%&M4-#FkOB!-zbDme z4^&&q5*1;HJ1%5{bL|c2hN9Ab27rcooi1|Z?DM*AdreSNuvqf_yS@=zAE5wYnc&g?f4@XrcwnVf*h*>c?afvVBUq837Vjaehdm8 zzh{qNo{)-n3QH$s#%J^+Eg38?Ayb09htNq+s%lG1Lw6{u(S7gAeRr1c94Woxqk-(td31Y6>)^Q`k0Ua{7| z+~k0Hus~X}c2O5iFIh$Oc(#fr0u31k8JpCw8yHlbh*p?Hdw@xu2DaMjqJGc&Jv-q4 zVBmj$&#R?yM*3d``$hK(1p2RsK`Atm*yX~HB$8mUnUse@A3w3|@p z>Eh=!y`FddD22W}APYa#Y}b`dDYGmpjj^Wjwuia0$tKZArCDhxnAkgxN9ni~kM}q+ zSe52kviWmBvhX+}&7q`TPgw6P7_~inaKJ$Kh4g4iHsM&s7CO?J4njDZK{(oUI7d!M zrKF@a&U)}(OIZwmu=C1FU3bg$Gt!me=OGY#^%)x^Kn)KjO6uM&YL2xy`;644A^*Pz z{%;2UZwLOxz<;-<-!skM?mZJbriF-x~6o24Hh+|0-=F-yNsR`Z%1lyaiE zR0L|IF-w|Iv!sH2b(~-lof%+d^lQ?Kg-47Dwxr_ZqF`V={n<$%no_*pq7!Wz06gIH@+F%)yoz(_`P+3B583=^hs`5h7`eR66 z(79j%5>U;06FyID@L0e#TTJvNRD-k8u1*)&;H#y!tF`9<7*rJw^f$Wpm&yWlk4z@ zNIcR5_TZGCn~`Qf$;OC#eJCXqtX_}ckvJRw@bx;u-jtizlJa#PbWDhwM?r2%EsFWQw87>kXS*E|?o?V%9j?j(2`Q=b$ zV>xqN#~#K&t9N-6S<7gV30-Rr?EjJuG zKmp1YEMgE2qEJPl@jCoR;IkO3s14c+ln7Bo5ecirxeulmhms_Zo_1<)36tE!0+N1p^dYN59rtYZzh z(hL;$;O=5;GAdY~^E&@o~F>1x8`^y^hk;3QJ+_eh@+s0VS{a)PUFAODhjE5Jci~}4T4GGfF4R|30qKx$0?YQlT|g5#~znZQvC3OnLsaE$}0*J z8(_D6NQ>ow#3Rkr9%7$)LSlR%txpP`tm93M!Bc`C2?5zW!`=XJVZGi8OlBomE61HS z-8*kC=sLHj(CunbqNLx!CyE3F1m}0*R&l%y7D)0{$$Crx0iJNjNK|Y*? zdVU&AFCKM?+f$hFt03Y1HE|@D+U0hj;la9xxs%*U_e7=T;wg8!a)M(p#2V!|$0@g7 z`LN@#+d#M02c?%@RDb|?;+c%^QYV|C^Mn2RmwE@e@2<)OzF1siC$ZkRMf5EKX;vS zrzurV(!pH78|BcqUw{5nFzbBKOdw9+o-`GSRqV%5ZiMn;pqx=$xdA#~eGuL~s|;C)EU=BbiQffooiXdewdni>@1f?`9wT-u_5TJa%eUdE+2io0D{$?#Sf#hB3#HS7?bGJ;_KuY@ zJL193)jw1__qrUzv5Dh zDy6y^=eS%14~$S<$kgI-I^dq}13nVC|35wm?n0gQ9Mcx;_K!7aH8vQPo+rgfg~vD= zd=VeNOhBsPXd&#Qx%rXfWWq-s!8EQ}V-if`o4<1-T2@1 z(|i49dJi6R(sZ#|$q~>Ljx}*I=Li4|6VUeI+S3KW&V5p{W>i|tMH!@QNgyMsU@2wk zbvzh}V6RsfKI9^)>cUfQ|3sPdqd3w41GHcdG|}kF(%*8;d=IgcAxwpUTKs-!Ql;Ut zQWKiVjO#@ey`98R1C7-46RuLDK%o~*+Syb1cmX(ZU54EoMM>Dk}GvLGQ# zq|8}~u_Lj;o(||fS&#@Auy@wk^E*|PuRf%mqEw(5Oc%q0Nlpw*d^qrQ_OQdI{0M1i zh9S)ejvK$0M%s?pV?+#k#N#G==T~-5Ojmtj{=p7e2$-LJd)h7m*+DjfD>b;_Twh*8 z=;5+A9PoBoXtTP0R{iJE)h;r|7&6BH3^7HNhn#ZHQj!62a5^lbFV_d96<-WWFT8l| zCM`}K#=$R|<7}fz2O(}Is1*cp>_FOIU8D=|gD&j#E%n{56mdvMFsN$=utPhd33jLv z4uYE{E~++m^<(M5PO6q1WM)2wSM0(tF@DeL-mm|#0FGl}{MZ3lwy5-12UZC@wSc%{ zV^&^pky%XElI1c$&-N64^arc|)^(E0cbU1%+-&%N+!fPpFNMXGgW9N^)_SXJQm34X zX{VGEyXPM5B5lCR!O%uXhYZfb1jZX9%q=F8laOwSK)o~2zKXy7-}H5~&q@v0*RNV&|7 z1NrG%jTRc8uWruNwgW(A76n^J|#hnv&Si?>CZs?rv-5}}t2#}2S6xzP}3-XD3 z3N!ym;gkWjRpu?JG_o75QE*k<5H7A+4^G6euY=;atI>Jjw58+HfvsEJ6O?v}I|Hs< zRb0>&L-t1na^Qy8<^u({&l$j4EbSl;YuGV5+wFQh`%hrTzS#A|OGFo`x?5dB94-b6 zi>F80hJfc4gU#{zBEEf4WZGHHNtF zs=UxL@=N;9Hn!5_f{rW|>aA$gYc(#S^_?i~(pcf5y6(MimNf%OQ#148F6m{<&n|50j z!ie{UX)_`R?YKIfo6Dg+#W4OKgyl1$A8wJ>b6dF^uBZp?L)%LmlWJ#Ezx^lzw_ z@(r~L`Op2H4Z^aS(b|qaCgJAgPL~SyMsW{uI(h_p8FZP{BJ$Le!Ur?6@ZW?>GqsV$ zkkftntSg@z3(`vkPl<z)=E;-<-~CP)=dEwAB$}pEAh#g+g%wiN!+vV~My?nDAIE)g=jY9?KqI z(GWCQ2J1_=no1)Lj`ZnQ<8+ymcyTt}tN^j+_0vQ%^%Zc+s)mTkdJr8F9O0k~l8qDY zJ~rg3upS0HUi}`hV2U>+Mm!8s86(Dn10In^81Zsrz)XiImVs~#E+K@LAib(#FgIP& ztF(3GACEDS{~QK9hUAvm)j5p^d3__LVZ?ns+4_T4Rg=I!9tSR>stwzZq2yDKD7b49 zd$0=pDw)?#@Qk=tB1HZer>y%b?}kj@$L;T~D7cAP5x=0$t}01{Di@hrs7hwv{5KRq4@wm@R;?12|O5I4+0 ztRKSMxrqG`!ix|{;mCQ2O@w?3I?4gb42kr5rk2R#j4;2gwEG26Acy;92`!zTN>WA} zDC4f=6POg#d8hK)O{ftP7Csm;+DcGn5A~DUHj2LHVze(7-G~2|in`!`ZIS4TO9oBD zC`Mc(FB;A@R#frj{0Ing)jXvr4Q-$&_X@;DZsrfGNua zfte8}g6o#*bl^Q=#IL1`pdUYIO1Q|>q9ic#)0=JJP0I*?RwIUUB(@Qh%{8&BBP%9# zM$nX2aR?3nSc(I=`b<9udRz=3#YyL2Suy;E)cI`XHAz!9n>%b8?ED65?1W)}zxIO4q()Ofxs?Dn7m~qc zAUXetDauLE!_w1S1hwG11(w~iewbg-%d~VBR?7C!d#M@>6cK0t;)3H7_%d3&0xA(& zyygelCcWBZ6y*Tk#Q@Ic25^>MiIPWhBic~r80Yf1(GErM>q#Zk_|F@6b0NaAIZ1I@ zli{?l18`kV7`#>mvN6tj(a5B>)=w9X&WW-q4k_O7dy@MJbSk>z2Jv&P_A9E-xX3p6 z5_VJtkh2qzJ_+H6!4M)Lzd@e>SJ6CR&N#`;@N#v#F*)QwRUAO`QoeB|uX(3ZuBg z&ZeWzZFbV^tN&@Wv5ySQNZW3Zg?1Qfya3L^8UDYPq3y#!0Xw}cP@o11JmXM&I9NlA z8o!KVwDM{>tk&22QaQ3}cahSdU!Qej5j3|HO3!Hhsy-oe>P6E0i|}l5ly*BRz^}i5 z16SI84pQy?!z{H06P?2>drae<*QDLYNQr{>kdWCNn1e3#4^;S{{#gYRyLWs7D>ag= z)PZ$6r|;??1AB2wpIEmtZjh6#WW^y$JCI+}M*#VtZ&2W%CmSf1j!h2&(g-#y@dNN4 zrp3ekFPpAA&H<1O@1SB0C~mHJ zLoKLI9ni6cOfhTKe43RKtH5$8YfZ6gc%pjh_qf32XEL~8{SIql6|9*yh*!g!0S(M# z4UfelVbBv=JYN|3MAV?uJyMTrHqI5wo*Xyy->~}_F7fgrQ@`g;FGDbst8RleBmCn@?V#sqXA8+zGq@F&TR+FY z2l{e~&rkoOA7e+6P$CHFd7pCL6LghlO*6J++d=z?r z+pd4Lh>NI?t*;eUiBp9$3v=*8f@k3<-8(RM_nk73oTfsZAK_+1Ol!w# zTJ+28e`E-xx7Bc6oB2bpnafLGxU57KH#e+}MG#uO80*0XzZ>ldw3k`G~M-F}XYP9{m4w z{Hw(>%Jzf*;Og``qJxY>2jRlam;U?p#AZ~{L{x%E8v~BkGKl~c2WCVhVMu8Z7JYt_ z%7D~;KjTh7SW9>WEdJSC(Xas&>hsDOw;HsbSlr|%Y>504Xfi9vv)~7w2V8azF41sW zp_rdxP&Js#BLV%C11^x5fOP>c$&Eb9V6Of!kItYSF%WQ$+Z7DTcZCL&*x&IF;pqY{ ze-Xbbyi{Hg_iG;!BIJ%q+U%rQ$Cj%F zU-=~PzMb%leo*yi2Q1a(nmZL`E^spL-9bM~yRB%%WXB2~X>&HK_E0jxf4pNunxqjF>ohLimD@n=7PYxUc*M7EeAizP5;|ZQm{WG z-?eHmdp+Qsvd}NYt%_lP?iaxWZd$XjYGoSL+b`^2nK0~jKLIqwe;2Oz-FBLRSs{ym zHt-YI`Zof`egiJLWr-k04H0IpRM}+yzx=!G(i1Ae-ivUbXwxy`qir8X3Fv{dI9Zm& zS==F2RFkume!WqW8?5Ph%~m}YewMb`$tp;5T$C8Afrr{#XyV_!X~4gG6Y&byo{)4c zJL(T?Q+l`cM%3?yD>Dmh+YW3Cg1OjfVw?w-AlRt8o~bU34&XnmmuOkGK*!g>;dvjh zQN&ezz)v2uO{TU>A8b4D%*6V0Pnc#N*mk04SOw0GsDHzBU?aZru9S2PXMOEr+}mJ# zX8CqYk7}~GA`Xw;2q~=d*uR!k_Uz?DfCOkF%Bu@e%09M3AwP%L~)$Se~ux z^F&HQ?=w1TsZY=>F;bI#!onqaOfT58gtwMdQ={Q%c~%|czfA=7jr<_a&S@80c%$}B zD-XLj0j^X$n}J^xwm&BhTVZ_qxgw}Gzo?U|2ZjulC!VGe8^uYPWox4A`!-cA^KO zzc-IvJh{GCdtAhvy&)Cej_L8ZP^wXU z)jr?*s@n+L%Lv=c4sSNu)A>EpOic_(M?bl6>RKl}8F2b)=S6A1;mraHNavdc%bh4= znUmD}wGZ-DB$Wt+_)}M9YFVHLN}vC~YbXmIg(@?g>3m!TaQ+#>yk#+IZx)!Hv!o|S zDm3Z9v!9e0O^tnzB-hj|uX1TqM>!QEa!4DR-37w_WpTDf2h!{*{1md{9yG0XhKY38 zMTs|5NweBe`XL9_+=2Yi2l*_-JW$p*9hBx*K)nX>@c$%Q9JnMz2*ZwJNjjoLkpY|D z=iz!vMJkBVmx7E%RIujGS(>wws#-3by~Wy2oxK%Y+v|C%kKytf;pUn`UYBdld!X$x zcTP?L18K4eh^xM5kXseTxZea9zsD;+yQxH9-qJt%<*npLk3gC{llZNhG%D>jnG;I3 zL5g?|vidJ2>wcAXqqN9S+C60DMv30fbg;o?FEjVHthB+-IL32jWv2UWW!E<{_vWrV zxKL&J@>W=`(y~Qjs`G)KjN<}QnD|65VaWPD!~BZC)wm3<*F*Ka@0!ZZgjB0n!R-g$ z>jz+jx*=SFU})HMY!e?+qSC%5J#Jv2HXMDuJm@z*1o{hgY+e}{K)s&g-V}Je(o3$m zkp?OnLOCWS9dNvyp7f~ z8cRixo~_tg@l8cVQ_z&(T|rZRgV5%>I}enQ5{{!J>e*{##~>j6%~9E4ihB=23WQ7u zs0bYDk578O7KeNcN(EID3x{cn;94DT`=Cd`@pbR5wu67h=e|NI8C5jm2?tm2Gs!OJ z0rVgEmWe}9aNFaM)9cyq6T#2F!Q?vswDtW8q>-AIiP6aCBHUB2XHSy^n|sr0JV9~J z%J+IU!+Ayg7rdT7PaZ`T!^-%Jvkm#Ghmol94sol%G*PC5SG}I+e18z#Qt4GGWq%bY zYU4S$$|gGcD&hY<;k`AP_+8=rni=>7VfYJ6q8{s$b7CE^d#xK*H*}m)#$HBZlJLO` zdbrQ?{R@d~8X9ZjER};sKDYz@7Ih{*WjUKO;9_*r7BbFNN?UOs}`u*Z%ExidhzAnnN#=*t>_eMkQ_*Ck1v)lnB`oyvVH zsVBj`aTr6d&2zN}uFBHnTJuxZvIY8u?@IahFK@~9q56&BSMhcoN*-?oagRv3uY4;F zo^;JMIf?PfcN=nlgBf6DOI3L`lBXw(`ZZOmZ6)bf3PV+Oo03`(|Ss!SH2q51;E3beL zj<5AZPpHAtc%9wcDi48ML+=PLZH&c&uy>;#Ckss*W2v9|gv%SJD&B7*duNG|wP|9w zxexSX8ghM34%b?HJmZAQO<7M*^&>sF>OK#5M3e8i$c<95ArhqK$jQ_&dbo}c;bR*^ ztQM=-6v5Zm3E*`ewf0DXbm>w4yo6fL+(O9{8nI@Eb;$F2YvS`UTp8%W)2%bC3C~Ne z8NC1BsQDzc`K2)QWiw6`o_N^?%I&K!kHVY~`AS)6yN_@~`b9mS5Bi1mucSnI`~JJ> z2X3869!_X}B^?`uj#q|j% z3RN`S7P2Z8V+t(GL46r*2B?qpJNdb4d?B3AYCLEfd?lPu zZTvkZviLS=*n>IIRmIc!1F5i*R9F}@y{a~HBt*3BJ?} zWbusm9nKosGZSI%`6X8Q8p-oTFZnb9xcZO{xFLr>xQN(-avYZ=#(=a5MX-5U0H&=) zeN9^35?eB<zwHadNc<7xb<9PV5YFr}9N==Bw#U=rGXeqEgfY9QS!wmO$-t*mneI6|T6aH!W?Z6VBXi_30ggaZ{ z9R99m961t(KTx;8hd)Y`8rH%V!}myZbF7jFK9FItDRfFr4EWlxMvrIXXa4C5G#EZZ zGH4s9d>|&IJd7(yh?1~URkt$s3V8TbH1&8^`tP|Y3vtX-1K&!WJPGYZ5geiwF>VDEFORvbu<(^N$*R9oH{-)&Ir4YV0#x^}a#F}ko zc_TQ+RalGQqBLV5TA~>9_rUr3Jd?a~H_KeD3jt$hE8H@!u}0LjN}-1H@KusS1?l-Y z*4#^nI%G1p`rgzW-U91$K*v-7ZTUPp&_nq=(cXWW_JFOJrN+Rj@_2^#?{pn17;^5t z4t5b$z#Vm^fdkVKR}LTCK~pQi1r^iT)|J-3K#3%v7*4y!bEjP&xk%IP zJ=y@aR=`zNlrpjVsiR{!(vin=uWtWXS#XBXv*L?KqnVm2d<1#-v|s%XgP!#IkE`$(2QqS>PBKB_=bqEQ3d>4FXnYx%O* zU-k;mVHb)De*Rs;A-&LS^;G(A3DC1wrLI;d?6(%7mA8#>zenr1tGx8omTR zZQ%v=2*auB@Lr#1q7b|5CA?kOyDL?(8oc&=o?_wKUE0`1Cy~zB83nEZ^G}Kmukf3W z5udstJQ_JekO?DknlMV3HVcV4(lyt(a+L0L%!U6S9r&=ZGjtj;W}}pItxa$o<=B5D zrz-m16?WqJ2F1ttLvTu4f?n(QJO)Rbyp^n5yoWeZ4={LMxV|R*COnq98<=6XK?a|j z0qr;#+%9+rcGNZ!tfj)Sy1TaIJ~y{xv)mWv z-fIfF>N@_Jv=UdZp^#&$9`cygj?Q}l!h4sH*5Oit$Py}{( zyC|!Czrff@*(#~L@%hGfx$)hOFa`~aulw1E^k3aV<}BFM;wx06|K9{Cls47*eJp_S z2mm1AVaI*_z1q+)UtA7cFq_2sLc6w_6qnYhLje%#95FcEvTx+RjX79f=j#{4e5!B& zIG^<)X@7y@0T9%={RKl&=OwUyyxYMt#`aKSvui7i2W29$P8j!kqV1%8W6XjM8e#92G1Lh5im6z4I7xm5ukbwaml$`H`H9;4RgUC z=T3G|VdZe<%T%+qL?m3r%D{&ohQ=wz>BW*6SI+EZ7CzoawU>sL9 z1ZmjGl4o=;(3i4TGQL1KN692{L< zsA%P9nUVN5d`<5s_@)Rro{J5Q@R^tgGSOLh-_V1gd=31Qd{C5a2Dk7~a)TGBDY?Nr z9j@XA!Ds!*N7&e69em|Z*R2YCZtTCGWh20n@2HV)sQvZ*G`0Z%2GPOb1u zDRS=C`v!7U|0^f>6sYJU)KM4Uo7s1(Kl&swTT@+1q(YZ7sku(Kvn?ep2;Nd3HC4p(&H zI*O<7lnhFUKH-}hjV%{0!ytpy05^3XF$ccDmTk#~@66HnY?1W6bu(%y0aie}cLY>% z1^$1BPh#Bn)WY?%T>if2jlML?o2E%lltkWE_YH@0HP?FIv$Zd|h32n(V*c4<|C%O<_spKS;UC@WMkwrewm_AAy0r4mzh=Qou(dPp|B(Nn`<>KLAxT;_}ry9{L`%U4;TAk)~ zp#L90pyAT~EHiD~r|)~-@e7VO(}vdY>rKHI;oFZ9>rL`YvXY&ArD+?OLRCWK zK0SO=XY{^gTrWJaFL87;2zE?B#CsoZv-}7jF31B_O$6fw5fJVZf+=Gbd{E^Gl#&HX zedSL99oQ-1_`c_GxsdwSauAwo-&zA-V2XPCEIuGyfBU^8rdVbP=Be(sg^}=e3i1iS zepe{qmqA`xiq5a~dRk5k$M$D{)$i*5twnhag8{#Zl#HLv?=;0YENQaVOX0!qY%g24NF?M5G+Thbf5d z84lhj5Kn>dA-tOn@d60@9)wF7aECe*45JYCjX>;95<`Gy(I&{dl!e$0@ctzT(;z(q z;@LTfeRS#Kr3knIQjYwx5fbLU+s6<;wd1qiQ(?jWev<9`C&B*(!ax~>&Ob6~Apf<+h#mAGJ#x|FzmHtCYRx3`l;lOwP2KYUZwwr73m7=o76W|GpIut41!RJubGq0mKzyzTLz>w$ZSRwzyuSivz_X@wBS1K?N| r&n-Bn8y6 zsKCMd11idcogt;-2*$!XFy|94Wj_kREH_dQ>pXEJln zytBRY&dj^b5uKF%JayzUg{y^jN^eUnODw(||9N6$tX8C{9j4kAq(vGezSkd97W@Co z8D4_KwLT=q^&xS#7m3gHwRD%i+0woA&2q6rcR|`bMk`|K48#|tZFke##@vHJ;+cLV zhCsRR`%z25FqF*NFiK`1AcT_pKR|4C>6#z*V^32jRQfl%H_%{Up^OC7vlzm1rCYQsz3@Ct-P2zzWXCNl&&DhsU;s}UM&?S_- z6_Ga~sU}elO@yREH&abLMiVp_NN;9*t>XcbN!5BR9@4^&sfnEa+S% zd43k2pFIQV3sMEajLFnvhy03r&srP2$R2tD1w;T42>>Y&s4x;Li2Sb#0rqZXq7mRK zlBpxrMP$P2=qbI~hjAUAnC3z)$VgQdpVFX6qY+J{XvG)`<65=_Ar8$@HKt8P9M)ch zQf8Zo>9deXDLW&vnzNFMNiKto-2tcA+`p7#OE!cO^t!h6e$EJ37& zNrA-|oe2{MlNFtLFSokL|J(S+plKnz-WuE#&!<`NW+e7XX;!=)iED(73Jo{3h;w1# z5`xWzdTODbYM{5;Oj2I>PI1h}HWDzdq+IkH=2>YmoSqv`yYqDObLvpO!~}0N`J4no zT>?{@P%hfDfc6t$`9a_kX5y$)+HEn@y$j7IiHQ>cT2+R$s*+$X)`G+%UZf2xp*bWT z^g=D#^HTg|ooF+g#SZfqkQPVl$nY2ZjcvC7ggRi~V9_tABLpz^yArX@5TY9GI{eXM zp5gtTa$&kMN|>aK#uFix5Hd8vjLZvC>SWDN|#DN&!l?)Z(nRZ>QJUqS}q8&1_*2;77zL`^p%k?$2KAnN#x(=6LO2! znw>G#xC5p8oYh4HdAJyh^G=`^We5f9047?)@>rx!Fk)Eqq^VdpY1$?&AiXjVOnhMV{|!|94por zUNuyrhFPLSk* z_^^b~jlW?@d) zQv9*-byyPqQn(eC7QS0b<>g1Jn>qehD-xdq$>G;^oB+4Kci7!G<)a8fjN&5XhO-D9AJpgeL-v4p=;1Z;FJF)_ArU;k96H<0d zOk#VW~E^5WatMgzcKtzZ-)6vVLU+}Kopht{ zG0uNT$mnnQ)$$G0NZ@hZorYbKft$nA+{hIaoEVRHt3t{^A#NNJYyI4c?+Y>(N?PQCHFN~l(0;P9 z*7G}f1&@-4@g=-kTWz4l7ktJ1Yf`O|7N7F*@zYLb@KkOdFYj81vG_`#oG&s!g~3=PA0 z8>?qaz-&xSbvS4-&xZ{!Es+m_;tOcsU-W(Bh|pCvr;eyYNJdM+wP^8wR^vNZfuBiGMxm{|)JwQl`Wt z<*0DZ`+Bd_@8M6}gw|mBJQ-yQeF#>X-*d=M3YH5^Q3<#}_*Yau&Jkjw)5e4iJoOZz z{GR?_%#4xVmfYm`L=SMh?1-V6K7hn($sCV)l>=|4576RxVOg{e_X=-CPYkvBnGTLm zwz^%ExK_9tokkV-1un@D^Cm3nydabeJ7;oUqm0MN8o&@Gwh7aRB}_K>E1DShEE#!| z?$2w2(=#{mjetkDDgZUYpW39(CEbq{4i3}cox=CSGKa18 zTk7>zj=#QWiB!W8ug{I>9rdS>~m0a;!9-2?vgfB~u<=G*Ne$A_#;)fjK}d%h;qFGlt?-&7g> zp7SRN0kMr#8Rp_3_kq5lXSX;P(bHaE=GWwk#C( z#KhrugytAc)batG%Z?4s=!A76BfVR@P;kd2;J1YE*zpgmVTBp$F^C3~s2D)pZ_}C(7kWSG^@pv=VsA0El@!_3FC)Z$3E;jj)4)2s} zC`cdm343E-Oql0obije|RqK$L?;Yx7Ub6xuk=s6xFnx3kjl?Elc3dXa?-SO=J%yJD z?zpTZtyjhu*CV$@k?~wAuO6EP4iUAgEF7e?hz;?24Z-;b9-)>&WS(1|lZ=`Y^ttG$~cV0}Fg4 zjBl6N-OQz>;xII{-{dz<;41((p9m2NBf|d}K&ihwZ@4D#m9X-z3gZ*T+Bybg{3}f; z!{OlgAh!xbpJ8M0dv^N&?n2rj$bSs{?z-6YXLrO}V5WkRfV6*htJXaGw~f%3HQlOO z4v0F;hw2!9h;l0GNlgma_pf^wS(aP(S&mw-Ti$h500#KJ=n{rMT~BI*T1@MQs#y=! zAa@1D@zJ^8-$FV{{K|`V29<0x;kq8@P_?885};7+P?=gtvHa(PIdNjr7+C`AS;2Hq8Vn^x z>*ZprBs{3&@iJkTZVq*&PmpxkNzeM4Z?Z-#p7@LfQTfkPAO8q!FUo5SnwkQ&%o9qI zCsMrw!mG)nnL*Fba_bCehs{-+~M7q#FwmvA7B6T;FH zhvC7FXMl0^aZCN4$9$HhY`xzzPsmT7fFBTEN}rDX!uRPhiXuJ5^SBVC#7Z-jg4XfRcUJsF0sN1{DP36kBPGP=Kw3gX1JXUFpo!IvOg0_ z^v_2W9F5`^;$h{#&Kb=NyZ8wmB{=n&Qr@?FTu<*wMIIQlE}~puBVHh~_zZX2ivVbc8S=BWs+zbgdC_AnT}uiIkJq(TtR& zTuwhJXI{Obwq5@9N-WYCx58=E;`hAX0^->2j9JC6s(V*`T`y15w!vZL#qKntvmWc- z=0m)+XM*VzoY5(rVX|KudRLIe7OyEYYwImJ>H@Jjjlbohd$%qJRwYNF7ba!$u@@wk zJ>4Bjq!VbDUNyfvpQcw3X+_|M4=-km9TJn5U#}A>`ZT15L{XA$hBv)rxKNCUH6=~J z)Nojw2K%YHUJd8Qfamfc?6=MS->Mr0)rjE*^s3A9h}Ph#7bP~YT@liHQDQ1(TpB=^-=FeKle& zDxIt}YQC&2V)55<+=?f9oisP#v7IFC8$)Si6gea-m6xgJM=W0dUl7lnggS(T(FwzU z_UjhMHRUz?J>UELTxmSn)W07PDn@4vuWmH2X80fFlUnK3_m|AW^C}aV+*ZMoG+bb^ zRmC}_^y)d7>M}>Et#(C!>&D988wh$gR&cBB*zXbi+-iLZ)&jldtub=Eu9Kn(%`Fw5 zhTOmU$?*3zm0H zFI>&6mWi}%A;y{e=CIC47zA4>RE|k6r>=<2IQa+Hbcr)!L%gNer6TR!ZBqs8p~c|$ z9Q8BWs#OcR6;V|yhWMmYr;s)Rrr?hjsWEJ^0?6mlrr^~Ep?=JSc?UnMTK#eC((YHI zP-fL%g05b#J!n!~Q9E;9Xjjm!RjbXSk*@lSW_3(iDL!A>6~DEip=)1w(B3kM&L@@<^&uk&zpc{Uut!njL`G*((b{9kHKyQTyvgXsm-%bq*^d>^IU3D<*2oauI_HFg`UHbW72xuxvn)iBh#a zg9~8Uq#Cul4Z5D{DxJvCx;2ze_pIMDuHOhNUQz7#_~7Ugi~OF0a3m9|aD;*Y5C$A8 z;GidLK9K|>r!oBh7mcrup-7 zd=VsAVSLVHTSWhmLJl?`Ppe;Y0cP{fs~9+DM4HnZ#Wi-+yY;!HB9F-__tXGMF>VX; zdmbOy1_)W&eTH5K@isu$Q2GS}3>s!7P8Jtx?lI2Pt*LrBO0Vsui~0mky(JThGeFLv=?&-IFIchpL{?_P&ZM^(J7~GJ!yw+W2W30 zdAMp7(R5P!DLvd_ZRt-h1H%t`*}*DvCypZO+{7~NhA5-5-rTchxo(Zk)edz8AO8M^ zW>q=VDnI-qJky6C?L<(g{}T-T@Bie~4ehGwkn8z`wAf?&WT;8;lY2xo*oRVWJ->aT z+2C(blm;1->PKF*yXPrxh5THXqTdm?UI@U(?bpr z=yIJg+Ncw6Rq1*89!>kTT!}E%&38P0J*ueu7N;C)}V~Y%Nt9vX45pX zd!_RCb}tHayEm;|J!PG-IH*32-&~}T1+}g%ITzT`;uh1k`t6_;wE;u^w)bcGoYoi1 z5}uTa;mRhrJbcC#S&tam(2K@^a-*i9*9h@$i0xwvonLkb4MUmvj%(8Cn)s1&pYqjz zO1aC>7^C=9&0nQSdrp9k%qT9X`KM%9_7Y5^NUNZub8C#52YH1%0Uc;57mdM5UfV`D z-s1P%@xIp;3~T=v?_XifQ`$WK$?i4utB`&vaHPDn0`K@hdQ=6+%s{-3_9<)0_PG>b z$mUs57H>l0;u^o_a{paH`pq^4ZdF+$Eb~|{yV8Y5@zc5$`Cu<9?<|U$Bheg8Rvy(! z+gP=T!;?ViFtKz5Z0RKuWmvMx1WQPyE&3>DtCXvmd-5%4WC1kx3dAHGB{EnB%AHTW zOMqQdL@imN7O8OBLFv*x( zY}g-4q*AVgjCl{NO41CRAKtHBL-g-(#&gIQB+9x_&}HaQQ19C>W;gAWWCqfy4G_1u z$ZAHK)B?QO@2QbU9^OvyLo{Lp!td$rJLI~mK&?YK`Q-*nST-A+59C}RX9QB&Q4gFG z*Q9ebpmbDTlg{or;I_zcU7O1rzgDcBCk0hgUghm<6SY;{0>=fN zWE=q$P78Sss_rrG`rGlEk)5>skuvO~rh{d}iglK(GARh~i_#wmV7NkW3k@J=uJ0|_ zA@89z^xtSrU$q7J)v3ixy9*-^t^!6_4HyYq+D+3~tj77BVG+O*tJ7B;TydX*YGrk# zdLM{2`7mm~XN*r3c#|g&Yo+VTny5PRo^&b?OkcU6x=A$n>;Vv5M^ufhJD#1#V&PTi zoEt-^zYyqNuv%(0GARv@65g7WnQ(Ies0W7lsKoNO zEJSPp&cB6_MRlWIxHgHiX|zD9`O4R(ps*rgDS!beBqoUPL2e1)ErSOcluQrPsHPNc0WA=C4|AEnZl zhXm%_mdB>rb&pNkXR%$k5<<9cp#kKIPq!H9aXX&uaq1Qan2`Aomd&23U3?z)y&>5N zrSyBw`SvY|CVX4YzA7YsBnztnPDe8dmv}Hs<(BwUx_3smI_nfX#?AOI(OqQax;z)bWBzbf$oj($6KA z!~>MDdP=NqL|Jt4&iRDY=33?~jxE)QwtP*`DhwfCBl>ZW8ENLuA6B|^evNjgWzh4} zAV}?f&v68q{hk${5kqhAAr^%|2>L{cGWH{u(6|cXmx0+M6h&ms4k9j)0DEKygrNQ- zuC8sivn1F1JYudZ&KrB?IhJ$r!=6Zl_Z>E6A6>Gw<-5RCb`lXf)ue^Zr> z2lcazpIVPUgxTxE+fnMp7O>-UM8C#}6MZN(1k7KIIM<6(ff~5mptB#8gd_RtB;iDL z5iy|>wLfbO0gdP|$rLZ^q9WlK8FuifD?bV6O#nV_tV7`*Axja%Wrs~;+K6T>)8E)@ z56?bN_Je2q@-C!Wx46GvYu#u4$dq>BXRBZljOLNk#`>$QEO-K7x+Al*Z$o#IEvqpA1w5 zNZbIHOC=zdZ5;5t0SF~)kOigHrc-QlUL)3m8AOu-^-+YT$AYQHZ9t2v&fY4_LE9!t&CoDNUp8LskY~f5xW$EeimX)i4hW>NJ)4K z()WS+o#s`ITkC@gSWr)6!)8!QBQ3|rRx3MH5}ry+xD0`^&lrpIfC6}UHxcQ5&O0ue zkL7Vr#7dOrb*f^ki&TwN0mGLiZZ@%wCs3IN{C=*E>$w+=lQjXMu+ zxP_-(C*0}b;m!`(9KagYs_VSI5;QIP4_Zi%llaF>1!67pF+hzDzYI{w{m5EqcEx^p z^HjLfxldNy0^M9lsw6d{75@V{R>-mZI|r>GIrfDcAg4N5^i>orlMOI9j!ZQ3c0LNe9%QJloyYK&kqMI)%K#}Zp=!~`wP%0 z0?9b^))HVt@wn|pq?ltBya8|dJDh;D+n?7C zokVP#>t}g!3(mRWBG_Pr%|#42tfgC#{tn*X0dpj-by5e?M3-663e!3FCwL7 zJ8cT*(RfmYY%8f4SnHiQn||jMj5LeA?y7hXvBeOkLO`eeerQ0I%4ek|wvYyN;9d7R z#H8GD7?IvO`6@LIG=0jUPMs^%TQ!%Xd(dNKLZe#>HH$Rci^w!F?OA~?Ub4wETfcFm zpiIrsoEtPJ+{*BjD??8V^gGCHzUh=Uq7KBX>~H*9}hBx3Fd~8|vniu%afuE^!8%RuSF` zw8=~@40ZAaM{nRM_o%$6aDSIVey8nE*Jm-3i*zUk=ohpLV{SU|lpC;$7lt!ETonb| z$>Q*p&ZE8D(kdrec(CY{-}09vMl}y42iOzlptLkmrIcSbno8hlepfzDf{w?)Qntw* z1a-8tq7#F4`U^XIC`hM;gKBIa6ZcC40m0jlc-)>Q;-G@UB-jV-w~yHiZmTHR0lSr* z6o_cFGfj+8LY3ZFm~$`{+Zn*plLe7dOojpUEAQCTdrp_8i>e?}J{FdyQT*5*3yK10 z{-nu%`>fp;OLsA>uVG)8TuG3+z2jScpA66xT;AESY}dsFvbt8CY<7#W`*aqB2-IL~ z*y+O?>~Hh0Ikd7_E%t`f4ZW^paX1sCOY*J@pi36O7Dcc{WjNSFPr9hOxRnp; zgPasFsgz*0##$9yF-(@@+*Gb%}<5~(PMHqCD&V{TPigx18e*j(kva@Nrzu^#DaQ8?#6+9y@u03#gD05 zGBush8PXKlKeiWr=c-B!`zV#4;az+C3hb(pAckx&`ubjnCv7iUaR09cK0M$@l6gxq zNA;i=;(0kA&d0at;1nZkc^G(2{j$;kzHM6G3>@0?eaiG>{KNp1@`@pQf1ymm`sH0L z{TndYAegKryBl_l&vv^W%Kp8yT6;49Q%WRDe(R(Io*G9z5BZn-hCB-eWcY` z!s^0PF!%27lZ1$w6Cw;{bk|q3@H=|R@P{J!-QUxNc{Af|yTM&<_mSzpse&2NCoKg- z!+IWVZjU2w;b!pO+In>cKaWS-OJIng?rPS4YsJf8!~u&ac)k><8aJ4tc-j%a5@(|f z$*GQ2HIuor!z>NwP2f|7C1LX{^@JY3Qb${WE67!M%v?ONiHK{}R!Zz2U=nX$zU@-M znrQ4J?m!QK$tCnMfh0oCH^NV|vhYzMYPKe-337Tae-Gq;AFm0NZW4-SCyiY1?Ot3~ z&^`Z;0CR6>8uV%4gmY~g+kE^zOcgV2a^*2 z1nKZjJ2)w6|8RW?%IW8eos3{1d4V%RxaUS zCbQQGUjLlV0`hIZdaQha$OJhnDLv`XbYIR&td}{7iM9D=HOM%}PZFgJX-3r;F;xfh zLV{y~HN0%=L&N#tK1Tc(XmOtNGvZGYBfban7bC_3>rUhkMr?0VfsvVF{eH|IfjbGR zMx+a#I!n@V+IsSj?<;_R!SYaa(C)r$-98I|w+O2qinkpqd-DiNQShLBUz1QxzttwO zP~VHvHR;&i@OtpftcIMeFmdC)k=Tm$;3|nZMqJQ0svi76K@W$-C)OYsd%mC9%m8C? z8$@VEH1#ocnu$sJn{9aS3<=aEEl*b>b}fV_<{ect-R;OYQN|Dpe*t9 zZK;L;b%WFc?prn1L?#v8{-fsFO(fF6VG+@Y(JTP{oqv!Nr|4@gM)O$loxp!L{6AVO zy5duSKO4)44@-hz_b`Al}4?MYMN3O zw=$|a|8^uzY2*jcsE;Kzh}s7RN4ZeSX;&qm#s|A`FfB^{A7HsKVvvLlHlsMbhRJoh zvY~hL16cS=%`ou1HHy#H=wqNs)kYJ#{ZtL8Gi>O#wdR`i_K`XKN2X}!IVkaHU_6i1 zBsXaSw%0^!tR)3Z;3)-%Ov9W6Pb@vvMQ{x6S&@E^VGyVUR4}J+n`^O-VBT~ zHkT9drX_+j&VI?rq_;Ormvn};og+r|IGM2o{|8OqwZYULkpGY0(=$K@sG=|4ARe<1 z`{kR@xR6eEKqi2LBRI{0EM+JCJ_~8MLu8k22bW*}J;G=mh`$SM^LtJPz#9VK9|yn> z0r(n)Q9NL0fePQV)8fW|7d;+m*hp``L8^Z%0KW|&QvVI{K>)%|zZQU47l2r6mwy-y zgOBsect#`JECcEk2GV%B4H9pX0-zXQ8Yu7-6jNfdjI)K>bb% z0Q~a-c(nYX8)W0VAK+)Uf7y_jSr99OXTZYH0reHIwxfN5|=v&MY3mnAZ=I|4oChnyx#}15*>3^Pid{ zhYcVdExh^b5L5CU(2W)7N~nG~wtTNQw1l(J;wRpaGE}c7M_qRCG_yu+O}9|63xWoy zJ=MZliI!^6qdSq;TnuhkzX18IgDN^8UK!YpnW>x=i^;;Jhc&thP>Lo;p@C@blx3Vn zZ5{M@`mi?Ct-u@{p9_S9M>Muqn@HKjvg$^Z%C@Na+9R}hzc;Q#4!9}>|Ixgo>Jl=l z07yo&-HyDqMn@ z?=|o&@M6`_`vXnoJwN5jrh&`}aT`!)3mFU<$SUZ_s}O^lEijP%!lg$vRJSDbKa!2Z zgfWj!jLC(qmEn^vFEkB${^@1zG6l3q32PtKgwFH*8hH_yi1QMi$OR zq$}@ff0intz<$cZHIuiYnJt3su{!*iu;;OIJYH}=X2$b`v6j#AF~MV*4qksH^ULr- z;jQ`e_51tC%{uA|x0n)Fcn_OyI_V=~fLB>-4daLL4=-liiL4Q@k|byr=&6-l}_YdlBi5Bnj0EN3$pTCR+D(DQV&Tg~e5ao)C#R zFEj28@J0l-B9K-?8c7H&yo@_u9s%Z~KJa5S@FdmaAA(5)kHtUyNRtOOH})fq0pj|8 z9Z2Fs=!QPzV=&(&S#ZfR9lq0BMiwU?T;7iwnwu8AEypq<_j#vmd z%k2t+_X-HYcI!AiQ~1I968PYjEiO#_d4Nc`az{SD8wf52P87dK?hjmUsR94PLyO~u z%ZrV8tq}L5E_BB!aG}%Kt$xq8Qb*gs;Mr7a^Pup|vm>c@eZpU#%}yLxjM!h71H1DaV#fo% zhw&_Ea~JbShs5js!i{G~FT>H@!3*%22hMpU%ne8frzm{cP~ zOUSI+Hfd$W=GuSOzT}*_Qa(|pN4LMT6M>liCVxUz=>=d%lO42P@4%q@Yq4iokvOMc zh+bi`Edx7%3-sG!O`3J{N+fps?zm8zQGCPxQ-cu@I^F+=%MQ=4+Cdv5&EjIKG53QD zr@iciCj-{M;B1q28@8J$P7eHsY#lo(BAPTrGNbhn5Z;zv0Jrw0b)xU_)VY2Pj_ zr{-+A#mJglaTscyzRIHaodX;AuIlFakY~XX{JrG8fv9VBWPhAnEM^_ zL+<9Y5LuaF6dRJKSQ5+F=^)sDGrl#x~cnR8-4e?pWGWVZjA-nx~CU>xFrR zn}xE-n7xmql%;S75s5DQMey*7vK*5Z7zFz^X`w+_Cc>3eBwmK6O31kdt6-fp2keu1 zM!#ptXTqUp9;6TZ8U@)>P5OQZ(yQCINplQ46_FQ-AvOREY%$jlb_gBE@0aGnlY3C8 zSUQ@*{epd|L)iLMx@z9wJ?A^S^oUAw2_v6M=O6cB-8z^pm@$;s3@L7G(|=d`V89Pd zKlle+k^Rm2-#H~dfUfu%d?w>h3EwR-*z|#WOla`lMS*S7gMqE$K|?QG!6H+3b3g=_ zKXM0;Tw#Da6hT-(x*=-XaF?1KQnmfKBsW;}c`X(l5-v)cs+S)9m&6eATo|VhrRe>yZBB{Y`tH9M`b*5!0-_n~wF3wBYQ>hQFHjuA{Di zOhfNmhqJzNG44&M-*bWNhTI(9$m9FgNx8E*tUV~nE#FG2>WvaZ?h|s6i#Hdc)LoA6 zUHSE=mzXxK-86JIV+SyvEwIm@dpeov_t^Y`_;kGOp_c0A>LTJh_U4gftpaW;$_^k+ zpQp-KE>bK5LKO|}rC4dcUCDhfsqAv$`&;aX-`@(_(C;}l!0>rZa1%%-ug?Xijv?01 ze0!>%oNI5(=JI`>DZWs*DrBAXQ1xdw!%_H`L;r8zq|q0;#L`!6kXR=@W?*$HjTIKqN4LbO=fM>zLC$5JJIPkHU?vwEcfG7J67$gP^YQo!p zQQHjtR#2`S1P}E90N78xp2q%Ec$zdo?z~+A;OfQ@o=Mfi;zDA4DxEwM4V#t<8$m)J z0<~`p|Hs2P$5~BfZ#NCEmad@G@=hb&)G~O?dLYmAg!`%X!dyMgLN9I11``2y*&8s9z|4A%6CqW(f|& zS61T5it`q0zvmXLHsY1w^*qsZ7*&s~vbN1J6sYb;Vxo7rTLtD0@}}R@>iZQIl2m?G zO5I({kKhwPkqEco25R8{1EJ}KO#Hs!dSND<$`fB)GOThy&WrUZGpT*;%EqoU;c=Id zI8r$Iq7J7E*IrCwGvMkI67irQe<>AH!kCxRY<-?BVE0DitpPF{*?qr&$_m^{{ctB2 z_~Cxf3;jd1zg%Aky|0=qNg)U5}5YmTla4{rQ|9tead#pQm_qy5Or zr1m;CrFJ`vCX@=-Gj)qBx|%LmEwJN6iFI-?sF+@l6Z9cqoTkCy%%5YnAn_NdfEcD( z@Yk61nIOFc##|w0)p%SiOked7HQg(Gv}z5$C1k$*KQhAMuM)m~ISCgDw_bh(>xH7# z8jAJ_Pp)2t8wJ*)(`S_|TR{J>V5C+IXBV z#Mw1ej90kdZp7h&%|0sem%jfDyuLRd?%U^MpKF$W181IEUvNXBd{J5oRzHY&OsbKTjTXJ0poHe|GG#l+eDbTDD#5y5 zbp93B)MUmdUt!3-1}l)29ftp4*&$aUIP;5*uN)y8Vgg*=_Iob)n8e6-`Xjs}4?3OQ z&m=0_i4N)VdaWo(Yr||Eu#jYcC*tP<{uBTXQZ4j;3CNUwj}vn9Addn3fjTLGm3`}R z&OVr>Gd|)FC*yr^iH?-r0cC@rEa+mPnLRB}S_Oa<0P>SSEkuGi2erHcidA3xvAz&P zS<`iPeY-pu?g#A>USAgn9Q=ptbXX&Nzb=l-927d&RVbKKWZgU=xn~tqyv}T=fRymr8jVKS!|4&hPbGy)W~!zJxXVdYtmV&EMjw{ zwV_^+RHq|WZ7P&5O}B#L{q&hzNHd`cb2BZ&pVwQGo{#0LK;<56nQ2LUUUJQ}`hP?% zxt0y)IE47WzEn0p*fsn_#ZZ!G8$P*N%m2 zZ6DV@G`R#w^Y@0`^^`57jNBUZd8oimU~*1p0~)SMKW!v8vuR9(dC9Y-ncSyYDpIJr z`KFM+ex_}jFR29QK4S^9ekq066Pr?jC>IZ8bQt&?xZ}OUIzx?HW2{+Cdri?-VytOR z`(vX@esih$U|w|9TB(AeR9I;m5Js_A)j@Xs$c`P>cT9V`FtxvnV)k?~c!%Y8r>uk! zkHLG$GV~b$1iYCzxyBf{KphI2ZFBujD@wul?X>8uQT25o*`cds@AJW`hna%h8f#F& zPK()EXgLj*-Y%CgYr`bCnY?8~8s+U1KHH$i*M!y$S++{x0Q|pAD9gOnU8Df*`c^*P z`oHtta=6>l=eg5oFcRh(Z{A&x4@jQB3=m#R@^AwQ^=7Nyvevr9B7Z@G)042@AT$S- z8%X2}i48f&aT%B&Sggv#2QG~O{kQG(J2COa38jSB$#*0Cn-9$=){eh}q>XuXX)!E> zt8h5Wfi21GFNO}>@7*RntU|h^w0#RB+VWt?(F68+cxOSGUplTot+(i&Sz%l@!*(Pit)irAemJ*x zzT}zMr_hCSy7@#J_jrz<^3PD9-i?H3XZS)jx00$ku^Qk*1_Xt`ih6m3rM7JC4d)%zd=lO^C zL5Y3)+rp4G=KNgHI~xHf?@PH5`@lavaB9E#pu~VHoia!xVocDwIQFul*gCZZjhZbf ztIsGDpahxK!dgMaRWPq`*@fe#gYbquzuh$B{Jt&}O!GNSwt0Lmuj_c%DG5mu?6WC{Uu-Qhw6hB>DE$9kyRmL#YD5&W+BDb zdCC6^-eab%jt|`|l?5c_@yr|CNSrr<4}tAd*+o-J!1ol>>6Rs=1K<&Z;d>U)0mJ7m zb3pMFYc^RfyGTv5yqW-}uE6b6lscuydN_+G^?E#6gISPccA?})T;j11s}TLh{Z#4+ zVb&YP*eC3IBW`S^x!6L~C4@Ti8qMIeD6_Jqmqz^Rqq5YzqD)bGT78dN;Q;b-0G%iN z{>B{qxKQ+FW@!0<0^BiFaBlcKy+X~KBk*Kl$D3u`G_N*b=|jdBtjmsUi8oms_5Wcon{E;q~l*BUDw7clbPW1@qRI;Y9d+YntN4<7}hPQzf{!YT_P0 zj@0cU)|I&HBm_Vpm_t03$GD$0vfP?+=c7@c*3y ze`LHJGMxj@6qM>{Z-yf%$Nn8TLDAQ)uw&0RDn7;^&X$-Z=&eD|qi~$b+u>pykGF%4 z{4PW1^GuWk`L+ks_5+j4Hp<}hGN2F#>)bUjVY)n?`EYT1>?>r2k*(hc*L+{uHh$Q( zrjOlh$kVr&f1osFJJQFtBk^g$xh)1;gsyEGTrPyZ6$e~Y+FNO{+x`P9j+CxSOvlw* zln$=-775jF72Dq6k$#$UgJ~PT_)>#+&FvZW*h_VP;pQ+0S7}4MRDXUa9k$I_-Wgx4 z2|4AH?j(6Pd05}@>+s$z_bJ>vOhK38yJ%YO_8aVCQq2yN@pgO-b$?aCyx9E>M|~1} zct@2}&`B2{pThG&0GeTt+n-|>gEDG90B}Xk!U8JK*eN&u5{E`6)L%3r-IuqJIV+&x z+-Oo>LYd&(C;af&BwL?-UF>{l4s-ADD6_)>a1UH{QBD3IN%v8@QQT_Z(-nfD!$r{5 zK|GQRsrPxh6~3qlV<*lJ^U-3h2|mEng)#AqqR!WXRq9*2nO8!00a8@>R1pQ8xB$K= zF!+8Ufedsvi#q>)A+p^*X=nNUU15x|lQzEX`pV5IjvBRIMgP=JI)w8odazgC9dGU< z7%M@LuJ`qUBQ@!Y(x(n|f%Sz!7bvg%c5t8@tlNK|U97d&0xDjyA8=Fb{DPs*^oh!$ z&g3Is*x(z`85`+0ATRf+^KTSBd5OxKUtsKHjk|r+wmn^8c#r8E|33fVg_({=>W_A@ z)O>h{y$X*OI^s4anE_kN(8wXY!X(peMl!`3FWtSxh|TwKc60~})v=5!9Wvv!_RLtMPH)s zpI`8GEZ>RvJlAOA#pROo*KeqK=|)-Mhv%ERD0X32NEpuB=i>QJ(8Fwl{mbcc@GrTj ziSrAxT?St1B1B>{xyV8%x>{AEl2cBVJRkJKHdOT*2mZdfl4p1StDNN71$-2FJ_}z* z1CB57IX3uS0f)rT`s8rk;Kk~8Yo!^9AHrw+F2R>Xz`0y(X@XDm+?9v^1@Bw>5Ww$; z|Dk*VoWR3va085d0grs+Z|DnnGvGQg`RJGmz8Ht#3vvf$XnR!f4C2ARznG`(u?OBj z*TLtVd`XRbLkwAvm1vQLl$_%l#CkR0`YfVQ#4tVKhLvp^P|%UH8HpuOARD}J%fZm6yoV8w$c*D7Sr|2$tmNy?J| zALoMaHxSGs6?#}#CN{=e8D3lVMR%|~G9;I5FJ`d7hdyyq1`u=mg|?lX4N##a_%5A2kM6Za(Y>o@)=`2*@>KXnL(yr0|56|3?s&e0FSukp zeaG|pKziBRCX*8-leZ@ZM#6!cvFMJcaUi7_KGX<`l4OWkpAHO-Va^oMPif0`nv}xQ zx{!Gz3(bd2c`X^d5(sVpKrKy=!v68m0I6!rKxkP+X$DYwEL68)0BfR(eV(KNN)rij z91%%D==@~>)EEO2m=SAp@yO3X^MQ=05_Jgwtkc@whcn?*2n>7}qtZ+!pA&7y%K2oL z+JH`}L|K`vIHZNuVE85tL&aDa%^lCeW|F7sKpn(ATl za3Dblk(j<4%P~TG;8_9BB!-Wipj{9L-OX3RGl37j`y6sN4h_UdPwmxWn=>7;i}Z*s zgg6bt;xzacU@Bt&1t9{`hv8iU#3>LSxf^z6f|JZ>CR+-(XN?_gcp`gj z*4VLG3vw3aBBA>IWSjp{81-XAEs&CmyXmLrL+`AJ4Yxp#s)q8vUWC~E1w-jE3m5%m z%!(B+@oUBdC5Pv}7Qbh^0fG2Gsr%BuV-%0V_-}ir>?|HsF&t&GD z+1`0)=ACz&V?RfUPU_fY3YQ42RJtv?1Zkr!f=PRRh$Xrtx_GN8@jMcPdXPBLi^K&z z&0VECn!A?mh$xBV^&+Mttuq4g4C`MxNaTBw=!F_9dd(6Od(kyrVnQGla?zC^g_2l| zk`O{kw?9BE1L^8NQQK_G`eQM?uG?Wj8b{kEB za!l`qhl+#wYKTWcY!WFd*qR$iVMswskdtN6>0+z~sHYPZlu4v1QkN3*D0Q0GnO>Ap zLc<`8GtAv+25lpdcN=?XYdEhJ;k{^|7H-8* z#uz@S8--)?zT21;4jt%3Jrlw#2vZ@j4H^s9A`L+vhH=H0 zghNn47|I75}i(KG_w(|`82Bjm>!kiH1v3WPQY zeg#t9gjj^|I|RWX*UX8s3@M4_!>j0S`*W-7a8|fIqUyQ2Q*}sB*7EQ58@s}*KB{9h zhJPZlatGW@fm5CAF?K9R@8$&1PA zw66@YA}wPXYCm7U0UGps4wC}y@47SEv2I05MQinh~;V6MRVe4cb(ZpDhxWtQe%3@lB#HYM^*lRYkS!^@wt)iZccj2ch zm?NeQwb_3~X>BZw1a?0gN8;a6TPTB)-U&kNQV5X^c0E2^&M}@p)3O{ERi_xS zs%iXWtRFvRn~rf;$kQt}G$5^pqs7iX!7xZ|%k3Xktl=KE(&8Oojs<_nb2*R1St)&b z1s0>dS8pLqi+}bo`W$NxkJAgT8hAURMaG+EQNtU?swsNMhQwgsK|Z0Vm7j0L;xoOm zFv2cx4E)Ezdzmg~1=1y2VyrZ@io_O4E{65TSwiZNm^;=N3kiidyf-HBV!a=WhkLMC z<&%k5Bt{=pM5@I3WPz$9(s0x{s>L(j z>R}Sbw!(XnmLu^pJcYKtQa7C&!==DE;|>mg%kx+%Vbn#V*SHuILJl;Og-v$v35cx2HK z+cgQj1EKOfcUeMHk>;X=RCrV#Y_L71L9Hsj1*R`W$}N#`D1~$S>tBI&zDx{3W7}|M zB!99QC*yJH#%Yqi8h306Yjh)}!TF3@X?+wK}nk!Xk}_ zttwj(Y{s_QV(zI`2N(RdfpOEhMwZj@sC*tMrG{8Lm!oZWk_*2Xz^_yHoUk*p8u9< z$T^%lxxnpQCd$z*mqlVqAC;Iy*s?omahuQ1;k_D;bz_zm7x?n?9j;~K9CQKxL(n3*cigH1)yPp~dEL~}zeaxRpM=lvd&aD4D2oF&{F zoH{bJ@7ZU`l1F{Nn;9d$JE_s{iRjaCvSWrO`VbN;By$|*R1RECAEL!+!jvdI?h=+q zjT^Mr&$MZ{B;M_!#C<|zR4RT_xE_@?^aJQOFBl~mAmla3IGm&fG*DuvkU1oNLWzHB zBjcVaBX9Ekd5v&>WPf=poIop{>V*SQ{70|o%4=XabrW%*MY)wyI;8Nw?=wD^SZ z;gHOzeST|QIz%Cj!N=Zr6P^?o21=Y4Y6e;E!VUvwOa{}%ogZH_GI*TLq1 zmi>YH!~C9oLcBT?pA;pFXW-e+YYdc_AY2$a67zyAW+J{I6vU(|kN4fF z-vk5KaAYy?!b>r+0Q%k-ZRGYooXd_1$!LcyA|vo_;Dxg>@%Wg~5i@#_0XCDN4(pJX z61Bp}*hE9{=_CUZm!Cp}%gqlgDX=*-IDV_hU#a0#xugX_SQ9^H!QXv^4I>AR8rEm#EwMC;d#ofeWz(^95;~>;vfV1N`35^oNEp8lg8fiLRD81Vm0*9~L;rHC>Ln(KhH(X=5S+M`E2;m8% zY}fi^+@?m9;c#fUV7Cgx+J(*Q_w4om%Y}3UCC~QVaoukGvnzb7U5E64cBwY3_;fwM zwxLT^H4N5oDonzB@76BD_1JaSq^e_h*StE?nuZ&`iV}Ogi>)j9gVy8xb?ck1sep+& zJq-6v9ke)W1FnGvHxD$p85%_Hsg#DB%?-{ydyCRjVyl;`p=)=Wx}5{-4=Qb-1Y8TX zs#bhTx~ziKEI`{0FICHM1Erb;MdG-`3BDx06Sn9e;H->w{hk~Cr1HUa`n4aKXlK9Y zPhmk~bl3;pwnkMES+$h-&M9GPS#(6v@AZ_p%S+G?8ydj5L1IF5>7&RY&3_Bw>HgNU61fdN*Kww`gT zX3+PLJ|w{4ekp9%4#!o;8?>iEf)SSMM<-W7QMQ2*=ldA(2?%q2gDh%Z-53hhWBHYh zNTU$13TO3+_^fb8A3bDL58eyA2qt}e{~%JPPA*RD5n_@!{F1OBX*R`qg?}bxC$91} z-DHheJn~N>$^QA-$NvU?7UeYrPfq6Lusa4NkE3wEP?9`?fdjWkSeyJ113OO=K23gz zsR0~EQkpT z?H1;yE`dt1lJH$>{v1k-mf9Al0Hjy@e{pS;9#eI|xfX?vxKs^aF4-+vQJ?2$Khlv@ zI7jBR-!u4BUc*;QyQgB@BPne?ppW zh>^=LoRFp(V&&8Ya+FQ+BaNylQVdi6=?K$DF1#(AO-qa#)8FltD}4w4Mx^pVAd-;sR|4fPL3wpu(@hD8<@wW66B>+- zL`JhUgcS2|?4A>@rVow$x;F>-1UAF%WPn*b0TbII1Z6xQo_jo!TZ9Lf{xN$56ZP{a zbcC=oBXb;EOuJPS)`#+fQEv{hicMNh&;0_c35BpmBz5`YSk~CqP%WujA|EMjpB&vZ zJDrLC`6F5-^krl{BrDlqM4AEVv#kjQkvciOq>g1x@S1N|o7!oec^%=`TIKkH-}7a& z-}7p-uqbn8(JSiywcpmsQ*{^Nu<~MemeE;r(_3&X4{HyT|6bp}itMU5 z{SvdT&YGjn7n`!UTQ2(Eu9d)pj8bIo8o}Ard`s6LB8D`x&^5hwLDwXjUPS~G*!y;* zx9k2-5~Kk3bWELIqyWKZ0%sH{Yli3hFmwjmU>l602FWe*5;Z6jHUsc@tk+3v`aDZ} zk%nzjA=YRdL?e}sZIH)-uptLA{@edmY)+sUYE}u84Dsq8{QC0P#=IuKr`6x%O63T> zwDorf&I#dFLxhfqPjn-2P#P>MfYhn$)Nn#!@uyxO@lF2Q6%9hgGed0j+RO5=3&F7E zS{1<;f*z4+a`}8v3M7e`$+2RwLCUoboJBAopd$nwWH@q*q69P?Zma2>baO0q|EA6? zGUfq+R|PYzMyyqAkgd~{F2x0RlCITvj+da;#82GEQCroLnd;s7EGIseQu3BV%x=Fngpy z5!eK(5TPVz4%gRj;JSdL+Tm{p0-{8~%{3#m+0TG}#ng>f5JgplqW1z>gaqSx4d!)l zw8+O^px5OV&&6|R#WUF#$Rr9s7*zSGCG@)4nCdV`s(Cw9+d7M^zO7R=>+BeKp*~>E z)?tuJ)*JQh6dht+CN71e(eLSa!1WLoIItr8o)7%gy2#>S&2&6tmcAQ-Mxoj~V``sA zp z@6G2F?k|x(pX4Ryvu+JLXLa0Yoj94AQ{ngcdY7zGjL?gd=_SiAgJy{E{zyBxD8^bU z;)prc5Pc-5y+9{4e!4VxyuQ1?%mlGfr{6N5rDbUSdP;B8ukd?*@fl(7vqiv=!}%!| z`aM~IF@h~JIzt#rQbT$$glSNlC5_wJS^ zWIgrLvaT~U-ZMnBDmTLOZfT8yyx9mbfB|Hr)YeYVC~c1f1*>s}e!a}WxT6Bg&gjc; zJGgGQ6xX&}if$RcZo#_W)=h3#44>3aYj;aSs!i=-I;Hm&DWqQMUEkm64ppXHRCY4K zbEH&p%_zhcKZMvF5Wn*vHjhT^rUzj=#2-PxkZ&V@Z$Q{BsaoPhMkxa=73~}%+Lg$W zcwE1hXh8L=^lMucLoV!=RvS{dU9h?4%z`Z#F=r|n5m{qoM1Id3{ePABdv*c`|E~0; zVL+E57Zc@pM3#dZG01^NoOhyBr}Kv{6!}A3mofC6=O?$DLpMtCEm3W>XrtxnXD*)U zI70^u`ySHU{GMgK|J?_E&tttGx}JXigXcw;W~~YUe#?Q<-gJ@|Svc zrP+$RmmM8wJOUbj*g4Sj*Z_cG^3wJV=zlkz((iOVbsCSPokmfGG^@UIQ6rO_;i6xu zbqcFT>u`%uJ6dbQ3fsNmNB@1JQ*P_lADz)2M%%g*kJ?5~ydQV8Y%S4!Qt1=BhaAXyXm-+EQqyQ zpz60nHy3UUP;uZ{jXu%u_dplwj?eDUo~%H$YlI;`ZL;HFXp}y*#)sm8&k)%7QN}Fa9P#Zeq*nx;>yBT?%~q z&)(nU^DZp0#Pc#y$)0q}m5*MLb&HY5ZTHYfB(ADFe$NQ;OAy;f7CFD_3XVdV`Hm+o zal_<3_MyGpFH-JuG}0)RRK6~af9Dh+-Y6O?e~~hlzX+2g(kcKluhN*A&MDmS=uop! zpXlA-L&9vJ2giJ<_GXOV^NsIy*!h(18K9moL+Zt~A4s+*j}fZ=;wsXJCY^HTL4{BH z;`FqS-LnS@5mH+P@xzul6A}w5{hr}{2qY7tNV}-O7gT(>buO#Pp5sEpu1PKSYtqI2 zKwgjisTh5sw4EC|TVg9fJ7`EWN{ZMESU*Jcqhg6Q)JoxobSG_tZmsD`=Ww8SzxLKb zN0B0f6;7b%UQ%QM0Jjz5Mg?_&(vyl~6(JW$&R+l%;q0N}x{!NAAafcr59_a2i7StX|*Ir#`#{fp#kARnphh>%-C zc1uNTNU4a}yNZ<;mX?&Z7sV{Kz_@qD@r12{o8d_d_JwAtxjAdCS!6?%Iw?`4rly4f4$8fcTLfv1 zCIWCGhi930hGhr;8GLfZ1yd2~2mwxGtXHMCk(YVESK?YrBdQ%&M4-#FkOB!-zbDme z4^&&q5*1;HJ1%5{bL|c2hN9Ab27rcooi1|Z?DM*AdreSNuvqf_yS@=zAE5wYnc&g?f4@XrcwnVf*h*>c?afvVBUq837Vjaehdm8 zzh{qNo{)-n3QH$s#%J^+Eg38?Ayb09htNq+s%lG1Lw6{u(S7gAeRr1c94Woxqk-(td31Y6>)^Q`k0Ua{7| z+~k0Hus~X}c2O5iFIh$Oc(#fr0u31k8JpCw8yHlbh*p?Hdw@xu2DaMjqJGc&Jv-q4 zVBmj$&#R?yM*3d``$hK(1p2RsK`Atm*yX~HB$8mUnUse@A3w3|@p z>Eh=!y`FddD22W}APYa#Y}b`dDYGmpjj^Wjwuia0$tKZArCDhxnAkgxN9ni~kM}q+ zSe52kviWmBvhX+}&7q`TPgw6P7_~inaKJ$Kh4g4iHsM&s7CO?J4njDZK{(oUI7d!M zrKF@a&U)}(OIZwmu=C1FU3bg$Gt!me=OGY#^%)x^Kn)KjO6uM&YL2xy`;644A^*Pz z{%;2UZwLOxz<;-<-!skM?mZJbriF-x~6o24Hh+|0-=F-yNsR`Z%1lyaiE zR0L|IF-w|Iv!sH2b(~-lof%+d^lQ?Kg-47Dwxr_ZqF`V={n<$%no_*pq7!Wz06gIH@+F%)yoz(_`P+3B583=^hs`5h7`eR66 z(79j%5>U;06FyID@L0e#TTJvNRD-k8u1*)&;H#y!tF`9<7*rJw^f$Wpm&yWlk4z@ zNIcR5_TZGCn~`Qf$;OC#eJCXqtX_}ckvJRw@bx;u-jtizlJa#PbWDhwM?r2%EsFWQw87>kXS*E|?o?V%9j?j(2`Q=b$ zV>xqN#~#K&t9N-6S<7gV30-Rr?EjJuG zKmp1YEMgE2qEJPl@jCoR;IkO3s14c+ln7Bo5ecirxeulmhms_Zo_1<)36tE!0+N1p^dYN59rtYZzh z(hL;$;O=5;GAdY~^E&@o~F>1x8`^y^hk;3QJ+_eh@+s0VS{a)PUFAODhjE5Jci~}4T4GGfF4R|30qKx$0?YQlT|g5#~znZQvC3OnLsaE$}0*J z8(_D6NQ>ow#3Rkr9%7$)LSlR%txpP`tm93M!Bc`C2?5zW!`=XJVZGi8OlBomE61HS z-8*kC=sLHj(CunbqNLx!CyE3F1m}0*R&l%y7D)0{$$Crx0iJNjNK|Y*? zdVU&AFCKM?+f$hFt03Y1HE|@D+U0hj;la9xxs%*U_e7=T;wg8!a)M(p#2V!|$0@g7 z`LN@#+d#M02c?%@RDb|?;+c%^QYV|C^Mn2RmwE@e@2<)OzF1siC$ZkRMf5EKX;vS zrzurV(!pH78|BcqUw{5nFzbBKOdw9+o-`GSRqV%5ZiMn;pqx=$xdA#~eGuL~s|;C)EU=BbiQffooiXdewdni>@1f?`9wT-u_5TJa%eUdE+2io0D{$?#Sf#hB3#HS7?bGJ;_KuY@ zJL193)jw1__qrUzv5Dh zDy6y^=eS%14~$S<$kgI-I^dq}13nVC|35wm?n0gQ9Mcx;_K!7aH8vQPo+rgfg~vD= zd=VeNOhBsPXd&#Qx%rXfWWq-s!8EQ}V-if`o4<1-T2@1 z(|i49dJi6R(sZ#|$q~>Ljx}*I=Li4|6VUeI+S3KW&V5p{W>i|tMH!@QNgyMsU@2wk zbvzh}V6RsfKI9^)>cUfQ|3sPdqd3w41GHcdG|}kF(%*8;d=IgcAxwpUTKs-!Ql;Ut zQWKiVjO#@ey`98R1C7-46RuLDK%o~*+Syb1cmX(ZU54EoMM>Dk}GvLGQ# zq|8}~u_Lj;o(||fS&#@Auy@wk^E*|PuRf%mqEw(5Oc%q0Nlpw*d^qrQ_OQdI{0M1i zh9S)ejvK$0M%s?pV?+#k#N#G==T~-5Ojmtj{=p7e2$-LJd)h7m*+DjfD>b;_Twh*8 z=;5+A9PoBoXtTP0R{iJE)h;r|7&6BH3^7HNhn#ZHQj!62a5^lbFV_d96<-WWFT8l| zCM`}K#=$R|<7}fz2O(}Is1*cp>_FOIU8D=|gD&j#E%n{56mdvMFsN$=utPhd33jLv z4uYE{E~++m^<(M5PO6q1WM)2wSM0(tF@DeL-mm|#0FGl}{MZ3lwy5-12UZC@wSc%{ zV^&^pky%XElI1c$&-N64^arc|)^(E0cbU1%+-&%N+!fPpFNMXGgW9N^)_SXJQm34X zX{VGEyXPM5B5lCR!O%uXhYZfb1jZX9%q=F8laOwSK)o~2zKXy7-}H5~&q@v0*RNV&|7 z1NrG%jTRc8uWruNwgW(A76n^J|#hnv&Si?>CZs?rv-5}}t2#}2S6xzP}3-XD3 z3N!ym;gkWjRpu?JG_o75QE*k<5H7A+4^G6euY=;atI>Jjw58+HfvsEJ6O?v}I|Hs< zRb0>&L-t1na^Qy8<^u({&l$j4EbSl;YuGV5+wFQh`%hrTzS#A|OGFo`x?5dB94-b6 zi>F80hJfc4gU#{zBEEf4WZGHHNtF zs=UxL@=N;9Hn!5_f{rW|>aA$gYc(#S^_?i~(pcf5y6(MimNf%OQ#148F6m{<&n|50j z!ie{UX)_`R?YKIfo6Dg+#W4OKgyl1$A8wJ>b6dF^uBZp?L)%LmlWJ#Ezx^lzw_ z@(r~L`Op2H4Z^aS(b|qaCgJAgPL~SyMsW{uI(h_p8FZP{BJ$Le!Ur?6@ZW?>GqsV$ zkkftntSg@z3(`vkPl<z)=E;-<-~CP)=dEwAB$}pEAh#g+g%wiN!+vV~My?nDAIE)g=jY9?KqI z(GWCQ2J1_=no1)Lj`ZnQ<8+ymcyTt}tN^j+_0vQ%^%Zc+s)mTkdJr8F9O0k~l8qDY zJ~rg3upS0HUi}`hV2U>+Mm!8s86(Dn10In^81Zsrz)XiImVs~#E+K@LAib(#FgIP& ztF(3GACEDS{~QK9hUAvm)j5p^d3__LVZ?ns+4_T4Rg=I!9tSR>stwzZq2yDKD7b49 zd$0=pDw)?#@Qk=tB1HZer>y%b?}kj@$L;T~D7cAP5x=0$t}01{Di@hrs7hwv{5KRq4@wm@R;?12|O5I4+0 ztRKSMxrqG`!ix|{;mCQ2O@w?3I?4gb42kr5rk2R#j4;2gwEG26Acy;92`!zTN>WA} zDC4f=6POg#d8hK)O{ftP7Csm;+DcGn5A~DUHj2LHVze(7-G~2|in`!`ZIS4TO9oBD zC`Mc(FB;A@R#frj{0Ing)jXvr4Q-$&_X@;DZsrfGNua zfte8}g6o#*bl^Q=#IL1`pdUYIO1Q|>q9ic#)0=JJP0I*?RwIUUB(@Qh%{8&BBP%9# zM$nX2aR?3nSc(I=`b<9udRz=3#YyL2Suy;E)cI`XHAz!9n>%b8?ED65?1W)}zxIO4q()Ofxs?Dn7m~qc zAUXetDauLE!_w1S1hwG11(w~iewbg-%d~VBR?7C!d#M@>6cK0t;)3H7_%d3&0xA(& zyygelCcWBZ6y*Tk#Q@Ic25^>MiIPWhBic~r80Yf1(GErM>q#Zk_|F@6b0NaAIZ1I@ zli{?l18`kV7`#>mvN6tj(a5B>)=w9X&WW-q4k_O7dy@MJbSk>z2Jv&P_A9E-xX3p6 z5_VJtkh2qzJ_+H6!4M)Lzd@e>SJ6CR&N#`;@N#v#F*)QwRUAO`QoeB|uX(3ZuBg z&ZeWzZFbV^tN&@Wv5ySQNZW3Zg?1Qfya3L^8UDYPq3y#!0Xw}cP@o11JmXM&I9NlA z8o!KVwDM{>tk&22QaQ3}cahSdU!Qej5j3|HO3!Hhsy-oe>P6E0i|}l5ly*BRz^}i5 z16SI84pQy?!z{H06P?2>drae<*QDLYNQr{>kdWCNn1e3#4^;S{{#gYRyLWs7D>ag= z)PZ$6r|;??1AB2wpIEmtZjh6#WW^y$JCI+}M*#VtZ&2W%CmSf1j!h2&(g-#y@dNN4 zrp3ekFPpAA&H<1O@1SB0C~mHJ zLoKLI9ni6cOfhTKe43RKtH5$8YfZ6gc%pjh_qf32XEL~8{SIql6|9*yh*!g!0S(M# z4UfelVbBv=JYN|3MAV?uJyMTrHqI5wo*Xyy->~}_F7fgrQ@`g;FGDbst8RleBmCn@?V#sqXA8+zGq@F&TR+FY z2l{e~&rkoOA7e+6P$CHFd7pCL6LghlO*6J++d=z?r z+pd4Lh>NI?t*;eUiBp9$3v=*8f@k3<-8(RM_nk73oTfsZAK_+1Ol!w# zTJ+28e`E-xx7Bc6oB2bpnafLGxU57KH#e+}MG#uO80*0XzZ>ldw3k`G~M-F}XYP9{m4w z{Hw(>%Jzf*;Og``qJxY>2jRlam;U?p#AZ~{L{x%E8v~BkGKl~c2WCVhVMu8Z7JYt_ z%7D~;KjTh7SW9>WEdJSC(Xas&>hsDOw;HsbSlr|%Y>504Xfi9vv)~7w2V8azF41sW zp_rdxP&Js#BLV%C11^x5fOP>c$&Eb9V6Of!kItYSF%WQ$+Z7DTcZCL&*x&IF;pqY{ ze-Xbbyi{Hg_iG;!BIJ%q+U%rQ$Cj%F zU-=~PzMb%leo*yi2Q1a(nmZL`E^spL-9bM~yRB%%WXB2~X>&HK_E0jxf4pNunxqjF>ohLimD@n=7PYxUc*M7EeAizP5;|ZQm{WG z-?eHmdp+Qsvd}NYt%_lP?iaxWZd$XjYGoSL+b`^2nK0~jKLIqwe;2Oz-FBLRSs{ym zHt-YI`Zof`egiJLWr-k04H0IpRM}+yzx=!G(i1Ae-ivUbXwxy`qir8X3Fv{dI9Zm& zS==F2RFkume!WqW8?5Ph%~m}YewMb`$tp;5T$C8Afrr{#XyV_!X~4gG6Y&byo{)4c zJL(T?Q+l`cM%3?yD>Dmh+YW3Cg1OjfVw?w-AlRt8o~bU34&XnmmuOkGK*!g>;dvjh zQN&ezz)v2uO{TU>A8b4D%*6V0Pnc#N*mk04SOw0GsDHzBU?aZru9S2PXMOEr+}mJ# zX8CqYk7}~GA`Xw;2q~=d*uR!k_Uz?DfCOkF%Bu@e%09M3AwP%L~)$Se~ux z^F&HQ?=w1TsZY=>F;bI#!onqaOfT58gtwMdQ={Q%c~%|czfA=7jr<_a&S@80c%$}B zD-XLj0j^X$n}J^xwm&BhTVZ_qxgw}Gzo?U|2ZjulC!VGe8^uYPWox4A`!-cA^KO zzc-IvJh{GCdtAhvy&)Cej_L8ZP^wXU z)jr?*s@n+L%Lv=c4sSNu)A>EpOic_(M?bl6>RKl}8F2b)=S6A1;mraHNavdc%bh4= znUmD}wGZ-DB$Wt+_)}M9YFVHLN}vC~YbXmIg(@?g>3m!TaQ+#>yk#+IZx)!Hv!o|S zDm3Z9v!9e0O^tnzB-hj|uX1TqM>!QEa!4DR-37w_WpTDf2h!{*{1md{9yG0XhKY38 zMTs|5NweBe`XL9_+=2Yi2l*_-JW$p*9hBx*K)nX>@c$%Q9JnMz2*ZwJNjjoLkpY|D z=iz!vMJkBVmx7E%RIujGS(>wws#-3by~Wy2oxK%Y+v|C%kKytf;pUn`UYBdld!X$x zcTP?L18K4eh^xM5kXseTxZea9zsD;+yQxH9-qJt%<*npLk3gC{llZNhG%D>jnG;I3 zL5g?|vidJ2>wcAXqqN9S+C60DMv30fbg;o?FEjVHthB+-IL32jWv2UWW!E<{_vWrV zxKL&J@>W=`(y~Qjs`G)KjN<}QnD|65VaWPD!~BZC)wm3<*F*Ka@0!ZZgjB0n!R-g$ z>jz+jx*=SFU})HMY!e?+qSC%5J#Jv2HXMDuJm@z*1o{hgY+e}{K)s&g-V}Je(o3$m zkp?OnLOCWS9dNvyp7f~ z8cRixo~_tg@l8cVQ_z&(T|rZRgV5%>I}enQ5{{!J>e*{##~>j6%~9E4ihB=23WQ7u zsHmba|M;ZmYjMcOpj1#bv2d8C2(H!fwhwv~9AEd|YCHI6eC{ihl2Jt?o^WvWK9lTn z9zg$rZ<#m*1-Cs8IlZ3!J`w!<8%(bAPg~!wKpLrOnHY_HF2X(adiFF)u(>y_#uF6h ztbDI$Gn`k%f5Ged^W;%fF|3TgINOk~dKifs?+~{NOcP}~c-8B9&i4n=EtOuCQubGY zqBfp`t8Aj9uM+;>6W&{siQg5@ubF{g5Qe|7B6y9QhjC&2|ya2628RW68q0#tlH@IKeTz0&<~svvPDtTmM6^UM?eQTZZ% zOUPNThxvGXePQ}3KW`mW^z|)D1}+Dn?4pl}O`#f}=XO8MO|8S#C`o2L#P0z#y(@gX zUTdr326Ktr?AC}zBpv|S3fy_G;tz=u@iTIx6^w9ucmq%xEJGv50y8_#I=YRxy1m(_ zs#_+8%DPp_^y<1|MHexAFAI7eid)mq2%#a5ci0b`^vY{ z;7Qk9lam;qe77O@H<$rdMvk)(IL;<;9WD{*2ce|#9NqBUA(F7T{k3Iw#T$xeGIOqyP{BfX?=(Nd3s6#klJ$XBhyd~pwDJo0 z;P_fk^n@BLjn~=Dt@04KHS~_~(#BXU2zxi`ak9{~F_!wNPq@5ss^a}7vUipUS(_$? zoBKdNrXknoP4Ki`*y`8zMn!j+{&lqlfGG5I(js z#A>mMO%Z&3od90vQEQJBNS7Yv&r7J~%q^5Wp%H6lScg2XwCF8N(!|nG^W6^9MqT5W`O!gzmuP<#uvi*tj2?;!B@ih z)W+XqB8zW>hCP@QT~$1tKadJ5NriOD1v~O6em?0;o@RNLm23&Ep;_~GKYrYu{BmbA6Zum)@O9JqKSa?d#@hu z8P@QXd~kk^)y#9&7O=^7z}X`hw~WV+2rq3(jb*$<#>RWba0feBs@k-rxg`c^jQL2s zC49amYw&IO=!pOJSaMI_EC=tJom?C*B&dhj6ks9i@oeeIGlKcigR76#;X@LLWEkWy z$#bYTvyKAAH!~6Do?l{>uaP`o^pZ~#fU6JLfE#l7gNukQD93S0Vhl)|Pz0No1z_4* z)YqidEwLq&I<7BA`rE!RjKm*7UdLQ?3E|8x!vQY0X?r{^J|lqO?Aa~NQz3m~>cK@3 z;6CQ_H1t;0!87ng<}10SGNFIm~d6=RMyI*yq9WKjEL2-wrJCi6$j7Lb$U9 z&f)KB#*rgo_yctdeE6e8sbMW_F?^3iH^(Y@-~$;Jn?k45#DK32YxHzn9l;@55#v@s@$#6<3JX7(xOcFRNx}A31q+@9Gn-i+RATub znO2-P7QELHESqxfkZIbv%ovJ8X;z2x7G-|Z8d~=~f8AOQ=5I>QT?*lAV{Fs&L#)|W zmN$Z9T!pm=E=n^7q9uwke-E6m&ojv@ceBjZx)3mCw!$sr8f!#ds}yQD4__rYRFIyZ zW6iyEs6!@mtM5(C;VrN}2XssY(3a1m13i?_6Yc${X%EtGjA1>8|r8aOZ=apmyA9W=EPTu?EcZCz>o3zSF#is7_tJa^h<0wo~^Cr-2VoQpKw z-lGj*YXw|YMJW@zpE^2*BOQ4>_xi>_&LkH~nk%@ro2kzlg^X8=rU|FuyGmBIm23x4 zrmm>=b#_s{NEBkFEM_y(SRjWip^AolK8&MyxQ}G{BbqI`?xPA6B^ouLoi6CWu$C`- z4OUR{2w%NA8~BLC9hu3a`V`=@se+@%=h+J6$y$fO)sH=dL`kA+QaSdJ&!ZQX@32sR z^a!8rh@*b#5w7f*P8|W6uX-xpAXHX=3{8#PSrAmd6TY_sp-gybXRPeQKx*I4rQu89 z(-vM(k1(974)67OCJM2;Uc%djy}MEstHEo}=P4Gx-KC9PbQ0-|ol)Q#F#n|3@Cv`_ z81bna!lRKh1eq`rrwOBkX|s@+BVBWiD@W;0$6WaT(SZ*eJ42@tV>U`T*V+WfQI7pb za;l>5U12AlZ%}-UKLn?=CFr$&&tq`3$y>>~#e0Yo^#FtCh3jj=Z^C1#yMY;I8)Wdg z8PJY{!R>-~V3%DxjhYKK5&a9feCUG@S1i~)I;yqtV>cVR^cM3YN)2j7=`pQHTqb3*X3m44PYy zw~MmM_X~`jl&zA=8=r4%mmA;h2xHK&_`08sNdMI>WX^(3ExtlE`u|OULTOW--^T(N zj{pD?9(LT<->VG`^Tp-B1+z)4FSKi`NpWe7Iurn*&JlytE&E39+n9s(b-sQv%%=(m zfb&@&lJ*xU9sog|+g~sgbzTDN$GaUYV{8vKHoLaMcu*!1>x6NyC)!ThH^waJpfT0} zo-z+P0IL~9J{ShzX#C1^TWzN0m#Dlk`QOI?hPc(PuictZ+AHtYc|*J6 z%o=Z~2YcmRrR{?s(RxGOiRN(xgq}q2MgU*kM(XTpuF-<1SQ!^3)De?p`vqJ z3b;!jx~U*-{yQDPxcNU=Ds0Dv0EToDu;dzQ130oqoI6>N0bmS=X$mreuZCj3kJ?;X z@HJP=#hj0JJW+SNBaC{w11l8X(B4ktWbnN47y(nm(XfF@909855SN_0bwkbd-7pvY zaqeUX6;=*sKF+)5V!3lJE4STM$u+v3;+}IExDwY9Hx)W2KhowRt0M_caB^u@0mgAv zLy(4@EO|!v0(~iaMWct~DXaHojpP{t_xI=$JzSgsj<4Ac*WSq|%ix;@8YI^D$idO& zg^E^wmKlj}!`JkFf^Uj|Ph%SZU=SS)UeHVgj#04j zpCadOy>B2#^}lk0Pl1Z=6t;mAJ86u3=S!KgyScO*EZu+wb3#};;fEC$!LIMsfO3+k z+mZP2DHyvOy157C!~>@{C}ht6K3|59cR*_pFnqfq0Hg}d(_4~CMEHOi!$nt}=?X!Q z@v)&%FPt=`JKoql`lLzb#G24#nGfk6` z2_f7nA*7}t9$Q*w1v@T{eZBu}!iye1Jx2|H^N)jppcj?~ZV<#0t8 zuA_MRPRXEz=o7xF(b#g~G7K_E4RBNU5p&=RY}uA<_|6=C&lXAFTQ{SY5?}?idq+SO zSK$A5_$0=CPc2+O%jNHT-snrSylI-`L`mdrb>DC}S97iRJzM*di^x~PWLy%&a-SaT zjA71Xxc8v5)R=;tcfdX=zgRjS77ZF+U_N5XYtG<;V41xERc19lUgv}RZ=}hm`ywnE zu)cGk(FJ{28(HM@jOnAa5fG0ef+&cZ9eq9kL;_o4RW2U>g{umtbE*-|vfmVbtkr2= z2m1d31R5^w&oa{%jc7BHdA|tjlJHo9>dhgG^P0#bVYP@_0~g)*jD%%Qo{#ZQj%J_ z)}vr8WX3CG?!IsI2Pc!Gd;If>~9 zu^c1x6+A28nZztSe-3f*gZv5k#`Uz;KFoQaT!5|2g_?kJ{Y`Kx)_X-9M5C*yH zIh0l{)>kbC+V!;wXjUW8-3<`=>p=GA$upNnvz~eTzaF@UXoccrffXE+l~xFGJOGYm s0gX@r3W`n+T%ip-&8&8XGGoc)g)8KFw*Yg1Jy14)1sIi+&#o{A0ON-4^8f$< diff --git a/boards/cubepilot/cubeorange/extras/cubepilot_cubeorange_bootloader.bin b/boards/cubepilot/cubeorange/extras/cubepilot_cubeorange_bootloader.bin index e8553b4e508e249789d04847e701687821d65db6..8a41060950c183f114d261d669d300c8bc75382d 100755 GIT binary patch delta 22329 zcmagG3w#sB8aO($yGb^E(DVhNE$t?0p>0}7DPR$hG-{t}h8D6-+U)%%)pO4M-+O;Izu#tN zXTEuT^Ucinnmy#ETHMspixi$Ev{Ob$a#?cm#iY-YV-oZtP3^MOG$TFIA@QZYp=AmG zkDS3JNL&^`qAVeCydR0Pdz-tJU9^#z3Iq@91ncaHiK28oCJ zkm&72VnZKlE{I2|tOKJ|1|Eb^>L>3ac46tdqh}>F#?a$5SbLngpF@0p85Zy!WJKME zog_4OzwMk|c23f!>U*jd>BT6@BC^n^Huap81Zf?METS3Slm7eO<6JcG4rRnDfG7C` z-ogD(0+(7)`h}F9YK4DO=sz#j0&#QbKMTN7szp3B;|mB$d^--bk}w9sT<8!=-G)d? zM7l*(LIV-$(8+X5kJ$o^h2q~mp5Y*X)X}OUg7jK?@||f%@E$y&$b*`ZnW|vXvuHGDLzR>Y4^uLzh*7XL zY%@X}nxSdPn1VR0KMy6XBBoD6m{#_M#Oh8<8YZ<2(o|NWTu@O$cv7 zC_*Sgcoo8{5cWXWGe*-iFc9QK)Bo~&uoEE}R~5-OO~-%lj^2O_!U;v(;=yG@N@4c$ zqHE|L=Tocea89%{rsk=-&+CwZ(C*dx4c*Z-r|KBa^a&F0KQX-ykN?esGJkggiLO+Y z0+Hrn!wnD0zUG3_t)xOJ9UjvsRYf5zGALD8kT{rAmAC7CxWF;Xz%nPicxNMj_n6S9)Ki5!I(LD`eQzLkzJ-jiA&#>WbNW3Fu*l{fq zUleAlblkv790RM5(A^lQr3PxL0@A9=($O>H_xyz zcMr;!nD8x@fSW*QOJG8Wm5a_CAmL%KhT!3b&BU>#wAW^(?<}@jBqmV+XiXW?Yf8eo z1RD~M`;mT73C$t#h#zXvpOum(8AONGDt1^uhqyS>KnA_&?`)IvXVd|UpG8+uM+D%h zL5!xC3Pd+*L&cZMYbV^G~8?bp!?E4->0nc`Q;V88NwO;uLI{ICZO@ z@m48~RqGp&j)QK$Aq!lD)^VYKYzfETXQRc-f!s3uo}JIVKgmWJj8#}v`!C%?} zGKO4Rt{oc-FPZF4M2k{yW|5uS-0f#(SOA`SS4@MYv=8({JV3)~N@E*@Tnj9ynxD5Xev zFKXEEy%Lk$9xC~KFBwA9b#WtV{xt@%**ARU3_pm+J9hDcZPQ@KWvOp3JkE;}nufSG z37PQNywYfUjU}>OV{d_}8zzk@Rq!ai&@I<*1TtSPhNJNvI6K;Yq8X>*@fqfslI|$o zRXymG7e$S7|3gA%x&Bw%w@@R2$9wM9zag2pIXuk`Uq!*G@W`suHx%QqY%z$H4m#G# zcnhd2>yfw~`no|%I*P>we%bd;a0t*DEgk_{GCVE&T)_&SCL?(TkHw~sJkj=Y5k*9n zm7r)_f*m@JsIIdsKIvK%#k5o6G5H&4ey3-el!YR^I3mIRnH}F7W-gTU$OEUrQCOP? z$v(zJ$2d0eyLc6kQsem&UaPM%(c;EHF~3o&G1KC+0X}K!sVtrvlgBH&Hef8i)T`vn zJ2$W>y}*UK*sw!hmOaKZlUgLSw-`FSFu?Ff3rcuAW*WSW3(P8LD@=4Fu2ft(IOwfrstL^3*NL0K8wc`6nfpuMJ2l7DU+D;2P7s1mgja_ z%nelYco)a3y;x1dDw|JkqlbSL^9A9j^syJRIPF-d>YPo~A*oW8m#~p*m(*#xFsJ-v;aMSU{1? zTm)JY&ji!?swT#pijLcq;*WlgM`^V9rSNskjniFe-T^=OXo>+VO$0^Ll(qjlj99o(|KVi)dWvogM!DYIzSL5UX!^-Jci5i!D%6n z;rP6!yaqs)cZ!1K-X~9MWW2LN@jN-N5nx82z7fskH6ih%J~%>wArw6WB{U(ZG&#Ld z3-wSUCu+u>z4#as&kCmoTVwAF>S1L;Gjgc>aM|~k5IrOt9~UMMnM%E+ z68Zv3f$NhK@ZKL*7Zcv4m-ZWmZgA)HKL}`cM_k|JKndO`N6?@wMIP+Wj zO;BxoV6TUqFp4rwLy}$gogpM5#`HE_*O+DB*^`9G*aoT$bBU09fA7G%)6SVFF-AC} z9fdieS34P>5ylVAh@CSSz!8Ke9Y6SZ~5F3TZ zlg5vKG(cEAa)N1r(#hr@&rd5&Nmuc}ARisXw@d6^=E8C@9u4eC`HkcGX@HxLgrAd! zMBVB~>A$(JdB*b+fjP6c3QdK4E+Eu*e;Lf=*b{(6Kh*RB|q!A^e`4gWnKzDJ4Vi^CQk?`;!v1e4_n^ zhk>D{3+q#IbQylX=O8d2iZaTfX_zUE)-W)UWBdqCH!?v7h1QgLkt_X}qhVi*f^v@w zlei(-?*}pLyd@SDq|EbQ^C%&l4NK}5IK_%#QdjRs>>hZ&f=3}#b3^bNVHan#nh%iE zUMy0m0e#){ka&?*n8mZsN6ThPBW!3S62Et%98=-=nhAGKwjN)Dl8>H>w~w+b z#d8wg1=|LY^O#^HDOsl!FG<2U1CO5;o;S>)uJ#IThS4d14K!V6%~<^O6BdO1-#`8E z-@x;uyoRtTX;4e0kdZop3iJz)q>f~QzU2X-Hgz1M5dS3$XH&;fpKTGs()L2eRlo32 z+Blf5U(-gYIoo;tP(J9}Bg79Mh1Uy(!wpowFFE0oG>DeGXsObvf<^!^|E!!#CP`_`RjPxWH9opi8zNC|R4PP!(mSpm;LTb<# z2OEpFk;MCbFT=T;*Hn^;Sm97ca{9yaacPDrL8)v#E=@BfDydd-s3*&a(=^43gQ9+S z4Kl zl8Obh!TOn$lqWXncmsc)XamAoGm^Sx5Y@~b4cjDbOWghCol}N1%`q}V&L5_u1zlFo zIA!U2GvYwp(}oj4FR!BssY$uqK2pxQc5_X;^2};1(ipeGncFP;UILmFYO-b(zo@;l z=1iS3L*E8RvLAah%l~!GT7PF1*;0~pWmbKiEmvD0Hf8WP zJoKF%D}iatRT+iUY(C+f#Ih~jkwi>`cIh<>yYp#!6%pG6F@A6{TkMjUy!<+YNYO12 z8<4?CwiQzDkl{ixBHxuY0(-|{u^dhfZJicQ$9~^Gf^e!d$v3MS2yan9ueqpkoP714TLVk#6|A!tO>M65Us)nl<&g0SLleTaYHs+vgkRSjip6?_CgPZe=q_|%j- z%nl6Tm719Q=O#xN=-1W-y1g@SnRVM7Yv*Uya6vYi6fg&xaACJ8Sy*h!b12G`pq$be zL3LrYhztn($Or=t^<9fto5r9hja{fHi(Yz0iCggmznkXzeNUVsjhiEBWEMH3C{>ne z7Dg}K^gj^uPYu*TVDcL1r3@d*TkEWA+kwK-S|^r$zsQEAiLt<*$-W=tUf6}mf%Zdx zPv{gEW{iv(T-9J*%kckJPHd&u-d8dY&#M^5jA<22DT9TZIhx|!QhMziOm$gfwRWef zuXRhsZ}kNATc&ZL1_YT~Yb?QfpvAm(W{x*>QZ%8*<>KSe{A)5{aA3Nc$OJfsO>G4v zTYJ#TFCirHL{*?wzc!2;QgXL`2A)}A=s}=+*k+wMt>5>x->^2Ol+w+^9KUPYKuKpM zDXCxE3QbUOvSR&aGii!6`z55o@(i(lpAgCbf@TR(0~X1mV9Vf7Y*4ICDSsSy&7nnP z-Er)znpw$X3XTWv_V8pTs7d`lDyM#F?=v$#%!1A?^LqrUv+Hn@RQ^lNo*Gnnm5J*veG{oZ_dS zB7HPW#I0tjVbD?)kk*36@U&|_q zT}8K6uC0W$vTsot9UjPm_u}JnE2Bw5ig)0)|q(Q*50}gryEhGX{%v6T||02?e5<;S& z+_VA-#}X2a?j^8@1MOmnFv;|=Fg=8!|C8)2Yia(h5}zlhKuYc;M|9tSmJ&85U#l#6 z0JHhlH4Gd?BF!1i;yNd~v*W4dB9F;A_*g%QFQgK z3>s!7QIQyF?J>_ZtgC!JR6-b*Hr2l+JI3-DPftux)HyS-Siufb9Fc4;ciGurpGxzmblPsev)(LpPXU$%YG^#vUz zbdNPS$QZxquk-xn>35&L>mi+aw-sf+?I!h6#vyJr%F$DK1j-?0`sBL{jAAt2kI7BSY-|hy5>kkkQdob_7GI;v+P_sGEs3tP(xL*Hoz-cb+?fG95ju zj||iu19eXt?;faneB1wf#oq_ddgh(Nqi8oTYLvrQednP@8QkC1ho2JuJx-557w|ng zM-J4TbENy)MWv%B`^dCTCGF_RIN}&J`R?!|m1~INmoiT7;g0A_e|{cB98gXNE3KV4 zmguyT%k-OL&FVU9&$^X{bq-HE)DeE-&hb*yH$Uph@wgKZz#Ti_#rEH$T#Cmg`leVdj)NOAoa|zwVc7V7FM|_x!of z1w>i)!2^U`{=(7A($V^MDbCz3X*n>cR)DoT+F|=nHjj%iiyt^4Ay3xTmL^7k5lMW*`3N1;`Wi7LRe<3rJ>L9&J>G#b z&0$22Roitn-P`~(3Y0Q%dgp9|kUy~;8I|-UYv$&}GpOWdx=U^H| zS_2)OTW!uh%&WY^(4ppX(Hx%QcWm+E?XvH#|Lv}DSnF5)ufZCp^m+WF-RtNVA^u$G z2zhQ5-u14uKm*50f0BU?sB6e}xg21~W;v}a$%4eC)w1tm-yf=jSK3s#Rb!8~&11RI z6&^H#pW3a;Z?%+_cNPtuBheg8Rvy(!J6NrVqf$W4GNE(`Y~dvmWm>kz0!v7wZN^x4 zt29P8_tdM<$RcR$1qewzR%EaOR9+wZmjUahie0u!D^gLki!x-Ek{Yxk8x`(a78*Ba zq}*gno88YE^r76pvMMiDeeBkFrt=O1Y|!sXq*AVgjCmidO41CR7ydJz0s42jlQ>_k1?9S`Yj&9s7DNLkOn;~rWkkyQI=>>S3?5mbY9$1}F&XUBl zk|qz%TRYazlftSfzxwuQ3$;Vr495eVVjcn%P78T1YR|*|O}CSD!#imuSVsfYbTIVT zvB8#8CWQfhQRe+23{NvUB16cT8+aA=^*_-X`5&}quGtQ}>y+Z<-GwoS*8o$j1&j<@ z-c8e3tit)7gQ9^w)@H6cyy{*R)yf)3^#Nc5^I_DoZ&W}NO370WYNhv-HBx&>I_Xp% z*a63YvMSjTaE3te9-@F{y-Dmm77H)B=Uf{={kc&0!UI2gNQHmv{rpJ{})Isf5S#(7hwOJ2|ZLb7=^DVat@syXf$7Xii_YgR`mJm`=8=; zyq@oev|(j3N7$6R^B z8Id;!jNO}x%_D-o&Am0nLEpyE|AyX;_shOb^2W0Ao}Lv5^nraocW^@q#nU{nZ4nm9 zmWX+aEvWx|74;O-M+B(2q}&CIhc00p-qi}=I?M&4hIy>&d_5k$UV6y9SadL|%=J>S z`LWf@yD{V(kV>nrxRD`gggNbEeT$U3uthROCz+fQr*ldXI#qy zd!<3sue*`Hvg9eQ4^(a_oxV6AJCA98c#6~T@YDk~#}zx7>?<}JK)wqYmLel=$CG?+ z!_pA9vGBpN2d3zko`nr>K!!qTeZG$a2bRSV1}*nMB@*A44EE8SRcxURwksgAqnU)A zy8@QbH$d=13&8B1M<&7mqyz7H%0(c+(gzlm+5mhmW1hPr-TPfm<8vQhA3c(!?mm5zDAH zq7loM8}2xxMxP~%{|Q;yg)|$M_SNa_2kh@#GS2;C7i>b7b@oQyK_BCO!+^r^ugpVz?hXN&G)Nu?^%ne@iCX2++3c`g}oPFNw{SSgv;o`>d_u z_Y$MBW^YlS?**Z{;B5u6e`7{McHvMQB@`77!{>!1g&Fv3;g!M((Vs|ud0 zkAe1SaStqVf4ioM7Jq35oao3h!Ftw&tF1QKS0DUuk48d|s-P4j?vfPz6??5E21FZH zX@Xi-%XG5pqU=i&9xpQBXNB!WLoEBDW(ACfSY@OpJi)L|(}ZqyV>303M2jfAJr5-vla%`+$9JeY7E(k38dz55;9BfTZj&VW_W2;QAz`> zhxcf4KA`7=W~!EOdGjSEK%~g9sYbiCF>FfM{o&=8r7Y)h=oK~?ZA7w~B{36DS?-*( z7IvSlE%JI=qEPB_aN{Bmf;E3!I8!pr0mks*mn7RZ0VH<9xFYfQ^(Vb)QLGE+Qi9PQ zvdxeCj;}3B`&p3i-rY$gm)hZV0h`2z>5KRResb27wv%3C)P1g42)U?LNfP@BH=9?5cy1@>rDGeLzv% z4BcEzsw6d{ReysVJLK5@lY>@~9OvTAkW&>!HK#(m2OS~c8qfRQB{1HXFP!vN!W0~; z4ihiaGeK%NQ~e$PM%g@x+0zJkVVigH1PjG{Tys90-Et1B#Xcur`}0ZfBTJSayIr(Oef|XaHF3Z$)fS!bVpekBSAa$kNXBKfmjG{x z$JG{*>KT}>Cre{N40y6EqInx%%fHjbs?}YrQVW#6v~ePjvdrR%b@vrq;Hj)Vr>~WZ z+3L?d<)TsD?1`x3#-FJ-+DS9NdcLT?ByoGOU@ODBlPrnCzA3SeELVb;i5l6yqcH0t zp%pS-svYmyU6_6`3_6DQ9Oz%ZJuA0#mzYPng@pO;2B|C5d(gB znRaBn3s^|u|4%F!Kx^E{GaYKLJl+(-n9)vP2y{75gPY`xi_o!WzVRaZ{Vp}dfD0vo zWp?eh+|$e+E*DMgIjtZmoGX(y71FQ@lP+Eb&c4wrPj=Amk)bN-H@__mcfTQ}nZ_Eq zHYLPTL5R=*jg*TyEFNdH6NbOGDBnXu#g5t{Qe3fH<+iQ(oL2cEHm|Y`~`{8 z%mX<9c7Zu4BSX}vl^4yH5_ntKm5)=P<3nNbDqRF~w0l}72BZ4tPWFQ^gB}j&vAs;< z)p`PfcOvnGGeg8-1%)ZF@i}iFcNW~%P_X57JJg*NNL92uLyT5KmHq^nbFgtc89>vc z1u@dlEEA|n-gIX6w3KFwnlMs90xU)_fjSdF-dDO#S)8{|I|B)H7sCeX4|FNj1gEtf z-|+_&fTi&A&W;j};$SAskmBDE!j>Y0Es9`^%5t$E;75h#X+s=@v)Iyi_SX_X@=(A4b^)48G=`r% zSHN0Q($i8>-ovbH4b5Vjj!?$HQ3hoDD{DC8Dc~(01OF{Q8~z{gB=k7Tu^U*~4l1|3 z{$Wr4Z6%e^NkvWWnR}!g>LA-5+1}J$N;uHqP<6Ebxp@%u>tP2RSm&f7jT?{qjNez7 z@zbF$2JJ080sO48V9F`HC$}J(U-j!=eiAf@9#(oOrO_VOT%lVXTF_TXvvfiy9d+52 z04f!w7l-nVI!*`mKCErd)^$Q>NJ|c~UDOtR@2N~4^nN-&!@vIaPq1sofCy1rbmq?< zPpmDv?^hEa74mk;z9Cs-d(bmUypoUNlbQ{1NRfpb5B^_QSDV01PtRL{-+HE3oq3#} z5Q0+wWEy?2P$6OC$}X0^3G6b+6zj=W1_-}rwAV9x^zRpFj4p)i?r z7=S;U$;cxwx`P}ha zUx#3s_WE1Qb9k&1(p6psds*5GK7o6WPQR%MXT*TC9P9*}c(koOk$A3K!9{Jyr5XG@ z9@Un>=s{EAHAT!Jek0&i7^X)CR>I#g;@8qTehYui6Fbn43~u{xn&-G%DrokrP`8lbf(G_V?u^%8%j`@td-d6ASN(#ki&nOQmDLll^$i~SgKdM^F|lz%U;Fm8g}8JRw7OX)EkYe8O_OzLcO6*RdWBUFWQ9G{+u=2$U8Gyvt)*I=b#?sDD%|*2%tt6QOZtU^fyMp2DH5{fayfvj3gAqa z*AN8;7~|?#u^-r_&sC~c@bVQVJ(z-j7v?{hNa0@L*#}2ERss``KSF7XIoa0^%)Y7} zk5x)IoXNi9hKmQB!3J_^$ndMapRoJ6t0^OCdU_ytH8v{T#17hYy$Xbt6Q_tO&b1kw*mF>0+y%1Hl$4+}uC4C3w?zTjqWyJ7aM*No~JA6;cjQF#}h;M^z z#fS;OrxR&|5x;2EfXSF*Wf`+a;iiP90U5%l%#sY8zK;Ckdke^aE@SL*E6WmB=QbX& z8yYE&5qI{EHXN`)>1J0PxNks*sIoTOMLWvu195|-5&ilHWv?7XX$}<+YW8)*s_0kS zBo>-|R=O-5-yc;6j;U3UvjZk#+_w@tZ4-EkVyOI~-Vt@+1`E11B>rU`0<7iB%r*vi zkJ}(cGoq!J*`u3~V!Yml_s@_(Ez&%{0#c&S#h&w%$ZEx@#xCzi&pj%}O_ z^B-H4e>;Yzbjm|$#D|g=r0qk&5gr7NK^1%kAMVBB;9xHQ2n&r7!z64ni_@!_F%Gw9 zH1uv^2n&C$jt9qMv$&$#I24-HY_Xu*k5z+4!+~zwt1nBhADzR$Z;5k%10@!O#xuV< zwNV!`swUeLY-wQIPAmAp67ME>V(BR!f@JVKi;;b%AW#WtVOnlmt0CNlcVk#(*fIK_ zo^}aoh!lSkbRe|YBm=Kt+-5P06!fpnLy(sqYHUO`N*l$SJIE3RMgVqO!-gpXzfq>1KJ_`PKChh zL*O5Vz&`-+btDWZ6Cl$61MzMM!bxuoL2L*? ztamEkivtuS$_k#*DYhwqMuq+iUg?0yE2IFZyqAXxJO%}pxj6l#k|AlzLqXq(AQU*H zcoh`uqyWG_9fC(IXI~>5=Y0S_v;E8Zdr#!`(S3- zp2ErQjIvtGME7Os;86lm*y#ul2e)_e7`^1n6sqUDO~Ebv1y zx&N&>#?g-qwD8KW1N_YQKwVm(F2a7ye_rt=f)LJnmqKyupYSn4&nKnvX1gEj0J>ACHi4H61)1Ay~Vn8E$6)1EJ)Y}2!>d=19OyTTU zOqGStAL0z-p%_gLSQAm~smnN<)*b}=64pn0RhWZgb&;T$uXDWEND3#HRW%HBr{*Xv z-sev&Q9{Q`!EHA0n6`wBwZLyWMvJ##Be4<@1{f4NIkr7!>QdeaU0>#>_UL#!Z|FGz zihdJK2|-^||D&L$ONWa=3;iaZ1?H{_y8ljNdC$*d6jMQDg|H21wwa8EjARXTWE_N` zg$s@3pzzsz9n~!fSLct$gM=XqCM2Z7w#)D-7Z+QCzVm*DplXb^gBGs`g~t|fk@EsS zd&=y9Z@|MjVb_9tFc#bkV%0p{xtRhr=L^3r*n=MyHa%R9?-4FMY{m10VYbh}3H!2b zI^H7WEG)x^h36M8jNIQ#ZV6I9aZ4$2mC&_t7)}w?i;Q@@Fm{nnb)UZ&P>?3fUo;et z6rNs`i{pgDi^irp0O@z#3eW{jgZvNRqDVq}*J>Jc-&>B6lpDP_Ji^+?1`7$5-z2W? z-3NmwieWfDi;$ON$sG}MsN(+0(SyoS_P->wE$bplDibCx9!g1)P_cLARoM$coMrU55Ob?%uN~T z@}PdWOsO+LSl4F&DZIR=eFaql%DH?j4r_i)7{4S1Hwkm#|HEU?EKyL7_vHhtjdeuv znuHF(9i;v8fL~fw6H%ceU4jXVSD7-Ag6E`(xP5IZk3-eiPzggL?D56x8# z>p{Q%&{D>$1?4FgD`f-lL&^)FBCR6tPl78X@I$%-%Q#*q^#5h%NbAyAIC?2pSiyD+ za8SUkt_MvAb18f^ZKPcZ@ZcP;Ck)b6@CZ)(I6PDM*!~=TMaW%RIR2M@BHk)p`TSm> zmZ5M~kUNB-Ydh8QO>k=^uB>&m9T+WQf9Key4M3mJjPTjgd|WNij~c>veG0yEI;UOs z?G$nz)lrfC!mLLhim3{DI9Jq7uVd|OUB53OAe2_=se6OM6IEtvXizv>mB;k^4)}$e zRokeEeZtx&wOZh)%Qx5~c_*)1Qf4>nUboqy-YWq7WEQxqUV3sW^>$FmT9Hm|3knae z7*4$r5Z103o&4KU#I~*kuI4Ft0QvDe3yR#OJOU@YyZqPzio%MVI`d#7sRSB837Art4;8dIuSc((U zB5t>{R$9#MesZHnmoe6@8ktLK;kH=>%~MH^6E4Kn7BxUt(jS#;-Hb>xZIazoBUP9| z*XqLDZ;&7HM?MRo9r)KhE{gjZFw3F8!2bfY7>?ucYV-0E`xiCeIca<1QY~E2AZwlB z!Argd8JxsLfBlNT6QAt$A>aBn4s|i__g$8EO7o%0nXaAEJP6C(jCW_)d1>dg>_$+o zNHtIZ@VxO+yK$4oK4g=&;CL^vT?toS!nw`$d+G(Sdc*wdbuYhGudd%>(Yp07$3Uvm z4R9I^<^VjNSX&0y5vqU8|FI>pZ5r7ldL09PmMxt8q=!MJ1)niH7 zGPEA&{`|t8dQ#1nP$NHhjGK}RMpi@Tprc1!2A(SYMpq0gHm&bHj~gf~4_5X=OU<{{ zxx2svXEP^ zwb2=OKsf_9B^5D4_dkNtmcyM&Bzm0Z!8t3|c3fIy5}Z4w#U|lN5w6rC@glrcK+X*y z_zlt=urTJCW#6(-gq=@3NPie;5Po|?hYt!-%ZF;XKCmnpIR2nC7g$_xP{><8lEQt0 zeYs08rzZ$IAJb^&1^@Jmb4v3yV1gO+SSIyIK)Cm@|7=Ex5UR(@hMrp(dfO zlE4OO-n3u9YcUB-I~(lm(va(_Ygrtd5xRPXg2K&Z36AUiB6!-78-nES1YF(-!vZo4 zP{!szD8nUHIZsGRlg*gdY%?I?ytK7y`LTaV%u!%=5tQ2m@Gq?RJAr?JP?GMrq;Gk- ze*e}e|JJ^k`kjT83+*{(NoZTRb^lg%eN6p!3*+9u3@({E_#KaKD;l7Ll@iggZGuX^ zYJ5XtOyq*?fHvfvt@|GxSHEMvW!C=U9WFupj@O_#!xQO z;MIxM*4q`_50b{I6n?nDzW2k8u+4qGPx=`?uMw^wDU@|%Z0Ucfn5?&_7|Gf6x?(Qh z3mzzuUQNUXX?E2o*P~F>mjnN=U#HRMhUC&091z(cJ#1nP8l4@eX|buiXYfj(s=bvj zGIusZ%(ktv(sH+>a)U%~yRw0~GjHXAMbTxaZwwm4+%eBwFHKtqH}AnGbe3fTA5n_M znSF#+3i?Xrf$M!Jwa;hk|H$)D0S6urQv(YA5HJR>1HW<{9>-SrGc~+$^aXo(sYdsz zG~2{LaV(np?4U?F436ZXLSXdt``+$LhqrtC$t^unuBst|XVQ(Zc#xQsPNxn>@l(@b zp(pkt(B%&0Z#{%_-Br}+TFc-n=_iz4-f5=WnkhqV5^ZRyudL##loL8=1H+Y7sSRw^ zma1>6s+ts2FL?+9rt|EgEV!SAL>v@uJ)4dx zVaRhCj$ZKaB8J=>{bZI#_g)3H6?lTmaJv||*FN9VeFNMpF{2`JE*PdkAP|2FD)>q; zA~SBoCa|XF8mjZ)?lS0tKmbx*?DIX;hwM!H9oN?MZkO4D(&3(|VTsL9-Q}qP=7gxM zP6fk?=}mZ;F#_CNXz&q}bFDTcUWE#X-I)bXi+ev2I-cY3y8>Qw4`zh%Yi3jBeqqO& zb#Sjb{`tQt2tPhisCzyI7YXj?=VPNVYORjK0b$14HE_H7$F=u_ec)Ht+Uxp!nqEQU zunfB;d4LiW47nB?&-~&c7V#I4MuK(_iBAa29Xhy=$e36I_lj)VDd{S=8igbCFP z6BmLOG2r_OxVEaMy})E4u>zkKfs+3Sjo^|IX-S^U)vN`b_W zVdtfficJw*0DK~7ep(&ghEf%_L-tz0(jno@Ivw0hjss)h{Pq~2)_35}1~pQ93BO15 zlr7{!F4*vD?Pl0iu!3-qlU&FE*Pcz|J4ygzcfY1?xfr2<%daEfwU4_r1=2O)dsFt~*-1Nk$_G41sGcvl{DdUPL?tZpaDpo^RIqJw-31wO!XgIRJB zu-*YHN&y%n-YeiG0R=%Cg>ftcQBd}|A$Q=u?ljQ99tz>-z$Tn~07`xlNQXQHAAl== zr0gyz8wO=%-&|;LU-P4O0U!l{{3uil5gop%lPPdHS-2r~*c+jxtT7|8-~^tK2!_%F z)#4>0FMxVM*uKG#tn1rrQMF&XL0Ky8GwNpAz@_5`%2n2~bpf9-D4g9eO+|f5me*f| zj29+HztN8kpn!#oe@eKD+v|H(c;M*<4bQaG zBMkP$MuV-=CN{;`>+1wb(-OUAYoT;ux*c@zEnnO~y77&en`s;Tw9%IGbOK)q+V^nV zOk48Pl4qt}{x@nS7v4??(Jxx@3&I00I^e(c#j!x4;TtO>3c$r2uBI&R^{Hjy*^TLg zX9fSeFH`~AB6tbVL++>u|JWD@_m{719HH9)H)9##;+DcCEi~;V(7wGSQ5+U}eIsC2 zB;N+XSd)uy2@ltd#lH%#*36zX9_aYD`n`3OBLc1>j@ATxD0H_O7yy1W;Nl1A=Pl$q zI*o~#F8QjP$n}`zB894&4hk8YW;!MXQcCccCv1c4UrG_qQM;J@@|b(r{ExY)kS zK0}LJhuU)*_gmtA8fwpIJeUw$a?_*b!+FtDW2XuRVuMOEfOd-gnhtVu#B}VkziHXu zg{gyG6tl03!Mkj~xfLaZzD)iPYy;mu2whj4RBaAj8;=A{xV3J#9i`!WciRm1*t$I+ z^`T2-pA7gW_rr8SZnZtEV7JX`FSNCQ1-Q#2Ox!#X?oL0mIU~{E3no2qydBSj{hiuo z+1%WcfH-pj5-$r)n{%S40ka|B9AB1wqq|523i=&_ym_cY2{%=Geb;(TX2O5tZF}qR zAqlQMU{KdfK286yI;-7iTW?=xQ$8d4vib>!4)SzpX@ao6n3$GxT^E6;f`zS4zW>4y zP7hX z+uak)5T4mg?r$Pd2Oilh*d#O!Ea+Z4QjuO&Qn@gS+rLoq8GBWRC@#aWkSsi(@8GA7 z1SR@)3t{USzEI1pX6rt%Aa`C99@FdlS-vZjZ;f|2VFw+=>l(>LNU1#F+j1(VG2qJz zXgetH5ZWL{h0iTSx9gqzysRSN``-Vc#J>JrVMH5qb}s0a&47bg3ZFc8!g3gr*t4~k z8D|f4p>UedZJfuC;SC*cSpsL<6HoDO*f)0CBI>@i|6;4Pyxm1B%ooD!XA{Z_!fZxc zgq=A1JZ6K&5FG7DYyB2tq)Yq!3NOpd{VDhDXY=PL_tAwC@8AAn6% z-9=N&z@HS;nYLx51K` zei|A$WCFf!*o$m+7<~KKLr9b)dUpoT9t!v-2-UBYQDuJNAFm`)6F~{`$_y&TFPOJY z0|sRKwh!@YVex77!!8QbZ3xx|ibcv6gKzj4-_-HWeoe&!~+Fv+I>}`YXXw(Bjyf6x935CM+ zhe97QfHP+Fi3#Ae`=e_f{D1Gl@0)K&Oy|HY1*N;%n|dQmxz6v&nTpPM1|5I8LG>Yi z?*WNfhF%T&7QnHlY=_HiJg$Y4=?@Ms;2SRqw}b~X76VtzHYnh`IiTeRcj?Q1!iD*K z)8RUF+6!bIkxf3}nN~MOA^xo$D9GK;KIxh zCkBRiuNFIA=8iN zt;&GPyUP-GA*qX|m0sE86jQ2qSLCQw+o|B{Dll>be-k21~T4(GnE2n-!Ag02Sfa4rIPf^JnHHrm{Y z^9KcJvBttemoX;(Q`FfSFim~uwDM}`Elg~)OH zl#}HTb`4_8owWIN&sSbfbWg$3qL*1R`B?cCQj2=B9e!@t8ncy6X^e%&!R;}$|1_N#n)=!n;xVg+nH ziG~m06(*T(Gm|OS`RVTMW^DZvXU7JxFfKg8+Nrcc(|6yrFn+2BaNz*dL-To~&c12M zhUO~^_9SkCS@zvk1qSB=P2?*BgSxl;fncDCyuoL;SmG{F_bn_qlfZW(KF>3fID2`N z{FQ53Ub7S#8=>Bg3a)y6!0h)-)@A@6#XGeH9`8@y$Ikp!~a13GvEv!(v8a{nPh2Ln+X8aC9dhks}{aLpCCs zg8srb(17+NIg$5+ZiD0md;gmwfjClsl6$DDuw&M?`KYt^5lW0f6LxwW3 zA;He@`m)cv!<8`+DK!=LPc6fqHM-u)+w`eL;l^Aa^;8K+2*-vi;~0n0ztLA&;gV)4c&P~K^o1&>2w>?;bLGr!SP~BID-b# za47BR|4CyT!rBx7x3td*XEMPUxIx1El2dFGDd)O@Mz8N?YcxecI8HnC1U*%71*K-v zn5ovDD!7ePRj3t*r5yq{Dl^hcIyO0!@^BtW%W`>`&jIN-ad zpVCD`m`lW75N!MU1HSkBC9pQujKRY{1EmWxqYBg^yu2sb@d%tUtKnhb0~!@pLL{8% zFjp)jv)KmpOeHJI6vYwEtPaDsc^GP_jnUop*_%k7rUP{lix4ip>w6g133*3)tYeDV zhP%E8`$=s`zk4D3M;`SDY{`FMDfnOy6wViNUXSP7`si#m@R0~bG^c{;3+ZM`X{Mo8 zMcGgo-5KCD^O}fVGT_+@9VTPIVAF$-6Sb@-;v=XAALkBT`tBjevmyu zz629>1$=PkbAVEWpuPm3{~%m@UjD{Y*dhG-#*_FVVfLHPV71_W^9OuFc8UN<>rj}E3DBuHK+`)dw3nj6pGBCyZ!k6p_I)R2yfhSCOTgis zg!CVw5+n2^ysO}ygz)7P^f-iJf8?v-oxq3x@gDI<7#RwWt@yvTNQ|+5qZR{)r#1tJ zDv;&`u{9Yu=4t>pQUmcvAnpf>{RPsjKyh0rZq;Sr_zJ|jdJG&(f!G#^J%Jc#EQ2Xf zywiYzqZ`O?1!7ZU;PM(EpBK2{Iy5&mmjO7_4N?aJMhpy-*_Zs?%&}B}Q6eD1#L1`3 zP|wg*&mi5%)X>z_Fv&R8gkiG8G8LouaSR-vff%BXf#Exp9h(R=IRiL-9uIV75=4Gy zDg%dM(&W5lVqTUx3>@XzKu6>;aOeZ+&@2WHS0H{5oE2jP(#$|y51bkMTL96j4V;hw zS&<5*6@hXfK6}>WbIY6zFIO;dfG|ktFqBp;)>kbCdg^Qw14m{faE(y|M1DPx-96cH wc{JmZ$#a+6GxkiryWE{oW3uWBW#CC_o-5>eTY>4@9%xbkunRG1a_I_V046b53jhEB delta 22090 zcma&O30PBC`Y?XZy*J5)Ac-KdLl#gVpkcA%(i#%DEYaf9#igxLv~#U>#HCYh9TQxp zs9n%&TLe2}wVhhKNKiVWrO?`T+UfF3tjwUaBdx7b(Dp{qToNGv_XM5!egEhAp6AQ+ zoSb{_+1~S>bKdiA=XAKKqi(9{B84Xj-IT!|TY7?OZoDwIrTdvdL<<4 z{YbP7w)a=Q)ZV}LrKpN%UN2%g+O{ARFRsC4iHnCU5|h~FnJ+O)cv5zG ziepe3i%}XvDD9265X-=G-EXMpe(ScT1YS4bufzVqRay*D%@5(++jxB*Xp!h?#b zg)Djo#X+0|Ap=65#)hgW1x}VTsFabhwQM_zD5Dm}L0}*t4Vtfpe6t}u0AVf!w#BZo zVlC1TbYSR1a>ZB(Y6$UsxGA~ZEUMva5_~1lI-t*Sk0bFJDd^J#V?$U%Fc@T3#6aH? zYzrhd+X8{i7K`XuU=f3mrVgbo<`>%<_y)+sKprOhB7f1w=C+~sP;Y9`JObVCejDjU zD2TJ+xeLPg5PBe7g-~4@yly-xbi|Ao)N;liV;x_S$d9e12OLjra^l>vj;PwFoTr^g zPiE%N%{%(X*1qFpG{z5+XgyW##M5qgP}XlQ%Yb8pydv6$^}QaH<8kTXor3qDJjM^J zO931}7R#Wt-}=XHLwbkyw|@2Z^&iwgZQJ|RweoT@1sxld(Ke)ItnrTTnzutz(02?9 z3h&E5m?gI&z!S8GdyxVuhB-E(2?kGp|-rnZF7iQo*pvNegzwBb4=_Dh*Ou1Dfb z;V%lUhLk>h>!0iOqRH}!^lmPxs~Rv#>L`FZgdW97WwNzW3>uTm)h&s_>ujt&)*4$L zH#^=|DLQiFmuYPWmMy?B6|~o8p>M6Qm|R>T&#tdRPD(mNA<|;-67Z1fXbD7-FYDh;DJ{F?(zk z$8bU4JfSFTBEA>?qlGPD;fgS8A`d~RNsAr(o|Y~{;`G66s3Zfz7Qq=7i?za+Vfqtd zSO&H55Y*NLfo;L!<^TrB7zu0G79=8x{7(y1m*O%ku0D<0!y+hzG=LH<%VAM{ni2Q6 z&76((Gv_?7W4zUJL-qC+q}6b=h(`8}iL;wWrj%>A`)srr2;^Jw+dP+lf0B*T8>+Dw z>;K^z!n8O%$msKJ`8+n1{9xoAh!&&#S=KoC!q_xruiKFr9yr3Mly&n*NRn0QL}J18Kq5RS#QdRz(1&e7EFK%gVqHKc zUX>VqSQ#mj6p)3APLt%J__&0{dj1%1nd zGHc~P;qnz)w4VWBE=U@VY9hnuY(Q*}FeNfomOBQqqOd4(B7R+{iPYmT;mycd@~}vP zY~g+V_izy^-2Y7c#Np%>OQqcGLNGwb>TKsa5(dnKJ`o0}0<7m>Gm+%y9 ze9sfjN0u)^Ktgm%9soyl-*+3D`>Iq-Hzj@@`~sTa@0ly<5YAKbv^RL)Sw6Ctrb{F} zy5d3YO|bOrZ@}NX5IP_fSP6Pi=D7A+uAWnHC@qF7;^K7GMq2zeVB(&WYE88GV}MJV zb0(Xk3JN)S-wuq$1A}s|vUf)q$|!cBzOeAOy=>SCj=8r(LWfKM{ucp;a~2nIxL_{4 zy%u<&_(Dmd8)+&eW_iSE{v7|1ZM0XWn>hYK3AXtRmx~tP3t;23tL4RiHjh7t3uc#i z-D^cTy5_M;Oyz?TlM2gqFD*6%92`EN;aD$bX>o0!xY*@cD=tQz@UKMYJkdg1R5G>+ z-BFfVt|4r!HUH+u8p(rUzR;p_Q1W~VU1vC?V_SZ1rmb2o4(8`O0S(N+!xBkTx5Q}~ zcnb)RMkiFZ<3Nk$!E{*qkDDfR(S4<{;QaBNlo6rL77KWoVBZR^h8HdxfA?zSY z7>P-`cVTdDE8~4YmH}YS4;HquK61#<%SOb1j zD2mnRpBVWQtR0lm=~inf@%9kPIO4*3dc!xKpzmxTbJHOhrtboBSeMx@6JK@$m`CB& zSWEQ65gjZVs5uxaKOyLQO}G)8gFA%8xH*(FR(K*V8;ioLaraJk593DKMm1LLP=r?1 zTu!!+62)Oz1F819>&HE^eMJLk-H+RgpevsWbo_$KH-=@6-FG(Yj$tD-qzxSM5T-(A zRktL;SpD5knvWW6yQ($?eXi4F4zVqi6>Ab9b^qY#yMxylDKT4kGk!8o5<25&;mbly zLZ<5D;Tz36q2n5k%!VXkPC_F7Tv(N$jcy#q1?&`Mb}uX)8G(0ulJHtWGX6+7lQ4D6 zeXz)kPOL*(N}MbN6H<+FXVQ#FTz4Aj6)hBp>##NsC~e6QFvxnj7Hj0ynC*|NYVRF(MY!_Zj z%1tfv%eXQp^4b*HPi1g%Q*r@c=L5&hKDP}9Z<=r;DOPzl@Fu*Q;5|c7CCBQU|MMQ} zXSjt>+9abUviDEipyAX7q=wgp^5kjDb_56yMs}e%n4dY<#L5`%p^DUuolWN?)T97v z-Yv0*mNLuVZg0~4cY4o`fd!Pj2rGNo@v}d zSbyIOKPFGHUmBKiJ6ln<%cbGMy=n|o7uIgjcOdw857Le1{AT!u=Xxt}bbA~+q#xzz zwgGH}qniNJcPfm*QvaTQ!uB|Hm!#SzyzdbwsZGO8+(?Ovz)IT&{)p`af7y1>GZ!$y z4>H^rPN;F=cH96J?ppr=sc;umh`e(t4Y!CJSMbd>N>7Q`{8R(oxZgbB9-V$rXgej~ zMkrOg{sYovEj%p*v<>*FMur>B)h_%iWk#wskjCGH6*>l3E0c4?cO{s%YMfKQzDFq4U&ySKUEQ)k%2P7{j@gg&`lreG9TE;`mW*%LrV?ZF0MY;uwVpq#8(^`vg zLYFz#*!8AtQYUS}nHy~5T$g20!VO(~slre9YkLt^T0WK7f^*GeFp-AvACz{Xht@vi z$>bjJAk7~=NdKw_>tFUz=^uOO^mdQF7t!Cso)v>Uo|(cN{fufb(k@87_Xqr#T(+3CDo{8G4)HiJ@(2wCZq7$ACs z!XxSTFmmx;Nq8mw9;(JJe4Bm<5~d9b>nGfUHwkY~m>70m7td*IBfd`I!i34VO$eK) zr`Ak3F==811tSp_F(AyyTn&Y^l5i}ucrhg=OFb(y0MZ{u{^{8vJ*4gn_559ry5-Z= z`z0G1_I(jVI`TA@BU5t37je3<<+IiD@+|IU_&VZafM&$ClILOH=dgnow!NK+SmDJi zjZl`AGI3wBHtEaloP^PIEq%WX$Ke7o;%Yp*|nV2Ofyc_PQBhgdc(79GYTqPZ1#T;(r|CNVMR->0L5&Dl9K*mBydrm#MO7fgDK(k8ZPIX(AJSQ1Fdnvm2V zOk!D6PfMK?*AabxW$*0RwnYXe_WV1vTKFY9_a0frb`#Q!<&_qIw+)4nGWkQKjCFJP z<}Wvydug3zE8#`E<+wBG`?Njid$C=Zo%2B1b8#bEzI4hnbzQLG`ms0HxzC~}0WIh;L?@8};x zo20|jYQ%C3g!UOSoePtQU&nd)0}#d0z97$ZL}n>1>SE%-x;WbZ83=& zB)7^d;%xE!E`T0S_q%D$u@atWv##lYOojv1Ut?d2iq(b-9xZZ zwFR$Nw+OZ;#@p#F7v+(i;jr?$72%y>_scW|d@*P>(nQSU+pyRo71%~MROk>;LxK*{ z9l2Fe0qPmA&3sO}I-RIZ*pVh3U}0;9A3Ddn>88tIT-4Du??qv>q+CWG08Rn zh*Xma0f9gvwM4E`0H^s_t8(jPVP)Pl%Go9y${SZS-kra>TS0eLZ6!Lfsy}GA#(|3M z+`_)3ea+2%M^x;^mtgvk z=TAYiq{%o41+1`d@^oR-n9SsLlA#k$8r8*_74+6cnCi1c$MFs*wr3%kb9?4$ zwmLAdal^n>Zp9#IZ8Pb6DOzb;E3ScUJ?QJZ!>|$dJv0x3zPEzZ*68wZ&3wFIp?&~? zI;76BVD7L_<=1bGte~_@u(IsH+{3qu))S44qbk~_+e-5k@CjJAJ5)Vw`}_{FSU?t8 zv}DnL)D@5%^gRwBglodf2?!R^VX+LL zXad5wgYpWbx!WumR~E*VY|f+sf+q7;nmZ@Q=YzhBLSMnX_Lql7m0&Q_eVsuGNHn#I z;dHH*t;_qj(H2rx8}wZWRBc@g?^SBZUf>U9_0u|&<4 zhqU9$5^R+sj#_L}>Z3tl2MVp3^QCb!^#dbSW{6EX{q9j^F+=OOQF^<6ebD#MfC*MS zTL!WOY@T9i&_^_m1Y4wc#z>SF2hZam48SuPvYc!ErRdharx&J^W)ed;yFKsrGFFPOxFo1Ye+I#5*mA%oR`!y}lZf&fFWRQ~95hl+7ytwvkqE zges#;b(0BSEMhKk@vb|uVJc$R+zC%XEI_zcfY^NUXNQdYC3Q!V$f#s4 zDvNfH7ac0(NXA}DyWM7lv8mPog;Ir>eBH=S51M2jC_Ij#%#`Cax4fT;)^EI9@2r9K$5EEOd|>VI z(aNKs^84JQRZkBA7%8vp-H!fu)fpph&*NwCWZG>K)kw4PA0BFQntQAmRB7FUZK@6= z((O~VcC4`9nt1%*S8mGf1N!3&dLwE3KCCJd_RZ5#C4wtD)Z2I_e0744QvsB`#z5#IgpF9em3ec<-{ILkiJ z|NgNnx-Ih{_1E`FdwuUOu!kD-ynlCI^$em6`@rS*b-UvLQr1cXu^ZQJ8K5=*rGjQU zuZ$9L;7v^dF&OkgAZnvM<BtyymMXo7a_`$xQcexgI;$Hh!f}iKgl2I zTy0I}Wx)EM^2${YelHskqfgjFQozQVQ7Pb$5IZK9xj*XGqQ> z%K*4N5VtC*PD)P-PFE;9Ny=S-i46VFFdIr+!^*u_{;@mOGdgiEyGch-6IpISpL3|& zb4h_ZM*$w^83&A-9oQRF_)wEXC@9(J$RsSPMAp|F*rO<5@-_E*J* z&NUU4y=4h&tkCbhiTrpT>lRC4)s&yTnP*1(;@V;7qfK%uZO(}fzB`fG=hv=e%1 z`BH0&4eKkUFuU5gf7mKWn>A5@6FI!g{0pp$ zfrV8>E#4TvrB)u*c}bf6@!I~9u?<_k2MsJGsv_6+)1b+%MyB3K_1Ew%eq+PN>3}_! zG-nLR6`kfX)TacdV!B_gFDD-hfpNr*)>hOwql`dTXeAj^Y(Zb9-w`Udh9wG4r8h~r z-M!@sG(%BY=K-L2zuQB0m)HCr!8$YEzQKPqG3a~VKW$fS@mmt>=)R(}F1a&7?E{_f zrveoLtN_dL?UlqitXAfYK|$X_|I33hMq~)@&a(GyUC>MEWvMfK` z@*H98w`A|Dp@ze^2PpkO5G<++nsA1nNCSoEBx$N;A<&3V;DL~;YS^z1MR3Ul>u{&^p|ZJAkRIe8S>diFesyfzIwrMZzkR= zJa}(Ta?%LWk}mTS(p350Odr0(jL4B;>LYV2u9n_70eIp`~wp3-EmAM)KA)^a-T zDUc9mNmMdg6Q1~fG96R9UR+V+Wr@-%t>Z!uva!mUZRM{JKQ|K8RBBa{zj%o1t! zmKFUpy?P_jIohk+2sEUJq}Ni*e&9%TB3f@29U-oC9$1O%%0_$#2Va8!1EK#{24Ad% zjWYNmSYQU$Bhb~|2O6xY!+Xjpj^=SGu=Ikwr?>z|#>aa^6)a^Sg2~H1$E0 zL0=q|eD7&@=&I&aSyxmh*s^&0eO%RSvuL8SY&2wy9Gbx+1MbE%eQpe9u}7?V{5c?8 zcm@&LP}-1hIIs|U?Z_J!GADi_Jy?-PSX8ltjPb76H_dg>YBKEhN+t zvGYtQa&)%!z^o%{tOo)it%Sxh5D1A?7e=6MO`x7AM*?ctX2#!9;1qxb+_2kBUqB5w z5AD0@0q1}`yiXW1CE)=fzGyODCzKaG9XGbPa^Ud#IIgjb1t=IC38{{Tk(fY4P` z@L*$W@VeSM74+XSZnhJ@jl_2c!492qz8z^swSA2EY5-+KfK`qWKk%arm=8oNE22Rf zW=H?`K97d$^$>F~1roHfl@WgvmYHJ}NGA-f~<5GBIW$B_ycHC_2 zBI>T3V9PCsD*qfI3cnA^`;dCaD&~ZaKf)g~XMOh*FW8Ro!apq&Dhq;DJX=5*)?(oL zNl`s$j-LB3P>gMtoejQId?i z1SOY=zY?Z!GsbpEPp%qr{<`XYyjoqq{6Tw-c5=%~kBd|Bd*L=4>tG4Kx~48Oum z@|+gVaI@@Rf&B=Ho1{z*HxSFui9s1?FOc{m*jmFt!^*Y{`&I(3>5D<%3nPd(nc23& z7OVq9jW!$V!$Fv^Q;?qV8qvzCPp_5aBhe%=-Yw`;$uSo!?C|^rJbyj6?P{S3iFv1p zktf?Y3_BOne=2M)oopZWrIOKv7D~Ym2E5MDB@huAfCG$%KqCCz>NZB4atbh}h1T-1 zjy2*M3lPrtMn(w;Yl3a=Bety?N-^SfNyc3U<7*U1I;`9XwR{z%Qxs5t>hFh-Z z4gIbqWJYMBauBTO!fExrY<$$%gct4n_yo}u5SZUe8BRY9Nh5rKOQr(H#G zmpp=vwCggD^DoJUR?^l8lo$Y7=FtA>40~WCc)Q~gIm~VY& zDd|5~U+VRAs8HHL@S!3B0p%dEq6O^(8!~7WkVs4P-FhouYGUkQ%=|&JH3=Ys6Q&o5 ziXErD=_=NR^C>~k&x3)+Q!a4zrP)6U5^betQmNgffhB-Y%BAnU{PYK4RC=qOK%BxoW-b$J+4msdBvn@^pGn-X z9U9+s1in3~Qo=W6k81}|`8!oZ&1lnpNaaJRjRWKm$)r5w2OyNGv`VicOqIzV%@h@38SN@<>vc+r#NxnfQkosu{4fe< znO$)rr82wYK+2A22mTv$G@9^eF+x=g2t%rI?Tnt*pD;&Uj1yVaU;Ah|>z>N#c@3~{ z^`&^$pnFO&nm}?guDi3Qz7!fTvM_iXDx;y)25Veqi4v3clyF<+_2d!m}j>C!;5HH11X-}Zq$GG z$P-DsOPGB+KJ6lXAZVfM@w8Lsu67kiKvTFjC&}ECpcza+dkr_9DG7JKCZ%hpWF>UT z;3>@xqK_J;Qm$UdgN+B)dR^%~9`aOIdfFSDC3C-%L@Ho_7Sux(t)5){HP6r+h#i0+ zK|meBAXKT=aJiW&?PSFDqMCkz#83iF*7NuNKurOaTsWzxzVzV|@FBYht7Rz}RQtI0 z675QDeJL3!raOio)!lsVebaW`tuc*9f^z8`(l^GdG~14vWqOMkqA8wk+z zOLn(M9y4m^7l(Uscx`)>6rDsUMt$kuLxY6fc*0QP`YQy?1eo2>`$+>XeBVu=0V`DOfToIqwX{n0wEM&@&Dv#dvMlXn zO%7hAFvTv>j+;(L@l7=qXjb-8lp0if261dSNlAc#M|SaD zN8~Ycag-FFZOk%>uQ{>?Ix4b6^_?s%s6pO!B#0RFf+x(5o1Zy+3H{Bb#Yg&NN-%{7 z>U%B#5khu?xj66=y1cG|P{*~ey5Q^Di1xVVh0Pzw)_F*e6GA<{+u;mRt~~9vFI18K zaj;per7t#zWtDe@8A`h@U8Tjj6FB(Aa@v+xPLVjqTK3fg^}hCctr3Mfwm zbYK@C-Ky6AFgj`AtpmgnW<#fkjA^=-OrBBdR$uzgFRcDc&nd3hW8p4xi{SrZPr`ts z5~f-{>Y?(xn{A$=n{q0lmr~6dSaQ6d)B*DdLmkRK8SIQF%(uGjcL@y{jWi&ggecUP zl8T~W&YtF6C5G;|`dDUj{-@kzVx%Zkk6_w&G{vRQ-yR>IoG7h=mE4@!PRo(xukae0NMbnJS>U(A+`|w z%5PIcHdHP7pLIPW*Y zqm|9q*vEr27=taz#UjOoB^WjTh+ZFU>d1hXQvT*S`Kw9k z{Z;L!{#7ipOs}Wu*N$iZa-(?l$zQo=L*IWW78&N>p1<5EdiLb6e-Gt-w9{P9>Q(7j z^Oqa{jBC!1*CrdtXKG9zF};hmG1kT7H*(tjlU|Cf4N~0;uj>2c>}a>Z#2!j zu2wSQZJ}sE^q7}^n9nWYP<=V{_iJI+U095<1?G9759q6V?mf1=`9}63P%Sg5?WLq~POItZvzD zj^?mCEHHSo6c#u zYMv603d0YiPAK&Eud){RFZ(ql3mBo*M*L?EUWsRLEm*rFh7_bJ|Ojg=oj>f zlCbH)>5C?Tj~>Yt2eY})V_uc#Yzo0gbz<#^uM56HPcyL_iCJfGDBgXhx|GOcvqOFj zNc`eVVT)=G!)0xX5{Fe`?oSkoP9&BKV;)MytwPR2iB!KNR6LY7v$`d0whY{dbepIw zQsLx)eiJsx+{Bf%?P@g$Jg=M~s-@3>WmdOD&DMj+km4E(${g7Y;olF9e>`%K5x)oZ z57->VD-t6f19^-Qlfm1MNFj{)No&ZkhA40Zr`RSqy%14>^y-#z+`Ga`c_KAhw~6Ba(41b(XO?JqQ;^wak%xJwdyq!yeznU_!U zjJQQ2M7@bqIsYM{>JvnNanC;_cJ2W#xf(+?3kN4UiT)QEkZ9P3G~iktl-0?Ak+=yW zI3wOSC~MTtP#dmx;llush}v@(BDNI5aR`5VI27!m2g{<-4?jZu+G50dAXt_lb}xh~ z2qbd=Vg;mA&`>@|WFS#&V;YIf%?L|-DhHkcJ@D9|ET!Y7uZHB&hVpo8_!K4s-MmqA z=_-^^Mvfha7;O#cq~n96w4I_ac^K`pWw+t~k7fPvzoks{B&CBoVG1K|mKd#~PH{Bo zqk`Ev1MXiur0M|>m5}&p4bw=AG))78{80_oqjXBM3-AHM14EVrqB0}S0!K0Rnb3E{ zfWLJYsJV}rQ@WT&lm^CldY2tsdKm%GYQnHnB({RixFK;>q9g6{^BZn$mY(M! zs0B|ku*Fu5!1#jlrQ>F4jjWzNKs8{XfjIA<9@rp(4+Do(PeRcAw02~bso!X&=rU=8Tz^A1w&i~p&$ zb(nO_MBA^BiFOQ1JmaFp?BLyLXn#AD!9lMLWoUp5Pq-9skJHeiCMe?=t-MYSv-OqX zOpeUjeIz%i&KF);0oAR6+zYxtYfj0T+eNB>7T&F{$^ln3E&evLovR!;2T#2t6ReFT zv)mJ`_2!xGOVa)(lB1+osa(W?Ri|@gw7|bc7M9E!c7K7LSem$$Z&$4mgRZ z{QuURGYtA9VfFjJ1h0Rx@6kWXK0^=#LAI)9qYSp4pwZlpsIDoJfK>(*yA)m@}YxnXTcmSSAcVqQy&v z)JJ2+v<+h27_S0rU?Zv(iXPS4-)$v%Q>@i3qpjCA(c+W-#Bw>nu?d`33s1zAlg_O7 z8&A+;5_tDmz_HVD&Lv>cti25#OKv48cr6Tn{bEgTm3rG-I9){OGaruyml?KB4omsmc0~CsXh` z(pL_2ucyi>Fm>{9sHFhf$rLh|HsTuLv!#`Ikq~3E;6DnBY#-x)3W>|+;rE0!AS8by zv@TmV=E*^FSdRK$vx*X55hgBA#zjKOasyr>tXr#FdmRSvwp#|G(p)I>Eu7Ct=6@pxvu+295E?Vaa1cqZP1g&gBel8@zveILV{5wu&wz7Ox@ zNr5~c1d+B7YQ8*#v_^<84e4RyAH^fUP=v)!tq)h;~Zka@YN&<5rk}y1J5F8%}lBaBVx*cS^DF|x` zlYqtF+N)c(gWCL&Rg5uqfa9Uv+zrd(&v8;*) z^iwW4#$pEE1-u$}@F<)4;p<1}Y}%Co0q1)?;h!H|1Kjo@09G#1=yYfNj)`LnfOIlwfxDo*HIRfJ7K&J+4E zbsv$_QVu@o+w+kmcvIuq&wu|sD22Zr61G0^h@3e3FkI+#4f1YbO#lh2|)DHn{aKCPFNCLryi;fy6WoiL0d;C+Wn<(6N$~t}+G|aa*rYme?()?+&6FhTNNC3SKkaO6Ce4jD@U7=qNnck2_dnpmmRvlgX04bg0}zb{ zr=F8ne4#bLP;`!r9swGirQmfYyWvqjiP*xH9Xz`V92$52Z-+*q`U$xpZWzb@67n)x z9uy)rCa~v6MDSXh*DkEskVOrR2z47$CR`sOkY)sbg|md$-4p;U{J_pL^8&z~Sdl4o;}Xc~Q-;nh)>5-@hTHHR0UPJ&gBxSfBZU{nCS)T&|46 z(|5oV*7+QtOKL~ny752*G*PSSN>RpZu5Ucm;MY#jFF3}J4~Me&cJr|Bx?gzgsU-W- z_Ug7GXUA&u^V^>vC0*DR^gYmCU0MjM?vYidn_>9}z^|g$5%s<4rXuwGSBLYK891&_ z9biR_K48vvId9e27rNGpak6K7)(*_I;bJ<|*F|UE0!0KCDVaL<@Z%_b4cG{f_>1EK z>9JYSwj;HI%unw$T@cE)+zqHT@)^OkoVPwJNS7-|Q{-;g&)4GSib@gw;rFB~T zR{^h&SMPwM2uQEt-jEi<1o&`R$XY*%S~)B%Uhj$`eI?*{ztVXPJ4PvJPd5hs#E`eJG;DKhz zFZ_PZB>cYc+L{{s&x3ypNpY)2PI$oZC2R7KVnpy%ar-2uW8UUhHqY+G+3w9Q@JiSx z(RExeo=~@G>?Tuh*rYCL)7-J5jZyhu9I?9>fd2c%0r?CWFkas{h^mMF$})ZB>{c(O zn&4{n(yDCu$Dn!o$dSz>@y~-uc=q>2_77n5@eqsj_DuLXZP4dInI`c?$5Q``UK1=Y z6D%(WeA($R@b%IIngo!K{>Otex47ZWhz*+;5{rAG^w?yD#sFOVDT&cE zIO-+2reR&JN1Hjtt(cTg>d@>j5$e_^*;`#mQ(yW4BqiOcI?f#_(ve*fZ>*IT_8`Mi z7uMW>^oTp@EW|vJ)`Koe^CO^MgLwFV46O{ENg{;drKU6;IVB?lMt#^a5i75em={=rYLr9b#CJd<}4|M@D7DhJG#l#1u!iFg3A`cEa> zA+>ggw8B_9Fn+@hi9W>ivEfyJVs7o;V272_#B)_u=G#40mv=C?mTWk(Ty6dIT4aIB zx?5uEih-WY;6iek_~;N}$wqt=f{M^dyligB#|;0~Gnab+p1S=C?htTa8-Wu#2w?{V zW6RE_oxHL_t$kT~*vLR>*!zZf&~UsB^cTw5{W36q`hE8fWx(sdhscpSQbBb~1jl3; zV6`JLMoTBBqL?`ufQ86Gq(7V#&uuqTUWyvmZ9=r3GFDZ0G;6BmJ+z+DSgXVIZ1tY% zFRH8C!sh(!37hj1gdWeYkAR|4!by}wJ$Z?&7zCuhef%Y8>@l#&xghR@fXb>%1Aje{ z_jChRz6W{*bsG!YX@>BxP09AR1{ECdd~=fnd@RleN~LsE-HPu$vgtLm>|!B+|8`)l zI39)fJPavAzQX|#eDYh&p6`BV`)f7QNNsDySQPLO{%Oe9&?dp^-nj|it2k%lhkScr z!y--ze&6L&$5Hi!D!yxxu~>Z{5;gwuUNu-Fs&w#a$oF*M7ouLO{6We%R13=3WDbtb ziLT)q_>!*C1~z%fmpnAeCKKEs z@sU%&=!@MWDl5Y+=99TPup_5%M2FQ1LX_g-kWV&*cqRj^$Qk`ElerMA$WPh~HFQtH zF0ilWCDagwPc3ljM5FY#k#KDpy$c&6z^Y5v05_g*u_3Vssv?GF7JN4TeMWFStHI@h z_t~icapsnXDes`LZOb<76=Z*WRYsWqG~x9>recfm@gE<>nL_GTE%l~fFmK(0okIK8 zso_Wc@_ODm{b7QzaHH`t?9TNW_EVXOlI7*E@lM)Ao zckLXWCG^|1)R{qHyu*aY2oF0Z;y(#?MpJV~ch+?812s z;6hjg=S9I!KrqxSOMDb`d;uR1JYaR(A=p%q_yEi_los$kCcIViEdH~g-=>GYm2N9F zoDTA~F=d}$qh#Q10NO6PNoUkp&8Z1MTrvo!P!#1_22vQFYtDS4b2wA^}nsi=b z>+*k?4XwNfXK$NMgn6?;x*+w*Qs|2sfPL@CCC>#ZF1OE_WSh%&i{kllA_ z5Dw}E>X&F8rARe3d3^6HT-C&+eySPgS-g#!Y z2;=NEp=Z0?{xhs48Q_VWtPT2Fp%{p_0RL)GI+1F~*(KtiFc);9$3j>+vJ2-Qfl>N< zfcU}5xBwj8BV`+*Y&et+`W}PkUT=Sb7a*qqIh#YZ5CP;1sO35EvnpTQ9S_ zy5&kZ-}Ab#W=A3xgk3xII9+&eM9*~ zpl`CUZfEZA<_D1;TyCERK|K9d=)APp5)EQ=^lWMZJyFLi`NUSG%?d}9qWET~0FL4@ zTiz{^EjKc5O= zf3o0cVa}iII92%OPg8K2KtER%@$Ud(hV&~2eMd%w_0MI*3=RKx$&Vf$k$lsII=0G-}`qM ziW|*`oRmER4hrU}1HPlff`i(xCdA*Opdu=z|vT`zcX8PZ?jfx_n zPv_7CJiWoD=cApCU~Wb~RJRe3t_i{EcA8b8>araC-S6H(pkc9d{KjI0;^# zPHqdZ$ib~}C$+xU?^L5{}3wI{dsfX)YELdhe! zl9U(;tJKa7iQj{(Pj%a%Z$t2whq8u4U&ze^)TvXT03};$4bV;%r)?!CAf?KHZ{nG# z)`0H|e_RiB#{upbXpK)gUI#xZpx^$7?GpR$gC!AN%sDuL1!5C8-%B$g4*0f$;~G@* z(!&yyB<~AXYDJ8@0mbVQE-I}2Y~s(sJ|u-Zx)m(A5 z=Z>1^oy$p}IFw~`xvx={gSH6gSNvsL9oV}mId?(HHzwHU7b|UfHkLPm_gl5C49;aU zMxrH3uzUrKZ@_2q%e^e~gHs9i%5FH+++d4xc1sb)@8DvTqa}vod|SbVqkS@&H}2Nl zeBKK4b5zGv0(Av^X`qJ+fWz~L=6bLOv(z-0RX#WawbygBWc;}|``8s!33uF+1s+T9 zdh+@3KAPG9PNbO5vu&{51tpq*Vm#xS$(`|-K}(3iFVkW>=OI;JAJm4hwGob%qKsJs zj~}1Lk%oM}Ys1qZrO1QQmI(iP!9sPk3P~@P&3pMY+}31^gOhr}>!3|tUl+L9PX(fp z(neV=7NoI43YkLHEya8!NAYlk$ofkxTXs1>l_)ASae#KZqz}VfzUVjFK*=MtytoM8 zFQ{J1NuN5b06$DMY&8Mj3qYQ1P7Gdt>`^3265Wu=u}1^GbYa;`R?0Idy#G=X)io%5 z{nC8ueGvKT=Hi{gy1Ms3Uz57GBy8SZ#A+c}g*AH(wT0?j78$oQ)0_={LUugOgElKlNSiL z_D#lFLb@<-ArkYYOP(34kiqR*0{`E-@G;ZPh-3MV zvhU8I_8hpwhU||KFoeazy!}&Sx?A7#vJq>pG2f!hux?~X=!Q#*gxB`RgVpkH`?YwU zaAAKUFl4v(XQtHsH?No>{U9+tKfug{1G+G#pX?I~UoNvh&yf=-+a0^jv0UkeX8*RE zX6GlM(@XOsaj)rBlc^U+>^D{R#+KN- zZA4@sDId;+6|sSc{yk>Jh0Sph00?!CSe&joc5q)N9BFn2M#RW~dMp53%m$Ejs6=rG z2JE=wlgEZ-lAcvj_Tva**g046mfxPdRoZEbF5&)&QPzj=BJ_*>8FP zKeWbA-+tAE{gg<6x?nO|=m=?R;H4(I5KA`hQ^e0&~{sM|e{$GYANSss0@RLOcPXC@jGGcb8Cp`Aq~l*$d0!!T>{M=XRHH7vA<#VcO!? z`@(Vif3Q^Ai%S6v=@eke6K@ANawnZTRgw*0OoU+yGl4sX;!uFvRax>mSI#AT7wdY| zd7>|p`duGZDEtvaH%+s_)y8K6Oie@+Mh9^csGgM`Id|@Vx7#BBm8b+dX7;LS5fGlZC{+eJVnWE6aoiIa$(IN&4YQRD8vTYt-^L2-8lvs=kOMYXf_U&Xgq*?CY#Yhx zx`y($_p`O?(h*MqoNqx!sRd5k-fszA_?BnQgG=t{TlQ%B*471$lmJsg@=t>DxBNNq ze-p0cxb1r#&XpDLw|%b-XIc-Mi`*!Ue0^njB5bq;w%fkF!)f+11msG_=^tbyIp7@EU7RGljoMc$&xGKEZm}0*l zb_5#)8cqu=w9rJZ)3E#eWo^&PPj3m_rPVh zeN$m2kawiRTDpvFx$T=YOoi^=gNp>+68aCO<1<41YpGK&fCR{dWWm3} z!Ii6U6+t0rbfOqP$ck`)5NsX`;i8w%A(t$a>$6}6=*rFuYhQZ`t^@hywRLbO*290^ z3_1h%pTEH$3V->_n`unB%o@&913k;5;lc@WZT+0Ng0vw>IgCXtM0!cSl?ownh zZVfQ(F9$Ww8x|toBAxK$>!;>B6OReSC;o7FJhpq`R*+p;h+PSBIeE@N?1hPl?T3&9&%5B;wEu5F+7XCrq4=N< zaDTKe14kwhx9Tx)RDx(A1{%wd3zR!($iR^e6i)?WOCZ}CNIM!caD?Wj<}v`A4Ip(O zV8j3%!&>r}1vC@BnPaH{<79(nD)pP=fGcHy7@~%OVKsf(O(Umrve%y%)k#}F#ODgNZiew{A`(%;r$8*4iE;}bskEq7VE1P1MRxo z1T?D==#HMw_%F#ubB6xjd( diff --git a/boards/holybro/durandal-v1/extras/holybro_durandal-v1_bootloader.bin b/boards/holybro/durandal-v1/extras/holybro_durandal-v1_bootloader.bin index 388ee7ac7afb5a0f3a9e53110a7ee7d5923ac7bf..419f629fa409c553651f7c1834633093755a2bfc 100755 GIT binary patch delta 21983 zcmajH33yY*`Y=9o&Pj5*(R2aQh4v(Ap>0}77odnpnzW}I*s>@E1X2p#AbKf+R}>^E zpp->L4tiNc5nNDIXrW5M(kkHYy$R6YEmWk65}+<8v~W(6w)wx4;=T9(Ezg(dnarG- zcb4*os_|zRGw6FDe=>!=y;t-Q@hOdtw@KoNPMd=t~~yK zD;ZXb#Pxn8CU}uJ!-vEb-qxOq7h8Lly;vc3>CemC#^^*$ord_lyyI?q$Cy81koZ|2 z5<{V$s}Hpn4n--f9itQm0zxQ7eGsv=W$TWdlTn_&*P*xcI&wdQ^rPiizTf0yvMp9;xg-$go=jBAm>sn|QP4JxfpXXl3!og>#Bh~^uDJSrD z?!Pj)lo@5G<+POP@NW$M=ciD&QO;@Elu`kCnNR_xn8kzBPeV-7+pxc##8D8NVMr)t zJ0dyZX=YIgU4*B>Fw@MvCNp#wOmAcS?c)KGNqY%W=k0QDN`-i&z${V#-kairPRxM9 zPlKIl(zXLoPMJ;{Wj!yeVW=t?I}MQPl#$SgI)xJRDNTmgbzYtcZ*H1y?nN-TnJ~C2 z^87eFKYkk0=jBR*8MC?90p*o{KI`m|ku#V96+{3K2>_`OY%m%ci2knz0rqZVq6y$C zQ>Y`g#bm7O8IG-)t-^njJ_NSQesRNQ5`Jd%FoD|c?6iy1c5yxTNxxiEeE8V0~h3u zJd22GEWvg<0PcGz{~qEC5MRiPg4ViHVk~FmF37tMdDkKS72;nZ7V|RCz~2S=XUO;& z;$Db*^VBVaZ-5+V+F$+{xQS2z2QX3#-zzx#u=3$$Fwyx@^>nY}iB%0aJIWDV|3t%Q z4M18yL>`2@j1jSE$N>qVuu-h8tyFbHW>~pn^GF zZsRAl#RP3EgHrzJiCTyB4(%U3>h+I*R0r*??@`yQN?kHa$S0LPg+`E;DUWlUZ(I+> z0qJePx$uJWV9}q8jVwr{gDHZg7@Gyt2vZlE^=D~qap2eSO`%i6d4nyiIgwAd;%!L0 zEvMV?P9)X~c9oVJT+(^4j0ySXK|A%(PAyPheHN)Nw5g6ouuTMvE3FU%#<_x>9d0Mj zno^j~5f!2%8|Z!nEIkO^h#5GhjP_V9^zB6!v&8y2 zkl5gZR&?jTP5Zn216md_w9>dCt<{D^IF{D`_>%V5#Zs4E;0b|VC_%@AUm9HDyr z-V&bS15$-BB4kwQ!~oYEnR)pJ%BC*IS*auHmUvsJCEn_F*A@>B{=A%-bzV-J1Xy1W zSl10=ecfHGf1t%BNF3+AAiNYZ9BYMlL-a?TA!(G33q`CE0^5Ye!+s2-W@OBaVV+#eepXE#>(8thCtf&n?IA+W6f26RniqP>aP7AG{!@ z#fx4>pKHyvVMEbnqs@V6@po@Vxdw6=D_8P{9f_>}fGw${)3(5h#fSP5;MF|7c=(Tp ze1&j6JjVV?e`0x90}^xm2@tEq27i3;*%83vt6nTV?N^AKWJVuSVyGqc6fgoLPLP$s z_^^z{QGI>xT-#jK2s?oWX6G1$U*ABiHUhC~NS}f5ErcTw+913SVQeg7Cq9eVAJY=a zG@_J%G&`UuH{E&Kyhw|7Ffhc6GRKqoL#^K3h|L$Ck4RRO4nb^*&=4^S&k`<1=qYWa zFc5JciS8T1(e(o}gz6#7@CSlxNHYFP@C-?hd{a*2l}Bn@IQ|zK5}y>(BNxwj)ypK^ z(+T+^twdr6JcV~|Y?#hZ;L~85KJYO~3Mhp=2TEct&1xX&x4qh~9DZ65;sWIVe(BIs zWbin%gE^ChA0tQD_sL9BXRzioUNZKU>*7Y#IwA(KSvRB#h9AP??YnrOyN&-l-CdFU z_Cau5l2Ik%I%H(TWAn?RZ1v`dPPMHKrZz^-D^u_&t;iK<+z8aVObkO4x^PyM?RYCr z#S_x)rWvyK2;E&b5*8?TP;5W#LN3i&yFCcw6FdXQR7T*F|(?1!IoC8%nO2 zbVu1LL=+xTUW&4#tnoG&IikAHJ^o4e!bql*65kDc3El5-SIU_v+=Ij8ZJ*lkJ)x!| zS%=(0cGQUKP5dri#iNv=d?~Nd)f#E>8Gi}CQLZ=9Vy&M~oO&{or}FZ7W%mY*#b>=r zzT)Nv7Nr$BQ8ycU(8IDvd1g|ZjP{klFlYH0{zzddkMkU!9#219} zm}J&;;ySbmRQ`C3Ibs&9i-7cgfE3RVK8+cH3xz8&1vppG#-#Kz%?!c(z&d|TKXJ27H?fa&7+6r0CQi5rDqV$*Sn5IHm(3qrxr;rM%D z_RtZN@&c93jAy1I4f+`!$Zv)%Kj+MiC@#MRi68dC87Cg<6W#eu439kOAXGvityz;t z#x+bhI#kQP7QksLeyvM5_3*G%z5Pz3(h%)RU&VMz5Of=`HW+Lie|7OvoBm;>Kd=ai z4++DEO$#|Wz%|b-p~R1c<--iPPS`t4pZns#b3nl;t=*;ODDgrcN;}}hdV0lo?tpaG zpT24zEbcG-N?0D5PLr+VC=$;JJ;N-qc>_A2UT8TGtUod!z3vzOT0Km#4j+c!7oHqG zl{%{tJ|CWmzZH6hPlBx@TQfB7+kVAv($=reAGavB7xbd#Kdvu;*V-p6(9EcC^egss z-aUug`i;=~Q2#zSUIM==%GFJYwt(~%nNKm=+j3oP3P|Tp5Q<=%sB+9DKxvtG@Y!MG zjFiXG5u*mV$JXUwAM6>4dpHMi1-&U$X&;1-`+dYroZ$kE>kv;`q(ttcxRpt|Eyk=}Rpz4VKuvv0hVX}t%7`}>>DyUJz z?;rI9$7}Kk#OwaI0Kx_k&JYuZ9t6#xC+l(@uPL2=ts4={TpDerGfiK)h zHwgKU{@>genh6^LoKF}M5Md?OJ^s-a7~MKx;5eY+Xg}J+@PpJ+*+5!S!OrXUEw-+( z9k3p?UA4aMt^^d6d1Ff%zO8|@2CbMk4K}k0nn9jQisNJRzPo|+l=!s|?G7#7Va9uU zU4zXA`4|Bz)eqLGhZM_yDwHQpEX?(%*lxiZjQ|eG)G#3R22z&9Ht5$JGSjXBsUP-` z{FW5kZFk_;XdvALo24NN2EEtU)vPWd#7l{PKOrPV4->kQlo9nlf_GTrFy4O%JxRG# ziBC`uHNvhjJGnG2&xbgx^-p@y@CmjXZU$OQ5>6&(YmBFqRj^sbVRwvrfCj`>It?L&4^QptA!|iG7x>Xe)zEO zWV{R38_>kP0}%wKK`H)A7Ut`D{Dkn9em3=kcY8`s^56U|*I5%5Pkq9I-22C=4}Jhf z7UegEPD!;X#d*TCl!=tLUw9#9G&3Nr@C$7z;~0hL3JAWGanz?pQ z>=YtKjtb$d7j$v_fb_aBY2+BZQFv^mo|--C==PD}6m0JY(v~t5J~UbrK%BZIMjR6PhjWNNX5p`H;Yd0s49nn#`ue;68jz~}+_Hc)-)~*U zHUy+OLV3mnJXLr$V+QUQE@mW5*werNuQ4{g7(vHa34CV|z60Pj4K3GYvR$5(fgVr^ zGF>mEs_ac+r8YQ7pAxbRaWQNAa^YlWGd(T_c)H^-WoLxhh9{#6kH+we@X(51W{+lu zUigrX5q>meO%5rgJ!%T;U2#mF95BeFxG_Ro&d-drmm)KvZgKe z{)(GZhPTW%FvBk#qN9Y;%vh^m!foP%$BSJ}jR|^Uu^>X`2J*;0M;T`We}!h@%HmF%eM7I5McuPrPoyV6wvfa zB3!`wC(iFKEz<6x{}?LBWy0TOj8)d4Fh!h$W@Xz^rgsoa%+S zZ_vQ;(J!4FfIS#QmD(m~{W)k|IQwv9A-(33GO9gn$_1It?^K1iUyzw91y=;Jc&dmM zXP_4>dS!^K?lcCETduZ+^itbYzE;79^K(_<7ldoZ6v{RrglEU&Fkw`-Q47j1eJ{10J6BjEHWUWA_G~;q?5YO0}d^{XvJBGNjgF0Z`Z92<%XBuX`GH{ROx#Wh{xM3Gb;O~fB5ukqsu7m zT+H#iDhF#iYDi7p+IHxIg2M*uHk(LSq}#KQ7m#KK8KF2h`g#4#q`bmo{yV+=+87HFm@GHXSn%lK_p_~*n}sX7rxmSb)+$6= zu?XX=1G8CIG`s{`CD_JfR8ZfGEjZ<$?rAb-!p21FZMT~AcehV9aE?}EKsp*=bTw-h z_NZcNRt_>ur%oYV6kz}NR=H`&5*1L+{N}K=M&Z*j6XqWJq-O00@ymLii$Pg6e+#{Q zwf>M<^}WWG`&6fjZm(Hu5lwW>-?VGv%FFP%s_w+?jg8$0B110?E5rJ8avrg|vj zkRqXQQno5f583sQy6hTSPB?R<9a=(^juj#X1zuuW80dmx(_qDb8WN@HdIuK5ib*r+ z^qcj)wKaN?q4n!1z5ellG_KDCYhG0nko<5~iNyiw5ZQl$Dx480#W)05SHMBfz%u0eHA;QvYnxS7;^Gu9rjZ`=p&rn!Az>)hWbRCn2*B+DO z?CN830vGAqIIu$=*2XptYy89$9yzij@)pZh$(bT*O&y2WD-gy)7(ae6ZihH7e=ukv zo(!R7>|mG#aNHVR#k5lylq*Sz+J_(2uOS*t{Yw3sPSvpX9r7w;8ow1bmN``mhz52} zB^f=z)rR1trv?735RgEpu76XWZ-l9;qs3$z8#0`fA>4@!7hEX)oU5$|#kBR9&>K&h zZd#D_$)R0Xw9`t%*^blQr|C!`VVvGh-uZNYgZnQ}zVqZAHyPYJ?I`0d7io_&40oY1 z_THMqP!B27Cf}KVxUIVl4N+Fybf77%RwLlQmV*T|I>-@!(EmJe)Aru-!x(Cn9H#k& zJxq*#rRW~HrdDOYz4|c9u=lPyJlJ+Lv^{BpYq04F9slQsza2Q|o_i9HprM)-naOF)UZSPG#Y#%fE&d9?xYiKbN z-ehtwcUV{U<1-)^fF5 z`~y7Ghv(l!&}QI64CC+n@YFTknrTofeMoxjwSPF+rTF2WL^R+ugWxP?S~Rydt;NC5}}3L!SE|Id3@{ zV-g>&dquwYjT4}{GKmZ8{zo=0Uk%eJ(rOs!oH|q1AztMffeyA-h^DY)pM8r5zZ8(} z_}=OcgSG#&?-f|{lrEotq-P!d9HdtVkCfFb@ve8|`D!?3`V;lEKct>)pUVJ-Y@U_n ziDo1&sS8M#`tC~9FLtPKyV@3Ioy&4LRcTC(t<{0Bg33agYV55C>Pn{X7#grU9j|TtjdE`AG_4lhus0 zX@z)OK&q2T8Qw|oLzG$sA|T!NzVE)QLhXY%`S}`4xHUVR59C}RX9Q9^P%oSlSL842 zKp7ZvMLzS!L6G7mUzBlw5W|%Qdqfa9bNnyE4*4fq zBmRxnj5RL-t2(7*Sx-^)p*6q?YXBodmi5q}z^latH-|(4Q>@8Yd1&Q5Dyp5;lji+O zWqSd9R|j+Ql|$O;J>|{R9+FQ6l@EriJka4J8U2nR2;M_fhO8%%oy%h3IoIrK zgQ!0r9A23JpKj9N-@Ts+TPDWY|L#4Q5RjhpPS{jm_>RmvKDx%0Oe__XgmESJ8wQg6(bsS=w*}ulTG466bBe0L-xTw#_(iJ@L!`dd%lHg-z+Q zYIz!D-krq?5D1X|sx=MN1W#~%l5PNlVkjWJAgsPO9gh;;x;JaY5B)$rkT+ju`5RUu z$pF*eO30$N$sqi3FK5^4fK&_QC%AAv{qa8Oc>fceme=w9QmH(mJOFm5K+c^;Fd&6M z2m^yG#Ay(hKwJW`4PqO_^$^!Xd=TP;5Pu2rmthsX4l8gu!285P$b*mwL6Zj7La-Qi z$V=DQ7s0GAT}cFzKSxI1`o%K2>6{#%uNTn@Ai@=&L7F_z2HWnY64R&wX`8pcWI%d8 z_`lh^@&16cDX_7;qPO>P1bVbSseNEWDaF$~aC6~i*_wcPvvolC*-GjOqzm^`v5C3! z7sV}R?4DH$IL=LlqMCWM_Ch1hSua0iS|r*TRmOU`#PsN@Wjz>54#;J-S6xV-ILefI zsj*E?scw^vQHe%}%xN8RxK`z-qjBzbc~XJOKx(Xm)INF0wCgUUt0^VZvp;~+=u3lA zbYAO%DGvRDsRyj~t2ROiSFJRFob&6KAOr5ilO&gZNstMtez5$3DY_-+VBZ@Qn^0<> zbjp8VX)NK}au3uX@jY2@%i%0y8?Coq1>qgdAY9&6u;J|maSzQ0b8SAE2t800Jm-^V zi%1iLZobKW3+rnZf;dYbSXi11(qT6FXM_LY!GCq|KQ{QUfekEDCb}u03xHEs1;9=m zTQ$1ujGR|>29B>Run;F!X>43BN;?Lp0c=K`MdrdSvic#5tVtBiqAL~5i~%mCG!dYL z7beHshnL5e?5-xHHpe=9Nqm`Bv=?Z5*I)<*S}}k_El4}3dT811>N?$S>wxs*00{El zCpd!4KIxH9h^aR0eHMj72>mbw<-LhmLgN~Up9f}-P!tg}yNI|z0_>4p5JLNoz{VGD zM(d6sUD2)TYP22gS#QSYiD-+r<2_r<^hLA>=OW>j8_emsSmq_N2P*foIe5hxUo)^XSgC&j8q&pkLe(qu&hASZAWCz zIkF%8HK6Q9>J3Z!8g#Y;w)f2G=YO&ZR-w`|a_ZPXjg196KBfz0=3Y`U1$0evODc#; zMm`gsrvyH6M|0n~6ZwC*W17f8|9XIECqQwn?UR^3urYvTkYH$+aMscub`LR#s`nN5 zNn3=s3g1#7+m|LJOe=~59mCS15%_|zsVE(PAsj8581;$#C=BZNCCAJv*rSnnUI-K= zB>w^?g@{Wp%RI2%6r9&Q9DH95Ft$Zz0`rkDfuC&u94s$LTq&pXcsG3zi4S`fpd~=! zX0S1a0AksuerYoxl&nD(G+A3uu`T&cSO*poZ6>rw5t<&0^o+-d7T27)QIw0sdu7J6 z2Az=|m0)#-^p}wSwzB1Vz6pt=j}z-krmK0o3p%rkVB`XK(SR<~pSOZeyz<)+G8b(wLwHWbbS;1cgHA^%IL9EgUt*i{t zNvcZ$DN%T-SU=})vVJo*41xU!%8`B@X%n^(@ipj60q;i)8*&Sts9&dU!CJH=AoZOh zqmAITO9;k}^ZfgtL3GM)L0yt&-&lfJJA{cd5o=D0lJP`J#*>l3 z3wCpwS2t~M2rXnmX^oBBKvj)&93NjB(xsO16k5jR2o!*(c$^O;z(d|dWbnK0xM@C~ z$GK6fP`b~hj;}3NH&KNQU!Jth%sOLaoQ!0gfYK#bbbOym+6?A3b&GI+>3s{UU=6n| zsVz=!f)(;EEzSmnz28dhBpl&9neh_|G<2%LW@!$c5_*4F#T7ZzaSTR<^#&`E!e+|M z#FOUR=PgA&=XMr*+-;E{GJ|sy2?#a@_Mq^4X`&r$w<9mh)@=fa`-ICy;vefzcv2%- zC(fk=gDq%V9`_BuvpDrfLB{)bCz4WXyT=JU6&tE6<_r1BnNvDWcnp#EIb$H^BJXvc z@aQ8aJKysd>CVOwLq$iI;{I03&*m434ueo{r3bfvt=j1^vQlse>~xN zIMUv`_HZZam3-(x% zi3|s%qL2!a3yBfKBP~wSRctGxr}Zbz;g__kce-g+$c5wJrNaSJwX^uR2eY#4zCtvL zKr&8)trQqhJZ@((X`X@UT3!|dGQ;xn@YZeoPX6s~HYB8*Rce6Lmo(qYqfC={eBFJ8 z7kSFQ=ghSVF)QRVcZFyOX?2G;a1*|2G}uTtzqn5~UY5CiSg@Ak-HGM|R}9a-%jAX? z;$3kKKrL~`^h{^Ghlw2BxxFa!5}_RO_Eaa{v%4tmQYZ`)?>W%TvU-p!Y2l;RjGH%C zDD*g&3>yJ~ANSZ%kgq9a5N;q%&y($@vZEk3em`(*9fx0u_AF(5ejdSSNPQjaIvsc|!Zy~l4!b}LLEf9bX)MFZ0h!R))*|gY??FmmvWa{^WPYjGZ)MLc^-FP=4u(G21)(}rVMTDCjtw!x5g&>%D>szDc zn8cmMU%0zKV~59m?k3$+K#rff4cc>Voc*3BH1w-Rm-`!7GnkF=a3QdwCO$87M!QZG z*$%YHOeulN4khZ3yYFrA9UP0<|w?SreFu` z3AssukVd=G#i$Ty(iabN4mM>616X>bFj|hwG=hfZHAhBoTUmyv4kh*DVQHGg4;=BJ zDuC`!njN>!IQ;Q+H^cfH4|FR-2vT=;eZwD60Gh%oZgwr-dtsqsPrF|6K&z>zEgM1< zYBV)&cawJ>@qc<}Q5kZ=Qx!?xvIx$BW%Q-Skc{Gv5JOSNmFu*4e`+E8h87mu$GxEl z@i1W*!9fSNBkfOa*x#zJICYAdt&YaF#@p@`aTpV-PxfsHqDv9P7Dcc{WjfjSA8}KA z5>`EE2z61wrc#2%7H?B+$1qs|X-nU^UrGV(aex!-1jLuB_20X%f|;eXx2?3Ims!#7 zwv%~H)e>SEJnMjxe_{1sxeIx-ThD*Z&w~F4-0{7R3hV-YxQoi|Y+T?jxTU1xZ&Hzy zd*>YP0oout0ongTx|ML^!Li%<=WaqKLE9phX6$HR(Q)8` zm4#DI;yt;AN&L!R_VJUTL$pBYp_B$&Y-^QvRd9{}OuD7xZ_<%hobjNbQF?H&+@R&O z(C`9HYnJvV42Eo=W7Ed?cUPs)tjItmUEL+4S=&Blw}|cnk1oPk2Kzj`0(NP$AzNbKWdc z$k?!=o27pR78^v9^<;O$&ha@O_pF>h+`_i$++U(x+M7Q-_Ke}K4%>;R$ z2Vv*6n@U-IWGd!f|LtBuJ7YqWv7GMyoECmVtBt>_!e0L^Ls&W^!M+b1+4dco_NzLK z5&iNqFg0xA(YDS6;?`{eudD5sr}J}pw6hdm5nNn7#_-w1KLcFjLUl;b%J>^bJS(r` zxA528F?V}>={NOi?swH{7)x+`OegZueMf#T4qIG^C$bZc!XEpp>wr5D2nb;_Ct;mX zI#ZjM3MyIg64+_L>pH&ZjA zHxQzyt#It;X}V@Cnb=GuvRWG@`udrq>z8i1)j;%3UgG+5KUh^FE)hr~$9ye#W@h6< zg8l(*Of!`9UiuE``yO5!to^Yt>w)Bvb-tb@<%K=fzX$nuWAlKt_0Qgn>K4nAo`!(* zpjUYHfy~hP-Yz%Mx6JVh=N`BRPZA;?Oqd*y_@GlMm5yCVtUif@@uw$=e=BiAC9($+ z11AH&<~K!xxyG<6M(hXv=rfh79f@{f@q@`pe}DjZrxP5KbicdL0=xQcECQD`c8b-? zh}bLae=uj^3Sj2(hbVOs2S$2e`c<8HtWw5dOxA4|xaD(tD~PZ`6LHA>gze8=MH$F| zrulPMVS~a&45%&FYhftIPZGTg=|gAJKt0|Cq)A-4vaz=vbXOj*zA8puDsrx5;y+F7xo`@A{& z16BZU6}HYww7*~e;t`ap;z7f{ZbU8pa)-=9dr!+(J>^ulpAlM-shEVztVrTvTEB<#Q|If4^I;LQd z3Ya1ANM1+pA!0QxRCn1cdY`ThNLL3GNo}{}Is()Kf(>|a)!CAmG<56tx+~X_NQVuH zibafeA?WA=1Ee}dUvV?q1toWa|2^-xow zQ%T!rgKeLwqxaCD_@NCZyLhS&>w%36qc}jWkrCg9>5Y)9V0x3l6H9Y4n2#9HF2U3o z516$bz@epB$bJEytF!>qV!F31W>rk{xB_RWo)#Y#A$U*p39vBqpJ>L;cstgD%xu%;?sm zb)d4aqg%GREAp#HX7lfvV_jcDjrqa%nOB$6tPR>%lWg(UR4{X=7QSyD>LPez=_zi4 zWAMw04oJoUpb}8CwB54QLA(pwcVk#BIOl)doib7rG5rK6IcTvZ07t!Ho7p5%FuV>o zL0($0vr%;@bqsInA}gi-Z4@N;V?gr9A&>?7Z463rLVO0wQPu?4^2G5@hWO5CVJ;J z()`Oo_#FU|_HT%Hf)EaRV-R9P5MsSU`ED${d_q9MGg`$q1yHBZpUx}oka&?)0Oj|x zV1-Aa!cr%vn^ZbHRe5kgIxzqh4k}&-6+5W_@J|Ne(TZ8u$j)~kz|ZJB+nAJ9*+GUh z1)j^D6}`?{T67Jp2PND&NPRnyQNE{WvMarOr}*IwgcpAqWIMhEx~T=a5*!c3SM2je zlyX*DeBT#djv6%Ntjh_TYSC(J8CFWP!ojKNOtW$}qKO)i^e6ILs=(XoXCS|=&_ox+ ztAe{RGljEZQ77DZNUI+YwPi$pL}VNc|iJ?kGabgz%D1e zG+!Gr$N!_d+y;tZz`{A9b^iDS1g1pL*y<~KJ0GV?Dez9@PoUN}p_5%g)Pg;Df$+hC z3OruuUtqy=g#zoR_?SRfPs3Y;2dc|~cX*?^I^u0Fx%ozY&n=7`)a;SSmk{K@IVy3#CHXGIF?*cFa;adF3K5FfwKN3qiva&NLIN}y(o^7 zWns;t(d-HDMB9Px5L#$lR8lh_4UvhO)#1#0`CV5Sj-u2dcFKERJYBBg|Wzj9Y|f;Qxc8dlxGx z`+I={s|;Y7g2vGSxDT^GFz9er+d@>LNE>g&;#FvxlwCZsL|7*7(y zTEb*t@w?XAruCpNe`pEg(SR}(i!}i~a52h@px~?}&&$E@5x5xbfu$U;6|}Y)qb*Bf z;H0ITp@lD*f$sqhb3G^~n9E_SXantxhk&y^?oh~AK@i@wjl(m9PTOkyqA+VoQPNNS zL>N^%3;2CNIdO0_1SDl3cxR*z{0EOONffRvG2v&0QIF^&cAWxOH?6}KkanDs1)LBk z)IOr5qWXnZk31Az8}#n2YM9o*+SrDEDG40hYjxB;1H$%N6BRcgT&T@w`lWZlS9kfg z98+I`4W+xC#7lElV2AvG5l`Fz|384Eja;$87Qs7s?c#EqN&BkR1|437`pYx%8Ua5( zm3nJHsC+z)+BP6O{rE`g4ZpDe@tmZPM-b~-f!G;OfIkeNe<;s_B6bOn^hmtgC)|2` zG(Ie7SJXY!*!OXen|);9s2jYq6-V5p8quys@=>dtU=EEEt>H84JLFZB+v@+Pezj}H zD&<6l0p0r6K}1>l>w*b2W#@s;|F9#jI8+6lRUAk@C zDkS#!@3>LANqoWaW1|W1J1y|L+X2tdIY5sh&*b83G51e5PJhM)PeyEb%GDw7Gww7~ zps?C$e%ysJYh9#XPd}8aNy-Rh@R7SNeNnImGFbn+MwIzMs4~+9TBF)??oU8HD~K!O z?K{mDfSS*#I0Nty$K{3GZpTh}5x0B!Mz=P7tV=aIm$brdGmmju8scqV0_^Vkg8;YZ zsd{;lu|u{2H+tNOxShpKP$ThfpBfh<(hMoBm#a*mL3Lv8Hz*IkTh2lZHM0zRoD}yX zV4OpLf&ckv5uDCpb*5#dw$t_BIKa}oL<4sh$S%O}B62;LQ~}!?AF&xWscpkIX$p^df!m6|`aI5UZQRo+m=CrB z73j1tywVubxW%k->0XG2T%`-()EJcdcmlDa3~M0N|ETX{b3#WY-*1=v-a+@v1A#By zADe%^cZRivv8-&1Ys9%fKD(!pG_xhx$#-tUrli8rbuc&>=n$6 zmcYtQ?R(e#8_-!ktni1Hm~MsS?gF2WUmelkn{KIs>4T1j+h({c_ql^OobNJQM>`vC z*V*Sdmx&t1GhNGiE3LSYPM139^xL3Q!6K!Ij@$n*N?isQ{gCK(TmW~h80#^4p;2(` zfEg2(i*N%JiI?E13QBGO*>8|%gE2AR6p)sFA{_tggLH$xNr+me&3My^44Tdz@@(U7 zRrCd7H4Op-f6MiO$w1HXZ_0Dv$ul54v}`nm`-H8_oWg65W~k>5{OKv@kmsqvu#)p= z2KBICnEzTt(@k89opPQQA9b>o}=dYj_R%Zw}v!EH@;+MT>F-LL$cEPjjXQSA~WQc9T&Z1TQN%8 z>-^4L(9pIt-n@1F*67BB#@%M@1fH<9wwP?M8*Jnvs!Cg zYKvjnRJ?d3MW=$pQ*jV!z0y2?g-Edsh(0tpdg2hvtt#$2S?y2?-`!x}{q9ES=02&d zpW*YH;cA&e*^meB6@v_#<<=AfIka9?%;CM#1b>7_9lk-HRr|^HNECT?@c-58H2O@R zRQ9YL5*y?NMpm!Z+JL+k87q2+tpGCHSMwZmdo!f0+iGgece-je$n>_W8<^X3R~%Rv zRet8ikUZwLX~ufFa@}cp3b={RG*9Hi%dj}3kFZk%QdwZ|mKsXwlNR-V=zge>18;{J zeg%IJIEG$eWWwJ83HE157@M9w@~kbaOs#!co@Hd9Iu?z6HqeV40uSg&;rQverboGdTNCIb+3xIHN3UT0d5ldzG68Q)i&cv z2UhJhD=y{3=tKIJiNjE6*DNUMlPI|RhQ~IU-RJ*eeY+NMa?3JtIP$v*Z_@{sQ5jCc zXIJ4#s&iIbpVSS@k+>50q{YpLQSHbYTgPl;q53`~Ci#YW)L@~g(Lq+9^e_J}!Grj+ zoVKr?AI^^e#u|VcZ9P~W#PAlo~LHOd0hPT(xFxTN?vS0S;?L2S2cB?j!d|O z#F4@mPwR1p(EW5Wn+dm=kcbC_=+$YM5+<%rw|k{6V68^tjeasqIo_W^3kA-g0l4!D z9B!Yqx^IxfCDu_S&H)Q_^qas)nyatNha0t^+5vG$b*WFX_8}XS zcH6l%t;cCHqcpe|sb6f>*LAz=fx#wvsgnbtCG;jNxK~FG`59^v8!`*7759B2Fl#tq zdsEkp$5q0-HM6K0KH;M^>+lU>!ZUwY5Jr8Q(Edy^E*5S-GY=bt8Edta!Y}-7?Hb%9 z^sF5p`o2%O)7H=@#d?K2yLrSd*$vaLV8{i|q0CQiV()(LNCYVOkoZ?YuxsHaN|QaE zs`Lq6b{-c9qa0c)!6%eCOgK{5;utmJn)g3AXt-TqXPZvj6t3AeHBbR?+K#Dk&1OVh zdR$un`?ea}A!|&-?oBvnH@FcN^b@RX7Z%i2Csc!e&@X)roLz0pKH$udSOpY^Qv6bz z&{?+{?-ORN(_=RBO(6-YG z220_$bz1u-J{GKf^E#uO$<1WANi|w?8NW+3kZt6ODVXJU+Dx#&U_c?tXQ{GBI2McRxqJV;gsQ3iLAsyeqyus`6xlrH5**bv1wad4*rxlW2|l>JN|QUo4_j-h^$XvW3%8xQq11=#H-Pg5={DAhQlVQD zh;Bsfz3~eQVs4h{p>Yov+YaQSDiuxmpCu=h`8+)`N?>` z22|%^)*05MCuR2xTi^%OO4>XQfr6`QJ8hXp5GaCqZ`0pYccX~U`p{VfqUt$J=*I>Z4Fb6Qw zDgU?yI77HmMWlCGda;F+E)ywK+ae27H_fn@`;$v?-e0XlY-iEPOA7@K%eltF%^jEir59395y^SgyObsbZ2O25ysk_Kw5#6=R z_L_NrH>Td~rkFRn8NAE-n@dqj=*Z}M-#U2b9sv(03dx%l`EaKaRN0n>-8Php@7ZnD z+hQ8_fB=Xtlbz8oS^8nlptQ~wTDaS4u@za{z;@g17Ob1^#UBcLH>W4~ykLt1Z`%nx zSk9?!=FP2b@rW}OBJqmwqbwp3N-B7`9xcgKUczy6|dCmHJS() zj<@Y=zz1b%Wj_X$yDTO3k7%&i4A%9wrB>xrvUE>B;nP974lY6v-4_wNaIW(b@Kmsb zLz3>lI2<(IZLh^8mW(JP98`e^;a~lzn%FnK0Ery)nz9mD6PMvkS8Ba>$ zLw-n&^vUT57DaXB!%GkAcQinr6=j`uUVY49)&F&=wau-BiSRf_OWD}M_T z`DAk>LSOHmXoC2c&EP2m2Zc7MJ^>%LCKeR0T`5SXDy^xGCCoj;7iqXvY{UCz?UkWb|vgD9>|9+cTvzbOjuV9w0}MYD-V zcF<(!LBcOxgKMYI$cqok3^>Szgla{M30jxLUs9FWrnI6_56B_4r&TJ@mdtErZJ^XD zoLjW~{BiRk$YIazG*3Twpc{qJd~WkxK9ARTy>9lO>r6PwyKYeC9oF!MuWdhBcbebo zrWK}(p|*4J<%OYEyTKZ6BaS?eTA?!p2RzbPzJ?ST(px@-hh^sS=Nm%1Rp`A|Eqn+%-fysdRQtO zC`ytZ7}!GmF~Z&lb7n|4T}dqkk5Wu$SeKFkfR_t~uSdWDjGwwKpnAh}yv1z2BBKbIg&KJBd%*Hlh#*0}I)B085U7?19 z#4kz0^Dhp^lZCflEaxhGx}aSTnbtH9?Lw))x_!W}$Zo=q_$3plNVZLPVKy}80bznL24@OOglP{2 zuk@RMD?2_BoOJ)`oD2WoI`Mm^TjA3hwEBBCNPd2GO!0$dF zGfUCS190z_Nm6#goi-lt1l9LluFfw_l7;9U52han4w!9H!1rB1&kaVmD?Y-6Nz#L# zpw@zC$uc5)x?h?nytHHd&>x#W@UY>J-C+KK(nC6tA-)rd%Y@52;_yO2+M&hMgt(Uz zutgaAa(dD$|A7_LLRhfBJ!gMGGLSoLy={RJKwrn)wpckoLtHu~1xn%;nY zRL^G~@JfZtvEe?duiz#X3(t312Rp%)XoXUrpiM_%|Dm`epdsjXJmRCS8d9D(RgdG{YcIAlD&=X4bs};HtVs zg;c)jrqc9t0vb7@;erY2&)z_mY*@$Q#x3TMizo{m^MrrBl5F=nHpEv$cbI#PM_FA? zfV=;)n`#dHK!%SpOyYLO8{Od;23!n79l#^G@CLusqw>c@nQr2OA%0q{H?uHgjEPed zb*>%^PTx2zdoP9nSewz1XMhNwjzg#!3;S8~k4IgC;`>@oR!ZVEsd22$WBGD=at+ z))TnLA=W$U0Ts_W4tglIx^QqXUNK~FFa^jzWZ(rDjGc@dkeB!9xfhBaxk%+#7n*Le zrhR^D#~a;4@EhhY`M3E8&(CnqYd8w$S2g5epGwlfKs=^o3t($G8aaqpm}I)cM5b8l zqkCR5VauO5J35Gkabe+>n@S6GedjeZug1>n-GcJ4BzxXtwejPZVKT-rpVHP zKG<|>MseV-n$DxDAXzU{?p9 zbnsz1U9TFRK|1*N=jwF5j$jT99bDGQr_9J#uaFgq`S6h~Y#r<%=L9)wKLJezDbf5_ zN%RRMetQBAUcDWzV?@*zN2cv)t>^`VIN-sOG{ity;E)b2sO-ogjKor?kONN7cU0@Xu2(5s|9QR&U)_KqL4faH!FLr1W|0~_q%Rkn;%yACEB~w~Oc@=XTwi57 zWghXg!TEarrc-7Gd|xL#RpCduRkjgN7u=%h-Db{dzJ(!9f|xufItzl&Z0nrVg-Kz2 zp)hK9krpVY65W1L?UX^=KsrsMoKza)gpRdTi41YfdTv;=w+lYd2>HROrb2*TQX)`bl|HExomHsiuBXPI)eT7|xMT-?qolx7W_t zLkU({n&KY~RZD~aydQIShyj$#eC&?&aeqent7fwcrI6es{UhOM&0Ks(I@F(9g2Zsp zuB1TB`t@K#9O6n91C*|Ow>ji5uHV4;sO%twghm!w-Z$sBX7V9GcwVStZJrPN$b0>y z$&LLH3sj8aHRtM0lz`Z(b@thWtRCl2+qU*pVccf`R_T(Aq zu$F;)3wNZFeo`6fc2|?T3#5#?3p?@OuvD;a?%ii5ZSe4k=^*d&wXo;acmuq~N#F+a zTZl=~@9rh~8yGAGa~yn4$Az>3=^}{Nk`yirU9V=uQT#4jojIff-$qe&X2nHCNuBK_ z_{60~(C^jbb3*anRJaN7*xuyv%^=+|K{@a3z<~56+$YEf{Y^CE133_6J+LEJ!PipW z1}H@k>MZ!&4@k#^(|e!5HNu3~mSdA}=(VSSM@W7BJN&B9^ZHwG^SVo`D0j)>SrmMe zG6udj5k850e{TSA%pjj4O&8GKk=k2?PxfVk`R~TQEhVvK`Ar<$xt(TH*mjxYovuf= zfO7%Xr=_&@tV5w%#!shUKTYp2(;kWjcaut`Q5&Hmy?;tFOup9z3i{?RDgAuVu z;rRmy^Kucp5uV4wedz}tTl^RTj)B0DUk*aTf;an*THjJ*O=VS{dCK3iM`w>6ZTw5l z*zB=mvlr$r&O<`&+bQ;l1&ED;Fjx{K zHfH6@rwS}nQx`$k4?GG6@}-EK_E*G~L%jSE#8yKHgD?U@GK4)~>55xESicxd3(#jY zsvAt8Nl-`zp%+r$nVkK{D)9Y*Kyt3!jZ;^QNnHV5-B^d%XX_Aq+A&!E4W!=@UVdjT r-X?h7nT&rHvJV!6rthhPdc0HEdoVfTBCLSP&{8FE{nv!A4(9%UUk1z6 delta 21988 zcma&O30PCd7C1h0?@e-9BmqRiB4hz&)c{&?t095Q5-o0RUD_H&`>wSi7ksQ-DOHXkHnCEBu@4radCf3 zZ~2QYy=z{KDvRdzBBrCQ^Mdg_>z_GDq z5JD-^JBVc>T4>pFJf7F}*=;&gpFKC;dS4mdgX>TR>V4gg>rtk$cfWmZ*}PKd zw6C&4FDhxX$U^5~@Z42l7L9b+pXok(MVOTUR|#c|P)7JqTCkceg=J||>z0|z;w#K$ zbrsYtlpDX?RMxR9o;Qg{=Gx+|@%$b<&=$|D;C}*)az7eqn+ma6ltW{aEl{w}XbP5N z2HNf_4drVgo(Qo?q^MBqgkTCo3R;4k9E(mDZ#6(Yov5HpB2AIHl$cMcGkmVhlB_Zs z24S3M?nCov8-cvfxDFoHMO(*M;&^ReS3yCaeNLP;nASo%C(atlYejf3+UG=CF_bYz z7WAP=Oy2hyb0VPwooJjJZ>5e`7RU3u=^3{kJcjG=l=*H{NG&M&Sc}vUCqhVr5M?x? zsT8dkPuVc8VOvmm3AI2Cfq~Em1+o~l0BO)%6{P1wSO8%*1hz5Rg0)CPkcVMhiDi)x zR1o6$P-9}LNmRkx1b7>qUBH9-VI)2&1-xuvR1l{KCXcM5k$|6g>%7Ghn`MR&Sr%o9 zVzMoJf0A%?8J52hx-E`)k9t-pHEw9E`^BcO;gb zDs|w=H{2-W52v}$zD`~iZN>U-H_CQ9_3%u=^Dl10-z$p&kP_jjJW($%B`eatF3gIw zj3v%~zF{jg81Np20stw4QVfD4J62#6J4*xC|J*Wi3j)+Y^E}LZUi5#q5@~ogY>$yQ zP}ii!&{^SJCLh+6$fa9xEfRaBbRO?RqDeTf&}vBSL$`i>OfMSEpGxoNkhUrTv80U& z(1tLQJ!u@w@EqMi(W z*+(jvCZ-E@*?&eET`Y_QHb0w4;$Kl$IAG+Z5X3Hp5Z!3kWhAUNMZ?AL$A8Ehl#q%uOC@l8MI*fmJh3xgqg zCUE`JJts7wY1DKlbkGHXZN%aRKL%(S32WF!BqE9YPxk|&MD`TYK&)jsEUHg4;@)Ol zg2f6UW<;`$7H<#IdbMs+ss0HAH_0-o{IhGaJh}ezR$9y-npmpg?zYmR$De1x@A6#U zJ&9IIpIM2;Sl`8K2-9M3KcmmH=J7bQ=%RtQBU)sA85T9XVXT^xH*81@^&jSwN;>%^ zRxCa;kO1TC^~J+~BD|LgCq_iuR6~iDFb5JR_!A&ji0K3I!RIXjEFSI0VvS!WUXmDn zNJ(ZTsV4&nfO1RnV0=u%;>3XgcOJhOHMmiW8jyby!d1XwK{#Snkp2w9w-Am)Xoc`T zgoV+FwQNVMEG?1D5=sep7X@UN^1l3K%e81P10Y_IG#quDOf^tzc7m`vB3ZU_1Y!$? z-4SDPz0ee)rwSs3e@EO+q9mn;b`F&b1+pMJD+vTjCHd#g~U$C(p+GfVhHHQIJaVv;(8HEsO__U5bNv#6yY3bEPOyyXlR!F_iP z>Hp}Bd=}~Lx<7hVTOa#q3oPiZy{ei^5_$td^?9yCLbH*kT|z26F&}o|KGTR!72gVz zntUVnJ$FIyQ;A%(=PFo11RVl5Vz z`2yZAhGJnY(qcaR;n@5;=lY{;;b`S95o@IllN@HSlrz&=gPacg`l)TC+Z0aeb>W=oZy)0tr9wD z1Ta7LGn}KafWs4J!;|2jUwEM?!G$zs5)*!!KgZu^9R}Wb6UW^v0p~C>&FQ4Y!+vad zYL&e3HPfhbc*0DfIVv`#)^F$VehtTZFiVRo{Dp;1_Zo2#YJ>kUbk6;kLx>fU64f*o z7YNbO=8@kHU_*`R4;R)*ZVYRK7IDAuNOa=8brRVJsz$YzfkoCUX&i_7PM)?RjjEZn z<#$&$!m#>YsH8-3h~a8sPoD70l9&!yO5(qU(zwcI#*>0hTIJ$ozlKApwD_aY89ie} z96ZtDIkM!$w}r7Ili6*juR>q2EAAO-8c_lJDByiRK(bc}2S$#@CgIG;0-PfZj!cgU zAAIytvcA#auV%(b?@eh6c%y`=F>&}_;ocZM?iDu1OdW9`z;tQ26yD>e#5aUbV$$(4 zp(iE>zbA|y6}$L$K+}XLXtKO6I0`0cxcuh)MutP4nX)wK^Pa%$CdM;Am@WzAH$j=) z&#pyk@|%%(dH{|>@oxj7d$@)wSZZP*tw{~-P@+M2ag-LH5*(wlW8Mf@9htm_yS!o* zuYVZn4=)F{Q0N^sC!}pi(=@+?5?#Wq*i1$J&~{krX9Ul~v6GD@w;L$&-JxgT4N7Zs zsWg;$eE_8$c49rf?mKtDd)A*`br2}SdA}TXR+iJqmz+T2zlDFsnn&IM^)ylzld-+AXmZyhv1Z(9FBcV%(ly3C?#OymRJ zfA|OtQT@$VRmOnVd73OEwvn=6O##oPji@`#F>;U3wk^$^u|vbF#&d*!GU#1ONpt%q=aNc#F-QW z64#zadPO6};aaR!1HGL(035hpuEiQT92-cF>*QJr(&Gn&XA+)F_=}Ix1K+__Y(wHK z-!S0$%?d3NhlGU0(fD&=a$+`)7ygpC8b2YlCFa=f_Q|*s2l7}ISsT(g^~4+)$k+a3 zCa=p1Q$60ta0^JTj2atz&)5wbPCbE?X!5@WC5%ua=}rlw42@OYGj^SZQw2*L`A>-v z|0zL@W&fwdE2M<5ee}eoPx=XmM-D1=C`tkJmd9}Sl_jTbKYmU^#}z>KJ0~n>|N$zn5yf+3>+6~tg_hfDXY~7!PxTJ}; zOM^0QdlSlXIyGFVM}=W?z`hT7_XqyrM!MmW-wobyUvGi~W|v(@4x0ZxV8*}($%biK z;@j0rxG1~sl2mgX?|HyMTGMc2*Hhx4Z-sRof7p70zifTgJsa@zP(Q3|j&Y{hlZ z;Ev%FYX_WI$TOSLa0|JS6TZ7f=_&D&kE)~V_nP`#!|NF;ZKVWU54CC@`-pT|1E~do z{%#*t&v3(~S_EbC)WQOP3V#!5zzE>fjE*7il|ahMkq-T)_e`{F$omJ-uKeZ{{+2s% zJqmV30&jLi!f@X6bv3C<$iAS&w@wS1#8J_Tl3!uNzw9G30z?Ex&>{RSIgh%}CtQy) z;MaxGn$kFv4{5B{KbM!9OW?1$K`aro1e+#Do9*+t`+$9sSty&Tah{Z`VgTlRAJXfe zAd}oDxHOCBRQa%mK5l4MLcPa)aFRr?VYuoFkXuf$*U4i9VXTI6zoe;kuq3_ub!73*mVQ9q_^t5;+U+9?#3gN&R>~>`GW7(}qR> zubbeIiv|6HE``I@!pf9|REbacEG0Lj%HMpIHDd9&5J-u^{}5tQr&6*ZVQ%U;1`h9j zVO#254D4J<_&D`0s@f*pPCW=2llq0aF?RvLt}$ane$d5n8tahvf`G@4$Dar}WA)Ta zV@}*RHk^`$Fd^Z6LPh#2sFW-T=h6$qC^13mT9F2jT@6-9DnE{D7$ zPvjQ@pHnB%(&>!2J(Q_V6!|f z1{lqgFkh`gT-Fnj6HY{P%kjwa-xiKzVt)9LjuPI;%AU%W(jFCs_2Il=)SJVsVzZXh zb3ek8Kw+#ANxgwYmNj-Y)=KKu=zGe$XT~-!%w%GJc#l>IBeHYul9g>WBF(TM+trLh zNS(X^Qpd6}bmLc5rfyni-b^^VPC0H1ct2|icwcA{)@RQzc~(8N=_`jkUDpn$pAUO- zj4lUGeV+^W$$H~VuW>5pnC=MquMI=%$@WRquQKZ#);x8g*qp;%bJMr>tOK5Aq9R*R zjpJ-;zO{D*k!)I6=$qcOw6}n!*ArO>HopD;$>1u0m7VO+ixlAaZ1BJ%WzFz>8^+E+ z8*HOd)F8PnLH~N8>I<%Ctb|1Gn+DzmV;rASQlKLLD#oS%Eu4hisW@fWYq-D!7&OW?Q;fk7-%?l%Q zGsfc{J45{>Hsh4<-6=daBwG6bttzrSAP}ge#)y>)E}VO)DQxq2;rZOj_dA*^Hh&Pm zruUg>lwI+7=*7!5@0k=ojdJB}>{QTg6`P5!tKxC(X0@dZpIgwAxTm3^=dhCPh$+K* z6~D_!!+5@OkLGT;^LAu#Il!C66$ZS25wv;wQ6IKfY+fXP?}t+W1%W^fVFD|h9zR7m zI6hHc*(d{0gtYM~RQjNB&-i#8F034HPy{!DDoj|Ew}=}YGH|`XqP-aC25wu4fK_Zk zXh(nv>dVk$MCTQy7-%CXB`D8tG;fAuMLwmC-aMgnFHF$)GAsFQYdv z#8i(tTFu*`+O7p;@$H(e*=)zK!3TlY+l)be*<#dpQ=t1>Bd&&HG2rdF!$Be7SV?2H zfcKpMwK=*pR5KUPTcGblpq;2S&zn8yjq>R?N0d?8#W<{F|LjAz3LYaW6MIFpRkxYu zDL7}bZfCH0+WN&E#IS%EvU|zyX9)$+sepNoL3AcSf{O9=>O(QXDUPc#9+)h{nYnm@ZGbI8IRl5>l6K+t5`OmpYt_=kYELx`R@ z-S*PJu!;)SytgeNxmAtSN`})lnKv)%-9np5T`eJr6`R+-8H# z{Bql^d=3P}g9P0WAHsJ9yb*&kPZce@_38$N=QE@)BzdWYtVhExs!E)s6K7J3Dg$2s zz^aXkae8qky=rX-Xqkv$fwUt_;z84dqZV1i^wFSA1O3vpxzfmK`o5tG6U0WHe&?{l zm!b7rD7{VpSit+E-w1o3Eg>8}@VvzVZw_FLV2g~-5P?$EkRA!457K1Hvaj_Pqg#76 zFx(oE!{jVGIly?Vh&g zy6Ji4-O-?{HO|v-kvSPpOmNv5{e@kJH}91ayY@=4tz$PY-Tceunca%91>LlEuQaOG z)E%Ky`ks}-8kD{*LrtD=Wm>!PCKI|yN*8xbMC`)55c@jBjyv(ZNr-*vPB;MZ83>V( zZzF&2K-ep(S`$S^DFdY!?HVQ8mB^WVLcfV9Q}yfhn>rPv+V)CShBR&uY_3HMOnoS7 z(QGmzvc|}W0^V1K{wyEx?gsw;P3a-SupUG%Cd=`-949qygcFTB??UM=*SEbW`rE`_ zWB40S%zdZ5I6QWzQ zNd*AE=0q84>92;&t3L3xLHQe-+Ab=6_^6stZf16Gl za=9NqgU8b@qo_if^CZb2BGH3LSI;MwHldN2GcX)KPRb$cZj5huqbUPTd$6MCvw`_Lz zLJQQfrYqV_<G7} z#n#o2(rkT~Kh*711Ej2l1`0T`#oR}M)xZwjv|Smd;=qa;{bC^Cg+O##yGoz4g!2jf zt}?otL5W7H8-bAmv}N{GI->1a%d=&p`6xcdm>q5u-?f9hs@+zW5RNi!MzP*rK`Yxf zTWoiVe9(ZhjbcbODYU7qz5xt0;xBfTrRvyNhP4}KMe}LgFlia|cJyE6H4ciOyE4>~ z&eaxcWua|rOTP?~n}n6LV;|^SSC{4~V&@g=U$dqZPTcA@hjOX3*0pS^28_oFmnEgEkW%c@_NroC|*5N{NX z)jvvEYoCHi5@{6xnO|+p&g2xH(dbBvQJ?JF>PNytpa;kOsQzkv!26~DW!U+Y?h&A# z&p_&_P47syhmI4f{?vNXhz3OIe5ml@V4|M(v-|czAwp_vAimp@XhLF9b-+7z5P`r! zbZ+em+@|6qt&3Sr?jkoDb4hBoUy|An0(m|DhhkD&c{dlgP+}`Vk!VOZN{WOwtRE!? zP^rWk>ZM3Sri->gx7JLhYb;Q_p9kupqiB)A3K!6GA1SgFfZGLelY(la^rYexMOYij z`4eCwnBF(Y2J=?4au1e&;)-<-FWk#6G7xl}Y`1{dG0^G0q(E)M0FQK!1UAkF?2j>Y z;J8G{Dmneg$w$cQpCnfU`AB6)gxnIcTP|9|%08u_RfszDx?S86L7=e|V0X zTeQiVLpD^o3)F7Z?2HJ&!Ajr#7D3vmi2|I+;aTRJXITUct|DsD`nXLs@~E~;(#%iR z^cF?dZTbncos_7ISkp^`+O!fGyCYQJ!n?Tjb?c`9_E^%L!7o>|nMzPk7;qX>d@8+- zyvzs264zUrQ2o>r0$sj^6iBiLyy-rBu-a;t=pDm6iD6q^o321N6qWG<02JqQxyg}p zz~{b_zhkIoDt}kJy6{8Ok(O~>vhNwG0P@!PjwA%U&-o_rs409$V(pz*be6?;7OlB_22 zlumLVW^A`)AF7~*L$~`VeP00VrwW?zi=Rq;`R62Q5}_NPLQKe4B^++8^P;UizfFLt zR6&R$$7)dCfjJ+ZcOhfCCS=(V2K7(CyHA)mJss~Bo}QjPI%x=L$zXX2X|7s{WJ36C z(m-Wnn(&Y58e0m|CWE3c;4PIlXtEv~@OlTeoQ~T7l0%^s(8raP_t~vLJ##;mx^kke zpGqiKll%WKCOk!`CDHnT^?_wSS?geK^1#wqB(2)CyqBg|ttW~>TV*qWh75y@O={d5 zG|ZyMOrkx=q|O1eZ*9qt_fY?f@c(-7|JD8%%HfO*yZ|m3#4BmD( zS25Eh8mSB`4Fw|yrt&Bgcj9SY7Y6gx1D0I=9FQzLl?ZbvWx$ID7Qm?Oxg&$dzE7ol z%W?_FDz?(m)=Ut?(LBP@X2LmgQYt4Ut%=sdw^}RW`NKDVTBqx4oqJaLY3z9j#PogE z1_@BWfVq>pwTD_{EzLbEb!o`|ufhMT!T;;Qe=+#qry26j2@H8F0+WMWV?di|74yu} z^_gbrTL@RPCX|__UuUX$O&&@+*-|b7HPV*C1e5|j*HFNFvwwqz zpmo6e7SZH@O*ia)7KK9y{V)U>-b5@}T_YhLk&jrgsTo-ae+t9!$_U2KM~o<9c=>g~ zG9){z3j(3CgxoR^2(?w^hoddWk-q5W(xpg1bz4mMJTd2E0oUy`(HBr1&P97}y1}fU zi}&=oLpjXRCB&9FSE9hKNX+9ih3N(3@mgVZ!4vAp!t%aDkEyxJ#&6@1b~H!dI`lZ$ z;{C!v!Gvk`O@Zqw%OucY%ea{i{4NsT?+4p*+7B&AGpsvf#8><%EgURnjQEicrNNpZ zick^t3y+%A$$y-#EGCMre2^7cJ{-13jATlb^&pk3hl<*I;;<5xVi$fE=o9TgjZz@rU`Nri}By@PhR)FZj%3$|nRWcy@r7Xy?nSi~S4#GuMz<;mnm`Fr4Ykbrm70wX>w zL~^5XyD*+h$KL?!FxAp3J-Twh@%ze?CWVU_XZ|H!U%7JS@^}JS<|D6~#<=cE$mO&g z4;J@A&=rs9cuC@b4X5bs5Ch9G#PG{aq~>Yi5;w#44VZwCSS6)%xQ;#ocBOt9s6&wW z0vJa_K#9pV4tm$X1kfD;@AE^5H=0;5;b0vYakN>`9uC05o{02}$ADH;e0HrU4~a&J z@oYk$N%q-DoC4`DA^q*_=BxQeB<7wX=A0}8&|grSekL3!9=~c3PBoZf=%E;FS->6* zTmn&(0XS&!cc3l4PE|7_PCNy8)Ix80SjQT0wHYYx2SdY@hc&{<_%YjD3AGsUx+LQ+ zgK;zpBqmmFfL6W<&`AntKUNrDqJQ8!Nxu_kMz{#nEYfcwZC5R7%1#P-Z_olY#DWgcgQzY7XZKpw$L#awW}$ zbVW-z9NY%NP@2cJARgzdn!`AFmr2^W?WVbSC?8pc(tR#fd}T3Jh$qvWs!=d0oX|r# zEny1+yPIG_E>_h{9{b(GqSCvU%?EnXy0Wr3xe<2TyR`ThK;ru?)IMU>c~D~fAgvdK z&eZXyrqEfT_k@9Lo@H+YxUgPt1tzolUWu7{#&qkvxv2NtzG9ENRf$qWaIYc(0l^X9 z5qzbIHdrC47bWX)0VH_B9wSk)?X)LV$vSZ!CFuD%Fu!=>1#Vw)*3W{357s4;TxyTU ziN=QN?&eN$r#v&1miE)0OyzXvNQgDcsm{|Lz4C77QICP{YzWCLZ&!mCS5yn-S4=7q z?JVV&-=*j}?a5ZA+n}gH+3hM3F-z40-rl1G0>%%nqn;uVp{m+LJ(|#xKD1zoZ>Ntm z!?wuBp7yLz_BR;Copzj4(q}LEssZVCb(M$|TOu-Shr2{%*?+;miv7WT>K3w{K7ZQt zq%s@&TCdE2|3{Q5uCzWopX{^MNF{w5{uB3UPli(EA{{IS#8FOt_vI%(0-Me|Ed=5u z?jci&Si^n*<;E%7gXN6kx~0T9D4QPmdrQO^n(d(DN@o(h;Xbw9ylfP% z?z0USCCzaxEVbY|bvLbycSUpTyG&kKA>JS7fb|n+NKbbrco=17r%;sMaRyo-IG{Rl zeSJ|%N0o^>)k&LglRSoQBXo=l7`JYhQ7ayuT4QHvqU z1Xmt6vJ3AoN&2J#@BZ42>z5?`+l|Kl8t?BQAk}fS5b@sP!sw|o;k}+v8rN+! z38rZ+UwaTOt0UF3S`7O04?L2%vxwQF<5N25{Q)z*4^KX2YHv|;1T=+nW1`G84nV^M zv;(;QOi`%ofRw74m=WJDgOn`=gd`O#r5wGE2OALV_1faQ+$2?7eA*M3A#=T#NE%>( z7VLv2n%p`1Ywr1PA$BH&*$_}`AOKCOG+a)4QVW@Jy{Mv}Co$AO1Rh}>uv?bEq}pKZ7HL;#_Z5?wVmfmHrW8Y`d|cZ%9u$_X9iDfC_KYV)Ip(L~ zCp{nLF<<~`;=baaui!cY^xUGIEfGfz+PQ_H9voWJ5+y|^5{j{}_#eSZ!Y(}Vb2kBi zf?BQaOs&g}bKdjVLc_jlaJnyWcj~sTw?W8@i@fJQ zHoe`WpeM9|a~^jVrXs%u>0=6$3SmXFpB7=)^um2t2$=D(x?%L=`keUgo3P23E7?9x z1qFL)rSb{aiCdaAOI@%nZ6Rb&_FttiN&~X7cr7%UDXPNc9Y&J{o|pC%;AGz}e*)}t z#+lqSyBpI;JZlGF*-*U+j=9PG2YXl+L}ZDS`A%Z&NNluc0=iEXB?AWRHy!rEn<~oR z5Y|mmD$opOijkotCmtp~5|}!B#8FdWloXd`$S{fr1W$Ri?R|T^h(VEf!eqbsx!oJz z+fZD1xJMQSwrBsot_whRkd5F<4Q@P_*VYkwxaJinyj>ICqHb8w@JVc~n~X7@jPXB1 zOcUi{r#%alWI!C84r}O+hLDWX_K?it_Dff3arPJvez6>9n?yPY^DrTuAcPi=`Rki5_oC_dBw)8YjcxXOx2R*GEC3*6~FfztN+Str^R9tqL~q3+bAU2by@%84sjf=E1@IOsz%>jW1ERWNW(tAkrP79{Y;FcEjS% zi#V#`=K8kYT;kg*>G>!SjrJAWKK~Q)8T*Q}e@o+(LA_P>HK{zh4{cO%HQXpJu|*FK z$*`|O61j`9`QZ4a<1&G-d%Qm+<1}{`+`($Nke>{>?-j{`9b#J!6M%1G7kwPnQHVx+KPZnSNbYYnJx%%clMiV2A~XuejzYzp}a zrJjjHIs><8?X;F`kzaG(6$80Pt1<)i*pD6&kq`}pszPrZJlaMj7*xu=5f zFBXan^KbX-HwvCQ`TIYDWgl!am9lzeD%QMyXNq{H}o9FP`!UgL5+@b1ihw z7qoB#J!SY^5%&6xOkwi8gb{CortZz-bFQnx81bgCbYAp`7cb7`7ISD{DUAPXp?Y5I z-5*O^xLw>8cg&skq3u!Q2af;Fg{>&WQ`yNUfYx4j9R{1yv0h{s zob!xWFGSAQmVYFnG_eCrXJBjvKb%5U<4#jFhh6G;RdZq$hRfkwburjq^lh_-744(rTxTb=^p51L^zs=9V4-41kYokjcr?2BXcOf?g1eQvkxTuZ3H+jr7U++pwVeiu4gF=7-dQAwB z9-$3`s@c4<*Aeh`OTw~yvqEo5U2d}RewT!O_fA=u1s-;!lp0odkK42|*Ks@uAJvAn zL*5_ZEsQiByO5Z11_$GvXDW+{cs4WW>43y9&*V2MXE9txRg^fW3~_y`P_!YjRLH(B z88->D?n|Klkc3C>%bix)7&21^D@s>IWsnBP`}I{gQ|2O0pUqb*LDG5o3{ggX4$QHt zF>0nBq=h6WaW9um6^8B`^>AoEBesLW2#l8EFA^iZ4T2aW#(}FI5kMI6$EKiV4pHF7 zO|i$}3PX4q(yJOra&slUO6ws1c(RH7=P}?QB)23~4!>JM90%|g}v ziMC6UYU}gIQR?Y?6x=0=JzN7$m&{8ic?RS@Le`ISO2^j{sysn79(R2$v9tGcqbo5q zv#5WpgXoG;CK5BZAPu-m2V}J}U?pyXK+cF$`epUnsjAGY?f4J?B%+pu3lO^o!oMI~ zx<43f!NjVC!!JS>A@*|!%EgFX1)&MTE(oNs{sF{}hjJ8jln25X66q~WJrThfVM$kc z-;T5o!*Nf~XhjHjAUV$#sf8`YPtLXEJ9$dQQAR)hXJE4pDIC89eq6_g7T8F7QeXce`JBLOcJ$ja_>{pKc3_kmD^#LudkdRnAu8d&6y ztFa!XQkorr4@UeLrYs#~WCq+{7*2I2_#QFhr&2qp#1EU2+L?Nk0)~BhhYeh983E90 z#Bg#XG=YA(E}<&AvfySEO=%TJ(AW>8L=dIV4soEm#Q>68ItR;|5z{1WFpBq9GZTJr z=K@fBhsfBUtd0TQmQj4XIx`MBQ|&ULo0Zj|)v%$Pk5*p-_tAyiQPW7*mr!Fj3>&@b7**Fd_R|4MDAp)I> z?zuu-WuFTuYR|gKHuwy7ROQ=qDxUv1@o^$J`zvasd_c^wA2<@$SG=xBI4IUrThQdRCBPY z!~dU6oeef6KvQ)Jqxhno%|th!vy*0b{-@QZK{7BSZM#Ai+EJ+SB)Ax-1^!%yws(UC z?DU#ofjTJgh*RtA;1qrXjBzoP6ek*VV7E zCf386>4LZl)(j|JW@>mWa>D2bwfI3{#)B~<&h%s52#*45;2?TNSo)yWcC?9o~fH2;LUlnkcQXE;HN@!%+A26F`Xvh~wR(VbDVR&tpD=_}yU z2>Liq-*;-ASv1g;FyuWy_z39F(m+S|ywAX~fT&7<_R*&DzMm(^W_7}T{CPrqA{^NS zcmnt)0OWCq{{;LCVe~^?^2jyn&#kKvL#mYasa`oj>+Oi*{x;%MRX zhqNOe_y6p+fNQTBMtxi8eP~jGZrCMCU*6aG7*$Gv10sJKwLAx%R0~B*>cJE6=OyKM zp^#%WV9%6i_acjg@H-k2HK|jNA?vHDB}BtTv=XHG3fmvKpd7CPZqcpet##e4!Rg3T|UQn66KNHp!XASPBef&&Y<`2cgiF| znU4ZUn-48t9za^+Jbh_E4?MvzmH~zWEY4_oU)a4O8DA0{@c+*ft`#!M_HE#BRi=Ze zBoonLxXANa;C2HsAyqaL4I$FTgGaSYB0wdARS`)TQW}Ise}JU2Aay$c$VOO8_y;Wh z(NfvC74++53e=zk#p3n=VNv84K(Sd#o`nGLL*T)4c$J3J3itB!45~)+%4nDb%8B%X z3D_ENo7~2uEau|3571e(GadrY^SDDn7q8HOPWwmxE<9HlvGOVWg0N#{QR2^oM5K^A z3%G-@&ZfXg0VdKw(9NS-xV|zm66wRLjcZEzvo+t?X+B}4T2MSvfQ>@wBl;1wACt>a zc0S&|2RhfRz;K zbuT>M5C!Q>m;QwWh~+LQslqlLh+C79xJrs~kYNoC94$&}FM-LQH;@BLjevJN5a+Ml zzda8JS}V?3wko@Ul4Py%4LI+Y?ez_$yWtMLcONb4X^-dr3BGZo3nx~u5ffwpq9N0v z=j3HyYK<^AZ9~KNc!rlPxVXvWH{9bN1$DBx&XDn2&`D)k;7>p0z0!RKJarrV--4SZ z1ePC$L~xIr(<0c{Wl#e{!u#uzbk~PSPFmo1xKeoCWd^o}Y=woud0ZOW2I%_5E&Mwz zUa+oH*<^t~9lz|-gDN5fh;T`1`*Gs9Z68Ak=#B?DS)k;Kl2fXzB_}TZa+4%CSTplm zta>c`AU$U%>mkG0E-_XE54CsF#OZtcu+#T;;wr8^Dd}2YY&i6s()ZjzRKs4lj?;pSCsWsjcb+@+$c%<_51Qs5dhTTZm`a=* z)$oex&^G+jn^MYgob!d7@jM6nGS9zPx>u9Km2h~R1$*o$p>l(q8T4NF2~TcFoU^2*vbn&~y2|w2*5`)F7Ip@_^IIy5 z^I@+&u+n%lByT@BWpvx4elp%v1k-QZ9k)!tf_-Kup5XgUSx(2TYTE+m8c{8KN+@3& zGes49=wXz)8tel|{LMaJdT2(p^>B?~KfF;`dlRmM!aX$mUTJ{=tmMEI!i<4UFy9#P z{cQ4vvb-N z7T&0R)yl&jO&Sm$eKZR{CG3B67S-h!u0EPZed8CRR*#|fOTv`Zxk>Joh`q21v2Cjn zI|*o5499}aVkLk_u6GMNSC7LV3Qeo4ZNK*aEhxpU96I3!JDBXan^YsGh?3hQF|Bhp zzPxc}H_mcxbb`0S9*M5yy78FWs>mv1cgVPQscLqlXl0bX7lv%Ed7uG*p-(CzcEi)F|)}-DaSaQJhUeed`&#aNB?x=^i3{!GT_WASG#o3@M;kS1oG9Q zwJwyk#zpG=JP7$Jl1c`0`;ogky&_lxWiI*O8uNO7kl)_ik;<~vDMD;K`I#@bGQcP+Gj zz{?LZTz(T=W>d%=6Ri1n)IR2$GtF@pQ zTI#*;Lz+C3__eDvD(^Fylggfh6!9Ts^`A-BgDUMdX}O`iZ`8VN5`B>AVM8mPVQ%eQ zXM^o>oaZVkOt-r#E^lLQEnatcnac9nwTKBy%T9@@Ed+`(l?w`I;)4T(PaE=%2`GYh z>$123FEjYIdp0*8QWt#+?jW#a-vWo!2jM3OhQ{s3xAS3TD(y?s{RReV!>KpGgWBU= zAhuAa)F%T|sLxwGkOq(c9*}`al{8S<7|t@*@;PZ=sITN?z`6C)>u%=*0QIAU6Df&$^b*-O2nc)2L@>fN zKuCj-4FQ!@7SBF0>xp{2-~-StsG3%3ch`zp-^=<5;eY29u*iR$eRK06aL?bimCjf zly&av`gHS&)FenT?nTC-t_NjE+fcLLpR0ae5Aeoj4{l9`%31sa6+~fsT zdB8h*V3<`VxIy9rr-0cPJBO4OhFips=4!!+oWv15Ruc$PijD!VYyk00+AZgEX}wOP zDZdHpAGKyy(_Qg9z?zyHUrm%gHNdSCtS7by0s1ll=PR3^8;?ob}bYbdd zE%la9cxdw`><~IPPYONalkejl1KtKnNVJ*Y&dU;80)AY0%BF=oEC+1ql-MtPY2)w= zL21`gXZnR)yAh8N*4fA6XM}ot0>;AM?6dGMf~-0nj}gXK#{xH3T)i~mK~UiNy*zMn zmCXm?#6aSFSVAbp4{E%#)lcEqgc)1(faZ!V#hIrAymds$7uP5m_z-|9i^u`t8o&4V zA)1@*z_lnvW~M_i0|5~gDS@wF~ z24LSkbjf`|Qs?wI60NhjuOxK=Tpoup4A{Jv`r*nfO|CRQY^_+TU-qU{X#eb*TpzCA z296T1J5cI0D+qH$hJE%cX=K4A_skT=FW+mJ@C$4 zJmvjNQdB2>6z?aln|BQ`Ng@^#+q60iPe}!El156P=mVmbj zDuVP1BUlAGCDPEJ7iMRJ%JXOtFNb&Fyu(oQAO1AB_$K50a5aw9t%tgyP#09J(BT^` zkMIJN6rf~7uoWUid0v3d~w&`)I@YS{i z$~7ol**05oq?v4rRl@Y`Ga?HHLI0&87v1D=^|jwSS$KYXj%{uL>B0N<3AjRHS?^a zp3qy9pNQuwK(n1`oo7vYLUPaJ1OG-Xr|w)}qu`>=K0eDp?sSlT7;X*z5g`BNmH-t=pHbm?_ariXH(yN0I=hf@({>99uT`&3PL0$=3h1)?!ok%Jv8%14}*7GZ@6ToWF1ZOy>A^BBoHu-qM+O<1I={=XrnETIzE*{ zWAKzZtDcW`)PrRiU94;-5M3G2!D^4@=dWcDA&}BaN{TiPwbhcIHHO!-q-&*QZ#({9=}a>&$LJxhu}50Ml2$ zx28Ye2zEs;u08I+MhCkaV@GFG*Fc31tO6m)9cwb$n%>J1ffm!Z}}h06?e!5L(@GnB9KwVgD7_ z@S*ZQ;GdRX53ckXCM7aL=-&zF?ALWu3CSND)T$7lFSbmnVJ&Pae6>Wk$SQe1mgJVn z3Y}6D4_-8^(d(`HI51a%M#9HR;+_M|4#btPNh7$Tq!9UYkW#tdJN8Ueli&NLPu)e`@p3x~y5N)cH^A))2)FNkiGBaxqVRU+ z9NfVI!3VtWrD+iRy_>-~4cd6|eu+tx_k@ONMT|QEqif?k6c&CaanoS$lS1vC3Kl#B z=C`msD7tKg@0lJuZ!CJNCsa1;+!529bJ_6}hcc{A*EP!gsx{p44S(5M3wCTu&Rq!O z>*MDZhFNp1EN=u4w@PaX+;(ORM9ULz{stIVzt`-Odsyb8BMgj^op4pS&Kl+Dl)??? z;X5TqiZToHtP?IA>5<7i>RYq(c$)3cg&puj!5srXGlVOXlfn!l43g7y3YD1DA5EI!x{H9?u^?6sy__g zm}cuaH);8Lzcz@i^>E7+rOg=C_wcdF9O=mG{bO)4WEHqk%3`7Sc{A18B;>zPf?pD< zUr3l}HY1G%?(>nwQQ24ssxXR&J4BY>V%d_*eyT`Orcnci>7pJCtF*&su!1H=aJ{e) z-y>wcn4LOlPyue1DmYF2-sgenSREML^VlOulq9+?onw#qy{W>}FIp&fzwq^oiBx;P zaP`Hx)Q2Fl)y~G-h39KOz??93cTvcO-H0uMuuj;qJ3-bMOuf5%b>wRJqJ__!1C&nX z!2A8)0%7c)r}6W`TYJ(KRp4po_gaLuJ=%ojr;yHgGX|{rOHPT6&+^-k6F<07JQ_bw zh!n=-452`nvjB;C(k1uQl_=BYTnzu;JMmHD&G0$I{*2PjbvDCslV|^)9GvJIcf`pj z8WkVlcfpZt6?$pNdmo%#@=mfu@jl}CJj|N;y#ERazYF)J9|Sg*ZIr>MXF$CT7PB_r z@cwB#gIeZnM=Uu2!(p}xh1Gi}jlaW-Kd|Pgs9G`-EF2#q$-Nsjp#%>(G*I3>iTcQvDyI;DU?0a^I^^f|* z+>On0e}rehDdd7*E%yWrb}_DczsY!WR5f+?)WXH_Z#JCpOCsx66QEGW zY}Ypl0LDE4fP}}K@DB}W!z28Od2n^Cfc1y>?lLJZY*dE>Ak;ZxSGs23#(fokxWVBc z5+nSoNC3Ey^&{zEk>U;z)VYI2ap>j+Fmk-v!!pM1aAS*m7mNpGBhevPUQV{1vTuuD z+CyWk0X$_NaROj7-*N+fXpN7){fZI$D3Jhl!Dukk;m{Sqj}+k_MY;q0uz(-NNA=yo z(KNgGyq(}^r+pYl)qtZQc)?*HKYM2wfTL;a&h4_9)?T3UCl`Jb4;bRA++TP!;j~ZQ zr}KsPCYm+Aa4+`Bd&|2=-lO$}dy>sl2?+hkzHIJrBIv;eL=!u~I(t{NWU--aH<4ka=@frbBW6_x5NgM}S7H$<1=-+*a;+cQx1Kewf?fHgIL`_dQhjA0_+mx7!G?0@cbkZ348kjO|Z%cU}7_SQDNq^CR7Te9V&tH^B&G(l|{wF~ms_ljlTdLGYPv zS(LggDU4e$B-9m+#+KFv!A`Dvl5ra4q|z8CJZq^E366m3x?~(9yiu2|_WSK{#(vTu zhs(Ec(ZoA=S_UOVztCQ%u}y$$F32D?!X4au%)#%p;&s=Z}nhm3Hgwij7x!7 z?$?7kF~XG!HyU)7I#Y=22ACn`?d3~g(V($K=J!qcEm>R$EVEaj%7Ui*9e!`aAZhZ! z!6-`>tnWN%^!`DtjV|$frw>xvD2OKy4$GW>4EnwGgA$kwYbM~apSo*cI%gZv0{d0r z-}O4pAvh&YLZCq`SYW0t8qsDX^WF~YlJHo9=G9Rv#x;{i!fFxw4lcRvO@(Dno{Q2%OtCJaOXRxrPr z_@nsUKLKO}SPUjQ_(G2>cyAg6>)YM~0io;FjJP^}iz&1nJ`fqT#U#HVE8ERio1O!U zr%KQt(1UKb_&_Q?BCI};Jn0jV@0g&Z_cq*9al$7F^5H8{QH&2HLAWUhMu-LQnUoKq zlq^{4^FSKtwEixfJ+J|<5+=X47G$LNUfYOo38}At2ile1*WXHEN@bQ%p6csb77gE> zARh`Ga)$$c8RV0t=>l4x_p>uX>%lBsAlx{(t0cd1B;YrhlJN`q-KKcwg-3RRGXd76 zrL^{LL7`g4Pffsnih4Du#hNGSX3L$5G{&U?KK!MC#&N?;gjb{!THiP|_nI0UKEQ9B z#Ppq5juH9}o)z#+V)%+D`U>LEJNY5-Ov;Ddc@Do5j|j#mzCIL>ABoF=8_p1(hYy0R zh2Tg-EQXK(;a&(1c()Ydl@Q*#6Ru^!?dWX8?uPKeIK;j|VhGSIdI|Eb<$whS-aijv zDWoePUYU2|o;RZ~L!8Y{Sl?1%q2}$BoC^;j_96sQll*?ZlP+3{*js-=ta}M!e_J-3 z|HcZ$#t9eSjxB9oi`f23aEe(6@IhSu2x4bIxCW|pKZHRD2R0x!@2|r(Uk8g2X+7^w zJo?UiEKGlAMh?9ZFbaW`=&c%#Q`e18U55hK@m6T58nK=B;rEvz-SU4ndF}FO))R04 z*E3EQT%kJo!D5!lW-Ej^9stLnfJUeQ1w|*PuFz&onLKfYGGoK!tt;et4+2xRJy14) Mg@NJRirBtMpUP%5dB|1?j(bP^;T^rINEt1|IOsGiw zf0c|VL((Q6l9C3HG~0`$)dOvPl`ppSt$49g>gLbN_2YCBrcOb8R^D+dy<^;8Fi84* z5J{m>&pC+NZjVE0$cEuT0zzp!_93>WeB9QVqb9asqGT z{wsq^n_YfN&PbaDPebrokVf4=<4?)Pv`Wa!h6*UnBpsM_3SyG3$G#2{M?q|YA)&PG zh~$K4m?R~15uO3V%rNyEP0(F1UC;PBCIKXq@e-uY+T{MUO6hQ+NumI}Kg|i9m;i;J z1v`t+*bYGB%XQi)%UM|iLsh}pX@JzEjfO@vX_Qnz#b*sT&&qS)%Z;;4{Rjp(2L?Bn zysv`yRi_|*R-Q>PV>0#Ip?v0F?>ZY~j33T`3K9TF1b|csHW&>JME_TV0DG%3$p~;W z)2PEWC1k>O)6;H@KZJMVDVZ+RhK$tQ(vw;g&2i{)idK!IFs@_U5aQ4*O>^dS#9`ez zsAaZEm_7}O^omn5t354in6wHgNQ*I=B~7qITX9;>&L_ZxCJ5|l*}@>{Njc!@@t>1B z^UV^fHV5131h|V(ei7nx5TAp%8_Mmo&C;9DS~tA^2Km21d=27j`Pt`W2@(=y`~vYW z5cfmepRZ{h{t9GAcRl#0zXzcJ7B4C|+lY#h!~NfuajAf7OL@t~lU}R#U;8ZkOTH zni7IG#Gtf4`=T}?-md+#PqS&&$F~^)qykduGiU^9nTiDa*``fU9PqpY zI2T_~9w`26v5^IdbTCD*6k~H>8e!^UbN(u=DG6Mg)Eqh^T+my?T9SoK3$91f4LQ?_ z8<12d+EiL@cuD8OGA87k5AD=JJ2gOkbvdNI*seMn!8Q{xuB=iD7#4^&cBGBG$Ctr$ zj;fUGxj^@$VCg~NM$N`C<+R&krf)1Un`9i`%Bz^2fy2vt`LsFv` zTG5@6lc(~M&1{ys&7VVB;>ouz{+MmG|Ae|>%V5zjsG9+VT@68O3xt?vdnk|JUnVd@ zz*8xX3K>&2CBU_)voBpmxzwcu3w2o2nrIC*Ct3zvH6_D?KPzYFoRu@C0@gPH)^)>J z-*^k_A8K(ak|qw=#g{@xVy*aI2!F&8l0oUXP{bM_u+3Qd#D`(jjEp(98A(Vc&rLpY zPU)r$XF?6`Mp-^*O$kh}6mkr45NlZhOJTCIT16bPVW2D{y!-tgWYe+o>i~vcKWo0lvBx7mZ z;Giqdx&Sr7PN0F=IS8TQHNF6-?-kES@RU|9`XlZj z(H)T-Q|Ax7CN7SA6gP{`$W-hU-I1Bpw1Oi7@FLTbE2%r+Hg9aoN1gb zYY)@CwUH;>NIlN^KQb}~ntru>3oR0Oy!&R;>#~8HC(zvJH58m953B+5ntXXHFIC&< z7&GH8qAqU&%7vkBmXi-->3(m(^R<5@&>by(2(-mN9`HE)a|N1w$cuOaHhkoYvQ|nc zJffluMOhN9FmOcmo>}#2?_xF6MM;f;uc7-Lu9SaR@xLNjyz)WqI(VkKm@FE{094;yoaQ;kq%lFMG>J$$}#V5w!Ed#%i z;c(DWkq;ZzEms!3VH$A;=NE}TMU70$_0hbjCIE zb;OG8$?-In=7^J`&9To6VndzjPbcPN7lyf~r9Wlyh3I7UD>9*UO>?}K0V4WSY>6I~ z+3jb9dRSdYe2Nt20+59Cl|MtMX=U7L=%__0@m@|q>9ll83`9?hpy7>{+6d`LuZR^f zsjTsMH?#@ly(-2Ou?SW~z;iG_iWi8V#f-v5;*T+fI8W5ZX2wMhJ^V1C)BeF<%#4xV zk=7FM#EOez6R=r)B9_ND#Mfh|L~IQ(-JFnSb-O6(Me*0zOgvLm$K~SPVqx4!{EIj* zZq(G<12bC~_Z&qA^fNI~&;pzN_|sRTxPn$BeKZKCoAkk;XOME^V zSBiKfPRqU%z!@rGgHtqa8IjK0ZZ;|P(ay}ZjJp&;w*gC|-pUD=moB&R4@%(1uobwJ0^av)fLbinhbPyA!c2+=Zf1U@Q0K5_>2 zMZEas$ZUL0>>D{1wv62PxP)^7AAH(?t7N?e(cseXIt_ok=eYdHZ>-NuRUB_!eZ#V-=HF}5L`&rS%-?r|bc zL001?P8>)Wh4+dh6DLKa0qGkWF>vyf6eBK3OdaPxo@PMO(&LC%HB$nv$J%(yAvY>^{D z6N=KvmKrC_EKdbe1D^D7q|ha^dzkYpq&PIZV->bc7G}bHd?Yi%(v}e?5O>{$^!?5- zI5FLhfai}Pl<~Xsifghk7Z%nfaoVT}w(cQ?@N^5xb~rd8)UCnr89uV?b_Kq2A>AM)cW(zcf+%qXoh|T~0D&i^Wj2G<+E!$zjyZfEP z%?3Fb5h~RU*QtXPD|{waq)aKA;!Cq$hcy}jypgfd@97VuEsJgB*MDH5oqo>{>>&lM zY1SLAz_n-~-6X5IF$xC#wzs=QQ%Z=JlHNQnN>wAHOMhviqC)T!JbaHyL z5lVBeN+pUAz#$d|GDLoM|G=C*laRKxyZ>XzjhOOyO=9;x@Pt-{8XhD=sSi za~GZ7?&5n8{SP>q;)18CQT$9d#YVn`ZDyp^UPf98VTCuMBHkL`5)NOVWL@2YIFz6i28q?{O||h-BCev==5}}Li!{i zE>63R8WaS(kJ5e;;7MMLO9DgU4r2E zyeiHZJr3K%r$+PCvN1>YjSi>aR6CNfoWar;0a2G(6o#eG0^Lh9V7xzyD>D-&z7RmV z9kK;Q352Nqp5)^N&0j26mSqVqL$2Qw3mZ^;3rP=owgneOZ5EvO-I*!)h#1I>i(chN zoTfEKid6sUh~#4yUvr7=nVdK}i;KHH)ct6{v%tr#2zciDEGyW?fM<@lAZs$7A-XS)$eTZtlMAF)t-uTCV1=MC)`;Z300>gX?&f+qzCHHN%AV;XTj%MSk>@_3 zqr`dHxf7M;n~aD9Su8$`NMQxtttf=l%Nr#1%p0Do>r#HR7E3h79dH7-1w7BU5#ca< zPU$o8H`agCsLa%L!U65Y?o6Yz5%aGJ;a=J^*>qCSIMRC}6~8pySVMM`WNn36*J#O$ zFOpg_g{v<5#`e{~QRS)h;(a-S?X1kQ?R^nMdV+rG^;La^G`)sMQ$Wc?T;_%aH#;;% z#AUYBAu|Pqjl4wB?T{LllnJ~Ua&D0Chjxe@R@MSM8i%DB12FfE@o;JmdA{|-(bF2Z zR?`fvKLf3cC0o=*^!f|RsE)Ad=VZ2^OBLR6PG;sRxMEN~q)S+F8hXLffDG~6n@vG3 zgR5yJz0@>UY)}Z{!U9$JIq{|;jk5a1SC?E7Di2;!u>7g+A74e9*Xm~|=OqHS{YS}kR+<~Wf zoisP(dE^A?-xxt7qr@Raxw1l26}4>3e?i=L0@@I#jvY1P=K#MfsimMb;Q2l<06Pvj z<-Q*hYsO}esA)EDV1yr(w|CGR?kHP;7t9^SU zw1mvtk9=7-Cndk=sPAUKup!1wghX@CX)_)>@=mtR+*7o=_pag%%m#%-E0$oKvwt4z zjE0Y3=Zb5`WmQrarBr; zGw+Em72Q$2!7Lf+>c43>Bvh2+Gjn^Bw>LHQ?pKFi7*US-Gjcw=)kwo)&M)}NHA?7p zWh=ZNg8|EwDJNNM|48;dWD?XY#-?lVh5c+`EJ~Y$==Z+cy z`wuj@C6Hf^IC6rX0o0G5&cmAc98v+#7=O1lzLB$B@|3!AD4YY7ZiO<3AFW#Fs)fP24tVo1C z$kP#!U4Yp_^LhrPL5b${MrorR-Pr!v3Q54^YH3J2qkgT({Vh;MTDQF&y|Q8~e;IVvY{YVWiD z9rB2FwrNDur|xj|=uY)@mYpkSOQ>zaM8y6Hp%_BRq~Z8ih%*a@LoURX5Wb%<9A*F< zw_Z>&9aI+OOi`kakw^ITL~qNl;n#PmMs)0u*BUZ}ZLqt{pSy_Yo#)RaqbIo99Gvuw zz+V*t9&B9e zR_ed#Jk@)OR*U+Hyp4SGsi8*KgO9)a_)QlX+`Anp>uo1#kJ68HqH(tV>O)WuDKn20k2m9wZ4{f5jmTwMq}s!s0$AhF>GOMz60? z*>0>mgtBb?YYz>#9Svbq3ZRtq=qk<*3TW%mH+e< z$V8w$_E(#Ga12pHr&Q>ki!p{Yn)^4d<~Q10UC>6@q3^F~*H=QT%0oZEJALSW;4p3d zfsZhZfAFJ|S9I&|f>O^%q{n{SN5fr8AN@r{{sEL>>%aDq_PIclsyx(~+Gy&hR_QkW zd<9GmtGuqi_C22z2zVd>VOKtV_(%D0Q-Goe=#E#wOcFmA z3_}@l#`l}>c9dn5vTGp^AnVI_HxbC_T9h4qVQV?oZks`NuMFX@-D}7r4g6;18Y%0n zWuc9kLVbx=5!$h-?Cao;mb8qvH8y}U*H${@xj68%a$d)i6{8+fNa~Olw^BXpqM~1l zZVCzuuhcdLg@rv3+s73 zu0VLGZzKH-q}K(Hlyz(H&UfYeHE_%fCG)f|q>gN#D*%RUo--?wO-Nc+8}M8hyroTe zu~UURG}b7~0+t&;*M-IiGx}78VB@OnDM^?o(;Q4z0o6m>*mw!6Q$YbUrF18ry zSiar_OGu(E`WR=2oUfgK;$`S$F?9Ac#3UUfF<9XYcs}ti2R2R>vwTgwM5$>9#b=e1 z7UCsV9p+db{BBN9Ims4x?-0xDf~9|BRc@^M#Hn%JCD?e_u-}tOqg)yJ=Dn~gNjGqQ zc)xKC)4#)+%pqT>r07MV7hpi4H(q;ke9JCbVIYHg4&pW!Sq zqR=A{0nd$rgRV;|)G>^cU#_r(WwXKgK+XknMj(wHU4wJtNBQeoP>F{8D4*VY0CXLA zccB(S9A233A1>11 zs{@~lyQd`BUL81)6!1JVFnLQ|(YrEh|M&`5K5IQCNt6aQnZq9qv$(`&i}VMsB+Ov7 z3U?fk_qu_X2jUD!&vrG-Nd|r6^7U9pIHu)mUcRz?J*AUf`x)Dfvmb_)!&Wz$?+?HU zuc8Sr1l!$Yvb5m{Uj2C~B+goa0hn#>Z=ZeEa{Sl-`(F!!k%MB$8kO~lg z*^&V&lE=6~Pof`#RxIFoLEL(KCLSX;-<~t-pF==Bkaxe#3Rf*eoB__ijgUo6vtA6` z&e^m&Ak{+oF)m!lTs7!9JoFf+6?DQ7-H%|alAff*X&42Vl1E``_% zu@&Mvi0dFe0Pz8czlQkhu*!bB1-KmGePSWxLr8`Yp8+;fu#;?bzV~k~qXb$2ZZ6y;TavI~viNnMuc018x^N#Ao1Az5l7yv<&AnCu$GNdc z(l8I#oNL14H_7)Imq<27m9{gq>jJM3o;>9_f*_HUAOEE?0dtq6G|WSeC*r5JeKfndHbu8 z^uEkn$8%<>o#rij``}v zAk)(O7nkLMh?q;BZ15Q#d}@Nv*x)lBHZZkJ^m0HK0H>K70PA?{+_B}S<@~v);rPk{ zyLj^4cq^BOGLFJ&0GknKmbq}VthvuD$0v&>$(atu)c}`PmJCqh8`BbPBP(J{cU2Km zn{S!7EU{cG*$TD&>oJ5vtrWnaW~7~86<5Bis#dql;`jXI2WfubG0;TG#zD{GPl>!K6A%uPuf-ZvofzWt6#IFOhM<|NOn%zWPAOZHsZU~`+hhgIjH=~V*k*@f9RTbKf zc5gD_vqZkd+wtzLCi*R>i z)A)FNP4k@ic%ia?A5h{b;g>}E#=gG|dd3ZjmcsnoceVtsX(}dx5?&!pZ^ZAx^bOz! zlyR;NoDVpnSY#y8i!#E&I>$&&z_kE55OuKRmqkZmd}?n?O$pI}6*MaZ)*234<2c!r ztmvhp;T(zk;E2kUiVG$KBR9dJa*tG`OKQa-)3{Ee8p{bZ->|F4pCKEDax4v)6Jo~d%w1^h-=ou3N)m9eV6EIyQGq;n9X`peEThl>SG6>o5K0WZME1LV> zl`Q;^E2f#8^lt`;jsmpy+Ck4CaGt~H>@>@atP-A3%dnmr|ho=swN(c21S{o07c zs^SE^R9sg)3M?Bti!;HtaH@Dp)Ti>pFsMJ49W|+7lSa~6Q7t5;P6K;N#D$k-0r+kT z4r~EVzHj`Db%}|tM;YEOO)D)Gv;j`E zWa(fXYrwT;OTg0vrGJfRER3iIYJsUPpb##DvLza%AXaIBod5CDDXI$rPqMhTM0+1C zIRgB1SRV;n5}dIwTN!z=ONn4=p~2j61mb0+pDFBeGx*%9K@PZqGUXUlJPX89{`5|TF^9aZwxJB zL1&K*^`NOoI!;Ke3F+3zcsecP3IvKkVN3ex+WH(j)lDB!%PwJ6i;)FjrF zXqu@aMyN=sH?fWw8K)u{C!tJ_Gdgil<=F_LLNb-mpy^DjQ`38}{f+vZY=GfuHcXNcwZrad*0!b>KWo)LVlV^@-mJ z4JGM6i89`^E18s1+uaV}s@PCniBKd=%bwnO+^tvN;fR5lQ{V15?&j6g9PhggbXQY| zzOu7hac3LlV+)ETJ45+YlT_Wu-8pK#trUgWKF6UiIr7WLbUzG*_bP2EKj#S}>l)9EUb zSf&G>8s?1a=nZ6RIeXmwq&f=*wnjY$o)4+D&a{5}65Cr%Mg828cGq!tmRjxXR?Gve zQ5}5G<+Y$~(ZAb9Mw}`vG8IX6%!dFqR(%1WkbB`K=yuIpkn^xQ#JOKl+6Kd1LYgEk zqBXBVi4{sL|1LpmNQr&Pb5K&FrrOe=-?wZ*;5yg)?xpa(FPuN_u7)W%P#Y@!NY4f# z!ZO;_+7s8PFeK&qUYFCrkRL+fER$oO%6!fiD>3SDKq?BUl(>)>DO_!K zkgj6e7@p=&n8Gh;RqyuFs*rQXz&nWpwyL4zm>aXQ^Nu1khCnh7y|oNjQ9QAsgf!2< zbge9p0jXhSMR;4i&>+0i%Z7yXvdVa%^kpr#3n<$t9ou+E(RqQg?LK{_QpySW+*K** zL)u*7jojpKn)FuE&9AOgO_yYD4;C#IcvrG1$r&TC?=g8{MR;dIBT!3%Av4>N=w{So zyS5i+Um%o2zMksByLT05TnL3>;@$guS(XRMk`_O1%j)S_t>AGU88!j}KjyX}^+*Tn z##Btv3DeQGKq49wD}|_&ol^u*QtT{E`K$@Q^c9?fv^!AH1%pIvr|V~BX&cVF;v(2! z#QG8j9PP5KNPiP>k}CY)IN?Ff+#)dDA@0CrLlA#@D}f=4weL%*}2O!sg3=hQZle-<3(9vU!AGmVPLO! z;qmkvC*ezT*~>1p2eC5jLxT`ddmsQEXflM{%#=3L0S{h*&qGY=9fL2@Tc=*4CW5vv zWOz_t7wfIs3$guZ5t-1~wqos4Z9@r}CZ;PlIK=ZdWlqPpZWNlM9iDT8_P9Gloqlon zje&88x(#@r3-2NXR$g4!7UC|Th1iy0&OJCb^;HD_1w@?C``dU8H*o z$ni6mUVFxcbKiG|hJMrJbbSYF2D1@vE(BK8l;>s6VAHA89YCAR^x_DoP;}%9p7s}& zmlVI%t5V+V{L}Smg6tv#N&xx=4a2zK9C+FlSj9`!Og~pm!FIAtz1Df;2DhTxNfsU~ zx{&XL^D?7Z0MY~O3G+~9rlbi`UND-<;H|2+5U0Yx6JROZln#PA+Bvfa)8Lb9XAg$* zIyk8&3@}N*G!YQI14+m1nGy~yDo%xc(0=`>z394zf*r6gq=y1Ajdo^AQ6bQzHxcF> zEb4X!u=G$-w49J_03FL4_N@N)@+?UcO6n)V(gX{sJrR@z(ESOM{rYLUFOlwLSYOlr zUS$YDYD4#T!hQvyDXg-md*$or7Atml@QSPuOh_Fgq;UZCES6uKf7RmtNPKQ zQ_N|zH?=q2aHUBjm{2~|yE%w1MG#vQ!4{S6U=KdzqIM^(y+?6Vi`W`fRcY@`EOiB zg2}}T-wOA_^KMsSzr7MWfg|pw^17N9xeBi304+OKY@4W6{QGke%&KXg$~go zrJGXft+8!$wQGZG{1?(Ko!CRGe{>{*ibm$E5LY z*S+KabcuUraSuj0wLL$rQWy+caz^_+-GeCoL;}(og!wCPUpdt>>=APG4`Z174~>`l z7dgLwcOCwtechYCo0lK`Ls%EgzeG;=pImSLZiKuqgRl!bjAbmZPRHDvzuzwA&Ym1) zsGxhlq{ZLSI>R5Tus46t64%X6vh4wfzCDNUx~2)ErN{j%z}T=wK=oZo#GTy?K4;r6 z%@P&}sG$r#vC@y+hVXgBJ7xP$AykKWR>t4alG(pe*eYCc#oX%grQbE{xIa|uU@XD$ zFg zEFPW{Ke;~;!qXPu3i9K-XD^%5LPWM2D<#btVp4v)aNVVWHPJjk{G#pzvrEJU0!ieY zZ$*4}F5WNZ-K~vjfs+0U-vjyICTN4Tqr?aAP96P(w{KZRQD4;`LH^#*;s<;Dt=$uiaJ9}@A_$JwI4}7 zFD*R<>0&S{)6&QABw_F;cCg~b!zf)PfF6D0s2cj^P8m$((g^>L^3i?j zM(_Zwfs*Zj{)ykp?946Tk_j>}h%jRs!QT`#YDju;BLXbU2r%^wum{&c7N(^i{LF6c zlvMq1op|3Y85ACE#d8t60K&9+Ahq24?_guAZe;`@{$xI4e}#~~0I}~vD1q=egsA%v zoBIE(_}`8E|E5nt#}o`Q3Z@FYtvAxUiR?^^Ro%AA{wHe!oylVm}egN3>-0!_*k|o3x$4g{7Ivo&avTvBzlYMFeeYdnnZksucSRvQN% zzD8+Ptv&&|)ND1O>krq0Uc!d1TWf!mUpqWcc;6K3{2FRJ6#SlrwP`KdpcOU6nrKM} zV|IGcK~tQQ;EAQDy9kcK^9&Z&?S7yV(519rH`hYE6WexSST=b4KV4li(vVTzGen;A zhTu5Y*PDzI1;guf5#;3uI~!Ar(#HwLZnBgNdr^@355o#L3gL7tgcy|eHN>AnIm(&r zT$wz{p?u}}vU2O^E!za(%7Hv_T0@6<_(*AMvm!sG7|{?KQR5h6Q=fn^3{L``N;=r=yO+y>#jVgtUm=_R*C}(G2r}1>yNF(W#UC{tqgTcQDfSm;@eA`Y- zWByH3r-w+#M!Mk&X?|}Ieg{CD{&(X?f)IB4*&sxH5Mq;E`Ccr1{3nA7fzc}J6+oSD z4rK~T8zgp<3ZUX%5v;HlDlB(!x~XL&)0GGO9$3y=_^y`&o@Yq~fZr5^N2~9>Lbkwi zfS=v-7%uX_-x$s`$sO)#t(9$D=n?Tcc22$3+tcu;m)0~+V4W`?jKgw?%CJ@Cv zwy-epESF{v4p+E)aBlIm{`!xAkYflT50i1l(8*ti*J{>~)VMl1!bu2Sd4SRmmrog5 z!UcJQN*H7-Szk$Xl0L+lDw5-@;jmddcr8IbP7pfCBR(kXydE_r4gs zM{K@No7N0)G&!;iM9CIX!CB(1eovAY>muAL%)v4DgDiUQ<1i&AElf}R5_Tm} zNo&M^Sw`Vh@rFf@CyUxDt@aLYDL7W9dw+hOf1y-}Zc1v}WlCvVZH1*nk1|t$kLs#C z94o$BH9=n=#*xjSx7qzrLka0$mc^p#vF!1IDc1eHA+-2pb$QiM znK&mi?rdV)~L)+$t8s^TQ)cmnbOP`+@yy^yidP?)J=VM|22f8qLW^E90XqTg)+P|*nM+}7X+7;o zgn)D1u29HVK@cB)a3Y>9?tgF{eo;)d7N`6?L^up)iq>uocy^qWMVyqN`ts3jphW#doVILXbWP9`cy8lejjWYz z9P*s@i4#}osN4MF{1rwj!7skH;x?+%Cw8u=AAe=A(26o$4&vB&Z(xUfw*gPt49_3H zEk&-}Y>g1?f_7+Akmx6V0xt#XP&kFNjSPQ*U?+rr7!Sj%kHB&DCUJ0e@&m^lh-)ZmhN9$K)#IIvL^GYT z)letTHG;0ufw|wIJp5KU3$Ycr!QBpu`w7s^p$Fl4KUxAuTv)AfMVa+f-FJ2{iY|+X zD-JLTC5%9>P}q=reMqU`^K6xO$P1x?*^V9Z0*EV}jC)7uIeEv-oEFd>$aP?SB%8!T zR{a)@b>x=#qN4-AvLs%99_O_+?QRlH2ikxHblMkQX$ooDYKnL2UWkTVr4!&Z7?j_5 zGO;&|Xe6Znu=f*FQs+!z$mZGW9d=jTANbn!iRqW~SDx3%R68DDwR~a|mX+-ZO*rqT zr*}7zX0`@9`QD}9l2SCb76u0cJ?!8Gs{CthDJbu`|nwas^|km40jiMfx&-4UIz?*Wv)0&e~x z$z?wWo=P#6qw->dXx||(F^DTAxDtw_3-C4WPBeoOQ{lAz(>yhl7Iyd}>EcF^q?(;gj5;X!c@_?l~)+n0lH{s_^&T%%dw|I2gC zE-%!8mBIT^7WIHn9KAec^gTgeCB6R-xPE%gNom1v^)Z2e8sL%ksH|&$p=n>#Hnn%#V06=t zV#LM`b^#08__e&S!-UiOy>wr}6hP!Y^0pA9D8HaTr$V$t1vZiLM%#izc zT=cT~5|r_}<9ktT5C#(kJF2X({w7h@25C`v;*K{SSe8~10n+rZjd;{e0?tWy{xe-#qY1O z?|pwY^tnOL18`NWpam|SDU^-*;CwL5*qEHz()Lt8!`yfdQkMGaYSYc`>di7; ze|a-=W5MeEi=!$|UyaOXZWw28l4ou_B~J$@$~mSfLU=g__D(BU;Xp1A4BuZ%MQMYc zQ2$4+`-(Vl1{m-ugahCZS`S>z0SI<+-A zLpwm$G=~dJh8{LOBqe9iX`@lxj12IO_+kKoaxy{q<360{tf9s?m`2pd7g0uKkCEzbNY#f(cX#f&Z<9_PvFfo{Oiu0m%Ez#w%I z;-4U(QZPa9JCgOcT{!&Rpe>Aro$R*bqT})8ac>T&1Z(5lYwh4P@XcU}oQ`T*@YMZl zUpFZ(6u|fo4X%(zpwRAnp=8i=KulUYYVsQ=WjN8EUW=!y&RDF2o|gs*HONMtY3@K$ig$!t16p~KGw69rT)8$*b!Mm*aP_YE{MsD+j(B42Y&b^MPb`m{ zJERn(MwFAFxqPz|sC117RLtTL716K~oHJg6hJcM>&M7OvVkzwv0Z9(S$PKN+iG3 z!q@h?HiJ}0tkfs`p{4W|oU9KAb1Ds9Qh_|P1xdd^1H_cdf|J27;&)GKsk`86-jfqC zBc`vr7Y~R}t=ojJig^923c{#oh_A0t#U*0v`h{>!B`N^#Q%V}-@Xn+ zhSXXf#%r!E(SPi>S|UonyhMJKnpV)aXm^?SPobl;KL7y&9z$F z79kc)RtvkLTgatixC=El{t|wV=*im2Em5#7HCTG#&am3O)i~A5popft81U@)%I0&=)wM>4v}$u7An#x%81_%S`aM zjxU5c9pG&6VLy7|0xC@|06$=aKky^IqPFmqPyt#@y-Gm^!Pz0 zC8UceKrU?2N#fr(M%udJWKsa0h_?k;^#L42G#LGIxTyyU7bq=&G6wJ$@EizYW&akO zw;y~KPx**nmO}8sRZiHE!Xdm-H+wr;vhb?_uv2oH*Jo2NyW`7sZ=LAa`> zgbSquoPD#x%GY}Uuof@5GrN{8rq!!*%ZIN1| ztxb)htZ9#0zpYq4f0q>;-r7%HMcTIT0 z@$3Zrl34rfy~baGN`G(K(@5FE;eOnBjnDJGKX``&M8ENXk|zd!+6ufH+zBGbpzO&x zNlI5p6sl<@H~+*v&nAocb@{fdzSJ_D|EML>`h^^BPie^jGL7H}0qJ&HXT{@= z1Z!@~K2z+)1Z!r?TZu7c*Ie;Jm>{|8tW?o(DzZEiNTt-P=_Z?eboWl{8>W4|n0l+1 zV)phjc&Fuer=pCIlfiq?GJJbJc)f0FZ2{a8giDd2$~8CcvZ8c++b#=ljcMEsav8cr z_BWsB>JZEvl-629i*{Me)?!OLm>+vxV#b!+sW~wFTQVr`fLOmJ9{(u5wk` zi}DHC(>X+#Wsq-!s|`fwCB%xE=ePj;4y@IXlsnIl1l?`>8wts!qsj?)Q|Lzcnh#YG zb$hRu2UUE0c_}P|OK?6YwF5SfbFdT!aKXDnzE6Yr)Xe=$qB;xU`#v4AH$t8T<$U3| z{D|JdKf2t~?oz^B4uF4+3l?>#Qi3O~{5?q3(@biFzTGv&2=RMc$X!DOw=NMVGr;Al znFSSMcN)^E%Bri>+`cN=^REFFujXug6%m|0o;%wDvsCDd=Lm<*2*vT-TDI|^2{{W| zalY5{ynNF|RS-i$JP2vjvBRLqAyTFtHpxgq+d?kx$(26OgioVee4c;$;=3vLNSc?_ zVe^a8^(OmXH>>b@{^q+!W?%cRIJ}cNGapo@MgiHRcjSCX_&nQSAAm+)yhmohpDQF( zD`8B~x-9X6s?<8Y4UM^54yie%Qh~N&P8(|lrBl&@;+1EQnLdCV_Dq9m)|vgiD2x{J zS{4ZT0^j|n$#4f0CN||<8!W+M}{%mP5z1>SIjORnGXA&!lLM=AECEQBfP9C;E zX9!MY6mR|(Qe;RKK82fQ76@k>Lwi-|!c{8zB})|O=EJ#fEm_t#O^HQW7X5i&;(PHQ z%*?WuTS}}d39F`<%@$HS+ee;S-%-4TXiT6O*K`_3B^wKk_<=_E{ z=`71~G62v~WBAVp7=Yn3mpP~sN;I1+7hI&NL9aH5sm*YY9A!-Fw;swBNW&iR1VZdbIJlfQx&v@uGnNjJb43K&8>29pR4zIvOrnx z^Gt=dHH~El}5{#WTyMlRf>lz zneW~pQ0qJKrpEKN}tNT(-e9>xtFGu?tsBArPl5=8LubTQg>7rEl7N;>4;B;e|pj6 z74^_X$fxqW8-xaLMt303E`?^-z6;>0+9gF)fw4zv{3QvE9@Tixi1;tAB6BV*4(Zvg zrjYX}2Yj={KVM3<4cIp)RzY`|dqY4u-41}e^OB2d3H(5YkFt!?cKhDma0~-3fuZ{G zXfC|b=jl`VVxo*axG>U3OLZm|hKw=sYoX56fj#0oyIBZ<;R2+j@@b-qdT>#s5Bc9I zCXm75=2BtdK8<3a(@R=8iA39GJR23O}SmPcawPSB@B;ITKT6jme=j?39!p0-LEL8=0 z*sJpBU?6T|su{4g5{(|lD@-!oX(Usu_0oMW8L{~~{%559lCv!0LCp9Kt#mHKnR( zyvrbjxCoKhOfIsPh*AOUDml~B!P}uIs|`(0gl1a%W%P*m^{hh@gd~DJb(cHNq7#IF9ZKwHC)~y zf4GKi6kG*>|0F|cv*0Qy`CBVZ@J$E*#ir}mz&r5N|Ne(IUB5k;14D*^kbmwXfAoYb z2>xCIgl)@k2kddu^>z@%Ny#4r|0($m`0#zl;S}S+6+fb;Br?Ocqph+Z?4}WQBUd}Z*DnhQaCXeZb(=7P~KeYs3!}r)ATMA z=P+Hz5T`&)-jf}L!FRT8e){5+Fri4C^l~w1FV zZMrZ9;S4NLPLjv`S039O>QqABO}`zEDT1%hnh4DGR^o(B>N&2W@tgYCI!%cm4w-Hp zK~D|bB&eGT$Mpf$OH7^zHX#|z)3zc3UnF zdJ<&WWxRPTACLaRg~YdCNll&!+5z%U5p&Ii1~|!PoLfckbq>f??0zNoL63(yMqV`C zsGHa^aOq8tuMPf$1m2MjYZ>rbzv;OSE2JBgnY*e8(nuL~3-;H4!&1Szmu|f?8AOB$ z7h*awchj>*T<~gQ*3z4vrJz7AXeEXypKC3Q4H?l~47Mit9~qcW_y+;_8jt5=@y%ED z36!wYT5AgF#5Yh>tx0iSQCe$#3I5eFUcCG&52^%JLpt7YB&R`7!yVaft)jvyhv!i6 zpNTQ>=K$eT$^XOoUGUcr$g9ZE1+*TI?U=ZJcQ&pP-`l;lG`75;nSbQ<>2^bQm4rf6^(n5lHAG8iXO7rq?e8hI5BTFAafoq==IPx2h(2=A!BPiR^;h<(;JT>c`Y zmy1*Pl_+BW2-vXr(mt)YXCEsz?Tco&f!YR|NQ2Bc@uz)bz~~sVpT`CiI9IBNr%KDs)phwuCCAO|S?i?U~V*gsOzf?WVLdNDLc9;$$BZ z7Y=sySHIZRzv9K1s#snxVmj73Hx$pc{*i-3eh7&JP~*uVv&1BybI*~O2uMYobKe<{ z(h-J$Q2O)x5lhldzoVY{mQ6>Jc-?^ArZWxL3zDq&RpDK@1!bfDSM9hJT2|&k~WJhbRGfEJvC<0NJspU9L)}CLNlQ&t7nUUPCh_1LTaq=2--UgxDlfRJgS$l){jLmLMnJqSGZ=4Ny-fDkzgkQ=~2>7E|hMpDU*# zw~B^A80VS?&|KO^ARjQUhKJR$*0GjEUOUiJQZitlooEfEwUEwFv_|t<5#EdT+0j-E zWsK1!11K7k_XEcKXy`yE8s{WgsUvmeN&HTF`prd$aSNVuj~kUz^C~{lA~nP*5Hcae zXf)_4idIaZY#2APT`01Gnx}@qKp21mxeS_zG-!?r()U1^2VoWjwq0YvTBIS!!!WKf zRnZVs5EA)t$cWf_G@AhT$nSw(gn~F1(&r%j z0HFuMRR}_^T(cnFGP)|6k8Y#~>`$z9;QVNNOyd)d;|`=J>-Xoj&Hd4hha8N?@F5bb zj#WDFG)%UN_2fJN58P!ShdU!-sX{07QlGwmd~IuOutdzBIHS;NNbUVM|G7#p8qJ?b@8pxV>Hv47 zjUs46h-2Tkjj>dVLBp6zReLf|!zNmgLVJq!iwj#(3GC19Cci7el2EChk!Y#d@m z41LK5Dwras2ld#0MAiSRn($0&niD$cfxxz7@fkk`Xc-A>*mfi$iTqFV1ENIs7}7wjWjQRWk2B)a zowx#v%Y^t*X*OC64AXkGZc?TGDFZjjGO7C0YqCPQ{&E8?8Uqt6HQZfRS{(EjTJT#u zS9o`dmD1v9>kCDV7Ka5{vxF5G%wT{-n_JrXUvI9>ijkUnauV z(1%sz)RB5JfB-1BBoD=hB`i)G8gdu%3sIXJb*TXP??5;RI4p?-+(7z62%nO75RO53 z9m4!rn4Hasm1U-oSwiVS?}DJrQaw<-WT_VIW&p(Vl7^#>kg5LhCBzO0k4L4+YeylL z*(>ad8jD+njwn4<5+(dQ>MjzcDm9EVpxi5%lz+mf1cx#W_X#d#mhy8clan8*>(p?+ z@JL)IgsGOz{mUSeI;9)li?kex7vL$f`#HxPZZek%({#$mq{<){i5nm%_QL%Rl0G=7 z?J3}9hf4Iq``<1cT8?r&&iv4udxeixW5({6nAGl2P1_)WzVoX19O^2GL2TYNZ#Bb3 zao=4-dLgxDwC$3FUV~77hPxo4Sx9qELMlA57`9xqX;in0KMAv0Bo$T3IF!k`f^E;i z%3mQypea2#FP1;ng){Kf9OGk2rLdIa*FV=6MMNv4}c@O@6779z8WRdO^IIzzl830yJtx{ zgbN~g+7rC%6d%<~(`Aw#U4cbH7J?8LGuqb3HFF9MrN?t6oLX0BpvCKcBln!tXr#qU zelBI^iCm5c6M-d|9#!X{sb9@;HB*zt1`{1mg{yc&`KuLtLiQNsEX4*sy-Ny!0=o(Wi0I z452e7A-&me=kOj4$9gbJi;w$DOP%f&;sSIQ{v*(7_qe@?6;e~wG#0HwY^*u%+aYXd zH2vFF^dwm)XWzgckh3?qtqn?2$8rCi;_nt5= zE{)xMya)P%y>NG&Y1DGqK0)t0L6W^%*c&$nn}ic_B{*Lgj?0RV9DeLEvZ&GU&t}F* z?@sRsdSisC@rihmaBsXG_Y3Rdr;d6f$n`+5Hz{dzLj@IInf@5@E{98e*BZt>;mzOQ)^$#Qcfu(RN2>qjH zhg}S4I_{~U#Ph<;gdBW8SeKwLbOfG-b&oR7x>OoU92i2G2b@?>ul~**^q%r(t=$JC z;EZ1mdn(sykfF{480M;HQr8lM{pwu&oA3|y zv5?3BadPO_M;U=tA15JI^4}7*>uEiR;xW|w5 zxJ9m|AT0=6lGmp^;$!r{TyQm;kvP*g0(WtzLW@NCkdTs+g1-|cr{rOs@JPzz*e0A! z$+vMn8CT&z9;+hviA+vCF&_qU+JD&Oby;DSC;1p|9?6wa;}Y&3_k@O17m*Sl``>^P zMkq1%b_t^ljZ@t{ZncI}g-RUxPl@>dl%U43|5M^sQbO1=X5!*ae!|C*<46^b(gD5I z@!Wk?X_;G&oR-iL1(5b`iQUJXUm?b$5K3Px>6pyTf=TU=7;ag|=o3hD!;NwVToG_y zdz?Y-hkV=n39n?=U6LA);9U`QJo6p4+eRqx0 zQ=;2Pwa~4*O#`lx^$e97C;_)Zt;SU!kS-e`H4o5#!$-9;+(@Y|L76tSw9=o>-+(PY z3ivUjBjCLfOs|b|=r_zQQ}{GWI}*szyN*{{+3oqJ?Imz#~bjQ!Wd0uVwDeRtkyr4mzqoFuem|? z5Q_wxCSNY zBes^Sz7<*bu7nIbB+7_iqQ%Mp24Y=lQa~Brcf~D-cqwe=pWvV~!b)j`jdcjZKOw{m z&uA0y^TJEo96U?-SQ}q_#{Q^ft~Aby#v}1NI~p+Rk*H*k-b53S*k(U^(+Keqi0u=M z;(PX!{YVRka}a9<`}ol^D$6MD6|!`TB33w=0b?N)oBo)vQ#V&p>TJJhTwxaabXhjT zxi@6v&(da`wb~lzyex}3%ZQOob#EgL9FylrDJ@3Q-%D&jA*rL;I zWKkgv;bAE4JU6Yq&z;4Aw5NH-jr1?OvHm4DmGQBg&ggRMdlCJ2I2+@U+db<}L&AH2=)evr3XB4VJ=p=rppc(lj_ZYW>GSdH!kP3!&02rwRn~~bBOem!|M!pH z{Wk~%sJK0RMh3K@mxQqyQz%(LSduZG0g^l@?9M30FALvgOrq*-f_&^gcsprOczf&} zFgZVt9T)b!E|Jq%174R9J#GT-5K6}BsW-+ReRy0XB@1K1A_s)kS<9hPnk4*`RT@Ew z$x_d@>%yzq@zI9@ghz-Kqm;ipqx7*$t_#0pYvacTdj1sj&i89p1ikn9 ztt(hZ&^t#+&Y6rY!o4|jv0r#ACwcN0!~6e4^cAB(S|jEE6)OKdlvg`CuS#&j{QZOk z%N$i8Bavfm?Gcqc@F%B*;he-+%}^mQQEaZq#Q@)22XnVU$jW^xy69*uw-m=!|1y6( z6aW2tbd2E0&6~m1fXb*b2y&s}rVH+QWDZf&9>Ptc6#Y-;{w|0p7=b+OPlyA|0k(c0INRPp%*E@@u|?+PRg3$`4)_wfi~E7qo_f0i@Zt=nwG5qJ)Yuo z(VAiJ{X)Q?O2@X#Q!GSWPvpP)pJJtFN~f z)>WNZWMIk&!c;KPYQ$Q_cG*Tv_2am2J}n|M$}V(%-gr-HQR(~sTLaw2SThl~gh0ML zRed+xW$rCq-8Z{zBePK^(z2x(=N*`@aK+5bxdF`1HKKlwECYeFv26h4?D0SMl48G>qpf_ZaS1cj4A-E+4qg z#L}Sm5h1@&Kl;6MH5(Vm4}E_Opdb*aAr!H~*Au1)M<%4m>)K@iicmZuoyr;(9-NSb zBZYMn42sYuP(=uj7B1k10|u@i7||Dly+A9K2$6R*A1%DtSWlrd`$J3W7WJJs%@V~7T@++nvHf0 zEaWh7v>P!9Xq$}sUJ8_%E5yfv0|S2}@2}ao0-kH0T&TGDy_TawEC!I4kG>p*(u<%^;PJ|1`NA0^I_aR7 z9`51Q4w~0;-F$O-K%ZBAN&3`|#)4!MUM;4CU0$PqBFrzh-7Mxn0^Uc^4e@?_N6;HJ zEc2|TWj9}WLgD!o=}SpoMk(vjunX3vOwx%ns0DRFuYYLyI>mUsID=lk@&c&Mh{%Mr zaTQ6RI>RvwtP%QHP!EE_?9Mq-+@1P?K#d7vqfWnVM1#%H`c0JHre78G{?l)Sz0X#F z90O;gSRVA|1I7rp$mlYoP`Vn@aS*OUnoL>Vwf=H+bJr6Lw?gDFIm_N3Vmwwvo^Vsp z`|i+gX2KPR0`- zT6RW%Y0rU;yQP$#-BQBIaT^zJ{AuHiUd6bQURt|b8r@{-jnXN7&q)z&O5dhHhbK~* zc}{tQ311*(iF+m@w)PIh9)|ei+i}e##J+JmybJL+5VVkQBY%H`uv=1{Oc5ES477N( zYqV%rB4^rB{RW~P*00fT=vItAyIWdo$mDjx=2|e%G=O3j%pxNqYmAI2=zTfxNBN+4 z=Md7rE8NKGn&C-~Y@jbL? zqvbiL&YkKzMTZNWcj#fitr+_6K7ez4=q>jnPrdn+=+l`!(#rH(RfkDC%_u@XqswZ539HipiBg7y1YKZ@8;!RO6d%S=XX0U+Thheu|y z?(~6Ghf%hza$v>bk;Y@7@w;3jO-~5{7$vXnZ9xCqbY{Tie)t5QK)Z~h3Tf7S?WQKA zyQ0OQQtJ|$C+R>$J~2sa!wTEYafknX<%Zlgpg%mfH;T3mq#d?Rn0_neaLopy7^ZTj z4~#ynhf|ZRTyt+^Y^+sd(QS)0ehA7d4C?SrtM!{Uy8EF8>Tt&u?S^V-bND?Go_+7l z1O1V0;MRLM+cwbu-rHAn8)if9Z|{-*`reys3w7vz?~ldSGl(*61DD^^ZBqlJtc3;& z7}sSUpuh}bhi=YZ8KL69mKyzHFzAIqRCL=bpSMKv$^7;zx|cyIMyeNq)diG)_6$1e z>~ogqs>bj!e7rF)(kQ-V2hm)+xhgpl<=Bj3tG$L+p517%-7fNO8_F|^VfCcYhN{*! zusDf7*-@_Q!n!J~T{kn9&*Vl(%dq$K;8kAZp!hkp;f^e>saz`yKfAK>%MiIquB9E# zpg?}SV%Yo9;7{@g&Mvo%;bkBu9P`MP_x>Oo5Mz(pLK4H8`VooY8Hnu@DqNrShsUG5 zQs;w~l(BL@d&eH`pHk6E1hPa`{hy^fUpo$nH;Tske@eM4*TW=(Po09FpBZR82Uqc$vfYzWG zD!ezGqNn|Ab2Ahoq_z>_yDTXtB$m|&z2k-v2vcus-Os`zN@LRM3-z>UUUl1|z$ zN$2(fc|G#GV$#{_UM_LI#MXhL)R1PB6v=0?ezX`wl@e=cm7)zfF4_j&T62`HaX|5Y z9BPG*VnqfkTtLr#q{w0bZac&s3hFGSCl#kCBF>VWKL92&_-z;W(4VB>7S{uslDj!1;8lGBfze1xq2L2@;ak5qO< z$Sone)uJ_`T14z`iq&Tyud42?NP64?FTA;)S+-hnwEnRj8zG)>ro z00vc8(AzB3Ov}PMg&ouK#*7XiEg38?AjQDRV^ALO_DVkX-(FE&i?Qx zYp5qE?xd89qx_gjDY$>BY8m5ME8A_8))`Ah74ul#w{19olk|Xbsc2&qS(~H^<6~=A z^kc}`FIAnq>_WPfamEZ++bJo1@hQoGQwkd-O>~148LjYB7#Hl6rj;nNNsW3)9gw1C zUxhl4R6d~@@-_!iCVgQ<8or~;uB(|@V_90AWXw$e~AY-lQva&R}k z)9b=uZ+pN}z@G+^g{Kl>4y6xyCI37awY?xNWWD@Ey0@x;aIE4$@-%>YsQ46e<1*fDQ z4f+2$^nW$-+7zo;XqK+eFiYP;xSCs3WtM)Pq2@J( zDD(ZUY7wZB#w=+f&5{c8)hU8Wbmf8xHmJ#|6#isPwWU{PRD=WL87xQ#$&}*t7M*A_ z=>}lC3~Vsz#2^)GuGi7lR7+$9F-=E7DNyMJg5Dd0Pk_=$G7fq7eu%n=-9O?T7DYk` ze=iJO2Xz8jT~3I{6eAXlghm#^AHp!aGJ-XCxe-N;EWaLDhGb{;Kp<3>kXr@ych|nWs?b?p};=@3%F&Qi9U~7Z~@wN!wr541$fthJDkHDT|tbqb0i83 zrNq|HzAD^ZG9IrKo+)`s9bH;Iuz!`Bt84!@32Dc0^v(TGf_H&mh%^=5+1e4juCh!5 zeZ7pE;lOVp@tr}imS=w7g)}3ILI%vMC^Hf)fQ%ReDOfZ_=_{f^VS`DXW;tG0PPAOb zAS|+cBJx71MC^s3{FknF37N9ZrQOL6#vZWrt0Mb42}>7i_<2R~DWo zgyT;^IaJwP%N*752l%&5*=K&@1?vG`2rnI5T@rUambH}#hok8zkf<#*YN_$YkbD+Bm@29oP4}lX!GTuoGG#EX!+!%aLn9gP4Z-iQIYTild zvDzWWZ?*566fRRQwzhU@5`iq|(N|1kU3VlGa9WNBAA)^?i;Io;GQjXlO{DB` z;dgGj?HjOXA#tsg#o-qEAQ;I8WuO5;;tOEj4Fer5+dk}l1W-<22zqw}5N|ZGV2{E& zut;fhfs@BUSj!WUp79vavYJn?l@%hWL zaJ?Cb?7M*xV#6BYF#L$^tbu?Xs_PgrJO{vimo=Qo0 zI?5S@XEM}Xj_}e5PR-#$0krm@F0Z4xu%1{6M}qT11j_Wd<|W}`Rc8bT?{Y{xx7;+B z1m&aGqAZ_Fl~h+wmEy@Xr)n2W3MceXO-tBFxEkc$Nj!sDP@c(n4a#j009mt0#{ zp4JXK>@8Y61tybsx~OJiwOS-Geh|@1!e{7sQ%CsB@Vg^GAkVe816)|Iw*qHbf3L($ zJz=_e#$48ay1CrrKBh$Jo54wp1O!xOvk+D_#s*6y3uCJB$wLdaiVeIy1Tez+%eB|rRCglPmXe$GY(>na;o#V zN3Xog`L@SEcejP*RG(9WD_Tq!l5S!MX3-@TkD+bWKhkV<7q#3qLKJK_@nR2krC~mXk{E7j4#aC@ex4oxA zq}U3PVK2BVM3(&*{HxgS-N$Ys+wn8UJx?q1pszK`Z1{gvneNIQu=8m?TccDlpy5Au zANOP{RW8!OLckm4)c0O~>H{!Yz1c+|PURjnRfvu3yHIYt@?5B#QC!^sov%Fr?;cY| zz&m79cLAvUNYkWcw01Y-@}XS&ia&DE+B6@@wewqSkX@&wx-tQXk(X%gCimN(Wia-} z^T$0kFd^^Ohl`i!xgedKt3S`ZYMC!FhX{_?t`?2}Jd2C#nhabUU zcqE*W2-G^7@K`ZYSqcb4%D65@PwS7GA}^>#R{7UHTF$yAae7_@EM9Xto<8WBSc=Ay zl8p0@RnuI)S4uaqFnO!1W1-e+i@Ga~d!tVg9^R*rB}h2A*48nJBQn`nn?_`xrEbotnvCwLwSF&1Ltgwu_SH2o@GwaErQ^RwlV(Irc54FrpOi zNp!&aNi<|-Ig>q%GN)T8%ers^S|B)}x^Zi3S^9+t4_4sTOUX)KV?WBF1=|N*IlXgOxFw(oS>v{bk_Rb^&(FLolf}Si5D~W!mO)GE+=< z0l<`Q=$4N^`;7-h!VdP2AM|cbvK$_TG{^J$gLV%uAwyi7bZG(1B zX}AZ6H+IEHu_=UNG?#x7nk4MP6F+kk04S(+(w(DqxpDp>k1agnt2U?mJcq}P0zv~@ zYw8Y3V<7Vs?>fTCdRR}e7`hEXUS8%s^O5PVeG0m$3p@``x{RtY?v1R2G~ ztUl`|vzVbJ%VmU~HJ2ayh1GxMKE{>0&D;fUKK$SBP8zUR!{RDLJyc)6MQbC<{S0~e zC)PIFwE|Q&<}sxr#e^jpG+(R#Yzq4UWt>PvIs><0<((_1Sx0nez%)ht?tcF_V}$27 zm5=&YsmLt8?rOV&{jawgjf3Z|#n18!p{k3HM`@ek=D!b^csgl(zGqC2> zU+-GJ^HDhqjk%ev<<N2RLvZKhZbyVOal&Xlzv@a5ieNp6@Zvz=4IB$+w_-X_BR7lr9*tA?Pzp-n0^ zv?}D^2fPi!i}xgG%Z8cMs~2v#Rj@ZI2Z@8$-O$UZ3#1m2p&k^zxF;V!C=A}Cjje>7 zfeYWcOSvf^vDERDNC|oOrj0G~_19WT`xpNfk_imZYjTkE2yGZto#xtpN6_0V39IhS z4Zk7vxXCvBO%e{?JH^llE{LR*8rFKB+f-ZNI1+-7I*YXd??2%!j5G_oz?=94aT*g; z_o?v&A?v<0yj7^Yuh2$YlGjo>q`+7xfVw(?&sDX@%+LelpX!VT^^I(5iz)HE($Wh4 zn5c%ni3(dx(Whzgod7L99YEqaA1!W%^o#%zW=_CA5iV%a+7&XjAqqTsDfS(>WD!|~ z^s4qaZjPi^X&vMrYbTpXRLFpLlN>-P>^Q*dJ17k;P6!t04_H;5g7N+oaCucV>^Ool zj^C}|E=lZxM(`75UV0xyzN7#l+DAC0<7)}k9VI%9JHD3KS$nuKbs$-bw*uoFMEi?! zkeIUxX@cHGL0OXw7=;@kVbkId0a>edsw(H|IlLbr5>Z#iJj70gZ~(%g`$NGNN=%wR z^5QJSI~O3f8^WZ8h}{C=eh8%S?-2W;A_W~y2T2Qw^d_d2$kdGRP*3&1)1U<&6O^T% zyy2}UW%5F0JoS7klZkHpT7T&()QE_Rjzf&L9yHP!K~mdB(U;tec74Sy_XP4#Z8(0zP1V zV9vf7CJv_;hZ#{7;)8*6pyWPaNs|PiO4c&OG{t~#l&gb4X#kszO8hb(hRUmP3eR_vUcx`^H zjUa@jXS)e9!LtkuvMT~Gqo7SWd852u)=clAS}@QwT<}jf9Du-C!8#o#|IZAAbdu9# zGKz8l=v)X(k3jRVGU`#r1a5o}%A4$3nKH?#_;Y&IZ2sep-CP96!YaX03)zo=?kb!O z!u<>4Z22?b_;vuiZWoMRs{&yc=dU+1S>0{0hzt$A3F8J_%tV67L#A)f!SozdybPAq z00CY__gx`qA3v;UI^`xC<3reVnXe)C2&CVK@M#=`SP1Z*Y{)O+S#b!&iik1XQVk`5 z9q>1hXHVYv(he+n1l4*1Saw3kMVF$Lf&xMB0OTX_n4M}>Ls#_hd`{6s6c6IC(*3_p z1-)N|S~~E5ZRsDOmIP?2MPU?Qw6i(LcH?(aM|TuzdFqXK`d1|AmwWt@*qwOQE%OPbK(_s~Z za*B|7qFxKLXsl{J;JrAAb)!5Atbt>M85FV?X>g`sS(K5q0yaLwrCnHR3V2KW3^_%L z)IGGAI4o>iq#5<3|3|k4{Cm|r7H)-D6!mO64Or3$OkCHbLJ|T5U4{i~HOA>LpkXTcYWkGpq{2ng% zf)Vl`AIyXkNPO3%izfXo+tsY^>&$5D6>F9+G1$;@(|Jz59v!odT`($ z!6HCVg2m}w^Mresrr}G%6Y&3!qc1I$QMPY`2iE2|h+ZxQ9e_JIp9XKW5#vc+CsC6j zZ4$Um%b;nJPr;2K3@HtQD*)iVNdSdu3o@Qmgtg?L#p3T>b?ptHSbm_E@u)!;h{Y{I z{aTzOKM&fyI`S+8fe!%Rl>^H)oK{GDWUfKgZmx|5V+eGN;J|()Eie+@~0ZVvD18Vty=hoFQI<+3sJSYh^CK#*U;Mepm)14wN{H)35#kM z$%)$x!-ej+AkPNY$oai4-)?CU9Nx>EyQPJ*P~Kt}^RmHb~ z|FpXF{lNmw+kJHSX>B9jjdbvL z_uFNC=aRU8fb-Xw(uwse#AF$OXvlHsIeFEWS|d!s*}%v}oRPH&K3uY2-QGtLTim{x zXKTSvaLfPt2?}DeTyU<6W4D3_UeLQFC|qBa#C{(T!3S)1mr%MYn;HrTb*oZ!*MZ*( zdNYH+!9~F9E;F3;WX;cq!}wBQGob7zxA0qLl90YiWs?Q}@NTk8i&TWq72#shmLtRw z+dh^O&~1-!vKEO)xKpZYB4-Z$=MG73u;vtZS@l@>UV7e6ras$wPGYPE9%^r+i4*sh z5hv~~#PwVIzN9<(V%z@bmA>bPV%m1YZJNcl=l4G!1{1N<#JKh^N3b_{J=#>B5JG;` z5K%X5gN`qCAkAJlHiT}(aa-+X@mqtn|?FEZV;|M~X^$JXJ3n6{Tq`#0ks zUYF93;QY_sjOTf9iv5>=w{)*2pR3^Tl+BRBIN-mtCzqR^Z+L!$SYc<-drwzgc`@v?2WpKs z!V33*GeWOD<_F^qMJWAOyW^$_?#+E_C*IzBOu0_S&3fBB=L%6RTi>%{V3rk^(plbf zbk+R0;bZMj4NT${dNm*zb`ZoE~dE&?wjsXx9lV!S(~MFW7fW^9*1v24)Io z6^vuWMqsl#g@^0zqdy(~o6uFK#eWrktV>jF2LFGg*Kn^(3t;j;92UY?j;EFl3sY7) zW5`&^O^4YImS-Kq-VRClwpK?y?ia*bBQ?V>6g)bGDwTvkJ=#QF9Ne{BofN!I#MRCG zD9+AlmsxnD_7y7++ckAaFf7l->xD(jXHq?W;hp7~)Hii+h>TN#{{w*ZQ)CP{a!5Abv;wIII@TKH- zNzBRF>;AlMMla5Ft#g9SewRcyalLqK)7t2@#@?{;=cKi>qD3pC^t}+Ux#ogS_=N%a zR9OzX@tvJ$L+EeJQ@KDOJ&JGW)%!PjpE-N3|b9p5GWe^DqA1|?e0B4PxSaKV( z;O*o=uN#49{0sJnd@p#6u&<1;uk7$;LmhRCcflToaH_qDNf+qvcS?f9{?K8Ym zMgg&WrEH}O<*sm%dOr?BzKW#Mfb@RguFt9o)j&B9{cjCr*}YI@t}BO6sRMpFSIGTS zQuZrlX4gFF!3hdY4qQS$CNY{8d$T0hw5)7&YqKW06ypm?8=Bo^LfxNIY#mOdX)gZ& zvQln0t#(C;bksSCH#AD~dQi?mC)WH5`H{EtS%`U{sjoOG&5wY34dUVdL9{G%t%y*C z7muXth$=w_yzQ{}`XIRo#OSL*G9ijc^No3$?<7@|T=?!9YdikkweZ#xPwRS%fVsa4NIia5=&`cEb6K9zQ}wA4^NFnaZ7iQdQbvEen(GB>xaw!yYI!gDn> zrdvHVmp3yv7p^|AL}mH(T2ztJvQ1)|N`aV6cn_mWo zK%e*WP$oQX8kT`Uku*@(9?3D8Ik45iRI8=Oq@nnknSh11L8RZGlE^ifC=W%&bsG__ zrwlc9C)+f2@*Y~xXe@PMdbVzR-IsNBonbS7c8AUU2||ziw+BEKC*c%Iq8__Mb_@cV z-!=M2=xi<+rM`#wJOorxS3daK(U>P&aOAsi#ZT4A!a4f)4&m5SDWl#TRB*iGjkR`g zPIyH4@u^tb%%K(HXcXRazm$Q7yc}Gt!xP(0?lX^A|5}GM65KRQfSZPdM;h|p^^pV{ zddpfoO>x@F4|ylR;Y7^!KJV6!!>Dd-4S#OFp;UDj5;eZj9u+9%$(tc>^3X3tsZxDW z%G}oo8p<&o+;~waer08JK5ZO9uFBt}d3FqxX7!Jk2q0@wC}a2prc z;34nFLnCZ3K?f2aI93M+>h6Hj!f*@tFLvdlq`_>TRnarEc=QI1A zMpJPI)<0&=si%9Awt_XWAgP|X-E0OyjTpNB76{i=&|7g%Bp5a6df>JT%~mA#KvTrd z%7Qn;CgJeYTIyGyaQf*xaGVgf{(k(Duy}m~_6WbMe_2L&evMGSAq|^_*ETG|Swe7w z7FP<|XP&_h;nim*g&p+Cn|a5O_dem$Gv+ZxgKn6A8AEQC#xp;`QO0o39vKA+EBMTX zFnyyI?s6>Nn1y!>+c$!7NjL*<9ujVDEWx9MNw#q~TX@KpjNcH}+h*ctg|BQ`iDQS~ z;cNIq)>uc&R$R~mK6WJ_F@uR*h_EkCUIc0_*x_JCuj||g2M7}HfrUlfS192*`+EEr zfv(rXOpL29&-p08TSrxVevOiWp&e?_N5sxZjo-T~NOQ9sxCy1ptOxmKK+x;Lo_Z}@ z4FOJ0{s?Vnzg>m&7>CC>1w17+N4gcD-?1mCDQbxkAEFG8Gt=;knxE}MGFtZ^U3qoy!9%l$UApL~!R>N$?jE~5sSuWts(_=0Ug9=GQ zZo0|g*6X16?65Fr^LU%zdn<_a;FbCm+#=1m=_Z%4#P--qaKE2Hjitxw_y|6^Bf@Hd zJ3cXdn?nEx>-Y`tlu76B<3$vu}3 z{u^~2xqZotf(t0ke6E3LD@i|$C0Ph=&Z9bf!uTy4sm}t!ds~XA>jB~CElVOcgXgt| z(=Q$LRtmG9%^JNg@LxhOa`8g)0vprxY&LblFMRmySltJ3?UVu8pqASKO2!=$CinF; zSQzwz@`#hXANU34xdM=>COtP1(De9o_fLBq*6put`y7-l60YPGsQlg;0dl97@VEtl zBs}<<4TKH2htzqs&M0}?J4x;ekwSHy?+dtbuI(9rS|u*}lQoL}Op3Ipc4WeuJvyA* zV}SZdzms36#%H7X{Eh>rxF4eVtd5_PVk@tM$~l}9-Hkk5I+BX2%7RsMk5AP@PKTJD zo&29o2l_DmdLPZa*2mzT)?Zz+O0u%<^u1#pkw-$e^h)ZB;l5#AdlaaBEshpGgF|ES zloqR=k9D+yITl^4>m(p;8`i@;x)#2k4=-)8nt9H85{#66a105mt#?ub!@}KLGm{w~ zk*{&{WbQy8OEsCcb)8H?8e=IEuL(Q1=G$KAB%0_c7BE_v<=}6!lS?5|MC1PoKqC@} z0*pw5-gIBF5iE3G+;qf&4@%zVVGQD#K_ zb^(rexpvUIWXK30EC(_40Tt4xWgS==171~r@513m2fVYQyw9EYNDlxAH2}g%w;bkt z&|5xq1;|3U{CD`L<<~>|VY*3)j1X)eZ-rC(>z1kH@K^+QP1%sg6kDa#uokuwzG9+V zV3oWJ2I1b6PN_)(cNEs>^~QAt=O|Dde7oewZE)clVnX(#xU$rE2`g2O)yY4A6HHyF z&zmUSbW;}Mu%-s4mO6F>G>GK*tp`%8^SDHYg0%vyVPKfWs0>_C{a0Z06~MrrD?Sk|+*kTb-_J zl=&5Fq~ja@vb70J#FU&nAHlaK%_)tr7Fb!{2>xPq)(W^M&4A(>(@ExUfGzfW-9EX8 zWiC1*z~0vlmyBDiF^+C2(r^a8V{))8r?k*obpBwUOy*JFoK?tMV8udh8)%%$pfSJq zOVCRBy`8=fP0e6WWvR)qti0aNz)ttUveBpCfW=$J9d>7fkIy^snUe56npzF6nV2rH zuD1RGN-P1zaKe2jcfxG~O&kX2Mzi&_o3z~I(}u96hHKR*bNax;hbMDydz38Y^==PL zhO81dN?$1a?Rhg^D)^tToIUvje2dAdhMRH0>!6NY)#Sg?Px)g}gq5GvF1^6zMFVQVo9DC63{Yof#AqO849)H0ccIXAfu7}Vdbi9z9c8#RK z(+k}Gn*82Tpw1Ml&Be-!#(Sf`Z@BYtEt%iu#WLGL7A(EIAp$nu@~5$Z}5 zcD$&^-GbxA*yI(`MTzOT2$KdkMPX3HRF86!yOFp=xb&hH&lYe~GVnuVnzB-xI^OlL zk&jxg^nG-)2hS%Fnm?Hr+5eJ^`&+I(#Q=r}1T@u@^_~ zHdgm0ROll=^h>wWe9r|~|LBj+z1S@GM|t*`!p{5Ea!=4;7ZdCEn2a|@*Hd>*EnS%O zdfQRIB(i>0VQDX2iu_T5zm|oazcUem_17-S>i=41yg}LOsp30JjlFW?>wQrS8au}E zy%Fg@yN1m9uutF?bVu;t1Spg}%k@n%fN?hfAmOn`{edBEWRyRp5biRSu>Q#Y?Iy+f zb?Qg}ggQ;kBG>Gjxv!EAv^o3%G0Lxs27pUhKa%#9DQ*Kno!(alc9Zjd*Fvs{P+rVw~-Dwwh*a`Z!*+`4$o>?w#uw?uK6!t2 zZ`|ElU!*6^Je7bjnC9CIAS4nHO2YiCZ(Es-^2u)?D9WB+tPTU@Rh-^d#+`r5LxpKe zU+W9UUH?H~c`q&pFr;IEKsTAi{PCxcmE{5$<6r{AjNm(<*ypFVR+oLwRdPvZ5}b=1 zNBg3vNBXcr;fox)VVnV;AYLP2Y8)Cng4OXh(ECQX<=nL^YHs+7x$KwI$NH$KS~zoY z@g+CQopxKf9qxLr!~HP#gxkPXx!>_nk&{bf-DKUQ!vRXT83hg zI*lHVf;R(5PgUu`Z(r4EhdbBgTVil0UW3GKa7Yllg{_;PXGY>v@SVFi;X@$c_AKt` zKwZSPL{6DE;Qfw41Qk}n|49B~a7m6N*GGY5k?W&#;2vlgd~c6@9gVHj!RP061FF!6 z!2bKaGy){~z!~|t*&iP^W7`2x8}Re250nF;!wL?an@~=C`b2|5 z=KAk*+lfa=WfGuaJ_Mx-J)pOwSBda32!=~&Jk=k8?&Fgqpm3-xi;lZG?F zl~qesNZx(G)u1k21cPuU<|r3=_vin4$F_&NxZ$%>m3V{ z)fkaw zyjPR9ZkIj$pRyFGOL^ZE@?VZGGX?3qFz^pRD6%UZtVu{aSIRIXnq`(m7)~MR>54mv zjm___1Au24(L4-hH29JZOfX#fg<*QV(}e9W=Oni9n@r*7;A@RBn@sZavZ|eYz3KTb zHK!8(@vBo;n!Kt8b-a7O}W803>>>VjII_py(J z$69l7t+1zcdqr`39H1zTlJWETou(w``A4^z;$2vmnSQc=6AITdeyRxjDe9Gw_Gqr8 zn+@YpNI=3G;Q9|HI)lbF68%P~UV!LtIMNzB6YR}hEa z&JTlUQa(GYSVEQ9bdyjuzJItcBz z!(c94!_5QDFoe$Wh;@({0yK->fV{zcaJYc?dm*fZ^lFIL6(aWD$Co{h;FKrj$gcpQ zqY$ zYu1&RXJ#yg*05s*a0eSQvZ?Vp*RNlL19f^ z{Bk?vE8+ZWQ}e%h3a%7GAUP*)#~G_9WUPj+zN&|&>@Zf_Nd6&6KPQy!FUK>49s8%_ lSA_5Oo8bch(FcgOYvO^lQTM`PoDMC`Vh~y)EIv^9{{c~kc18dI diff --git a/boards/matek/h743-mini/extras/matek_h743-mini_bootloader.bin b/boards/matek/h743-mini/extras/matek_h743-mini_bootloader.bin index 121b7eae3591fff9d19d040c26b79a92c3a72318..f00008ad995960c90bf1063585a431df485344fa 100755 GIT binary patch delta 22144 zcmb5Wd3+Pq8Zdm$%p{pE&~$@zpCm1`O$+G)77+@?M&@YR3rRfpm3GYMd_@GrHMrs;=fLeh}DQRwZmA`jxp|jEgYA7~uebNDdc92S)}EDWCu&4Yodo}^wEb3i`^4L2ka%JUiJ?&M z$05{yS2RjSRt!JHA(Y(sA!4gaHa4D-P_DM$rZx53a!x>aWhoYLJ<_4R(>CH8`cB#& zE*5pCeMXmec(4QnHoUZCnZC28Kh-E1(a+Q_s%^DJ_*-iZwK+i!8gK?Q1UiJQbJRW zq8z#iO@(2m8v6}K=q?bhWxO4CKuIR`4G5jJO8v=YV&e>>NI~)bWCwI&1Q325=uDNm z4GLwKXw>26vyu{qs(`W6P*RyZ4jNG=Q(_*aN*{EbmFC0D4RekC2nIJF23JnvPeT03 zlMp^D%_fjB8vAXKKl^rEV}*q5kp!q9LIIH!AQb`)MnD4*|I;9pz15g#fO4~wsm7{8 zvS9V}^nvUHxE@bUbE0-+pvsGmsZj*Sp|upPm`Gtcfo z&`u|m`x)|o2LBxR=fLlVeA_&e_#U*@4e>u9{SWZ3fqyM`@;OO_0;DSu5`Tll-@xw& zzdu*mHZl`rLvtSa%h!XDA6FInujvm7%IGmxg4Sb7$Ckjd=Y`kM{kEspHQ}sqTSU!M zO(&X=mgN7|ytyyD=4cbc>AynatiyAf@RaLLl>V0;uzR(l1n@f#Yp*&{<`p~4Z#5N2 z>2~VBswyNvL<~y)t1o;b(%RI2^(i+!`9(Ffx2aEAqev=tKxIV!D-h$g(k8Dq*fdzw&8I=i(3JV#Pc{`U(>W-G+S)shn64Dyar^7Z%usA_WroZG1w$1hn>V`9gMZckL z24HwS2(fM8B3o=){ONL@;r;G1VNOt_a92)fSo5GWcvZN$WR(QCPMY^$JF)GcJt&pZaKVVxgJWB;Snt6w zRz|`c+k!+Sk>BUNLU-Y&>5iBx+>O$`j;cafXpudPIPldhk44!LM(l;lF>-s*>xfHnku%2Lpf4FU$;8SsR8Y6?6REW?KBjn^THEvG6(f#G5Itt_q7mo{Luz zrp5h(j5f!dW5K$Di+YO<(c+20^imb1FlMgkeJgbBZLlO3by*ghv3QR+4kqmK#KLbZ zq{}q1Pa;hcOqhmNk$7B^i|dBsOGBEFm~HjOK|mo2p4dQw&5y-*2C=x(BNG=(j5er< zREhP<0#&C-@_>Ip!eWef$eCkVgqi_*N`T%za38#f*yvFJHwb?P?i9Ga;0}ZP09;xW zV*55Cwj-V_B0$`owAe2zHQapGxKxd{Gce-w630`GWYad)AyyQsM!eg( z-dNSf@xNP;xK>CATV{P{kV(9=3(`eej>Jxgg?7EvG?$;kr^4dB2XPtXBJo)WMP9hS ziG)8IRCj0da{?v4m6*goFMPHF>0I`#KuXr&HD^eDF&|t4W#2+#B$W8ID|F`!$VK9A zh;;>8e0~t-H@30u5Ah|`9v+F<%&YD)h9Ax2Z9913-O4f6OVZG8aJCB)nvJ+l3F+~q zypnKBjd4_$(sCS8qSK#SBI8kNfy3YY66}>#VhEbjjWfe7hud)qo|0ymC#f6h-s;gu zT_|j#{{StL^0@wH^DarxE#PTx+!_k*qKDU1h( zV=XXnMD?C|@~hq@VN4e#KJWh?y5H`cEoGok7Y>cJd~LyZ1{(?_4RQhw5j=SZoRuI7 zL73c90vePS)xL$_!7F%_9L*Q=DovH17Uy`2_?M&_11;uz`S@8!Gk7XDkC*pu##me{ z$@#LL%`8gIx1(M*c(03P5Aw{k;}Y6k1jE;P8NM;Un8&%ZA%?v3^E(UT9EdBCn9w7Z zGY?trGmp&5a09FEm4K>AwcBY?>BaizR>lLWi| z4O$%bRP%TT#|OD^5G|hZ%*?ktSBVQz2mFShGfu5ADk1^jE$AXlk*^G4eU0%i2j(Ov z1~j3?qe68=LYU1@_KvberDgzi&I|h^64Lhh7`_%Z>_M+Ak+}dUBnrM%zN(FJC8I-T zx!3?Jg;Hqob)hd}`Y5t)w73<1DRGG~Ju-Q>Y>W=yE4(pAn^Wm~5%vg5?QkeLO58hyQXA}8ORxUP>34tQO?c44BIrVV-JU+5BNy zeb+6@;P|i}I*Ru0c9Q!=R;p}?hs8SWA>Bs|w*8?r_}yoY5G-O_s8Yd4YzoXbuM$>@Pi zA|vD7lp$P?Nx+W@A+dLi5I zEVnQxE)$;^)#~JIt_ly@SHt@nb?( zdq0E(10-A!7RQebS@NIwX`woPES@9mh@Ubg*Gq^za`7ku8_CfV&Cf1LN>%Vc88?pR zyCilubAFW=jYdv~8LdoKyI6*jg8boPW)rYBC#S9p^xH(;BM0(#5P z0Gfb$*4L$N=lVc{gG|26qNrxUioaJFW)$ zWm_2Wyq6LG1+K$8s#IlBwT70)S>i0KTM?%aR}2wiWSg3uu;{B1nv(1}cZ-}4pM~F; zXpxI;65av(1+bvRKZ?|Bl8fI-!elj%?-!m|FQEQDD0Hf`lZ@WBKUf16U;c_P)_)z_ z|8F3KQC>^%%oJ#4mXM~Iio1kmnu(0h{nC(7rzs>#ahtb~j`Ud4
    *7UU$pC`7dc`bhq5Cw&>1|;?Q z5n>J9Ewz&Bc+@>*Ju}C)EzmJz&wWOR3$1BcljS9w42T0ZM-@UCoV@Nf6h!Lf43T=K z4KLSp$xpAtB8_ne+%WBa_p9x|iE-)ki(XU>tUui(Pt$b51?0i5G=rlFYv18RJ+ym@ z@fcjTDLtcQzcml6A)6{*U24)anR8V6Vp|%2)kzO*TMd*&jzTAVmCjqwN-TT4Zxmrs zpkI1@Mc)jXUPD-xTf8YZ!kgNlDZ-nwMRtkFo6)2dDf&2sM%YqP-UKNFWd6_&VRjZD z0b+&2VkKM!swNd&1wMByth=(!f32zoT7MBZU*TWTVfpm>3-a)ekeTNsHm^$&+Hp=| z%4J*u@ck(wmYsrLusA4zUw*SWa0_!)ZKRi~meLI}ph*@fLeB~JO-QCJK4JZYSR5j} zJwdOAWl)l(NZr^dzlgMSF_RN)sWakjo}YT`|@G3g&GzaJ;sMq6r$V z5+8%yxBTSJhDB);>>$lZnAHI=H1(s^-+)iTaSCsTWnUP*b{VcZO0pGqM8 z%zD53pr6rHu3yrph^$;QLi`*%hBV;-{Xg5KmeI=p2Ze{$}NTM$wOMl1Y% z!b0mZzn<>{GV;K14;-pt2xwS9zb(MdAujW(2r@V(FMFmIw!;Ys`Q77v-4<07ZBg@G zmbyZpHshYmGL!;zaB!IzA9Q(*_NgGRtVqv)2doWQB=Gm(Nq%>NuTFYKFL#|nfu$2? z(%c>KlWVMy=y!)f=CmwDrWTTGAav0YT}nu6q>e5k0?slKgRn3@H3TG0QK_(FK;(&1 zHT}LNuwzmU8tu#4{;Eo?$k5u2lvews-#vNA0DE2m47eArEwRw={tPZ-f)(G70^)u& zkf8vBYojX&l^-#S;s3voG_;tYD2Vz@fWnakMVEL;S;U$8M-Y=N4-3mfXw=(iXWT&Z zXXN-CaHPVQ`f1kip%H-{96#<3zvKkS&M>WK;HD92PG=A|+R(tZr&ftPCfD4`VG?3o zX5@E2JiHwMva0VSy&3%N0IrenGkTabtV*0LZj`CtFi*R&^7%;79450fu4vdiaGQIl zbRUw&RvnUJtja@D92e$!$+uk^bDV7+)BKeyG;CaF*bSB~moh}u{$>th%W@I>A^0EP z@(U&*cFQgI2KWcSWkNo2`@wPRc?Hu!rBjYXIqDdDP`jQ;OSNmX>$?aUreOE3ulwj6Ig8yEPAT{b_Ks1%Qqc*?W=>6Sn4Ptz^z8hnt*_to?ZHO(z-L#~mpB zLkDS((v5YXiPrwg15gjiQ>Wj2=)m#b<7l+JtjC6Cwwv_;|0)hP%mgoKXaDf4PNcK; zmma`StLOmDFX>|%emdP`b5$-GPy|BcSbRQye2rPwD)>H~cr>8Rw#- zcp~lKMWuY)njf9iM6Kh;=8&Vp)43XaLfDb3wq`-wSqJ*AT##G)GY`z}k<-@xv;)?O z({GMDP`RGSJt^Jve(r##xu)W31HcB9qV1#N^J z`00vzeHpYWKk#pe(+3{vLC~iEa}47j`ux}x&H6cz>;9bd*l+!Oq)YMh+eie2Y^t^Y z+UM$*{mqJ!U_(-qv7dTUv+>s}AmD$}>Ofd(1v+k=_gDFX zj%P~~9+inG`lX1or-Kp0{AnQ<^;f(Y}rJix7S;aHTxA2JiS-dPoV^%y7Jx_6F6E z<8u|1A&2Me(s&~hmsk7U7lv+e$FFxPaEHf} z8@dMf#3kwbY7im@U6M|{zt?4!;rdR+V;w6>%6f|9&Pd8UxPL8Jvq%cAqC7!2vW?U> zRXbc4bdq5#U^p%0*{S-)o-H@x)#G|-`Gcj{OU(g2hXrfRS*21iz!#<86M*n+opn?I zI19aR!U=gBtfT$|*7Wsn0I52&XjNZ9#AoY)6jlL5Mz89lX)IRZ89k%Jfhbm`ula1v zoeHXh)sp7Dz}XOiuirhLe>?} zE@H9pqGQ385zwCv3@^m{4<~8x?ZFd*H!sHe_Tb()zx&0(DO+mtKbBbA7gxBFx$7xW zq?B;TG=4rp-4abH((SzxGmBNrT+x8u&kepg7_CP-wyQ;o)9ad6tj8KcF|Anh=9Lxe zDUIZ8V5|dY_lK0gQ8z`~?}r;+K@(aCj=L#jYr_@1`a}@~&RT!~m}lxgKJTpg$nXE> zHJ{fKGPB#P=4s%H>k4JS5FqVkb1E=_PjN%;m3|!1e!M31PD#V#h3Gpo6H@(vJutc@OE#O?$ zOoDc@Q(Cd!x)fG@#Tr8P-X0m5_3I^4%NZ#&Pb;F;fP|}0K$yfAfF5~EkzqU%7Y^1G zA@Tme@BG1+?(w^~_+Kh5>+gROflO@Jogi&4rg)kMYA)0$nd2~TH2X9s)=*C&O{kZO ziqCmyY0NUl>RKm*>)enpDw&m4=bCZ$Cg}mgQqjsN(l<#(hL!79^j9JCHVh zydmX6^KmJ;;<%&_kJsBIPHmGy)e0{ifpfM=(`G1iq{c=F?UqK*`NM%UmBmj1xAPlN zc=QFrL;Kyi?TcsHw2Nmon5~yB1Q9NqX;{JdVeN9H!(Diq+o4?^AVMncE4_E7X89R7 z_eR(zlrrRIhZ|Nz5xOm>p%RIoN?J=cXA+OoTJvRK+0i^g%@u{Dua8m4V-=z^@7purP^8rT{OX zoU+^xI_aqL2_>hb-11X!ePx0+I=)A+^8dbEjf}q+$^Md8EC2G++L*2g~gPWli{W#c!)C()3OLkUNYj&D_ z?q7Vs$PYfn5nv9v5490RaL7Iug@OzIJP4fv(F4Kpz2FZ6u}3h9u$kS2T_6t5$Zl}K zLyd6oh3e48Mx-gYQBi@mq54fme3r1bcpI+YYNXGjdYprV8%|K&=YTx7XIi?c8`>p2 zg)9hUf_?PZXpxl}#51->OXo@B&1eD=|7Jt|1}zf9*n@$Kw#jxdaM2zB-v-y|e&PPR zQ}8>&^LIZO^0=J=(gM<_uMmE}d!E8%Zy7MGG78hDr&%Xv$Sr*>G zh@nhbPYoT$F|NjZS`4Lu;g6~_yk}7NARK0b#anZxd1HWc1uFC6x)4EttnVT}1S= zb0rGYqb%VO_6QRU6TnR7LBm>ARm*&piZAQm1KTfw|1Fjt*z@#|d-8Fo zZyB(KWuGCZ;NyOIFH&w^KGdYKG*~`0rk(xOBAA71#&NSI`713f7&>4&Ut;be6_Y{w zDz&8mgQ({-AU@Ool{13-$r;c8-5J?J$eZ{4L?#2Gcl8kPX`mVb-6{dm4xz%-5ppNd zFe`T#4!PTe8TlW|kmY*=60YaR;21$skN~pwl!7$;olsUVHT)}SB@F7%<%f(4xS5c6 zR;VwCOX~BY)KM4Slz3n^D4}3CQ6|UJ=_nVXgDPZ{KQJ2nEV91Uk+UcNhSmR z)8dCdlf50DOkA zp0;1M;GD~5A~*VVn6@xF(JncKeTAt&p&=HO`E1ub#2ORBB|Mdq@N}db1d9WjSGH_x z3eIOiERXfIAdE*Ej*qPh>Q+j4CN1Go1VT(s>;>oircIq2qBNezcw9lrG&9|oI?pZOF;cT z`A5F4Fy$9P!n=3IlU!<>%MN5C8>}hh^ZDr+GdqvCbYXYfBf;mw?y?_oX~U-5KXvKp zuI30x1x zZrK8W8r7lgxx5a;;Mut*jpVe zUZUp#7j?S&M}Al7B8jPQ1-P*7J9q+xB0j2p1`sj+EZB=fHooqcBd&+Tto<7f1oO~& zewaGQr3ea3WA~msSLwI}Bz{9MFw*g@;|3l^l2Hqw%C9W7k=Vf!4;8 z>k3Kp3@q0ZC6T}uJy9CkUdz|qgg}$@yFV0!ICe=X`bj#j zQx2hIV5*dWBV}S1izn+WgaN86oZ%$CY+GF+sV>{8a2$*$Ey%W!hJj(&iL>c z>PL&o5=ONbsF$hh3du4tU0H!4o|k8K{NO^tnd*^6)~k=Wg2GaM9*Hq9>|mE3?{VUt z1fxm{YTAQbc@$yTwzuomkLFu}+Z?QEkB}nc>k7Yfc7qraPyW_Px~BjEzjo@>XPh|e zQ&({C>1K!XN7yBp9p&PJU=K}wRpRs-MOX(QBQvvLl!MPdcm+?tjn;()AM`5ZH#`4w zeib7*$$(-2VL@gx@eezmeg(Ge(lEx_&s9=zfGiJN=QudPt*Ug8tp?jH=tus%#3&a5 zLj^#0=|>7p{2G!P4$5y(qhEXY6P_M=AIjZ-#nEZxhn-sXm0c@TkVUH6ZC zgAAY)Qr6S`#IAEoWc3|d*}d(CzT;Wo!cnuKd7JZ~73Q4qf19%?4?5y14 zMaBKci_7|%)g6IVOi>fe7`e&-ZGUIAr=9t{(W&Ks;O~dud!4cUwleGhioTo5>1tl= zoN+@=#r9BP)B6`5=z})Mu}6-#pk6s#XmF`oyKWyI1pFE}0Y~;ZX-Mh7lfUNQFG%}& zZ!d#(7aRt9R-QleD6Y@RPvqD9zMG#09iqi@7bVwOqT0*V>jE44H_|N~+e3$4vd4mm zN$$dde4Uz8L%WMr?V0Kx7!2vjN{)-V!oN8y6GwlV%Fp#|y74odni0TD)fJw;J>t9S z3h(}1&xZv}UNWyrrpSKuOgt~=!}$1iEnHG$<3@w+)^F?dV2P*UO+aXGl7i9?@lyk( zf_~O#e^4Nkux@oPOJ4(W8JMe0< zJ?wR>hEdAV7^Knj3!k{_iD~8$Gmb-l8bVxuDm~P{$Q^y%+4$%2=ia++T5;%4{<%Q< zMRJ4x;(YJA0n)w=lzp(nP|Rw>QZV=4^}B@Dxl^qAQo8qBTDXp$)BmXmdGC7qbBF%? zE>M=~YW|aX4o|W{y22%6FG;(>x^H*moNLMuMpQ_vK##J8N3~sX#6I2x=4IP1&gB>J zsIC}j%Zq;G(uXb}h9+Ph7_32BR>D8hqQk$D-^yQcMvjaljeFy|@;UBL1$6suVAxC- z^3X$#e-?%;%g0mMDF@-Oz2<0e3cKg2f;!wW?J6Y1p3H9A@|;l;0Fe~ zokW{ZJ}5kT@12W^!Ca4&QUSX6I*rS-n;HY-qdKq}?AijRx>Oo=AhF^o4)|Xmttup( z(WZdu1rq&7{nzqZ!a!Z6TNfz~1Mzf1q3A%ORT#cE3I8P|+!wnI)Re2zC~9oESlL|NSS zM-?zHhmR5&QyWmn%9ik%T3`(l>`N?RVE7PoKCHCfLc35UJ%Dm{8pF>p;#i3mFZ=yg z_fvjaybi7jI6_7o2OJmSJ{Zw?SP2?*iuL<3yAR%HC|i&=WafNH%W0a(FTOLM{N^ya zeuum?Ze31mgGJj)ag4Z6%GNfRp?3TCQDDvs1ENYh%@-^veF)eOl1B6o`$}JLL@8DU z4{C^w303r)oe~%qh%fptNr(1?HG#=#736G#rI`GK#LnIVHlP?9e_R^h1O~1kkVN7m z8xcTlhM%crfEKv{Tr~rz!qls$Ch7j@#CzsSATMf9C`W7#xUmZm`^f$ObyG;(3JL#$ z!0QXaLLA&MIO`(BCV?vhcNLr)D*tcA|3Be+s7t{hWw5kh48D=BCtNr!RCJg1KU?K@ zTQB=$iN|k9)ud1#Fn>tAQEf?NQqhe+t1tb5L^@=2cobsPOF)q6_mS!peaXqF7Z=?O z{Pw}`Lq(!9J_V!;lW5W6XVmgq`Ch;K4_`)RzvFi&P9bf76KMNXHC<1Gbc_a){8%;C zmRUsG2B%W zxh}GGI;?+W)r=bvG^LjBMdSBND&W5N`o=pE2w}?kG(N3pUy4`Daok5^^xDxKA;_RwMK(T!T36z1bC@|&c;`xl!?5dn{2VX4^UuNG{Vj} z1nv}I^{Ggdd>i9Y<`l;h@psteZ@pSvVmZ#K%mV`h^P% z!mQadfu;i;mDTA0=xGScjkBLKFzH>*b0n>PQ_tA({SIalS%uGxf9r$=-Yb9G@9rNa z(^S&ut`HMoi%(vA5(Hqfy)preIDyFquFFP7e+t4#JZY2F(c)s?ZS?3Ej=xpf>USRv z6mJd`-ybNx4~lP87{t9c7I5)H8!f*5pQ?ug9UJJnE2Q~11Le0viQNB`_&89)M!ys& zu{ls;lTH3f6o6p7PsTH9S*;9kR2WX<PN~o~H&S|C4+S@@Vz_SIEJ6HIwBc5#4RgdBPBdD%Aze7H?Y!)BsXwp|4S-8VR@m^0Jj z;la>S)TAPJT6V}RlUij-H&fzDxDjPtsbbPBwA%^(n!tI^ z%;YRsoZu5SKEP>BP>m*6teyz^f=W5F%Hjk48`g|+DKG~Y>q_C92h`Tu!=!RzX;sU} zaB3Q9u^&)uagS2J+T~AWQ6qt9;ZAI<#p`T*mlZWc@3ZY6R1g!aW>ZV(1X~Z1 z6q&GV$uD@jV6BY7GlU(L*{NkH^IsCG&A4EI>_JB9{iuYTHwt`AO=I2fyF7u)(9O-lkj}`zweadA^Cp;@4Xt)uiuQo1P zj>HC=@@K;h1;ie*Hw_rA8|+|btgJSsLaf?aYF{O)(5P<1O=@sMok>;yH-^zlRT>m#tmcIr$58J~n=go60 zF%@Sl3oDKYa~}I9s@z!>Fvu=%n$yHu*rs83qen=8Ttgim7Vdf6K)pRI)IOfa47*bX zg}*&sOP%ow53N$EfPydEY#GJdc=fVUi$VR4*#eWB=M!pIW#IKf+p1Yqv`+}FN~Mrb zm|QiE%7J=S*@+d)5qt0nc-*xbv3I~CNAoO*k(cub)JL1Z%D8F*J|JAIs(wH}^kskw zf7Ex7=xbz+PEw7?hQs*qb#_o#hl}RW`8A!=n%T8A|Ezh=F>jrGs!WG&{LM!Aa{7lE zQz}c&0(G2hr*%3z1`4O$mSI8Sphx)m38OU}^bJmstc%rYmfCdyG|x>ZN;8PB*?ws@ zzNSB3uPsXO#8BI`XA*bMUK)@W9 z9^!V|>LfF_^NE+7>a6Di0You}m zNP6vP9l0J0o<1b!bvOX2blsYa`cEhlS!w1Lijxe8u{5WOG6 z3wMtlV@0lYK}EdB{h5Eev;Z2&2famY@Hwe=c4jLGaHJYg!ja?VQ43P*wkR!Qx2WHy;Frd@&e@>EerIsR(zV%t*7>FJ zuk%-41`{|)kUzk&v_2PWpDtn zM9`0m6_^#uD4YMb0iR7;pp?L1a&5a%`>5U;3+f2Jdy)V41A*<*eR@0@s}BB4Vj6*j zL{M)Flz-vLFG%?ppgd9^k~GI(Yu;mhCCu~6P(<_g0?Ll+4;o`TD_+_2N)W*14X{ez zvjV|^J@?Vt!Vw6~9VBwBEzroft-B;fPhPc-$Q(X;WzVCNo3}k^oWJLlLxbbYI6I>G zE#sce)XyN_r5iTmtZ$u+s|HT!6Vi6+UU;Wx;PIWCrQCZttoclmn}3v)Ra+&7JPza{ zme&@d)Lr(UoHLq^uQ0x{>6M7)xaOTkYzH!{9nL;(RZ% z8OuE&LqgSR4(}J_HLEKtjW@e1FK=cB7Orks5?*@h z>gZf%z%Xxld6zbW0XXP`P3^+OgAGJFQddZ3PL9rCyx!>JI{`^Y0T zQm?8dlxI?PAOl2Vd@7wh4n@yO1tbm!MWKd|;s1O9=PYzoQQ39IF;&vfD7CD|KzFuN z+PZjJd%U@_imQ@$(^`frtqRhzRa>jRuc~U3&AR9$q>XIWd2;BX0T`?sI$I8^t!v=B zz@Z|ziatCT@zhQn@^L_`#`0cwmGI@$3D)-p6}+YC!*w<=uZSKllu}StE1uS{ZkJJZ zArFS{9a<%hLBZYkL(Y)9A0EBoNi9a_*+LLLIs-afpq0g+fz7A{eJkV8ZUMz(jR#t&peu_&W5xccndGD4r~g%_Sn!iBOwV zeI9w8rD@15_XxkOHzxcx=!E5$G33Q(H1jLm&7m3(KBQql{jm z_IVy?zkfZirbc-M&+`TxCQRKhKC$x_WlKQNG%y2R;-9q091AQ;Kmz%&VB0VgJB6P% zq{XBT@3T}|J~Kx)?c9R1cY^uh40wr&#BD;DwIZ$p2=5{HS0DqbYTFIO0TRmr5qAD*E;+B}3wuP=jt1+d=^kjS|hzZo;)FS!UjAsWXEX zP}pTtTet90phA1FE25RWh=%7^6I2)RCq$lioIFhh%~zep(7Fm06;lDqqaAg3s3?D2RlqJ&eyw&Ue&Hr!bza&)_ zeK6iU8w}i4GXNI`IV(&I9`L%7Y4S$-VRL1LcF6})e(kBNa&4$~GngNcZlmld1-dl= z$3le7FMTIP&G^|lGnw(q*XVOE!TPYW1MnLn+vh9*BYqK169v4%PJma~e)m}~lNixO ze~NeH!JxB;n8ctiA~LzKMI&0tcS_*nC|8+f7Xa$rV8AQ`h!L9)uq}X!z_Y>qy-lP&XLr`rQkm!}r@CwFppBfRdjF zS|OzM_f7sW?iYXn@^&2>4AqymUf$9r4}nKRyM*G6arkv%*+wl^3tKkEQEI>N(Z<;d z=@{8dj|jsXr-z^RVJ!$E;h~%y-l-0{zZPa~%Chd3kQR(~*MdQP%7BwRR})(zXCW?f zCN(bILXX#4;##%lO0(D&VQFp>B<1n&^{*62=jT|!((w4nt4KYi6?5~MR+0AgKds48*m<@FpE@64EwX;Yr#jn?ufBu zweB%S{TyRSYyBWLviO=)#fR{sv&KT@kAy~-qybVCd6eDcdWh)WVR_fMrx#Nn^is_G zy$s%AzV46}6U5OAU%wQY2ahd5@@s0^X+bIY&YfnhC9PH;F0bdHCa&) z2MB>F@W#HcPyqtzZG5~XKrqVTG0UJk!mBqB@(|bVZo+#d_ckA)uO#LeuZ_Cw#R`=AQA{f9z?{?_{CDJCPH7pJ9%!5g@K3fx{nNj99 z_REjy%-Y9Sn2$Ty8Jf3b0L+FQ{Qw`wnsv(azk*EeEZ5G7v z$`%&HjoryeqbRPd2;=rtNbdVR3T+r?)m9L$)b0LfyML|%wQfNy*}w%VZXMgS&xjm( zZ8&!juC1F+s+3rqsem`34mX0hhuoevI37py>Q?eJQY!PhtG|k9^}01fs&2|Pmez`4 zAqxx8jb_{XE>`AspYYx%vG4p?5ZcL{SqS1)1COlYM^Y{XyzWle_t41e_el&`kp%^- zMT`kpm&aaE6j^4rqw)7jK~*Oe3J?a&Z)YtauE}3i@Wk1}#?K&yJyU0#d#0fmh0uIX z>mojv*LJ^W^q%R8JIXt*QpWA((54?OznbfeANJBR!}(y#nb^|&V6#2cV#QRG$xLdm^OE1kyoZe2?4P(;Dhn{m?S96;m6$bz>;pAnP%k~3S^>tU zm`*pZAOiq-Hii#UzyS1LJ53-|!gQ?3XujYiO%-|70Z7^5y(vna-fuaO#gm5J?lONC zd7o@$@#Ird#NlHuP9ZN z99P}ORJe3J9F)!zK6zyUUMSG7W{xuX6kw#FguBA)zA8+6bu7*j?tQhCo8i?2R8z>X zzBRfVrCf7*fFyyh%K*vYb!U5pWHom?x{8{*HgxCEl+%U=}yu<6hNASP?JRJVd z*QP0+J^0!y7hP>|+2q*%My^eC+By2r+7`ur{K>r% zvjV;8b3X((m%IyJ!ST2bB*3@mIj?)-pm5@i`_jsR2xePk@O2qrsELyz8WDC>zYQimS%N;i`{uee$7n9GoEl6w`d9me4E@x3%Hclq@; zF{yfo(QqTan!39(e^KlQ%?G^_e0xWklix$ zdoDVuR{y`r@KL%!+-7^fHx$Ew3t^}}JdO)(^1AyJ-pFu651ujFON%u|7KV&5F&U!H z)PVNoN1KTcg5g3*QQ=jF=l9_J(O%^HsDP9V3^$89^HBk^-Z*Mw`44(WGlm}8@Q(9a z7pFLA(0CL>GkfSz&ZFqZ9(iB9X^=py7(uwnI|!E3WGF#iRbU9LcQg!v^2l$51ct%7 z{CC>K8e0v3;sx7Y7sXcOj|^r|3>q2C4CEc{dkqF-CF2I*<*q#QTEU~|sl1AOLl0}% z?WMNA-#Z$=Z~UJBh`;abJo|%92jN<)fHdq;xHT{kmm$dn(0T%m8-XhZM_9xz=^yuXSN!n&Qo_+FaFGL;@np9J6Ic7|F zR%d@NZ_6>G3_i#cnj-U}oN`OTvomhc^iCsZH{QVDCxTDn@%9;kINQE3Wl3TPpD+CD z?E(#8&TKUBy3#Izpn-InO4+GY#tt2;sUnYi;!)wwxaj&c{NtAAyKJvdHU>^ik>v@WX(pL&-qP_`L2HeG;h5YI5R=kbfSxa} zjcC!l&h0QVGFS}yC-|C<1F8M)^I&A*cIyX)+MVe!6u-k#Z4Bzf11P-OC_67JsNRc$m?!>qB_0-L00DI;7A{3ci^c z316rPokqS0=mQut$RkVD_|-SvgU5uG?`GgTgdOj0Es841YvJIX?i`EEvcni_cRack zbnRH1ntU8S&K9g@ymT`5()4yC?V@O~zL+hyD^eK;k*~h#=bEmY293!*~;tGfppN04i@PlvV2SJ>a54jZ&z2%Pz_`=h>Z(1u-5qllnz<9)- z2R8-WtK;CgG`L^DT?aP+E)&v;OVB|+xNpEs%K&-`{9nL9i|D6x#HuGCRtxC~;C|AB zF-Rsnzs@H4a9}auSa6}>l;99L*!zAAKFBsGv1)dCu5sqmSrf7*P0&A*Jt=F_q^u=5 z%W{#R`XD)L|3ipv0!O+be=WDdUNd5MJ%ZSyixInH$w>aa%Mkky;js_K7W}jl<__-k zQf*bCqDV}KRFV9PB{HRPS(dy14zJ;oVRcJ zDXS-@tVaH8@7n+r@W}GH4I}xRAiP+}{BV(M?{&Ww3vYawBADN2gfBjfVAp}H3z|q4 s=DZ&*{Qlv1D*i)Z^hX-}|IA{t;WByN3Sbtn2TBJ3`va|$W0x5N0OUmc3jhEB delta 22011 zcma&O33yY*`Zzpu&Pj5*(4-qp_be@Rg>*s6qNGWCx&$nn%BBR1dJvT&crA(~Wzixo zg~Qd_x`S5)g|^UpDOg)Yy)IXO3DA3i!ljB5XhBbCA*V^3eD9=q@9+QppYM6TJkMn2 zoY~%aXXc%Eo73_G)$jw=a*o24LNAqVi>pN1IE!G?o*Hk7tBkAIVM;xP#E@Ym&hjF0 z#c1h^U~V}vrof6{{0Y$>VCn9=m0xiX>J zT-j7j-9-5bD@~Q>9!%g(;=cK|1Zx7n3y<_9@GAH(gi*eMMtWvIY!>Cv*fa|i95R}M z<(QG4J1Ro?28gFXY!WFd)LIx!VMswskdtT8=@P64sHYPZlu4v1QkN2oD0PnC!6p6|EA!A-7bf6QB^AoI8OHEkLM7Cq^3SwL4RI2L3%!RU*`M!$4wLkWZ+=2i%&?XNPUl9GDy+m4@3;QGHI_jI+9y%wS z%jUy6lDJGOZb0Iol*!{pB;FzXOQF?}+V9`|=aYKTX#PU_IFGbd1BfDR6ha$(5=V=HO5 z)lA=9X*R)z7NArl032Bnrb)0Oag`V8lohlFi7UN&*lRYkS?n|Gt)iZc_rbraV1AfB z)Mx(*W%aQz64?E05{Z97eGG%r-U~tO;}D|T?Rva_6~}M^&phG1kZ9qhkQjU?q>>dO zmP8(cP^XK_{6tHa!>EUIpp6U&_ID8b-4i&AZD$=+R;VMPx#i*eoyR}rSg zzYjC|0&4+}vr8`+csruS^TSydHN0W0n)3H-NDTGu;Zw?c`Q=tDF7qYA=mxzB@SgwFCqA1a{!C`hq3sKS0=Vfj6S5C zR7vv5f>ozU@?d;O!s0~Vh^v5KirQSLO9hkgF@#1y() zVttztJDf-+3#A1-sn&qZQZ-cc;7Tpp%>cw_B@IWlkST9%MC>oZiilMC{o@cj^p5a+ z#031I@JWQ8ni3(LjJQiaC4x+da8Nrw^bRd94|x9R54DJFpsMyB&GKH?xMXxx$(&xX?-{`x+9Xp~TO<;Z4Pm zi^TWgsW;f7Z5YOv*wT4Ld;xV$i9&4dRZkVeMQ}e{Mf%?dBVQ0S^)WW|-bD%3o#M_( zXfD#6k&p^cDT4jkXd2h6;=5r5AgQoY#-R+(8EAU}w#gbX3{CIDxzYU5E}V{MWE!vW9N{y12$v?vTSI^EL&&yW6cjwa)I6;Hv2Ph8P_ zM8#4RZAH2;9so!5z^Qd@1Jz2Vml9tKd;{I@cFmP^21aNox7_POXn8Ss0;pq|I!jiLsElQmbe~$#* zM25pbi%#x(ApfCk9k$M8>yvxJ>7$=DSX;As4R`6G)x7>;q~Eg= ziAx06_<128`86F2%PH{#p*SuZuMr-P(-%DFe;yVy%II;bG?dsqf-?3vu%2G`gDc=U z;mfRj7qE{8A4cN8g%fdRwa%}DRSYeU)t?aXyyb)4S1+`Tj}h|KF?hdF zrk+Dxh!b8@=ip<)3H6=0S-|nJ@yAAGO{BeRj-PhOb^+J4_NOhyFt%5O$?*%So*0!i z_uf9IyGISsgVy)1tEMb)O=eNGC-DK#-^rwkQNx{ARK|eEaf~brwwQw^DPcMN zPNb2M{kTOVe4CJr>jhWB)Nw2h6i_G@L3}V&i{G{3P6;9EVp6PbE)Vakr1~ zT;%jng`%|Ft726wcW-5C#cbT(m#8?zW(yPTC)3~`XAsrIKJ=8J& zIMUp3q3j`N7@W3lN5FG^6lGj@UUp667Qyy9FN{l>V!JphlG(+UZk;F|5z_-E|I_L0@*-BUSYk)pv7LVYcKE) zG7Du>wJ(tJRSduu?nQe2(_}LD3SViKj++g97u{m$R6<2g$koQ>{>_hpa8{TU@TSmv z*(HbA0Q>7_I7y7K0BV6cH$(Uuf=pPejZ5DMy|C?!m^{LWi4fvP##z+7x+5Ie!$f{v z2hu3SZ-q~^sklS(w93WYVZp2AaJ5jZTTB&tg*SEisU^P7 zE36TV8$Tr?>F=L?@^4^LQBiy7>~vl(9u}_aW?+|)sh`YH;$E+?On(O>7bi->Yx+B= zI-BsL{$0q3_XAEiwUIjxK5G*-Xox^OmaGVT#V()HBiX@@7Jk6>8{6B0fo zWKX=GiX0YRoOs8*vBP~2WdM*j{r`4tmF`vj4#!h0`qZUr|8n(i$%_1*5eex?Dv~49 z=J!lLUex~8YI#K#_vc`KKCDM|$5`46JXlfZ;)%le42^oTbVQnONRZ2Wj!1J2iE^q( z!!cs9B;1`b2@Z_DC$O01)2so8P}rU^4c7`MGUioe`p3AEfz?e1=&c15^9Gd}v8(E>QP*&Mf% z0Y1+79%5$;+cTezEIb^|t;8`^zb>A{#GXD#M+uQxxii=b+O49nKAabfdUKdn?9_64 z?w_zEP#9}O(qJHoWsQC94U)P$`tGX!*>RnVvzfTl2WXY>Tvpy4vdS$+q>1Fi%m860 z3L$k0Mo1mYhR_Y))|&chop}@CmwM&6C*b+AE8uyhOZX*gVfhPc|Hf}y<(axOa0Yp? zJJ0BB#pxe&;a=Hbyyif$uGLzgE)hHPxT`Mu=B{0NRKdFiW_`_+fdXWOmo(LX6q^ud9 zZ^76ZXoGDxiW(%h$Sc*L4A>6P&w@kU*P%NQg{|7a}G_>4+2*e+*b24HlDu z(5qY3aQ?5&Es9D|P`It8lhT#x)U7Kzv&g`l5sax|rqzhGitVyZnySa~z+&K- z%_ytD@pb*el){oDzFR}wrf4(p|HA!~6)Ebw*)DT`$-04grJI;dGLe?8#5i})Vudqm zPA)HOot!lp57-&%yx57;esrbr*pOr$0<@~g@_;~qlG-CyDY$U%fsU|ElZDaA)9!2S ztlsoV!kWS7qfu`4pF%HOsy|>-oFDHj*wCw>d#X1P{ZjRxw42nHN_=wBK+>+Zwt+oL z_FQZw)~om(MjD3mtt*+k?kd=x#pMB46kihXJR00n_S4WW<~ zvT~;js@x=bO}h+05gK#SsLWB}vz!DRE}YFVD1w_n6()RVSi+6^4cs6wO0Nd`fnF#P zFmGK5Z4WS@8Zix_CyAaZN-@$yFiJ39)NbAchlPB4551|dVkus_D4EIcA(JS~o}?5Kx$wF!e%u-T~Zr$FDfMtmF&yMSllHcx|q zhYYTWfak*iwJEwHR5KqhSfn39pb%&-HXBIY3tXw5yJvv$nGV(pCuGPrvm0QlCv5DogCYn1b$EO3H zbHbMVJ8gd+8B+zpn)mbsBp}MvDu&Z_m^VE*xS2MSy4rx}tgm|08hEb$(^AFF(^`%S zp07Y!KKo`IN-Kmuft@Lf<_l(zsZ9eOdbE#Mx6-_p>*X8E{QBIgi_({NGyypB&?+%0 zR=hVx$7y0TO)Fq9BxNO7`GLXC)^P5d@{0Ix-;+L=hh6KpmF1P(W=}E&%31!2J&Vr z!~h16kt$n1y`ZW;8uX*a1^Uf02jh+nE<2;Iq;Jor-BMEDZYi#N;-(dwe%>^@Uoo+` zpVsb{#y6PyBXmmd3sP8{(!1H;;SN`3oKfCjLYGLH;&47;6B=2Ru7RkbbZ9fPo5X6Xas598bz~P?N?v(442Iv-iapLhN=#YwKD5g*3>gGVL^qDx_Keor{{B=8O~rO083n3U#LJDuDL%vI@+qS=w6IAehL~B3|iXF z>-3v9xdx#H>QKjJ?Zzr-bM&AH&)$QJKxttcx^)m|*@gxW?!T3(`6o_KvQprZh9_{QE}i-jXp6D@IWA%p&b=3 zS;B!c-BC&RGbqVO^&>D0fHKOSPDk{-V0oc3nUCUQjk)1Q@gqA(klL-4iQy>QW)z$4 z)wHr_lf`zs$R}+m*C>Y6kwP0Qo7=!BBK~YgIjVCTDzSFMoM=9S8zU{Fo@Cz@UeikP z^H+toW^xT>T3Kk%+KO+2QlX2d`MUf^q|Funy(}TJm2_UgPl+5 z9tG<8Jfxo8_@QKbpoLKNXV;TPG})B12r3*LP14gowy_Zk5mH+Z@m-cA6B0}70-lM$ z+>9x*&M0t?ijTA|Wi|OrTxh~YsoQ>0I`b}&*OuQEQ+ulVx%kBrTLaoTL#k0yB=%ta zcrkz~B-YR@MH;f5v<k4v0GxR1c*m6{jo0 zdPvS6026WZ-cdG~_c$weWBKRKIM>+1z2qbVK`msv1w5@Iy{?N2)H4Qfj4KA%I2&+3 z#?X-#iI7!t`jL~5kkvm(t_Jdv%8m%RC1kfsw1!oQi2Y5muIKT}s{ZnX$1O1Kor(N- z9_yA!AvKhjy^(K1yVPB99MY-AI3QbCnCU>x%f0m@N!khhw0yZG#ftTnQi#p)fCc-) z^VHmujn+J}p{kseC{lB?A^-=gy!TlIX@e#Ta3Y6inRkI@2{5>ds3q&;H`dFedM-+{ zKVLIg8rih*Jm?T9Q5msjkOp034KnsesQv-(;@3B=pAOh#Np}XHT+w4HM+0HNX-xO3 z^fvOc2>43eZ0SJFGs+2cMHW&Z#TxKrdhNk#kF!Lv7v@e1+v41K8M>jUtkVEcyw~X> zN6uSb*X5$^{`wjG9SQ1^gQk65lekpx^HMS7t@G|n40vAhPTO8z@}b1qdoSxOOK&e) zn{BA)U@DLnKou}2KVD9p!)j&jSQPLq^8R@^)_}4@d$Viopv;;7yZvvi1;l%Vzyi>S7JvaHW0Me4d@)FWqu@cFI zu-T-6n)VD~>I{u74QW%$Z?y$H71C3hoF_*-r2#Fc=SRGo;PG>P^glR6Jftqov2s2zS4{+|l|KRNtL6`YZQSHQe5^dti9)?J|HvG{jX zP#nzxe-u$A8pBPJH4$k|R=>{v@E7Z;rzoyl%E1vn%p~RCw^H>GHNe~ z5Qw??gbfnL8yGB%)XiPg5^F{N38_y*{(lMnUkUzS3;v72{~?XvGcVxxR0pO7xyFDt z$to6@rE9az(mxxK(V>G^n<@Y-Ej__Xl(U9m-{?2lR&NE5AS5)yx~qamXn!GU@>c#5{!$4=1}i0yDz z9<+B45{cn!*vmp+_IMeUX%ycQGH2Z%w#LB>84IA;tjC0%vlb{y9PKxaYs|vHtW2BX z%m=bbJ+v8TuCvBCF3F;L7%`lw>aVAj8phpHLW|+_X^D+#G%CFGptc|3F!PrZTX?dK z=q(YTP<(;XE^^V@dqLO-M*z)pE~J0mh4p`SQR$z%==3g^z8}#)26ay^*J(g#H_(j4 zuD~@)UL^>|TryZ=95wWwaLzahuN6XypH@efR1LlVq?)T~|3?DSCUf-7_y2^%XM93q zap6799f4~q%T!RD%edLC_#-5KJPa1=jMH66Go}n=#P_@?BOGjNjMxoK7HkWm!4=Uk z4Vz@}yvL>C`d!3IOo4_Wtb+mdx7HM=Kq}b)6}9E?EK@3;J{|bZI~)pkoGe{b$_|+f zXNblxH_(35t}Hl7XyX$B`2bRFUBw*M@q76FrmRyx^MZ8`FT7@+P*oVH=Gj8R#+QIB zM5^k+3?p@>gJ@>pa^Tq#IPQwl{KJ*R{osmj$2$X_w*y2W0?KyKopYeFBsR~$HDXG3 z2_YptVfDoJt9rL=#B)`+TJnJwd^|v*ghdPjP%Nq`QyxiemmgRF=5)N17HF|X_@p!$ zpAo(<&BWgeH%n(kc1w?~8fpD))e)1zNlZWg5{kLR)Vsk%GVa`;B@ToNirxk>Fi?Jm zUuhy`jtS3lvuxjk{tt+$l*!>HdLP)QhGn4KLE44A!ZWF4>O_wBr(w3ocoSQtZMgX;*YeuD~^+ygVa(TNzLo2w@AsX836MmZ~%HHMkFD z`J6Rnrj$qt&!8kc3uO<(Ga2fx*3gnLPR-#00d()63$LNMkiKXMhlB4y7|L)v7bV~# zRc9Cn@3K*r&|MyrMwQ@cG^c78ObQ1ySw&0Of^s}g!GxTEF?bqw3Af7cvW<}KxvHit zwH>z7N3^&W3>_bLQH{iUbic&-K-*9pI$Ot^Izs1!-W>+Ig&cc3z=8F8E0BV^dn9JY zansFH=F-8Fjb(1vQ6);N2bU}o5D-ifE85X6umgj#1&Opo|Iu#Mt1XNTESnc3Yl{Gy z3BvXxQL*)yJ6*{-Z~-Og`FSwYc*u`K5&LBj7gC6Qcem)n6RhU)I(j&eucvy_%I z$K2V31Kryel3jI14IW`pU6fBTwOq8bluv$#qVJeHSDERs z9djF${mya`vs5$S?*JtbFit!7yGubdtUVLz)`XT1p+(ERFM3HcY?plEG515t;WnfA zq8;az582DVZ9}>pedQv>mWvE~&Q&h5?7!e&#h!K@y@_ncP91YUqs#@c)+@8%|50U{ zGh@ikr+VvcQu&aE|J-%VouyPcNe4>-p_D`4f9dJJf(7csE&_21_kgKftY<%ga+8#2 zg5`|jx-HOo?H+jdm@*9BA)C4jK;>^Y4K1VE-H^)%bM0&X$VIi#G346$Z7vvpjgsoh z03gO*qT0=_{qBcg?Dc1lxvOD9KB)^8FVYJ@0y|T8mV3vtSYi$k9I;(Z907PP7t=Kj zIH^D$7z0NX+?zigb3d%K4gKj*CvE45*6MTjz!-IpmULNdCP+Ky{f7!pf-Z%Ju3 z5OhK)oMm#TMM`OMszJ{X4txLt)s-eRS`1f~0K$+mri;1q%6-qPD9fuYO4yaz-++3P=F3gP;xcOqD z(px`>vT5P3wyx~{fps!HE+DWYSoI&aK9dw(a@cgF>sA7qpcX@viOvEprVqbSp7MDc z-uayiH!n~5w+l@??^25@rMe3jxLgDejL=ZVG~*dMIPq=)K2o^B=0*%Kx*P>A>zQ&lIR&S;lMyBjhi-@1k=o}@7#!%HIeE$ zT?YNBWsfGkSjz0u@oDGiHv(q55l=g6I@6`(2xtn&h9sGD5_E$JXm8=>u_w4f21=y2ufuewIw z2Tvdf5(Ly82tbo64VRah(nV%mFRJL5Neng6WIcc91!@XtDnm&-jb-o)2>yFn~0rvFxYI zxQPHgzx2hfi2Vlb{E|>N4z2HslA@Cc#b_-1dvKDl6HocdMF60nR<|o#>vZ9~1MW~; z*tcyC*I5ov90!C3w$_Z7C5?g1Q>?Rvll8IgKoN8sguJZObLunGUj`I(VHf!MaVKCZ zin@?Kwj`wlRy6xXDR$mj(s-GGnE3GY(3Eo%EbuE9k{oDdxG9|O)1;1#Q}aYdQfa4GONF8_y+m>A}?*c6mq= zcOk9_e8qHJHpl{YDJ1I{cLF@f>ba2fhWrDia$u6!uJ=o?oiu*63*WPIz(-HzN752O9 z$Zy6l_irjM^{*0XqqO^Un3VR`0y7dRFtB0&>58)-Aj>KRYttLJxdR3)j)JhTjxn?_AFo&dyKF-3$81 zy)E;uslsT{9{?!n?Hp?8O$6Dp*$hr=uU?qXE#**S1@N~26toNC?)omUncKl#cE#TA z4SHIw`ArV6{e3lojp;>RdZgtyF6^NaJcFHf80hXb=N_<|9U4S-p=NTc*|+&NN< z2vk<#zJ+sdDO1SBqmaE|@u}$b)m^z`xJGjbHGPvTmprBxYUXuf) zM`**K>NKw!Yz=s>Ndk3GPUw)-2XbM+BT7QiJ<}H#f#)A7rG}M0;4-bsZ*2*}NA+N> z-*X1u!bmf*6Ny>JaWH=Icug4*)@BF&K9KkgxKk+SFkDt`lsKvkaekpt^dPZ9_~9Pn zNpk(3c!m~z0U`9>{FycFA+u%RiKMHgvPhGYefnCQEprk-(#|V2AP>EEoG9QrfuUBl zN6prQM3LekF6^=y!rS+be|Wq^i@$)0V0(ZTe}m8l!X_i8gV08V6h{2{XwVvoC~(82 z*pK0=M0h3AtJ-6@`I26xZ6*JBnu+`uFyQJWwcM@J`STHQ{oWcNB)^4Iwtgp}n!`lPbH{fQJNFGPxduZs z4@(nUiGCbqBQbk3(tt;HK-M4wHsc0J=#0oovS#fJRrZxL_n>h_8etKUF^JLDfzCcYKx*44`l5@`K3jeZ z{+}x!g#V4@qAMvKv<*{eu`a-96%C4g0S^_($sKb3>LN`KfxL*sFYB0QTBK0P#q7x2anz#182Ytu*Z~ghG|A=;LAX7w}I0xBLG^B z7|xNz4$!GLCDumQ6yJ!VDXn53n)r#71OoR7KL_e+3?QWiPQt>b#liqK7{z<)n8MSp zd;n^(TX8O1-=E8*3C22`{v*EOF1#n$X7`#>mA~Vi=*2rY`w#^roFNw7&_9jELgyQZS z-`IhD52Koo1A9-XzUWjmQ^EWzkdMTpcB)woJw0yoFXj{tL|yUAsM7U+Hq{wyYR~^? zQzwE=3D8uN!YICKXS30bm+Yk3*Z$LL$0!+?k+xkX3vEBtc*X&9?f+vL+CB;vu+wXT z1;AY=<57p=qZkb>X82_sqm?(vVYR+Cn#qw>yNi?tGs2?FE1|i^q4a{@ui8>_=bjFLhI?Fl1(rB9LyeRE%Atg%t!@?GGVD-8%I#%K0 z=%UhDL$4l$l^RV}>exD6GJ4_HvAsBFRBTB8os{2m6&#xwP?4O6 zHIW2s<_yH^Va7HS# zSLsD?{(O9w5dFZkcm)W#+||%0WHgfODnSRp9JNDTJ5vL>pJ73{sr(yU&NFqH!-bpUXUu$FKTSd8qd zY2N}WcQONNP?loxLqB0sm?yFx)duh4*&yOO^HFB0nb<&kRt)YfU-yRf=mg%cv+ zDH7cLL~Ix0S7qjcvo3MaZKe5UKInG<%gzo<8oDn-`mj2*rh-3F|Gk~&6IZE)<*SPE z!@_&3^tQJ@gM6)>2e0hU0@sM^6vKhv4@dw?*=ec4 zklm{1vMRsP8ezbVw>?_Nmco-f(iUu2@onHut}Zz;oUhqGK!;v>85a-%x4BKQfvFhj zb+5eK7S$%0qMWg|_MiRrWjNNl zao&TgbK59M)}7FX3x3|#+(tSPf~}qcZ@}b|DRpbaMA-osN@v^+A?IPoyBg_~A%yOKO7^{JY z+Aq??-+bGczxg)erLH|9>AGKSd;cY+_ob1jw%w(P&K0(o-hU|skhBwggx_C{V1vzn zw4p36h_1aOM3wR)bbJvUv)=;lh`6qg`R#*B$<%lD!|aYNd;Z$-uy-|4s~XBs z##@dbTs7eLPB19cJQlCOx7tQMyM4mUbxF46T{WG>t=+3lFKu~gjObtoOlTKT)oP!>hsm@m6SR<;@xIW`8YHpn=)M30u zLmUY)hFEkid6;Y)xV9|5ZC@ZQNsY9=QNPpPyg^W{1)~J+fiJzFJ3>jtF~K8>zGr;qvMtX2kPM zK+rwbP?+g0=2520(f35ab6)_EWWX~3L56>WJWK@bt^7F7&S@XA@J8*MRvxy~l@Z~W z$8zwqLgeFfsQn{?_3;eq&m+Q%k58bs4-0LN=ci0vh1i|27PXHdb}G=HSdQfqxK$hi zn`VJmpq`k74+?ot)Y(4u{w*klt@0lxHbYs9i&P^AfRfuKG2QbvytZL>KhAM(aDacs zE{Sg7`tgK@+Q?dCf5@aW()ziPqLop4U-8?V3qZI1%8-194A`b0>_m-2e{Y`t(CiL3 zrJUgCaMQ{h_{X4C`pllgBe8K93CcCawid7%x`@?%OD4Q681}djSW{oIFZaIUHp0#^ z27Ytd;mtOCHs2^M)Fgm(^FJ<}xzPzv2Ao~%JR`knc(arO;`V0gS|`d`<0SQd8ijln zNu>sm=C7{0%<5nbl)e0a*HD(;1639{v-zYN;M{YBzBLK9H%raVMbeVV3Qacf+(#uw z(`0Xyv zEc+|eNV?sl+8H6z5hS->TGWTK_c^fUI^>7n&SxPeHM8GzP@11$N;HUv{|C@R!5d73 zGQ8T7rXy0l4A}2cPZ3<-Sf{ZqhI?#99dIE|rf8jM{X;QV9e zz9({%xNL;5PytVfGw_mNy}673QpuvrQl2LH_`^ z%^<(i3y!kL>sd9L0Z*q#Wnlg!rEA*5IVK|;^o2-_)zZnSD0WT;43Yr@=KD$U+!hn% zrl^=+Bck<`p}MBKO;aQ9qxFo&QWK(QYj)IpQ&ZC!GUpdp$ef=c^tpap1{y*MCsBHd zdh8i>eyD!`QX4~U%*PSW>U3Kb6gDS7gT!wQaX z{h-zkP9hy6Wl}n->A-jHseQ{NJ68nYzcaE%9FIc#?t`2WZ~^lCDfym;&m`EQ+iLNh zij!7;#8U_71#y<}dX&cwp_&QR{F%ju64hNu)Og3cRbVb4Z$>VJc>X z(GB-eF0XL!Gn=tnIQz`&GQw}Ggr}ZO#b)8p&)yIBDhHp{!kxj`jnCm$LD)Dobe~t= z$hVGo_6-ZCH=2^4A9lek%NTN@G?w`p2sgt$-!cvqW=Q;#Q1F}&8ZUCdIjrPBX0oGfn{j&bl@CkSf}<8=ejpX zRjq5paM_@XngmWM4FwlwLoa(kVbXFq#GM2DJZVpsLZ8#X@_!+4(REf*=MA(bS?6-! zO6p>`NDgBddDPS6h1;|=xybymwR(mA!M#$6{mZLzeYk!r_&&VTiqZ+i8grrkR*EUU z=$f6z_~g3{g+If*urhKog~7>mCpX{{+qVVp5GHeY7r65Kn3SkqdOv=H_?F%wyi=EG z`vv@-Wq^_*xP1}ubU+D^DFM{gAmNc3OOH5rQg|sH4CicpVnJbpHASaLI0d>U0_XlT5>Jm1OG-{Ezstt!i6nnSkl_9 zHatamZ|fA0L;tn4Iy@A_cnzmtIqd213*5Gh@i+Yc-Q{CfS|rcIBjn<+(6lWETZKd0 zCTeGbBRr$i0E_W5=qF#6u;FEi(qLiO^Aq4*^2`)G+X}EKWIsQJIxr$U`24-bL0F5| z+um)ZY~kQ{m9O%7-u9DwwS)o92V}f3{GJU=CUD7%2-uQm#%CmVjYy%I&b@GlP_RFr zB*eT>Xro6`D{$cx)(HM9DcqjYkpat5=FjOfKr=|clV7UFJ&}A~#~xG6`A9yqGqfa$#hH1pm7gLhi5J7pDQCC&7H zY#qB>7xc&~t}B9jjy3HOpeDAoHu32knt-P_S@nE$YcrUG(S@2$0@C?WJ=|Sv;_LX( zk|wK}=d9geBprYQMquh^VooTo&!iZy@L0VXUlq31=h^)5DU!go=@#%pH_O4vWha+J zxcd74TYyr4iE7xh-&$Dd6|4B(|6W$61LnAZp&} z=P(ynNqDPsa7fFw!=95qBY@xr32vDR=~FZJtc(H|E+5=$t8ayOR+Rg-W1+MRK&S=~ zx?OUZ=3&p@e3xN&hsw!qNm_m_xY}o#l*kCd_E9|?w%;|)Am_ov5u)uN?pbW5Qo~x< ziUjz+!4j+F=^KV?XgVeMS&~!2yyz}HH?-45pg#DuIzaHT1+5>~2O*Cn0@ zN1U3@Vb48*n=Z-{3PVu?<4GND0R<#EQ0stVDmksKgWS}Vs(ha0Pop|~KrYpN)NKc~ z{h+ozVt)_(n0%fGeD_K0$M=+mpJ7hI6)})-;BtU86JnodJx~g0%i3& z)A`nQ);~arCZHIOyJm97T_(`dVQ>~TTTi-3%Rj?qUJ^eFH(*i5tf7YwP2={vl`Q4) z#0927RVjte~?Hw!gF(mk5_$${m;MSAZ9&3eFOrXN!>havV++ro3#? zT=43GMk{38*b&=@(yzI^z_3Uz!ixAjKYE3CU!G6F9pa&v=YkYg`pPHx31RS+(ya7X z5qtBMG54|)U^6-au+bLUN?W#Ak)AxEu7{vZ*h1mKS09V4h7VQvJQIOHs#@_IKF?I) z;;YYr-tPW}OhxTcw%z9`7G7@9Caye+bjBO8kw{#ARBV5N-_}B0-p2E2@&e)8hRHZf z7;c!i2t+68qHD$~lZ%A)UG5l5bGSA2p$ z0w1!~=+A!7y>Qscd&%;}jl^erjK}kNevpK}?7TO#2>4&NT?QYh0WCFnhxd5LHrwc@ zs0(i)N)K|^(dU^ir0<#LDh|CR+U>;;MGy8sImZW)&eDxuu=5=Sn{Y_Y#+isQ=8ws|+-FtvUGnzJ-7 z5_cM3HyZnK_-uDp>e{~g^^I%_tH*QDZ-vlU>HP`ulB7ku>03hKBhkgDLZFqz)sQ~V> z6|=tZ!5t>W*$wJ&0E9Y8j6PTGTe)u&_O!M7{9=Sp6$t>Bus$TcTdKGX1atKXy&r(IxO1@73+;O$8uict(+AAN@dBX>j z%o=aF2Ycm%RsAt{YrWy_RPzi1!f>j0D}WGBKqwCJvECO;ZIoAj13^*t>2JzkK9ySZ-Idf8n1 z>&c@7RKzOa2XN6v7t5V=S-F>8bzFz*VeToHfva?V?54t}l|;M9x=Dk>o$Pr9Xi8P> zCJj5=>$&a&id1dZ=&fFl%U7cDdVYbAe9)D8xV-_KVV525-jh$Bf!0-nL|Yr2Zp2>G z%P%q`@g4Xi-~YgOOThhIYzJ*WF{zQ$@dtR{K8&D36a0_mZwJTiaB__}_*u6Eem>j> z4uMYtk`KAD6*~A*o^D7L{AAgGKkY_M0njvV3A>r+y&rF&7Z&nxa!oIyFL48{S^TB_XZIeSc)-k3st zdrVl;n4)g?+2I8KyiE=_hglHdTaU@0%zmHH(5QK&5bo$8gVYWei0?KBzw4H7$%n7k z(Kl_;^vz8RnkfO+#Jk=}Q01-Qe-nIeyVAhUgtQB!bVIyZW{HRKehwDQqE6yz;&ZKs0n8QZnqsN1B%!e>E53=} zYzjRCAC!#RY?7aqRqo{LOfP}uQYG{@>EY%?peY^yQ%G-4o%%UQgiKI2{0rQ%ae&6A zsB?`N#dtw>gj8Lj=Om+E*Glb+<R3Y|J)SE#)*aAr>taxWU)(N%m9G!mw zZp}~#ArjNKV>w3Xb9h$3Gl^Mv?u0n>c76yvlk#D=pTlp*H!)oCWz1z;&KY&OvM>i6KCXNCxj0PX_Sd{V2S1 zPD1P{h|d}h|NFgs%n&2d8{o^qapl3W z{P>6dp8-3MlY5tlyH@5iaBR&3>MR7h2}sWe4x9G_u_X|D1F*l=?h0|y9$WEMkd)na|sVut^3fK@ezZ#@G?cO682GLW4=*>`C) z>w~xd>lr6+T&g;`U?I!oYfFVVa)3ivKqFKpCoUA7%(_gS>CckMddrj;B_;7v- diff --git a/boards/matek/h743-slim/extras/matek_h743-slim_bootloader.bin b/boards/matek/h743-slim/extras/matek_h743-slim_bootloader.bin index 2a5c57d308b2bfdb05ecdbc317bf51dc4bee40a1..276cc5c99a30da2de309b3c54cb516361718ed54 100755 GIT binary patch delta 22405 zcmagG3wTpS`Zzpu&Pj683r#OTdZ9f@T4w~p;m0jlz;#HEdcJoM z-`I1~@u=mDq)yfLRxi?uQItt!p;2|}87T?kIv1HlBYY?Q=eyUjXy_Zth}Dpvq?7!1 z?!O|q)LCUGrS#O9@NWqH=ciJADCeYPOs#;pEGU3dP2%2}C&4G-EjZ9d{Aln^&?S_* z6_J>TbdxBDCL+?Io9U)rqY0V|g|{$)w!0uFlm0q{&e)~i)C%!Xfk~twdvB@>8ZiL~ zzYH~|PTvZda>}%tXzLkC1zlA@-)YFHN*xWAs8T60pHgS~TxX=&FmmHeQ!j$f&4$iZ zlJDj4z5FDE&q&h=WK5=B2c%EG^R2Z*M9xqI6c8bUNHUNDp$cQ5f|&oR5c1xxOf*8i z>8aGA>S8isb@bG}oP)RyPtI_o7G$I$RgIbDh{M{m zP|9oHF=-Y^NR2g`MO7$8YdIxl<&n$;CrI8?l9fT?8Y$@Q8aykt z=b1%RWe(NT4*7n8^k2X~3;tQ~J0aaM%PhVNwROVx9}xcs_}9R{mN)UNBtiz#ln9ZR zA@VZ#z2NueshWpIf*feZU;Z5ILMVuu!|!rxUPyg`y1bJ0I(=x>5EO zCyZ|e6^iL}8@{M6CO~8vl=^2+^g5(-X#VU`tzZ6G4b->3M^&pxDRn_%Qs_(Yk%qCv zJI*w$hvcC5Lzn?!r+jbGoux;XC(^=%!NQEohDn8qjLW{0N(OaTW7xC^UT+I;O5!uD zcncEyqzoJ0jzovBNul9}7I+>kYJ$vpP){w?Qw_LSn@!3KKPisb*+!C$E3FWNhWR#H zjH2fy(Vl$W!rVGkATi;aOaT|kp)Q5#9#tVa#>2W81xphgH)NUJIh=Mt<){M3)M!%Armi68r+7VT*%X^Kv?o6TaU`6~#EV|8Tsi#}tU9lxSZ z*i%?^8FfYg46iE@+YBzY(V@eiEa4eG=&cZDC}V|tlyP`6ghoXSjW8?wjFdh_IH4J# zJfOiPNX+w{72Z~k#Nr{A`J%}e>W(UN2u**1}2np{JmCMJQv8d;E!#5?tMvCN~f>J zqSAliD#EmQ!N=%wt+_U=FS=l`IS?)0^krJq5W`rxlHGP_IM}!CAtbVaxEl!q>x6@Xx~U!!n}w zO6k1(P<1oM|87I#Gs38-N9=F;nB==VAYP>9NNk6%h>n-)XY!NybeOt#;adi&NPG@L zvF9JCC*co$n$8@4MkvQO5|e!6{Jy0~?{SU~#f-p5MM$q(XoilzUr-D_+dQWxfZ&g46J%4C5?GbBOM) z8Ft)*qQ<%YM?%J6!|&D~phl7(*WGG(TQYESd72x&l7fTi(UqsJ$|hafq!X*`bgY^2 z6jGPg1Bn2A-5@0$!eWUp=>2YRB;YA6ehj#%dnV|04p#Cs8OUpR0ycc=j&+uYNoEEM6v5ec?0ZTRjmW09mqZa^S{B=3W> z6D%Rvl4l{1K^bu^8~Gi)f=8*t`BGl3tv1kNO`wE-Nvbu{;>rM@H0^j6PvzzF^6m{7 zi_b`MzM^Xbi_#07sGAMj>tWf$JTs+LLc2#l7e%N-ub!b$^n^-+Z0+J@(>7+$t02@{>l^4Ea8gUxu6&871%S1W4>b6Ks#THaL5rPX{tuG2GYfI!hx7k8NUoN{1#Zn zhXb-?<~(4QcychEuWn{MspyDRE`IBWl4-QqBJ{*ejr<6{Xz@6~Kyj-uH8zDUIrazC z39ISRSd+dqNOqk3?eQcmf)SWD>aVf<1KPNf*)lIdJBa!u?09+7#^1~ZrH%% zj}sK{?Z0ehjP$nDrl2=&fa7I{49)ajBvwo2B+RRvcniIk7N-hN#OZLK@Os?j$d`gl zC&#DSJZ?(dB%F)Opvr?nQi>t|Z_sdl7)pf=I5odf#^Y2Cz=sk$g=xb_P00^VZ(=;N zWh5pinBN44RL-fZ(WJZLr~Pm$i~IUTcYY&4$)gJ8N(rVnsq@IN5`>S2Yw&x*_rtS? zZwgxL^)`;b^vF`1?op)Mvlxl@3E?AVC|d@(rr9NwcwBg7gdV>jygovgD-6B}O9!R5 zxl|k_w)dm-Jx;8nSN!Y_dcO{2tl9!W^4FsD)JnH4l{^ z4copjWn?yfM_4*?8r7s0j*ZO1PQg8L%DDOgTt{1}x~dI|(6XA&%eGRYb3nF}RC~?& z>n7ROf?o90uj>n7DDMli)Uzr!49My_Zc_`b0|sblcwm>CoH;U!sxb-X>U)9$VvMi( z50x?KJ$;NI5!*;vFqa6a(|tqV4jX5n#0a5JJr1uF(&DG$lfonM8Bx0jt~a~@1Lt^x z4J(DW;}h|RLQ}jZcJ%NqBD5d_SWD zqJ^*8fW!j-P*?Js6~NeB_Iri#S@AT?wlE_x8#97E@d^Bpa6NH+N~T}Nm((MVRgv{{ zI8@ZaM0v+Sz+!Hg(*oR!}kO}fNvvwhY1UkM(Vcy``hPZ_(~{klu={Y`^K!` zcvT*$p+?w|G-=Y}0HFlQ>7)kiBwN&QetKC-x`GGt`Oq-FLt=L^=az}X(apke*8T{6b zv_m=nXW+W~Y!gtB>w(w`M*`9U6}fKtXPcle>wt>n09!`{P#wb$A;a`~Qj-EU_iq0q z))lrr*2A_-)_2|0VZ8VG;z}95wVu=lwU{;zRkIPQL7wRp$H(RUd==>^@qheiXISYr z6RzuZ4OL5uAOQ;14wb2e5X*llOii9#cvm3Rb`zFeBoJlB`ay4RFm*{>y>87u6YU!G z4#2LG-<)dea|f@*0A?oI%=OXG>D~U$CRGW+O-iggCU8|FV@fVJP~v7k0W&OH=rAm# z~9Izv7mIKLgg&Z*X9h!1Vw09%BClm#_!1bA|mcS$&{ok)GTNeI*Jg6RH$@TqPh>_ETk#wa=KS#3N&=she9 zPaTKrgrZa(H9qa|W2q4o?AfbFKSBLd61qn7m1m^RN7A8t7YG00-XPtt>W1@eINI-4 zHJ)0!O|qgv?|unsNhq2plRN0mIiBD6^-_6hCjUk#Jrgzvb<jawvjYutSmUF9R2=jxe}XZO+3LVV`t@*xQo}q1r1Imv*8Aew<*1g3?_-XGX z(+N0>)4GPqE;sb8Bx@{5V=-&%t-0z#u{ndk>Zbd)t^k50SD_b@^t}Cy#ImhDk%X;* zcIh<>dkScJC1G=J^RwI#KkI<12tUh~I3*^(pk60ZbSs30SXq+a3^9FV{7?^JkQN*R zT86`7l^-ynUJXaZfVT^_2~~6OT6H7T{vvS8!as*c71C?Y%cI-E%g;(|eupBW?X1L9 z%D5ts6{Lw+b_!a-qE7<9@>WCWl;*0NNh{TjmbEe`Ju&I+H6O{Hvu!Y^YJU`cq# z8Zki2;ARS%GGFEYVB8m*X}(+3%vc0q<*HkoJv{G%|`Dl9kCVs)f-@HvU(RwO>FT z!hn9%h~I*`C5cV>%|Y+aL7zK=Cwu?T1A-wdYeaRUc`d{LOMXuqz4qSH`FMWiC?>B> z5Nk&Wm&d6}a?9wob1~Izj#b+nivG4umDd{xls8T1);e&|D+IZ<`ckX~Jj`Eblk=$#!T)AI#E z0zhV#AT)r9EC|*De`2F-ZA!%xxO*-wBJQM8s>D-&tiVvMu*%w=6MFbK9%$j{EKpnegXaq8dQGbGN44N2BMw~DlP zyG<34hgL(-dpO8wtJW;)QN&iQ9HNj;oIu)Wn1UNEQsb~C3P7KSo5I%`gx9kt&ENM$ z)!G9I%X(gnMcGw<4ZCoucArV{i`td@Y=?qwt6FOojdaytHEZK7W%zVuchc5|hVDI4 zVdqDbVclsdkKJUXVKL|Bf9oE_ce`^pX7b~K0F5sUdgln5vAPla+pE^jlYe~nv)d3- zhk7fF9XHSZNYKFd0Ihj&pbPfeC6*qX0X$y zuBUApzQeY?cu<#hUv>pb16nz(LQGO#TB&ikl#o%yo5+bD?|)Z#-#LcEr_Mk zVcCGJ6s2o>2N%JzNjGYBFY9`%t8^km>()^^-SVJ!V!sgs!7QI;5K?lsQRt*d%IRn5h;<2^1n2=O&Zb4HjHTa!V?iSx;^S9%T`KRB5LW&MeM;m zpl!e@CJgx>fPeM2^MD^U5wWj8KH?%FAGd~AFl|&Ooc8{KEjFg zXI&`cw5zoT#kTes(e7uAU1nr`W_TwS?X+C~b^FQglXR5OovX8xF`pc$cmL&?kDj^Z zCY}4J4P}1dBK1-FkuEgO-dlAL${~6B)LRc9Z0&AE!{ilR4piP^H30mpIan}bLp1V% zfmhr}Z|}7n#89f_Ak8o8VPbVFMfd16)e3vx>VqiL-n;7HP~9<5_moMlp{ggf|KBVA zY4Egr{&75xcJZQ0K6>SkZfcy)^RP?UukQ|e8<)N<{*->!gWV7cFYXWt8m!Jro$Aa=zIhb~Ho8akvn zV~3>XK)aC(2)aUNj5F%Qt5v$*PMxmz`4t3tf0W{YciZPkqodj&ug%^8+j+8aVuVrL z?|_K>pk{knVg%@P#J3%f(lKpsf>uKfRAN&4aN{Qpcq_^@idi)f2RXNt)iscuF*PVF z=KQ8Itl2z`>|W{oo!x7|8y5J(#?@1{nM=azGx#mV8d+G|`qJ-0J6hrr+FrjMq^$Om z0q-sUZ}Pcq&sj!2CKIESO&)pF%wJ@^VoXCH8i&L;Ya05D;O_$8F|Nq=NQS3Y!!(Mt3OYKk#+bd2S9nID zy)6}@F+9a@-{irs2chu~y2D}ZU-rKVYo5~P^N;ncqhEyZ>d=w0dL`cRk@T<%j+ucZ z9UV~ClI?RDcSqMej3vy9ZB7TKt9=hD!)IX&efTigQ!tWFzB{VS{R zV8!Pym3szn*TIJUu|z86O39da!>T0B!1>|--aUl>PFE6#0%4-88-<;R4u$o-^;}NV zPDy4Uoq8Gk7B^YVNRwWOw*_y{IdM_?t_B2<%8Sye-FrP&8Ln$rJkhqatfH$l@wBAMhx6BlwezL0YRa#? znPZ~1s$1Z=pi_(^0mEq_-$~Ui@Nc}Cq#4~s%OA4f05t;?BsQ$Gj<-l*0AG}OUkJj} z_4ddRaOMTxfF1GavaF{lX5Sj1ht&X)Vas}G8jIDqplet(P{!)a zmHSrSt)SXi9jQJ5>`noUI_Mo2P=#Xh<-^+OI!hB(N8(AR@{UhR9sH{5{qY)7M%XwcU$U4ylRVp_WL zjVnvnP+G~ohq3paIS^h3TiqmGZxBv+1x;un*zP8gr42{$imyr_aK;7%z$|lb>#Q@@ zW556JV?Mtzyu8z@;b~x%w-?KRD?qwS)^y+vpXU0#_XKfBZStyMxjO@o5uUy~dz3T? z*aJg+SYr9BR>IBz<=;ZkqPkHpwA{_vHCjN`0_kZkg3nmq?>#;EG^gRU{D619Z3el7U5;O_;0FZkbq|6O=Rufqyd4$wYv;PSvF zfm5f0N)yzY?b6aU_Qf#kOIH%I_fF5qs9!6S8c$0R`8pA;03=-T6@N3o_j+(cDaF$~P;(I`$(o3HlXX!0)k^AV zq>TtraY?xkFOGkNv3pj@;5auHiYn&u>az_vXT9{Gaj|G;6q)O#6652mmi1sr*&~%z zUveQ`(imgf`G!_0bz!Syh)yy%Bu?XyA~cEs9fNbXN>d6HdQxH?gmy{8X8hqo+N#p0 zf#o>@6drw^Fw#M9Udw`Vhi<{NJy!cA8$pCiRvKpTTEA`y(&G+1#p}{72@xR+@3+h; z*Dg5?``!@mgwp!G?frX}#u2(LcTW`(Kaq5{9L_AZ(mLxU;NQ_KfSCCbC=%ZWo)0|? zI^}#a5jwys_|7NaW|1aZ=X|66Ce~Fg0-l!Mv#2x|Sj6$4-xXQ6*r=+~fQ*eA`gBm-jQf=dMQTh=$4PZ0k%n}!2mQ)X#C3TWu z5?yJa>kM+KrAd%Wcz8;JeWWF>WamPHYV)jfmn4*FM0*O%#1Yi77j1l zxv)mN(>mz=br86D-_slcX1{ksGtnT2?`Kg2xUf%^NcBEq36A%I9O5A$_6SB1UbB<1 z3&g=5*$FPJ{}60^5qh-l5YiUiT(}TzMRn^<_zdB1@m5^7$wZ$+bvPFZH{GD~&&7gJ zc5kLR3+g94g-i)@!XA3$aFLZ6#nX<*EVHCBRx}ogKf#`B)FCm7Jsdh{>m7$f2kk-d z9dMi;5I(;*4ZkH^xc8y(C!GwC77#ymsZca^mcs08>@zMi3GYtLu#ap1K$hJ`n{mbp zYpnBq49>P@ykTnz?RT z^8oP8bKHnq>qffmZmfILO{IP1rqf#8I-sNe9+FNGEfX18YeUeR2(l7NULh14v*Srz z7>{|ngeZ1rN)+f-S=dF&g;$K@z`Ul}_>8)`akg5`SMR@qoEkic}I z#N0y)rh=qJYEA?G(7dXNSIa>k0XV@6pg}Xg%^r4@VCOjqRG);NRLCO zZY()sQozB4#4|#mC^5wiI+V!sZ%91w8Wa#IJe>C54>GpJCX(kfVFEwZ{tZY5k+@RI z;PFnPOnTHO1NjINUk0775&+9K4tQS#fRc@eg^g$P3AQ=E5o4 zNWlAf|0R%bGSEIP?g*lEe}}4>7CT!2CK|F`U@dFFHD+tj+c5Z_9*u<_RYNI8{F@}> zFM)t51~@-fZh%_;8l;mI=Y!rP;gw zx1_o_r4iP{$Dn})@a%7)wiBZFA&ChPCOd4J-eztJD-XLbyyBvilOh78ibBV;-Bk}dD5a- zC(fk=y)C4;pZFucy*TYxLBhLsCXrNXtH%jcBO9hI<_r0$S>^4=Jo>16ow49^QTI5H zd2~@zou7CNbVq|yU(wzvyRU@`u=$0egP{V7yA++rJlRot=P|p-5Y_D}6fr~90WkJa z0_ns*T%UM~fEQfe9_Hb~3VYG)1^$=)alH;Z3x|iCJ?42NYJtDjLnI4$d||Jn@cRa& zUEf(KQcR)9FzxO_k!9N8U&WkuAL&E(rZdMp&qZZI$5uv-f&a&%G_KTM$71{Y4TZhj z;#T)DPi9nBuCY<)As6yIv>uvW`98!v z9;I~ck(IPSHy4vCNsVab-yp>XDb|0dpp_)WvG`?3sg9yrQlZ`V?V-%I?oT|Az<6Ih zcg#}-Q?R!tOuR_X0w(JFnjiVME%PO&t_k46w(Q^u6iWEGmI9z*g5zN=_B;6PzaH~E z8fEWYdoYZL#tWk~N{>PrmBH@K5EbF+Em4}|*QjtLP6)g$rGg=VlERrL=X(nCS$mww zL`48lk+MSMl(Aw&l-Ws|ifdtXwC=bm;=D%jQ8%qno;?cYQ5=ws+l!BSFe|z4Ekt8T zPR6OXl>(`aCvGn$)iW?%PnE?2SM-!6qGb!eo&T_#RVuq#xf(EiNz*+%$});a*WFuq zj;FHfPF<-Gvz1@DD@47r#T`-4P5Qn;ZzIk8?mpRYLE?5{!D_)flT3-im*uhcEN6m; zi5lCnwJ7U6!4)!Issq>UEJ{Bg1|7q7d%9Ux2fQ*ZeAbfL)wM#V!?~oR2vGVc_#>UH z2UD?y$4y6Cf(d9$oT!XSa!uwz>awFG`O60U`nPbb)1F{{2lNWD?e5>?B`rAjiW`P+ z=NVy3F$0!8=)bUxjF3&!`1S=2(%mv51CMm~{R!Fgi`1;8Z*98XKyTe&>gx zaM#;Xnqh*TYnMYP6?iHY;7Elyp2ZXOHp2gGFD`HsU$%97F)1$Fsc;=mA~ndil8S*} z*okxKcTT`a$FrB*vp+y=Ik@TIP-`#<^{dkP@fpc2q<)>KveU0XfD|O4)Z3<9peBO+ zQaRMA?~3#`&H1=qw17-uTuYJW5zY2uGEGd!_)r(m$+O#j@Sw14&CnzpG{-#3sI*^( zz8L6sn8$$MbK{)^qsoeETa=!BituaOS`3=U3hlsb`f6KZq}ZhG#oxL+K?;c{e&Z(1 zQ-FY9y7ijVZan@IPgvOZ4KDYOuu3o+>EV>Hh9zxW3&-j`Mgzu|?26L-s$9wz)87&_rLr1{Ma8`{E) zPOWTqi=&~nq0gNvj$p!cDgF&1Xvsp*q6oC8EGN4kKPFt9KGIGoi%tEfe=h|f#{&eg z6Tn=m(*5GT1lpp~-qzBJUS>sGXcp5n1T%(?GC5;ULf+)o@jvhn!2cX~La(C& zyMUnYq;fkN7Pt#;%Bh4dDr#!)yn{VZ2if+>_NMHX!+{2es=edR=0U)(g&lBcos)`G zEy68**36tD|L+N@Ar-6DGs9Ul%UCUw`u#*fnE- zmD*nX{hc1)v%UD<-wk|J$SfxNs$`DsMb9Sjaz2VrYSF*l3LZt$x^@fXMm{;T`l>qdzCCY1M~He)HPi%P@XyVvg#;%7~=8!UA9H?(jatv1|H zgui<|bM=uM--hxs9St{_)p&vf;uRhldr{g2hJm{d&A6rtXT*TC4Adwad9@g_-<(9&Im$(SuR3#}F}>*q&_N!G~#)j+O9_jQF**j^D&zamNnzBZGVWx@t9d zLjlcx6Y4h8f&6s;p&P~Fj}+p`?4-l6*Qfd_bjm#_AI;+BH0bl>dQgWBGh3}HJg|8)PpwC zCv2OO751R7(@k^|l|JEzId{*W0%mz6mm09W+ihBsQ-3JbKdKFD!1C>AXq*|?g~Wx& zamfGjcy%#hjMj&&F_0KM9=w*{7zN5I{i;}T0BEPL6pA(^+J%SiPr-i*&)=U&VV|(` z{v7)Xpy=_ZC~Ywp^mYK{ujs%NPX`(CSBVin07i=u6M$$ZtOp}@G^s#^PO-rtW)H!o4pk%4g_qBkbey)H z{NuX|$$u`R?{iK}v(_Skey6vv3Wd^x&3Rw&)#j04LS=n!RTx1P75%zofKNF32U z?6KXqQ-M_BrXIbmYCLdN5V3hLo)^5fguq*y$U=b`(S9i+p41 z!7vttkx2Z@Is{NF2r^q3AVh8gOU;NTA5*89oTC4u9ltkI0$EYZ^Oay#0`8f)i2e3~ z|F|9G+YS+T%>x@AaHHmfFa_L2aCUG9!IeIU*a!Ys!T+x0|1TVXhAHTz45k(=$k)+z zgaxOCg`E|>&s7J#_Dh4ZkaEa(nN(0ft1V(&NVl?tC^1VUtAA?!hy{_NgIE~c(b*S!B zHFO;fk}(?S@e?&zS78@XIK=^Q4UG69U_qo*30ROU0pou>6pt7XzroZP_Lwy7K<}lR z$)*GL#Iyj@V!Wp;c2#WCRG9zR>VlgwG^LU6MPm*~YGA$h4vujn5WrOO8GN`0htr}I z{5vc(Mhug%!6?qCVe;%QcMkM!VF(I;tr-rc$VPE_jXoZlRBbY$n~&Fkc*Blv+G;LJ zZylP;e`1PreFr5T4vpubn$#vuNCBN}OR%Pa9Y9*)e$#LlffGxYy9toNlr1LcH4Fll zfJmnGrnv_E9e5{(Rfg?3|8RFmNJUusV;~Tr#pWOo4*D%7qewyj+T8?r>7mBP)S$F+ zys?ukv0B&%$*MR4?kKpQ0IPqBMX7f%9%WB*J(YBqQ~u^FrDe9Snl|&XJj>A{9yXsn z0f&ylxn6w2yuMesdtQ`1ryK}6&`;UjE`Xkv@Y^_NwUNo}XqX}C4C}i_j_GwV6UZ#= zGyT*K6TDacx1hIofDBVbpS?m%haU{ex10pwmu#<004q;0GX$2)L3)1*!bm*nkZq^M zS;0H#(Ke8DJGVXPJs!&55Xycalzl&BU#BpNdmSv`;s*{|-1P6FM?(!8>FrlY^>2jo zZ-X4^|IYDID2Ic7DU@SFD93t-{Np$PL1IwGGaA_z8Q`cekipCC5O|Fg03E@yP=Uvx zz)~ltol-h7O}=-~dvp*A?3KL%ng~(=@;?*Gk5)Wzg>0PnLjGADUpFLYPj4q(Du-{2 zv!d5oO^dF<^&qx84WXX~Gc9#RQ(YOB?WTKN7p3SXnf+ zcgv@M&aniYhmd*dz=_|7mTdBXSid4E(nZi+zL(MrrH>m}%!R0vilFzUX0pl>=|sKK zHJ(Q>=8a%XO^cfcUo>5Eo(AG5Cig!z$JhtJ_DFc`_aWluC%~?1z%D|IJoLQmYXm-= zC6=gil+L!Op`*L}k)@oK7WexjET~>hPPClxX=aVumT9F#E1br%j&v($BLb~KujW{O zb0vt0F9U{dhI%`}UlrQVnR3pCMQu>{?Lkg=7Zjt(0c#*qKBa}Ts%?Xyd&AmDj{*Aht;KItR}zVFfCq#jl@j&8L-Zx zlVdw#rY+(1(DfyLs!qe(cwO&N(0&+bN*MGu4?G4kyL7m0w7_rRS)lZ)q5B^;RrLOv zCz}TREBNhzvn^yaWF%{#Bd>xFBDv5=-V=U(NJDuffq6IwM+kR4JSjdMwq1r#IltI6 z=xy^e1XOwIPS^p3jSp)g=LLRsTWly*4PZDeeE#rVi3s$tAo;^y|8KA8UM=Bc8WJ0Jnvz>qz^E}j$_z%Tg0LtT z#|hsqnxM7AoZNEBKyEZ0%It@mCXb2^~yAy}_Y8$!NfPBZxHlP;+BH(ip(6 z@7DpZJ_JYTLje{?wVV>>Jd%Q&g{R^Fz~MI@kx}+ff_ql!LCFV|qdjol>Am2P0bg}9 z5ws#rf&q({plXti#eabUknwO3Iu{CMLFjCd@gyUxAyf+%e{QL6Tn|$C2bVA&HHcWj zxG<;#LP>rO1gX{J`>7z%Z_P-vXDP>Pgm~MmvF0VQ0DQ_BR`|LJNGqUX*MmHSxe&gJ z*3-@eaCp4O9R~3VaKc-*iFlT9#{=xpjRHG2&Ym5 z_Lzs3BnkgoV#Mo(l*e@8J5GS3y53NKe1srW(Rr|NuW!27ySV4vEOb8mlv4Q05U+%izl2e(Oc40!Se`2QDJ zD@hd_Y>~W!*F0je88vTNZP3&uDF0LzUL*LPnnryvD3mNur?w0V%a@O)-VF#lm**ra zA49BX1!8AC4df62emKv9sCNmEK*MvXU+7vs79SMiSJXV%(EoXeRDNvmFj1+<4!KD& zBEOB|qgOdWryMO>BWBmOORJ`Dsr^UoYS*k)^2stiy7`lX@XquP1(T}E&Hxdc>ZJ90 zCk8^K#gS!0;@o~gz0zcV3UmT)kba9b8MZB}kk}KrCLe|qsj~;a*ZhLVfBqiN0u68jZ&9qB4 zL#4?zX9oZF=N;8(a9&$h6$(zfZ@O(21hYC(xcHi*Y; z`i&~v$c^g4BR(L<5-z=hb6Xnf8U)kc7C-^5=G8YFlnt9qYM1ua7>Jd-AfF0@&Hzs$ zDwz@W1nD35e{M=_pUw~1y*}TN73-ehcka(km(N{!MI}+KIA`I~i49nix5hW%++Sa) zYarEZ3N`YxTfZ^6aBK~94mx_sspF}#?=&T_VAJ|Pc3%f1%ZG*i;1c6aW$q5Jnz`nP z`Neos5en~h)c2X-2IMymV#L406gk#e-&bRw=UgVLWzP!>pB#Q~O#FL~qO@gjQxl19 z$5}97i?tq+78wM`HfgazcuIt;yhuC`UzLz@6>xlmG#Avb`Np7k=@-JGC-0{Z1{wwB zG7WxT&@YQuas8lf&~g0x(mWt_J%hsRWn(GaFKk%m6pW)2ghP+3RPzV#*b+LVhg6`K z$$UJMdNd&1|9JA~`$N`i`oSA;WB8hjXsbg_LS3bS4buGSzk#J^(h0%2)L_>GXBPCL z!8^Adwn_Jg7X1B&KDahU(*76_Vd;}wgyen(To4Jv0@4kcWxot_Ow6*KQnll#BsW;~ z`7Kr*63$AStCt=Ar^Flr`WHdDjgbF^<)4xKFF<~zIU;FWUu}3VdUKS2bAL?3wj#=j z>JFO{+J$?c7-1ip^A!>ixNU?o-!#1~F$QvNcStz$;pX=qo7k}RA=B*lHXregw&I+a zhBr;`ZJ>SuK{UN*10Mg4oAGQ${oXTV3xm6eMjqb{+Zczn`y{#bM@dz^Nn*(TM=oZ` zmSU9tw)1CqL4E5|)8_S?V)a%lt8 zH-E*RMbVa1SBK>>ea2bqrRnQVO66c!JKHpwk0`_9tbRg64Z;->a`z98czAljyJ+B3 z_k)ET7>G;;a%?ZqOT9q8M1ZF3vatKFBkhKM8^}}k4c^WHicr7zKz};qzh{8l*t-n5 zs~aPDCS4CZ9ukw%>D19^__TC5@JIO&$amxU8xP`KS2dNh-87TQ$kd_MGE z(Z5U_fxKDqNO`3G8S%TB-g;jWp;D^3s80H{6^nxD;vD{tM;&VnO!>T^qnR}RQ|u^wfo zbgW<1*nKi8@jMbo3oXy-(lY_9Qu8v92Ht`(hB03FXPI8N*!aRBa%VFOZh9dR4+>$c z(=jFFuFkOgyqiFkjl`=1WL|Q7mqA_y=CMJzfDB}7zxUbxA+nV~1B`+|Jq?_I_{*S- zuL4yvdYFjV6>1mrQk!Samhs?pmOl ziLC1QU|0#g5s%VGfYA>PhI7GOvlVXDK?Own%!1v?Jzog@t3hEaj9POSt`z31d4QVX z7d~CH4qp|i-qgYKZNyyWvzyy1HzMQ*WgB>d+l9e`~C9mw)%c= zj8Dk2o3JP>vnS#wg-v!19uN-LGpPIE9+REN1wx8LL&f_Alf#Ikg!PUw__DCik%(i2 zZynQck1)I@1E&j9YewR&!UHu66BmM5FyQ?TsIBVeT|hG-u@Vplr3Snwgflg(@h+ia zoeu5kk}l-1-$nKX?}V=-hxtP*1fjvF#5g1@9Q-7 zjeH!a`X1_tX(D&N;p*5}^#%Mf5j?h%TehH~+io+$W`Jdc@|)sBI=IX(TTGPu$@_9NTG3+2#G1lUo0cUa-c0y-WZWbw(8>GK@)UL5?F`=63}JbgIHIvwor z)deuIKF$u;+h@Q!@wbWT5$ ztn47to%0*DqR_v7n7tELiVWaHEKJplFkR-2_w`ToNPfwB+5`Oj4JL z6sm3}HzWmTZIZBfW1hVzkWz~Cp0p0LeJw>elAF>2KbH(-bsG3wxQo8SHdBq;;%(!b z-ZRDh5^u|BdOsny^qO1Ehx4Ml)Te2rkLH` z4BlbA?vj-fJTmzATZbMmKtN`RQ)-N%tKN|yxHi}Cw4pS7_fD(M7F%BjycoJbcDI1H zU;ri!Qfq8sg*&ZgTamRDw71=Eq4MQ>@P6Tqmoq58PiTEvjV}u4ULGH3g2z{a*CxR` z0zJhF5T0-4lWZXZSq_(OeBK*AgOQNIc+0MOyjSu*IY7uM$*Ue1Rd2TGt?O+|t@39j zZ{7eQl!2=aEi_=67ZWvbuJb$)Jg`ia$@iTb2{P%{cjA*uMwJorroe;nwE$X3R2Sa@ zCyaS@SqZFw3vfQjH9#tig!c=4-iiKg(t|3bOUc-?IJ!L_Mi@8XsE0T!%KqAU=?T46 z_vBJ*t6L7U>GKZw-LRg+&XlG8(15vP%M|O}k=RqIO}<>ndg1W{s%-!SKW;>l=DGamP_0|X*vDA6o3XLH+k&)W` z1B6JI_V{HUmYL6=sSoQ`pz~L$nAfe*pmT`eez0cR-Zdo@W?J><0tp|h_f5~Vm062z z3K1(No6S~IdV`<*KkGkY+Uoq+!&2h`qrBcZgPVx`MfiTuXDYkt>C{p%ip6xMbt&lp zn6Y4ZbOSnI_|k0-iGmW$ChK`OscN=g6N1z)a7hxSPwllG9M6-AyW<0jQmD3*c8faY}vVyzXz!CYF=Scl(nkwU@DwC zehzZy3!Yc!;ztF`YuRZP0}8OFP{Cml@bIum5^$hT^%SY-7M%CG>68BtCi+X^l6BM}xlYsMz?D zjgV52{0JKwH%AyRjKf*NLSe>(p%(~@KtUay3?{~Zcg~0ZpPcv;i zaJb|;ej;Zh`rbY4$TN+K1Nh@P60;P&G3b354k~#E+{okcc92NlroaN;$&wJZ?f#7S zfj(s$W$;7}h@Zi@`=XyvNnY>$aF4U#1+s$3t{(8t7dCFY3;!y7xh*zvnRG#7Ixk$M zbZ~1J=7JbcAbny75*G=7ZqwiyLi8Jn*eqnfk&*mn(*X|~@x)c;e~_5||0owyOIN>9 zVtkw`m;u)`}!&}j}OTjH<^^@P&Sy} z34ebx#qM)#NLUEXVeTCsWp_Fu-+dR{R8#O@r28n-C~kG^?vB9F;bQ3OARf&{)Cash zia>0%u?rUr3(#V%iG?m>Ostrw)3u-z`q5$LmC#+tDJlZ0=)x{sI4pn$KP)0SL){%u zo&K;0*>4_qu>AYo!x&>1ZG6l9jfYblHfsHf{_-w5g7YhSv0vVkWcCq=l_Ch&2Yg`5 zO}e5Cs6$;~1H+&TlwW=`Jk$-=6TI6Y);ekd6fZdTdMI{b;ZSFMqH?G+1t>6V@KxxH zo%9=km-qPTSBoAyN98XpG)y_?(SiDx9L0nL;n6Vvz!mrAMR$Ug%F4R3a=JA z;xVR}0a{O?(L->BNv7M4WQsL@y61HxHs68S;UOqY4398($<5I8t#?d}pXvoz*a7s= zeEzu8@0hZo`KrRY#Eme^-dl>mh+M#l0(oFq&!*b|2As$rae9*}?i_XR!ou$p_%6if zyT=lfE4Q4#bVbceS1d&zpKj`=*u~uu!*Ko{H_vy0tYjPPR4%uZU+tzQFD%S)8+fIg zAc@`N261N#5u2(SO`Nja@0|n8HoWr2f%R>k-+N!6kn?*jK=zRDQ}6~HP<5e4=imti z4vAm*?k{2 zLL=||k(UgI-uaseH=4=wX)1UZ55YTmduM8URqzcgz`x%G)b=_;G0=4|yC-kOk=M|W z6^Z%qS{b$uHIQ?RoV8z&;XsP|zfxk3fqDEfIC*t;xKa{XT^yCZt)-$Dbk+a|bMi1f zp?H<;8W5V1Qy7V*P#_0vm~XjY^d6|L5Aurpj;~k9T>tsLbexnYE_e;YlM)27NQEBM zS;WQ!8^dcYU-g8`Vr5ytGBh;e4Txva<-Jh{5To?=_WE0*L@=G@Wu%>5LN^)=(vW@8n}h zgG>BwvywrD;BY$TNe&uvkaYbq{J+xS)fq?+cft#9kUlctfP?qT206U`!2(MjdrStg z5w~M0;o{DCJ3vuOKvxZyWooD7O*8ja!=0kqDLIy0c&^WpPxskl>AtnI>L|hL_YV5T zLJfh?zvRQ*El?^UF6)U~-ll;}%UdRs3#F3ShJn#=EN4A(%X?rTtpr}O49NIY@Y#S4 zbc4fOX=0Glg5iWxSXLJ?e{_*~zbU^Zi#GwT9t5F^wdrBldOjH-Rc#!Iv_zL>!6He3 z>edZlO>9ZPn=(LYV!%&?XOIX_dU+t=-8vwF=C3vnkNy%QAIOL*QK#^aI<5UfI9NUh z$G|%um1crBoM<;zE+iA&4k%6~%Pg{zh!$3Z;Vm78inlVFTiyqoNt&t?brK~EF1h8M z1xtr~BQ4f2aFyYfw`_pahO|2ulIsj4jk=w8%D?kcWud|oZbvZbL+4m*I~mU<{cMi}+!1(EA-+HOL1c zN(|!%782M*P#9OjdomwFF2aO@F$0+64|S(O7tbBVr19CUFpe&mg}nT^j@_wlxb!c4dJ^@7GWfKJ5$n%-ujJroVrCDY|jMLOdmBG@;A zT>W)3;e3%!II{cb%%*s-{6Gj1pT6zOF+y*{w*tP24{x@h9pH!EPFKP=$sd0EJL0w< z8S;e_@7;Q=9^ObP%0O%y_)2i4V-WlHXh0xv9&oQg+yMA8h@W!XJ^z2E&A{;%h*fof zYJu1kh#i3#Xexs)P`pu(fukA7uLWXVL*RlJAfMHEv)mFRMi$U4^yYx20*n#?5hhMP zWrli&rg{eHMy7_QriMwzsU{4Q6PBse^Tso92m&$4NDvT(vMUoAI5aaDIHVI8I3$xH z@>f$CIDC^JZ2gqfGX0X0N=Ij3)f9&RZ$fi`ebQ_Oj=($y4sRe`2%MNo1Y&L=mIY#Y zAf64Jq>?Oz=ywNB3;?YYW@v;k7;J%(AO|RCO%_|OW%#}VxV8s~K|=STv}&=wYBA8R zmrV>Dt&I#EhZ`XBr-AI{lM9ze1Bdv}F1KeqFqwCSJ7dP=&=tyzEt4x($nzcnCUSeA PNddqPWZhgJ&+GafcAdH3krQvbrws4KwI~Diz2U%h$YAQ*@0eFM zzZ5#{udL9EO4=f_(0Ld(e7HjA~eENxotLzc4m z3QJjS1$6`E#4j_Kbv_i&o5e%(?D4jEelH$ukLOkJp9iDdj|SVPL2MD_(AX3!6zn&d zgXNgP_B%>L`P~ptg4irlRH!X4n8J{PmLMnFs?){Wj8IP}Dk!r^Q=~2>=2PknpUY5^ zSw_PkO!F=MXg+NxkoTL`!o%8V+c;|+ukG(HDCl?0jk5*QT1aQd*&=zZ2=7J5+(;XS zGN#CaeiVtx`+ie)By^w?P4nVyRDES}JimvYdE@?LxE4=c;6{bi!jg}*NDXl!gfs|I z8V!1qq7@SEwn9Ah0*mcU0=)BTRe*EitoNJmul;|-@8ke;mN-x{~}MOJ^%z-Wvg zA+hXaX#<{e&5bhtbXxiyYvpCpHmvV)qb#>m56=`l|LQh=R9Otbln6)ViHY)3vN|1W z!)!>)SmPW&G;VVgiLr}9P z>|?FvV!$}IRMnKg)3A#cC(@pL{nFezQ~(=vr`hj{wZ@jJXT{mdMObG`wYL3B=i`_% z+GDfOHfsxPW)A@McJ~uq$LVo&l+` ziV$l84?(EX#ioC#rAuJc1DVi98iX(3MC{jp#Tjf9>!dP5o$<{->e$st94p|^gyWjf zG-`npn(v0dHeqq84+E@>gf(mv5|KpyC;I_SB6|{PAl9-R7Nbrv;_jBp;>zObv#@^p z>|Hv>QzAKF{Uem1v{%hDt2P`p#cL zm=?VQj6T5Kou&Ut=W7CwpX-8tH{~(`K(#1b$!{UAZ1Q=bPFCP9A z;k`^3{}|FGTjOmsw2H(wNiIeWCtAZAkeFxpCqP0W8V2KoFE$6Tcz6JdPx)lxFA}2< zDIrx7{jy-yDUv)GACs^+-aqKh<(HsFH)>VGB%FZI4Tzi+j#w3>KZEcsgn9^V5RO2Y z9gSGaHpC7jkjX+R0dKM`AhVYD=RdSei}o=9@i|GuQT1fX2Wkwj|TQuD7JQ6nuL(1j$*9VxSsa^11q~%ELgs1SX=Njg5Q@AvkxDVl32DwPw2&w4K zdmBjl(15l(hnpKL@uS2f{n7csN@Vajvx9GD4qSDI)s=FgWl;8IBt}DtU%SF<3m_MX zZ^2Vnutoa-jLu%)a#?&1wN8pcY}OTTIm1P8-(5laKl>t|Lwbkq&py?b$Nsh%*8Y}0 zRrLi4y$PY}2d+~>bC9M(LMl8dA2w@^c~qB*Z-eDvl=8}C97^L{fyU>c-fA%nP3^{6 z(fr9)oQkIzOmijuZrr;iqS=F#cBAWi37GoN2zmd%`^0JnHU%28iDg_@~6x!k*D%u~|4ax&UVjp3&(s;X{u; zN){v<`pv?a=zS^80dJHrF(wW#5=vwAxKCIWGi}tH0j68SrSKj%CB7px#iZkhg$ps+ z_?QqmCKmgI^f6;+%nQtEW;_dIY0%HCKz=iv3OS!$iPYq`Ao0{79CPB|2Ss;&6AaU% z3YMA@NNZN-5xDY%En~FoM**Cs;5NC01JlN&>g_ih<%TF%`g+Dwf}q=gt--)+xQokI z^7@C7{@^ksE*9Kl=7yXb)-*3Dp~QBfAl8825LU(Nb3Yt@7S=FIYj>$Mlqe3Ow1ZBp zr`LYx4tUS_)7Kw>o&SSh4jUxXY2r(cBk|wDnOMu{dBZwbz0mSV{c!>BYkpxuDA`B>p)btdi+&ZuYLZv-3{6W22&t0iq+b^fwbwino@HNR{rfMI(h$yL zCxvD9xR6Fh_TUy?_$q!ZJ}J24Cy&a9rEhG&I;5qYacVnpJaQ%J99qBy)8 zYt=vzXAA<{te0!CMlMbsM0#8+*HVzq9u%HRcq-v9K1L6`0#~sWiL-qppyanGv`7>M zW#U-;cOfe=3nvLn5?A3B!dHpe%gjC*SJHqyHbv&+X`FgeHlXTz|1q=IWrNAe^)cK+ zk}IRe$KEymaSf-=BPCk=??4F?l+fKOVUnTos=LOo)o`j{i6j3h5$O{i7&`{n36GDR zvUHQ5a9!m5P=}(FtSe%940lgia@w}~vl6OT0IBVg*aOVD)nW_^V(G<#<|*79n2~0Q z;g&a#IgK>e-N?}I3WM|3;|zGO4WYDau1oGI+(Ot|KMSLhCfP3x$+&IJDAVcGaG@R* zhD8ngGT_}G_=g+mMoNA+bj^LW8HoB$hmH{U|0U|q8ej`J67ue#>|DjphOxGx)^#f4jNEi|}&CEa|!$vH%JGfQCO?V)@J*B?yJB& z$gGrI)ihtqQ8578bRW{|pCog6Rrp-9WYk7ryy$vkixTQRA!KP|v)scNXlAKd0dJQ1 zF1h6p+hBkF3QS1}%zqnD=8F&_4kC88utpo3`Wf`XHZkIwK}K8+Vb$O$tD09ghXa3@ zz^`pa8ijaG_)wb+`|Uez?3iL7-VZwm=C&*_ij--Pi*tQ~Ps?FJD9|mU7W#!(bveoF z{4JMR6BdtrMC8*yKmPFFz@?)6rqEfbyj=X3a7{N2#|r8Ci3}zF=o9YK=Tp`J;br|D zRFz%$UVi{ym->XqQtrT?3Gb(j5BX6S$7yWC-fP0Sl!>@q2uambt5S|nNDZfCAxubk zzc6k5Dk^(GI6R(Pm^IM7JPklRKm3z>t8|a57Y?Qvbi}P{`fTMs$%cl#zez|(Qjr{) zvth69bbiz4E9Ipb+)Kgycvy_;=8^QTz=GwsygwcewHMMfLP=WE_yf`jX`V4&E^j{} z%`qm(sdf#=h!09gqiTs3Bb0wSBlOV^T@^k|OO7cGbpI8LIeyJ*EKc;>R zO~JE-g!H+1NLZB~H~H%DTYn`&_9&1rNcqNK`D0LC-OzGb0!+StT517S$3#RfdsA2` z54_oBp(Q;ox??C8j&L^9<6?lbtA@GVCtOK?GBWRYG`9?oF8_Ve1SaOkqjZ$8CL?Pa zTS|LW6xN6Hf=O=)vxzNQPS5=WD+GnHCM5L*5?R*N-LzX$w?*Go-ZLwwx3PhdtRQR|8Hx!iD=}eR1a3IhAu$?lFeOl(>M061^!`@B1`BtaCSA{);EfX7p*MxO>bPZ&zTzoz4-0XdmtuA`|0; zzfOqK5veHd6fi#;ERF@Lu5M7nafHR+hk&NH1g=^!59JH4?}9?>2Od#y_m+8%P3 zOq0hKf{dRcVkXyy#U?5579D}{0Bs=HAfu666=k5X@Yu{}rOQ*Po0oMKk%2iQ7*oMa zs}XAxn`E0b<*RV-B3eWil#%QFqIyA6Uf~J<&3t z6SGMs(z0b3XB}Lma7E3|;)UNPW=zDr4u<+!Y{4ntyHj{; zTsZeYbJ(Vd!u`f6_cpXtZ2B;Mb>FkmD68U$(DN6oKQJqP9^=a0(50Z;D>e~*Q^gb7 zO=@cyKD)3tac^T|??ENo8B>P!Dt@PlhT(kW9?M;G=Wfs7vVlR0D-3x5B6y7YF-JQp zHZ7Ka@Z(8CK-StNSP^A`jC*66_3M(DOpBEa1*G)gpBOP z+|aO*>jR$Y#Xt`b5G4XOt`(u}0R~hh=6>`T(K|&c2HOcn3C8oAESuoykWX!=H|3Qs z!Alm7WpdidBnn3+s0!1|=uL|-)oY1X^A4!Cb0JxLJLhONIWRCjL%@7(!XOxIHtBmP z(7&w~SHaO2@b=zfaS(8m!4(nkz89c2MVE$Z=HdAZ_5BDG1iLNs=L~s`e*LD1GD^Dy zhn4J~^VW@m$B5R#Q4wv^ZK8P!&Qh$~5p15eeQ^shEFgyLUb6dHLIHFtU{fPGn=#-` z7_QjJ=pO1*L|3dE;m^>=sxrt9cpnB3LN%eK1O$uduvq$0Gy&mHpS%odZg)%OkcBxU zhZgC8pvk<6=FZCTj{$F|a4~0w{iVSX)ex+CZ+k!jDow3mI9;=4(?flmX$z^V4S3J_ zD>ki$=ZYtmC~o|y<*49k3#8>^=O~nt2Ymu_Qyk6b&Kgmp2E6o8H?MA>c`et)*Ax%y zv&t_>pE=Mt;LStJ#l(<{>-3L@_~rH+`5Xvd2MD?$ehc3b@J0;DJnL!MjaMI6cs@h= zLXwwS$a*yF;`ND>b>b{)ab>{kA6&UXF+nfRqF1iz1Vs;F`jK{YNxZFG#8HcFVR}%z z*+9iJeV#OWy1sw7!VIxVr{6K6bY*D$W=e0@KL(<@-voP~1)=>lI5@@PfHxa3MzBRj zXN*88YDkZU&<|-cWm#AHiqVa|k2BnAk;CM)J2A+3Y=}JJ-2v~1gZrcz*$+Rny6+5) zYsQE+v6L<@%0+B? z9%5HRTy-nfPeSbSTVWN%J0bj%gIGKHdlCxnlT>YqBBPXn(usDB5gkh8Og^sPNEDj- zb^486iZSi`r1i!$ZZB-E#S38zMlGI0Mnu*a8BxId%JA*-0q-7Q*WZ>NFj7JNf?Q0N z;|bYLYQiWdn(%`QrMq0;_Mzx+6Z=fzZ$3Gz#}d9(8rv4rO^bF~ZaC9%ruPgTDm;^? zw+Fnd2miYd0^WND-*^Az$@iWV-I|Rm0Qhw$%6Qd9I-n+uaiNL!{_0M##&1wxIuQI&IkHe)u$=NV`m;3Tf7T?WQKCxFW@XQtJ{HPSSyN z^z>qPX52q$sxt5;r z=xCe9s@oB5`UsRJ7__#V*XlQKa`!J zJ$y;GaW3Tkag_Aedvv}%*rEIA?ZwtTfYR*!7mw<8r~y*eN&^KP-D>HlKy&YaZrU%6 zP;p>ZO@1*D@IoNEqMfC?tl_|@?kuBw7?fzDdJq^2Kt1J1r6by(vp!cgmXG3NOj+S3 z@qGsfl-jLj3E{|KH;HwQ3R>B|$!fn<i7*4#LqzNm{{Waye~8cWfeLfuqKX^``J78 zb3aLWYtTfKSXTA2H2uv}fOwN=s`^RFT=O(cl1Qrn$owi(mVr}v#-c;5CVjGRiysM# zfF9KQQQhVEfcH!P%dqn)-6KFfpM})Z8{d=c57ZN?{`5N1h{iy<@}a`fp+r6HXKQMp z5FxeI5Z`G{G$XO7D&QRt%*}`{t3!d?ReYpv39HFj>_+1*NNtV_QpW)xul0W_CbyUO zaB+(ywh|O{#$=PENNC6UF=7CfO02O?iZmKrv>m#&8I-Q^K=FPVtb>lCMFuNeK+k=o z$Wj1qC&bMPs-4o4ic=L~?IhmFIS7hPl^sGe-MfVW|= z%Y8wC+D8B$?H&zmoE^9yQ|Ms5M93;R{m98j$m(s9tATu^av(x(3E3?dZDHjiV*gOA zZC_PZ-cu64$_nG&lfaMRv2L*xQc3yP>p5n$SKSK7A)RcB1+s;O=}uJlps#u`Q9G`O zmOp4svSEFh6k<0%V8#CMY&Exdqb-|ksB#ymYN$CG5rBggzI&~Lv_TUEIFZA%%s1b< z7#Lhd)Z%q<8>{6}?H8n3pRDdHimcuEGpG?MQ5mtij|O#QB{KCysJ?}FaqDW=O$F?+ zq&uTuu4p%xpx!XxG^YAgdOLZU4}2xAvo@o;X(a@@d@CuCWD9uHeU4zYRV>l*g?SRg zwzxK4f^H}(<3|7}&gXKIBj+`r`%?b);p%Dp9r5bIqvk`c6S!pGvr+-%t@RyB2zYn- zrfjb+d{1H>U6*v$CASu>-QM4RG#N+>pbD6i?=L0HX0F17O2c(1c(7RO-(^D@l_H z-S`w@LcS{DaBG_%ZR`C#52jKDA&MNUL3sz}d}Q7Q-&9SABY;7h6Y$mu`f2HSk1%^$ z*4XI*q$PvpLA<+cBa#VWvq=M$O=-d_(=_%Jq)jfl*%1hkxvdmJQ( zdjp9d zqv@6Fh^Eh8*+QTp!ysdmn)U&MsuR&;X3-I3Qs;u{bvGCj)(^Z0|Bna%9~*d~9L~tV z3t(>Oe++@L>rPPmSci9(QXI_ze-u$Jn!?SJEdgoGwqc#);ZN65k5gQml!+t!m`TjJ zcbRHA<5@4;XO}jZ3Plz3Xyvz!ID4~npJ|zBXB6q1r4rMl>sR+-$azaDYrE(|y2SCO zR9E8}DP`#y$%qqkw@8}EEmC--!cSqGvqzdypvWLKsvvbxikN#D>ingYV6ss{X>=!% zg#+F@S{=HI*%j7hZ+qSs+<> z8WHAD%AhxCXd#T+kuy4IZ~IibyDW!rtYRA-Z8Lxnj=)apuo&PRIU$vklD0(K!5eKA z@%+K-Kd;sGx6L~v{XG5$2*mt+#tsS7bqp3q>c(Dbv8^=cjMS|m|Gx$QF9-jx2LHw2 zf4^qfJ2x=wtq4pBa*Y9PqD{=TNLOcBq;DZy&de*bNWaZe^O{_gcA~Xh1Zt$QNSbhq zq=I~PqF@$XnP4;wXbh#oggcY$DW$0;p}=?sa#BDtrFgwnC)&-re%LPk8_hZ~Kt)@s zbhItW8eT#ys9^5}b;_mTfcN^q;~Ik2LGKw@*ThsEc7#RY5JHcJAm(kvlGSw?)C%W; zWdn1TiG^@m7|thz60!45C}L#!b;B|wJF6Q4p|XVBG7t#0Rpp1H&GkrMbbaYkB%s>O zX8Z#&sbc}x?l9BmP%X|ud#}5}w4Q_a3ODb}z#2h2GbaBB$0OGH(s&!1fW+^BDx35O z4%FkpQ?$`Ba*EbN?0~cKsH3fqNDN=VUKUK5V`NmiNqkM%KJ)&t)lR10lncdXJ}P)- z&Q}yVn{Jp^TLh~q-EQo7M>e6Iw&3)&w$aXuvZ!`O3}?!Fs%fQ$@zfWBm685YVn^4Q z6h697+kL+eGwbiZf zLG<@QWt7{k0mQZe%}8hsT&3jYLZ2y%47MN^n}jI^6Y&~hMZuHm$injew;oe-l}+Eq zBkfp@zVX%*NPNmKNCkO!*EI*Os;rYijV|M6HQ@J=cw_(!*l9nuBF%_ukP%<ng3Qw#oRaDB3nT;Jp|CbeLy5Ugfo+YI5uK{^4Qf*zq9M|y&`NQUnAAaQp+d*Eq zX&G0Z7pUObJi^5nf+$3)>cJi(wWNY%X5=#A*%~pX;0q^Spq7MPp zJ8055P+$@hXy7WbEW3pjh3#S0#1yPLP(0{u7D|iW(Spkd=##LBLH>zBmBq>v$xZSP z=7V(|@1X@oTqca-#^Mgaz@>xP;%;tQWSjKpiou3IR-7;^T*LNrZ6>sb1F%acAwA3DN<=1YBt zuwHKiN>FvT#7sMFzVU;lsPAk|vB%w}1oJ<5Xpw+`UXobRg!Y0Z7<4U2q$T=xyX7y| zGj=d>o|kO(0w^X3*N;TS)>EETCF{hwl%VJ5!c5~y=eU~U%wGfvAE-?vxzt{d6O9km z-N~KgPI_i4tsSR42IUOrXoxk+Y0gs~z4A`yVULmSY78-ycc{TZEUK0AD<+qS4wmxE z?@)A~@?**$ybd?x3jxMq}URXVLRO=BFp{@{#ERc?vpo={nQVqJWnaJ z0IYS&4ETRUnc_<8cks!+YP(d@ui-y&pYmiVRW8!O5B)c0I`@^4^{dasp0oWwm~ zE)lEQ524%yWk;}_NnE=HI$wVf-aV=egLlZTZUs>JTTMgDX#GCO<%7A7)wgredgvH( z9sD*ojK5MzwWa|OBQMeV&F;gV@7LJck?IIt3W1KsJ~L2Nm3_zntW(NIANd(bM|l=I~Cn z$SU9MrRA(^GNegiLonA#~ zXs<#RE8&C{&GyM05j(%yJgM*-j;d?9R4!(Po^h9phR`6=XG~9bCU_X7p-U)A?>r4H5FAilxUQ}! zr8CTf6}av~g3?#rhYYmvH+!q0r+2MPk8=s^2v+@j4NoOT7aljCXuTPa#;L^+Wr8c0 z8{Lifmn41Ci1&Q$#&r)S{o9Sk|Lj(aDy6y==fWWicwmIx#Y`QZrh^mjCg3B9`#ey?F^*kv?D%``-;4*n{CjqIJqlJhMmJ~)$lL;U6hSIopgIO?7 zZ~fYXXjv_(p4n>D|8UrNMix?Yn~HIp*pJ7kbbv4iZVf~AzL*YRNZg1x@G_zpKo?Jhp$3CxtaK1d`DFhC1x zpowO8w*HE{2@YUdS(dT?lUYm^k7NGL{4@jrr-gk5;j=WYT31-07T z2Cd7Dvp?{J+QYtTbh^)Rc>E|JG_bX%JuhjDWS(MN^_;Am^#t;v+aTn{McyAiHox1e zpz~V6?T3I?#Y+O1589LBU>H zp?uPH{Dx-rQWx2lcCsf2E>jq#0ohox2AVX8sxWz{$!vw^rM(3>*|*c50Q;PACO6ON z!88)jH~?5SRBr})K4suQFUx}DFOf3eNsI%DO%4N~`(#lvV8C&`!BKc!Mfn@UdMHW- z3QvO=8A@{EVd9ZpJmQErY%YwF;xdgHz`i;%`rFDfMAfY#Ea-ubIO0VN+S21@$Mw%0 z-uS-8;=+TyvM?~B`)j(-0TDuWf;lz#09{;DOQ_@OSDf&6b$F|~abe>pvAf-5#PPuq z-yU$9C=Wa3u`g7T@o{iitfo5~Lo!M`LJY+n7cSG{oN*ldVmWRy=^)I*gmi(r0XvcQ z7dPp`cdH9WV_RdtJ53xD779wK5nR#ESb{5Rf|FosrJJftSbvWp)J4^iW6i?H^NPI~ zrYT_et{?p3cPpSg0nmY+fOM-$e|}`qz*8GYWz5=kH<{B^Em=Gx)UBrYgWp;GSMHNs zq1(cBa*N>qUUz)Iqa2o6F6yRoyBclog6ncBzK2rI>|b)MkF){n2tylTy)rl%kDG6F z*>4jXG8-vCItfvzDJBg?!J0kAIg1Qk@Ab0iWYL$vY|9D>O-y&;Iz!=DZu#%U+%)JE zJt*@~GCe=Kb)j~Bu>P;4YdRh%cR6Fc6mr5cRn^ByvB5#0r1$@# zMwEoWONIUEKJkYs%=3rJNByf%WSJg!{U2>lzj3W_<%vJIr-Sd$7m5t?Z}%J53Z6dk z$3KE)?{7DkvU+7I*1U1;&Xs$vsh-ySp@7^kp7sbs^9+$WR=W2KTDXRuHvXXqd*hlx zm@+?M)Z3tbe7k<`RaF=xUKf_mj~?~n`FY$D4%L*xc)u2^=EvUov9y`n$z5{C+-e`% zUa9#*4$%B#C4q+NLOy!1{tqr}c_E(0PB{*g_Nwb37|M?IA&20cuMSbai`Y3pUY&wx zelpezkqfltCqXkIc7k;f?8)FcRH$m&VUFgoOC7IjNn8&SZRSmvwB(;bL zWfT6sAR9j-Tv?!vwn9#S=XdTxZYrncDtStLR~UPD@;H;PZ-uq6Z|NUF(ZC43jt!6= zp$(&|#j>KWA>h3#2@l11&KXa4gQ+UODA{+q(MUB>p5k^*Al8cPLw)#d@Zqa_H$z^F*LJy zV0;5nha&?L4V#e$9I^wl-7;V+u7gC*h*Jk-b=qkv!{rYA762ro*0~E2`xglRgz&F> zgTWq5R4f{KffpmT1%hG;Vk;mtK-dC-6i&DgvE!i}1s&yrfClo#W~Ppa;EeEKcX|I) zpcan|$dcNwd#gwpZLo}|icezF(DiFo7cN7Mu!zXfh|yMoiasttYTGILf}7DkU2+rt zpDF2s|BWT0J24fs3zHb}af#6?b}J4Ayi_1FtKapzn>5`If)f%yt77VCk)~;2mp`t; zdX!3OwgWyG@ne{>bda1GaT++BsZIyqBS!pG>Hw|(L32_EQ-@N(b%EY)2QOVl0JNGg zoEr(vphB-rSRY+ka6O8qw2DJ${D)E^2-s(aInYjH07)&Kg=Ni%X%aS?#Jj7QydT{; z0Mx!=GWMscVnBUo5}&9t#6f4Oon~~svI?{sc69yGstb~)VG(!OJlgdo)Yt>V0LSvB zRVmHppvo=@u2-ajBSdQ95p#@-pogXBx(RB*;|#P<6~i#Upo?j{UR))sq4!g@7$_pn z`N<8(C2(c5*a2D)@Y)T4WMkNEHi>couOo=FB|)4Ss!-}gZbCQ8n&MiMIN7NPeL1CU zF8@jMJ}ykKFHT9!o&~3S1Ayyx!Qizj5Rq~A(od$NEP$@DJ*&Y9BwRwmP%tYHSk%e{`YCHuV%V~kz%h3LQuz-VJ z9V}1_1s-uK-XE=@#l(P&W3=+!a#*b|52bTt)$S#w!D_JZ(lTgn6_lRe^?74b)|?K~ z{L}Dkb(Z%#D`~NJcneqFe-=`ghR0d!ie|dTS!>MGT^FQ%^`t~mPgvL@4vbu`;gJeI z3@_#fv7-J zW@OF`^8R1)WV5?qKmL-}kq8Gk z0iFQ95de7@;@g0KA&h-MOT`WdrU!CxjfuIq3?mo3A#Z9&S6Mj-rw~YRZ4-&C4UOFZiG(O2t^Op;VR*m z2g|{uJlkf$&j^p(KEXc;lb6ngYZ==?Uj9yKU%J%r*8vP?0rj(H1tq@hJ7&J@qU*&L z!ZK{(Be)puz7>ooi8TRE3WTK(8SoO}`G>Sxo38}k6#IUCUjIS~7uA^1SZhvdT?^R2 z^jHfe&Jq6kP%gehperV&ya_XU(K>^nCQ!r=2=&V* zus;u+1G3(gAY58jQZeNHDL`DT8BZn}@;Yy&)sX%=fOPpB<4Kf9azoxT@MHuv*pT<* zTV;}<%t^4j@B|}R1{eykIJ5OtVbAhpd_ib{|9>8LEtgUDZvzL{ z8ybjuH4zs#b0#qUxPLYHmr9oKqgSmhJ3ey?@WFxF4 z`~w#MY^`kC0t$9A1!_=@VsTr5uqg6#pzN$9&q4tBA#hSUxKhJug}eFrMpct#MKnwT zL0hCUgGV`{+#C84m&HdfcI)j8|wtr~MOu2c9R4TJbb~LD;^cDDjse zB2dVk1>6BxXH$c>7-WH3-l= zmOJ-JOXi@gr7p&^FXTsQA6Q^!IUnPZHg~&WGD9L?cgI`rc6IF|^pb&UcT zf{|YL!t;$$kT$sVFC;)LcR@)Nw(CIHnu5fYQcMG3Ifn-i7bSI+z~tXOm<KaLRBOQG2K3vq>5zqY--2cWFPO4fhCddFp zqoG01$;-afnqY3)hexgejVxR6;*-g*xyL^WDrRx5F~c47!+9uh+Yfu6bdM2F1D9dr z4Y;U6VEJ)a1P{Qut%7511~oV=99f$*?&>hfNelb|w-v9tEWp-~t*{6E0TJ#vZL23f=#FuefNnX%lSN8yI60-t-Q?7zUv8G< zMw=nO)uzY7kJ2s&SrZw~4vDcDd8oaECjRT&M*P>e5wCac2}#%XV&hx8l)hbqQH}eG z5?o7#hIKLa*dVGS28r@z2lR6R9J^lw{)%|MkGTDV63X0t?!8@aJu5kL^Zx*erqfK`E4ns9%p~yW<0xKZ%*>>lkV1Jb0r*}x)oAb=XHD`sT?_LVEb#L zR_rcDX|FlIb60}b{8pZYyAN=!MW}pS&J20~@Ci>no;dfx*2D zco(!*7U#o$yKjZ*dPwem@IC2qMEz{Kt_Y^zbu`>C0~_|41MIEQ`^}loh8tD(h0fKY zTK2S1z9wd>D)z01QR*tN8^C=c#{%hrnbEd`)q>;T24M{tzTj=AW1qCp2+jb&8N#fA z-7eo0@cy$!cx%l)v~K9{f`5$`g8=ndoN6mvYe0Gp_qMbcCikNufqQHMwR}i;;xT6w z85y~&F}H!`*@hu+tR%22b<`@qkh#)C&GHL>U761edUp*Ahga^VrVR+wA63T(t`hNl zD?f^JaN6Zo-lToi#=|~M8WbLVG!s89?0spD}?^YppGSIOYj^*OH6#yRSntZ~JRTJ=0p?Ou6{kMU?2PL@`!^erCQC9CJ)yPSr zZRc8>95SFl=|t2aWg( z{qkutV7|U{5akd3jb-ZcSE|j_2Me6-B1o-!Rpz@4d}1Z=|Cw`L z^VVyo(iyWse?^I-sjL}qrWfC;U~w&!9+;@m7=WEWDKVN_M~x)c)UK&^YttvW6cchu zInBNz;mGPld$SX1YKs2`S&6r*t6dQy9nm52#%gI{H!>V@V$C(k55JYqLd*jlebq^6 zeu4SWARhi7K+A(ypa>;+u|7pduHndlgCFvi4U~&i2%|3t@r&qYE!P)nzLQkD<-&JY zSo^8(u7uVNdLJ2Lxcp|gYp0MmLSf6Usg5`BQ_ zWkV~TWp3DumaIMakjnbmm54m0b%(_4E(D4)jSC8B;{Ah! zR~z<@3n+ru_%gXcuYBlT_Z)5kq`n$Za0h@b`v|zC-ynPo!PvB|ej6WFrqaG7-D_l^ zHk^EeJg7e22Z9TAN(W?MB=vcV2GiiNdr$_(R?Cr3{Xnf;qPWcIHRy4`==2MS0DCsGpi=moNG z5D@oPJs9bphoFWq76K}%EY3PU`^h@I@I%lqs9IP!D#x5eqPbaW+OnQpT-|BbpZx{} z47!f($OK3CdoWPG;hpska7_8!Uo54f%4R&{;QH6hvd(-M#RvY?;usX#eJ|t;df)a7 zrVWXAzuF?f7T>lW&rqDT@q^yy;g}*G8a{9D$z!N;Tm|2;$XKYl6Nwt%7>^2!6y(jI zcZ2_TqGl>TFQpx*1{LjC4ld@2&Y>#!e@AH8kcHnCE^L^OpAvGPS{ZZCkem}6fV=D3 zvc9SJj547Ui7CSIr}Q{Y_}5d(YzCozVqi!Zeku(kVf@qS_CaqYn47@}KSZV_Z{RmL z=|J8Nzztzwmj}JcgCp!R!3`4cI|&Rw+}>1L8E!E@mfH>HivYJ7dQgjY_6@!Rp z(!jW!*5@>t^TD|MsLfDCcgJrBt7}et6;b?D1IJD@OMf2@)t1oPu^}9cy>u0D<+&Cc z61$-(Vt;1Af2I4haP?^owhE&*PKMhxMH}y>`UZs8H*UrrLHo=rG9m;l5L%u|#unlH zGxy_kVcI4w^&Z@p+q4lk2wj^dhaU3DYxssi?+Hmrw41>PzH_q0W(jY2ojV+4wg>R+Wy&2@|Vgfuk#~TAFY_ zDDnK>M}U*7Y&ifY27(L2;5Crq2UXsgs;BYm!pzNjKy$_BV#BEbZyQze#T7~h-UXn} zBCLvf-i=aZwnKakjQ(w*eY4hH&5h=gxkX)3&2YIIq$hAgK9AogYQm4n zC0a1D)$m3j7+8iTP6d{9nr(77anXBqNY$`f443t}sR`iPvOD+uEa>GJT)?eA9^%Oa zNrAK{OQJh90J|`J!F^6rXZJQF+U9UyN$LW)o(^Lew0nOUfZMq=xe@)atzxPEp|_<% z$7fgM`f&YLaG`jk0i{m2fj~#(*yp~IMi*Rg&q`tZ@_ojvfAj z1_(hM%i+CnA;8ZhMRn1K@qXf=ddDD>6w(FOxRlQAI`Bp`!&frST(L9DJHbKqH`paI zz*Ih5?Fe|Ap(04IFoKn!S0W9OTU^8=VGgK04+rsba68UD2sQuVPlG%e=Z9NBwWjal0=aB5?XljpaNp@oVf)qu zxD5BsRy|G?zS^2V{V*h4+B!#ZxP@$rmBNf|Gb3jXfeuVVF7wIZ%I$!6vhe)2Z2N)$ z(u0%nlW>(a^@f{Vd=;CbK{Ae>MUA7!>-aD}p*hTEwTUfJd}D(E{_-&!j}%Gg?&g1x zP}`X+D0N0N*37q!c~Wmnelnh`0A07iHs6-?q~xB@2mXy(PePldUE=Li!)F@F)fMv0 zz_VVM@vH$S2rHho<4EDkvy8kL0tP51L2+9Lc9Q{}vxzdKL8Pp`7Th=IO$b zR76=iERh91RW~8}QQdp^m(2%zG5vNg&Ai#m;61i$E?FsAM$>&qY$LKn(AP^)?vR1< zIsz2Z)`nU>l|$q3)LNUKk8Y>~Lo+&G*+L+?JgA2|lC^vlA6i&zv+$g)4a~2-aJUGw zc1#DEZ~Kn)1ja{%W?VCcJJ`!oyUjaV+v1VNREWeY!go8eBRfI49=JNy3LftkIe66U z5tKXQ>nfU{(VKDsE;btN?zcO};_$emqD% zZUEjrWFv0LfIf*eMZBhwrViq9jZc|^7*0&{;74%+QgY;MZ5g3WzgY=EL z*fPR>b;5Zpw`&KyM|~y$;k$u-(tRqVPfkC$EDC(X{NCol>IQgcLs?%q7fAO32o(TA zn_CXEJKz=IX6kA&RQ@OY)AFmqg+9})L?#HH9dOKkT|13X{P97>3UT{l%aj_{%9g_C zQFM!KlJ_G?Zk?jgDK+unY{Qzo-pwBe<|)u<_$o@|E>P}3TnT$Lf-6djk+4$Lur}dm z@bIZ@8SpM0z9E$Fim_J#%~W#QW^w~mD))QSPe(QTy-QLt2z}36 zs85@P{1-~_D?-%^36m@qq_M)KMY1?5n+ic2M)7b{%KCdOTXNA)6)DOzYQQjE)Qe%2 zcKVDqP{s(Z7Z%|;g5kxi)G0#>a3)p3VdD3`2t>!$fWdE%J%mI_qHEJR_K@E@UU=q3 zD|KZ+`1-{}s&hcN{Ng;S9wfHibAVbszxzWVgwysEg{<0x*clL33fuQ2$UY3F-rut- zay5J-!v}U2hEp}*{eG`S7{B)!{Jika-gL!!aKZC?XAA9nwF%2kBAw}aOe7K?JSjFk z$8W1A?r~#yG;zKVDNMu}LV*BgA2CoVICzc*;k^3V&`^_Qe{A#%;V04IaRr}4R>tm{@JEs*ciGRECxL*=kzbdz| zhb~0^h~amOLe5Q(LttQch_b48i%i!kdli*Gz0lMnH@)2(!Ju(t8-6q){pVMZB^!1* zxcD{){!M^F8FO6UBmfw90RR#ncicZbs11+sC+5NhxdPT7-nY}NIJZF^4uDW+iD~JI zV=MPn{K3Ws|F9V0S49HAg{&V*2Z|K8fS}GED2hYZ&w-ue?Ov8K^@N*R-8*4CC<}=V zg7xKO`$@;v_@%ux#u~s=)*&YVHtQWX;D^@u=$o&Yu#XZ6Q0GiW3mpz!5&TFI{xPIG zzz+-fVSH5oEgVgEh|fC+j&?Xka8w023W66L2J*AFh5nWf}otAlbJSK!_tC6omL$-;N^6 zC%=xMBztbDIs`COa&|`%ckX=;6{0PCvo{pC{s&9NJ-8UakWK=Y+;Mh*BYVQxlSP>T z#(0>f5EFP|C=U3k?d3&ZaHU-Q53$bs8;;ox*nb%ob^ke0EHkwy(9kA8guy1xr$d zfpEo&4zS?+G@xxH%5x;%c?!nvfo^U_vx)E zWg>h}jp1Ue&-8_%d-#O#n5Ryf4bE4#Pd;guxv(ZYRpv*!d-#~A3a*14$gFXiuVaXl zASTa=&Vt}G+qyXQp`GZ5})_?X1ID^;&WR< z7*q%Wr(uqiprHiGZ*Ru`M?QR`2J*w4Y)c5_f8uk%x%^3^9Ihp^AgH%A%i!(bZoQ?z zSdN5?wK4WQxC?}gQWIQMzRME)o?MPK2fms|->^s1H#W_$qXbw$M+PQ9?e~NK?+#$i zO>Z6CzRTlpdS4mJu)b<8aG@0PcK6VDIHvP#H@!QDQcK8p&tzN*#B#qL43ZJ9RJit` zv(}nJT-U&mDeowM5Y`+TUt~FA&Tq}+%&GL|Dk-K+5i7|3hDN#?f@j~2iCBtS-h z#bD%vIdlatmxEY-)B9#X=zcXLu9n|y4()(1Sw?L(%g@Qm_V88aU0^d+3HsOcxLzoJ zEfqHkt6oc<{0T^hOi)gI7cTQS2Z?OBT8v_RAV1g;KI$sm}vxpb`5> zIP==$c%?Aq^)3idy6sA;W4dto+?uVk`;~eCJhQsb~z%PS* zvNT;l>+^nbT4+0vi3@~l2X>a^H;o4TCQ~wg5x>VA?>zU&4sb`ny0nzGzRf69%lN50 z?5C(#gF3MJl5URNsYqj78erpJ3TPUxS%~P1bVA#kC+D44gUbkbr<0hz70WR~pTM&M zo=MEYa|^_wxAH^anUoK^^&EaH9u&it z3>?~d5S`O=Ahb4=7KMuc%$#huT+8rx1p@~NgBUZ0g@Iw^@?M&@YR3rRfpm3GYMd_@GrHMrs;=fLeh}DQRwZmA`jxp|jEgYA7~uebNDdc92S)}EDWCu&4Yodo}^wEb3i`^4L2ka%JUiJ?&M z$05{yS2RjSRt!JHA(Y(sA!4gaHa4D-P_DM$rZx53a!x>aWhoYLJ<_4R(>CH8`cB#& zE*5pCeMXmec(4QnHoUZCnZC28Kh-E1(a+Q_s%^DJ_*-iZwK+i!8gK?Q1UiJQbJRW zq8z#iO@(2m8v6}K=q?bhWxO4CKuIR`4G5jJO8v=YV&e>>NI~)bWCwI&1Q325=uDNm z4GLwKXw>26vyu{qs(`W6P*RyZ4jNG=Q(_*aN*{EbmFC0D4RekC2nIJF23JnvPeT03 zlMp^D%_fjB8vAXKKl^rEV}*q5kp!q9LIIH!AQb`)MnD4*|I;9pz15g#fO4~wsm7{8 zvS9V}^nvUHxE@bUbE0-+pvsGmsZj*Sp|upPm`Gtcfo z&`u|m`x)|o2LBxR=fLlVeA_&e_#U*@4e>u9{SWZ3fqyM`@;OO_0;DSu5`Tll-@xw& zzdu*mHZl`rLvtSa%h!XDA6FInujvm7%IGmxg4Sb7$Ckjd=Y`kM{kEspHQ}sqTSU!M zO(&X=mgN7|ytyyD=4cbc>AynatiyAf@RaLLl>V0;uzR(l1n@f#Yp*&{<`p~4Z#5N2 z>2~VBswyNvL<~y)t1o;b(%RI2^(i+!`9(Ffx2aEAqev=tKxIV!D-h$g(k8Dq*fdzw&8I=i(3JV#Pc{`U(>W-G+S)shn64Dyar^7Z%usA_WroZG1w$1hn>V`9gMZckL z24HwS2(fM8B3o=){ONL@;r;G1VNOt_a92)fSo5GWcvZN$WR(QCPMY^$JF)GcJt&pZaKVVxgJWB;Snt6w zRz|`c+k!+Sk>BUNLU-Y&>5iBx+>O$`j;cafXpudPIPldhk44!LM(l;lF>-s*>xfHnku%2Lpf4FU$;8SsR8Y6?6REW?KBjn^THEvG6(f#G5Itt_q7mo{Luz zrp5h(j5f!dW5K$Di+YO<(c+20^imb1FlMgkeJgbBZLlO3by*ghv3QR+4kqmK#KLbZ zq{}q1Pa;hcOqhmNk$7B^i|dBsOGBEFm~HjOK|mo2p4dQw&5y-*2C=x(BNG=(j5er< zREhP<0#&C-@_>Ip!eWef$eCkVgqi_*N`T%za38#f*yvFJHwb?P?i9Ga;0}ZP09;xW zV*55Cwj-V_B0$`owAe2zHQapGxKxd{Gce-w630`GWYad)AyyQsM!eg( z-dNSf@xNP;xK>CATV{P{kV(9=3(`eej>Jxgg?7EvG?$;kr^4dB2XPtXBJo)WMP9hS ziG)8IRCj0da{?v4m6*goFMPHF>0I`#KuXr&HD^eDF&|t4W#2+#B$W8ID|F`!$VK9A zh;;>8e0~t-H@30u5Ah|`9v+F<%&YD)h9Ax2Z9913-O4f6OVZG8aJCB)nvJ+l3F+~q zypnKBjd4_$(sCS8qSK#SBI8kNfy3YY66}>#VhEbjjWfe7hud)qo|0ymC#f6h-s;gu zT_|j#{{StL^0@wH^DarxE#PTx+!_k*qKDU1h( zV=XXnMD?C|@~hq@VN4e#KJWh?y5H`cEoGok7Y>cJd~LyZ1{(?_4RQhw5j=SZoRuI7 zL73c90vePS)xL$_!7F%_9L*Q=DovH17Uy`2_?M&_11;uz`S@8!Gk7XDkC*pu##me{ z$@#LL%`8gIx1(M*c(03P5Aw{k;}Y6k1jE;P8NM;Un8&%ZA%?v3^E(UT9EdBCn9w7Z zGY?trGmp&5a09FEm4K>AwcBY?>BaizR>lLWi| z4O$%bRP%TT#|OD^5G|hZ%*?ktSBVQz2mFShGfu5ADk1^jE$AXlk*^G4eU0%i2j(Ov z1~j3?qe68=LYU1@_KvberDgzi&I|h^64Lhh7`_%Z>_M+Ak+}dUBnrM%zN(FJC8I-T zx!3?Jg;Hqob)hd}`Y5t)w73<1DRGG~Ju-Q>Y>W=yE4(pAn^Wm~5%vg5?QkeLO58hyQXA}8ORxUP>34tQO?c44BIrVV-JU+5BNy zeb+6@;P|i}I*Ru0c9Q!=R;p}?hs8SWA>Bs|w*8?r_}yoY5G-O_s8Yd4YzoXbuM$>@Pi zA|vD7lp$P?Nx+W@A+dLi5I zEVnQxE)$;^)#~JIt_ly@SHt@nb?( zdq0E(10-A!7RQebS@NIwX`woPES@9mh@Ubg*Gq^za`7ku8_CfV&Cf1LN>%Vc88?pR zyCilubAFW=jYdv~8LdoKyI6*jg8boPW)rYBC#S9p^xH(;BM0(#5P z0Gfb$*4L$N=lVc{gG|26qNrxUioaJFW)$ zWm_2Wyq6LG1+K$8s#IlBwT70)S>i0KTM?%aR}2wiWSg3uu;{B1nv(1}cZ-}4pM~F; zXpxI;65av(1+bvRKZ?|Bl8fI-!elj%?-!m|FQEQDD0Hf`lZ@WBKUf16U;c_P)_)z_ z|8F3KQC>^%%oJ#4mXM~Iio1kmnu(0h{nC(7rzs>#ahtb~j`Ud4
      *7UU$pC`7dc`bhq5Cw&>1|;?Q z5n>J9Ewz&Bc+@>*Ju}C)EzmJz&wWOR3$1BcljS9w42T0ZM-@UCoV@Nf6h!Lf43T=K z4KLSp$xpAtB8_ne+%WBa_p9x|iE-)ki(XU>tUui(Pt$b51?0i5G=rlFYv18RJ+ym@ z@fcjTDLtcQzcml6A)6{*U24)anR8V6Vp|%2)kzO*TMd*&jzTAVmCjqwN-TT4Zxmrs zpkI1@Mc)jXUPD-xTf8YZ!kgNlDZ-nwMRtkFo6)2dDf&2sM%YqP-UKNFWd6_&VRjZD z0b+&2VkKM!swNd&1wMByth=(!f32zoT7MBZU*TWTVfpm>3-a)ekeTNsHm^$&+Hp=| z%4J*u@ck(wmYsrLusA4zUw*SWa0_!)ZKRi~meLI}ph*@fLeB~JO-QCJK4JZYSR5j} zJwdOAWl)l(NZr^dzlgMSF_RN)sWakjo}YT`|@G3g&GzaJ;sMq6r$V z5+8%yxBTSJhDB);>>$lZnAHI=H1(s^-+)iTaSCsTWnUP*b{VcZO0pGqM8 z%zD53pr6rHu3yrph^$;QLi`*%hBV;-{Xg5KmeI=p2Ze{$}NTM$wOMl1Y% z!b0mZzn<>{GV;K14;-pt2xwS9zb(MdAujW(2r@V(FMFmIw!;Ys`Q77v-4<07ZBg@G zmbyZpHshYmGL!;zaB!IzA9Q(*_NgGRtVqv)2doWQB=Gm(Nq%>NuTFYKFL#|nfu$2? z(%c>KlWVMy=y!)f=CmwDrWTTGAav0YT}nu6q>e5k0?slKgRn3@H3TG0QK_(FK;(&1 zHT}LNuwzmU8tu#4{;Eo?$k5u2lvews-#vNA0DE2m47eArEwRw={tPZ-f)(G70^)u& zkf8vBYojX&l^-#S;s3voG_;tYD2Vz@fWnakMVEL;S;U$8M-Y=N4-3mfXw=(iXWT&Z zXXN-CaHPVQ`f1kip%H-{96#<3zvKkS&M>WK;HD92PG=A|+R(tZr&ftPCfD4`VG?3o zX5@E2JiHwMva0VSy&3%N0IrenGkTabtV*0LZj`CtFi*R&^7%;79450fu4vdiaGQIl zbRUw&RvnUJtja@D92e$!$+uk^bDV7+)BKeyG;CaF*bSB~moh}u{$>th%W@I>A^0EP z@(U&*cFQgI2KWcSWkNo2`@wPRc?Hu!rBjYXIqDdDP`jQ;OSNmX>$?aUreOE3ulwj6Ig8yEPAT{b_Ks1%Qqc*?W=>6Sn4Ptz^z8hnt*_to?ZHO(z-L#~mpB zLkDS((v5YXiPrwg15gjiQ>Wj2=)m#b<7l+JtjC6Cwwv_;|0)hP%mgoKXaDf4PNcK; zmma`StLOmDFX>|%emdP`b5$-GPy|BcSbRQye2rPwD)>H~cr>8Rw#- zcp~lKMWuY)njf9iM6Kh;=8&Vp)43XaLfDb3wq`-wSqJ*AT##G)GY`z}k<-@xv;)?O z({GMDP`RGSJt^Jve(r##xu)W31HcB9qV1#N^J z`00vzeHpYWKk#pe(+3{vLC~iEa}47j`ux}x&H6cz>;9bd*l+!Oq)YMh+eie2Y^t^Y z+UM$*{mqJ!U_(-qv7dTUv+>s}AmD$}>Ofd(1v+k=_gDFX zj%P~~9+inG`lX1or-Kp0{AnQ<^;f(Y}rJix7S;aHTxA2JiS-dPoV^%y7Jx_6F6E z<8u|1A&2Me(s&~hmsk7U7lv+e$FFxPaEHf} z8@dMf#3kwbY7im@U6M|{zt?4!;rdR+V;w6>%6f|9&Pd8UxPL8Jvq%cAqC7!2vW?U> zRXbc4bdq5#U^p%0*{S-)o-H@x)#G|-`Gcj{OU(g2hXrfRS*21iz!#<86M*n+opn?I zI19aR!U=gBtfT$|*7Wsn0I52&XjNZ9#AoY)6jlL5Mz89lX)IRZ89k%Jfhbm`ula1v zoeHXh)sp7Dz}XOiuirhLe>?} zE@H9pqGQ385zwCv3@^m{4<~8x?ZFd*H!sHe_Tb()zx&0(DO+mtKbBbA7gxBFx$7xW zq?B;TG=4rp-4abH((SzxGmBNrT+x8u&kepg7_CP-wyQ;o)9ad6tj8KcF|Anh=9Lxe zDUIZ8V5|dY_lK0gQ8z`~?}r;+K@(aCj=L#jYr_@1`a}@~&RT!~m}lxgKJTpg$nXE> zHJ{fKGPB#P=4s%H>k4JS5FqVkb1E=_PjN%;m3|!1e!M31PD#V#h3Gpo6H@(vJutc@OE#O?$ zOoDc@Q(Cd!x)fG@#Tr8P-X0m5_3I^4%NZ#&Pb;F;fP|}0K$yfAfF5~EkzqU%7Y^1G zA@Tme@BG1+?(w^~_+Kh5>+gROflO@Jogi&4rg)kMYA)0$nd2~TH2X9s)=*C&O{kZO ziqCmyY0NUl>RKm*>)enpDw&m4=bCZ$Cg}mgQqjsN(l<#(hL!79^j9JCHVh zydmX6^KmJ;;<%&_kJsBIPHmGy)e0{ifpfM=(`G1iq{c=F?UqK*`NM%UmBmj1xAPlN zc=QFrL;Kyi?TcsHw2Nmon5~yB1Q9NqX;{JdVeN9H!(Diq+o4?^AVMncE4_E7X89R7 z_eR(zlrrRIhZ|Nz5xOm>p%RIoN?J=cXA+OoTJvRK+0i^g%@u{Dua8m4V-=z^@7purP^8rT{OX zoU+^xI_aqL2_>hb-11X!ePx0+I=)A+^8dbEjf}q+$^Md8EC2G++L*2g~gPWli{W#c!)C()3OLkUNYj&D_ z?q7Vs$PYfn5nv9v5490RaL7Iug@OzIJP4fv(F4Kpz2FZ6u}3h9u$kS2T_6t5$Zl}K zLyd6oh3e48Mx-gYQBi@mq54fme3r1bcpI+YYNXGjdYprV8%|K&=YTx7XIi?c8`>p2 zg)9hUf_?PZXpxl}#51->OXo@B&1eD=|7Jt|1}zf9*n@$Kw#jxdaM2zB-v-y|e&PPR zQ}8>&^LIZO^0=J=(gM<_uMmE}d!E8%Zy7MGG78hDr&%Xv$Sr*>G zh@nhbPYoT$F|NjZS`4Lu;g6~_yk}7NARK0b#anZxd1HWc1uFC6x)4EttnVT}1S= zb0rGYqb%VO_6QRU6TnR7LBm>ARm*&piZAQm1KTfw|1Fjt*z@#|d-8Fo zZyB(KWuGCZ;NyOIFH&w^KGdYKG*~`0rk(xOBAA71#&NSI`713f7&>4&Ut;be6_Y{w zDz&8mgQ({-AU@Ool{13-$r;c8-5J?J$eZ{4L?#2Gcl8kPX`mVb-6{dm4xz%-5ppNd zFe`T#4!PTe8TlW|kmY*=60YaR;21$skN~pwl!7$;olsUVHT)}SB@F7%<%f(4xS5c6 zR;VwCOX~BY)KM4Slz3n^D4}3CQ6|UJ=_nVXgDPZ{KQJ2nEV91Uk+UcNhSmR z)8dCdlf50DOkA zp0;1M;GD~5A~*VVn6@xF(JncKeTAt&p&=HO`E1ub#2ORBB|Mdq@N}db1d9WjSGH_x z3eIOiERXfIAdE*Ej*qPh>Q+j4CN1Go1VT(s>;>oircIq2qBNezcw9lrG&9|oI?pZOF;cT z`A5F4Fy$9P!n=3IlU!<>%MN5C8>}hh^ZDr+GdqvCbYXYfBf;mw?y?_oX~U-5KXvKp zuI30x1x zZrK8W8r7lgxx5a;;Mut*jpVe zUZUp#7j?S&M}Al7B8jPQ1-P*7J9q+xB0j2p1`sj+EZB=fHooqcBd&+Tto<7f1oO~& zewaGQr3ea3WA~msSLwI}Bz{9MFw*g@;|3l^l2Hqw%C9W7k=Vf!4;8 z>k3Kp3@q0ZC6T}uJy9CkUdz|qgg}$@yFV0!ICe=X`bj#j zQx2hIV5*dWBV}S1izn+WgaN86oZ%$CY+GF+sV>{8a2$*$Ey%W!hJj(&iL>c z>PL&o5=ONbsF$hh3du4tU0H!4o|k8K{NO^tnd*^6)~k=Wg2GaM9*Hq9>|mE3?{VUt z1fxm{YTAQbc@$yTwzuomkLFu}+Z?QEkB}nc>k7Yfc7qraPyW_Px~BjEzjo@>XPh|e zQ&({C>1K!XN7yBp9p&PJU=K}wRpRs-MOX(QBQvvLl!MPdcm+?tjn;()AM`5ZH#`4w zeib7*$$(-2VL@gx@eezmeg(Ge(lEx_&s9=zfGiJN=QudPt*Ug8tp?jH=tus%#3&a5 zLj^#0=|>7p{2G!P4$5y(qhEXY6P_M=AIjZ-#nEZxhn-sXm0c@TkVUH6ZC zgAAY)Qr6S`#IAEoWc3|d*}d(CzT;Wo!cnuKd7JZ~73Q4qf19%?4?5y14 zMaBKci_7|%)g6IVOi>fe7`e&-ZGUIAr=9t{(W&Ks;O~dud!4cUwleGhioTo5>1tl= zoN+@=#r9BP)B6`5=z})Mu}6-#pk6s#XmF`oyKWyI1pFE}0Y~;ZX-Mh7lfUNQFG%}& zZ!d#(7aRt9R-QleD6Y@RPvqD9zMG#09iqi@7bVwOqT0*V>jE44H_|N~+e3$4vd4mm zN$$dde4Uz8L%WMr?V0Kx7!2vjN{)-V!oN8y6GwlV%Fp#|y74odni0TD)fJw;J>t9S z3h(}1&xZv}UNWyrrpSKuOgt~=!}$1iEnHG$<3@w+)^F?dV2P*UO+aXGl7i9?@lyk( zf_~O#e^4Nkux@oPOJ4(W8JMe0< zJ?wR>hEdAV7^Knj3!k{_iD~8$Gmb-l8bVxuDm~P{$Q^y%+4$%2=ia++T5;%4{<%Q< zMRJ4x;(YJA0n)w=lzp(nP|Rw>QZV=4^}B@Dxl^qAQo8qBTDXp$)BmXmdGC7qbBF%? zE>M=~YW|aX4o|W{y22%6FG;(>x^H*moNLMuMpQ_vK##J8N3~sX#6I2x=4IP1&gB>J zsIC}j%Zq;G(uXb}h9+Ph7_32BR>D8hqQk$D-^yQcMvjaljeFy|@;UBL1$6suVAxC- z^3X$#e-?%;%g0mMDF@-Oz2<0e3cKg2f;!wW?J6Y1p3H9A@|;l;0Fe~ zokW{ZJ}5kT@12W^!Ca4&QUSX6I*rS-n;HY-qdKq}?AijRx>Oo=AhF^o4)|Xmttup( z(WZdu1rq&7{nzqZ!a!Z6TNfz~1Mzf1q3A%ORT#cE3I8P|+!wnI)Re2zC~9oESlL|NSS zM-?zHhmR5&QyWmn%9ik%T3`(l>`N?RVE7PoKCHCfLc35UJ%Dm{8pF>p;#i3mFZ=yg z_fvjaybi7jI6_7o2OJmSJ{Zw?SP2?*iuL<3yAR%HC|i&=WafNH%W0a(FTOLM{N^ya zeuum?Ze31mgGJj)ag4Z6%GNfRp?3TCQDDvs1ENYh%@-^veF)eOl1B6o`$}JLL@8DU z4{C^w303r)oe~%qh%fptNr(1?HG#=#736G#rI`GK#LnIVHlP?9e_R^h1O~1kkVN7m z8xcTlhM%crfEKv{Tr~rz!qls$Ch7j@#CzsSATMf9C`W7#xUmZm`^f$ObyG;(3JL#$ z!0QXaLLA&MIO`(BCV?vhcNLr)D*tcA|3Be+s7t{hWw5kh48D=BCtNr!RCJg1KU?K@ zTQB=$iN|k9)ud1#Fn>tAQEf?NQqhe+t1tb5L^@=2cobsPOF)q6_mS!peaXqF7Z=?O z{Pw}`Lq(!9J_V!;lW5W6XVmgq`Ch;K4_`)RzvFi&P9bf76KMNXHC<1Gbc_a){8%;C zmRUsG2B%W zxh}GGI;?+W)r=bvG^LjBMdSBND&W5N`o=pE2w}?kG(N3pUy4`Daok5^^xDxKA;_RwMK(T!T36z1bC@|&c;`xl!?5dn{2VX4^UuNG{Vj} z1nv}I^{Ggdd>i9Y<`l;h@psteZ@pSvVmZ#K%mV`h^P% z!mQadfu;i;mDTA0=xGScjkBLKFzH>*b0n>PQ_tA({SIalS%uGxf9r$=-Yb9G@9rNa z(^S&ut`HMoi%(vA5(Hqfy)preIDyFquFFP7e+t4#JZY2F(c)s?ZS?3Ej=xpf>USRv z6mJd`-ybNx4~lP87{t9c7I5)H8!f*5pQ?ug9UJJnE2Q~11Le0viQNB`_&89)M!ys& zu{ls;lTH3f6o6p7PsTH9S*;9kR2WX<PN~o~H&S|C4+S@@Vz_SIEJ6HIwBc5#4RgdBPBdD%Aze7H?Y!)BsXwp|4S-8VR@m^0Jj z;la>S)TAPJT6V}RlUij-H&fzDxDjPtsbbPBwA%^(n!tI^ z%;YRsoZu5SKEP>BP>m*6teyz^f=W5F%Hjk48`g|+DKG~Y>q_C92h`Tu!=!RzX;sU} zaB3Q9u^&)uagS2J+T~AWQ6qt9;ZAI<#p`T*mlZWc@3ZY6R1g!aW>ZV(1X~Z1 z6q&GV$uD@jV6BY7GlU(L*{NkH^IsCG&A4EI>_JB9{iuYTHwt`AO=I2fyF7u)(9O-lkj}`zweadA^Cp;@4Xt)uiuQo1P zj>HC=@@K;h1;ie*Hw_rA8|+|btgJSsLaf?aYF{O)(5P<1O=@sMok>;yH-^zlRT>m#tmcIr$58J~n=go60 zF%@Sl3oDKYa~}I9s@z!>Fvu=%n$yHu*rs83qen=8Ttgim7Vdf6K)pRI)IOfa47*bX zg}*&sOP%ow53N$EfPydEY#GJdc=fVUi$VR4*#eWB=M!pIW#IKf+p1Yqv`+}FN~Mrb zm|QiE%7J=S*@+d)5qt0nc-*xbv3I~CNAoO*k(cub)JL1Z%D8F*J|JAIs(wH}^kskw zf7Ex7=xbz+PEw7?hQs*qb#_o#hl}RW`8A!=n%T8A|Ezh=F>jrGs!WG&{LM!Aa{7lE zQz}c&0(G2hr*%3z1`4O$mSI8Sphx)m38OU}^bJmstc%rYmfCdyG|x>ZN;8PB*?ws@ zzNSB3uPsXO#8BI`XA*bMUK)@W9 z9^!V|>LfF_^NE+7>a6Di0You}m zNP6vP9l0J0o<1b!bvOX2blsYa`cEhlS!w1Lijxe8u{5WOG6 z3wMtlV@0lYK}EdB{h5Eev;Z2&2famY@Hwe=c4jLGaHJYg!ja?VQ43P*wkR!Qx2WHy;Frd@&e@>EerIsR(zV%t*7>FJ zuk%-41`{|)kUzk&v_2PWpDtn zM9`0m6_^#uD4YMb0iR7;pp?L1a&5a%`>5U;3+f2Jdy)V41A*<*eR@0@s}BB4Vj6*j zL{M)Flz-vLFG%?ppgd9^k~GI(Yu;mhCCu~6P(<_g0?Ll+4;o`TD_+_2N)W*14X{ez zvjV|^J@?Vt!Vw6~9VBwBEzroft-B;fPhPc-$Q(X;WzVCNo3}k^oWJLlLxbbYI6I>G zE#sce)XyN_r5iTmtZ$u+s|HT!6Vi6+UU;Wx;PIWCrQCZttoclmn}3v)Ra+&7JPza{ zme&@d)Lr(UoHLq^uQ0x{>6M7)xaOTkYzH!{9nL;(RZ% z8OuE&LqgSR4(}J_HLEKtjW@e1FK=cB7Orks5?*@h z>gZf%z%Xxld6zbW0XXP`P3^+OgAGJFQddZ3PL9rCyx!>JI{`^Y0T zQm?8dlxI?PAOl2Vd@7wh4n@yO1tbm!MWKd|;s1O9=PYzoQQ39IF;&vfD7CD|KzFuN z+PZjJd%U@_imQ@$(^`frtqRhzRa>jRuc~U3&AR9$q>XIWd2;BX0T`?sI$I8^t!v=B zz@Z|ziatCT@zhQn@^L_`#`0cwmGI@$3D)-p6}+YC!*w<=uZSKllu}StE1uS{ZkJJZ zArFS{9a<%hLBZYkL(Y)9A0EBoNi9a_*+LLLIs-afpq0g+fz7A{eJkV8ZUMz(jR#t&peu_&W5xccndGD4r~g%_Sn!iBOwV zeI9w8rD@15_XxkOHzxcx=!E5$G33Q(H1jLm&7m3(KBQql{jm z_IVy?zkfZirbc-M&+`TxCQRKhKC$x_WlKQNG%y2R;-9q091AQ;Kmz%&VB0VgJB6P% zq{XBT@3T}|J~Kx)?c9R1cY^uh40wr&#BD;DwIZ$p2=5{HS0DqbYTFIO0TRmr5qAD*E;+B}3wuP=jt1+d=^kjS|hzZo;)FS!UjAsWXEX zP}pTtTet90phA1FE25RWh=%7^6I2)RCq$lioIFhh%~zep(7Fm06;lDqqaAg3s3?D2RlqJ&eyw&Ue&Hr!bza&)_ zeK6iU8w}i4GXNI`IV(&I9`L%7Y4S$-VRL1LcF6})e(kBNa&4$~GngNcZlmld1-dl= z$3le7FMTIP&G^|lGnw(q*XVOE!TPYW1MnLn+vh9*BYqK169v4%PJma~e)m}~lNixO ze~NeH!JxB;n8ctiA~LzKMI&0tcS_*nC|8+f7Xa$rV8AQ`h!L9)uq}X!z_Y>qy-lP&XLr`rQkm!}r@CwFppBfRdjF zS|OzM_f7sW?iYXn@^&2>4AqymUf$9r4}nKRyM*G6arkv%*+wl^3tKkEQEI>N(Z<;d z=@{8dj|jsXr-z^RVJ!$E;h~%y-l-0{zZPa~%Chd3kQR(~*MdQP%7BwRR})(zXCW?f zCN(bILXX#4;##%lO0(D&VQFp>B<1n&^{*62=jT|!((w4nt4KYi6?5~MR+0AgKds48*m<@FpE@64EwX;Yr#jn?ufBu zweB%S{TyRSYyBWLviO=)#fR{sv&KT@kAy~-qybVCd6eDcdWh)WVR_fMrx#Nn^is_G zy$s%AzV46}6U5OAU%wQY2ahd5@@s0^X+bIY&YfnhC9PH;F0bdHCa&) z2MB>F@W#HcPyqtzZG5~XKrqVTG0UJk!mBqB@(|bVZo+#d_ckA)uO#LeuZ_Cw#R`=AQA{f9z?{?_{CDJCPH7pJ9%!5g@K3fx{nNj99 z_REjy%-Y9Sn2$Ty8Jf3b0L+FQ{Qw`wnsv(azk*EeEZ5G7v z$`%&HjoryeqbRPd2;=rtNbdVR3T+r?)m9L$)b0LfyML|%wQfNy*}w%VZXMgS&xjm( zZ8&!juC1F+s+3rqsem`34mX0hhuoevI37py>Q?eJQY!PhtG|k9^}01fs&2|Pmez`4 zAqxx8jb_{XE>`AspYYx%vG4p?5ZcL{SqS1)1COlYM^Y{XyzWle_t41e_el&`kp%^- zMT`kpm&aaE6j^4rqw)7jK~*Oe3J?a&Z)YtauE}3i@Wk1}#?K&yJyU0#d#0fmh0uIX z>mojv*LJ^W^q%R8JIXt*QpWA((54?OznbfeANJBR!}(y#nb^|&V6#2cV#QRG$xLdm^OE1kyoZe2?4P(;Dhn{m?S96;m6$bz>;pAnP%k~3S^>tU zm`*pZAOiq-Hii#UzyS1LJ53-|!gQ?3XujYiO%-|70Z7^5y(vna-fuaO#gm5J?lONC zd7o@$@#Ird#NlHuP9ZN z99P}ORJe3J9F)!zK6zyUUMSG7W{xuX6kw#FguBA)zA8+6bu7*j?tQhCo8i?2R8z>X zzBRfVrCf7*fFyyh%K*vYb!U5pWHom?x{8{*HgxCEl+%U=}yu<6hNASP?JRJVd z*QP0+J^0!y7hP>|+2q*%My^eC+By2r+7`ur{K>r% zvjV;8b3X((m%IyJ!ST2bB*3@mIj?)-pm5@i`_jsR2xePk@O2qrsELyz8WDC>zYQimS%N;i`{uee$7n9GoEl6w`d9me4E@x3%Hclq@; zF{yfo(QqTan!39(e^KlQ%?G^_e0xWklix$ zdoDVuR{y`r@KL%!+-7^fHx$Ew3t^}}JdO)(^1AyJ-pFu651ujFON%u|7KV&5F&U!H z)PVNoN1KTcg5g3*QQ=jF=l9_J(O%^HsDP9V3^$89^HBk^-Z*Mw`44(WGlm}8@Q(9a z7pFLA(0CL>GkfSz&ZFqZ9(iB9X^=py7(uwnI|!E3WGF#iRbU9LcQg!v^2l$51ct%7 z{CC>K8e0v3;sx7Y7sXcOj|^r|3>q2C4CEc{dkqF-CF2I*<*q#QTEU~|sl1AOLl0}% z?WMNA-#Z$=Z~UJBh`;abJo|%92jN<)fHdq;xHT{kmm$dn(0T%m8-XhZM_9xz=^yuXSN!n&Qo_+FaFGL;@np9J6Ic7|F zR%d@NZ_6>G3_i#cnj-U}oN`OTvomhc^iCsZH{QVDCxTDn@%9;kINQE3Wl3TPpD+CD z?E(#8&TKUBy3#Izpn-InO4+GY#tt2;sUnYi;!)wwxaj&c{NtAAyKJvdHU>^ik>v@WX(pL&-qP_`L2HeG;h5YI5R=kbfSxa} zjcC!l&h0QVGFS}yC-|C<1F8M)^I&A*cIyX)+MVe!6u-k#Z4Bzf11P-OC_67JsNRc$m?!>qB_0-L00DI;7A{3ci^c z316rPokqS0=mQut$RkVD_|-SvgU5uG?`GgTgdOj0Es841YvJIX?i`EEvcni_cRack zbnRH1ntU8S&K9g@ymT`5()4yC?V@O~zL+hyD^eK;k*~h#=bEmY293!*~;tGfppN04i@PlvV2SJ>a54jZ&z2%Pz_`=h>Z(1u-5qllnz<9)- z2R8-WtK;CgG`L^DT?aP+E)&v;OVB|+xNpEs%K&-`{9nL9i|D6x#HuGCRtxC~;C|AB zF-Rsnzs@H4a9}auSa6}>l;99L*!zAAKFBsGv1)dCu5sqmSrf7*P0&A*Jt=F_q^u=5 z%W{#R`XD)L|3ipv0!O+be=WDdUNd5MJ%ZSyixInH$w>aa%Mkky;js_K7W}jl<__-k zQf*bCqDV}KRFV9PB{HRPS(dy14zJ;oVRcJ zDXS-@tVaH8@7n+r@W}GH4I}xRAiP+}{BV(M?{&Ww3vYawBADN2gfBjfVAp}H3z|q4 s=DZ&*{Qlv1D*i)Z^hX-}|IA{t;WByN3Sbtn2TBJ3`va|$W0x5N0OUmc3jhEB delta 22011 zcma&O33yY*`Zzpu&Pj5*(4-qp_be@Rg>*s6qNGWCx&$nn%BBR1dJvT&crA(~Wzixo zg~Qd_x`S5)g|^UpDOg)Yy)IXO3DA3i!ljB5XhBbCA*V^3eD9=q@9+QppYM6TJkMn2 zoY~%aXXc%Eo73_G)$jw=a*o24LNAqVi>pN1IE!G?o*Hk7tBkAIVM;xP#E@Ym&hjF0 z#c1h^U~V}vrof6{{0Y$>VCn9=m0xiX>J zT-j7j-9-5bD@~Q>9!%g(;=cK|1Zx7n3y<_9@GAH(gi*eMMtWvIY!>Cv*fa|i95R}M z<(QG4J1Ro?28gFXY!WFd)LIx!VMswskdtT8=@P64sHYPZlu4v1QkN2oD0PnC!6p6|EA!A-7bf6QB^AoI8OHEkLM7Cq^3SwL4RI2L3%!RU*`M!$4wLkWZ+=2i%&?XNPUl9GDy+m4@3;QGHI_jI+9y%wS z%jUy6lDJGOZb0Iol*!{pB;FzXOQF?}+V9`|=aYKTX#PU_IFGbd1BfDR6ha$(5=V=HO5 z)lA=9X*R)z7NArl032Bnrb)0Oag`V8lohlFi7UN&*lRYkS?n|Gt)iZc_rbraV1AfB z)Mx(*W%aQz64?E05{Z97eGG%r-U~tO;}D|T?Rva_6~}M^&phG1kZ9qhkQjU?q>>dO zmP8(cP^XK_{6tHa!>EUIpp6U&_ID8b-4i&AZD$=+R;VMPx#i*eoyR}rSg zzYjC|0&4+}vr8`+csruS^TSydHN0W0n)3H-NDTGu;Zw?c`Q=tDF7qYA=mxzB@SgwFCqA1a{!C`hq3sKS0=Vfj6S5C zR7vv5f>ozU@?d;O!s0~Vh^v5KirQSLO9hkgF@#1y() zVttztJDf-+3#A1-sn&qZQZ-cc;7Tpp%>cw_B@IWlkST9%MC>oZiilMC{o@cj^p5a+ z#031I@JWQ8ni3(LjJQiaC4x+da8Nrw^bRd94|x9R54DJFpsMyB&GKH?xMXxx$(&xX?-{`x+9Xp~TO<;Z4Pm zi^TWgsW;f7Z5YOv*wT4Ld;xV$i9&4dRZkVeMQ}e{Mf%?dBVQ0S^)WW|-bD%3o#M_( zXfD#6k&p^cDT4jkXd2h6;=5r5AgQoY#-R+(8EAU}w#gbX3{CIDxzYU5E}V{MWE!vW9N{y12$v?vTSI^EL&&yW6cjwa)I6;Hv2Ph8P_ zM8#4RZAH2;9so!5z^Qd@1Jz2Vml9tKd;{I@cFmP^21aNox7_POXn8Ss0;pq|I!jiLsElQmbe~$#* zM25pbi%#x(ApfCk9k$M8>yvxJ>7$=DSX;As4R`6G)x7>;q~Eg= ziAx06_<128`86F2%PH{#p*SuZuMr-P(-%DFe;yVy%II;bG?dsqf-?3vu%2G`gDc=U z;mfRj7qE{8A4cN8g%fdRwa%}DRSYeU)t?aXyyb)4S1+`Tj}h|KF?hdF zrk+Dxh!b8@=ip<)3H6=0S-|nJ@yAAGO{BeRj-PhOb^+J4_NOhyFt%5O$?*%So*0!i z_uf9IyGISsgVy)1tEMb)O=eNGC-DK#-^rwkQNx{ARK|eEaf~brwwQw^DPcMN zPNb2M{kTOVe4CJr>jhWB)Nw2h6i_G@L3}V&i{G{3P6;9EVp6PbE)Vakr1~ zT;%jng`%|Ft726wcW-5C#cbT(m#8?zW(yPTC)3~`XAsrIKJ=8J& zIMUp3q3j`N7@W3lN5FG^6lGj@UUp667Qyy9FN{l>V!JphlG(+UZk;F|5z_-E|I_L0@*-BUSYk)pv7LVYcKE) zG7Du>wJ(tJRSduu?nQe2(_}LD3SViKj++g97u{m$R6<2g$koQ>{>_hpa8{TU@TSmv z*(HbA0Q>7_I7y7K0BV6cH$(Uuf=pPejZ5DMy|C?!m^{LWi4fvP##z+7x+5Ie!$f{v z2hu3SZ-q~^sklS(w93WYVZp2AaJ5jZTTB&tg*SEisU^P7 zE36TV8$Tr?>F=L?@^4^LQBiy7>~vl(9u}_aW?+|)sh`YH;$E+?On(O>7bi->Yx+B= zI-BsL{$0q3_XAEiwUIjxK5G*-Xox^OmaGVT#V()HBiX@@7Jk6>8{6B0fo zWKX=GiX0YRoOs8*vBP~2WdM*j{r`4tmF`vj4#!h0`qZUr|8n(i$%_1*5eex?Dv~49 z=J!lLUex~8YI#K#_vc`KKCDM|$5`46JXlfZ;)%le42^oTbVQnONRZ2Wj!1J2iE^q( z!!cs9B;1`b2@Z_DC$O01)2so8P}rU^4c7`MGUioe`p3AEfz?e1=&c15^9Gd}v8(E>QP*&Mf% z0Y1+79%5$;+cTezEIb^|t;8`^zb>A{#GXD#M+uQxxii=b+O49nKAabfdUKdn?9_64 z?w_zEP#9}O(qJHoWsQC94U)P$`tGX!*>RnVvzfTl2WXY>Tvpy4vdS$+q>1Fi%m860 z3L$k0Mo1mYhR_Y))|&chop}@CmwM&6C*b+AE8uyhOZX*gVfhPc|Hf}y<(axOa0Yp? zJJ0BB#pxe&;a=Hbyyif$uGLzgE)hHPxT`Mu=B{0NRKdFiW_`_+fdXWOmo(LX6q^ud9 zZ^76ZXoGDxiW(%h$Sc*L4A>6P&w@kU*P%NQg{|7a}G_>4+2*e+*b24HlDu z(5qY3aQ?5&Es9D|P`It8lhT#x)U7Kzv&g`l5sax|rqzhGitVyZnySa~z+&K- z%_ytD@pb*el){oDzFR}wrf4(p|HA!~6)Ebw*)DT`$-04grJI;dGLe?8#5i})Vudqm zPA)HOot!lp57-&%yx57;esrbr*pOr$0<@~g@_;~qlG-CyDY$U%fsU|ElZDaA)9!2S ztlsoV!kWS7qfu`4pF%HOsy|>-oFDHj*wCw>d#X1P{ZjRxw42nHN_=wBK+>+Zwt+oL z_FQZw)~om(MjD3mtt*+k?kd=x#pMB46kihXJR00n_S4WW<~ zvT~;js@x=bO}h+05gK#SsLWB}vz!DRE}YFVD1w_n6()RVSi+6^4cs6wO0Nd`fnF#P zFmGK5Z4WS@8Zix_CyAaZN-@$yFiJ39)NbAchlPB4551|dVkus_D4EIcA(JS~o}?5Kx$wF!e%u-T~Zr$FDfMtmF&yMSllHcx|q zhYYTWfak*iwJEwHR5KqhSfn39pb%&-HXBIY3tXw5yJvv$nGV(pCuGPrvm0QlCv5DogCYn1b$EO3H zbHbMVJ8gd+8B+zpn)mbsBp}MvDu&Z_m^VE*xS2MSy4rx}tgm|08hEb$(^AFF(^`%S zp07Y!KKo`IN-Kmuft@Lf<_l(zsZ9eOdbE#Mx6-_p>*X8E{QBIgi_({NGyypB&?+%0 zR=hVx$7y0TO)Fq9BxNO7`GLXC)^P5d@{0Ix-;+L=hh6KpmF1P(W=}E&%31!2J&Vr z!~h16kt$n1y`ZW;8uX*a1^Uf02jh+nE<2;Iq;Jor-BMEDZYi#N;-(dwe%>^@Uoo+` zpVsb{#y6PyBXmmd3sP8{(!1H;;SN`3oKfCjLYGLH;&47;6B=2Ru7RkbbZ9fPo5X6Xas598bz~P?N?v(442Iv-iapLhN=#YwKD5g*3>gGVL^qDx_Keor{{B=8O~rO083n3U#LJDuDL%vI@+qS=w6IAehL~B3|iXF z>-3v9xdx#H>QKjJ?Zzr-bM&AH&)$QJKxttcx^)m|*@gxW?!T3(`6o_KvQprZh9_{QE}i-jXp6D@IWA%p&b=3 zS;B!c-BC&RGbqVO^&>D0fHKOSPDk{-V0oc3nUCUQjk)1Q@gqA(klL-4iQy>QW)z$4 z)wHr_lf`zs$R}+m*C>Y6kwP0Qo7=!BBK~YgIjVCTDzSFMoM=9S8zU{Fo@Cz@UeikP z^H+toW^xT>T3Kk%+KO+2QlX2d`MUf^q|Funy(}TJm2_UgPl+5 z9tG<8Jfxo8_@QKbpoLKNXV;TPG})B12r3*LP14gowy_Zk5mH+Z@m-cA6B0}70-lM$ z+>9x*&M0t?ijTA|Wi|OrTxh~YsoQ>0I`b}&*OuQEQ+ulVx%kBrTLaoTL#k0yB=%ta zcrkz~B-YR@MH;f5v<k4v0GxR1c*m6{jo0 zdPvS6026WZ-cdG~_c$weWBKRKIM>+1z2qbVK`msv1w5@Iy{?N2)H4Qfj4KA%I2&+3 z#?X-#iI7!t`jL~5kkvm(t_Jdv%8m%RC1kfsw1!oQi2Y5muIKT}s{ZnX$1O1Kor(N- z9_yA!AvKhjy^(K1yVPB99MY-AI3QbCnCU>x%f0m@N!khhw0yZG#ftTnQi#p)fCc-) z^VHmujn+J}p{kseC{lB?A^-=gy!TlIX@e#Ta3Y6inRkI@2{5>ds3q&;H`dFedM-+{ zKVLIg8rih*Jm?T9Q5msjkOp034KnsesQv-(;@3B=pAOh#Np}XHT+w4HM+0HNX-xO3 z^fvOc2>43eZ0SJFGs+2cMHW&Z#TxKrdhNk#kF!Lv7v@e1+v41K8M>jUtkVEcyw~X> zN6uSb*X5$^{`wjG9SQ1^gQk65lekpx^HMS7t@G|n40vAhPTO8z@}b1qdoSxOOK&e) zn{BA)U@DLnKou}2KVD9p!)j&jSQPLq^8R@^)_}4@d$Viopv;;7yZvvi1;l%Vzyi>S7JvaHW0Me4d@)FWqu@cFI zu-T-6n)VD~>I{u74QW%$Z?y$H71C3hoF_*-r2#Fc=SRGo;PG>P^glR6Jftqov2s2zS4{+|l|KRNtL6`YZQSHQe5^dti9)?J|HvG{jX zP#nzxe-u$A8pBPJH4$k|R=>{v@E7Z;rzoyl%E1vn%p~RCw^H>GHNe~ z5Qw??gbfnL8yGB%)XiPg5^F{N38_y*{(lMnUkUzS3;v72{~?XvGcVxxR0pO7xyFDt z$to6@rE9az(mxxK(V>G^n<@Y-Ej__Xl(U9m-{?2lR&NE5AS5)yx~qamXn!GU@>c#5{!$4=1}i0yDz z9<+B45{cn!*vmp+_IMeUX%ycQGH2Z%w#LB>84IA;tjC0%vlb{y9PKxaYs|vHtW2BX z%m=bbJ+v8TuCvBCF3F;L7%`lw>aVAj8phpHLW|+_X^D+#G%CFGptc|3F!PrZTX?dK z=q(YTP<(;XE^^V@dqLO-M*z)pE~J0mh4p`SQR$z%==3g^z8}#)26ay^*J(g#H_(j4 zuD~@)UL^>|TryZ=95wWwaLzahuN6XypH@efR1LlVq?)T~|3?DSCUf-7_y2^%XM93q zap6799f4~q%T!RD%edLC_#-5KJPa1=jMH66Go}n=#P_@?BOGjNjMxoK7HkWm!4=Uk z4Vz@}yvL>C`d!3IOo4_Wtb+mdx7HM=Kq}b)6}9E?EK@3;J{|bZI~)pkoGe{b$_|+f zXNblxH_(35t}Hl7XyX$B`2bRFUBw*M@q76FrmRyx^MZ8`FT7@+P*oVH=Gj8R#+QIB zM5^k+3?p@>gJ@>pa^Tq#IPQwl{KJ*R{osmj$2$X_w*y2W0?KyKopYeFBsR~$HDXG3 z2_YptVfDoJt9rL=#B)`+TJnJwd^|v*ghdPjP%Nq`QyxiemmgRF=5)N17HF|X_@p!$ zpAo(<&BWgeH%n(kc1w?~8fpD))e)1zNlZWg5{kLR)Vsk%GVa`;B@ToNirxk>Fi?Jm zUuhy`jtS3lvuxjk{tt+$l*!>HdLP)QhGn4KLE44A!ZWF4>O_wBr(w3ocoSQtZMgX;*YeuD~^+ygVa(TNzLo2w@AsX836MmZ~%HHMkFD z`J6Rnrj$qt&!8kc3uO<(Ga2fx*3gnLPR-#00d()63$LNMkiKXMhlB4y7|L)v7bV~# zRc9Cn@3K*r&|MyrMwQ@cG^c78ObQ1ySw&0Of^s}g!GxTEF?bqw3Af7cvW<}KxvHit zwH>z7N3^&W3>_bLQH{iUbic&-K-*9pI$Ot^Izs1!-W>+Ig&cc3z=8F8E0BV^dn9JY zansFH=F-8Fjb(1vQ6);N2bU}o5D-ifE85X6umgj#1&Opo|Iu#Mt1XNTESnc3Yl{Gy z3BvXxQL*)yJ6*{-Z~-Og`FSwYc*u`K5&LBj7gC6Qcem)n6RhU)I(j&eucvy_%I z$K2V31Kryel3jI14IW`pU6fBTwOq8bluv$#qVJeHSDERs z9djF${mya`vs5$S?*JtbFit!7yGubdtUVLz)`XT1p+(ERFM3HcY?plEG515t;WnfA zq8;az582DVZ9}>pedQv>mWvE~&Q&h5?7!e&#h!K@y@_ncP91YUqs#@c)+@8%|50U{ zGh@ikr+VvcQu&aE|J-%VouyPcNe4>-p_D`4f9dJJf(7csE&_21_kgKftY<%ga+8#2 zg5`|jx-HOo?H+jdm@*9BA)C4jK;>^Y4K1VE-H^)%bM0&X$VIi#G346$Z7vvpjgsoh z03gO*qT0=_{qBcg?Dc1lxvOD9KB)^8FVYJ@0y|T8mV3vtSYi$k9I;(Z907PP7t=Kj zIH^D$7z0NX+?zigb3d%K4gKj*CvE45*6MTjz!-IpmULNdCP+Ky{f7!pf-Z%Ju3 z5OhK)oMm#TMM`OMszJ{X4txLt)s-eRS`1f~0K$+mri;1q%6-qPD9fuYO4yaz-++3P=F3gP;xcOqD z(px`>vT5P3wyx~{fps!HE+DWYSoI&aK9dw(a@cgF>sA7qpcX@viOvEprVqbSp7MDc z-uayiH!n~5w+l@??^25@rMe3jxLgDejL=ZVG~*dMIPq=)K2o^B=0*%Kx*P>A>zQ&lIR&S;lMyBjhi-@1k=o}@7#!%HIeE$ zT?YNBWsfGkSjz0u@oDGiHv(q55l=g6I@6`(2xtn&h9sGD5_E$JXm8=>u_w4f21=y2ufuewIw z2Tvdf5(Ly82tbo64VRah(nV%mFRJL5Neng6WIcc91!@XtDnm&-jb-o)2>yFn~0rvFxYI zxQPHgzx2hfi2Vlb{E|>N4z2HslA@Cc#b_-1dvKDl6HocdMF60nR<|o#>vZ9~1MW~; z*tcyC*I5ov90!C3w$_Z7C5?g1Q>?Rvll8IgKoN8sguJZObLunGUj`I(VHf!MaVKCZ zin@?Kwj`wlRy6xXDR$mj(s-GGnE3GY(3Eo%EbuE9k{oDdxG9|O)1;1#Q}aYdQfa4GONF8_y+m>A}?*c6mq= zcOk9_e8qHJHpl{YDJ1I{cLF@f>ba2fhWrDia$u6!uJ=o?oiu*63*WPIz(-HzN752O9 z$Zy6l_irjM^{*0XqqO^Un3VR`0y7dRFtB0&>58)-Aj>KRYttLJxdR3)j)JhTjxn?_AFo&dyKF-3$81 zy)E;uslsT{9{?!n?Hp?8O$6Dp*$hr=uU?qXE#**S1@N~26toNC?)omUncKl#cE#TA z4SHIw`ArV6{e3lojp;>RdZgtyF6^NaJcFHf80hXb=N_<|9U4S-p=NTc*|+&NN< z2vk<#zJ+sdDO1SBqmaE|@u}$b)m^z`xJGjbHGPvTmprBxYUXuf) zM`**K>NKw!Yz=s>Ndk3GPUw)-2XbM+BT7QiJ<}H#f#)A7rG}M0;4-bsZ*2*}NA+N> z-*X1u!bmf*6Ny>JaWH=Icug4*)@BF&K9KkgxKk+SFkDt`lsKvkaekpt^dPZ9_~9Pn zNpk(3c!m~z0U`9>{FycFA+u%RiKMHgvPhGYefnCQEprk-(#|V2AP>EEoG9QrfuUBl zN6prQM3LekF6^=y!rS+be|Wq^i@$)0V0(ZTe}m8l!X_i8gV08V6h{2{XwVvoC~(82 z*pK0=M0h3AtJ-6@`I26xZ6*JBnu+`uFyQJWwcM@J`STHQ{oWcNB)^4Iwtgp}n!`lPbH{fQJNFGPxduZs z4@(nUiGCbqBQbk3(tt;HK-M4wHsc0J=#0oovS#fJRrZxL_n>h_8etKUF^JLDfzCcYKx*44`l5@`K3jeZ z{+}x!g#V4@qAMvKv<*{eu`a-96%C4g0S^_($sKb3>LN`KfxL*sFYB0QTBK0P#q7x2anz#182Ytu*Z~ghG|A=;LAX7w}I0xBLG^B z7|xNz4$!GLCDumQ6yJ!VDXn53n)r#71OoR7KL_e+3?QWiPQt>b#liqK7{z<)n8MSp zd;n^(TX8O1-=E8*3C22`{v*EOF1#n$X7`#>mA~Vi=*2rY`w#^roFNw7&_9jELgyQZS z-`IhD52Koo1A9-XzUWjmQ^EWzkdMTpcB)woJw0yoFXj{tL|yUAsM7U+Hq{wyYR~^? zQzwE=3D8uN!YICKXS30bm+Yk3*Z$LL$0!+?k+xkX3vEBtc*X&9?f+vL+CB;vu+wXT z1;AY=<57p=qZkb>X82_sqm?(vVYR+Cn#qw>yNi?tGs2?FE1|i^q4a{@ui8>_=bjFLhI?Fl1(rB9LyeRE%Atg%t!@?GGVD-8%I#%K0 z=%UhDL$4l$l^RV}>exD6GJ4_HvAsBFRBTB8os{2m6&#xwP?4O6 zHIW2s<_yH^Va7HS# zSLsD?{(O9w5dFZkcm)W#+||%0WHgfODnSRp9JNDTJ5vL>pJ73{sr(yU&NFqH!-bpUXUu$FKTSd8qd zY2N}WcQONNP?loxLqB0sm?yFx)duh4*&yOO^HFB0nb<&kRt)YfU-yRf=mg%cv+ zDH7cLL~Ix0S7qjcvo3MaZKe5UKInG<%gzo<8oDn-`mj2*rh-3F|Gk~&6IZE)<*SPE z!@_&3^tQJ@gM6)>2e0hU0@sM^6vKhv4@dw?*=ec4 zklm{1vMRsP8ezbVw>?_Nmco-f(iUu2@onHut}Zz;oUhqGK!;v>85a-%x4BKQfvFhj zb+5eK7S$%0qMWg|_MiRrWjNNl zao&TgbK59M)}7FX3x3|#+(tSPf~}qcZ@}b|DRpbaMA-osN@v^+A?IPoyBg_~A%yOKO7^{JY z+Aq??-+bGczxg)erLH|9>AGKSd;cY+_ob1jw%w(P&K0(o-hU|skhBwggx_C{V1vzn zw4p36h_1aOM3wR)bbJvUv)=;lh`6qg`R#*B$<%lD!|aYNd;Z$-uy-|4s~XBs z##@dbTs7eLPB19cJQlCOx7tQMyM4mUbxF46T{WG>t=+3lFKu~gjObtoOlTKT)oP!>hsm@m6SR<;@xIW`8YHpn=)M30u zLmUY)hFEkid6;Y)xV9|5ZC@ZQNsY9=QNPpPyg^W{1)~J+fiJzFJ3>jtF~K8>zGr;qvMtX2kPM zK+rwbP?+g0=2520(f35ab6)_EWWX~3L56>WJWK@bt^7F7&S@XA@J8*MRvxy~l@Z~W z$8zwqLgeFfsQn{?_3;eq&m+Q%k58bs4-0LN=ci0vh1i|27PXHdb}G=HSdQfqxK$hi zn`VJmpq`k74+?ot)Y(4u{w*klt@0lxHbYs9i&P^AfRfuKG2QbvytZL>KhAM(aDacs zE{Sg7`tgK@+Q?dCf5@aW()ziPqLop4U-8?V3qZI1%8-194A`b0>_m-2e{Y`t(CiL3 zrJUgCaMQ{h_{X4C`pllgBe8K93CcCawid7%x`@?%OD4Q681}djSW{oIFZaIUHp0#^ z27Ytd;mtOCHs2^M)Fgm(^FJ<}xzPzv2Ao~%JR`knc(arO;`V0gS|`d`<0SQd8ijln zNu>sm=C7{0%<5nbl)e0a*HD(;1639{v-zYN;M{YBzBLK9H%raVMbeVV3Qacf+(#uw z(`0Xyv zEc+|eNV?sl+8H6z5hS->TGWTK_c^fUI^>7n&SxPeHM8GzP@11$N;HUv{|C@R!5d73 zGQ8T7rXy0l4A}2cPZ3<-Sf{ZqhI?#99dIE|rf8jM{X;QV9e zz9({%xNL;5PytVfGw_mNy}673QpuvrQl2LH_`^ z%^<(i3y!kL>sd9L0Z*q#Wnlg!rEA*5IVK|;^o2-_)zZnSD0WT;43Yr@=KD$U+!hn% zrl^=+Bck<`p}MBKO;aQ9qxFo&QWK(QYj)IpQ&ZC!GUpdp$ef=c^tpap1{y*MCsBHd zdh8i>eyD!`QX4~U%*PSW>U3Kb6gDS7gT!wQaX z{h-zkP9hy6Wl}n->A-jHseQ{NJ68nYzcaE%9FIc#?t`2WZ~^lCDfym;&m`EQ+iLNh zij!7;#8U_71#y<}dX&cwp_&QR{F%ju64hNu)Og3cRbVb4Z$>VJc>X z(GB-eF0XL!Gn=tnIQz`&GQw}Ggr}ZO#b)8p&)yIBDhHp{!kxj`jnCm$LD)Dobe~t= z$hVGo_6-ZCH=2^4A9lek%NTN@G?w`p2sgt$-!cvqW=Q;#Q1F}&8ZUCdIjrPBX0oGfn{j&bl@CkSf}<8=ejpX zRjq5paM_@XngmWM4FwlwLoa(kVbXFq#GM2DJZVpsLZ8#X@_!+4(REf*=MA(bS?6-! zO6p>`NDgBddDPS6h1;|=xybymwR(mA!M#$6{mZLzeYk!r_&&VTiqZ+i8grrkR*EUU z=$f6z_~g3{g+If*urhKog~7>mCpX{{+qVVp5GHeY7r65Kn3SkqdOv=H_?F%wyi=EG z`vv@-Wq^_*xP1}ubU+D^DFM{gAmNc3OOH5rQg|sH4CicpVnJbpHASaLI0d>U0_XlT5>Jm1OG-{Ezstt!i6nnSkl_9 zHatamZ|fA0L;tn4Iy@A_cnzmtIqd213*5Gh@i+Yc-Q{CfS|rcIBjn<+(6lWETZKd0 zCTeGbBRr$i0E_W5=qF#6u;FEi(qLiO^Aq4*^2`)G+X}EKWIsQJIxr$U`24-bL0F5| z+um)ZY~kQ{m9O%7-u9DwwS)o92V}f3{GJU=CUD7%2-uQm#%CmVjYy%I&b@GlP_RFr zB*eT>Xro6`D{$cx)(HM9DcqjYkpat5=FjOfKr=|clV7UFJ&}A~#~xG6`A9yqGqfa$#hH1pm7gLhi5J7pDQCC&7H zY#qB>7xc&~t}B9jjy3HOpeDAoHu32knt-P_S@nE$YcrUG(S@2$0@C?WJ=|Sv;_LX( zk|wK}=d9geBprYQMquh^VooTo&!iZy@L0VXUlq31=h^)5DU!go=@#%pH_O4vWha+J zxcd74TYyr4iE7xh-&$Dd6|4B(|6W$61LnAZp&} z=P(ynNqDPsa7fFw!=95qBY@xr32vDR=~FZJtc(H|E+5=$t8ayOR+Rg-W1+MRK&S=~ zx?OUZ=3&p@e3xN&hsw!qNm_m_xY}o#l*kCd_E9|?w%;|)Am_ov5u)uN?pbW5Qo~x< ziUjz+!4j+F=^KV?XgVeMS&~!2yyz}HH?-45pg#DuIzaHT1+5>~2O*Cn0@ zN1U3@Vb48*n=Z-{3PVu?<4GND0R<#EQ0stVDmksKgWS}Vs(ha0Pop|~KrYpN)NKc~ z{h+ozVt)_(n0%fGeD_K0$M=+mpJ7hI6)})-;BtU86JnodJx~g0%i3& z)A`nQ);~arCZHIOyJm97T_(`dVQ>~TTTi-3%Rj?qUJ^eFH(*i5tf7YwP2={vl`Q4) z#0927RVjte~?Hw!gF(mk5_$${m;MSAZ9&3eFOrXN!>havV++ro3#? zT=43GMk{38*b&=@(yzI^z_3Uz!ixAjKYE3CU!G6F9pa&v=YkYg`pPHx31RS+(ya7X z5qtBMG54|)U^6-au+bLUN?W#Ak)AxEu7{vZ*h1mKS09V4h7VQvJQIOHs#@_IKF?I) z;;YYr-tPW}OhxTcw%z9`7G7@9Caye+bjBO8kw{#ARBV5N-_}B0-p2E2@&e)8hRHZf z7;c!i2t+68qHD$~lZ%A)UG5l5bGSA2p$ z0w1!~=+A!7y>Qscd&%;}jl^erjK}kNevpK}?7TO#2>4&NT?QYh0WCFnhxd5LHrwc@ zs0(i)N)K|^(dU^ir0<#LDh|CR+U>;;MGy8sImZW)&eDxuu=5=Sn{Y_Y#+isQ=8ws|+-FtvUGnzJ-7 z5_cM3HyZnK_-uDp>e{~g^^I%_tH*QDZ-vlU>HP`ulB7ku>03hKBhkgDLZFqz)sQ~V> z6|=tZ!5t>W*$wJ&0E9Y8j6PTGTe)u&_O!M7{9=Sp6$t>Bus$TcTdKGX1atKXy&r(IxO1@73+;O$8uict(+AAN@dBX>j z%o=aF2Ycm%RsAt{YrWy_RPzi1!f>j0D}WGBKqwCJvECO;ZIoAj13^*t>2JzkK9ySZ-Idf8n1 z>&c@7RKzOa2XN6v7t5V=S-F>8bzFz*VeToHfva?V?54t}l|;M9x=Dk>o$Pr9Xi8P> zCJj5=>$&a&id1dZ=&fFl%U7cDdVYbAe9)D8xV-_KVV525-jh$Bf!0-nL|Yr2Zp2>G z%P%q`@g4Xi-~YgOOThhIYzJ*WF{zQ$@dtR{K8&D36a0_mZwJTiaB__}_*u6Eem>j> z4uMYtk`KAD6*~A*o^D7L{AAgGKkY_M0njvV3A>r+y&rF&7Z&nxa!oIyFL48{S^TB_XZIeSc)-k3st zdrVl;n4)g?+2I8KyiE=_hglHdTaU@0%zmHH(5QK&5bo$8gVYWei0?KBzw4H7$%n7k z(Kl_;^vz8RnkfO+#Jk=}Q01-Qe-nIeyVAhUgtQB!bVIyZW{HRKehwDQqE6yz;&ZKs0n8QZnqsN1B%!e>E53=} zYzjRCAC!#RY?7aqRqo{LOfP}uQYG{@>EY%?peY^yQ%G-4o%%UQgiKI2{0rQ%ae&6A zsB?`N#dtw>gj8Lj=Om+E*Glb+<R3Y|J)SE#)*aAr>taxWU)(N%m9G!mw zZp}~#ArjNKV>w3Xb9h$3Gl^Mv?u0n>c76yvlk#D=pTlp*H!)oCWz1z;&KY&OvM>i6KCXNCxj0PX_Sd{V2S1 zPD1P{h|d}h|NFgs%n&2d8{o^qapl3W z{P>6dp8-3MlY5tlyH@5iaBR&3>MR7h2}sWe4x9G_u_X|D1F*l=?h0|y9$WEMkd)na|sVut^3fK@ezZ#@G?cO682GLW4=*>`C) z>w~xd>lr6+T&g;`U?I!oYfFVVa)3ivKqFKpCoUA7%(_gS>CckMddrj;B_;7v- diff --git a/boards/modalai/fc-v2/extras/modalai_fc-v2_bootloader.bin b/boards/modalai/fc-v2/extras/modalai_fc-v2_bootloader.bin index c80dba5421af4f096554e4f4240ff2f8727ed3b5..8675496c4ad19e30819220007ed8f5ce2b21525d 100755 GIT binary patch delta 22047 zcmagG30zah7C1a}?@e;UB4JU(BHSdPKtRKyVy!hKaM`rDwy0HuXkVyp#ig&dwI--- zQM*vD?NjOE(#2L=1*H`&LaTP~dx^?>DD{=r)+lIuBVaBGknc>e@4f%G{J#8tlbJhn zX6D?PGc#wK+v}uuo~Mpprf`+eLFsMrCGmxq<35j%h|!8PwcAwFg0x73#CHdxOJe>X zC8LUvxY>uq*nT9=_abp^e@jp4D=j^%UMUqjbr+=C30e_TXCS^H?Yx`bIpI$jBz`e~ z#89Z`96&93BT*u2!zht~fDlSl9YkzZ@us8aC6uk}wd>5i_N*@;{b&gma2?X4o^R|V zHujvcKU{J_QYUJAtCnfSFv=vd(5X7{f)odNoy$z35uW4z``l|^Hv9~A#43O% z2Rc(H?*O38Vy!0JazRo7stUlJ21r%nSZG9*NQpU=I3x|;a2=kS;zBLRNR>$wUPTc`BbrLliU}0PHEat)9GatQOrC)_ti1@e z%r+6zXCaYTazj9(${ zg}66c)ja$L$c|?J<&U8*g#6f#kxKYc#@R-dj4pc6N* zIzs5bHf-q$uQ^rEaE8y2c>jsn^?1rH7fSuZ0rb39Q4AEFgLOAtDE*oP-e@fq$mw($ zKC3Dq!^Scw@sFPHO-N_g{L!P@yylZ?Xm4|mszy=dlu&FAsq{HCf;3D?wEaTEW+?W1 z-h(k0UY36{l`KT0g{grh7?lpw2U8Z6{^t^`Dwy0DG&6+PTZ5b8_!JASMPi?nV#T|V z_`I-Lq2Y!XayBepLbTb?N)5D91vFQaURB_~DV$Xtx3P@`j4LV?{f0$WS`4EX#?kH^ zU3pd=%9WVl?Ixd-K&XpgTE~=%_6(r^F|Y(7aAW4;$YR=UG1Gm^%_fP76#!aQg0!ll zU@pdj#N%G19Z^JcNIc?&R7~^^LuvtX`Na- zxk&e`yIGLk?r%3isKN$odXg;|n{iOD$M@Xdo6|*6odf{}{-Z z2^T^lZF>geN`mW=nCXj!SRpq0Vgk>0KNjEU$KumInfQ{#=#+)}DpF4d7$9+qBoD+# zBrJ{_7;t4-7oi4N{A!qo;}CjbKsBL=RYCeJgzq67h0qG&FocOwh&4Zl*q@W*$b_Lp zzh{A8R${#Kv}w5p?PLJOOA^OZN6C7Gjh{6NFNG$^ibf!ImQWu$4lfWch3Y6xm@pK2 zABpZ8!O=BCi-htKtMEsHb3_9EPH>M%342dU=H*ALnmPVAD-xd+Qo>fueWRa=zo!H8 zMOu!;c6bWuc%gm{KZQ?*Y5K^^#LJ)*wizgiy!>E2Nx#>x>CEJ32Ous&{_mF$twega zBO{PAUHCa{jBT&P#CHU0KHE=lZ@w+Ku3bU~JTa#@+*)G_?NC`;VQNQ8*~Ky*CFeW+4KF~gRbnuj(uvc< zttVP=5}uM`GtQMXN9peB5vSZJY=ZOe5;FQ5ezSZFO_B<@?oPv-l7U;m)7;o~6r3dw zuLF9Ua&@~-te_*!j609Ix)~@Lkl!N39mV1UUccw-q0vBxwD>;In(j%z$1zmK)8y4& z!4t9JV^_GfR74@6B}FJB+!A92%n{Xne$8jy%fgrrN<8HM8oJ-v*;u;?xH}g~)Pi5!u^6o7d zi_i7T`O>Z}EK1IEpl&wkpqpin@yxVV3GFQeG#B_7{%BqikF#gN(|F&!ymsM8xH?8X zUjjxW+2NqY`+V5&%u0FQTc%Oxadw{YbNJ{)y|0?byE$Iz#!6a5z8QHA*D7%#YJ>k^ zbl$agKVpT}I5myM8N%cUbJX(#*id8o!-+Y`g@FcW@rES491$1xvP9@z)u`4mKuj*7 zDPl~@u=z6(#Z*hEN3 ztQATk6Ij#9>(C}p`I<;m=!38>{GP*pQaoSyJaP=q6Ml-!#aV(TDrMw|!ABn@^x8Y{ ztC=y#JK0llA#}iKc@-y`^>X9!nvGgBz`;q$C`L(Ky>9aGCXpt0#IZ8 z$xZ5Pf|pu2Hd4dx_2Xm(ztJh2et1-p&UU9ku8(l0tY_SX2)gxK>h)HRzq(?jRrfH` z9axUUhlJ6iW-FVAxTbl9l-MM!9;L^dg*Qj(vR)l}9w-ecDCH`{&B_D8L9liDk zm)~>Fm$H5@Ebgy-a#$W|4x_d37!uD5J)_J~lZLcFz0k5hP=Bo7^R`cTynK{k89fRg z7M>hElRBpsz8sx~|1R{5o`#PI8S0VIe;<_XA#L4s{JdSZBexf={&{mQyw-kUsd{ed zra@U<$K9j1bke$V-ngd*5RsswYfP+HtS z{A{;!21*PPaP$PcLCA=njz1SxN2i3nJ$S3(Ie1%+hoNrSAbb!Vi{BB>MQb9T8pPS` z#Nf0pC*ove4Q}2b^hb}ub;9VF$)WK;`i6Q8EIcKK3X5VA4ARL&0}@x9L^?$y#p7D6 zQNyNp&WHCPom_)Cx!B@EI=n}&p&;Gl6F!W2I(Ctl(E%^OS8PFIu6G!foMr{c1-FIi zv14$PusAjyQ^NMx$M8y_KQ?1|vRB3z)+4t?k@iF~ub!9zL)G9rV)8gGFj>)FhA$(f zGHTrD`^P=O@#<^>vCsD|Ko|jny$fNKp>eAF$F1dfRRE&)KM-v?3hE$21Y6ut}=))is;n2EN|K^gyC6H0S9I6la&!tfeCvh4Qw zzj7h%Fy!9{Z@Dfu!FIkGn4DlFAhM-zTJyQ0{4ll5swXWeVCTKz zU13>kJzzOzy=r;eH4BDdMt@Wh!?)Ix)}R&B*5PKhLNmxci{kjG>>q9*9VLG6MSFsZ zcA9WquXDIrQUwW6sb;uN4WwB9bD<=DYTiU&qV+bc(NJK9jP*mFUVma`RK0G)ArtK! z@(jWrlGB`M?Q{8WMgZx?TFv$0fb`qm&L&kMAzn({eNu>z7$tPZ%R{$$$+*K32Yeku zPka_t>=jfa4X|r0NGOV)`>7Xz(v!l{G|t;XwhA=pG^C6rCoI9JM4 zF+c-pUId3qfal&XjNleluJmG#K5A$VgNiG>#@jfuk}tgzQuPrWh%ZT$5x+)@`-U*= zqD3YJz|8etbIBntg%$S;@E?Uh5f`Bw4+QN2#Fj%~N@A_F<&0Z3m+nKlU<>eLE$xDn z8;9RG*3X^7_zj^^J2~kM0A(8)ag2` zjUMHc@NQUeKos{5g%X&0x!55IOLRPbQg~Olfcm9>M`C8eUwzHjStAxtf5w8W`^V{z z{tY}U%4rOmkz|#N<-+X5sg!R}csX%AGvrz86Iv4|F*32uFL)CtQJ-%YGL!Z~!F8|j z&!kDXT?idJPRUs=YNPof&)dSZu@mqM!ee7~)Pixxc8m?7V1GZ5ypqAkSFnEPUE?i@}gA!HOL+E#KBTjH<9$9=k)-2 ztWJfK&yf<37Yl!+jEso$BTm&EDUJyH!!be^x$LG(IGVx;0aELP_crJX3fsbuJzhE~Um!sTB3yyX+&Fy4>scVHP`(9X}e=ei_HOS@)_ZeE~gMqfNchYLk%8I$D2n~jJAF+?3q1dyE0W~3zbvIa;!^Tus89rAD1 zW0A(V4bGw#zvrbEkd%(5%`1Ff-M8VJdU=Yr9gZq5cBdGf^;q`?AL6AwQ%t9Ml_RNZ zgzVRbzI9|_#c4{++ImZtI!|m);cvL;z8!0Ux5!fHg&FC*?SjOztv#Vcnt*=k4dp$# zG`)^U7q9^kiIE#-DDBV`kr>%Rhs5OM*6T!yZiUpaut?y|kkd!rAKD>uNl6oMD;yR} z`(f_u)o^|cdd?5QCJeGlRU@?iJhU#HdpInQ-f&qS-WELLqQvHOC_>sUN=%uI%Ln;8 zNyM_V&aH$~q*3WW?ZLVO)km1Jj@) zQ<1#ssQe1j(M3#Fkad>{@9_ReGz=hnZ!_GpSXLqjHH=CR^0(e3G9aHKJz2@5eKle& zDxIu2vRqaYUipn2x8bQ?C(R9d{(6d(8$)Si6gea-mY1l?!z;J`55$U7(1wsce$1#} z{JP56rkrNK=LdhkD}^Wf{SSkJWqjJmsz&ohhX1$x-ZpyUeMO7#qOvhewlJ76t}v^Z z-nal$-R4NO)vg$5+g^67fei5WS=>fD_Im_Bw^3h&wLpS7n~WT<>!N5vhO5NKp!9V= zIp|?hnhB3&8#A*F#?ai0)}Diyq+=DnHtohBZgkO|hBGmAt`91RjoX}@v{(+8JLd!5hWG%2I z@FzCPHYSulhPxL48*JWj?8};Y@!5IDeRq2Kjge*|F`2v0n(_G2_p>eLuDrF~v-3AH z8)YIbTaI!1fd#BH0$zeG6RZxMa|)2ER(97g~57O8PWr2;5tNmKAfgYfx;DT@w$R`VA3uVN6cu3>_?oFCgXjj2r5-s_SX1hVQWMDj3qG z-Jf2Hl7Np6Di!0DSJ&yDQ2Jzr2L3CMUC1OsydO{Wd&UgylAbci-Dgo?>ckl|H#u%n zjSVvWo-in!mZ3=3L3RzKt~f`Q5Y`-NMivr9W2uNiX&09q40@obWLPnvdPK?E-l1i% zVv>zo-8NlsRfSGuXx%1Cr(5IqOd2r4npYJ1Jw7RBu!uAF4ihGs9u}sDFt&e^ooOS@pO@o{ zAX*9qS<`Ic1H)=G*nT{1e#r$Rn`_>{fJh|LoZcvIvZKBoPplGoOpdij2T6)?Tae%L z@Ze4ukX1cr=q(WMgy9-aKV^WIhFOV~#fF-DjdOLIDxQrLEnzYT;~oi%2Uv37l+NSQ z=&IvVv`uwfisiz*FAVLJMzyjHqZ&SQhlGu754+8>Wm1}mT9PIq_9qAvAxxe;9JfIn zoiiLX5Ko8DJaITo12}F2uVC7!RLU7IM{T2z={69prEZ;WLx*Bi+fHe{A(?*>HkO5D zONrKX;VgnZ8LKUUNl*6wS;6lCJ-Y54X^8=*s+txPXsl0lQ2G!D(qD9fW*U2msO*Zb^RLcHHeQ6S45vM14DZ2)Vvb-;EWZ=4ij6c5`WBge1VRU8`v zCKB;Y`@?iZ+v{K?P?v#OBzdIq!v?$qr5eSwYRCh~+Tywf0vS<_(jqQzFUFb|XOi73 zng4V58uUp0*R5PVWt~$QRG-4v7HDKaZJUd}4(w>Lm9(vX7w9!@g@c}7`+t!yXnVS3 z%p)=}Oxfg?ht2s>)+do#%RjMxyjw$4^pgb=+9FPx<^m zrR>#cf>C_5`gQ5veJ4S8WfYfH|5Gxoeg>vdq*Z|E!fIpsAztAggATToipJmsuWh>< zzv}ng@xI#~3~T>a@9VJUDQyn_NY5tvc}PDKI8vTjhj+g(Em6TSGZ?3%eaafLeXar+ zvU$!bi8CRwvfA&tJaAW}ex+T3+f>$Y%OaM`EOVi8{LCIjE?9UhW=+*Q#ZT{tm=%yRXzC;hc*B!tcDR8v8sm#4PF(_?HUmdOtCt3-Jx~&D5y48 zN1FG^^4AY*6CF8+`Tv2(BYKL)IO~E@H9p zymP^|;i10}Krh($4;N|hZ~b2g+owj`{?>mm*6(?~f6CUHy!R#6{>e42c+Lh&6e$&K zGDkli=5C3_66p_Ki=N49WbTnb-p};E)<4pK^lV3?6l>7euiSvOgkxH{?zL+xH&9y1 zb%3$;UHB-t7`D18x?Vq=@CusnLa^OUAxj&M;I&^ALgIoI7=XFv-qyJnEGK{azaR5C zjlnZIEgGH%nRi!#3<(5Il%iwLCA&>2SJ?- z7DBKRwo5BF*p|bruUtn2l0PvcZ~aQK)OcPB$kUAX}?%UJ%O|# zJ}N3MYsvEH6^zZjUIxdxF;7%6k5*l5z?qw+hm6Zb8>2|wEEO6bUB9XaL&*WDxaz7C z>Egy2lP)*3N{QvIk|8|KV3#Bge>H4iVG>bJ0bKx` zs>~0z;i$6l#b>4Lva@h}rGr&Cu1sy^vQYAII1OMk;>;2kVwO}7nI(0cU=p24U{dsR ziA8Y$CA>U6#x}Yns&G#^A+?2;1(h+y8qt=k>D_=K=BA0VrC~fGCqe!bPLOW31W)r?Z1Y5iV*KIe^mrxzfLc(nq7|^q@AgnjW;WFVh;{@>1 zIA?rPUDY^Gt>#O6_XE|9;eU;x`}Y5Jz%y}Bn3tP9e|MArrmAEzXq{#JjC%Y5OjSSL zg_19}fSH{mnlwh7>O;vPV3uOUgs{>DCgSmt@M`XBepyOC;3 z307Gmo7)(O+R@!BUUuJc+rNR7?cTlGL08f{}qwgXbCk&s-7Q z53V@=@2<#3a;(4YC%OpGQ)>o1)Buv9vR z`H3)%pKkjSOfpDZC#CRs4}B1c5BJMJdw|4kV0=`<9I%apo*Ec?vNl=JaJ_h%ZO&=L zS}>hx(x5$x(E3EAW84O`qT=k0{46BiD>3d3=&WR)g~Uma{uVpSc5A4o`KT@+fZIp85praY@i)itr%(%UCS?nw3X3| z4#_1%6(-xZ7b12u1oJ$^n&QJHJe890bfoVGgF4Nt8h6wO<*}g6#)ewZVIwWa$5bgh zRT7>-OSlAqV$c|abAVWQ$eW7vKIa`5&ByRKD||gl@j6v8RRyX>Dv#ky;%iN;BT~W% zNW!rw#p8^K8Blm?!0x7M7UmS)7jA*I-C9{ykkAN==>u9^B0u8e!FIgZXfv2wI|#E|wS{;r(AZ3g+Cg zS0qcV015!Y_agC+%_rSSVXOmZQG(tYFgH*7j^9;~^s^x0y?f$FDYe7x04|FS(iZS} z{PeUL?I+#(u=^a55OZPo+8ig{y0Gbv58Vd3qd}=JZSR!b-$MD=oIKIaP(HvN+3x5)A^x0A7rOB?LlrXD6bdITk75Bjq0`ASlDdk>`C{E zu%+G_H<83~MqaNy@0$js-Q1ZcQcRx6Ft&DAp2#w7@ULRdyN>rEThoP;?x(|2p~H1y z@*S`FnhP+;Gd8_NBJ2foK*(qBfF;l5FUDwt1pncK5-$D>h;Fp^6#2V%! zfEpim8K97R@n-0D-8+!;XqeJ@KvviSXfD6oqOBLL`x_Klp~&)|BD9WlW?#MyN~*%B zmPF{7?)!*@NmMoH(x+WMGwq-X@Mxl_8 zYRQE&-=6^sbHL8;`uU{$;V@h8#v?&Iw3lZK(lbEdtgQPuf*LT4#EZZQknQNDw1dmxQ#`^1Jx=x>=>N zo0Y49$}5}hjO5u5n5^JDygRxcs3qEvlIDnUGhyR9cI2mBCX_?op6amSx;^>HmxBOL zTz8~dLbii64D9wEoJqfR8s0R6z3Q^Oi`X&<4?#e! zem``eO6D_C;#)}jI`ENu31U)@jHKQ=?Fuysw0}0`FjimZ>#ds0QN3s>nbD}0e9a2Y zt^zVoOh-ll#Y^(^wr|}iC|xr==LXG5w=yj0$KfXi&<=7N@O~HGLkO%mzotd$&Y_67 zv$MsZc_a@+wf>rx2q`jdSHV}VPSD}uNng5bq$7OdMG%Sx@&%2< zgzFAG{TeLd`1d906HRpBJ-F2yD)l;81}Bu2Fe#0l6G7NC?AQKgh$ zHkyjysk}QECjjQru$JWxGIX?aRu`thL)Fe64$^61o1WOu#QxeqAn;Bkp0KBgI4Cba z0ro-r?c?^m+bRlnz#e561!5cROcBGC(4sd6rW}d3kL?T$(<6BiQgoUDlrC@CQ+r#B zQ$16X;j6JOx5W-P|v0;acyz`jhcmCg3wgo4Oa^*>PSr~cCd^iVI(U%*PsRivy zeSZ5-*J<(oq&)bI%*&g!Po{J;!I!{i2e%>3FD}^M%71cbW%F9>4Xq7*u0(MZ6QoP< zZV8N*EHGLW87(T!!5)6ZMb*Wwe?TAPq=0p$1hX~9s@P$}Fk61l_JQ-i6~VAa!=PXX z41AGF_oM47SYC>HTZ>A2nYC?!c}>y~S{Xj;fRcY>b>F!1c#})Vf6G4z|MOijz4lV< z1RlAQ%IauX>dL(>r((LOu<5-EkMuwrWG5i|pR!vH2i_^0sjuVD?S#yT7PiRYl}{Q{ zIq{^=`F;5*KOXF6(BAwLz$nY}W}L!xS$XmNy5IKl)1X7NRPLtadTUfmnPz=pjsHrz zrDMA2u%8?;pt6y>aiCnU;WW_hQgutZrVEfUXl%gq!3MIc;Coj^{D=>e`8nRrw||6f zH3DRlT?OC#iSfO=3hw*Oz=s8VsnTyq=Ez?3R2(no!}z!s9UM%sT9hNf+3DBy25?Q& z@@C-9p6pkq9_Ob9pp-uvGT+IUNm#$Oo27388xF$C=B992^Js`3G3`zt|zv z&f)$N?$mVsyhdg)XvjhB^ZYu1l1@bq5%B1gsT` z=4rBYpvV<3gLMatrQkM`r)u10isWfW+(c+y3m$plUW(_SA!E zuU~j$ep=8&{hc7w`8{R*!uk34fZtc>1F_Tnp1go7DwTqrNGv~v1M%mlstSgkSBYSP zME@!O&78(Cu<_{EM~Z{ML4Bc6w85SxtaucLTba6cpd3)DML_!;qM zi4org0gMr2fORJV2qShhslf0|v3@^hkCN*Jjo|n(W1ghrwDsg4-;)RbLe+y&L3{f% zbq6c}-XgsCV4Ur6$ty=ul7a`d{H8Hg^lR-B3++8E{UjaVA65^plvPl&17>d0w-P&R zEBH2IjuDsjkE;jIO;FGw@h_VYynL>osbzq>xDDbqBbxe|I?dDs{q=Ude~twDla}Yo z5L*Yqwg9pJc@F|4Z4W8~OiD(@>WJ zBxNu|;K#g)t|QVpEtGfKN_(HK@_Vih$>LjYOVtFZ2gF41{i?RcGs)=o@6|tD2Qemi zM0gZpG|ND-=N}@~Df%ZDqgh&bC-C0`|4Rx*S6mV>X%iXoA&Jq*Yvl+1p6f$t>AlY1 zTsVoeeJ;@U*=o9u25k|oH`>J0)mR6dUNFVM;2Ie5J(%85sSKt!9{jh|rvmwi0hJU? zjp2Yv(+*5rqM7U_;O|NcFfGP=izC-ZHcc;yT_0JMdpm-rH1dOJ+((icWbK1P<6J1I z)m6r)@WE~zOpB8LAFy5+F-XD&n^Bxy&15@WnSfn+U=;pZJrZ1HjpCYWeKd5b+HOL( zAFT$>hYj7fR{tcuadZLyp()DwHPl!Vc%Q}9iA|b-Q8wNhV@U$rcv9YB(?};7CzhV! zB4Z5RToHbcVF;)M)HSWQ&D9X^#jFkDk8(51YHSuhWddU(AS!bA_eHR zyU5@r2Ra*9jgltt#!j+QYGE@YhGRqF5bj+#(v~>`_%pE9*j!E+H!TsQapp5dCbgqswxly`?ixL= z*U3yIL&e-cL9VBB43aEm_`0B;C@e-r>e4B(p-M)9DX1uA^kPK(?BQ}slkVB9n=OOj|P-;nC{&Z(b$u85q&Yz@rjuMFcE?aOgxM+)?4h>gm z8Y;`5-dp=I5OO3Tqxe6R-&dF@@P)xG+V$$>sKJZozO%l z#OnjQF*Ad+Vo@vHcu1q047F%-78;0>Pg%lQ)Yc)eIbm(6TY)(^0WCuMVvTJ}6R8_t zQq_o(*%mclbCeeE^~M&-VXO+l12yNEx`@1$$!j=9i#K7jFcU!p9Fpkx$c~7amAoD> zuk=!NpxEPey(d8HZ=fk*$kROd2q@x`LD{#|Yv5U6$f^MQ_nJz3f6kW81i=&HcA(A{ z@-pN_HUJ{8LkxPhz>Dk`ZYJm-pLf_A>5-Unn!zi2=T9!dqP8sNWWAqo%r@+ zBUibF{C(1T?(YqAa&8t zxZ@Gl5GDhQKeSXeZU(*kLzRqM4VqFcR`_+m#mFy#_OpsSuLfsH;9@ifR&u;X&{*e= zH&;f&NlQ6`@?JFo-vbQhX3$+QSAy5mdfE{K0cW^fL6EP2AiQIpgy#w!)@Sf5!h@Ch z@xKfbc~$Pn<@W;RM8nbG_sIQ$n^vN=u_}id^t=lm zzN>39?;FUqq7;{dxOP71-zm*E;Hg{S|KH%9Bb9EkhVph^v!cXm)VyJ_LWftO{^~UF zYR7A4Qtu84v(_Y2wL`+wYsOOGf4_fCW_6@_%y)HJ~DL71^Rv2Q5UI3oPxsm@bwO`p@xf=ka;!j()wAoHUF%6 z#yNMre5y>3Zhvnl!Y=)7?v#q+3&3Y4I%vJ#fkCm?Vo$RoalwGVtuxtHgM!}$ifget z#ag=_i9NnME|g*vU$+0;V1)6V?f>0nhv(<*plXrkaWPex`-cmsJnMuf1J*y~Y?t;L zc9|$pY3(wtaiX*;C#lyn2<0l0G5{HT;;K$r9;kuzmjA60Zh8Q!%yWWbsp`DzGtl4) z;<^~yE|VFcmT(GA4?M&PX&JZ2zDrup?OFYTOOrCusTiL{TH$I<6P)Jy80*&nyQk(L zz|}ofBP}&* zxSwIfIrJC!UxJpy=^R{bTvcQ}Q}dl2%)^yxxbZ-C0fr|xDs0HTL0QOqJvV?p7DL~2 z9Xq8(5SKa`_s*b;(#~1wO`tWAYQPQ)qy54oR{d6$b@Wzs-tm6mwqmZngtJ;2>KX*o z!4{wbt>)#|8?Io2&wc^b3m6IB(SJyzA*&gWR2bX?peBStKKn@T+>d^62 z@zOR(>X&c>DqSh_6uyU!_TX$AR?fj-Ap1 z!yZM%MPh0V00V!^4S-ca$MNq-3*pHEhID~s2+{6 zT^|%-BOq7Y$Ylh$4H1L|q#O1}-Uic6{E;0}mHmVyH(2yJEfyUTE=n&}tvdEEi8%_K zE`oYn0sgr)pAh)x03KqG4w~Gv$~m5LP0fapVmcPLhxZEjC6I@7>$?LPhCu5jFGvA(}Cx_M>vW0xVXQD6EtqR#9Jy`YG^)M86ZutL=>ood8 z7hn9G4H8?Vr3O}~(pZ7KmK#cYN38`i+gtHG)3*&$mfDI6)1A(WEfQUObqmwCXzhVz z;U#BpjL2sCjB__jvo@WPW`J+$JkwM@q!^2H2M9Yg>}_j7-$~Anx9TgrV`dqt97`i&dJ}qz4TQRL7!WzzTYiL*RBEs05}@ujj}> zGCbWoC<7BJsaMq)!ZXQwSWQTbOQsXYqLDL`fj1b_k3ef1&Hw%o&T>{!nY&D*s-z!L za%q>5Zf~Jm&o~o`T*Pc zfa$jo3L(sdfC{S$Dvy;vS%-t)510p8-shU11FxsN=?JPCTVZWqV8~P5hs1dAD7Ol17!_K`0!I|zZ-ImO zij=&!h9Aw30sSD{fE%oa|M!J+Po?Acgr2A7!g*Zq^vaQCgK}Q1N9hS2o7XpXp9zb- zjKs0RS5ND3s?hy(0-FYRpTL?vBt$%u4EMaIK9geW_q+h6Y$VFgFwEf+(Z9lJON_N@kq8tzbdT(pBfcJzP-jfH>4WCD-_#}I84}XA2;UL{{N0aeP1rzlRsmXITu(}Km`%PKkPGc zk1(b>B|3TVu(iT^$P!tatzh5eX5DmI63KF|Grnx9pVYf+-i za?rZV0ya(I)+UW@D<1{+z{MRAP2@f^+`k&HzJfm>8pu|1F|`BN?XntSf59@sWlnP- z9o*eDOzA8Fh&_X<`c-0x3~r2$f8RRk$_(fy1e`R!KBjP|f#d*R4e6J~)0a8GUL5+j z>tB*OgFY5#nFZeM>Rh0Oe%Pi5Jd?d}=anWmjUTpDl0y=(d1o1?e`* zfs&wGBZzK9GycL?QdI7bt{I7pPrlBO{S!GFk5~nO z6aez$Kr2MN_`2Rd%JUp3P<*c@SPs23zvYxss2^QB9(t>9+ZdgcbwOliX0T+65@ z^_GMuWB3YCtOr}>TH>FSTyw4df1?)C=83zmLA$JJ1`sF$dE`o+PMG<;9uR-(c^lk8 z>wkVC-Y-mep(5md@K1+(F3bBp!G7Vb7m`OkF!bMrQ3V4Q!b_eLK62qjxcx#DZV(hT zqhvd50w)G$5$YdV_scc2#ewh9O`mSzs)ml zpb!wq@$Qr!QXySJ%7NwK?K$w$QG@n+$g`mIbB?Qz=`Fg)S6W(Ka+ukEPv`*ImxJUY z{L}JV0VtYUQU2-+CrpPRhdsZ`H0S(*ZWK)OSxt-hY+l#-w#j$CBlZ;Uyg`|ET0-i- zwfbnMM4C`k-zF zx_pC*c-0aPCXEp8TT80-ZBtBMszrav7xRJo(5zHzv8BMO5V2ya*=!-Tw|L3_Q{LmI z9gYv&ER_Ki<*DyCB{D+vPN2!r9H6M%r>bC(%(ZmZFzz+*^Ur7%w z9aMk^h6+v+pQlfF>6Ou7JbU+*5^knf8!+r4NNVR$ zQC?wr?JV3aG}eBEHwqQ6<}2sF3icZaW}*JoSlMfVl=Icc!k>pPPqB^a-}n=cy0|cW7cCK7q8x+atrlV0S`ne8KwMQDQS2WknO_3sZy% zI8CS&W3_K*|YVf!RhGd=>^2-C%Y5 z$xFB}k7v$jsHNyRvW&>4?(-}XUfnr)a!N6|4{V zcsJdiQ;)q=&lhfRZ-pzhAzo@Aw~HRJ(^%RSSEva&?UU{#cwh9ezEM{p-z@hj+`COd zm*To|#RoZjDl4yx&O<(h=luXQ!yvam%Pt0` zRlg75it6QgRF1JrZu~VCjU7{e(TH^CZXk08tYh(o?Iz_Vln%~&!oOZmu=U%w#FRsK zn0t#y>75RMyZ?%dYV!Y^ppR0G;tu=1?hp(J7XYe5cq|uE@ALF1e39YCE}T2UM~gKk z7Es2RI6hJ5Yrx|4o!!hU0bPI;6+TsXUKh?A;X_03{ba<75TxsU{op-KP*M8S0Tfu@2ta}I z%5Mh;&|uyEd+cJ3y#|KjIr~93#g^v{BhxP`hmpxez7az&12Q&(Hw<3(qvv1Ff8-LC zQ=Vt+VvT!!)Xsg~Bk(@c*Zh0@0~h8x7S|tx^Q#>4uvg*H0wQi>f*D3@H5xlSt}w}T zyOB(>#!L6SYQ*M0$L!efC`<|tF?Y$$(Dj|SOpKT6g|V=~&_nk*6VAV7N{8+%^6Fx@ z!Yq64D14)`fF^R~z7aj!?+!4~M9!%5+f7lIsQb$EzKP+x5TD~3PrS5Ta{lTyH7{K& z$^YPdQ#Zvf?+zJ(a}Kz8@R#QJov=|kT@L;k7d5p!FVkh>9}9B+qNWC6VW|@DVfM^8#N@gRc*8Nc^l{4tETmuIjLs znUVMbd~NR%d`N^?=UbXk3o-AJ^X^}e-_nl&{vG%qE*HQVJj@2yzQ~8_fYF7Rr02jL zVgwSqD)6L*PuOXDRqzbr!GAt%r|q=|asYL3bSED@BcJ&~79{4tXSlFsxP#1-r0dT> zRY6MB|5Fli5{ciRBwyFE!6lARaKcXB*;3jI7I7E{bNmQB;enOy8qnF1Ll}ugP$3gs zqVG82?cLB^AHa%-PHk4mod12k3LonLlpw%ov*2qCWMq*FJ)|oU8)K{tuPynaCs-a4 zl2B7-J#8BEwBGS{&eqc=8GM!}BuVB&S!LESPv_pI={+XSVY-bWj)#~$$2oEX&uq)W zq-F8Je4a3FPre2yXBO&vMdgq{-9S1`rW{l<!JY*5;sHCH zp`SO%;Zqqbu$)Uz$pB)`fY7;zv%yek$@^Eq9g~`A*)z?(Rd5xjW?E)R7JNd^o<-*oOD%cBWOAZJl6!b?EF7(AEADvS zA51DlVhE^L5+P=NIxr%Ra3+a$LZ2sLkkUjz97{w~5I%n$^m%p+N?O`GH*?|l1 zcxD3GlV_yG8m5qKyyM9mB$bhNPdS*v0%g=)*vbEar2=&)+nb;J4u3n6(Q5e7yE`_j2YyWC2RefJ054V@Y&upu>alIyS*@~IH!?=o4T{D zGV5+rjKlfJcJMC1y5z*xo=qr7!}#b#?4#+OCfZHW;BPWZ?ocE%PNFY=&Ck`}G86d~ z>4eYrotSej8hk;(Rh`82-B^wh`T(94@JwR(atV4D;-I_bN_Zyl!FQiS?#7{k_}G{G zW3cT~Dq>gbL4O8u21%zN_FOXDoQ4n$=}#dq3F34JEAEDm(h)mmJYwfV_yNKS2&*AL zvuH7t)f*6d44yxNus93+Vc>Zp+_Ikk*owyxa0~>F{4x;|mcBE1%<`@Zt7nyEn`Znq zV|>QM@rJ)-PRy7%F=JWQifklQy_aYkxfHO0FkBCzF?Z9|<$$#nu{sNU$F5?y{K^XG zY1wdk!txb=ov?1*Q@Q4uNz0+@#gBqJ&q~BDcpR~FA%5x+#8yIxgpdSb9E1a4>e8$p zu3rka1?V#ZZ5>Xad?+MH=!K;BCuexpgYyprlH@V2w6aZfQH42T5Cw)utbY%>r&e&+8%4YVzsSSYl2IQ z+C@FKRp{c<#o9%Ka<6D9wA$Y8H_>{pO1;wB8U?i{g65C_`QHil-uwOE^FPm@=b6l$ zGuu1wyfgD|b9SDldfe3E3l!#rcFJH+s6^TXt6$N*CWpECcCnf1r-p*7b*zcwLXft~2*I@{?>2RN@`D9%ZBMw;i|v8BE=~9n&hO zS3svdHPw1iNn1n~I*)+oj%tf&q9guH_c*E}Yy`L(C}V;$!hh0&&0;O7%p708z*3o1 zZKdJ;|2D@4$U$lXw;U7s4oaqrS7_A-0HeXl$$%3ig=H zp>j;$*?TI&`E3x7hS)4pRJg4$l){jLmLMn3s?#Oej8IP}Dk!r^Q=~2>7E$VKzuQor zQ%S=hOw%nrXgX~tkoTBYz{84I+i+_lukGn5F79zmO|*s5T1e+5+M;=_2=7J5)My)q zGN$O_9u$qq`yNwXG<2X7P1BNW)Zv=4Bz`+R@%Fq!xE_z2;Xx(TENRqsq=q;JLMDV5 zlL?KdXvHYXj&U8^iXzLYS!xIjgdQl6!=PD6gQlqSYmC_p^Q2F99unKZ<{VLkk8~?;4j$N7Su{c!`7my1hB{c80bVOh;tx)4#Lk6 zIv@lwQeA~u$dPO2#9N0}CiBsCbdTeyRZg52?TD#+%6Z(0^n`wYYuwl!UH74r(HK8P zqV-sX6OX;&LD_$}EIp1D^2%5n)^~bPuE(W^X9}Kw^%y^`DFZ;tg@f`Gy}W`@q+>;d z4QUx`qT@{C252zoI|u~;QU;|P1!r!8z$kW2lv@!X1RCXGwhLnavw%o*Q(#fV-9Q~< zn!+bXat1!4Ifcuz;cZClma=%f3yCJ-Uka^;)ZTadpHJ#VljRHPqdd}94WN^>Q3!1a zYWApon6*j_8i!S=nv!`Mmd>0M+FPWbU(kSxVO4H52iytPgbMYfL|c^z#5G@Q+dY3e zj<2M>HVb`wp~VcVSb$Q|0C03ggeJ*`#1(#|Q&!L#B>u&(hXrQ0Si}yC-X`kFfEWB# z1(U;cpbp0`D7%A&k-(B?Q%L+9>WBn9><&ZhA_%cf4n01&m}9u0Z>q32ELM0iEDleA z)G#*8n#_|R{AI+@tdF&HITFY9=0GEv5L|l^`|V$FHrvFysO)f8Qu9wbb{P`20uE1O z<~=9-@`xrplbYayPC6j4O;~&?fB|Ag!Wy;-iAW;<69RxNkv)bq5NlZui|XTyxU&V9 zW3gI@AChLLMX8_Gt94^4^v@W%G1f6vr>@Bg2LKispHz=y-3TEcmbXw+h1@_FeVlO=CB@8Qt7f@?)3}SPy`KlN$iu>Uj z(*MyN{en=lCC-laUXoDl8Sa9FrXbBZ390btB3O32%tP8$d>hQ>NU5+=#-U8k9c+97 zsDGIlfyQ;<+*tltE6%{<4W_A*ejD!E5Y_BON~8Nn37LY8zuUfp7D@SEx87-dQ!=Vx zH8tqOY6^=q9=@`Aez*lURM@#kSMHzx>juVKLLqSjK)g{(*@ndh{-E!xfdn8vTKv41 z(dnKE`hFZJ=V&sXSMX?T{MZxAM^(&4u{NZO-~n(%cb!?$*j24$+9~l=@N4LPr)P?! zLpVQzr@g`ZPV!NmG+ip`(G?&PLJ03L!qAvFdmXonQ*bCfo-5|mx*8)bUJ01E7o<89 zEuIf>DU(m+a8zLtC-2&bvADfg&Q*183`3bEF4Pqk{(+YbJHjy&+9b5c1mLy>7|vNz z%;CZ*@bqe6M#=foWH-`ON=)Q&{xtu9ZEz5#TR3s11k6HQrprZ(?*_1O%@TRZTjrss zap5GPB_<(#N5H}1-5QSdVwM&k3zU?&Jj=v6=q&t4pwphm_90eCO;OWWoF&A@TH?O% z!^S%EA8xFXJQ#?A7U^E$@z|7^^%7YCswTCT0qW|OG|v5eJ5Sq?M%6;v3V3RoU|2mb z*HGfE0fyTKi}6T6mdacJ8WPVBWO6kvj5i$}waLY?0S$*TXz`rT9y@VJB0SOJPlVRQ z1Hy>7H1_%9SD`Oh4)@2Ihg8D?3i>_@lI*3zn{mUiSvV0_jPr#4xUBfd{wJOwgpK-t zvoI!lXL@tc7bA?1Ps9%jGvoERTUZ@Ge#qNFrbEM}^Ii`n?iW6f&%z6ZuJ}Csu`q0C z!dxk+X~u<`9G@G`fkF*e)Kb*MaL7AJmI-}M2~KHdyfZ@S%3x75l*vDJEm~95g2dx} zaQcaV>k~bLHB_NeV}hB@YG{WN^MzN2YVmQwIW#wZf6(SM@EY#&q9wfkQKa9$5I8}h zd+5}#e+_7wXOvUo8DVmQ0k(wI3HpK$2c8GYN112cDh(yx>_eIRU06@A_`wtOoeX5H z+5_9bnSdNtRgTNVmmfjmzlDD!SYoFP=z!#*;0{kVa)Q4Q4_6`?gTg_G@|#H;z497|N%@_{8Z| zZ}iI=+V7s(ZT&{*NE_JWsVNIymswR!DSXiPcR%Sqrnlv)$`tgujuWb3n4fDWBcs?r>ZqDdZe_S+S^Q7qnjL(m)AB4fQ0^S) z@vlO6(wHIlzydQmu?}e|afC1?InAg#k#0od^5aOaXreg04Qth~ua55n9$PQhVvQV* z2c*aKaxDevQGLSm$$5NK! zXN0pUd3KXu#+5sf*QUsMDw9)>&Vzw`A2?+8xot4Zd47hQMRH}-h=lt`Jf-2(g`~uZ zz`Ibw1SK?gOPFM6gzEkgD>R%cRN~-&N+|zRf*Qg8Pl?^6gs^GY==o~{goh&sk~$ov z1A43Cxd$rKGB+JQEuq5-*xuVEb`NuYnHY~kD1D{4c`P>tCbd~&xJAuFPaw@L4>I() zBjCjLx`MtN{V4N>`-*2QHw#wk&q8AAX#1sp8Mmn!<+xlLF5IiauohsM2YtJPfA=8W zV96i)Z+NaZ!$Gpup(6*1YQvL%T@SEr=vLJYhxITDrs)y?)^5TvIdqq#y2E(KLr&6~ zh8wYx5`+FlwiWz-+Y$blq$;l6f4i?cT1dT4O-V1t{XLFAo6X}H;3T;UJb zC_N?q;-~8AhMndf_aHq(r45vT8=zL*lYb>$)qWrf;O5EiqGXi@CjNoVCZ)pY8EWdC)-iY@K!!#9%C4Qu_+5RLiHJ8j^ z^MK$Xjuh;gJl!b2-_rwZip)ycRZY{Sd=&#QkMkqF{uwgKJ$r@InmJRS^Op?s_sPAd@Ld3OA=+muhQc00~ogJ3bO*rEbw3P$RU0hmh-Q0*p&mVd<{#h z3&PO-h@B}sr%k}$3$JQN;B7}*v?nm$Cal(viQWd8Y!f5S4=~~*5atP=>tm^leS}99 zuIt&6KYWT>34=>E0v{Y1(UbA^QM_Cn(~Eb*vIH8rcVGxGwaHGoSllb<(mA|ASe!na zD)$Sg((}Vs1zN7MCM+Hng6Z-2??QaWcuFxKOv@O_z^UCUY|OZafu$=6pJm)b)!KzS z8G9gOY_Cv1{2l<l)jL{hRaCM>c?sLomf zm9&y@I;$jt5{F40i!uSSi-I;g@t*I4NVik6p=gdw=72Bmcu~`rOXL;V+^g_*z!wQ? zP~A+@{l0HQ#Nf_?WA?Av8lfgT74Y;*c6@YIker;cVwCa^SCl?>!FAzmwl;p`K*wK# zzDEL@WkKIV0oyXx8T8E(A`D}(RVXz~#{prtA$jaS`uF{XNbo~Ik|E{KhsysG%B!6% zS0%FVo{(VfQ8_XZ$)7A>de{s|<3B3KiWx`Qb!YwBp) zCaK$E@2~2dl+ZHUz$ETgz=J87L| z9bxI(<@jvScd9k$d%0CunLDHW1@*w%Z=CWh-8ne<{MegkayxOxM_i;|)}3g6i&MFV zcSgy7YaCcf)=!FliACqM6{t(ZmOSp7hrYdI1@JJV6}f_HBxhIiZQVnN2-C_!-}Kt~ z-NiJ$k_a`h@*PO;(EXnqkOElPu}-~60gg|GPCQc90?&6~>&X2YQ5IDT%^c#uy!uykyP5fN3!3n}EWcYB<2K=u8ewn6_F98igx`>$q8y1_S!n<1u3ZdFu*I>c); zpO&tUqwZYQSwsfZ3j|>*m}oU(ZDNybou+Cj?wU=D$bzy9Twm4ANG&Wm8o1NLt&6n~ zK}5KjCr?%1&$e1ROICDEEnUZ~lZmu!A;!7;XDi$>lXH0?EM!MNO7HQ^Nm1dHgf zfJ!HpfN;83UWqh+c1z}vg*hY#7wLeY$-Iu{PRsF6LEi--cJu`Mt9^r7D4==Y*`VZ6 zHBpNhPSX&&}(X!ibJf-lSLi!Stmr=rcHSC;KDPwfvBx+7g&==@ivRW}xFHWMDEWZFM zB_c>5ZCrU0sFiTc99x7w78GWnOuBcP6nC$_XQ0{)u}P=jGN{vKX#ILhZ`VH=^!+nn zg0;_<19uOnp;#95d#$?+-QMvO!z~jzOwO{SeT>(J z$P?Zc^nKj7Q<{+X=yS`uPtthTP|>E`2+upE)kgAWBg6m(>?2k7PI`J(XDp~=P1E)3 zWiG}WA0j(bprm8}x}8!=$4)7sZN$3y>waA~sZ%kcxRciIl!k6IcSh-y{uiW(Mx}rK zK(jYenR!lmiwU12Wr>?dBX;&ZhKe+YSu=JJQ3(L4}80Oq1i0c`jzDE!1ZCT%c*Fn(tK;H+R$DVor8PTIzs{(-Ea-r-u+@u3) zJG)SXd{V2;2oqMLfh|fIVx4sZn>=Wwy{G69hB~7U(cFS= zCRV@l&vqyFJb4IZ+bepO9U5#r1{%N5J=pZP5P(tgs?H7Qf1A!6aC;s-fk)A9lc++P zmEU@(QR(hzF{sqKg}O01+$MZDMr+3k`|S~j{(a?^+}@)N0f`gNXeXn{J^d_}vq3fk=d zM1*JmC$m7WV(+>03C_0nbboU2if-*x$i4Xq>96aP>Gn{Eo=^THwvJwuY45rGiEfJ; zAZ4vI?0|8tmL3WW0}kls?3KY?99U6PKnwYsHJ!NIse0T1j^@D8)o|BCtb% zTFj9_N1c7a`aqma0=_Q-7$#Lq$O z7*+26vO7E;<(9Y}wx$f12iSXdbN`eIm!nZ8v9k6x>E6A^0r4i$RQpdUXZaeKB#~AD zkVUnoTmz@@4nqf8P5Lzdh5!;~!+vl$fEunQ1$|!!UW1iS=^lsO^La?ES^K_ZfA}!j z)z_>fjc7oYE`kc5^rz_Q0K01!6e3$~9mMxpQ_M&#tquA{^dk^Bh_3CN0-sg!(YCp) zCV!3x4ZkF{IW9@(_Q3Xf_z%UHvsIm3;%ten0R^Hl%_J$3&tm;hF^DQ8*4Q9L8x3yS z4&B-eO7{rZ@qX!RfR18C1}ogKpZiIX`2gHjh?^DESxQeTj#EUOB{_crOeE6>`q@z4 zQdaK8^3UA~o?Q+2hskma`ka03o=XaJb`an=PaLpuc3^)@;eCfCvaOQSkDPpD zTm5s()j&Q{IS|=y$+lZ1+9Ik%#NJe_IJ>m6s_WXuC0^DoV_GX`g~b;X>|SCpFzz@ ziOQ&D-8866YmlikO7%UwOI%sMavWffCEXbVa>ZG5IqHf4PGg*3rMHupMZj3%25U2F z7++4HE3%RTskWdm%kKzPTgnnWV}v&)VuO3_73hYdvVQ`A68&xuIdb0gd#)619;h47 z-;<;+`NVvnbtISOe_kqvycPZf$wA+X{;`|uO5T@PNBb3>b?#lFwcC5nev$@T3!n;^ zlOL}nPiD0;Z#)9w$p30@yb&3~+q3Om>!x>7dYNmYwr~K0{wL_$B}|`?g|`dOO~@Ul89-VxSYAS!t2QE;5I&nUP}7tt{C$GP zo{qF><#!r`z6$9nP0o{jzTSQJuxgdK@;`J@dbiI`U#|Uq~ollmGuO zCOk#BHO2Oj?V$xf+v;I%3c#3HDlJ*Nu$!irtRzZ7drb?0h75y@O={X1vb~}w&7vd3 zq)r9P?zZv)-@e{g;Q#H={~Nt8SHT$>d>M=zJx?M~kKG3vp)vhiD=3cUfIo_=5>1h2 z$(D??X4`@htq4#U=WmxL z6f3exjao?Um!hU#g*uN_Jf-RL?Fphx`of?zd{3)GS3SAfy09wAmd)GmtYRA- zYcqftj;0fi)&S?oQK^cQw58bg-)^f;;`iVBd4;a0ZQ4oc=MiTh5bO3yJ0w5>1GY`- z_6}-}ts?)V)S)5&zlHv9LLk7mF(H8|j_4vr0RjX`aSO)RiT*C$z|?;%{x zDXg?ezfDr}ngW!0w6#iv-AH4RG?5lb1^Ma}!7RFSz&sh$7%GH^O{wyxyu4?PgsMESH|OW}O(MVlA~g+LmgKEGNd=C@2Mru7RNMR_{|9g4RCY`$Uri zX4{C5SQH5%{F5+bdY`klj{Q6p7X!M*6S{B%u2BW_*U&>#>0Ax0vbks2=B|9k)DSx6j8ri1_&N3XH-z z%+ckbAA`ll@J`z?)ykt(1bs?3ki;CHBvA5+o3EtO}37|1m#d=<6`EBj^EE8G-sdrl^1OLd11gZys9u*&9jAs%Pj#>fmGFl zj!A0C0LjJ3<-oHwc)}B-`QDSl{osjh!rOzsw}M1p0LpC8O>>~pBL>Ofb%G?1u)O4K zL>;ljs`ixi`I>~OrSB@h;{x<8SO}CRrY)4{`YA@d8_bT9?C?B^=>oM;Sq(^aMzA`Z z6AHL2{GBk58z0>!J+ZjYd2{hmv%*bmGXD}j;F8nKpdB7^;Z=zPzMG;qK@2>`0K+dd zlQPGJ%iKi!cVOc|;wmYN!}at5FdX&DK>vZnm%;2A23kwDso%F0&`nf8=%EaZRlpDRT>{yX0XS&!I&3EXc2x@_790btX`#0Q ztYeM1)&g7X#{+{~4Qqm<@H4iB;D!-9B^h@ate`O zG<3V>nhniZ|GNzfW#!6;zLWG@up!D#M#3WfdeYBj8`#dFe;I6M#H7;Qg2(IEt6IRX zWO2|ZeMUwygwrl2*c>*1jkN1BkD(UPBwg$$J&7&}RMEoW^32E^Wr+P9!ipK7kbFFH zgZ*4$4emhM0e4NAIW=0s<0%PGM222?CWGJM3@?e`)Eq7lK(`G#xh+bBsd8~ zpiHlORuV2!wM206&Oq9^ z+^njFJob8ohb!(|FatJ?w#7ANX-%-+KA^=#fY^^(sa?dj1B4d${2eC#u-gVroSKjA3=rz*qjbVnWb87I`ifN?+iZSJ)gQWuUdlVhV zy}8OPI}|l4JKg0XW~m0i+lQ1u!1&31&|3;})T(pgUQKv;51RFee~X_q!?wyt9QQ6# z_BNWtEe@Pl-s33$rV;73c9e@0TP`x}1y8xivj2jA75kIt*llD#e&)FMS!FKtwNjZ4 z|Boxv-I+ZOKFx2hlgfKE{O6wI-fX4HO*)thh@)Kk&dbmI6)ZdNw-Sg`xrfc=VjcT2 zlpCo$7b<5GS8RaJSM7&)Pbeec9kQ!i0aSjlY0@%UwG(prP_ARypSfsNnxEu4_)T`m zu2E90nE=G#OSEde=b(2HjJ@vsac?zD$j7ze;w5@Ih%4u6&vS2EXG_e71V?OZJx2hZ z!o{_Y1-2uY2d1|^1^31;$Gwj#?LAK)3g-ZXa-}xHs|ZtOu?Mn5MObF5Qrmo;ia=sX z;7!S%4pKoFg|p2rwMZ$=ZZ!zyk#J}t(DP`*W5q~i2_Ot9<60R#tv_Opyr33Y<$GPU zoOO@k^t=XmzFlQ_Vy}C22^vmHGOj?vpQo50a$y-qs3$<2Q)vamVyIqR#@GgZc zLBh$4P0eFCBBXt@essxq9M#ZrrAo{VKk2Cw4dHE`W6&ISX~urj2pvH;mpvyNFG`xj zSeS3c_3BPqnIwEZDb}9lO7=2JL%UF#b>RfmA)}_+aYI9C`h^HDR^Wz9$x44+H!{$| zUt0~GT`OdITtI+DK<4i|pG}D^IbuHAdM61DSBqiFWOo4<*MWDJr+(guw}0!w4UeS$ z+k-~@>`{vN#47`fzSZ?0A{*VOKbf>sOlv^S!O#dJ!$FC$)20jrubWJ)W|q zl-Z%<(=X7wgBE%h9&0~lKG&+`2y6=1>J*uKBy@ubY;WR*6Q$wqH>C{C=8Q{-d1*xhorWZ9rp$&%G@8OkopWP{$0>QvnNk~%`@X=@R1p;ad z2BAfjhRe%JZG{%?M!l$_UxK+NRnRCsKj9)Z8Wefqq@i7950--0*9BM~kC17MYc16- z((WoF6UDUW6OfGU@{wo1^P-4c?chWkwI{q`%Hcl`KI!=guMq=Cqj#14as}5Dpr@5? zX^lE))J`i2_u6rIU2BXKn?m-8U1fg{%@TIw(O-H902EYf^BA;l56=708y@jZqsw!i z!y|^k&H`&`{7aI?NTw;?eVCJVu-;%1bQ=P^tkierGxK|03c9cr{O`DvFcn3uNFQI4 zS^^}@eo>0u6H0d3uMjwsfSzIWBYRxF_0WHv-$WAb)2G^a-%j@lAKV0^@3tlgaY*jbTYWzH5n}>`z>HipUrYMg%?wzG1ZW5+H)u~ntNI7lJz)CM97 zv*N6WOkjqVP|D!uwX5vI-&y@Po?~2z$HHCUX2bu3o}?Z}70^`y>YxhR8*QHATXHI? zlTuFXnR}?4v;kCup^boGA|D0 z8?+iNwEc*>HCNl|u@81fwvJt8-+F+u3!)BcxM}_kw;u6tko0^ENJG2IzWfvNiMz^j zf6wHUAx%~8HK{7L2d!3cb=*)crBx4J#;~NrQn-r=Mc~?{;|##qt?UiUKF*y4hp##= z>}O;Choy4hec0B0rPogz%&$n+nMNYK>Qr zO*cg6Tj{Q^XyFE0W4x(|c>9JyD4w2de+P7N?;M_bT@}HIw_RzhB5!?- z)8gQiFp=iw0pAW`>5Rm&n}T6_nn=Bc>W=A)$2SvUv4*F_YyC{>)eE;gDk44g61S%N zp^qUKNJ%1L*@V^^dH7MmJ3||5g`A!XKX^*Gahx_(`#m9JX4>$3{oRYLCEfFHhNK1~ z^f~O$-i)di%i?Zl(05%D9-o;L-XnE*$T}4zVb9EQI7euonLJ^@cMetqj3^7ck(hk~ zhvF?KYRZV5HYw!wfW)s)6g4R)GhFtn7_na&=KeyVIE%yzVe|uOsm&mo-f0I{E8R`c zm%#ddA4eSa*hw}UBmN-?Pd<=uuW1UKBm);8-6|@ZbTcZTUxf`aH}U^$xmp9F(Q7A& zx{6d+HN{NQgD8>eB0lD_@%84!^Ga(2ctWCT`Zg-4H%Fgl#PD85JO?@^uycyPN{sj( zh;odW2;O`|Tw%n2HiwLPhyv$sYAkygZZ${d=WMWv0p+^&PD7J2+a_-LLi0p4 z{pQqjOan>>X8?M$9sF_`0nlo~4auvLn?WaCpS&uzrubG2O=%Se(1?$v6p+SG4sf9E z#Q>68It_%*h?x>Ln#7s4OyN(Sd;n_a02%wUweg@2Gl@^v8WN#1)mAgQRZ|OU5Ief{ zMC~PTF`dmFG{?EWh8o*p7z!lLuT5_@3%|^cwG)J}^i&T)CU|s#$+vm{W)!qFZMVv5 zWxMFzR6T}$6zBib14k-wZs2bUiV|9E4}!R3*k(3~ascRD2upKASTfY2j8WXk4wO6A zy*y=%OYvHIC(fQX2^az=!0U0t=(Q>kpK;zA z6O+~62t;Ju(3voz$IXl;i2Ts}{W+MP1B%y!zKj6^yo&C+Li}rA3@Wyr^pJIN3Km@r z>~}{YeGCFwzu(6~fcIoUy5L#yA;>8a!?=YSN&rjaub^CMyY;mLIQ|H#;RHwo-1l9rUtLem&$r?oxaZ2dGU6 z$~ZBV@dTlm@;0tSbwlwWUycdi$4+sku|mk=EDr+fk;~Rn_CFp~bF& z4d8ox8d6sVhFcp-C%T7QcbV^XUy^nnCM8NcBO+!4sP2Km@@EESl}_w=L8l{p^1JZqLrGyj`iE3#Y_xbmxb#r`u;;;;DQnNPX?UWX z8t`2MC!iVNmGv7;_evppUMyTa%b2It&x3L_Ig-Fct!fFgYHVtLz}M1?bwj)gtbt?f zd13K9ZP~%*RX{wc)|w`i$+oJwy2G^ixIei<4s98imns4EDdHGbm}T1*00A`2KS zC^4;7rXZs%q6mc zz_r4)N2>5_VXV!9pA(+5eUASrOq@Rze7m=U#QcMBasK=vf9ZwG7Y6EQ&0|1@I69A_2~4yfbctR8Hh|%Apb|WE|JvU zwTc#lcf$g>axRtFq) z_Ak+JT45eP-Kc7^ERKZ(l5!!vU75eIe#{aL?Na zqzXWkA$>%xX;}q-vhF(v%_lEb3(Cif;f}%7$Mq50K7)L%gAe+)3iijfl&eqJ_xMA0 zGQ$i9euFRk-+qJ0yOuR^0pDo6mv8}*SsNM!u#Ft9ZWSnh_BDs0z*$Tb#; zOQd)w8RbCV!P3-o&LwgG0FSs~C8KMXiODhm(P(h$IeF#RS`$pw*@3}ZJA^?LUjWB8S>z4R zs3#Cx)U=Uj7l-`S;#S77o{*Euf}mhrnZ*7yAc7~{)K;NxMRsxD0M>7m<{AMJsHg=} zn$gV`U`EJQo!P)ITpu7XX9jP=&B5#L|IN8H0Hvq=DokEsu*-sf`h7X1c`Cx+i*Olf z(_!Mc?HEo8=&lDjAzb1??viS@k+YJ1tyz*AZHA&&n;r{4NiRAGon*VtNsP_NL+vdz zar)jg==8mbxQc6!O1idJ8uz`Z^uO2_)3_6E-^{naxbMX%6!xH zgGZS2R63X}ZUU9fG~xm%Ya|12>J2yQn+fk-V*)?o)|!@LXWJ60(ttO(ZULyJwf!U}eSzecAc=4aC_MJWBA!+F~b+Lcod;v~M?oa1uduC>o{EfdwU zH66=(rr2-^o#i`6XWcFa4F(n|nJQu5qbOr3m=TcpyJLp*@Wfc#{yM?2f3>h2jAQWj zf@7yN%Lo>A;09sN!G2f-;QgaTIJo=)TG#(Kfqqh({hkXM)a^TgB&uod$I_Ab6XElvwf5h7{}vMa77rZp!0igzVGpTBzrN-5Zk-zZ(~Mmfveq~0(6 zkgp=CG}zkz>Z#4D4%I-0NB*~lvUDa?neI05DK#J(Q`^MjQo5!ol4CLrurYw?TT2g1L-CU{Va%#tq~Dj4$ZarFUW$rqHz8V28LMmB8Z|ZY z4qDG>tTkbJwq|S1*EKaQVUvIJgiZbxLWk$(LtvDXa0juF&(K;GTdIuq7 zLdb=H%4^Chj?8?f0Y`icx(8JY3ukb)5Lh+L_8;sxC^Id+I>1JB)+NbfT-j7XIHAnpfxI zcLdMs>G)Y;{Ig5qALy5Jq7yj7_6@6=x=t#SFCe%Scj8$+&J->^o5p67jZX~r3-UFY z7zv}+WZCt(KrIq34 z@WZ%mV2)1Zh=Qvb#3{vvKA)lw@k}Ndqcgi*CUX%Oqo1%DYUz%o&0vGgPpT!_pgLfc zh!W~=1L4A%HL+10P?wmaS#SdBI3e_`(ZKbT__bs33}N!x2dVB};k~u%u~*1??sXZF z3~GcgpG(6Q;rHj};Vi+jPD{P-7am==7CVK@>&Ap1@XL4c&OYB!Nl3SwhwYF&FwHWC z+*FNce)SM@`tyf}fFch*nIUYjYvC5myY?*VR-{edoVSbZY|}|z=AO-~V76(Y)iD|WCJd>~N*vz*5ns)JXp42$Z^rrc;I&xXA96bo zs%qya&jUqZ!1p*Xk~J-R;A}zS44^EO9sqUVceQKqTSD1-JEG$=;aXH zw>^9$%$oy(3TaQ4O2e8C_=JH=p7WAAugjTYo5Fn~sf*!0I*g(3ao;b!a2b~-m!==J zRnONictR&|;!B=M=}bVr(^&W`ObaU`Cs+iW zU=z45kJz*+bZ>ANhj)Naet=1hX{Qh3-NZ@s9^sD-$@br1^~eAv#4jf3Ylada@B*ky zK;=Yg{CVeg3g}1=h7hoSGcMQ<6Y}>!CS0bIaRIn)N9r~}-EgQI^gZ0ir0#8foEM;^ z03{nktq_6bYiQ*K(1ixtkM>3yt<9I&&F%6CxLdSW*uD{z+QP>h^*BRtZ%n4n^b0pP zPEj0eA&X^+P`YViba6kZ$28>foE&b__WH&OuWrhFY(^02!J+pVxR#o6+e7ZIiA}K} zM#oN~hSMW-d<37|9AUG<^{5!W(J6p$di>gtN~QBN`7;t~J9!OdOlZcM>9(QI=xu4w zByrWCDmU1s+ftvAJk$B$zftQkX!Dei`@97Y6P7=3$6CSr{AgS$jCi3s@@jyvKl+8e zzIO+N*IvjRI?(@L3Lm_iBKb-Jf+Jz5(D_0fzE23gFhZLIwHS~U7IQCwqVy%u!NE;G z4HhI{EBFIRz9gZnt^j1QHFcx$X2DtapvevMaiejMld?xz$yLGt=y1q&T*B_=11=Ux zd%?g&E^846Q}QLYklbY=g=$*JB}Bnhmm)0OTxkErpH_hj|6+^czmy^!sm+-{jnVx% z9Y$yd>9_N9)%a{QpVz$K9QSiHpVjm03U}GyJL!vhBxo zZ0BDy@9)C&J6$xhw~N8sZ8zMq3PMQt`aiM_iYW+~OR>1t1ostdnxa5~ZFSc385|mp z$JN{Pe5|tp?AGXFO$!0(YM&nN8P@Z)e0WK{&BAlGHn8S)!TBQ0*m5t3m)o~wQH)>s zbc-5a6V7hQvvl?OY0xA?p5bK~MqawO(IcZ;=V?mOi}guoEAU ze0_ZwBs9tQUSF=00u4Ab5vYJ)Vw10yd~JQ?YX{&dL{{B~0)GEOVn-@)otGFR(x#Tf zinX&K26VKkFG;J~k}He5E-y#=>wzeY#2-P_$6P`sVZkoI87^}V*k#nfpHjz;f!>px zr?s$QDmksanOwS*ssg^O6EV#J-?x5s2X)tz?jWd-k2>~(vlZ;x{s$%YqnV|V=a|!Q z)eGb)aPpV#g*f1IfCC&c(mg0KDe|uH2(5^5JD_-Z(glT;pF|u%*axI=N4tUrmxLLu zEDzeUk`K*Ko-vi$-|Y&QO+J0VJoR*L62+lxo6CKTvb0y>qXe{6x4oa(lFWLX8c^8VJ7ikh9N&R5u6z8zuSg!k zi3H$=g&@8%jXK;blx&-VUl3m1_AzKpE!#`Op4yJsQV1)A?c0-OO`()?`_kxT@U;v- z7-twx<;1%KK8rAF$8-24;o}`yidEp`7w}CMF7D7KFFb~Hrd#pRNPOg&*z^Lw=`eA( z8_J_m(}hG~6wVeZgsHQTSRh^Uj9-ilZr5D+|IvjHnr=l-C9WVS^K^R)97F|sDchdYX46uQrpIbVyMIMOq?ly;=52)qd zpwS^F*6uc&ZVj!a?i*h+H|d?mBLPWd1FC|OPPzmIq6Xe84Lg5tA_9B8LzLCNS8BRN z*=wnydrM56a??9qQ4AVB%=wcE>A$>&EP1ei#TTgN;J*n_D0_Y z7YOR~o>DMFod*NQJ6$Ye>WnnCdbYxNP%aXka4itPz($xc0>}~nhC66vrF*NHI

      { zKjzq&G{1|+SOXZ$J>Y_}liu|J=4g$dzVo^X`zeutd){QU(2)QH!JHHo7)k&E%&~wu z#!uOM?xOErhxn3%pl^#~5Ph|Pz7XW05uyNlcZ7hxdsn~+m!GGK#+H1S1i0f?dA{;$ zB5A+8N9T|1PO)hGkv{B~cUN`B-LLgWdebc92?)Ju{*3@aA_1W|EWrA=l-eo3{1$?u z?D_fXFhE}U=`E$)`47BQn6_kZS2%9{4+6_NaT$Oi9Rmb<$SmfKJbkP*2f!Es6BuR! zcMrv$0JXWQ^ee7{OFEO_n&&*y6-7PPg%t{aWZx~*B=FnunE+EG(C|U5jIC8 zu3b@c{Z}ldzn?zVMMW)!gC7@N^03@#kBxiDQ_D4b9_60$7`aN%M_wv&Y)Pz#&`mm= z;-I~4Re+9H)fA>-CrQ3BeX#XZmumEIM&fyQtaDc52xGYaTjRyK+ z4HE5*y>jrCdA6pVpJhSf+r3Eq2YlBA{MEˆWkU8(2?c;D2Eph7+T59V(MPx44| z?>F?>w!KkM-}?I*?&L%Mt~*XYa`!k3w@`}9)biQ2C>2D z2ZclEGzH&)eo7ky@mL~zf^_*uf56w!FM$EEt`Lv-!czy+IK_l!Ij#y< z8g%x0I1N66K*JsXSr*!=5$z^2-{*iF35P|c%B-^T$W~U1wUo$Ei8e-i$2YQt0l;9+UZh;G0`HkCc=0HU>A#8i2X9)`3VLvMR30n%iQt385FL* zk)2r2uQ!LEgAY!|tT)Tg%PP0?wdNPWe5n!)Z|d=TLe-lY_yggoH`B&^4w4@ek^$d? zOEE6^{y`CZf+~jbgNz8*62bN{3qH#736zqBN_`p31YOss!gp^zg_j7$Z!O2=!jZRD z-T+iLil=54ji1f z_iW88YKjBIr%^I~Hox7RoU{Zy4Ry{Efb&$ae$)U2xeU7{v4++IbPVY;? z_QY(sJq_U{_}IvD2+mBzVhG6)W3qcAehjgmN8mQXg2DW~ix8W5H$CeASxRb|eo0BCqqDDS3ecLp zg$x`&3xG>(ih;fW(*9Wt9QHu`5;*ey8;Jh`@!V1d4&ywCS@VIjQ$Ra~7>pqd23e>C z<7C(6=7!9bz<>v0kh4BlKxoxsebr*1RgBF*qZ%1FZZ|;09|PI@C$C)|&3fVO|9ZyB zf-6)fE39CdY_>v(;{kAJ3uuH2P*8Mo>I!Yfn8_1YC^J?}-nv4bcPB7~+XH0-SQr?N JO@6q-7yu|sB%J^N diff --git a/boards/mro/ctrl-zero-classic/extras/mro_ctrl-zero-classic_bootloader.bin b/boards/mro/ctrl-zero-classic/extras/mro_ctrl-zero-classic_bootloader.bin index 0a9fb48ed280f9295b272615386f0c7805038ec4..619a9added154a2e0f852eca428d3e5009c36812 100755 GIT binary patch delta 22619 zcmagG3w#sB8aO($yGb^ErVk)}Z;}?;riIWJEFzL7?e-C{<)QM_K*1A44;Ao;iX;Wp z@=z;_oL+PMOr3`GoV5G*``wfNfI;Hv zVI)REz3+xmd+`{Q&e}0bXW&8zrT_8{VrwckA3ZCf0^NW^XC83me+u^xS+IZ`kskGb zhyC`GUW9vH;G1gPX6!nfMfaSGt?1l0G^Z+ zcsut$8C?3jiqleN`ds)og#HWDsX>%?S~8|rLS7D3K?<8pqq$WTK zrSC!{CnD1%%At#hOh7Z!G+;DAccJ@w#@~4xKr)#x!reK$G>~2?9xXD76o3z;yPy*j zknodGXX?yd0F+mu)x=oONh&~90l3ousY)LYji}Nov5-<{54p}s^Wn{nb4>#Xked(4 zEg;Wp;d$+8xIZUV5z3fM0}d#!`r}z^hm5?@45%OifJgvHg;0aB&_L|}GzhT2HzpbZ zt}2~6T2o2}tdX8Mn0Ev>;^|p#)Q*hQ0%_8VNNY5rN{UvbQ5e^;?FeybuBs(#7UHn> zJk&DVMNFT8n+(foiPfBuR7|=B3ew|@W>FO?(OAw%IRylm@C1Q9BUu?FJ|P9Yy@B&m zSAkhX)#gw;T>$qzlz$KDc}UMg+5_c|d1f&Pt@Xh3FOdHWq}L(6UXXKM65&RKjGrL= z3DN;b2MSbeqi=y6XwIL03-lrs#KQM7ZpB#3xC$8P!k9XG!13sYCOkRD5nK0Y)2B^H zM;QI5=B@oPb*Gvb&hQZu?>aH32~Ydgjk14p0za=)Q~*a8V%;@2%Dw7@H(E!9a(di` zk7`N@*;odp3(qHw+hBib2C-8!blDi;`(ip>A1zBPx=Z@Es<NH%2#DbxtZy@&TKjUn+g>_QdVa~+X^ICQd z64QkDm1)PE%1lbjg(21e7u$lxV}1+>G7{$479=8x{M-G4v22Ukl~99wP`2MyQ%Wd? z%doigBx+YiP{8gmrW%&VB6X4xQ`_#Cg>`q#-l=6gHFAB;mKLPp0OMDKLREy?eqm%v zImh2=rNztsd<%Zp#^>LaY^8Mi8Z0V(m#!g9i&usiUA{HnhV>V;)>xUcvp`v5&jb)U#3l5i?nH$L@N!gBC$h~i*Jr3Tf&== zn0LEB32qc(yFW3M;Rs^!l_4x{_RGYVB}S(#BUKXpvQX7&l01|ik+3*P&_u?`zXXCN zL<+Y@CQiSfMIPPVWp%5*9|S!7aj9QEB*`a4jk; z`U5GGmmjTZb_D@D$PgY|~tR8lMTn(c)uLWl##s z2$aNKytj$mzdfYs$>ZmQAijtE8y63)MtYBPaww-%xDcH(exJmoc86*{HALQ_?HBP` z)IKH-vANg0l?)%n<6V1r!Le zJQn;Cy5H@tl5$Xl2S+5@KC$83!;B@87P(>VKME7`O|pm;#KhXS@q2g$kJ88R<-A&3 zW1z)n{bl^KQk{_&pYZd^vrpylR6!vx@7s#8_}q}3uk78*qRe6^>SMzWdRX=t&&=qM z(7rN2c$uH!j~18nxS$H2ruyd>caL5m(qa-V^>W_YA!TYhS$EgD`8 z+<3^(0l&R0kup__TEoE8Z$eXSO4g47hOdX2cg!zKWiA3QiC+aW`IEhl z9FH<+@iW02JG0;jJkjDOgy+PDK%X0l4X2R!@~Pl;q+=?Wa+8#=!ufCOeXgLFKluyv z2J`2^I8)^PFx7(I!$DGUsn8mif{TTJ#TDUvAt63%Qq;&p4-wWM82-u380p>VtwC@6 z2*=Bg8rtZCNUV{}$(UC;aXo#I7E6Rj;&pgXcqx8*>Zs+IA~myw*pU|}olDS2nE#c+jf zNc>d<+}}oUBWUovhM`VrNzwhQ9BL--8jDMe-Y#=g=swLSL^nOLgUyL1U`$c68de5FD9K^Oz7R)6< z>0Lvk&kh@Bpu|{VNIeNx30Vm<@mIpCgskXyMt*H3Z_e>R+4d^ojf5n8SZGVo#MO@A z0(MGxPA^Ox8NqH#mEcK8!3Tus#M_pPhbd-g!k`0C;+PS{UAGpt5&rkPRV` zbRc-})mxERJ!rUj?-JK!`~h7ky&{W&Y~A>Ym0gfT?#$xGiOhy=O$mKi!IQoKB7p^QbW33@by> zyEpiS8)-)&|331o`+Vzf{V`iWh6+al(*D-3+PwC|9e~T`epMX@T%GJkjSN4^IaN)h zB?T<}9^XpqI@+UL`!2F^3a)$3{BCSCyrfs9mY=dTyr;6hE_=4}QAsr>2 z_o2OE<-1L|alkd&EUAJ7s8lyvrw;B|{u9BRIz4TMKizf{re`F`TE?b;cOaO)D!xg# z@sNpj1-v7|tEuB6-|_Xds>()L7BUNESGCNO@>C2AWPuOC)j)pZW8tOePJj{*DeJ_AvSuHmyAZM}fs#^}}y)dPIge|HJ2KC^6#C`+UEx4u# zP24#9Vd#aDSN5vnBF+;bS6(q!(s6mPL`Ng6OK74&ajjogQ>royxoZxP4PPvkDS^oS z^tdr1D>I5`9S>UONfWGSA`-uKpaG)}>axcM(Ig}`IgSk)Aw2@AW0FyP-_g;JG(qp@ zL979aZ$?7K*chQo!`NSO#1GU|p6RCzeFl$+!O5$qX3t0f(8Z zoq*ZQh;~YcphiRwfsg2ovWFV$w>nxwornF=c{;~&ji?Gb4hwZk(_7|XPw>uv|FW57@-Vgv1jvavjY3JF=0y)AM+W;T9tl1(n2lkgr`Php-H1R_b*Cb@V?67JFQ_%Y#C-9qZ8 zAwkmRrTxX<_6uvo;>RDcU<~=~C-9yi11AML?+-};}=e( z=dl|`GI^Q!ub^-gtGgmWM{30lXWfd>N;^|<|%1prYa^RottwmzTe6q0Rv(@tQZ2l$44S3^W)m68W`w{Oh5I73k9?wRs@MTtN=KaCr z(p*ELT;6$HsxlEf1OcMAuzI3X&V8*^)<=g&d!Vn4Sg z=w0Bqu3?*k-uZ$#dm5fCJe55Uj|i^pB>Y$5*X-MJp9~nBrq`{0cm#^5=yUnK9=-pyPxK`rMhya@wP! zu+AkVmkCCl`4cI*P;AriI{rMdX@s*zB=rYD|1|cr)Jy7)_`525XN_xHsAtBVKSaj} zMLCnF$}6@Q5eGV~I-F>)g*|OZN$TYflX~V&+v~dJUv0o5jd3T48|^{wbHIqg!JPSJ z&!`7Ce$^z;(sqF~;=`USqpJz)Ug0Brw0D~6W01l!dZT1NH4m;Qt7)>vV%9cU^VP*- zTNZ!KO%Lu`2f}E+LN65O@`>jpmhI?|Bnl|>OK)7(UqsXEi9#xHW5<@UWlo7HENaq; z6x{)LqlN`iY=)dc^14usXs(u45L-DcR>Fp9_Fyj4t05;UN;PsjoB32dC8!yUZ zI>TqdG%f5_M0B2)m<2Mf1WYm+B9@(j=CL>=LAu~pb4YaJYT8KiH7%A+GCqP|tcW-- z{M(S8VgteUN?q(-i&A5XwVRs!{hqnlVy<6k?)}6ZE~HI1$Y2aq;lfEns<72iXqQ>! zV3t$q!5*VGi40gUkRDz*gu5ECR+Uax5w}cciCOiP9CzaBJ{Qf6c-NjHof{)*WE43h ztB_k%%VJh-`yYs9r$*Z#FoiAjDu$2b%}wS_-N3(SlLH66KL&NHlHytm+k)Qjf339dp$>!~w@F`)wZMyon~fZ=>!oPIk88w-q5GGEM7D$BY9j++ zPnq2bL^cngb)P{>?voV$PVJ^JZe01T=DB#@0^I-tgG#-5Ue$>A8=r1dYz3uRj5&T! z)o4veHL0oH)CpZsAXH%Ob|dMEbo&|P!Q=}`y&nQv(&rq+l)ZC$`8orByzR z`xeq7GVeO}dENZfg5u-;TLb*2I5W}0&An&Lc;dLb*miSo@w&b_C7YN{GLe?8z&Q87 zLe>=vFTpMltdp`Usqe)$oc<5@9EmexL$YdhZs>4Z5+1yQ()WlD~WY!`~^S4q+?YGkKAHWzfL)gK}|Xq!-rI zXarggu;{j6K?UN75OEerpEpYf^W{^x3wkF6dTi<@+NR;VZ4IRXUCv#(l_&!=rLamd zS$So>?op**R%YP80JWG55~Ta_l%O{y&>%f-kbBOc(9nsqXzsS;sdaY940@xXaK>as zt`4&6;O>%ZjD;v)NHeC47^f>m42It1%y6(K#%IE;0&_LW)D8re!>r0QYIWOn12xq; zk)d^)DV=U@&^vY52&;jjEa>&a_9d1Ey@x;^BV6H(1obZp)D@t?K-4m#2gc53`2Q~^ zjVLE93T9d}uy7n<(J?~=7I9!Q4KXGe9u|g&=rVt>ooN%zpOxeDV80M%=FhOl43C;# zVPW!i1|>I8w#dAZfo(>lIlWQb>_CIN9$h2ynCx;7jgULWV?{yl10%bEAZz+h(_10k z4dfcVf7}2s4Wp7IONulP80YCWS3eaeTBBu7#xn*cPtaT8pVo6+8dq~%O0cVrOG#X` z@7cg^X>14EJhu5GPekY6?fMEJ#b?`fSSR zRRVC_Mqa^mQrVO%RgOBx9n) zPlu82P3b-Z3{5R9rqNiR?WFV(PNYBYLRn{BAb!Sm^c&F|j~RQ-$oklr9xU2vx&E`R z(|xDuXd!N@&Q9L(^hlHYPmjIx*ey3f=ABNI{g#WgN9o78&?Ngn^%1Ctxg~Q%vIz#Y+6{O}ZLcVKZ3 zRGWKo95K|VTD05ajLIhSz~*(j&31P;v=M&fyQ`XwmC&mE$iLy4K5`!jnD&9-2N>`l z{@~-Q+KqFd)cXPHalrn;XqVy#e=tp82xZy_u79A}9&A=rgc;MCOas(f?dBh^f-`2V z&;7?b=NE%PFI>RLl}{hNEFEp`mg0@wl9~gDQa&)`I-N1zs1vVM>jrvsx`C(G5oY~H ziU+0qkRyYR?gUtyy&IPARO8eLqj=Z>8HGVjLq$>qxY5K{9S_j4oiBqUNxcAEXPIM+ z?=|CHDBCFJ)IuIW)>kw(6Uf+FloNY#M+MgGoK04%O#YA6iV~0eez9>)lx^;+u%;}& zzEmR%>)cZQWoQLUT1DHN8o&l_2kmR0???H<&L=D>56VENY4ymX=YB665M!G|`q9g^ z%_040AEb^+C9coA*pHjgi2sEdMYG0P_c;h5kM2+I|+J8!h zN1lXX6loP8x~SHedx%$fQqaNnO3@ge=Ckkc;1`45TfVpY!eOreu zKLhtqhPIF=*W*3!NcX8=TNz2#(SBteSuWQA3|TCzEXgJ$uBr`sFAo21HF=>+fjd>U z80%t|%Uj?^6ZqNviX!j=R`!-AER<*t2CIedm2)5A15+c2By5f`BsDIrifd;UM*75w3E_hSCAIeA{!m< zTpfCEPEWbWl6LP1tJ8)`|H3LfSn)TP$~}j->tKO?S0asa<>Z~;fLTepf&Iewm3x%` zovvgK`NKq69}2q&2!##4@*7TRe9@+>( zu^K26wWgn@u~>tPdZS`MJXU9~KeYaK1=Y#wNb`OW1B>9TgWgGgRVb%W9@R-VT3V?_ zl24E-1czn;*y&R3en$udHxk1#>q%x8vsie>weadF>Cc7G3-|xSO&a{`(5F`mw*~5^ z+omR}i$5?OY@f)d`JR!ALS+Y&g5GC_rfsV$en(;*A714u=5C}!ky63JbM%8zDVTV= zk^bP-gxRb{<{5(khbM<#8X99jdbYboN;2r1R&T^wA~vmF|I*df8!4^iKET)q&%GaB z0qfs1-9Qkwc?C@bB3J{bk@*h$@H!%!oU?%tFwZ>DG4Gu92tzM|OgHv(=9P(*B zFRZ&G3r`SUy(2f}`w?Ip!2dpp<*!+Z?gHX}JK=|#7QNuUgR^V2z@tUdqg(`^wRYJ1 z;mD($hS%~Vke6Z!azsqI)eOExC0ya)p@%dR(lSWPAhkhigR~CPI!F&fdJxhtA^kGE za=>8)aR!8(c(@ASN`_0F3GQQXA$LiuH`-UgaIaoZRFgk2Bd_*Ch17CZiYU~HXdQ4L z5Fi3LGoo-IIQzGi87Bn1+lT7P0^Vms|67Niy({S57JSxHIWVvmfhly@>k4cwr+6Cd zHpvkt$(n?DlQp3IbUpPb(nk2H_~iWiRwS%s?4AuWkUEUTqKbK_=6o~G+afJ7t`O~v zB72KeW_)PFntlu=2c(LcD=wrTV4JrHw@NBlu2J~`$YnaazXq3vmCnnXCJWIuh__7U$N2v@(;gm z71HBwJj3hKtqMsS%kHtcLGeTPf&adc41^9?2c8Sbvst8xhriHhzln9#%Rzyq4=gXw2R(5z z`Da7_5utxo=s!O6uZEQ?S^{HZ5cmS%R11O-I1s;JV#OJ$V8I#Kw{jt5AbEk>#^s~T zS0L zNHeez!&RgagE-8LG>evvso1-$R=d|4@cs}0)qUtuus})1VXy5Y;=2z&%%TXm!ah)< zh&K^Scw7Xd!%HC55so7IWDn5`$OVgI4_slxM`6W_$U>WsBCWC#j0X5=$B;0gEbVWWEgc@Tq&J>6nRhHYpqafpFHQ{$*sD^L@$~@l=F&G>%nKI%GKgx^%pC%(N@u5r@ zdhRCpVFHryQIR_BrIR(K#I!|RIjk)LjND@+Q?jg&iiOQ$%%NlbMQONj8c1tXoC?o4 zS%w%bJ7SvDMQmQV!InWsblzDq`Trc0_aW8RRl`kM+X35qrmS;6+61dG%RGMelwh@u zg(wY77fZ|?q+&W4kEFH?P=E}44m{5ae&mkjzH=w@e|N{VknQ~SAhAY(qd_z54S;w_ zoXNx|zeo7Q+!=m5ahI$1l@5EK7Tzd+ONMM;8j&!&BmqYYe=14A=Y^+BvhWwek&@{# zA4v}ZQa4r|Hz{BxM&dcaUy_t|4ZK2;7hjTi15wJKh7=q!0min%L|{G?rtmZEpMxU= ziR+~-9`7Z-vImA_UQ?3AgiOwym%QYr(ap$$|DL!oX9& zedjTtmDOjimEL}w&N6%wby{g-h6ZB^SZg+?S!JVD%IIffB0gkI^+2>tw| zYLF0uguH(nz5<3i2KuMPMwsNjZdDsC{@4yQ(U56^wX6Zxnyo=^bKt)iO$3Z;pcW(U zk!1W8TZ1VUR2x=qfL1mH=~TtVpf_1~u2hGg5SmKInf61=GI$%}kdoT)blqlE8`hvz zLGSR#1h+_DvnoWN5p1BHS8O={3b>EJS~5c07`^C}+(JZIrd=pQ><+jr^AT%Gjgjzl zO2RXdeh5M+XkOK_t0}CQ1qTB*)Pq|AX*oWzM%km1@GM%w76jHjV&Ro)ewxQJH?ubU|JrKx7E(CMFN4Qp=Vh1Px_)C(tUI2}q2(C!{ZOchd zMl|ch`IMlyg<=k-e#1AEX8a&Xc;DV+QcCUeI6+Ke!?dM*F+VeBR@X_7KKf2)9HdWJKWn?fJX~1u0GfZlZ@Vvkz+q=$(Uh|%Ju9Q{_tklb>Wn8B4>*dy zYDU^EJ;fr$6pIYgw}kS0lsX#HQI#0DkS|CFHhq{OjeJCxK!Q|;-{@0<1zaGm=-&q{dT z=P#V}RKpM)tPK+{)AK-U_^S3B{#DCjiD_&Fy0GngctV9TKEAyO_U_zTtIYcSEY0?J}W7lZF25cn9tke zMJ74|h>DcpzEQ@B5z%HR=_%@L*PQ-C2w# z5J<+Ux0QoziKjM{lI9s0u16~3Kn-}r6474IH}G%wu}WnhD^~-juWG%6M>$6E#O6DT zFYr`Ousc)pWUaMFG<`!ELbggZ?Y*#_+(a`J;#~o zVWKB??<&c;NO*<3FV&43_m*T{3*;_x7%n>2N+l6ah=0fOMRb z^}2*doU4Ah!>U7$*$=KqzrGC;|k5+vWaIUe=EDue#y& z?K~sYmogAdm~BJ)TR??0{{N(c4y?wlJkz7}1g9B76w})X41uoXX$TaZdl3+O{7Vm_ z-|JIS3&({1hSp-R!fo>L2w%&{(cTL}%bF!|z7AlbKif-~*3YhtKL`n9i1 z!d7YcYfJZ9D$t<3#w-JHAp|r?NQrWJCQc_*ESK&IAOj?lbA`Lf` z%J$+s`n8YYO((Ng+=jOhn+aDAT&N=$g!WaL{N$|EcGA91RN3k0;D%Hrq}1DHT%x9e zflfJ!)R!fCo91Ht0J@(HVSIauW~HW~lnfKoJvoHp1$l1g*B%s>s~H_+gXW}18J+R{ z=o15Ihj|QmzZ>r*992a7r zo&pB^#I4tyb>qqJdBVcJYIeE5fmwptNDrrkIW+w_i8E*w(Vf7I%&d|~7hinrDxUcV zTbGu+*{6`->iW(7QG(>np-(fOrB-Ub&M{j&@b`Vu&aB)WIGO z(`jLIo-)KF{nSh#@NOiYaAb)%thgi%7Cy(#p&o7rXcIsqzw;TIACc_njnvKo7+{f(j&ME(I?<~rd zCp`YEgt*RF0E9j2{#(SB;y8Gt90MHuYk9te4wMea)4Ra85+e54dIN@tqj=qXIA%>yO=k*b^O=-z3_jxJ8{5K ziCrMd_E7oV&G);DZpx{|UMhO#z@j7l&<0ud$nvJ_lf#Avo2tG0kHv$KUkfYX=sYJ4 zsa$yKC;S^FS>GS*W6-{m6ClsZi)Wp}jrql?{Q95w@iU-9bidp~$@RAQ_63>^p$YvH z>6T9HrK2x96Tze+_ux>uUc+gi-TT$;xtd-;hV*17%SA)!x9;lHsP{7YxxOtozlT*b z7F39a(y#u&_>P9sJAXFt(V;+}+-s6KZU8-=%***`KDk{7n-rP2V<4{Wrws-OKh*MO zkhdNmQf43Lr-z`F-y8DYERjiAzpjs^uYi>UlmWqS%k#MJ&HK$Ay#DDfp>8hs zrx=%}_lLDIgF!>~VZXO$7-gJFKw1O8=#e`fnPD9bNI8DP81A{D@=^aHd-SjFqc=L9 zeEnDR>f<-~Cqwy{$PWI4`}JRqkoS2Ac4?=voYh5VVD9x_?+_B^O|u&;bl>N+@GE-K za6=LP`mfnf9>4KL2$tz?zQH_+r#K*A;gPYIrF{_VxbNtk>#A@@^h;~NPq2+g_1#G% zcHa!4ce^gl1HqDETBKto{0$?1A#LV&@K@b&qj+R-FaD}} zlDnaRZa)v9&2&S+!|>4?rQs`!@pN|DF<5M`yAHT_%~vbY+lVcM1@(lWnV*KWLeYH9 zY#o?d#f#u?0mmjpC>5((wwvO3+L^oo=b;?QrA}0}ks))yV2$NXtpRV42;~Jz9c?91 zPSTcUso2n{ke?5DZwgKG$7zN~nABe`-gK*AY8)FPaa(tRdnEEAsYO(mFNJIKCqpb% z(%qW4zd^~s#qVGm+|FzG8XG0H3YB-Kjep$NzsgeFzwAaxWH&&s+k>P>Xv3gtGq37z z0(aYxu>0kLfj#NQUka5xlOC`nvRC>qdGB!k`$i^y=NA7 zA#vF$97;bqRZ~h7qb;Eb10)6^Vz96!8oV+34RPWK$WEUs6rB*vEG)ez4gV%Qbx#t7 zhlIWN97uq@dmVXpj+qkQnhTP_!5^5rlT4dNAVYRu%Y`^#4qH009@LBUA zSV!AL{_*X_Yawv(}c%WTKllYA^qSL^?bwCLS@G z^zU*c+_m|xY{rAKFePyCMIRi`!Q-D4aqmkFk4+g!z1afi*TtB;U25I}V zP}^r}=|&nXLNv(ZAJ<}CrCmhf6bHmLFyh<51(DJM;DS^M6#rA9e8h-vN-#8r113!u z$b0E#vgkmFG%die81JZv+Yr|}6UINTrs!rYO=;u@(S-LUHK^VP0~6c`LW36YS$wz$ zheI5F@E_4*GhNQKSIBE;k`wW~j3X zwJ2i}Z|osc%nIuunH9(3IswA{ zj#|uq44aO^xkY@~yk$VReNnVMZx#r2;E=JqT|hl8(YJBllSU@HyLk?TOKs^LH(|iV zOd+Fi$n@kIs?g-=Xb6@2L=Ya|rzX5cpvL->fi-2OTW%;#&?{-0`2PCqf+?>4vMM z`IkcQy8$BeKM?PPARP3wA&9LZh%FBJyYWDRq@avvG_rab@Tf47#mnt*^8%>=_U|>J z3J*br)lN=3qkLS3{9wR)A^;T*%3cC1JE;KhkA>jTx_hsZh4W5;pV$3ab82o?7eQ$j zJX@TV1I`*+bOpA6+3qadeH+NOG?vVCWmy_bcepM~ZyqHOCB63WaER>}{}vdn&>C1! zGIOB*17PPk!p@`2JagpZpGT)`>WJ91E;-Ug*j;{*(u|f*8d<@Gq?5{^_t`cw%aZ6M zz0x(ANAS+u0_1;Z;2F~u=UEVrV)Osoa;$v>>1g4FpGSq8Z-KkYfV+q+vh*q0X9!Z* zODxf|P$t{121NJ!BFi}|Eq>sOu%IS2+0pXCXPY%@Teg)Fm&0x>>&~=tHe%2Ucr_;r z+X}!u`V(;I3TU?n(hZ^YoSDVhu$Ueceq6%ora?8DY_JAmWmCFIK3J4!AJfu#lLEJ_FJU zof_92J9`zc2h>;ls74KM<8=ck!0K_gDPcT05KRb&twQ%|h$aj`NQnferd5Vuejc2jHmH{@`ekT1^|Vry@4pPb$J1BAj6HyY`xvEnsY4vWoGj!IFx_>YxtfA^8Qcm)4NyMwC7BG7-m%=yDdfJ%?7oO~Khe5sqE@7W- zDxN3&%l0IGL72CyWZI7-MAwx&i}-!OEeWt!1ikWL=xkDL@H&LClF-#A+6ICaamI6O z+g9LD=tlTqRS~WgbPwvn_k0Y2a~g*&=-n;Mc~C<|jtJ`?ToPLoiu7L4G^dHRu}vf1 zM8EK0jh4DSAUt1Vq!I#xv!;+4@gDFA5s%bUcMJ=!J)%~FL|wVn7Rft!%}R^SsCmU| zgLba~@FO{RqcHNwZ0fCmFl%ilRUZ)kvUWW6s$Y0*ZC+~1gAnGu9;BK_5qldDe+g)bl_oQpy2KjWE9^L%bLDXdW>!NAZ73V-+O?T3Iy%U4X(eB8xA#vfbki6bx ze+10`ZZLFRlAAxcexibJ0eCV#tS`n&&^w$5a5o5Xss?2wR zNvh_o`y(*+3fI>sW;dA30CgXy;PfC;oRF4tdmRnZ3U2Qs&$=~PQ(TIP`J@%D-Xs_v zO}3wKBCesd1&We?Z(QwSM4IW6Y=$~%fe{R^PR#uZkJRE>vc%yAV(Fpto@KgWp4?cG1zEVmhnFC z<=}2<&9G?XJpg1xt%m2Ni(M&pv3=Z&TUEZBrK?9|Ex}@yc^J zzrDG!SpXL}jK5a%{L9VC<{c)rOZ$8*FCvTzyU@Q5`sM+3KmySdw=nG~@gqo^EU=&Flzu@||11Ewy-JEg%Po z9(C$?s^Uvc8O+#>;dk8_IIIw6_L5b`o67t>5Ds$P5&OOIrXqBI(9tw#g5#H;JK*eD z+#b_JXVcQbTKgjB8c{8Ks%OnWl@%A$S>7%>YY;3oa3E9`o3Q@@l(7bmjv~?RI1iCp zan|F~a)aR5Ev+yJkBD$+7>O6*X#td61BTx!Ed+OCp)u%P{gH6|&-c*p`&)#_H5&Y; zFlkMKiW>$ugO20hloo-A>j?-8)=Z@Euu!+gDOfWTh2syYREq3&9{yS$lr5eWxIH_RO7q(kY-ITMt#F66ha|c68%b5OLt@B* zPA+y;eJRR()%l&fsHtOhtZC<#ow3bH&3jGQ2?Aj|tkuqk)0tuKQ$ay`IN5%0drezS zDN!+BIGV0iz#b_(h%`gqdHza~Vi{efNJEGxR+?`v;J%Yo4!Q8%HTK=_u7zzM_I@|H>~k`c#)% z@w6Rowo3OKSe;5^18!Pjs2mu(4!CMx^)t-icDS?FS67>E^;B<_==v*LnZd>D4lIwc zoVgZNzziDaZIP-rpO$7pfarYFbUva2i}Qwws1)#41V_&>qV!>}b>sv0l41_RA7=Yy z{6P>5z6E*ZC%Eh%!Jnb!>7!5E!Yfpom!x|Q3{=OWVb}(SltU0z9;yT$P@ng$;Y@hC zeT1AuB=u@qB6ucK50eLp$(eNecr<2qCQNkr6a^S|6ZjiTaK5XC%4;xG$hlyj^^qbu10=)53OT3ON~;;*6gVHvZkg@Hv5vB2yn957sy6}1_4_Qc<%PY zrG_hoc=5_=N{z>sKGulueJA8MWO={$`Bo&FTBVjP8;GQ{!=yX=4GQYDUE7cmw&2%? z6uhnJtql%{r$`$vl`>FGE1q#+!>cCQ#X@*1+3*^1EDGzn7fQf?EmS_9a`!-+1Y6$I z8}JOpS*vZ>>xS7#VheoUds~m7n(@`Pu7!qT)tyL8^^NtYz|BE&hP~(fKf|1pDlbWy z`|9{{dEq$k>lP)50 zym0yn9nKcqPo%Lqa7+z}I3PqlnTaXkwkNafLlEsnoVwRW$ROnn{RCDkhzbqD32G2t zhrN#tj|#8ErHaHw;G_n9K>R)+<03)l&`{%i0`D+FXu-3N3HV3hh$9KBgl`PvB0cv!|@GjqWThkmslw~$eCks=QY@ju%uuaksoI`kq%CF8>aP?1H|4D zRnr^E{-#u1f99H87opnG$xSLO?oi zm`PQ36I0N|ZCcSzJ`4k2qq)Ycya-h9fe9r8ijhDT2$+D1po_wLtOi9e=ygG9A(Syd zNw5!v=yPBj&OZP(Px~{WOvd}+;3KKK2kM4F-Jo|7bofU5gEj#m1%Uh@)Cy4?zHACo z5Ped+H7@1V&`eetkyv~JPfr4$>494D644gGxF9rb)un2N_n8#km#$H!YTMkVc~*$- zxQ6oO4Q!L&s}Be_w^k{rkIC%%lTiNj%$Qe4unx?xaQsmY2a<=pF9~~|p8Tixf=CB( zxsO4Ne8yntEV|edHyd$rv#9aeHhO~2mei`VR$IlkSX*WE^9HiuIxD~7zvps@GZ%(3$W|6LYpfNT-G1mq#dRfHSQ#=|LYx^9AIE1VBz zK!#fd=e1DPb6|UWPNFz040$KOs7T(ef~77W-w^C|Q}EA1OWnOQrU4)S+PtrcvPZyC z%RH6ei$W*7Vf*LvfEM3LKkOhU?rBVvbje%WMo!AC5h+yDc3vpoHqSo8pH_|w{%no1 zeI`XXQd={Dga0&=(_`TC;q3k%+gvs7Ot4LE-EWHjKEamN`etHW`E|FN59dX9osB9U zy^E^I0^TX}sd~u15!26q|{u6U~6w7tC}5pl+1BwiLSZJ!)d1)@gq`ZP=Kwf<5CnCEv1 zX*&|^ayYay2PHTGfx%cWc~v7RO=g?ky2ZBIDt}z^=8O>e9JJ}s z)C5(11@SWHJ1>Gn1ruADde?<96RD@f;=nA{mgmgVZBxN=hfB@w;YCb z$QwRPmgO+H2>-PF*AR2hG({uy_1@`5NQbtQ)0#-sKyWq-9tl+o3zpZObfi_3S1*g^ z_AisX`XPlbn#K@87j@F6M;fqSp&1T0N9#-b}e(SqOVqf{DB%+Hs zy9g}HMxeplQURoX?~icw7}|K@9*KeAIc1ne#F$WVRpLcOnQc}(nsB$ItU0YvfH7o# zJ8J_&RqZuaW=)hELpPFsETU(QL9_ zbd#3m`ZOU*U4&DlD0Ak3?a1U8(VQ<+|Pb$vYJ;|6crunKll}P zD<22Yg~H(T3-Jn}@`c=t*&_-F*-*hI_x;*hRY(n|6-EtjnLh9FFqWz z6+TPi^Zpe!RaFz-MD4yO zs~%)wwnYXX2Lc;6L{4A!5h2X$odai|?|z!hBeKZ*y$glscHcJXa_jpZHsaxH%->O# zvK#3WyOH>?bV*`*V4KsyXuNl;=H`gdzmD*vZ^w6vyluBp1u3=tef!sM5- z5_kW%RdM|PK!c*S;iWSB^E}eec5OH9=2u;4_HDj7w+Z{G{!cv+=?dp*BYf0w5uAtL zZLI7~F4IJO?3Zq(`F46)|JW;#Z}Am4GfliVD9f zrnnauNBL3U?GgeRLU%HC_U#g6zj?~R@^AJ|v*4IM=Ti(| zpS(ZWJVYo~j^Mt@KLml)1Qn%U9YTTiM*#|yPku8zga+#g-tG|V9Cbj7ryU196uYc= z6qzAWIf_gX@<#=p2W0F7Zy;X5Lua2adGG>NxUAUN%NqCjsoih%Md3G0U-EDB_ne#O zT-tOD_PAw`hkXjK77+0m)677vN6`3Dy22pST}Cp*8u&WFi$-kzgJ#D@sW3G>!rUu2 zL)W)nGci7D0BB(c(nI%!lg_?o%7yN$iyM=+!60$d<@cMZpLlJ^CW zt;q8k_}CptfuXPKfmN47;{G8y95;BPrrWl_jKmkfj=Uc%8>A#K^xqN*)RE?sb83{H$j{0y4OsNZUX8>_Cy}UzKJ0IWUl`{ ze|3t~Cl`E#4J_V-vPgxN=qzGOqK)CTmQVY`<*^ZIbqj1Cn^K<8J6|u{_OVIk!dyg# z%#ZRH*ixP-x=GV}O`Owo6GNH`DS1wI7KNVK_C*=XQ^WaUVZz=LJ8(`F8hk>@s#L8Ey%l=s;GMWRxpI3{n~h(NMa61@EQ2i|`p5Ut&INDs0c;m7HAyxlG1eTknH)=F<_<!cFS80Gl)DRE!Hq)Y|Ab0q7lN3NV|6#`+FJnJM8TL zz*3>QCBHv2nT0LFl2^j`?}zDJCCHixMYN}ba|~(bNg0L&v&@nJ6oAj1a)oWgbLn?~ zOH4`do*2A-@EIo;`S!~NQ2V{!R7p7eN_GOp@3GaIlwEib#nhT)|5ppw652!*MeobZ z=xa?jt<~x##v~Yi`JO6&*7hk!x z5EQE%FL--b5Ou2c__JJt;>SNba=rYgMcqJriWn4!*u#+Kd5=+Aebfh(2yCHB`gUPL z(6&J-EFFbsT^6$?+?fCLvcfO4=*c8VldXQ%X?1AWzfCZTG9n~HKbp{%(S zWV~>;v`hGTvNU&ceh-pQkRNZe;_x;>RD!)7w#|@2p#r$s@i)P?$M0}#x5J(~^PNXO z`1<3{{Fe@rxiHBgaNKSmB)J$u={4X(djWkBumNNoR3jvVQIe;D6(9rT0IW$IKq$ zzH&hKj*|2PjX6XIoc8n>R!xySbOv{Lw&DM7k{sjd^6r827fD(du>U2Jqu^Uyn~1<-tbH%_8&{5#Kiyr delta 22400 zcma&O3wTpS7C1h0?@e<1ph;Uw({~;%v`q_X3sN3RNZQ*+zyd|(p%Nty6WTtQiq z@>naN7B23VR(BC}MNnyqbtzce6?AodY=U&RP*|!cffn_K7IK@k&HqdayZifp-|zc= z`M$}0%*>fHXJ*cv*W8a3e;x=3M8=%x(z_;RF;w+d$Mx8tnwDZt zGyF(gI@sP{@k)FD+E-%AV|l%Z=~!E3=vryJmxDxp2#I%~#`+PS_Y3M-Y~9wB$m<3icAa^^k)LRLxE$}p4JaG+|H*+Hk-^k| zz_FmbvJ4s>sIJnBO4=f_(0Bwq_f%O#6CH8ye!x)`VI#;@Lm3m45&m;8*euqf^2`|x zD=g)SRhIIGD(W`MPh4p(zqlfiH;YFW*b{Au{60L?naHc)e=_v)02=C?0auGC2Vm2z zP;kIx4wYkuI`1nB=j-4)1+He1qQY&HLw6YN021WnS#`QZn-S{iL;V*w$@>9QUNkhI6HN;eZB$crNg}_Oo^|`NJTi;M0(}x~l}jZy z#{wz3JjNQ$M_6KQ(V>hb{1RIO-(ahh7|3UGF7g*`Y#VAPy`$m?YD@Us zNY21Vv?g;|He83qekqH`^+=p4{7a$LklKfC|8u=wG+928-pwPhs)2?C#$dyr2=yhNZaM9B{{5EBT>(l(1H#c|5t>9B64&~XPFY54kocru539;RSvG%Og$sO{57rj%*82W+(1A1JWmcX+Pg!DJhy zH&kOW-hcT9!nAmMkkJ>|3V3WNzHHfh4$5h=!rW(2H$BEFK-i zVr@Vs_DGCAtdvwq4#+}Pr%CeA^|*w^DFTj)m45&}xl&FR3rJO!Lk|a!1uEnQ?ca&-PN8t-)ma;?2Y%VC!d=iD)BwM z|M}vvHOSy~<%QnN6u}%ps8%mh8r|PW$P{e;(e@=kB;~)~eW&?#$*6+G)2I`xC@j)= z{Kl%~;TCLfEaRToczF5u+Zk^Wg~aWE?+z)s4vQ=NLEmR1@i5zH@vno7PWNok_svKt zN0Z*Xf~R2Pd!AT6s%$BWwIN*u4~QeW@7oQ{eN{@Pn-b3kKZoY`d*(?xg!3bK+8cb} z3?J1?)5Ve=UGt#!CRmjAH{tJHNF9(STM2nk*4Xx1uAWnHC_Rpw&8cq8%aw&Y!XBJM3osIK^+hemPMGimp6j=&r_y-GPqW7n_27NKZ8cx<^Y@?4Lv0Abu zV@~D5b@UNhd_O8j{UWgd26J-y*;PtbQJkhSR`4AZv(IjqYZ zmx(Vufy93ce~Y)o&KuFeq5;UkQ2p^i-|Iq(Iv1Z5tm?Vcckx1lItO1D{-(Zv(ig+H zk+xBdRXY@+RW*;3?W4r&!?Fef_NME*-LickTdn(U`)ugSM?yhDWyNd5vc~SaJA22l z5gO744tlCff;VMWRZB7q)!+Q2`Iy1B>nc;w=Q>5^5Zgjou_g&}_YaOfJ9v$e64Qmw zgh_a&AWNKuyM^M!EM@EPPt7}_;~I`khMB@|6O-`A!hu9>tT2oxvr{5+dSU6v2)^5A z3STFt;17kq#HnNMgGFX^Vja>_;sjw*Qkqe9I^BrGb*GSC(L!;!4r|rGY40Bb*;+5x zVvSs!I)wDNL9V6XK5t0an)F=iul$T2#0;)#2NLJ{M^PzkQ)rPm67YEhF-A=z@lzo$ zITt4j%aWhQ&kA2B=cSqaGOpB#yf#J7Gnt%vN*>VbtH5!y&uxRj%M(&k;v-H6-hyWn zJZpqmDe?NF|9MvW8Ez5OHp!?7?1K|FXgJkm0^xwLIc3`NEde5!k$p%F(=+#mSP{oP zT%MM>v+10KniRmzyCwD@b78F*heC9DWp?W{ZXS$5tHf}tTF0G6np+-Z7;s0xp6qo6 zeLoGO%%9xXJkz*Eu>39w(Wz7HSB7QW&Q_G;a%s45uL{G|g|!>>9SHu-gLI=MzaIX{ zbF=lA{^;Ef9n$~OuiC!;!)<`u_I_3Ec$mJEU<{V|clQ&C$f3I;)i&XMk2(o74L4yU zB?kSgY#aE)wiEnS+iRYAKndF*!+q`qh>N!41_1ctD8Ls1Ao9+mG~8lt?BuU+Ppvt-*23K)Alpqp)yQz8rP>8W+Kez^g#*CBkNSvux9Ki1H|s+2&njY6I_e%`ea47{|=tbjKw{MS5kxIPZ6=zG|uN@2|R zA42S3Abk%>dl*zl5EE(J8Lz66zK!$|A>p?k+U@A4V_8FZm++c4+5RXL%)KF5;AK3+ zv6Ij(w_~-nQkpOim6eUsw>X+(=*4qG>QsQ$y(e0>}BZ!F5RxtXd2NxN!G*q zX(`fA_fPC)qb$8qv}JxpFUQjQOrFl7{cOLcmqu%Q=_m~MmR>{~Y-?T2fT;iwne~(l z(3=(6PHB*)k4Ju1Bs;j;a^3b3h#D%lo-`WvpGNPs*%9Wq)BQP6)H1&`6=zzz0ALk> zT3ZSLO>0YBhi^Ncy5vQ)r7x21l-Le}2+oY^jf|=gaU?-A(k~x6W?RD-bRCrCby|8O zX`Hpj7VEkyi|%B^NajPN)H2?tBDokTKQFP9ohF4}en;Pn=~T;EiLG3Du9>V2q-nb@ zZKt%4d1&oY57I97REQ{Ys|RWR;K7<#J)nGfD1DoU)}Qw1p^>j(-;P5+c*yW|GzWcY z?ZKO);~Lc^?ANDfkPNnk5vu}>xE#{5z!Ou+W?$Ui+hq=!{~A%eW?QMH_1vtP2IVV^6AbmT6YBdc}9H}+Iv%cpDP zW!c=T@OH!(3G7teO74e!-+*jU*!D#hVug>hHNvLs)Cv27A4m&~iE?@82hu!alAP)! zGRpiQ(x}>E#VF-3t|)!%ikrgaY;9crNYAf>zGVT;+Mw^zfNd@74Eh!cv4&~bD$F%h z;(+jmAqjsgv>B%6o*zN_u(`<`$Yx2?oR23P3wZ7&DGY?i&xQ&>_+xXtZU!^}2MpjI zL7Vez^yCw<+)6yQ;>X1knYi=s(=oz3Ik_{~GTN)6us)I(OnOU%O>EP0dhVaV3s3}W zLQ;P)nPp8qEp?K*Blf|H-Z}AYiw#Wt`D3(7h|A5pPgcI&gfycTgq}7OM(Pv{kvi7R z;hVqMWbUPPmaRkx@0R1vpzmyZ(D!n?uqAh4=?m(SEnhh0S-LKeH2m0`XL37n#=Bgk zU)G;s{v*g#<9nmzKQxbQBs?)$zs90-+6vS~Vp|?}!$aTRw*dspDT-V{J(07k`HucE zM7eBdp>2B0^8VR0y^*M!z)&2(P;~$24x#|1W13ShQlQSC2}u~FtOcI$K;IdF!M2!0 z4U${s3%n@8TPFlLK?PBg;PX%XCD~|?efB(jWIf+6w6vc{?%YG1HzK38y$#Hgi%SCxqXE>~_Zbf)!*n=|7WWES2JLw{33T#+xktW+lB?;&dYy*TG zq&sq}q8!XrUYq%xbbUH?=eo`!GGO*0BvZjqs}XAxTVz``6;I>7#k7blD7(P*S?$8q z$weOo?hJ5SV=bUMvT{rBSqq-17KZcURE-+0n_Y)rNd z03lUmLO>!|NG(yT6(C_h-WsuWlJIK&G|Jf~xbnx&9_KFD+^wKHtF{t5V%2Z7Th-Qb zd~Q)+^1kNgzQaoPVq7`atN7g}8W8@%lfwPvDR?oP%LDN?p(yD4m5^1SANPJ&)z&5Q zW9Lsov!qEiq{*!C$)xGRkx9w&YLK)eIl(w7Jtb?n&vUgl=D{VY(M7tg&OpC+0k&G| z7F&A%YKauqO)@G%lV24ftSDH*4UZVPeh`CS3HAbWP$Ce)+Yx#($b<}(Xgx79#wdn5 z2_Xrg3tKE(K_HM%@1(a*E?bJ1E=pnYJIUAyKNwX-S>^QB#hB`|#Hx7*RNK9XOuF6k zG+P}Q1lVDar?+BIF}IoYy%Zf`TPr>d0!`4@cUM#;dP`^`1buG@sjabP;hF`wa*=)j zfsLrnQaNwf7w^|^jVh-L4RL+VXm%Lob<(P05w zTP#80pM&ypq`B8D8CVtumWU;!0YWD8R+>8}$LE8-i$c zdC*4>_wZ^b&1<=CzP@BcpIdQ7I_p5=L9Yt05R=2MZqz>$7LeO-7jmG(A0*_4>mht! z&=)l<^KPPLw_kfk;XRA=MIclzJlIox@Ftlc~VxnH0L$6tP5o~=# zVME%nrHMA!++&v5BJ{Cfz62}Z%mvcenfif|Dl=S7I{mIu3p+#Ww^4e#etppQ&wvS* zJX;D{6zq>;Nzj)E6eH9ky)#CkbT!?A>Qol{+ zV!UyoX=e%)^&H;1UrO%TFU5CE*t&e{_gm-mDkjYCrM3H|adqb2D4o*(f)vrL^luw! z^+qZ)yOg(>@Fh}~SThB&^Y26KAK?1V-K%vfVqdzOUWMxkNMVp)K>q#&X}_fENER8T z4D61ydz|P{B3If8{T5=q)^F5r=~j&E+%Ii1W^((4`S&GM{9)u?UeLD}RIE3p$Bm;# zD7ly>#}o5h)Wk6^H1S(E%5uBE>PN9(^_wE!cy>;&C31(9(h=7~i*{OWIMa2e?+hI- zwA`n+2YqXY{yXJ^zK4h2@%-x9x1SX~nk_28?T;>${hFJ=rzVbbqe=FGisPeDX5A@2 zPTG0Ln-RvQS_3Rf8B%X_BRf54qJ5z7IEFe?j?>(VekNAG@gCe+1M82YY=0on!@00fW-mkQW8uYw>Z(j8bqD=e1)%SI~)PN~#rGeRvZMO_i;E{1aGo9B) zxj2ZQrhpg>`XCX5+3vDE)<_UNcbC(>3`#apy$BpYV5xLu&{3T)SYIel;bZtXQ*IdgaQ8F3ASO*c0}U;57O>l5-DXVm)|xm<{DU&C0!4{#SRrXLRCTb(4;uCbHauKIc%k=ZXS# zjv_qPGZrK@JIFVt@S!G&a8R<*kxhwr{8^&6FEG~{FT-vAj2wR zmTXMeQY(+?ydur{>)QU}=!Pwq!1hdu%BZ#dG}y4Kk*POI^%cBJ*x0afI#7=#%^3r7 zMW?wG^+kYCG2O4ymywr+AUWbjYb$D;QA)5Yw2}g;wxBP|?+8_UnkA;)2yb%4cK4QR z&Mq~)@&bIe$t?Z@rGS`|dI3!xE+1Pq*%@#^0c@8u7 z+p_mn0O8P`0ZKm*1UIyTCZgdd(m>%kNt$X|1U%vsxFM{n8uqM?%2-?9kCS28RFKGK z8PZ;0c<&8yVN1lE9-Ee=?7TlW zC4B^GNtbyEX|CId3PQwb0=v2;Q~1aI8hbj@rj_0SwYf}sMw7FC$TvK!<#gOLpdu7W zL487b#el;GJT(6ksV6Vi_KAe@HTnNvg3gzC(kr!2h2@|E~?cTmc(p@MZ8m z4Xj6CrF;NvcTKTgbkaBQT05i$?kE~R! zV!WGV`|Z+ZQ<11*o~r(;8Ru=29yP5L?TjL8n^bCgYSY?&3^|9S@{X%+q)VP)%5XQI zkJ~sxR;G@=j{v0qaJcDR$ zD1FE$8(IXtcI1x@`B*=Z9xBf#BC6Oy$Jz|wWkr=lgf+l!@_|%AO4^cbhi`XOCGv-F zUD}`<=vZ(@x-{WiNF=!6%wo6!Ckl9(soVRgCAPBsGg6O+{QnU8zaIL(8TuDP{{xy4 z-~8Z+uPQh#Bqj#6$u_aTBHf&0k-ma-J!f*cMfzcmU^2z2;8~q4m_>IEIEI57gRsh! zW=}86C=Ca}GMJwZ8Yji;tvbFQec4`3Hojg zK0}N{rXk<4k5D^_JBWCfMUjxg-w#7WU?w1wsRypILc~S_H)J8*Q*z;z30%zcO(<$~ zw)McQBWtV&5@D@`$1;!zi&YgyqHRrJpD05DYS?DR-;(GEEZ~M+X8HnZ!1-w3Ee}LV zZ-gsGtsFWQy8@q@_D>vA3 z+o3EtN0`E|gYrJ4+Oe8Bq2mwpN6p#ae$NZG!@M9b8ecIvSjDrGiNIO}Qa`Dx2g8um zmH|qLk;{Q+Yw)xuM)Q>?nfuxk+k*E7eSZuRjUT)PVEpI68cTe^!JEW|?h!T@bw<<@ zf4Ayj$&jyASX}&;7D8FTWP(KuqJA8zE>V7v)*?R!Q5#9%rxO_Q2_c0`!Ck@(E(?Dt ztm0-wcSujI9&-M?`UA7VO&nVP5}aI8S`k?1$6S0>;*3NM-3eEaA4V8{rJ0mDCG>H# z>|cW842hehEDkpim)D6w8JI7S_%e8z!@#!8wha5823pe>gT9wW5N|TGZG|mZ2QDgY z4#2}fn6Oijp79#ds;aX$iVKivk{It6bXIcAgRld*{~YeWn%8!{(1gVNlf=E1V;uIG z!J2(mc&B8Neb_gFj3%^D0vcy2!FS#jS;7u1d3^)wF0bTjkv}F zjPt#bQ3k>S1IhZBZL5Y_jCfO$aaY0Z90QsTD>nj^FN1Wd0^rAw&^%+f?b>7LcP%v= zTCx5|8x|@`mH2C6S!sOHZD>sf42k%g`rGgf{Wet_gyyUc`lOEu-eWlJYC^k|5p1Mg zS9x4;)ke%dmxl>l(It6;H-(d>nUO!1Aoen(H4DLB_+;evimrre+=H?M?&=bAYP5uB zP!gVn41@4Yy1LI9UKGKpIb0xsCjrd-)if8@6D#3Jh`ESBnO^szL|mw9i{Rj$0c8uu zva#t@5uQeKsusblZ~@2)TEbS8<8upUWTa7F^LI)UOhW}j*d6ChR+RuFaosb97hY_f%SSD$cQyyh@5fSeEVBVasRpc z60fI2iPBF(W(TF^dlpMzNeiL^xDgIn=R6JrNI?q$i=B!CW1q+TQ{cAWBN zC|MUSpaeZXA4VEaxxm$zQ{G%_1+2F++wSGZRbUOIplE%Wd46EJMMe8MU3D&=6aN!;bYd8Gr6(l45k zZg)?qNU^0N!(Q~1iY)st_*b##JtuD?`>AhFd7o3}0$LlD+3^3QGTogy;Na8zwRWj= zK*RslbIO|yo(9suQXnYh()V6{_CxTez1>bQPURjqmx{IQdr)qovMW^1ByQLajc+;( z@19adz&m7Dw*#vDUC;m-ZQ2jHd??qk_FgX91Pw#3gWu_a{#Prh_Dn!x^d;J~&2!Yd z3i@7q;gq)u2IRe(aPbOV2?|J8%?0jH*2NNYjL?W}Z{P^R^SH6?(?Em>=7BeJNWs1K z-6`)AO8dZXj)!xALa9<4;Z=kwv)Ch9q9QD_U8!xoNkt&BDDb+JZU;F(jKbMwms+Hh zX15yD?8tTyz`;nP36B*cl|?`>q#WDM=xO~4bL2&}$SVKbN6T6FR8G%pKz^$)!LtV4 zQ;N`dQj&4qn>F<%(14MJ!P`&~3$->_)$M8ATYZY~@IHksUcyPMTkTUhqIP|;ZA#IX z9M#x%twPKVKLhR)LwJYhB!I&%&9pC?p&@AIs^?7eWl7V7h2>VV3GixFO|z>Qaul>XX&WT1r)?d^u% zz6~-xE+DugnDuWvpG%G{I${2x{Z1kpuNK3UN$vt}Y!5zAn)=sfy!Y=O+_)_D-ySsK zl1DA7l+!Uc=B{=nM^IC^HYdy66QLPQP0t=crj3r zZO_x|c<|xCTCXd)&qMC&N=|u$vt;gL$piocyr3RHw0iRNH$0lR5UYli3<-4vg8)*c z;qtOl+sTOQMHT%Lxk3#zNzdPZnVJGNxo`rfzT}Z&h^)H^t7RD(RQuTWV(ltzeF+&U zraPbDWbBqt?EKP;B678(<8IWR_J%3PUmAVV^ATPn29&1Mmwa~(HxQ&36z^(}I%?D| zC<^!D@Y?nmDK?pKjQWzlg$4<`@sv+J1OW0azG!xNE^v6l7+^H8 zv}U{{X^do?;@nLf_%*%3LTEOGc}cPF+mFqE?o-f{+abu2I|D;e*pBpZMX5zFquEc2 zvHSj_`fCKuM3~*s`-uZC{J<^X0V|d4fToIqwX|CKtoy`m&D!N|vMlXnO%7hCFvEDQ`9+i23eU^?X5%#f?m!Z(bHTVGh>>%$t5=9J#!4qc3txp}k#Qx@zqQiZ%2#5j*)c0HfCWP#S za%u>Wy1K4`aL2WOaKYQPk?rc{Ma_SWuk(-|Cx&`_ufv(5JmQqszDP;>$H8W?mcG~= zmR;5rW+>^pa-A0EjpyJO&v8>p0});(tQ*vA>_Xb_JfsQ#-6kB(9nAxtOmSR9I2dI{ zX+^u@39YD!E<&j_9;z{E)5C^vH`PeCH4C4}EB0X+rl8%oY3Q>btw8c5AP05<(XA@| z<c#%|2=7%P6Q5l z*_8;4UFOB1e1le_1=!2f?YY`sK*(r^;)I#hm;BuWbG;zysD@kM-+pVEf4ijTV?Y(E zFZuKy=CkTca(~R^lp*63gdJ4G4xr5nu9h3eCAaG#q8nCuSTc7xz7Rs{besX?z26Lm zWuM~CK%iYM7k0^*f2>#zLK544sQBhNBe-^Bq*q8hA$Cp8_j(@5|Ah!?n-*y7;~)-> z!IqRFkz&FUjher!e{T-EgfdPiAf1t0vTo+O`)#8}GLWSre(`+pvnj&+v&v8Xt4L&- zUQg4{9nb&ir=m3<{LDQcdVje{WSD<@{`AxA=Rf%QZ=te}b(+gqy)px9{`AuWYxe%6 zdS3Ih0&+il-Ybl$G(_iH>Aufs;V1OG@n=QEpMEk3WtB-|-URd8n@#g?sv;Qij{O&` z*=3I9uv?v|YD?Y(>Rrwqx8x!5AP!CmgJNzS@$Dl@z~nGJZPNg`rR~j9k+D%BKR@Ez zDZH{UUfVa!q+Y*x%cCOd(I5%+dJtL}bCJ{{DwIw5+rm8jq%gQp8*7D}fs0>zin!^V zmaFDTxL@u=Y2!`){?*o^{^dW1R0AWlni3=}0t}<7&9b`R8T8$hg!K>QgbzqPpa}+j z5OsItq3Me!La-t!rG~lP=P|F&cQ%FaqdKv6#McFHp{H5cjl}HJICR~0y1Im@XLCZ4 z3`qR^bYY8fF2iMSiV=sEVeU^9icTb!3HLvohFgWl9!{eACE>Y;^JiAKgw2sb9F=Yp zl}!Ln3g|asgUn50YTK??gZ}gT)5OyBDG1Q2mY6wu&>&J>BsyOSQ2R+yaf9 z5g!X1zv*KHb{!4h^>O;gtQ$J zDV+2uVkba33K}W^1r79zZA>Fk!5Lv$PsPA1%J%2GRS`D#cRZK#a5hEHWO(XF3q zu3U#25mC`&5u>dE6Lmt6)V5Rf6%V6*zVr_K|F*Or{%@U(k)G3Yx zeN-?fcfkFlhkzac#R-XLYnVoec%^9&mp`t-dXzzFUIco;@W7Deg67PKvmjzlbvpDO zF%Wy+1y=9F=F~2x5v7B3o_^5|vCWJCWHn*fHcI}m%s`_i&ui6*%<1~CQ%OP zb%kiQG(o^W~5t!Sh|`PU&I zi6n5nU3rjE|jCBv7099@fZ zhehXx`_QtPwm>;@c3jO^ZiIerLYwItOw^ zOu>I4=MIB;Nm%p#kHMRt>?6lh5L|&FTa|NACfiQP=<<&#)7W4Z`XjB#sSX)YBj#GP zYChXWiM8O5lyzs?G(53EjreXrsE!7Vp+CT!mw_n6lHZYwF9YOQV=ZN0XM7N7DbmB|5*O%T0XctTx9I9@qn+5+?c+vJ({7=EUd_I0pcpX&c zuZ0`SmydaB5W{vrUDB+k#NP{#tVqGLg=bb6@KWK86&Id{8H{;C-#r%!ltKt50h!rg47;myXnj7~06`qV>>l*fb zbhmsel=(1-w1oiq>JZWz;d*6A4;%j|9RY{gSe(_qQFv=r8onZY3jhB&@#88PW&bL8 zc#{EqRsb9whVxHngLj&V6R5h4maHm073_wUNK@^L3f{Zs6 zVJ#67u=q=Rb<1|JqCdKt@v6c8iN&2kB8SK?fJL*KJPSb(dLZcL@EQ%L6;|_=MpcVt zbu5sda>02XGsrFw!?=S-In3p+9;I_=S0W@_;Pr%q#a*ER!*wrzA6_76S3i$m7G7Un zoc!G|(Hi8g+1x>xOVeRH09R))6s=LS@5$t72rsTNtu5ov)PCszN8M_*ko4qiY!V)O zQa`5dV+gR)I{2V(_s5c;)g-W={dy0Wh`$*U-hc8@ISKn=xX>vhOZ#nT;vCm{9%&0+RPoIa&aN){U@%{Ew2uzI`VuZ6I%#9G zU_JsWweIDYnq%PJ;MTvK1XsBmN~*99)Te1kTqDIfNgqarjuxkOmBL6@4&~XwW)bvF z0)G32=f{^|kLtjAE7s&TQjk;Jtr^!Tx)`n=o}e63N<=OAqGwMlgIEBVhdY#@a$@cZ`}F6@r}a4C*^`><5>2` zP|V4SpfGb|B71&Bgc!E@?ZW;I+0@X8(6J$P{LK-9X=dSOdmLmIWV^Z~#%AQ9_AZ*l)$bgQtKUhY@wFdFx{gmWyw5dG2f z31Dn8_gr{;&!H!0HJ^LTyztPT4+h6qj0l(>;ZF*%Xz!TzR0y!RLh?4SvxS#hKuMdUl*Nq8>|voq-3i2Lr=@ z#2+0CrN?K*+78zWj>Fo`!aDGI!Rw2T{n8>M_{KpfgpmaYV4*4K`$wDb;kt(*lJzfw za=jM+S;$+TpxOaPGLT-wy(uk$3GmUduw?y2YSpl?YrQLm^pzYMneSwI);a8plZ50o zI_l|wU|M6M<^+UoYYLem@L>rbuc@OTB75Fb>crqpqM7gD$8Zi#yUNO&w6EECSiY%4 zg5#+i{JikqQ*)`FfH3q_CiP`N82|Km>VPCX_;h~i)zygYT!UEm(}oub-~5|1kKMkP^3g&ew|9xlztqH>vmC zFyyPqT^car4?Q(mRiPTlunpIi;1e~z$aZDRIo#TNG>>G4SljRA!A zlMAz7gICK^VgfSJ(;%2^DhZWLx1~^N!`#oJ??v zW|)DyW(>W={o{2SRScLdspWg%j>H49 z`m>Vlph~+#T4}5p7`I`EL?2}O*zl^~F}HVZu*1q|;<>6S^PQfmt2>z6OE(-|p|YO6 z5j9z9-6b(~MZiyHa3M8Jd~AqFWFx-uK}G09Vh%UtV}}3ina3@JyKcXNI|#zpeh`E{ zg7hXNW6RE_oqR;OO8ctxh>?NXu=Ne`VBmNM_%GD4`(@w?_4|s4GU4&xL*!&30Z`o% z$uXG*SnWuR)6ywvC~j^hP$6m%=?^6*aNEt4m!igYn-Hz1j8)Yg&6;X?53Of3*6J`l zTfMvb^Xlrhu(>~Y!sdPtsmJs4qhNKEa55!PPhBA^1_A4Dj~j%>o&)!s2-n+?P-%6E z`o!{Q8*#*YU{z4Hv9OzF3X07s_O}NW9PfN5U??1fhb+hbZAz=Sb zV68X~h4(xHIYYif0TCkfTg;wse`Wh~HPT3JYsGjJ@DPb<$k)&&!Q$Sz3E!_cXXA%_ zyJ5c~5ej}^-^t^sdVCe%wb)psdH{(U|2VG-JQGzqcs1mEHt-`cE>&EXG7r{*VK#+> z6NI8`xCZ{;52ape z_gosAO&FgT92R1p&%{WW@qCtj$oFe-GK1@Vm<-e8!5?5F1T8xVN2EbW9`dCOjS9(x zHb{K*B#8N9_lVNUa7*|Ut`3~asT{FjwSo$zxJUv|5YJ?SOF6UOWil6nOZh3Ap@!~B zd=Y%D`H3~e+*1p3IKK`Yd{t+u-K5;1E7f4nS}t3f1lpBMT5%( z?Ut!nBP`zX2<06VnzwAjUSY~_{~#lhze#ZaHVs<@?{6Q&Swh8DE%laPSif}(b_&02 zof>|`FR$mFL%wE7Fxt&2b&>~WgNz}EdE=PxVQ*u&-!+W^%N-JbBfMhQ!qF3_J&O_t zg-do0&l2WO;2b7AMtH$70sl@o?nuH|_|h>Ke=j7|WF?FrewVM}kJ)0K4KL#S z28bt|4X0)yXh2w6vpnfBu|_LEyyMkdcp|GTzP zO@y2?6ld3%;J9dYOB9%>tlt0HZX+mN8`8r$zy`jC4=-x4 zS$NLY0S?(d*m(rou9>~|9f?R|DnjB7;k#XVW3R)< zUxGKMlaD4?PRY| z-FI~z(%%e3VI+P7+B)Xq%ZXfe5w>r+T|4OeC}085!J*q#dLKUFU;gQ1#5BlB+T!VEUF8>AoY5C326rW{QA`_(ByI>dod&3N} zAxyYyY=KX)lq)r?l`VrW#ORjTB;QAp+-g_ol$u0{z+p{3-AHf4_JKQ zN;r8GSDYFrVWrBsA?Xr?{ZzLN`Zfe_dnju-^o4wYfjW5-%%5aStpVPthM~AQZ0J zRtm?{86&X~C0f1&xi{dm_~l-fx$KMp-(@$P?QXEeIJ>1t5_&bMu_-9sgopkh4jnaQ2@n88MfAxP6=JLe&wZw_ih)Y=Hg zNKxjjfhUen<48k3pLci~%J_-CWzh(_^iT>ecGgzCy~x{D=r#|%T9_dFYr5?NMzkO z9!;tgGK5JuTX;wSkC9j)UGdCVjSOzrQuzPIg^!wUMb0O#Ym|AeyA8IZ0>?LGS4CfX zqCR-GMe!bf2SU}>pjStH55v|b?pa3 zTc>|?m35y+?Q?e$^9wmq81NMdHT$Q=b+^9fWh0-y!F+?V!n%Lep5wne5pS2qkwcL&Hus(8yNRjOE0#_15w@s=CBI^ zwcHytI>dyU17_2$aW&KfGm4fbzS(>tAc<^1RZ!GR7okAZ$e)YDF3e0o;B|M1vYI~^ zn{H9|8me$+k*Qa1db2NzLE}@L=S@ie=?!GbgGDXAK(z+{O^`y_^W0x10U8ei0umm7 zA}}(fjf@H;7r+6r*=!)Pf45n2VY50C5TVWyf71=e4(^M@!_CgXh!_=6MFYY`Yye3I zixqc~pw1mEPC&OVfb-+cK9(`{Mw;3^yP-cQ7l}?`>F?9*CmlNym-o>aYk*F?R+HIcMmKA`hQ_9t63{zxD8 z%lj*O$3Cd_M|#sNGYATUY5pC6LIOcyc36P*?<%JJ@>>W>vKN-C!+=7i=XMoy7vAww zVcMcM`oeMhf2dT_i%S3v=_F9elVArt@+O`;S)2oCOn_kuGeKyE;$VP!v7-1hu8d3k zHs1A^^F&`1^{YOtQ1~NMqlfJ&cPL3C`Lf|m9$l`7a}Xf$wL9SRaO9J5@J#^?66*)$5Z3ZsbvM7r zg2bKhCBqi@kP8Hsi;b=DZJxUt(Fu6pIEbLU1O7=qn90^cBzPn_feYM}oWNZGM`^?0 zlZxa6cx;&tzA&g8P=!7K_uo(A5oF1C?8rCl?tQlZ33^@0owKkZ;+&_W)Qr<=86q-M@ zXpsXbMhqt5rx@${slj-qyW+_)6Iip=T;VP%5YWE#xY zvlpT*>)ltxL{Y6w8S~ie@(ub0O$hvW)H0@&*mQ`@$O*{eyhJOl(rVt)5m9?5a@j$s zgw##;v(w`8Lt_9xKk zSgg_2H$IH(Z&<#EKU(E1m;xem`|;7z7A!2m8g|KRY<4iBdDu0uC3D!%!A{%17Pf4^ z&bD1PyDKd6cfKp+6W8uGq&Duv?r2~bvLQ)eMkl_q13H1=4qyg#F>oBn+9-vIAK68G z1ek6hJ|P)E=QIXiX*cmv)DHtOl)J$3M&if&5`Ba*hHNK~Jw%V1@44|a=0mBsC$W|W zsJe(g*yWZu@uf4wKc7O!-Bo`!LA=f`M|u($A_D_MEv+5(J?MR|A7R9E#AnYFe*kXp zCEg5tL0EqoSOF#miAT;>`?`fx7Oq)Kk!pdq+K#_TvAM9{ZCxZTA@2+7NrjX~KdlrK qONH&%O_x}2df0v8HxII~NSZ;6KgUe3djy~J0i4jO65SMYX5)V+?1!oV diff --git a/boards/mro/ctrl-zero-h7-oem/extras/mro_ctrl-zero-h7-oem_bootloader.bin b/boards/mro/ctrl-zero-h7-oem/extras/mro_ctrl-zero-h7-oem_bootloader.bin index 1a056aee87f02d0b61b42d513c72c116b9eadf5c..51e7816dd033ae84f24281d94d8c4f873ace1e72 100755 GIT binary patch delta 22150 zcmagG34Bvk8aR5+y*J5C*K`5W{U&LlZCXedpomDCw6_~rR%O*dVJ3(U6>vmFlCo%7 z)XK$~LPc3zP*iB4GZd_?g1gQnK*!R`Pz8y!h&Qy5+oVn2cT%01_kZvGUVgumbM86c zS?+hfbI!M&+wP=#oYe6y3Rer=l-`zHkzCr9_;GS{yjG;Cy{6hWq(vGezBv?E5&!=v z8C{0NEj}bB3?gy97m4cz+xjbCYU^L~Ql;3VyCBs~(2AHk3-JYM&u{5H6Mlz5;@Kf2 zhC{t?hfrJ5D3r?DFiK@0AcRuCe;cvY<(rS6mr%ZLz^*e7*z-Pt^rID6zzs-``oFZ3 z*w}y8{)dVSk~&p8P`z9$Mp7n`g-+F}7osf9RjqsfK-{%4Q@{wn#BUS@EDJSqY z?te14)VbwnrS#M}@NWqI7o<{mQ0`gDm|6*WSx^C`n#3b>&O%Jmb=cQI;wXqsFeH?^ z8H^|52QMw6BD5D z<6vj%^xXiITdvhaSuRK_7^(usP6MPWbu2WZN~OdCN}W0AydcekH#g2P4ImiYJQ&;p z^1K$F*Pey+1!)$+jL9@$hw@p!KWlA}kvozB6+{3K2>_`OY%m%ci2k1j0rt1XL?gh> zN~Mlhmyii-pr_x-J%$_b)C?DDLq=+WG~s2WH5ySRMJrM$jBD98gg7)u)to*9aaem1 zYME^!rq4klwc@PAYR*Y2Mppp^sWC>gs0x;F73ZX^d;&~pg20}WEDRE#mI9t$|3#@Y z-z=gkbFiIGfcqZGzlZoD#253UptYXV81p%)2l9S~yq_Vy3Gq#c#r&*u@OM$V1{v2N z9)NftU)4JD2FQ+P|M6FUFG2wvz(^&0FXL8>t{77e6I~EhOApwe*wBb`qU_PNPc(kg zh;)R|uQhG$kE%V>$Z&=ak$C^9*^PM0FD{h%s{`nHouV8lx&Z5LxKQ?W2fWcbDwxyb zGJIHFLeR!CC{=hdVKk>Ga{?#<`50oPVJhP67n-&};{nfGfMMZ9`QN6JWrwsd5wPH5 zvthDef?~6OUvSkWlbb_khVgo9XiFlWVZn7sydz~;aXk_@3tJQ#Ze-c!!%`(Anh&ki zLMzokVYS)SC4rm5ImJmE+f2Z?vPv;vSZt-mNP1Bs?Jm$Q%WFV|5)-=9SUzCV#g%Hzh*Wq_p@eCjE zR0?nH6ft zVJuwfK^qcT-(hQVX}9%Z3l^6QCBVD7z47oL5BV}}{92?M-X)<~i0hP)0Z%L_kFwU9!n;-0c9^_T zQhvFNN9o1RK-2R;<7>oFG^Gb;M_Es`;WRuY!#G#c9H;wgBF?x`RO#3QmSUtUq@{Hs$J0omgd~W6X@Zh`PE3&TJU#Rw?l~79a2i zJYV?70Hx95+dxgaCj%abe*sUEH+cz9#D))CQPxTkg@sp?p(snd6$Xx|zVmB8>{}km zbW`Hdz!%W{9@i`>3x&CHSiJRPE50YhSS)Fg3-pN zb_pFQg#j=0G5qnOG9Ks8f~WDmc}1PY2~Nb7OH9~l>v`(~mXX&m-p1&m2sz{lNP!7 zxtHTn8ZEX8p6KcMZ^IKUwh)>V>->E#B-Won;$O}LZXz91&Xk#?JQdD+OYe0CJpAdO zp*L7RkHnb5AB3eA@Vplw73T{rF-f>c_%5ap=LvDK851IgAAOXN{=m>RGh?Lpq_zY+ zvBMlMJ8o#Dk07yHGACkQ<-m3H5n7xkJRYmVcZ64Br-p9}Fg+ZfYIVCPal3FiHiIe; z2waLG?iEEz|yFZ!rN-42LST$PDZt-t}g>uFvsK$(*Vl2JeM2Ro^pMxxv-r-bn zl=!b9lz!NOb@aM#T>;OhzKjhAVA?+S$zfe)IgHlQ6G%KS^o=&hO!8}C*+4geVEwTH z&+9_rm~8x>ux89ms#Ps~G$srGL+BebZOpM@+(28XhN`WK;JTW{%XU-ZKZNP(G5C=1 zpn7iQ=3!Yw_iv|p`>+9;9pyXVA_s`9Le-pT4S2pJ^DjmZw*IU#20Z6a6AEIRsS3;` zKG)$|Ra{2o>%+e^kvHdfz-*gQI2f0J-w;~kG%-&N z<9v2vXjU&Q92pti7Ng*fOTrC8Wc=hM$*{x>jTmGAN(>)H+)YbCE1`d%OVxZ1@J$#m zjwfTHMCo*@0f{S5Bb}m|;&C0;sA0eT+=ureom_)Cx%jaU>F_?ehJy4NpKvJt>Ey*; zMhA=sU$qs9h2D`t7PKlrX%ZB*qDaiDQZn`rd?RBRsQShF<{CMj0BXx_{g{j#uTA8g>7H z@C^PAL5*Yo2f`-oPnAyIyyQc69VCh{JCMQj_^$g4SZ7nFv;o$fXw+h3UVP^<< z_60t7A?*m{KZbvCU2OTaKWYo`P@zab+F$!so7etrCyZrtzp9o4s*d%c28JJ@oLP;e zB?WB!H@qt?>#T<@C#+X3ue)Xe24)P#mN9&LBWVpN1dW;-;4+_NZ-kInz~2GUXD zH(s7~Hw-vOnk7|`0F`P->eNDt`xvO{<^oPMO8XNB7238las=CcnLaT8NXxuAwPy~walb|oVniXE;+=Nu%v#3BdQc8wf+!d&p@~iAx&uH z#^6_lFS&8pa>C7>!Pp|aubn*Ba+ok5jF{qM#3Tp_zVHgQRoxO+kzh@*u4_S@LR>i% zWKK98JAVF$sEzQYWNCVu<$Tmk{PF~=T)ZIRy|Aocy6^Reld6q!@ve`?n>2g#4>}&m*HDd9j4_T0jfBoqFe*?FR3YtS^q(LiHLRsom$~P=LmpY#Dd!F|GV!~Ba65Gp_3=(2GwlEr-1G|nNSg$&BO5zT$yqLH<9NU4urP7#1iVvNIaWu_ z9(Q8L*f0t<@`m))3>H5R2q76oi?Db$(6cffMtQ~mFV|M-0aYIyeWTEOWa+QoBU#X} z=hXnxl2lZ13-EhVPZu{bA$-e@*eorDSJar364+CkF&1Y36Vuddrt3GnL1)}JM^bqbOC zQQ6P;do}$#SiEh;gUXky0VORt0=5GN-PjtHN1|$NCe+d)`+D300=3@ zp5{79-5z^?W$%nJtqb+cn2Sg0D4{SbXOg^pixF`k=%_=9h*Qwhij<^Y-Vmv0-n65( zTmIz+EYcWvz?sw*@Vw9lve=QVd8N;(?`-_CQJ$gggd@v~-5Ew_Bi6mjhk0qw6w^m= zRHyYu$gVZrSx=T+qNc*EZM5X6i^SFp{)UUbvwIzIEO`pOP?XKbUyxX~y+52tDbO#y zaan&MO|K_Xi@=Q@UCNd^B&MLSQ72M#JETUWPf~1#oIB)op&AiyDq4WI;jmZK6Uj*AkrK*kk=+@2<4**Rz)i-Qux z3+^@r&sVOxl{8=7T(L>Uhw+OQVHbse8&Z?3!2MjUjlO?Ta#WFaQ=_lnJqK5q>lT`O zKQ@O7DLDoi%z-LYIBiH4wi*g-vI;rqZd7^@+Vv)p0WlZp;e~@^S0mP<(#gtWmdPrj zR(&bQ9eAqONpr)Vr_Yeijo~yhiX4)a%PUmNqE>DHABa_FM%o}S1jpj|= zK;dYU9S1x=26U?uVp}4+Kv+VeR_7-`oAhN^3$$3U z*~sy_UWz94xJG;oy8lanFaR)Jtz-ghNi#bD$>ssH?o)_KIzi#<&~6Ih#+2P{nuF&q z&UA&3eBok@b3XHQ4FJzt3@Dl6-!7?GUlKNh3#i{>v&6YSLHY8f^ zxKyOS-}+Pm2Wc?`JSPH-wrb<@enm{x`Vmg*qmPg_3MS%Ko75b!N&%$xP)q10gU~Wz z%HpFRR&9Deeog;#F(|w0&motu)*dw}zE?Z*p6XW69aWpmqLHrpvu0CVML9mdpf7QE zQ&ZpJ$dInlo?X3&j(ud`~?BKbQP z|MnY()WOjT59BPetqd6We&9fl4fn#X8;O7w1`^#K$S+4+_6-q~Y)nD!3>~bOPaqZW zjPv(c)s3`O!*^TjOZ>X5`?D)i8nDwLm13gu>U!N1N}sIMz<&<16PYB458;UcPm;f0 zddeVopF_c^6KBxe>O1=ICP{LRZ29Nl_CahU}AbG zsGMTcVO4=n6Qyeh{L5igr5m-n9lC+)DxJvCy3LeMw>IFJG-QO`Kv5d-_~398O9Gyw zaA*^%aD;=55CJ?b;9wwP84(tuXEOZ%7m~|7^S}sUlIdY# zdI-b&JK32w(foNiz6e6DFgVVAc>XZF2N1HR|17-~;yr+_k@QmrcxjlG1X)73dB8YVx4G)s7|{|b zb1?2vuy_KVa^IAmlhT;#lTw^bby7;;BE8T1_ei7L*{0D=AG*UL$96{EX4wT&mWbMt zCL#7a2-y%OOdg59g*d8UB*Z~H8A9{KkuVY9xQ)Dm>7X(xXR;i1j5(p(NYtUa^}3DS ziqRc=qz#62ei!U6ixvpSC&pH!2Yv?#cs?0Ix;LbU3@|k{w3tF;eWrubhdGe`q7!AD zceeMVnD%}nI{2iq*NiMrj_Sdpjh5>_?L6CemW~u+Ch2VC9nTIoy8ig&+fUwgk-@y( zfimB8lJ+S57$=%w8>l)4^^iP$`rU_)wfD872zh0%9nEO77y#eZ94wIWL3a54;TK#; zZyTsMhM`vJF`8fA&&24~i>|R7s};68&m2RUwt)@DM%s>swx>;Tjx;@`^Z&i!Z~W(7 zi_hQ*w38QA^0Di`c2N^_&aaz7&j|iWTKtKinXIwpK-)RT`mcA%Z3EfIX7$Qx+d#%K z+l1+N#~!QNNK~Gbe)<4+Ok4iLvmgS1TGn4>?!_@go10vr-4SC{Hkt=EuhVU|xw@f^ z&|}|T*KDkWR^`Y34bSwkhk6mT8TbIh_=i6D=(={}Y$)}7KzbaoeK69c_`&Z);~zxn zwt<@;Xm$je6y+htlt$A4wN|_N$LpZ6U+Z=KzR&r@K)?e52)T0G@hj5trfwYAQ=*SL$wc5I2`%X4a3NwoD*&(AK zps6oU2m@P-xZnNeTVp*aN^QWRAMpMt zU)b?xlwV6>|Uh^->@c1(@jUugrfi9{sW*_Ah?j&@itx`0G zrg&{T-T38z=dSn7zED`}*Svp$HBM;@_(%FT)6YTrncxxf%zC`{ZRsHu94o_#I@+hK zCEMj1fFYaZtcpYv5?9p(JY7S-iPkT5DsYF&8f96`a=8m!XdFMYUr`9AqRQTqxP=nU z!DJOsy|j&0i#Rd`)DTn4$G{d|CQ*jf8%?l;MB1W{adt@gnnh<`flih~XWJkq=@^m0 zGSK(@-MboCH$}|q^=grdq#cwlvz)Y`7TL&9$LipFb9%~2wzLO_S)Ddm`e#<*#)`i? zRj%2*O$QtFI}&M>DmHeJG?01{8AV)u(e?_DM1W z8PpDl+gxNdBTae{t_yf-BvOX!34Vx@j6eiDcLv{cT~?ru5u9AR&JvE<2Im1e2gsR# zRCY7~=fV}~iyF{FDz8ZA4jyq^WVoSI@mR;|^2*+_g!7WB0M1)0)-IMpswuDXcCLxq zt!{(kfle`w0Sc#u0teObuy_0IM9tV5Gq;;>?!C8t6P0sNxO`-2#srMHC# zk+aD63he8@qc!|LXwBUCGVrc5O4sxkM<3k?OtBg;60xSArmPYiGU;_)`tplD3K2J%J1cr>3$qEe7q>EyEg-m6ZYSmopfy&$Ogv$ki_yg zEJStz_P>qLLv^!WaNWzt*g1mZ6s{vxz;z-|F{2AG^!2>B2aA*j>A#t3%C zPHFW<+X|TO)$569^83ihtG!e%HJ_Kl3Une`2h;}$2m{ItD_95?;q9fyaehzTU~Q@2 z^Fr`{$Kdn#2Rz#Y&sS6q46H?cEzBfY5-@MF__d#`r=CFCFdr40 znD@|%xRs2}y+Hm>?NaKpcF7QxXs}D1#x8|v6h1l{=k1oJ6)N_pnCvM0D9&!GTH zr@KaE=lr&ZXV`TQ&pd3gUA2Na}LGVKlfswa>OoR?d z2c8Savst8x8Mwe`yNz{K%Rzvp4=*pv1358={IkLTu;9Nc_#YemSHsQ~DS<{R0CWLx zss#bCF2^nyUw%%?UvLi2t!%I>CoWK1xjdA95{?1bg*dasg_$MQ60@XE6ilKs4a}4Q zF10KXpoHh9$J@qK#Fp+`Mo4XuW#Ov$a*b#!)C_FI5DGP70Ed{7X3?@y<@=V^X!lwC zo*(=mx(`0V5o8W|sy`$K-q8106b2#W10_OlAePYhHBdTi1Fnux6p<%;h+IGdY>qt; zLWYjRju)1JHXlb?Wf|Iy8n&451!8>1yK%!#6MYFa;5;PUc7X{#4+}!IF%c&UFBm6) zpGT|lNp*GeJhhsy95@72m&9L-r|%s4^N?rCurQ-A|K7bVft#v|$)I+Y@iQ9nJ1|v) zxE`fnYy(3*NAzlpIL(LB!@%&xh)cXE9j2bU4a$1IBz#z?PI={YbqP^?5q&>v4FgT+ zD9My4>!YIKuo!jpM1NrlE|>z`+C+!KJw}!$M#_$vCUg>wSazWKjy*E>JX!pI3dsAA zYU`?@My>U*^<7iOg&(bgMVMh8J9A>7%F2SNAJat=b1$iw3hE`PH4OwH1D^%YGXfvF zqPcHfiTpoYG0o&Se?3675ulCM40+^3U_k(jBQe~9QqtTJdJnOwst%M4d0r3>7QHD$ z)-Q}mm{}Z$BZWT}C*h02w&D!@xp1s_YSf3)qcEsjt4^8}uoENkg5WDoNVx%~gYd3b zB;G)T@@)`<*51!pSC|OQ--L<$blYd3El1*dDTBxRh(YBKgECM9AaMuSER}#*wt3i7 z3kW3(js<1au8-K(f@Z7*`-dhA+M@^oPXrr}+kjS9ox4$-hs1j&#=Q}plkBsQI0@2U zK>C|mtv?qSkvRSov7KZYhCNF`MS4!?=O{rk{WP~|buKP@)EBKLNyT50je zHo%F7EEB9{4YVyA2N6wVzrQ3@l@SrRV&t@RRPb?M`Uc_yk=DpKf~BSJFZ%B-c_(MfVO0q zwlaFrA-ROG(sbLFQp7$3Vd^}@nv$a=Je890bfg~yJ3Gy*ns+yb6tSR%#)dl3JtHm0 z$5$(RR1%&+OSl4oHqRK33t+-|$eW7vKIdH*&ByaNFKPqI@H$oT)g`KCs)*q$lIu*Y zBSyk0NWuvy!{dyOA5wUBfvru|DwLPqw=5NwY5S_`l9Xmx5AV?8Qb5mpZB#ws@|H@B zk4TXrGxb(;OUR6n`$H?QNLluiFewQ9iby zNVGGQPcd21bK0F9sdt>Vxebwh&LR;rR0AO6C?$|V{LA^SyBLI@wVfeuE~IDx&3o9p z!y7wbx3REk%GuNIm5~p7Yu!Y2#yLd;_M$JFkakN?kw`H`BExjLibR&_fPWQp-gWX0 zvb9_|?S48k69%?Eavc0W5~*>f4%k=N-e@Ws;8wJ|PP;QBBb`06g@84xL)UwC1E@>% zZ?};Vr|=J(io{yxeSjJt*#%I@y>tt7yZ#Nxc{Eb#JS;11gJG^9O_CPT`oBVn6-q4s zDM9N=iG9TmD5;L5+ESt4H*7)RTGzYomGHhVUOMfrf+;vs6Cz%r=YrJmWzE<8{))vC z)6fEVVcYid1Pi5nY+E6m-GLlfi$iw4{)f}7CNd0=ijQ(DbA>f>Q@(7{ zTS+%Rxz09Smbe30uvFlEiKYbM;~6owEJwVXi5%a(yEv zGd)UoV2UA#F};<*5a>#t25-VST`;hxzHlS@-99D7fTtmWW%lkfO>Se4R*DApf?AMd z_H~Kdi)mPeiCx!#vu|++rrT)e_+XRtYhM+II`>OyhKYKvQx2(A5F%7SBb8zfizn%= zgyF9*DRhxow!6NBRF~~jI8P*!7G%3g!}TSyeK?nX?IU>89QLX!^-aVkLf{~v_CNsI zSEchg8Od#=eVwSX(Jw%PR3xa>Tc=&7CV_%ZIWnj(iuG1aSL^_Km`q`8Td`)ProMzs z6Vsg&9O5N;cE?w46q2nOnPh|Jv|AaO_Wj5c1H%q+8}K0)-bW~^ytuYa=`Ns%fU>8} zpn0Uo2GZ4FZCkVylUQH!xvK}%Y(1o*K_uQ~6+Iq$kdLcVNry1s^0g4u94 zr-U^$^#zGDXcdtiK#a_c;&3NlbmBUm{ySNh6u;4@kl*e6)%9VVK_=l^6M?{cka)_TA>xpt;uP5U z?6*(ai*BnZ*z)>q%3cbjD%zPLMk%35Z#>L7*nsT}py`pKXelns0BVxg?3n}Y<(Z-? zgftKji_s{)Z;uCgU+y?#vfn;u_r=qF4C`w;+$UEOoYwbz%^#KlmO?9gdmi6^ak;Fa zLnoWxX6$dzfe?k7j7_^;Cv5P}N&j!}EXtLq-3ubgTNcC4zlQE=Qf8KPD)q&kSAM3& z`_qcxH>#*;(m|Qh&4gY82Or#lG(WmvLtA#mp_R>Rvp2Oj-EpOgqnQw0ig#-eTe2Xw zD1t32%fY^f9}%w18e=1z#m=GgKa~NJ;{XHL0cb8$>ArVe1#3y!Kzmu`0JE+mIE!f- zLK!1R8IbKytnN!!5pQzo_^e!yOdoxsZWP_)$SaO`P^rk>I9RUNa2ja$VRc)! zrWXc7da{x2qQ2xCS5$<(B1C=3m%oqr-ujaJelqZpL2r=k8Q~ zfn5ffVhh>I0O6B!-L407e{}_JezIGrox}Yx%Bku7VXe$y(2#T3=lOXErJadGS_8l6 z@p~ViW*PBXIC;w$>b|A&Qs0p?`WM&nTkX%h{)>6_$y@w0!TihQ1pmSH`Y%Sv`z#2% zw8L1&>LSxH_xdmQ3UPC%*bEhP-)FS&3wp+IOA-3|FPYDry!Ckymg#P~#XN&2+96-z zma$i)1K<#M;P~vDs!&GsNo&APu$@PB-3i3O+YJ6$yD!h-7xSpT4Bj3z6>dY=LgH5e z9(5sFq+=!gH6wm5ZRU6K*Ih9qeq#E?)>Y=H=j{Lc)Aa%-^A8pzB*$2KVq9zS>G0mn!F{jIHtZ zuc|2OUv?|VvKye+9RboKv|&)SnpgEVg1K!_*fT#XWXWKUizwk23<_V(zi07ua84so zYM}N$muXdQ zh8S@ec&ASkiVpC26_!4bf`1jBeIS9tgTlTCa&7B?qsJehv=tnf-huO1bmNI~35PP- zcbwp?&*>~6qz0|P%KHiLpSOY1ldfm`@-|?-%t?%*tv^?T;iD0fbir(#D4zZf5Tq#Y=ex+ixB%OgrvoYT?*j}1RI27 z5XzPy_QC(7;{P`C|Cjbb#}o`w22%_E&ztE6B7)PxvYyI;r>g@V+f~0Tx&5|OLxB20 zECM&K8f!9>j&9$ox$-j->ClL%Sj1?SgYqumC)FwXii^=aTzWV7-w*!}m5Q#!G*B%} z1pG*hMqVdB67c-&&&nQf{^Y`Gr0q|GZJ(>58)(o7(ZG*?RD*SuHW7tV93a=gh;IQE zgi8y63X&xd{LcjQ5hK1K!PFQIn>3xk@1>f_rUQPov;fm$yth1NLrlwbnE#mS!rRd_ zrI8;&0&bf*=)XBy=scw*@pE`nrm(~1sw41S;zP|394HrGJB7w^Nc%CIf>U#@Nmsfb8_ z8WbYnE*b#FL0@MwiWH2m(?yV%9_(yf4N9B98+*tSTksa_fv_r0LO2EC8=&fMVo>Vu z6pyl}I3G`(?2!NEg|c$%CoQ}97@p;55l1X$KY~L?;n*TRX5KO&+_NasmOBF&IxxuC zTu#8AmdM*U_ZcIT+1)f-(iyh&ju|)LWG0eXIBNQ)6DIhG{I3Dez%Y4D6@BqKaiCoi zkk_4cA)V}qOaPx9aG?W{%T7jr4$^RS$S$j=#kqms$)jU9@i%B&z;h-D-V_9XKM4LF zfNxe9#UpkWXz@)uE$;kJ)lQI#q(X~-LGko~x(|SyV+c8q5cBlmkA50ivdP0@?6Rs>z9# z8#>dhQCl-Dl(-yDV_A2)g|iZcmfxc}UC^2e>d|XJp-Z6M9*8#t_j6_jXT@S_K=^S9 zr<(%RXmY?Bh?Y-T!CBN+KNy>^Hr%bi92~35g|wv_+jA|Xa&kp=^T=>&kAr`>H=#@p z11kp~(}EM~GV-oPUc(7myagMHnaDH1t5gYA@BG;jO%G;1p>64KyYA zJ*~r!fX*%*?#C?i8h92sy=oZ#TP>9XKjh11g8T|`C(vvgc^mR38(|<1K@2Ln;G4W5 z{IFC*^-BWtP%e%TCOYn;D?2G9QQ~?bba@g^5i*wR@f2bHa*g6XZz-T4O?Y;B93C(Hb$K3+ z6~10RG1Uf0zw4BNVrUkWzXw+);=B7c(4Yw4d4lBJ7`)*UUVC)3a8K122^$6v!pjpa zF&v*I$j!0jwuCX*aMFt0h)R_GorLPLx=2=quyjQnB}u}D730~{gHx@C`;@fs!HUu< zzXx_-a4BKjS>SI7H*$h$HTWC)!8fshXWWVMD6k57;K{&~)a}3sOftaS3?NMbwBJ00 zGzN$phjbv4R}OTqrOH54SBS-=wmrhal_|JYcnbdCKe2bEjIzBOIJ`mMNVKqt=rG*J zITRRiQmbwy`c$NeH(>E9G)>B}`0oIQ6bGqG!BiHcE(REPGQt|doM7?Ww(90Bpln~V zigBw!lZwTvfDZT}`6bYoR+Hz)!7mc{AKLFGc2WLgV zBM$^Gu+#)@f|Dz8Y;B~iz-SR;Jjb?f1^R?;gdbKF;u=Bsh%R*RN8mW8v0DS4J;Llq zG*tMou>O%H(bYkB;02Ad8(AycIP8h{36E53seAmwi`7Od&M!Es3z%WgVXqMOcpY`` zknq~$YBg}wm0PXhyq(vqtgsq2uUf3o?o|MOJPU6Wh993vz3CTbtWBrt{KB8tj-~ed zgxA*QCWk+Q*gNZht9b%AA3**no&~M$Djw;Ocy&m)wRSu{CM2z^S<*E0_aImNi2sBO z+*oDDU8EXO)kgAB8ysL8jS?+k^J+V#4YTTM|5f{pbM6NDRGA*#{>DzkWcsVZDOKec zfL~2@(0aWC1JBWB&$1$M;gFEH-eh|m)c-C}bc;0^*18Qy?DySup$wz=qWy;^BVc!S z;Fik{&(GOGMnxUptbz2F|E&>adH|}-bAn2$`n>ByQ1%Kp*T-kpo6G?95U1euz*3x&mUH{; z_0kG%-{a4_G#L|}it%}*6|T-C7@kP9opK6EO7T4{k16t51< z{Q~7-zm>BPTY-OVa8TS2fLRXx5&j=SE8sW|tud}Cv!1Q}+D=;&R;l4O16k_~4=&}k zNM|Sh>|56UZ8JP=2|A*0v?)t@ug4YGBQ1p{=Q{RCiy^LbGVVPg7o|P3vRgpYBGp0# z!1MEuSoPag)-l`FMJES=?TWwp0?un|YG@L`1P=4B)x7wZCS}u3liI0$F&c8^PJmNk zunpiT#Pl+{kx>1k-oKj?I%knRV$e3?lzBMth3oI8YnQISppvL|oV#rGq$VuM+vA#W z-VfUvnn*J{gPnZq(r-^L8eap0gMl7*=y7+C6 zfTjj+4a%b94*db8t%3W6NOajRf~QuD<)pOSAlUavD-6QpBHS!RVi!CufRY0s4Jkvk<;U1GhgWtcg=`Lttjmar_(7B4Badeqq6y@f02sYS%af zOM1L;@==v)vHy1`IlHt}1@@Tnk7iPT@Cl0^P0o5C=%%Ij-+~LQH=V>f8|)I=D)ViX z7SH+-To@C<&a>4Drw{RC6<5cy8NoY9$S;IF8gKh~SOm8_a#xOAG=Q59Ay`1V5z5%{ z8)Z18YWpckZm{SJ+AKOGT$FZIuQ~CZ#2g1^7eT%40KaYR-w6CRLP?sFlD7TDrbD|T zy}O2@oAwk_4%BeM6yLdQ*P&g?rs$@ZO^oxm;IX+YXI<*0Nt> z4CJ2ah-&1mU56f-)U{v3%SKOOmh^=BG=qDwB{W`o35>0tw_Q)#R~O)CtQ1EbdgRUN2$j=8e~ zQkJ@^D%0Jbs;v@TcXcasXYsnj%cCmJ-H6C%?ilB8k!Ec^E6o50(Rrq+d{{Xa=ME88 z$?qu-j9hd>sY4#i@CU9XMI5+4%=F3lBfuD(1AgUu2)2{(XK3Dbe4912T%~zMdeFc? zbu1c&te{9a3SQ;GN?-x?dfp#Oho^gn$#peSuev#mXVUesc#xQwPN$AVqh_YVLWl1a zfMPd}zqJJCIjgDMdei7?>3fu3*=wXb+bCUqBCTt0s;cIy<@fZ^I)KscS9Cf)h3Q9!Tl+>VTJ1iwD0;H`~sZm@$tMaoc#l!mHX@U+7l_M2o~1@Km~ zp*7-Y6w>n`lni5Ux;`n9WH52ekQ{< z=-CbiZ6w|pCXfSZeelFvV>)zL-ct* z1D>tA^#HI~NL&C!hEjc=4~6e)o`EZob2sZSBRsjeMBfy!TEa^|yFtm2_;=WM>EmK+ z80Q1`2%4YOi0e?Q%yPt94@f#9+}Nyv8@jPz7hKvM4aE8uT;HI^t1shsh?cUQTucRX zUcJ=_TMCvD{&AWE>EQaWVMefJ#R-Kw3uFTL zjL4uYneO6X^tb%~c6}$QbLbO^mRaDHt}cZ6AB63A$TQIkcV207SNRW?s%5(6Z%9RT z=WfV#VY;p0Q$f0ob)Yop)(Daq(V##7xfEOYy=z7)(N;OmcKL{Vv{H0E5mQVv?2JL>1JvT`Sti*F)fwB{!IrU4Zo-SWq&+ z7;$6)hY6?%vM9XAY7hhi9w(F*Kp6v=1pQDDKZm#Dyu(oQtS=qPWV{b<$C0{wp>7D& zg*!{o;lZ{?tO7s^0Qo_%6(Tr%(HNjS+k~2}F-iM_D_LbkV$mr)H34j?1-UWk^Pu20U^xEyT);(#^utbaEt|$fNS8d@ zTggqCH6n$oTh9q)+vnPfeJN!)|4)_(>!(tfJ-H|m4=#A`wa!uFjyP*h z%OO+j_i@&YmN(*K%5J*Ud?+uvYOPe!NGhT{18AqztLh==Ms&|!>uaV%eVBTqk75q? zF?g@#7pJU@(3ipco@L}400_7@aaxTrczZe=^x)>keO8o)@7ZV3Sz{U-K;}c2$u{Zp zOdp2ng3=mmNYOrv*;;IA2V-!bOIWhwUi_}GcSlBocMz<5;DbAb2U9#%XWG%$9*;O< z5fZNmmv`hu%>q^m`qRIH}QW)mye$S6k#yNuK;+!k>dQ9bB3qs;?kc<~&Cia8$6cmC5&C8Urft_SfPP zOOwh8|5WHk_@)mnBbJfRK?29Ty1W!t%4Im*<(fg8CvB({1~AFHM_Qsnx|EE=E226J z;Ekh)?TwIULD`==u0E!>=>D|Y((aPOv<`Yghsd@ZA{XJGmj4nY?&+pTgudE0)d=y8 z9po-25;fqQ&4NWj)y#tCwI>y66=hY+BDq7$Bv0O;LKn$p=$4U%=kXl>C@@EXWV;Ac z&+x@+ZUfu+o(VY%T5joA5vLy;E7-8I3mQ3sGruZUTrbU0r7ypj> z=&Vd@xuwLa5V2ya*=!-zH+#wdliri2-HvzMER_QkRr|L#8>i{bwp2Y%OhJ8U)w9x5o^(cL;2X2`RDL(Ww6r7Pm(lg*0v@jLS+W;J@n z4;OKnWO+B-YvXY}oJ_wlcs|b*Nr>3fUdf=GT!EIca8RD;j^a)U6 z5&HLNk}ChFe5ACxWR9t-&kPq(CKx2~{FB*~V(;LW~1M6RWey2%!31x%-pYYvZQf!0vt?|pC zJIuYtqwF3Bz}ik>9$aedTo#o%? zi(rhswDDEfXKqe$!l?BshGz8AVVqYnfW7kmMDrlQSQ&zJqi+x#smV~3K6P*itS>FQ$k@vo5BR7(2m2!MLDLufTl@nT<~o)(o`5rM8RTKF!lQ+OxQ!`hz}Dkv>aeN|CI z!giQt&s~LYbRN(|q1+eIzwlMZCoNwu)*cE+Y5xC&6i|2bmakB?DIH$|OKjWgNE-T7)8F;0O5Q)v?sxCooM5(K4 zR&vT2lIQgy*p;dhIB)^Zmpt`D37q741$Zm+d=9>d23%n96KtT><&b!2P!87(p04h; zE-)kUCHQn-8+=p*oXf>GTi|m&ze!T9kpJc&0{9*9KT`e__=QK>;OZCo>K*y6-^f?* z=D@vS^3gFBd?gOSSL2S%(GIBK8AOZ!d?imiU=QZN(81@Od_j$TMGRSpWD42~%SZ?6 z)8s@x1ey&};vf8Pi3H+E(`oYYE*sqE2(K=QOyAR1IRJ)pz=JtCLQnW-Wv2!-dgQD| z;)K&kRD&b+T_?P~8=AWVu;R;SwkTxI|2}_thSVnkzSIR8Z-QB*LQ8ZNVspHe;k6Z? z^oPo$!%}J&SU)l)J*{`VUa^ur!$uE2-zWfpWL>v$d)cKOCn$T7sTxxQ$XfEq|tYpc*db z)Y_)yR^-9=>g)yd9a{{2XVcsUO0Y;Ci*GzMwA7ak|BHN>yX(0CAA8Aq?5^jZ!xM%bg9oXd6?2fL7Yd# zUJz`DhJBuQhb6Ez*5>1}AA`yT8PNjNBYe=1YHdce-Gd2trXJIsVJ?mRZnW_i%5PJ|Vz3W*G>x4WbE!HrlZ1Y{u@?p{% z((YTv{#Hi)20Q;huoQgT1}e`KX1_X$zcxf?D}j$hD6B0N3|~kyS4uO)nPnAm@OB-* zYZkN;tEA7>PSiy34j3$Y@Eso~(gZx0K&1D0#!A9_uV%(k{9bE~N!f|-pr{&??2@ds z#`-dRkW(%E`l=4!6k_(Lf$zK%!)VvgKO=zvmiUZ6F`%iDtYYdxCrk2I>Xy zZI({}N*09r6x{#)a0B|K{ZC+Y0rg(?* zk)7bXfOYAq?fsikh=%desn|!;drY*OqQRR*c>LgKtP^Svo|@Ad2aYA+`%Yr|w^)u5 zItb4ScqTD?1O@GfIOMl-B|H=O(BGcJev89{@rm7s;<3${31&|{Vv8ZpAn6SFL|{7H zsfG{*>0^+W1aTUKrN4zYvq6bB9SR%%Ys^;F+UJ10&j-$p$reI%dIP5}I3o$fgj69!LVo$jI- zl*VF|h7d~o^gYBf@Lc-`>Yi`ibR>b-^*ii3bH5`m!S+x&-i_-~7V3M`fg6y))VJ3$ zr+jW1G}>QPsTY;BMP#AzFnI5-w1_4;?Cx{FqcY4!fUAN$CdecF_gS!6tVQJ+Q|p&l z$`dLr<@J@+EtHqA)LedkNdj*c56-bC*b?~Nc(5aZSHb@T=;dBC*fAAiiztW6CR-t6 zzsVfT#|(DdQx?kCLOc;-vq({)wh6%}3{OxKq~uz4x&)gM%IQP}Wfp0Ql%>Q1N}c6% z8A`LuY3PJ$uB9K%rR@are$yIwSrcs=V~yvv{oRFy{f^o3w&1fCo^#`Ek-S!f@1kRN zqzywJQ)FR3ip1o5zbQ8o8qkTRISDrENL5J!zl)xJ>(Rrw9#46|jf$vw()e9S4RI2L z3}1F=DzA{aa}i$()}5^Qr9N^G_T zLS%WAHIfgrMB5^R2@CiIwtBwaHdkUGoyk7WpSQ8CsEzc7twys6U{Cxp+=Ea6XTx(R zgbNV5Ap|f|U4>Z4mTMNoSYyi*`N$f&-|@`4Mw}bzh^l#}@kArilll8=)0V!-nhzQo zjqy_?T921C;>kDMDC-ZWrQfkeULI}3`W`pRaXa+gNa7dn%BrhW~ z(y=DYhO~?|-f^aBGgKJx9wHg8$Um7bw<5p-)WpLO=STl{)sQ-7!Acl?19eYo4xJg! z8Thc4Brem2YmwL|W%9TViPMCCE3_I?djGATp4N*d%NNpzxumWtz#*w)0@NX>*<ok3hchT`ZwO+SL5Oa4=<%WD9K!{?vxT=pqJZm3(gPP}rHo76O%~)LR#{e)RVGY}iL?n^_$^NPmT#CizCs12RIE9b~aHnNCEUHd0 z;*Qp7Gq8Tz%pE$$QzbW4ZEi+d4M&U8kYF68woe(JSf=6bv(aLoKi`Vq=ehj*lWdgU zP=&=f-^FVP)8efGMxSrX=dq#qqLFtXS`77NS=I1`v1v-*vLi9ne}GRZ?cx{Nu=wO) zB6PFQmjM4s@Li@$cpB+atqC?7YDHqZBp0KGldNHlNSrXmp9l{M(J+`0{IDs2#X|#F ztntglZi&%{l#(Jzep#^SWJw;34@+2_DBy@_`7yxZ}M<}zS7PWqS>8Kfd{1EfTsf4Gr69~{tj=W(-xIevlf zzn}kL1u}S?xxp_pg%(xvnEeuy(iJReA0T~by(+$d+9pRKHs_kRg5e^#AFd(2@YvE= z`y~mz1)=&3cV0rXkfu{YDm<|OR#}~SRF{fxhv6G1O(>UfD1&nanqGj(zDf*3Q@U|Z zG=IDer{k#x(`-p!i+eXmw0Mxx==xDYra;qgw(p=ulK+?Ox0_y4LY%s!Xk~w ztgT!eYQgq~GVbxU2NwUbneh}+NZbtYZjq8|vADz+@P0iU2eXY9KObOpx@QC4ABRgh zn)K#nJP{i|a!2zKWeZWX4e7#o036Z1XVx_JRw|h;O8heL4K%;UJxkIdoEOH^p1^&l z_=p~wE|&D@iW{{ZfkkP58~#3o&<No|5(qgzmPOYml(&81riF-k+ zG11~VKbJJ~WHv`lDB$G1TQC-P4am8Qo-H9LqsWPRLqgy8upvh|=H7M*?K1)R?S6)9 zEGp#igjw+RivNM4bH#}+q$!t}CE+Ld)BHoWkzSc@;`j$8;1DvLPFj4&kB!f-kQcpS zjy;Vh%qaG_R*7DQ+2rC>D2dW(u~Rq` zJ$+OnywT!WG7H6nLh9&LcH4=oP$#S#ZnW7@2}>;C{V+h1R}Ldh0W3B$EMzpK<~T0i zD(AwvWIo_E3r9y6;#}d@=*;oqLr*6lN~X((g%@PC0UX% zr*h(2`XDVnEX<72<33?^%+yhD2AFOQm&SYClz2dBiOIxEh08Iy@gG6E1)(U-2%(@^ z#^E$ApobDAAtyHZ-dTZJEsW;@8TnEkC}@GrCGX2?kpx=t#31aE;@<~FcR@2C(W46H zniR-rQBNSf$`f9Q)#4Mv`>{DO2LiT61FzvOFI&OuA4mEFOMzb$dShpY{Cil_@<1si zo)L=U4ES|nb(}u`gWuld0p@SgH#uGx%te#YR-TCu&*>2#iR{y-Y5W4cIkRLy{;oTjVISGd9A3oB2)IjT1l_}tLo*;9GZKkYPlL)DM21ec;yv9h0X+lT* zcsxyzB}~U%LUBT-vSsK-(^lxXh9i?3B_QqxHMO2|#h z!AZiRq?Pzt;fJK$RFhA}l{O-eO_BXf2B)5w3;6opf7tAG*%-<3Xwn+K&$GHNV)|JXGePBnqluvb{0JbCd3KVi(sKBR`}nR897h~XY8 zPtDkRZY1XqLpR*l zTmI;a-0sjJ{U3d*%};-_31HjYr>YqP(|0_K!6M)GKEe?>beE)>BY5{CjifdWH+C&0 z27JqGYxo1Uqx@ytYwlTq3EKd}ebWdv&fARZp~4qODtr+tM4nlchMUigp76spN>7PD z`>1-lVUM}rH8TC6&}K@&4N$7)=}$AM2U4if__-f z0PY3haB4m^&nNsEV+0N$MpK51ghiS-JWhC4ldB!?^SRrB#gJJkyQ+Dvl&4|H*LFTtk*r^?hA355rJ&Exn!fO4b^hY2o+sufS zenwmjVUd57Rn4ng!l8H~zorFg6yiUGAM~mC@4^jzTJ*ZEtovL-AZ`IN}Be|+}Qe}LCT11fh!sB0(g=K3%Glk3W6~UBf?VElOqyj(lv5pKCz~BW8dYnw7@_>b8KI9}a$Wc# zOB<6n-2JD3cadMSD&T#@Z(GGS2E6kG+AtYgg?kNiv0vC_NYtMh+W#jan~wrNVQS2wm^l?bgA{$+^CIXjH>Av2RW*y9r?H$IkR%;&kCQV1|1Uk~O36TxPCTnuoM z4jA4YLS*){krR$ab4&5)ir?msV`9#JOh*ZOvva1hWwb{{VSP9+nDmw~o7k%5^xRJ{ zr%)JcLQ-EKiDgaQ&9#!cJ^KENo*8ki^9@Yg*$-%yAj`?UM^?Vsgft_PXm=|LA!YIh zNg3<<(DmQ0GxyLs%SOV?b;)r@!24xe!2430@KnwNr7x(5H+(W`(%Cb<~Lw(9@7&c|Fvm&Em>Ph`V|&kqb*-uB(~;q*WC22-D`kBnW)GS*m0a) z&A0cBB0@?V3vJUI7WWm>^jade010p)y+ikZQX&N~uag_~A_aIp72K&vUJJb6hQ2dU z2it5CHArrim#aau@FGBur}$j7X2`pA5NX&}6=F@MQ8ZEkPb5zQQA7?h{kQ)s+w5RA z)TR>3jLGWn1N!BOEd{LsZ&zTzoyifhX&>$n?iRwU#wZ;Tu4FC1M`J zjY+nCK%|OH2nYlUsX1b~0ywqDTEaGt7q;e2rW#v?_Po)Bv9A2}T?)FRawE}4RsLDK zQEe^9r|0!1?QUx7J)mUI$CP8eir;Rc0pM@l$=nTh{)<^$F0e`QMFH;C!To+$gGOW+3xFmh)Kx2SE53LZBLN2e>KNI4Y+iw+cAPepz=!SSd zz9-;~7?OF`(Xv~wJ)`h^iS$JzExm~KXxIhok|ycI8PtNRfY(2`V!dLVUYtR%SbZLJ zMuhQ4+R>#6wh9qPEwF{@qd^S@+M;Q5q|wv#{lk@Jh)p{Ewh>J&L+dwDdb|GVfcGcA z36?xt3fwsCo?=PBn+q5t*do0%MxZn`JdcLZ56@)Ca<282pj*42VYpQyhsj=dY>@HT z5P8G30q;kHd!&1FAOFj$zEd==ixq9kE%3faT5lv@wm=ME0QIP__t0}IdZIzeYMQIx zBy%#JnBcTC`HQ*_Y}_Lyb?=el+Q)8Oyz!TfGkO$b3wvno9x1lg+!LWw`d*O2nv}jx z!!4e0Wk#p+CKI|q$`q?7B6jvYi2WPH@85~7lMuV}PIv|4qYy$MJ)iu&31N?9Ap-h+S`#u!?eV-}(t!HQSSi-kR$?Y-Sv}mX0hEtuVdQZ`z z!aMiq?E&wq!T*`^0q;YD@4KIP_Pu9Cw`PM1V0*)fvR-qM`l)fTE;QcWUvYS(mg%?4 z50iT8P?&s1o6QJgQ>6hCr3|vky5X&EG|t{%a2P|GiHB)!NgorfUwgOS>HSY1Mp^c< z{#A!ZDvyH7?{ke*JtYWWguJ3>Gy30EXAHaCkDtWjX_rYkrTEiJG@6 zM>kpX%G} zN5Xtq`bYez;c7y_`;GrqSmc!MNg$Meg{S8?yeHWoJ3_p*z01RWvE zE#Pe&>~ddHppFrMN4rM@r)CHK#uPeuL?RTFY;f~s&)qDalkiU1re_dRSCr1hF8z=<5* zWxl!A1;E29q86-;-%ulu>bNA$_C4E+0^l5RgS7=UOf4nQ62m~&tz?Oc zFwBz_w%N7e3N%AeS!V&Dc%REnc9++EZehi=c>5aP!Nh=fhi~$WHAU}9tfT9S&bsi< z1hw~fe4GkY1h4`u$B$PMXR=zECkBDI<9lTw#)u4|U0L?tjdOb_z0A2{0}iqlE7rDL zS+RlAN$vxT{g&)w71Xf*c0Z->4}dvSK@-;S3#q^0v?NWk%mW(n1w0T^RRw!i``l<- z?{5=e*i;b6W*L-TV0iBiaY1v~jBcBjqk(qRmB@g*M*7RP3=rs^(F}U|VGQb=fVWPt z-kXVc3D4Y{lbkk;w4}?tgfv%eLS7T2@+SJn9O#yG2^o%C^=|S(% zke1VN&wz+fBn9;G|aFQo3=XxkSO%G2cizr}=!2(>2J9LD&;d;v+FnL+GzSb(M1^PyH%qoeq&3@yb&kisSW7)aaqUtz zj__k9DevK>s%4C4ootU?T5l>6Rm@XW-#6jhP0}N#rJ|itWNwm5O;4>`)rTQvzf|6S z*@bjTV@>If2bZ?;|i0V>*3t)p!z*6>ndVvT@Y zpvf8zcyA6oqaj!v^nUOuY9sdRun$=j4k7g85HtvC0y3GpA(j;&HXNuS3*oMi3!hA2 zs+?^?5hJs$8)h9@W8Dx4X(cq4fj~&CsvsO~Is*EMG9;k-O=f(CSlO|F>$jQdbEqEY zq1`v#U~SLCyM?5}B&-%D7mmlPh2@3Msw0ak`u9Jr=Bk>%Pe9saj=r`3&tMVv3sT{P z2OC-f*HzX@ph1>#GaB*xNc?aB%)S|C+mL2NU&e@k^P`M#uxl~mCq9$`^MU9!MKnOe z?C87Tb!)gDH!-zRAVP<=FybFVwK-0KRI*+wYV*-I&8c|G6kxmVaVk7#Nq3aydv_A|gFCtz?+SR|2oQ-Mw9cSJ=0K}QY>I*F#1!im zmKSw|)eyU>YG28qw?!x`en$%~5uh@`A_i7J233_PkEJ%tKLG20BG`KbMtoct#UV(DIHt|BA#Ji5R*SV&ET!8Gfmm z!eH$*Avsp(E%B#FOc{WSSv$7N69u1c~=6i>GJ{a&SAux%xr5x zGuDBrLz@lt;Q&n7iAc|QjA&Wqm)DB(k!X?_&j$3R4`;2X^f>MllU6OH^!F(A7k`603LM`6~=oAIiA2&?%jNz7Z zhoR58&}?YI`rm9=m|m*HKL{12aYeVFH5m{jVz=mP#Z&d0RIT9Ru{_|FJ|l3C;N z?vjVGk#=6@asFi+QTtpRBK3++$sM>Z94yTU|E&bE7a^>805pnEhHtLujIYAoD9i7v zDlw--N_Z+I;pxaQ0Pm!$yBkA`!Z1*+CC z4!#*smY^vcokkVm$uy^G7R(AKR9Qhw*ov~fF2Rgks#fwg;1(V#yU(t98?o)nt4dOv zVJW>2MnXW_hiz0HF{3;xF@BJ%3qxn>%{q#pyy}9NaKm;xVn<;p9Kl;t4|`S)NYRxjSbb^#~tU6d!{R`ohLj7 z<-N|)5NniEohLkc<$caW9wXh=6k@38RD%OmR2$`2Oez%}EajKqqv$^2$x&uH?I%1& zWsj>=#4ObS`1^no2pDHwhdjj~8LjIK^=Lv%`_a5bzHL5I4cjIkd&09!InZPhw>fZb zX}_cN+a{#j-d!qEY^lhw=iQ|u%l;ewRqR>!@mt7#;>-!pbIKe5YppU1{-0E)xib14 ze5$X;E|vCc_|M%ZJXuPWi!`th5K1}qJ(r*T1ne^JwGoI@xW~+;Vh#Hdkh!Tr<7sv4cXOg04jf{YN#2l+XJb5Fx9c@ZYo*_4MVDf-|B|`S1GBs3;<%} zBU-n~eaN#6`d)MHgr^b)fRTm4TT>AYrPf&0ZK>Qly^7G#UWF`9!imdU?2|Ym zc73~PV$pXT)zEsSLd*$0<*pD7q3!PDP#tz^CV$%m4M8)P-KUx^N}3~BSZu}h>KsKpRvqAQ;p-HrE_rhMLncm30i z8y2Pf$Bo8baH~a?Qr(90-EM*hMyM@e8t_yd?0B~UA1U1bA0GsF;jSi*=??V-rWm1& zy{<&hlWe5GLmUk*g%6)6Ak}lU5b?pnqUfnI;e*~#8rQEk3+8EU|MVbQR!@p&w;ARLa%sc(C%oTCXj+$4#DUOHOzK(`Bv?l1K#%(1JRsqQ#x7zvkAwgIG0$ zBnYTI5P&LG8ZI|8rHzcZUR2RLNem^>cs+mbMQS4GFDi>q^K-FCBSWC;5&$^D@(yUtSBFoZF z*5trd3Zo1l8w*!Ml?G82CO>a7Tj70iZy`?gZTBa_I%k}zEwg$sn7B_l09ZCuZw7ik zd0<~J%Yx)9kvu<0j01_y4g;Y3cyTIVz;UzDQFK#9`J2LeC`tvoJ%bn-N>UPF;E`SY z&=GOSTofh6XB)Fj;_HsA{`T@LQFSK^3wn?b9SI@^#o$r1juC6%?c<_ z1ax30Al<6cUmTe<@YW9U2(zZcO~y1`OD4|~{$b8I3d`orEaV zm5_>}V9uW4oW+K&_j*}$y!abnwq-?xCT6;DgP|yyTlQNCHx(L1i)0>3rsqeu&C{+6 zmj8t`O(y__yy#2-!Y=dRV7fu8(L&ve)NMK19stN_hwOxy)Rp|x4Rbv|;*f@$pMus__#em8}A zepmUZe;0`?)8jt!d;9Zm-Y8me?04?@;P;C~BE$U0{pO9r=a2pVk6_+MJIrOQUYU+H zZ{E0X#jYEw=QY18Aoc6#J;Kl&Lu8(n?){n;ZlLFlzbnGtykQU~&rKZlHmKj;J~I2d zDvS|t3ybGQk9zsy9Bv_p>dK(M-wV}qE=?m7TAp~HR1Avou%Lqs6084wN%p1G-5FGN0|tvD{B4Dmb| z!oXw-PBTTS=56L^4!hI|s@9}+Al_x)c1dm+7>k2b!l0O2hP}Iq5HKM`PunzrZfSFq zRAg*W$j=UYw+i+L; z%nt3Bx{Tz_^&B=mhn;E$tQM`e);$NTl`utDY`zL~98t3dvF^(4_WeFY4(syS+g9wdkqC-L%@O%;Y8 zihVp{fDtc%HV90R;uVPz4}o~bh{@nSM}!ha{GugjXG0XrKsW*?3Bt>fUe!FBn@9)=AB1S`ic7$+$D)U zPy^nQ%qz!uM%*9~5`TnKHvUsWRY!?BwQVp}07 z79zG1LL-FD5J=|4M-V#}@=?%GJ_u+aUuLAx-K z5!XwMR#B@s81Pbo?3{krZ*Ed`KL}1p{IZ&90MAL926p+gYOF`;l;%ai2MiAkSq@0f zj5r-UuT&?4-w^{o%$=b1K44DiWExN!80YC1?cgKJ2!K`-hJ7Qk1ysoOiR+@P3U5Zy zlvZ&Njr~YU0s;HfFbCRM3?L;*r(s$%Vzz{hCh@^)X2Mx_9sspxnDqU*>KIU5nZ!R= z8{(lc)pj$wSyc^M4LiE|RP`lE(>R|yWFGDM21@LLZh#l|;_9>(b5L280>=;1MOv0# z^r1P%MbN|2v)u%>;Ccn7*~(!UU(m(0-z=$?)zN#YdJGg1=l$e{?Gm^$TD$;S5L&zx z0LjKsYc`2;0IxHMvxPyN8LCnGcy3%b%9-q1oixd*2z@oJd^Z1i%N{OFurEkU%AEnb zdn17Bc0uR0DiD!z?(-%lv#V*2(6%7Pt~jXpTfmz>OrTTIy;q3$YHdJKd&*6g!I!Y2 z3f=`#6rPVm_Enc|zqy zm!g3RreB40Bp!EA4Qgm9IUKL0I$H)P(b}`WPZt(?+W~b!vz!uN6-t&Q<3eHC5(8c+>{_DL+I*#ekP_c7 zJM}M>a#2l*P4(uKwl&akOeb3?ah7mqNj||E5e_^gboH*I z#Q@%Zlza*E36E8F<9cEG(s*1V%wL+9X+=4y{9Z2myb01*4v?)^eBrR7&r&CyDL%XSz1~-Q0BH-L=F5XfYlQgHpdL2<5j+A6g;<>4wpMs$St`CHG{gVD zj&>}QQTFcx2i6(DW(Ad_18|P!%fRg>Vg#ycC8|NBO#nY>nM8m}0_z}>Fg$4x7X1P8 zlnqa}1B@pHVJ%@2u=qz?Rr6-hqCc{n@u)%niN&n}!iUJufkv~6ybA$fdcf)CzzPkg z73TAEjjCqL@@POm<%Dw~X5d}G%W(^jvYCtDKSF2I&IAZJ-{TGijk`hvitF?IJ$Q}~ zx%_$jlCX1manjF2L~4*b3%PwTm!`mW0H)4B&|9Ng5SJ%Kf}d)&X;m42s^&WfSn8Im zg|H_Ju}PTuq<&QGXXFTygAaJOeZL<3 z@5K2;C~asG%m+cH*1fc|DGHtqF8xc15X)VVQ-yUPKTSsB3Mr=sr~3+nK=q3tZZg zizZgD5))+rqS4T(=j7$zXiYE_9m6AMYDQ)$IHAdIxD8JswxD?n&n^cC$F2X{!BMDv zQZA_0j%I%gI-M*D2-#~B*t5eTII+!c6Sl0$q6UYBBWqH|TpuQoW(0nR6MNTP7GPJ% z?4J)D#iijbfU;kJk8WQfh%vFk(lsi(EO6IF%OO3gA`HF==Y+N%Ax_qgF_eJrczct1 zNxZ$CQdKS4P3c!#B)QRMC}^|kv2a$};ULo>%h@S0HX{$Ex6#Bwd+UgU_EzH7tvx2` z+Fx$kzeDNUF&Ndf2adulw(r=#BLoIxmziR6xwnyBTqB`D){=MU~Ga1z2%Dj}z%MshL0?IUN_1# zi7z=8`CjsvV0oEfc{$+AR)>MFlOE6{fPC~XH_qJPf;S^JtaEir`;4y@Q$RakD_-qF z*{fWn+|NUht|CvVK#4zbS7%lROCZCd|6M{^{2&yW>oV|3Rlxga3s0>|$a<~V;+iKt zHeR7I0M~w8Vl?%RI!UgnUtQzYW=?b|#^sYbG<%ALBde0^El#AVEBOSHlI~Qkc14JE zM5n|XYovMI$Z*h!H8&tV{7yOxF%P8mH7BL{8Bni5Jp4a~mIV*_5W?{Cku)7Sb|M2t zeaKrnP$5zwjJ^V-ETV$7+?=QRK~mMqg&(f5_7gu`3vB=|j3I_AXn_-H3VGuMTfrUu zj^*Zz46ur(n}NEf4~+7tA{ftW;JWv4)n`|g=*w&R2fw_Q{@{o3Ox{WS##I_s^qVay z0X><@1?4dD(LutJ4SUA~6v3ly+1#L)8G6?}i+cc`x_k<5 zA8=oLfD`%@!rKsx&0CLb<-^KV+E=89jSQ5Ay>E~Q4afUHf1!-sCj(ok&s#j00k8iV zBuCUp1y#-A9Ft*y)sDm%EuEZ-VrFIl79s|aet%Ltx7kd2C~9<<3DJ7WSXtHHq^Xj3 z(|Sf@tqRezRokn+sj6xXnfa?bWacjry4}A&0%}JICs7jh)FrZF5Rm@1m;q?)&tRVu zA-)9xl~$F+9-aMc0}lHL)C#Ir7IxDN!MiTm{@#Fs;~U>u=Kzn3Q~nYu9aXj9dk?I8 z-7Gs_0MNhhUnRz((C&vJWzf6dFM^AHv)O&-3ER6>NF%kb6628HO<1NuZ+)u-i+k%j ze6QlPjUV)Ghy9AUDEPd+#}A{bF_nDhd}ER7J|t>)O1ox%ZSZ@jQYf zWq*H8k28d>=Tg}$LiohMkU%}3fstT%KGQzv{S#Q3!S+5xhH1jUudoqqz#w!kG1 zdXoo7xMYGGBtCK+_z>McxY)I^es)*T{1rLt@ zoD{_8HMmTO+%O4igt83}Q=S1~|AtN2Bc%W3Z?YioFMR%&RBRD`{>!5{Q<%O{OTFV0 zmTcUB8-+_7CxssL$?N#WL2r{JXzb?XTFDL5LB^0{p)t%au(>hZUyqCe-5nDDEZFT@ zIG*yBJ(Cg#gzxPfo-RZ?wA9G~;U0$xj}o4BjKzNy-gG2lESz-A#J>n3)tT{QhCbvg z`44Q-jrA|$yn65`EQIry;5Hyws~0Ce3OYW&mj@oOs&yZ1DoA_)rW#7~dmj`2QT;rA zL$GYp!*D#Ysl;$1z}rTZetnISf%5@qyXYfgYq-Ym{e76`W;NnklqRzsYHv*x-GBkb)Ftbx_le!Bb^|c{Y z<0>&+*5{_iot4ye`&o@|gVNPV&t`n(2U-!**6eNIy6_BJNjW^vz2 z>OwdU4t*H3doK;ZNmrVjR({-8xmdsCZK=rdC?dXY{X6ZTWNIR zCHIUp#xLJvobU?_04pQASs3hQ_j0{%5y%H2q{$rK4X*KiCMBwiK7{uY2hMv2nUs(& zFxI7=e^Cd{dSTjcg%VJ*o3P2`|zz}o_)K)MC+SAfom)IyFj5pRWApb|Y4 zM9P5|asB}qq<{E{SDcLV!%;X=wgJk9LfL@#F=*|rwkLT3ate^MDOd}UKfZxlUI4!v zf7h{raHF;5GW%keJPeNeyd~`1l86Q2{VjT&F8r`1k#Y?QJzHie4z`k&vqC7`Iz4jw z5a`D=7gBnAR)$w6`VoR9K z3MZDL_@+hy+{R-zd{``fuU`fLJM33_mYZLTflS;;+@ z5BvwU9S1LIll0U9c$x9lKhz|kopB+oY8jsJCtC#nl@#tsX~}?DsT|7gHbQx%-^DLf=(6jeVGrd*cMVS$jXXt^XTrpIz^Cda8$wj~F8)>XfnH3%-AglX^)h&u?S@NM zMkdcR--oslNdy5WDHc|n;M`$Va|Gz9t&R13I)}#KDfKozAKlmhwr6y)s+E9rWl#^t z1nc=~KD4ObX5l$oJ6L3UVdoKMZJUN?2|KrCCNe%EV&l5W+<{(}sx@zGYfnHLQxOuc z39fCqqp!j(B7y5u$mx5F9Gq-+aY?+8qK>sIz#=x_{p&!135<_kTzjMuAC$blK@4J; z`s@A(jKm*7T*q8oIpNFB!}cw=YX`ia`b_}B4+DFoM^s3knt5Pp z6nKpJy?-C9X@qY!l=HRo0qGF{p%Or7cgtaf2fT0jufQ@7mHz?%wETK-icdEykqN@B zZLkafvwkYs5XRoow!obpiBWcf08Y=8c3&- z)3%TUky3@%($hYrdyTpF@U~zaSa~ck0fz$-9 z_|i0p{oak>#s-zV{IJ9%$$LY?v?9h`fa28&=M`3d2666SACf{HT?!Wb3La=xKSxwd#ZZ^un+9qqKe#`CYOVv*FiTB_S>^TWhj+OT7RR1` zrV3(p*x=s?WL(T;8Kd|Jlh)ET~MM4D8`fSY1~P-8I*(=yfiJg({57r z^#N@VTWjH@Dax4M|M=m_9BIhw^$bmhltMR3TPS#UTB!CGVcJWjvtKy@mm}HKaBweh z9h9k0*ZObvQT}KYW}~bY3({C2g-oHU<|00Vqj)$_Wc@9UExqigiWTJ=HK3g??!_>d z&-;uv(D4WzFU`mI3*%qTNuM;N0Iy6H>@_H?-5?!Cku?PL$bfNlX zE9D*#etbEJ>KqWRzdVQf7$m;hS$M0ktM(%xpwo91hpgU(*g^;^gq^z*WsSk7k9Mt$ zTnQIe_`JD56IG3PuislJ7o4E8i(wT0?L?Us~ak2RY ze(Mq9S{KWs@pFY3VLZ+fiUlwkiTTnc_tfRc;Bqd6{~w+Bkm+XlY+}1c8K=8iVLQrq z{75!c^qo86*t5-wkMR58tF{8YGVFZ_wl;YenYXx(I7N@JcRugG1Hw(=q0FVg60^-R zxI_lD<6v;>@Qtjpu9K*3=2oJ9Ax8@R-XdZ3o=GuXEgyN<@Riq?A5msV7cwMt!F@nN z>z;VLMELg}EuJk5>`4TMEasKWl-mEvD`rR+C8ql#%uG113uF4lZeiXlrS=^hIghg0 zvCSOEm7HtxZMtc0`~p;ZX+9+GGX2eD>cQcAOcgzGrTXws{nG7J-wVU6KlXD=54Ont z5uUx~kaK>u+!HW5#Q5sHX4B2sYU;kJMGF(&ZaV6hMAom$FY2L-kUwJh-QtjQ)8Y}B z-5sK=`rTsFP0C(P6-+BK^~g2)M;XHy5`uzeVcHgsnI_yM)*~c z0B{lON7BAx#T_81)BB3!(am#U{dl{VWlTNcrZ)F>=nu+4VxwSvHPwFHu_a+~FO9JV z@RW1V34qOb#|`+QH9q?G-%Qv?i3F%~CZmN8ho%UAqzHd3X%6ti0)7}D)qe*^(;VVX z2f@)c#|Vz90Y^dbg55xV_D(kdN7L4v-flOqK1UTyF8VG3FvP8Mf9=tP(>{5>&KKU7 zWYPG-z1S!3tLPbhzt$J-NwrKRAPl7Xwg3q61cbs6KkM68O!?$D5#(ggEmnsBhDuLw zE9TC<@1a7pMQ`+)O4shg-JAJ%38^9O~!xUly-wee*KlNfo z@z-1#mvAP|`Do+O-U#Z6UaU~~!Uu1fW`N&~*94dvi^hx$;yBPehq>k4wJU0F=!&KI zx6{XasfgvU=i`D)Zk9XkwsAY%)m)4Faqbznkt=t9=%KXb+4zWJaO9Z!31b1AK zeYeg(l5!h#7k5)ckSGqFz;?K)id06f@KR>%X{+c5OE+M_k`iGc{IH@EBzB($RFg#8 z4&vqs=(`7+xdr*envN*7kY9My`5NaRJVtJK>mlspQpzM?+#5gGRpL;J0{TSADcyHt2xOl^`A* z4~21p-k&*=0X=rBVXSb8Veik1lw)z-k~&mDFSjO zlH;1@xfW=bYNoElmTWtBzT+o)yg}}V~07}ejdAQN<{d$O0 z`OHwHH5(>;K2*AD2y3HC{odI_lr|FLnM5!J(UXSzTMiFNU|g)3fX9B}u7UBL1?L*( zIj#yHH>B7fhaF)Z1RBl`%(Ku|jc7NKna~L{m2h2Dip(l24R2$$SWAfv6>np-x4osU zB%N?$MDKx1Z+oZ1N+9n@hqZJm+kD%5&kz;7_zvzBfbVKj*PXnX|IJImg)~rDE6jc^ zhWm7o&Itj-JVN1ZX<+F>+PPA?G2SAx#zO}`0-mv;m3XxH-TMIGStc|OgOLxe*l`8V zQG?ul+xz!`@ZoD&@%8*Bb7&{r^cc0tEI%hJ-^Ev(cYw`QCH(Q49*&Pjzn+dy36oz> zopcT)Kqe>)z6-}#uENa(1)$N1VtgPg!f`?{dCY^0Q@(~=vS6;S0vVtxJ1e~W`ZI7l zi0qBk*d{#t#(Gd0c;5H{e=4-S`A!;BCbNd}RDbu9Xt;lZTrxQ94hOt5$S2Ft1++fz zg_FXLec50aY}vQHw4ix3pgon6@$>mz<^<=tC%1t+0@h`uwfAj8p<2dIO~8JNdM&6N zn=9#N$(@P}#-#y<{gr^G@rH$nw@4@Kc{R5<`G$(N0MFITx|p;rmty^Wk|R#EbJ0`{2rDD-o~_ zBp>v4K3W;q)oo}q&hSI@Be+zm*+V- z=brPP<-X@V=e*mwhuzdSZtCbo3fqNl%IHX`NGZLTbUGy_K`+wOZcAM|(jy%bUmJ?A zNcjJij44CnvwkGT4kB^34~Z)W+xshDZtq|9a;4Z~I49Rn)Qgz<6ykI8uHVwTCjJhC z#8X2^R6xDYhERLaXq3h}FiK+}AcWGsd3djGX{9pE88jxE0j?^I zI$BdgCa95~dF#$2xDijw^`LfSrWVK(cObplj4CNwl}ce;$F?KHp}Crtj9G}o`twlB zDq{K!#Ay|u%B=2;tZ^`g3Mfd6HCshZsEDgLBWLFmU_t`~_>630kob%olx_yj%U#e2 zsvc>m3*f$k^6wx%5Apf@XlSh`E!KKQ?t#2(karE@pCSGkVi95y;vXUY5#oXTq%-iR zX&ZS1HKnVNC z=1u+4b*Gvb&h!xy?>;f72~YjSgR*{g0sXF4l>-GAV8e9}%DL)-H(E`Fa(XFNr;!DQ^e_dmwBmALnqX?;a(-W0 zH6?engw2lNjrQ=?BtFxI>yda%&a~qOByJF%Qt7yn1)2|wk`QA)v{DDH)Br8j<E0>+h9ib2z2J1s`hi;`$>fniBrBPx`c@NE{qn?PvGVE&RTMQ1M1buuh1 z2wd_!99vF%ZC3i$GOI;q5(R+PR3N>kESyWQA@QgW=|`2(91;)tpcVaDIcbJLbXcuo zkM$EsixUjwrI&ulwmH8?J+LRR=ttBO!JxEDYQ(+|A-2V7!0)Z#89pdg3ZvEI@ibwE zIyqwG?Xq*u$r&?*zZu4;-`C+%B<2s+AKRjSh|+7q5X(VeTd;V@k6{Rmj5)RiiAW~@ z4!>Y3-Dq{k*WezM<#*SV5S-vrEG|BY+SL&hkTT4dj^(jPon*u@ZPRCA!}QtP^^CVh zX{_1Uf^-~=>9wF>j?g;X!;{N6{w^CW{?ngVf#0?Bd3Pt-D1)&Ei)!Dc>j=|g_aI}) zv*p>bvG|h7?nJaG4rWzoA&0SXrTZL6Wc>&1DW%=^hiq89e<%^&$LmXg{{+Za=o6km z`qYX98x5@@u|rmhuMQ_wgf}5^(w+W9NT|fW_!B}I&L9?F9mL`@euemw%ox>R)*puG8V@R(UGyrgZmJxjuf&Y6LOQ|5Ib=*V!uiv$VX{GX=zYVVZQy0Wtk4` zVqi2EWR9nfk~P%22eAXflaZ;4+);>Sgx!(j@dLu?NCTyg60SzxrBp|e86fi`m`5q; z?SUwvY}6|JzR)@<6@M*U7?m0Iww%E$kJhwt{7-fyJ|#p)EuZ)5Ad_-uH{^@75{X^# z6w&=c(_DTkp8?bHzK=;!Kq+hyP!fCbz9y1>dr;RiiJudKI1l+ZE*@Hmj9yo6C}*bd zRaEl0y)u*19jf`>V(9qviZ^1&=a{-NEJ;fQna%;b>|P&WX04XvgVzYNmOftUF5g z)s8ylMNt#of0L0p*!+|2uh1fa$Bnm}Uz1JTLZ0Tvt)XC-|HGOy*A-K*Y%_?}4m#G# zc#Ehj8u$i0V80#7BKgqnK_=JQVyAy5HrglCx2S7e^%6PuuaGVdi34k36uiABCm& zCIlfZI>xbu-_5Idls1|#)|p#}u&K`Ss~dB&2LpA` z;&oZ}oPoDyc%)}rer%>Ibi5X*@sOVbdV5JGWttYPj)5nSurDS#^J0ME>tW>`^D9!A zi$F`_=|Bcw)5dty&~ckm{KCiaD4iDD1W(M&{CD7q7F!9;iS>a#4-y+rA@R?rfNQrs}dD~_7l=z~bCk*!IX*SK&!eUKJs2utD&_?ECaZd&B# zAk)L~X?CxN61NE7#${6FK|zyhihl)GbwLpIL63s3~Yvla>}!F?3k(M z(%a3HxFhg9`6jEYztL^xkMltb(m9%r~Sx) z_b7D~q)+*Uoe9sREcP)5;4Jv+O-L;CjSRA&O$E}!O~2$3dd6vK1XEX>m=i$_F*YC% zn0if{P^BCr>`I)4R|?-J=B8%&6ntqD^4e6{PiFAi$+|RpqG}DjvAnqoeq4ncd4=SS5}|Bim15>r}o9Q1yX;lgCEg7)BYtxUYJq@(W-g zUJ}M9Pj>VSEBMW=DBI=Y_%N>q!82ugc`UwDvy1oCggzj)5K{@NeC5qPF>Bq05- z{hAF=e7Ft9vY}s7#{rGU`B5Xoj}TH-6KP2W$G~;pa@%VA0oyVA726x0D!{<3!MHMp z?`R^eK`WLmBh74qW{|gv;`q4yZ?7W*C4S>Wd&0_gS#aZkd!$)X1qo28Zlq2fq*(s6 zke4zob+SLreiIgJB=A<|rhqgMOj{AxWLS5|Lc0Ufu<&Ba*vL10J*}G35sKL@G^Hd* zZuJp#!lH(OxrFYNJX|hBrRL&Sgu>La_$fZb*=)ZPhL%sXU-vNZs+@2jHCLze`8>yg z(@<1U4o%BEd6I^KiOlvPILOEZ9T#q;E{e)#=9RG<^n;uLu<=OccWi{|8 zn}+g$zhJYyZU$J&H8AB)q0snLbkVU`eiBQy5=Av#*f&CZ>o zEZ=BG90)era3aza^t2&0sh2lI>RH!st?O2PwHAvs#+`6PwFjja+d=kf$ev&Ny!O_* zubPyZ`Yt%ZeAt_5b~jH2TZPLPFGA#WgK(_JV&owP@5*N|yE-Irt!)KkB z*@A9WMCW;#S)kyGLDEkbvEmH0j>SP4;sv*xL#HiQ(?(jaX{lJR;3N3Os)+N#-%M%A zc3_3B)WzJrC?&c`zrM-e@12V)tn~}6y{E0=LR79v0aKs}7v3|a2y09Q4n>6$lrkD4 zNase2$beLfjPSmpp=%Lq(-;)xu}c&c(JQ`E;!Zrx=cc(~>6ufcb8{q(%p!*r<;n`p zlIRs%{tIHosgX7aOhF61g5e{1Ym;?-HxM{l@5DjrhoE6aVr*+cTTuEoIOxgb$$tOs z@IdIy6P8Yh8B^0@UC;3UQcmxr*WXpP7%yIs%;a|pRjFfyp7GdLYGu4Q7rv^inh-$5rBE(EXo-gdKp{Y6JW`l4o}U zj;#Y|^=A;1bfU`Nsb3$)jV-&~JQvSfU>HCkW7k{fRSiq$e1`Qg<&4X zq^5p-C-gwUxr6mv&7>#N>t~P`l;(%{q>l()06DXSqydR!Nw5|0C$=cor&d0O`xXMT zZQXh7^Sb#d`9;V5w+Hz3u~s6sS$oe|@r1E=v+dU2qSbwKiq|vi6(X%zhH=h;g{(UU zUV>d9R87pPq`ni|aN6HJb7anpO-Z&}9u4X5w>~w%P1;OB=~$4_SFc;zuZpc+Gs0GV z{4vr;!#vz*ms>`yPyuB<*c!gxB)mIu>f%EmRj+?PVO9V0u_&kdPhpp?)E%;@zSFw% zp6*uBoz?5DqM5G#lWu){ML9mZpf71>b93K;sIZG;%CX_BoX>7E)3BWL3%>9q^L?JY zEm?dnFi`PDLFpc0s>v|sa98#EMap;2fA|}Qw4u=oeC{I0@}PF$(l)KH4M~L8$^aS zY@iH=CxX(HAv5d+s?wn3hoem_2}+0H$R?h~N-2o8kX&L>f^> zNYpAitw6%DghZ1E2`u8Q10#e;A>8lpWM^4V^JkU#JP5qP#Jm}f=%Eok9BfNc zXHfP4W(%$B7&wMRnlqZk4Ni1x=aZ{M9+Ok>(P5Heyfze+{xG}?5VETOQ+gA`y8vAy z>8DNb(l9HDio{6kfO(!_L-lj9qAg0{V!Wea@dTxE|J0u2^4OZ=a=b%xTu$Vod@lrc z$zwX$<}uA5c_X66bw%A|*#&a8h}t8kAodFg$q-WS7>U~;#swom4e@vgZ%rNv=>W&A z<5f&2l|{Kzl&Ev;F~d5d_B5<9tm{^d>D(o+HD&PIVRKouK-fDut|BA&J3vtSWC$7F zlpi#~)YQ^qDvga0M2+DE{ ztUWT)b_}#VW2$?k>8V}+=Z3!tob@a|g(uQ(UeqYZt@+wRO*FW_ZVo>s+?b-rp9s-+ z=p4DwcJ7h>s~44yft({%y-M0Kka@&0apvuDN2=Em1t(>kIlvv!mw*2p2mqjj4OClu zaV*i=rc~&+#+ubl)`1PH4I3PuZfGO?$hTK@>nfpD<&l5EGkxU2UIc9hKfo~lp$|U3 zs$Vw;N~I4-j{}YmM!FO~_?>71gDAr>@bd?{t-)qhd6+r1$udAaq2KVsRZz`8;q&~y z&-uk*P=Wx2T)Fw^W%+1xw;X5gmbDyM6Y_u{R~yW6W`lUW+Az>#Fbq7mnh@*PavX?p zhn(qjR42gN9o?{fr{`eJ$olfeW&#;gi?U-bZY#&S?X$^lmBIhMTT$Y1-!(heMA_%A2y4pZ>q~Ts zu+EKTUxs$D#1*uosR5Lx4q(vt`hHL@?0lvo`4NQ}rEc{qqvn367!YHcZ=s2x`>1Wc zWrlb!#LkJu?$7$eMx&fU*JZh*HffyFuYUd?a{l9JqFH>j_RsS4eJ4SMW)_#${zEoB z{wz$RNNZrAi)zg|hj^7Y869k|6wTqOKF2mM-Vu~;``+pchqeBr@6WKtDSZL|NdE@< zc}PDSIzpaZgLl6pKd6CYWjM(|`_*-1yIch@WV5WQNU|VtMQu>JIP{yG{c@KIcWUg> zw#6(rX@Lig=V$k;3Og+omAxhL3uT&v$ts|FX$Pwnaa1bkB&L;*g)O{Hrc5i>Szrl? zw9Odn?v(R&i%z`)oh*gUHbYF(u_A*Np!@lYZzV8ps@Rolv?3KnyC_3eIcY&FvQgo# zm7(|MjFg*fY4;7Y27RdXPpry|Rey17Jac%50XFD&Wzr~DM&5ZJtV+@ioEN^YJR|h) zawl=fA0{gLP}oHnP}r?kpPAIUM^>1~pteHX?jfrg=`xCNeNd{ENf~Y+_#p~20uhvM z4IcJfQlZWfocwr|CH%4j&I57|kTU^koM-^fh0F4nwV;z!UzX48JLt73aATM1vCfs{ zmAz$&XJt(RoVRwYUo3~!P(Jm|Nfv6SwjGWKI@LTDD4Z4wTvX#jzAZPCbmMwy>U*i%&|6W&7n1Ss;ExZK$`ah7gz{y9h4^eHKCjW<)}`&v7(h~ zB>7}e1z_IF2hC23!|x1%;6|c}WW7o3VipU}yBA&^LH)VV@WTCn_mBqvXYiA&1zQ4j z)9h0cv_&6S4z^F=Q+?0Ng`u*8i9zZ4!Kqv7ir$e~=Z9Ch^116MQKU4m@f`hNgb5~Q zPGmfIHGVd$Q+P)s7{jxJuMCbhAtT$}A}5-RO)J-7Jz<+xu6gC^%5{`p_8edwx6ZvE zUJm=;RKq|Jj(HVL7$VpMr;_y!=kRL6o1C))6EM#@&@u0v?c`7Y-=ki*b2_Ka2;h(r zmaU!_#ngwA^sBL zFT*PboHk%*fXRu2kPjgVf;J;4^@2UIOJ2Fou?(hr$zyGoG|jzTdn| zbTF!{jdH2^(Y34kF_avT%WJNn$h`87&+8;z2^u-a$Iluj(Sx&=4vk%xDSL|f6uh?h+`KRBo z0vT~Po*}snD?;4Hl6x!enWbNG7B;*Q5elUbNuT-;tc)WJTHb+bB)%sb?2|aF*g+d? zS3qD#^9Vb41uTBAf!v241Y>RinFs@r4m=l-XRAmPb8ms!aT6P=mxB08A6QzJ2V!C_ z`Da7_5utxg=szy>uZ5i}N(OyY5anDzNwA3SbTCQ=xwNt*fD-;RGr=*oBCd4L5<+T=YztQ;lALuhES*zgE-8Jbc>dZF5k1HR=>v zzJMBW9ujVPz|@|H1;J)c!V$uA=83pQc;Eb#wx(siR?Alo><6k#=6_6}Z|(onkTi8z zm|mDaeRpf{XHCT&po3QMvzqX`Fja%N0cD(T2ZKCEv}%kv!;dl|zzD{O_xn%=Og(oK z6!!sHI9#YredT0L2~m3y-9KxO06pkv*^;E_qhjE&7=7s2mBLh9FcrA9$u5<5tRh{E zQXH{N>>~QGoM6i>XVj##WbywosO&?UO)G|)^!5Yx_bi#`ey|HRVY+qP?8(7uI~(!~ zD3Y1!q+%Kh8R@%0mi<}LSQ}=()pQ=&p~yL#5Hmz zkM|Jc${z+5panqUR^{ffkT5Un8Iq;tmO@I;AKrKexEi3pd z_6AD~h&HU!1g)$M(kZHoK`BXiuEc`Dm6`G~coM9X*@CF7aM zI0!a(n%A`KYzix4K?jXZ^`Lo1dX7)1QTJ$MJd2ib1p-~3IRO{Ig!7O$4H^CJ+a8)v z;Bj8`T9oN?YZ7WoG%ZvS!&ju#TUb}Dj8l<}6H%t*j!76&N!!8h21bZG%kEkd_an!Um&_NLKS@ zX4)yst#j7m{<94wUQb69O6veGCK3>=`3~ViS+WDH!s9N2(2{#D?ih_#%F0_N=axUSrfuZYnZd1(KTu+a65GE^&>B+WT(%WTYNDw2H0bwDM+msi^PYD(yzfgF zPI{|h3J%tWiI?elAT@kd`!)Ys#bTLhYz4fq?Ynt`g;GAQy%5gsU@ol1At&GP{Ymd1 zq8tP3kA(5ic~O*3?NzCxGTDQfqAEP2JxX`#XDS?tll`yBX`p&mQ#i}w+OM*ncf^TI zR0JRusVhZJ9VFOLN=;PHxx_Ikd7f4h%WtNU1`7ASp1>vSGvo5d3w?kc*# zQ`wDYu2zaU>Q6kCqEX%MiD=@ce${NWlWu28J6C^s%e~ghN{Rusy4{ceTQR^T1Mp+3pmhdZ?K>nMupfe&kxGdcAR(B1F!Gk z8KJ&}0oSrDJ2Kt|ETr=PI~EL}G;ZaY9*(N16pbR|!Nm*CusFtDe;^dkDb zJ~hRF2O)uFcJHy=(as*K6iw_otspC$tCO}A)36GYF8&CdeXBP((?Po@gqoyZ|7&r$ z`!zY;G}*{?DIt{xLWBlrq*Baf@f4$-F#HWAg&qWV!o_pv0>f?_9WxS>R` z2T!73{}|phm%ZYNdke7<5Ht`_M=%KOYclxU%#?Q0zCqMD=ocYDDiTy0?K3V>Q$Rtd z9vRe^#YVgCV%z|Fh)iKzd$Df0uAziX6Vsg=8sY_IPUl~}C@e=eGRY?0Nv}F8{kxGT z28JExHR1gpyoXR!d2wC4+FL*o0cBUaN%u&R1Ej0Ly7m}3HmRZH3r`QI+3=LlJ*0aI z2=KJWs5|Syx$k+y!oF&Dd%lKMg4swfr-n5&?M0b0=~YpkK#a_+;z&1NbnGgg`8!#c z6u;T0Qr_uj>>&e+2Z9A1!NhAWJo73n+htLVV}PrsU;|kZwbp&?7PqR}O_mxg zGxgW}1)0$-1~~wBfrThDQ`D%H7tNM3cv{j|h*M$U@vwN6E`mAQUDb=h0{w}TJsf7x z!{I!6kV*WpnLyxONIc=p6meKlaVl(l&YQ=bMK?7RYvcQ$u4-}0o1W0){Qs&7*WTZ$02D1t32+r=Knj|hLS8tWjO#kQfdKa~NJ;{gNM z1!ykQ7{2pd0b@zoKu1~S0JFL?G>hpvLK!1R8IbKytl=w95pVGr_`mY^!T&v;gaKzI zb^|NhL*;chKjbOAsiYEmsi>I)i;na|8)Vxf+nc&i2?rV+s*dj8HxGh-J?wxZ>zp*C zapNhc`F+Ki-yQ5@(B9$`z|Sg+W}U)~c||GwnxFRaGoVBCkkU&jjrO?q1-iAN1^pxG zmQLuUqb|D=K&7Je;!wF!$LXNmhqUcEx?UIz>B&L1i-wYKJk=?q-pk-wQe@$d21lqL*P6gzP0w3_ z-+Fpbopqd_7J^cLXPWe8u|mei)qO1eGqB4bQ*0z#86fuBjd>AcKo7w zmb;;XZa)tVo9RYAdg$nllJMn4cp5wP7;LsbyAOB-ah_Iv4R%uw!d@YIek#@rx$||i z4WMfkFM`1Z?3&=zQlx3wYKi4(SJGNM31!P}ZGxta%$XBrYYcB`4M;)4mFKGsw2e5% z$QzsGB2%MEc|IWB6!y&@s~Z|-Qm$RR>CwR2I5tRJeeMSPNaRIQi^wit3K!<*;zL6C zJ-XPxK*_+xZ($wW$?NzUJMm(gc~9!NT3`Q)ilY7{H$ptS33}ZcBt1eKCQX}lMSm06 z+XjVA_hg6NKiK0TTKENn!pVE?Ts#vz)d-Xp$i2^FSuv^UXlQ&?C)Nd}q7$L_%*1Xa zE;)rm@##}FB}6jX7;-;AVi0`H3RTMt)+~l>pA|s zwb-a|6QgL`wHgpzPMji&mCt}T*0e;=GJs%^>{@D%s@P+RzYtZ?Xs5lXn!bhd_E@6N zGGh23BmPqkI;1CqjQG9Gh;M8TuerY0ykt^^b*9XI7#0@M$35jb_#+EbVebn`~-R6 zOS6()2b^kY0j9+~y*zepZ0k&z|Ja(sn=v${QyxU)-$j7k0;&XQvUhHvU2+;t=sunp54vMM z`By^ly8t5N-w^MFAe{6IA&5;Oh>cF=yK#Vm#Gry_bc%Wf(5Nt+$txX@c$riH1^B8^ zg-4;nN*AY}Q8qSRc`zWI2tb8{idR6*PAUNWQz3Y?`o61VC1! zJaeG_10d&ELe3+^JahQtpGKB!%COk9Iw{gk$X$7m(v6f)9A3tS*ptej^g923mOerxEVv8=x)|P#0lF9(Ydi8G;zj zl8UHVD1&X+!a(=?BFi`%Eq>sOs6b6xa-vNNpKaA??O8TTTneYLqC3OJ*@;FgAn8sP zw8epb^hco3SS)G1!r+zVwn;KRt_$v1;?~yF8)*B`Rt#X^qlG(Il;YMTSTfQ3scfD3tX$&$$ZgXGE_^&Pi@64wa+CCNBd zh+k^NQ-$KCI@MjiQb0kv@YvFLJVAJ2X&#OfPA#3B<^ZJMb}K+LR0ZXS;r>KIci&nX zG~wHhk(}#;*FC~ZkB$+ts=rKJJGc*Co~Vi8_$)zQjwM$o%%O%OmrWW~iE{oaqx$TN zB&$N0y)2%RWx>8|0()|Bn*BhZnigJPR$3j9VD|-|62_Yi?uKwZCzRHLyI}xa6AO68 zo1}~evycQ&CZ42j21j600Osc)(iK4aEkj6Wg1BkO05W;yK=%_=8K~+Cv6$SxNhn*M zira)0@c;g?Ez1>@*J zNL>h}vLSUo$aqr_))D3ei{G}_v}^=z`~52zuNG9PSgZ~jfFDv`0EKA{d43$+B7q;$ z9azcnIw8_NZ-RA2EF8U*E39aT1vn^RRyTs)gSiyGmNwF^1PD0S>j{H=6$GK)J_XMc zzOX-wUlyz@il_cCOoUyftB~Id)DjP8MNm=(L$_IKgFl0hEAeY>qV2$F5odH;_NZ!fomRH!#x>s#>X!i;L zKc0=(3BNo(n|doCOn)MSst*W%cw!v&nqPS7iAgELD-iqBYT#;~MC=`a{LwrMYTXq) zG9dBFknpc3Cg3ANCB6er}R+#Y9xyo}rP_zNCg=47{OLLO;_tG5W;lSz&f zF2psIv_MhPZ;fl+j7T$GvfWfCFEE4V)rGlVpgiKYau#Ac@UM+7iu)cg%b|zi|3S12 zj^prJ^QtoYr*&UDX?x-dE!=G&Yn|c2qr46ooWz}d;}ailfTxWiKlF7Dbt&(YJi%S^ z1JL9=*DiT6#FcKwyDRLxysIjw6;v&99aI23zwn6NxJ6?hyG2`cd=S{Kgex!Ny!PhC zW&v#AF#mepOMh-wH*d3O-TIeeAXn)II1L8l0G>*0FJqbr)j#U{izTtEitG`CjuEHK z1Hmsnf3f^{;p&STnd-okmaLr8jAdm2Vd!VoaSlRclFyB>4VOuTNb#m_qh{pE5+`% zOmH4MRcarMQ7duRSjGrRK&#Z{{u>21(ywx=y9G0SFKpv zae1jpaPE?qnS{qhxI&7=i}17nO0EOJZ;}^+y|KU?lvaKuy!pp_>G%CD!tft;a2F(X zRlJ590y~3&pNa*-oHJ{w|yw4c~>#zLXF2P30+IJ@87O&j%nUu zVch#y!tF~3zw?p$k`YQ+Efam)7HH)2*4JdlM6Q*N=tkb&zWa@^Nm(^gYL zM9i0urs-91Mk)>>-JrDCUnx>7W2h8q@bScI>&*q+x3b2m6u!OAzWeRs{tjhS_L}Lg zcFNF@L>oGqt82I#<()mWf#E7@)CRU@Tg{g>HEoL7mpp`lQ_Q|V4ia<=Mym$X-3DU5 zgPIUvtOg2QQx%%nc)b2V^GE0 zo8DUM1c!>$p%OVA)wJRn2iCr3QCuv5w^9tP633vhp8KF=ND2rupH9AKpiPD&Z}VC_ zLv_|>ACf$<8i{j(PkN~J2&x%ZZSPuWD$?AA#1!8cuLkTKBxguE=l==ToLqTH&e&VW zkL8m=sR)B`-FioYd}(Yg_t0jY_C5(SI(=jM*0gE;guMd++nl$($Xsy64GzfQYfq5O0 zp8BtgT}WI6R%(z3#P0$Mz8WmbjN7mUOsjc@+5))I3#uTHe^eKTr2B`EoyoZ6+Mdzx zGFwmv+`cp{w;5{tJaxdE5RKKTKv*fg1t%LLz~_Yqhp}Lu)rLfHCkh#%S#Z0!^CLlg zmc#D|(d+I2zO`)KeN?4S*uQQAzAmIc_dg24j+Y9jpG(Ch!uQWTfQ`b;^*Rdsg{AA) z;TGZY`a8l7`;-m#rXfi)C~yu-@(tMogrH!^Wzo^h4<2G3fBtABCU{YL_G~0VSee`W%?Hnzp^bVHjsa?Y8?J9q6SSA`yF^XdL9VHSL9fAXhCKx<2m?98g$!^R*fh1L3?TLlYnoPx z5em2wI^iArluNUqpD=K{`0|*_n+-w%65kqBq|g^R82ydFzdZkxwYl`MBwH2urE3d; z00v<{9+D>e;07#BZZ7}9R=vcq^i8>_{>*iyA;Pc;yedeyaW0e&-I_rZBRcdKzL4Vz zzw^vWWBkfBru@q=5v<|}{D&(Jdy2vLUW5&VY@Nw)H#-RA&!oh3)9>Nk1u*DILrjXg zo9KcrZqbVl@?8-47|C^J`9;8b53DE!V2rr3fXf6_1Ys23VcX8R=x|^ABX$8G1%Uh@)C!RtzHACo(q`fD zO|i+Zg_g3$jKrc7cv>P@O%K$Hmx#Ck+67_XCPRvDXs<=ped#)7skYB;nr8$5j_W8- z*}yjWC1XJNVN;cg`WV!f;={t!%`>Cl8pa0Dzrr0kC0t@1lwK3IY|ef7y&y7xXYNzr zC7*sPbbVQDiJgtO*jd!LEIU2kU{7o{*s5(}Ta3NANsu)i(d)Js%NOR@K_TDq>2;)= z+KRb(wlPl`ZK+Qs@YSG-54X*;r935j=GlY)Lha=4+X+GUycNGFEPvjCHw!;KKN%=A z@rCM$S>SID*Ho4bO6s7n^@WTv^8^36@L2sqMlMbN#yC{r932BnEGDYCR(m{ymEZwRaECgWd(x9aYjQ3z!GOY`0)$`MgP zE)4o56uJ`($3H&_P|+!Wzm43{rZExHWob(rxhbz4g}n0m91V)pehc(?5rx1x-Ym&te7Hu6CL1l*fAqt+a{ zN*xJ$aBI^ZJ4(lQ?y(u{u}zI2^Px**oAgUFhhes$wALP0w8v((7u!0(8r|aHsNMi>K->TiZJl5N9qz;$`96t+~-vz-k14o?4M}y}v{S>iL~Q z)V6qs5^k*wN;d{gX2N~r`n^r~pe+4y7=yB2mbAmkO;)?nw$Z-QrhHnK@`nk34$^dJ zWrC=_jF_48To-|(f_1GLNCHU`_U3&8TkSvaLjAVOJSj0 zg2P>@8+1tNL!~f)DZX9u{TgIQ%{;Iyx~l-*IA++{1bH@;^O@_)V@8|dk1K5*9wkic zpcFntcI7ao2>-P5mk@2wv_v8F*FDqB5MS6zu5uz#2j1B%SR^zpENEVP(vV(NR=p&O z+rLDX@&;9gC@#~mgseMBI{I;Nt_t1SMwohrFV=Ev*`~u5cH;Q+s0}(paIzz<^{LUlK=|pUg?O1T^W~iM*~2RE+0eilif8b2jG~wNTX@M|p=X0RaY2BHrdgcV%;+K{P*LUg?|8N57%{NC!gHi8<*z$sX z^HE}L8)HWk?-A04i8x!hN0@Ve==MJxF_TVA0|(x}yB5R$H!l31`DVl%4qQ}FhO4`6 zFv67Q{DvH<=qt~t<4?7y-pB9WBQq<}D*?EN%cLl~;bI$)8{lC2jluIvQ)M9_+?!bg zyfE9MfX~T*jvHL3FZ+mJqa-bai_w!elXXP)c)zqzcy8An6EC;E?`0z%yUzR#WvaW8 zF`*lYkI9#0rUy4q~1(X90fWjAlPIU}AHzh2A?lAW{k8*lk0C)E#57ip{7a2avGK)K%`}!g< z47db_8o=YY2w(~NRsPs$b1yC&<)_6u3kyTWnD|mrXY0T)^|jN=t6{hRDXRRM=%QX+ zG|G}6;C!k9>{Iq9 zSqBNm$`GWR{Da_0O@^ZOYePd|{i9$AluvmxJTwf}8@$sg);a3{6`P$0y%f8oXk;*h zqIzU7g~&fD@DdEhLBqX1oE&?CFx-xUURAyu=O|^H-cA~WV*{trda2r`*)bJ^>>^d8^OYq@Ca+K(h6PQ ze%-?Or~$x*15gj$7fd|+x+Mp?uP$m#+yb*K-B$U>L$ZDf%jb??rrpX998j@+kQ$SGBx+wW9dlv#os;yR0u_6fQX6;rU)r-0Xr4&h2sW z&w8k7ONu6WOuX7dh{R#>fY!C0D0MY0YEC^%mfjeGU8y>e10UdgS!x(cFhd@a>-8B&jyYe`^o{ z{8soMDSsLq!=oH<_ltbaj(o6hm)#+U{^`G(+=ZwKe<2Q=^ulEuG2f2SXC zhH_x&Fc9*oH1g3fWFwL(XfJFd9cWLI6L~*qHb_Ze@INIoNF&WB$@jV(aG@izrX(t3 zS9|3E7|sC?)|633!al3JbfD2AXEhQho%~{M9K^ zp9J`97ihc*W|0QnZ>SJk66_4GulS@tTp1IQTDQRdu_gH#qw9@=EgxGHZp=lbEBq*L zfj#+|!kaX`$HKWRH!;L15R>O5S7GRxZC{kWG$oub62|T+b^zs6p<6F&Try}UNT&rj zgYH5)TncO_xLqWMGiW3ahw>c%mB+S(btwRD<&YE3WP&kpiG=6JPO)vIp6fcAw6UM9 z)070@IPK9B^whw0l)4%Dv#kR)a5JaQF=J9i9(8rN0knR=jGlxKSF({c?C5oY>jRZ^ISOv{EF7fwsl~vC^*x zE95A5x)`K%;G&^+{{q%aWf!3{G_Kfs*iz7*&8xX8S&9UWqpkHp*k?W&CQZIE99f|$ z&xRF|0L?ZGV_i(CU%F$M(nUj@N2FemYlnvY(tE=)*c$8d@wn5VazSRa0QCs3H>NnA zfKz4@1O`5(vA{}*gcBX+1xv_mb^$$8DT)e3X+%4#!|+iXhKjc_y4%v4Hd3bPK|RDC zgiCKrD`B0GXQanErj%{DEiD};ts(uMCG2ly)Nio&{2P{nFWo@p*+Su~qxm0)=o~fh zkqAY!r-9)M>E_Alrg*EOA|BqZ6L`&nHe!|Zdkzyd5xfHiiynN{$BlGB=>kafk~B^h zUVSwyp5k}gYc1+7d<#X_S`-%)rM31Q@TEND{F55N^@$7@ewhj8n)$MOBb!>>P$ z)x!6$e~V8DN8We~?soU+6cuhcB8P%cW5&W~Eh1)+&jtnn^$hYUGW0>f;jeAN+P&F$ zj_}srZMkvf1uY!h@||N>*mqkJT<%A#!shVKTYql&|ZoLZx&(6 zzA@M!tlf8F?)&lJSOU)PB&L6hl^CHN@T`Jo62mu8(2Ed<{Z_7qX96Go+jGQkabzey zwqbt)cAU-vv!@ZUlOc{L=}h<{UOhJYdc2INITJQ~96-@+?7pv0Si*clL7Ak2oa z5CSxdilJ<`39*gv{0aoPfWfYU=VZ8mea~adA46d0CUE382_Yfz&0&UEzK?0&(qL`X zf_%%YKjluyojk$x@TAGPlPBjc&0C(2gp9Y-a)S@Tt3Nc-4XLjBE&bRMXx@(4C>sp5 zdZhfT<%lg5o_l+2dD)|gePJaG6c76#&e;M^E*Aw;J& za7qGXdMT7P1j>Q<;#rgLEi*HGT*1Hr!XTl`P+GNEU$q$MvAazS9F>j0RYnaE`Taol z?8&anqghY9{a?>GdE;`~$p@D6Og^_<2-v@WxZIu5WU}T8W#G{{zANN;Cj!&EJxl)c!DiCIWIE!?kUq{vEc!DeZEb&2!>1cvz=yf^_mR@IWf_+{Y-i_-}2I|@C#PulC+(Vq@ zWwT46)85Joqoii75)Yk6z;kDXRWh>?f24bz6%lp{TqTq-LmBd)G_jj)1!ZYd>z0_y z5-QAPbrsAll$)@0M%jfW38F1OGWN%Dt$+Js)DLq=d%qvO&RK zvn5oH>u=914Hs)5&V|?_F-*8UCzQgFf|ej>oXucJuxCR(gQQ|C63fuKjFiu4GyLwf z()1EK2=hE^FPazOu#ceydpj+Fhq<&Mr0?K_fd=5c>@SU5dWKiO-@xfipCHM0ytDyN{?&sres@`W zooke3F?MY1@}O*w%Lva5Jpbe|eNtHrfRvCrWm1x|lun>?O@tlkIa|E*Oyg!~Fz7o( z3;av@@eHL60T!So5#~5A=07`ywlN!4|A=2v=cK0aS&>4f7}1<0q}y=~l6vHH5!WJV z3i-QAucNj1-}={+M#*gbTt1vb+o}W{(l#bQ8-(XSa*VQ-OF`49QcY8$$ig03n8bSX zjf?Z@Q2}hf9hQJQ&K6gyof&U0mz+8Ai}m)si|66kGS+LivbUC6EwEh)lo}2I4=;_- zCD@U)(vJ-4QdWl~(QkyEP;W|;L^GB4?$-_usZ}Uks{snbL zawzr1FvKr_5Yyx|;zP>?P6+zukX>OhWJA~pJRMS_RAIJ65dztj8aMm{JzIjL{Jtz` zBMrjNW9P#jVdl3%6D|mR6P8v7Fu=pfSjRUZ3CZ+-a-gypmtbl63Dg=E$snWy)aZEu zOPUj$w6kT}Ol+JsYo~$pRw^?qH#Z@@PGBW@far#49a9D;mgVL6-jNfQi>i-vPCo?X~L91A|zB&W`9EH#ik&Z z4)tNFI-rm`WzHB@LaQVN6rrkZLDJQ$@JX^)or15BW_7x{O->V(M=M)&!W9uo>xoyr zY~CAvT=J9-crUR^Bwc`~$c`5p<_eRAG?B?b8?V^Eg%)Y~pLX1Cd|ftaU~kkLqzVR0 zEFQDAVsW??JL*e?N7o)${L^O6TgV`3Gr+q=PO8Du5`WP5)nFW~Hdgwqk24sa4*Gr= zED=~bnwRlJZ2G_xBSw`jLNRt^h!6pA#CD%q)7V|1<~kVZi{RJL{T|P3*?@3vgvfe> zcb^iYx>&YIHlnK@)Or;5oZ~I{I}D)>!UP*d4@w`=S}oKHDgmX&3I&4JP-$YNs{ym{ zf?RE8rSkzHY1YXsftipmD7&{{EbZ!33gul}!cbbF3w4Kuzvtz{jtSiKHW}?R1NdzL zPG~4B5b%WA@bpUH-oo=miEgATles04C&bg@{q~_znQ!9w`(!xu(_AiAdOLtk&#q7w zzF`@88cuG0#em1qusYo>kI9)DHg< z=(NX3E=7;R^GP7uI>XhEP1Tm)-B>4kFsv6A_!Zgn1q_`Nkb!UdrIEGi1ud-4_X9du zfps#?(==)I96a@q=VC^s-yGzG8rX}+0*Ykr0<13S{9u|;*}{2K(MNWrG!<&1(X4ci zoQjz-ED@eq=`3A^(m|pgk;3mhaShspeRJ0cOJ)UZv7qm8kY=wOM7n&~Y;;=aY{*S< zLcC2WL<*zCpwB`Mj3~f4kC&=EB*|7(L_J&MRC;Yr@g=l;f84oOlvx0PtoD=pxgSzH> zOBm@4nHZOeUnh&>jCt=5J`Z~brM0^?I!5}fAEg~|VI#Zddr#1JDv-WzA57DkfD-m) zmdh-b97EE-$=~9vF|!8^uxX&>V5t6>pzn1uOq-35ld0NSj605O*Jj~sa!q3n`dlaI8seK68`dR4?w-D(XQ!w$F;Xh| zGJZVHBDdma;0`h|Azj@(@N45%7`RTLiy@1wOi09^l5Gk47&3q-@Dn4lx?t-lD7>4q zNK3*f{4wcBm^ADz*kq;#Y(RQO8cR|VQ%stZsU{??K7ov?CPu(DSg!?2JG~#+WusD$ zbxLVcKQiJvrJjLwPCxlm;xoyQ`8gwS5kkclB+c>f*H%-Gj@$m&`h8$>?O-bO03u4ryU|W?z@eV}<+6 zQqr~_JuRc7Dxl^aGQW>IzeebHcLbktdPvrUzyAx+CCB_PT<; zUk6ayukNd!$-;cteisQ&p6Iwdpb)k;qb!$8Cxm-77?v*V-Jox8@b4aE7%KVwz^|Sg z&A;~y-{CYMhxN z`k6YmevhTsJ+%Cw(q@L>dZ<0l~sp3u8p~HZw zGB*tRt_D+=k7zJ%c;CXh2YtVjIVo{bANV_)H6?V>GSa&z$n1)^=#pO=8L8G!(GU9> zz`aQRnv%!N_mi`+Cj2H*=t^-RDc8l}apW;wj()t~?>P!AhQh`;G)?p5Tnz`{Oz|V5 z@o74LM@h48(XeOySjPgXQUk`;61_gI=;|N_T3TvR!J8%is~#o955q3{2~MdJnDZ_B z5&tfP(-4Lq0BI1oK-PZBtC`2%LdJ*?Z(B{C(~re7kG-uwiSbOb*f?qQOeo4XaZ*Kq zlNLjGBrwdT6}8QgP(4vx(~NW~>F=b)n1cUCE*axSPVU2dVH3fmPa7OY%QPq@Yaa`L`XXV|X`5+!z~_P!D8HpS z9r5Ii3>}%Dkvw*H@FRJyDM6`h|45!~N>noK^dy@TL^@4Nj1;B*-4$hwS#pE4Wawij z40ir0=zAofTNU&@7_hJ68-l+1q$guCwvp`2c{o6-G82vM1N;9(#qD7rjnMMvL*@Sk z<+Tkh*JMg7No!_o_Sr#X44aiCz!{%7x#8g?Q=TZiD2D+P@>PExFcEx~*UbSZSqam- zf#9sChfg>bBP_)u%C9UK$Hkugkc}qWva+Z0rL0%OU}L06%tmX3U24$_M&VzurceZL zMsiOuiRaCoO*OK%E#{u`u9!)>W z>%-T7v(D1R8mt>BGuNTS?LprctwG;Qt>nS%drMx>4sQ6SL78qi2Pc*vdvnb020Z$( z5b0O+#9Q8gvw2Kcl=7Fx!L@X6B^g&(4Gs1@ZK2eXBV6~ew|1`q24$iuo51r|(SD@kTQrC_n}@MT13Zy32}BVki0t3|uVV8;#Zaq; zOg4?ueit+@Pi)R_3HmyMeV%lIl1;~8Z|Jlj&zqtRRJc+!10SWsQW#J?ZG#rhDJ;4B zfzr1GZ&Wss%Ew1K*bNtyQSITd^Ey=F?P2#QbQ8ovPynP#n9H+csY#w-A3Bj>KtN6? zI_PkeHdPsDGrV@oY5Cd|=Jqv%RpLN9KvAZFsn#OiE;T7O>dIH*?ggxbtSBST^;Pw~ z$rB1c3f%4$HpW;%1mTs|t}m>3oR(b5iBqcF(X+Be(w~zt9(OxA=AzVsQ-AQJirAE7 z?*&9^=z@Sip^%%RmaBkMd$>7b<9PB^?qsH+g&fTtQ83b-x4uKgwpVPVDyE7*>o;m` zW%%^`?xfv~jok;-{Ds&uY}AN5%q#%>jc1hbt0!+;hL8hnQhZ_1_ZSJwGmiZ5T*bzP z%JqaE0DRd-45G>=v$2a|BkZfBm2fZyecg9h9?JiQ7DCYXZjjj+QyQ+Di|5TZ z_99Rv)L7@u9`MEcjT@uN82us~QL=aT{#yl4QvHUrBF1jm$chY{wAipc)I4kd>JGMe zz!u%Lbl3BA=NmM@sty%vPZ2v*5y z1(i$;1>szuvJC0|=$1|_4--p|H`)P3lVu|-oL1tqLEi-um@wV(O8=1R2$s69JtzZ> zW|nh;q1n1|NzW$MO6%$=Ijq>Y3Z5(eyhwHHtX^P3XEBhJPhG=6HiJHa^(l@K^JWgI zQ-eNspi|T~u%ce*5NnGEjoIawNPg z0u9@M!n=-D+%9yzIVj~v%FcH`oWKW&`Zr5an%#p?ISBWo;OQ3kdD1v#Qo?cX%m z?2S~Xom1cB!WYWv(&~wbFSrZwFF?HaPCRuI;-9+{wnBUWLf-_$=h45Hq2L}_)0QN0 zYK4o*VBI4nry99Zju|&lC8u$%aYKh{Wcwa@oheP&O>*vvFaOKnA9+FFE@0K)k{>n= zDKnH(iV}~@aWUhDxzM;XZj|nJf7gRzzUwhZzWMabE^Fi#c~o0$Co4HvW#*}Kr@BwE z;pCOOjEgn{vc4e#Y&jBNZE{ev`?Z(L3^p5e`PW zNUdFwF)?X|5$e$M;UDX&vk#>?dVl`Vuw4s~@-`NT-H29eFS7>|=nPL!p& zu)YlI*UyR((}W=^0^+X!ny71F#JS7E8`6cEV!a}~eRb*AA<*FC!&;^XEpmAe^9VrFMV0S=b?AFvU5y)GJX zqJ(FKf1Yh2@UW`rg=^zCR4b#~FUvDOTh&uEyl%rq&|xx?I%-u93%bxsWbTU6dmQd*OZL~nLJ?KmKJ44l0 z@>E3_;Z2Iz?A~w{x?z}%vj9-M-|eBN%j5xSk>8{zS2twIu+ID4A8aXmu=SW5Rl#<(xL0_r-lrHPZ zeqV4vFBpWUKtw2%gU0x>@?NJMXlU-|a%WDA{c{=R>T>_zV#-8>+mh@L+8gaiw#>=2}xS=-c1-GW`EF z^#5AlOXYA-244azM(>jdv|V?D4rtQAj#5To1z?Dx$|ZB8MYbm*y~RFga6bC^TIMN6 zXp^&WQ~+~HxeqMWEaSZE6nh-iLl^mQZeUn^beq!CK9t=7A z<+8S)-N=wM);!wXcuG!Pd`dRqq`b|tZun+7a=0o02GiVK^7H~#2CY#AsRMG-g;8t5jf_UKO#WjZBwz;R|i(}6~pmyg|3m^f?crZpXw{|lN?WMV={6apzA@7(e+S`O)`T*v{L4(DGskM+S(`*G zk~<6Rhe2H?DKe)xQcFjdgacz4%uNM}lM#(JgXFLndST=AZm<}nAQNM)GO+e!TVx5f zphiI{&}0n;eK-4_(orn-`#$&twNm?Z#9Dx1DbK>ASvdu#un!QdSr z*9s=wSKl1Gp|MQ@4YER**?`|e(&0X^>ZYA-MY@)punFn{GMPd8a8+_)}2XjWk=9bH@zg0r8L}*65;RAv~beII7C2rGaPfD@-3B6i<5513gKrkUq*wZ!z)eD%C|u_Sq1IK4YDGa zdCRpkv&Xf_lG%)nSL~RKFHz&~$&8Y?!duXr0tgbdTlBQxsm4v37VzL$9`wndQn-f+ z`sEaNqXw~wb^R>jyr1n~>wkx@0Pw)n*ElG=PFGl?L5Ek7F8pVZ?o6FC|SK>~T z5pY))Tat&%cq${~87Q+4p6O6`H-r~P2wDN>5zt73y10@R!a8GQ90|7j2$be^&riVl znwAIw-esZ;qA4Ab$`spIu^_jmg+BFph){aBL-Q8m+m=@r zr!>J6C6be80?NBoohQ86>U5Xm zgx93*a+gS$XX*ie?=ysgan^mvTLhBPx^v-PU3f_^n*WG@yPr10w<^b;@GevLHJYXE zPMlNH>n!=E5gB%LmPia=B60i$Pl?3y{{#OT{;cQtE#x?H=7jedbvA&tR-FO=kE>JN zX}wM{#b51^OL}$UXPy(@47J8hJ6Hq=Wn9LtpP&91>@x4RQizjc=O zDrc6~Y=+L)9e{UFs3YJVa%futRPj#J&@x)L2Xe(wu5;BNxo91947pBms|Utksb*T! z0EnTNXx%2yA@4F6d-eGf-U^tI530hY%j`T5K+aX27yfEnAan0i9PzDn0tI-sFrsxb zun@r7ANZ~;IlQR^eTsxWmre=uEAg{8Hs_02b!2qYB-UYAoH zz~_fCIK$%7N{rg#)`FNF*$NCeC~0)zF;b+u5DRYasOWEP4Jmpemc$?=qG>2Wf$=@_WN6^jBo>PsNWZh9r7Ta*0 zwu@CKxMKwVJuWYz5bup|fb|n^N>6tsdO3Aw2PsOwa1vUeIAA((eSJ~tg$OTJ;rh#o zYJYVP%4EsMj@Hbs?llS{&ZDp+SoQBVJd+etc+B!q>+J+IMk|G>6Ww{jh)%q>B>A&O zyz3txT>nV&zddN|MUPg}sI{#)&*PzZ;7Cm|SC6L};KaKP_(&H1|M;M|i*z>%TxYm9 zIK>2Y9JR$pkrtyB?iX0_5`5qS1*uM8N!0s`3S*`!$ot*lEUsH`A(m;a|L`JKQAew1 zwVI4)9(+7$dl9$WAf{em_Xe$OEuMVba;{Y^P|#Ga^+^i%IOqmb&|b&&CyT<}ugjx# z6EhOdDIk^V0NFgaM?9wZ%VP z#dQ?uxkcMsqYjz$a|^@0IJ~+wT8>Gg6r;BI@1aS;Zancz4+VgMT5X<8z1xFx-uH$( zBED&KdCm)X>@XlSu(hVXDCC$xeuoNx-J zBEJP7{vClt*yo%prFnK21{3!wCjiTb z8!bT3C-?2^=6R5OWm@KYnR6nk$(af0K3Mt&MyDG9(+c>}Rv$z@$9dSZv#D5GpO;Sdj z@H*zJ>G%XVELO1>8pAS5&xK_cpSygGm1d6-;1?$dlV}GKUM{Qy#BJC3;&%i zoQ-Xby`D5_WJEY9WrlFYy5cCVm~k$OsTCfkK5^asnc;4xo*rvfF+o)A#xPAmhi_f~ zS66I+@ouWq+UPfUQ zN3_n@uM5@xiFVB<0EN8dN&v#H@ZwN@re3Fqwja^9X6w5EAd>@%Q({tE{0|ST^}MJ< zI$^GV^UX*6n`NUI4WdwO@t1!RGdw=c=%QzvN0*9??A?%_l_x&OzFiCvt{-PVFO z*Xwy8_jk&q&7Z4tj0Arw4qHbRN(>j4VAB0V`>G}EA{u=%9vMu+!qwAOPqz;#$$*!N z_}%l-Z{`T^ZyG=IKZO#{b$O2d*7odQe=S_`(Qm@Dq4$>xC64>I=dZsOJp0jae-D*? zsNGV^8`Yz+?ytYzy<*p|nrC&tsUY{OXT9XtxtYUrZEW{fEcq2ZYx+$U@z-B7N&39R zVQ+!@?X9D8ZfGJn={A`&FJ{=wm*xtK1XNoJp_o4iTbAzbyu-f17&UZML< z3DEp~1%-y|Kz_FW=x;*AvO+wSpL`4`?G5(jL6ErPJ>p;BAy6u)dFfmrApoU4YG!OcAQz2kN zn31*X0NwKDM!C>buTq{J^lc@p?v2xT4{*uXF5L8JsCd*zU54&~UWQ$uwWtVXC-2^y zgC8g7@72fHAgA}j_ntywil7%NMd~&-?7oySW`ECeTVc=Q-$J5+33?qBq&-3#CQXZV zc~3*ocS9y~@5>7Bl{-Na4En%(tNOkv3&w%d8!e@UwcYKpEYEE?8iJ2$$NE9vId}^r zO~-B|Wt_yJc>Br9Vk(}^4EZ@A>FbmEP3l>kkg+aW8c>J1KUb;RkyJ`X-JgP+$@KdZ znI4%eygzqZWmDKp1^D9_)-f5h!SMm(I-IF+Q{T*%Yn34Xyn2#qn!W@ETGJFg(+Cno zvWq%#E2fg)?jQMRR39f@1Z@zQAf>A^CmjOujFU!z`y3TYIO+4|kev-NJO|+@Tn>mV zLq<*02w|>l)aV=NKb~x%|9KoZ{3vaS>++fph{k3{$AO<>uJM3f(?Y}tlECp(v-!oN zX!MDDRKjJMKTr+clH4mFiJY`SrX>ETpl&b;e!)konnrg;A9lnwj4>wt=dH zQ6`cyHz6H(DF+ob3ScX4f<(?qclRmk^;0#O*UsVn0FZ=Q3+5yK0SK)S{{BEHI6{ee z3x-~JA^urI6&`}-;Xdqu~;_9gg&XGqt%X^;zweawu zBDw9RuZot@hst=X#AGfF-Tbxc@-?Ut5jA`S;`CLZqK*&J+75=j?BVp!mfVK_=Sq6u ze?y7nNg55>g^8TBUgq?w8r8v|j|paF_qwlmXw$tQI3ekaDy|+pCs`KQWNQ8O<_!)j>4&133u<>{EjRXlF5ilq8>qWz9)hGB%l|`>MDJXFa(9)Sf{) z_GhYML2+f4{#=zA51natSkTSND$r^;(9I{RF3Y-x1;QcA2=~`eV;2kqys#Hnr8Zka z%Bp0zT`*c=6{8CeTVmZ5Jv=+dLs1K^S74g07=-x+T}<1};wnWgyO*iMKoN27zdUeU z0$0XL7eNccN|%Em*<{vO%#sqoI~T&)q7cq9tI+82!njV9J=wiFX_8A7{%UI39PzW} zJwgOowJfs<$ii5M>Y(Z`LEq>>3Y~`SzDm7U zYl5npQy#hvzJMK-_737dg7k3+-;IC}0|DOC-R6R4)%zfGM2r%a>KGFA{RG;Pwwqr& zfnASa>Q4eYPpQ1*R@F11{A-Ypq~lJeUJE@fa|9O%sv4@E_+>!t`9GU#2{m=#|Ju~4 zP*Vh&s#BSzmz{hjy1COyn|L_E1~qfjxQUNvuB^9%|8pz zHdlGCtCE#|AKWaI_nwAS*WegiebEf}7+bAnn)|Z6=O`^v)D;o2Kma38``}Q8{~4TL zG^6+B4`HRo(3Lv0P8SYbx-zsEXAMXVYm$b!=}J}|Wb{M%WdjtDcL#=r4tBbM64}Je zFd&U!iIUz0-(OZbH2A#bXV+=qE28uM+j8~*sF%o!53dAoe7^gk=M-Neh=Cy6)H6{U z-%8Qw@((N3*BWo;&@B+<0rY)s|dD3q>#!5-x?PCR719-0WvB@zV(X*BdnE>fta8c9? zqG0SjzQ!tIF|$mI0c>p zz5xIk2k{?(e@%uxtY_l;i0R>6Jb_d^JT>70>^@FNxvQje=h`y=Ie z0U2$#;^)Y6`)BxHBy;f``~i6mMCR|wH;We!d!motMPn}NmNU|;WYUsRxPaWZBoi+p zRZH}GyT1ewQtbcfMdM2)LUdzdW1S_rbqx$0v!kqxG@G1Sl85giz9kb4Z^Go=b}K+| znhkY+fC~=^9o_3#DTsF*qi-Vox}%jzn@{X-UO^?`)8|5Odxv@Cy9lPFf4; zufdxzU*Nn+%HhI*?=yHZfv#)7_sN|y$x!CwAkybU%Rl!cy$RyW{YE(Whwun66kusa z>r%3HSqi>P-iH5w9{X~cf^mEoJg_bkY*x@XIso@*z6joKq(-317OEOV`ULQkR>%~n zB(M%58AD2kuoMW=R2HOe2RUyt!g|UiVCnbP%BIbrMSpNP=hcG#6H8lzln+s!2aRSW zeI`L*dcf)CzzUt9C#B*%lcveKJO{2dCH*)+r3R&|K-dRsX$l+%VCoEpyfvyw=klcC;HO$; zUR5fds{Ymqmb&Fy5?EdUcPXboZX8zgDZPT^6obAUpUPyoE}sADPdhG21Z z)bEEALf2K0cLQ%00=_)|9{C~QK$f}o$ctv9?8R=*yC>|dyvL5l&2&8}B7NRAjo1i& z(b~d~`f_!Ly4mobU&MJ-D6MZKmV+Qu8(w;`F&fgDZsSXd5G&nKQiBa3KTSr`3OTlc z4q~wXP*L)^5}4|F{W%U$S_FOLf#81Qx$+_$Qf)YA$%^boMpm>XG~&FUw$?Y&?uI(} z!E>mn`&@$XPjG1)RXDL~m6WIe5KWm4MnPHjwcZR<(LOkIr)FrCf)kqJS5M*-h|h1@ zBJ#_@!Ex*Vc5o!l$CbO+j^M9^d`^}GNz&Q`{_LOxK5TPZ$=Wp;O#dL+w=(ZK4Gj=4oca6rO2>#)r<&+=NQ2t(mYeHL( zQXgyQ7>1xb&faucQfF_MTv-Yxdn@(o)_)`$+FowlzffsdlD-a~%wplq^qo_}}e{>NuDo_@%3@BW=1^^K{-xzUY(vFzW1 zFTN$G9>qCdc{uM**q(WTJ@S3J9HB(OQ?@_~8+^{MWQ{X-^++HAy6ELK#VGA{*Y}=E z@Dr!lC;LW@42Qb-cH@BWhM)ZDsU*iEt(7eW4Q(qdJ2&qfqFmS&^xfN9S)31>?!o2e zn_+o-!ONn{8GX@wQx!_T<7~KP0fy@fC)gBY_FA%B4Y#Ts^IfYXt>W3vRlT$AxR6cv zonzB)fmQ-bj6xH)|4}r0C0GoQbj5kE{P2tz`+;iWJfL4sR)ft8USDwTk>{JhHV#Z7 z%q$oH^UXouKU>JFtM3O-*1wV8SL^XRWcZWunl0ekkBmCuEqNgbIjm1CH_G8wlrH~GwR z#DBR0@t>`P+jl_SVg+7E5S9aYpl0%ujVs6D56K5Bs~o@d{VgQKEgwAQ0W+B5sE1ag za;I9@Epu&i*1x)bW*5$KuXllu!fu(Z5xVf0nsvk1nY+Tqos-wi9xmBAwg06-hkG6< z!(ZxEPE`Qk^}Unoeb{fUQ|2%OXm%l8 zZSlvDm2{_RtvgC$qt3~qsal@ji82qmu*4kNK5>8( z@|)p8no8L)!JdCdy<@#OGYyQQqb)#ONB0f$YN9yrYv8%}K;@^`)aZ-r#{0gwKKj1H zkfzTxe&ZU8%6l!=vrove}5*($?~eC3YHuPZBC!e;&A37hp3gig|3qCTs&+Yi>dnRrgc_pHB5je;W+fm$2J#W+a$+*(%`0 z^Q?9xbwX3r>db=!$G=aK&S!PFl;91MFx)QK@BriOBfB?j!d?>l++P%w^-m)W&!u21 zaXY2CwWbVcdxPkn0;~IVd=KD>Rn-2@W?- zc>d@xP~9Qv&t#QD54TfxIno)ak9^_~@C?E_^~}jWGRA4f!^mUKvG{rNvNI85^1gEx z{)zNC)8oes92P6Y_w6wab=z=m9XJ#g!1YV;8X!}v7AHOgD!zbE1QxKeWgi?WNV*r6 z8cGfL9wvXQdKSMy@-`V^Iv&_moOvQB+J}{Vb)8Xw?*S;g*rQTQq%Pq5ZIBgaH{cqS zs<0mvYXM7dk#9EX9o51JAw^iw5#5ZW{UBR`lkO$_9#tZKO7EkB39eQ&0inSPG=2*3 zvQzDoItw88wE<1TDk)OY<6*{~mHC>yOEaOD58y8A(PLrWED$bedx~WCf(~HcHF()` zUe@MxHze6-3*X4v0=NwhW9WDIF89GjSC(E@e$-yE*tp~^xzPE=b)_-VxCI<6{@Q>> zPXpJpAur``!)5pbGK7rH$XkPk{oM+ta0c*X~~KS?Tx%Hj@JIL@%laea%n}q+5W01?Ze; zGxRDG^;Vb-D$zqBtQ^>e^A5l){XIav;uJyvuENo}^-wn)>IQueLw9esJ}wd{NuXq7 zs1+)Id=0I<0Dd=tj*t2xO}6Hr`E4D_2)OR^CV6g4A|_<-79$=_TDBxI?g4UP%WT!b z7P@s-kesbEhR+xP{g{s4epAAw)IQ%NQnfYbvAIEH1P9!w;fCkvTcP{MQd0~_%`r2X zG3;1_7$GJ$N7!v}V<}o}Y#`t^9=qXik$nC>@r;bxPF+W%r#EBWJp0I}jrNqM6NC!T zgJ;_3*^{4^J@drizftRP@B;dR#6NGviR7W@9XN$tdVV49Ij!Z*)M|r?M0cRZqk(kk_jpnEp?gieDS|H874y8@&b?@EshWms%-nn+s^Dkl%EGm;qO( zsE{xF;#z3#Dv3drEk{Ytwt0@r{*+QY;ZOD`@k=?fq{Z#S z#hm5?mJt_+i|Nh3B*c{701bP%AbF}qws0sFRhAA5<6gg}lb#6Cox8+WEeEWrll)l}%Bgqqa5FiK7KH22ZK88^xH0daymC zOO-7Yq^tc#xF%R9R*B(-b#|*L*xSG&+YLt#F>jxSXOri)rzdiLDq`c>$-;qdo~f~H zZ*5CJI&&eCu9MHU=Zv@p9|;NGm_l#gTb1Bsvr9-4NtAY^Lj@MGKHu|w`DQRa`f$zB z27FNV`TH@5VY2V7{_F+@6yMwon0s-BUAbQNecDeyH~>CBRL!(GPdu=cntt+J=Vi`> z^vNZ#d3gY)vrT(hUe}gbR?z+PYGk|-h{8zv0mOAI#FbIT>;jzMN{7DB_esDEAbj7q zM}AO)j49~{mPUieSitwU{^|yJXGhszx$c!81Q03!gf@>7X1LGyX5cF9^Kj+w@Xso5 zgqHXWiyE0BT-grC@IUIN(i36q9c>HW#Fwdcyp1n~FNqiy+GXD-veM>I8PvK2aKYit zKHtVqgL74A1bje5u@h825K~GXB@`vc%2=&wSd(}W{C+B1`h07Gw>*q39L7R#@-xSe zgZ`7AsZ~Hb)q=j6UWk;-1HQ2*qniW1ul?Fi=8ikuAy68BWLKcWk;EFF#gE-*Z2ySf9$jcANT#~XoJVGyF+yN+Fop3>A6K7KA4*q^Q+}WYx z!LQ)nR$c^^SmFDYC(oFR-tG=p%sPG0GUs%50wbUdyUTr@vA$-HZ1`6E*Gc zj}Yq<9CHgJ?74PcG=nc(rM(31IddkeBucP;3yg2TXZ0(+Ja?%f0*sd(a7nn%9^KF( zN1D#Sw?+;YWftbyC!9antx$Niw`S*wHdvoSDyAZ6E8t57HB$mjD8Oop5S4@zA`JTF?Awq}y`QpucG zPQdq$>{__E7rX(=)F*2KH+z^s42rNbHmeosY>-2jP-Ro07$qpiIf*&fM=riRm-!GxzM9#1E2*ma00`*#T}5GwcOgCp!XonA zu0+L~q15ZURt{eYAFS~Ea)2gk8t~qLuYe@(eh$A#_U=wstpoSHfX_z0*{x4pdK?+d zH)Dq*>5=17(+lF(qtvx-q=?4PBMLGeXOM|x&U_^0$(KD-m!nL#YZ3ha;KGN@HzVgz z+cio%-O&QaQJ(V$da9ytJy9P$-K6>ezX!f*E6^*0zWd>5Q+CjGi)*P<^bmjN_x(?h z{6y|gpA9@Q-=u(#$bfbn3~ufIpO4Tp)N@2iPNEYvz6x-4KftQb5d7b+K zrH6H(%!Cdkts)=niN{OG-}mV89CCe6B5-7iSJIPf{##Z`lP}3!=OtK~a9+3ehIi4%&?H~Kf-v^0DUD!o)cl6IN@Vm5c-$UWxruDB9o2i-BSw}CA`&mEFepKK$BP4#TKGK z)ZjZsVdtmCBQU!=B}LUcMdq7~ql(F&R%q^0n&0Y<;?S5;4QI{B_~mtE&4EoVy}&dF z|4o5H8MEErCIT4u001%`b1X2}uaArhB;~;ku>w92*|WofQ+m-!akSkzgrh3JQ3$-yFi?QMGYr7dv^A%9I4rBrGx?JXzfAxP3F|yx zd3BMjU)gK$NA@IHb^b^n_A7hJyGGoj_eXkDtWzlneJTDe075(kp&%^4`?nV{e&tOB zCHeDlD?!v_YhI|~b+mX!blRJmoP7WuC)cCUSCNjKf1$ zM=G4)^wz5ijN_W7FdaWr_T}{heW^&)8R2-!?oZUoz6`jO$Cer4A_Q=Jtxoui82z*u zd~!gCq}o0u__aJ!*&)uiB55mp<*o_72m+qvQhhUg3E_@NbPV3t_aP|ngnyb3da_mE z3LZ(X-~u(JS8(UTUD`1C+#dZ<8eeLFug@8JHK7lM{rA&p6j=JbGy1KwKfZIuHvzyP zI*jy#Vj^^mBKXD?J$GvZLpirWdGSY%1R}+u6W9S?s-lh2FLbHX_OzDwf~6aw7 zr2Mez9Ej|G9q1;hwjJcn6EJo!baM;JN!2Ges}%14KDWWQH=s2L7(Tra0#bt>G}=40gC&X2s>WM)2i;0o3&m6a8y8g0l(s7HzjdhWu6#-SM(}7zjNs7FI~;l! zPpax-9EyG?9Ih1c;CKinRVVotTGDkLt6#e9HA{gTrP8MUXIU%_IjJV#d%8e3#NY{_rU62f5J zy$?0!H$Tu2@O?Evn|yj;xGf77d>%BqdI0OAO9H+*1B`w+#IvYm3bH2)-)}iGAcJwS zdIBE%xu+WDcQ)K>nD4ws-l$J@%!LzSDFhbo4$QZ*Hl5@!)0J=zRx0JXm}G@bQ4-n8 z>#?4ZI40iC>2LeWT4+Ay#;D>0m)!Ohz)qmg$bj{13EyN=`A^kjgv?<=Iu*Jgwj{wh@-$FfF0-l`! z@N6@hkHN?XpV)DS?oor_ecSi9AbIVzjQBcnlO_Bde7rGwlSO%6QMOC0vg`z#sfJvB z&4@oI?CYc9Ya8jWr%XBz5+E0n1>b>dEZ5-61o@!SiRSzuE5da`FnP>}52t(ur4*r3 zUk1}aS9X>-UVjR{4sz@D)!0rRdt*K541Rp$d;AGG^4GUhxl)BKTx5DXm&CyLC+If> z2R)I1cMka#X@;QQ@4I-CY}l6tcER`d?I_7_8UbieVHDy5ahD~*b^h_~;EsR|X{l{J zn^3r(3osLKfMH$>X~*WthS^G&DvfjNfMI_nsB8GuO2u1bARFF1KG&@Uml5zzr!jjc zR$_#j;8_LFH0I&C0pjpG`C;%(%SYUKj=U2O3&qEt-=BaTI0J4xLwE{47P0`s-ZaEt z9}9gzJRQPbcvlMX90)Jo3GOVoEuD?{^$=behxlzYh5*f?=OE9WgZO9R{ZkN1A#HLNFe!N_HRsgB;3ETJC>x<~@1%1UBmT$75P#+o zXne^~{)@}t!!+decjC(4TMf#$JoRzJXF_NP<-7;NbqL#@LVU`fhHCBr zdlc;<_^3KD41J)wnjnzYULPO7{6|Nh_ie0iS9 z%$a%Ta^87o=Dp21;-)@!Q^zh**e-NZMn_UvQt_q4Pm`kJ^&(B}w$!#FJ<=iZ&4IYG z`2SzY$Py$z=SO06KN4s9khr41wYU7$*4~w`mWy46^K#vIy@;tZ5TBQK{+8Z3{&yH8 zo*F=+0_vR^K&=I_D1~)kl)^wj2&J5S53x^_Zaj8QM!AMQr@`9i%=rw`_A)HsdSpbs zpE^lw?mg{XT6SL6rs(^sm+Hj`$|ADRsW#=joCtYcOD&=qo)iD`+~-_6{0w!(YJex@ z1m3~@R|c0-UV27OOSvEZO~L=X6zUF|a7H$#ltEr5R6r>f@z9(z5R-Hr_P3Kb65{({ zNGN3oA~|7c7EuXZgr&hS(=2^v3v?Gu*D?O~9DrofUW3$mhuoJ^E*{Ibh!lYLrMRIJ z3!w1RU}xI29RM`0RIiJ)otHH*R27V!21rOlBbpRS%%ij!{qFPfJa}{S97`X9!Oerg z%_5kvSo)msJnQ#oJv_tfkmm)^T9?IP5edKo$OtwN1r0|9Q2el$IwLl*K8q%B1sGOoz$rQ%5Y%4+>nxkn-n}Im2zW}wY zBBswmoKkj1W_4#}je{|iK|xBi*(z#+MO@igIWw046B;1EXJs3M#AoGzbbIK6+yRZC z%Hf7O0PY7U{{i9)5MRiRgx0!JqOE7;F37t9c{d=w1@SG2MTkX+uR(kb;=bI(v+$>B z8GZxgM6)0J*HAY?0UW?cBe)dYl96SjN?~I2B5UbB=Tqw%aCW3Ks`jad&l-?{5cajk z&ApMeryCf~^f40eKRLSrPyWS&GXCWP`dyD?f1Sq7z;1b5~rVXt!66tdQk9%chpSxgqp z7|c>k*6*vVy6B#!keOk;(H`2I$fw(I9TM-z>2|yeiB92Zm5v);tGTc~30>wwE49!{ zHIP+pR&`O}mT*#a!ofBXFs`Ir444+%X)%Iclt_E?3>7)`C|_nmw^{sd0--H|sT^G{ zIS`Zqf2S8%}U={X0^ynf&kE(GNjj(gmUpVB!1*W`Vl2Ghs5`N(2D+? zoH)%OI;>W)%la9l#c>Am{!9PDwm5%8U9df{=o;z@13X+-BlbfG(M?VR{-BCy_<&R{ z#Hz>QDZ(`M=&<3p%gj12r%e-H88cG-p$-=#F}Hv7@h$2{D7_{Gu^a@p35)OhF${r` zF~>F`5y|BLdB2cZylJ{St{Qit48Oa&sJh5}S8c=M!c&NYNz<`B7U@%r7~2xKHFX9y zOr5!1&v>hq#_CN?NXNl=-VO*;!?X_f;KUM+zt2XC-}`gQ@cVW?=l(<+WiVD_QSG~Y z6Jc8H>}L!)wj4V)7G5^loro62{){p$pHh-^On$7KTdLquTA@48_!6vum0~EG+=a6u?I&AtDxREfo-6B)(LFUI zPJ2iCf6i+?cf#92SqRJ$q9z`RX=50W}()4oI${1w2jOxn`qJDFXms8Yt6K{+RrD>Je|o?xp};@XEVm) z3;jyIyn8c?(h6LthYdO8W!d9AGp$WVdy8TC3;hg#te}L)xwGJDoPSPb!ddg&`e7?*i z!-9W}7LEQI9`ELOwHK>t5&35nxI8PxMW`MAL(w@;f-o348qW|CqO8-m4`5TRyRg z<9bvDSqzbc$7+uEyC5P>EZ9d6D>9q5)|u%@zKd_@u?fo zCM>51qAkV;Vd({=BLPx8e+Y4Tun2!&y>iniKCVp3hw-EB0jWSZ6P=H91Vv2x_z{Co zJV9u@Z{V7hG1EI!ngdeIAjd0?nOf*WNUWBviI~^8a2-8Ls%z0GzAh;Q`T;*92JfYJyOs18L3LT=H64;m@%;yjN(B&5GR; zur(O%9DjBB3cKM^WH_)4i4O_>*xBlqA+C8|F(oz&^G6!-CZT4eA?LNB7h&n3w05_K zqr`s~wDCs=aXoFL>MJ*^g3D?auh>C}e;-urAlVFvZ8ZgKSlo&2d zk54wqr&3HvTz(1}R816*>#$A>`|sy|yaySSI?O4>RzEV}JxUz~>1Mz1O8m1)i+zj% zxDmc`GZOQC!$ZkyQGxJr+b?-`L}_URvy`8Zg(+cW!jpJ~a5*76InAfwiyM&FrpkOO zjn_`h26Q$0k6I+R4dyOR$Vwa)y3hX(Je%Q}70MGw8S4K1EcG+|0;p|PP-EHq$FAXc zO)hD{A#6#UJb9^~@N(pQ(gJmoEh?6uRhpcp;(_HoHiGYz*}crgm0~O!-bM18C-bvl z0zMK36Guh-I*8JKabNdL<`=+HyDS(+Pjqw*D)<+gQKrkq@gZIfh7rPg4@i3gUwDvy z81nCfzj!V*|Eo806L3+XNI?33^=dY*{>wHP%f?8c0hj*xYaW zmfP0Y57>^|uiD=B%!2ow(H~R7@NEsGHE6}MWw@Cw&T{v)C=7u4uFOX6d(_mPC*h0I9 zq(RtK@>){tcRYbxQ9zjqc56c<4Ek+fSF@&=&?Y7BKD8ruWVEXIS|cTH^$|3~vV{S= zgzuAbaH$ZQoQ+=>rX`oeP4XemX8WBSw0wg7riX#nIN|N&Y@N>M^Bf|aNEzkOG|iPK zXc(BjOdo<{i%i@h!JE8z_6i^7XxO77px$yHZ1&MreEHq5>JQ<>eOac=_;p&`JA`3d zEwQKoX0GqLM+tE`tf!ygz$%96U%wx*Z$tPRf?9Z!8-<-h6E_wY9KXz+#<)P(t-mL- z-~i!L7;&_p5fdQ92|wzisfq!@w+LYdcHHcbQ7hqE$x4)(lzik&{MvZCQgq9BH>@Hc zg{ec~WeN6#2Bp|33l;;9pBA={8|x>Ru@L)hC=vodg5+rjAu}whQ_=en@&p(2W_7 zUlwMMF;LUS9{=N*FbX#7m(o@+So|U&+)XQRVDU_#Yk3-s>dMeRJe%bQG(B**#iAn~ zP1D&GJ7pUhl->#;JxN9KWM+q?lv8<4pRZ7sWbm&;?vRw|V|Z;dNe@bI1Sw;F25^l{ zG5n4{oUf{H+@(Ay&oM=}pO9y1wkRXo$+7it-~{Bw>y%28ZAws5!R*8U;xsMM;)sZU zxkebGm)`OSJJUJAm(Inap{_p!qzXT`G9WGS+g7p-0cnviK4UVTDO6?5#e+giM#AKM zgZuvwZ8wPFbhM4YcLw1*0AAbBaziG2=4lzI1{EXojRIM7IS}j_l!|33ysXE3y0}QAuBU`lCpG@ z8F3&CX+wz^l-JdQ)TCa{0I6r)u(h^R`PDj*J}_>Fqp39@z1#}&+Rn^*#V=~_tpBP( znXd1Elgo#_>1KBWHoU=y`Dkgf zV-0XBIVz)I%Hkd8WtMI04JXnL^h>X==*_3;wM6=XU1B3LI62rSHm&}P6PnsY_K9Mb z%;e=a7(|M0gVeC}O5m-KbBDY?v_s^kvSwg%I4qXKMyzen!Wl9sbqv8a46;;p6SV#! zv@U!R8&N>7zod+851nyAX7f5#VeJ=WW`Tk$1Pwx}h!tm{7cBP65HGmf7(9Nt>K4*V zbyL{}1@JP9Rbdx|uT3eGeMk^Z@iT9gPtLe4|BV zKpI9yc<10~wTQK842sg|3Po9D)mKW~j;HwCG&d-%KTY~EhttR`a!66CEYnm(R&Dt& zh!v-y4Iy&eXzfn{Lsdd^UQ0mwF3|5u=gH>(-C!R%-h?INqGGF?tQ#2qpUSE2^oILN z7URVWMl-p>kJ)33b4uwA3o+GWjn>+os)6=x3w~)N*xWXY+u+0jNeFNoj3rnP^p>~L z%<+b9iY7F-QhX9h{}do6JIp|f&=xz=F?wb@Ak5l_)_e{zNhhfM?fMNN+^CYfjdSqa z1%^HZ(s!M8?yNzn-DlVkRZ8g=V~*cFYq+MflGN01XooH+IDfEytC@5~y8RsT0@A!7 z7xXciY#>^e5H6sJ5I&m;e`1qjLvs0(xMv|S&(Ibm}r~Hp+w#=EaDbaSvqam&T)`JGPL7OQc9S<=2 z%JoZoRne7ehZ&+zK0*3OK=`k%a?^+^6%fUe=Fkl$;hpi5sly)&UE^a4weFl}I#qOg z4hau`Pkz zQp9E56hWcJqVPSd*qxw5lSvJu8IVHXT(yCz0nN|=vFszG%twd@M$R5CK zzI8nV$BRgFMzgrliSF!pYNg0ya=<+?NK%Z~h62)~gF68sD|^q-!rya8IuaBK;nqI$ zT*Jo7=c7eigu=ymV__)-q*DLnt`qX8>JxID=7gNUMfhGC+9{80V;e^{e(Vj47}F7P zn`IZsnIdXcPeSY&2yqY+?ir4oAs+lKDDn_%fUs}kaL@r9x1LuqA?;KKDX+tBF<=sv+qt#{t>{fHI9L5DX z+z$s|_8_C9uk0v>TE$0cerYcgZCERM#;mVaIqp1n6lFO2)*T&gI||yKHrYMg^yH5J zbHm>bo%1X{jmOh&UeqYZto_DAjW@WzX$(CrbWhUb&xG)MbdGFjJNszw^-D@eU)IrC z-AdZgmwwbSe)`=pM=RG8Jtk$G-p3u)m;U%XaP^>e9jdf;<7lF%O)ArGjW(+rtbH5T z7&baQozO<;(eJM7)|W%8%A@~;XZq-pZUk)xKEg2mfsa19u3tYJN~MoTkA04hhPxC$ z`kiKm`cayr@771Ut${{WX^1(w!O};q)^GgjIw<2;`#isIV}3CZkRSlrmcMZ9ihQiG zQ;sor%32QW2RT5GYYgTXvq8LBY3S=R82X-HLpF?WVl*a$QH-W6>yJ6=VDEpkMkcM==u1Kc{Y2Q@xWpKYrsG=PWyFf$g z0ABhn-%rYg?a!8teq13&sGGgYh&ewf`oyTlJ7_!-|5Vd>#|-gah@ImL-Jkb{#GGK))V{vn%IJqOb$(i#}(q8fA7VP54O zjSjVzi{{W|pJSUBzZQ`0`rhdYg_V8H_a|7{ls=Dtymur0BBY-So)FKi#k=2=muTSB z7)&(KeswL`99IGi*&1h+C0dYJRTGdd4g4kmzuKX~?HYTeZ86JDSl~fp`I)_{{B}!O zd3RCVLYd}Zvht{I+QDi?9FYv_gDIt>V8bqvDbtGe7Fa?eZ8Ju@+vQx{qSLQKCrhET z7a%6-XpzARcR>29Zw2sLs^}GKwIUTkyC_3ODQQ6~vJs)K6~XuBjFg*fU=I$m27R#f zkF3gzReyDBJhOR+0k-4!Wzr~DLf&~FtV+@ioDROPJj3+wawl@gA0jGxP{<`1P{^G( zo}JLVM^>1~pteHX>LIHc>Cy^tT|lalNg3Wn@I$m&1R@~a=|AGRtU~R>IJtJ6B`mH3 zc7L+#lM?`GoTv{@fh+QtHK0CJUy;x5JLI(~aD9jB$@Uec<=rI-=VVPDoUV4PUo3}I zQ$F?W2^MOHwiONoI@vr5D4Z7ZTvYudzAd*Cbz{0|<-=vzPt69qg&iAg*=2GF;1^}w zAH?u1qa!?soJIcEVTb%3t>OPhYsUK5fT^5Oyt212>hOACTD5?Y5i5IX8jIC9zk5U^ zu&>&TwTIWL*93F&lq1^d`m$!Kp5&83<$*yf7gR1uCciTX zg6oNzko6|Ai&-qZ=w5hz81?6a!wdEQkB2n)=l;)xl~dvzf9^k&5RhK%pS-2E;60gj z{^dGXI%hp4ij)R6nPVRf^QXj!iHwJ?$IWDQ3U4fs_jCQP_s5!$k?m}f6HLa273;B{ zFhDETzJ7hhdP*;Q4ls^8=RXWBg{^L~p)UaEw~8j54s3Um$|>RATEZu7-Bobc8F^su7&sz#D^gM65=mI%ln)*U|E2XiGh#{ArXQ$Eg*G+-LOMm z;aI;6CV9nLA}RbnM)H!cmdZ`%syUL%QYZ%4s9->c$x>+EX*R?5-@ME4e38yOFf13VSXwmF=xrL zxaAJUyG{Y8x4A&nFi%upXv7mX$q$*Ai4I1Uu}LmAKe29QFNTr>a%uHdH!>uSHK$%` zY?D(e+GJB?qRA<9I;R|_Q~BvAoU=oomaj6B8XFiq6ne>6BB{?9rWs`q4_#YPh*98A#g8y3BuOeikS^~NNIL(3pn2Tc; zj4M4W=Po!4r&Si%i4zxS?OYB@I{}+N>^+=S=EAJ9<{_)BO%yDmI~6RB0WPH^(as60 zrYAT?mBkeAsUVcL$hNR5zEmeV@^yXdF@$`b7{DP`q+3)GTe_#BM!&~4B>gx90(SpX z9Kq#)wEAOW<_{{p)aC(oP&hh9Q$|ccHWktzdWO zh#rg)r}$A?7+9$oagh(D!OU~FL76@z({^O+{Xz0@e7A?_sVLAzg*G#yAbgrXN<~G% z5fOX%_?7%*oHrSGw23a2ca$Pkj8Gi4jPD@otE@oN9cRRZb7UL%LqOSsG@Gji8ua!9 z_75!S=YO&bHX+YCX6D2|rJW7h{|jVhDyf(Px*@qG6@(lUp9#-10v~ HlP{NFv% zP2>=NJ3w>toaqMB4=>eTiQ8kE;CQ#>J5LOkY<1d8z z!YO4R%TK@y{91LwqJq5|iRa~8RaI5X;>l=@kH29V=|{{%0L_-9$cU$yVDM1lOnDoxPJ9|Lrf>QX>T6rL$E;B~^AMWZZxp=AY(ome2` z7CgnUQPYBTs45^0d_u+*&g-fOHckv;6YaWc$2nJRL?80gAZ=%iqD%G&a#5ONWietO zgJ774SW8l*jHggCo{o(DV1TE2P1BBskOCIe&)8H4N@t|!`1opdmqx}jXc?CwP|}&> zaUKu|4|!9N(eJ+Nq4{_o=R~eU={~n6zPd=$L=`Z6SyG*abw$fK8Ob;SrAzLp_yLvl z3Yg9`EyARd`yA{+#I{vc7bQ2r0(zeo7Xx~Zv{JhWF9@XLCz55zOrzb}95N&1{?PI( za;EbHj0zi!HX?t`lbI=}EqBga3wzJ)D)M^TBEVD*-c2MR*d$1-YJzP*AIe7pYG|4M zz1{Lxk0~5H8gp5;)d?Wp6TTOT|JroQn;OBoa1JFH?Lj;Bq;L3LMX5guGTyrLG1Ya-YlxWc`oL?VI~&!;@{TUW{jHRr%_|U{ z4CPndqv|^4&5AGroWm5+<1P>}L)8P84pRad#6R30cnd*xTHO)iuhvWCY@A)t=PdZD5$QK|6^Im5ATmscr$A(xcKFvY=R7CwAV>50 zQ{HDIGN8k?5o6*1@d%werO&zSprf&%k6YH}IpxiWh;Vl)76Lk{c0>2ob)Z`@zSl}d zoXkIBDG+O!4*_ai#3g`2-iJ3qw`&hV&Jz)8_W?z5D-3g4ut{hUt^G5U*rCMs?-I23 zAe1OM7RyY1 zGvI}7-OUp$6!S5y`M?AOvccD6z{&6W@s#(`2uI(Bqai%BR}i67dsXU)boNlXs0vMM zjnJLGMTH_U$N#3B0%mVDg)=O!{VMB)7>CG2gaJ~Kx?JSc(PCJH)kV6BX=Mzw;j|^} zl1}wr53N#PI0;@p9B^Q}icWelE4%M2Kw}9c<1*SyfHlRFb`_E48JMnBrO_ZotSSp@ zt>bs`@Aj~2bq}l5!V;)zp30+4vv_jjeFYbJs@`$-dbyaT{>)P@8r7|yum*1OSB*wH z>E>t8na0a9w-*bxGQ20zlHiW!+4q^8&;qFUZXJJ95QSK1b)(s91){jtQS+!1*a`1S_AQD zY>cRmNOVu(L20qOIO)?y{Mr|AQqtZ)UMCC^u^pbDl*O$$=embrgAwYA81PKXfV1r` z;3S#<-*I99-EcF{bg8|8$)+IwjCKM;pv!p&4PJ(GF2Ts2`O=H%4|>!T10IM3nAyF@ za!)IJxLh=`=e2^YaIQ(*Qb@z1OuTdr+8Z$_nUI6X`+$qP(msN zBoYl!Ou3lN;z>q3ksfvx<$Fl1*s-gK)K=_KIo!t+NfU}4q~TpfiamG&{njV&rrGRO z5Bm;mA`lo7w*>;wfhLX5PETqj9T>ok?q!HcJwRoI(LU`mH3@Wk>fu3sS!lHDF2(er zN63W6v=-`?>vk29X<|CFgG0QibY!)E?L{G3y5TuD=}vjo5ve~6KQS=w5U&aE_uxH* zz)A~iTh-n?iikTqTTQyh3qVxsuWgNzqZ4-(ec|Z>4IQ5JHxKEa0&@J+W7M7V;Oq~) zAt7Hix;@{(n!#+ims7)vn)0&Dne+}-L_5$XGovuv%@-WMj;H@l4y$-s1k=Y=Qm~y=MXYllzr(Gpbd!Y#i%$Iwe^F*Mi$T1A zJz*hAPZu?6LuWiF50nnqX^ZprS*Jgq?qOJee~&9`K{*OwrmKIsL|ZG!$aPA^#AFdMWyVs%R)E@R??Rm z)fq({YGYx?l^e8pe`*2zVhai;Irb^kUMBP+c=_OVr2EMO`&-2omtHZi)!EqAc*m0> zj$}d%$-d1&bSZ+^q6oIAOc#6PaSv6Wu%$jzO(E*^TIzlYNXB|-T&#d7qPXTZ782GRG2jPFd zC%(^Fj@`gDcTqW=jgNTpZ!4+zZYpAW-=d?vKpSKyAp4)XM+qk$9LJr%?R5>BYfvqmI)-!;ffNvvl1s7}6ElKXw&;>#0l{@j)6t$G7SB z53s97fvmEt=&RocJat#meHA~O_=upFNY+i+8r_GUN#vD$1fSSyfP;yw) zK5cs53Y^;0{pySp{FES+`Ulg5gM|ti8`t!(^ete_L44Unb~o(0XM)%B;Dmp9gmrVc z$0FUj?jKhxOeP&Uqy5sY0hD?=4(Uz&qE%B@O|uRAIGp&^9P0g5p9|(+Ca3$4p0|H7L*Czlun)JJOISlhD(2q)WvZZ_JK13>qkH~F3%{V} zOuwo^-~J`zxf8#B5rkzr8-HbJHdiH4y5A$a%?FFJ#Zt z%}fO~u6PM7H(=BR7ncG}(^g9~PrDM=;Rz^Hc5CA`Eo8c!Fi|6U3ph$)8MuL5wSl&A z!6|5z3rzJYX#1oY=4rQ|LxWT2LGuS{D4qAZK_Y;XBXB}lEUC;LC ztiwiyo7hcTZd8M;bMiFN-h2)WwWcX@h5@9B(XOTTh_XGFxQh{G^>*5eD(O2YXOAWF z93zJIGvfDhz#%;qV8kC~Mtlc^F-D9BR-XtgjCiJ514d(t4FoWI4DKLknvfxM#yr`; z=^MyDzPEt<=P<@Tx3Vl@T~6}>yP=ul7;$I+1j7Lv)NXaffO`iFh$`!_U9zK$0gzZo z9#P~UDSP!8N_D7s(C2R)T}{8nNC;gN-i zJ^J8(LJfI#Kt}Q+#C{J!u^6$15Wax$7=%AV$bJa1)Bm@M|J}&{D}5C@reKf?m|AeB z-bmLIl@cvfbd~o#TOE)bSBDfyZMWqb0@Mq_6u5ZR*prwvbopy@3LOy{gBaaX zP!R@(NOg+7;$d`;6yFX0_rm{@V$qYB3f$d9z>m!6ly%BO0qMq2W>%m3XAe##ZGRqY z`)mzePlMix24?+}8f++ch$xie0J$bcd>5!7TwVZFkR*e8;dC$`G2%fPrp9!@qU!+e zFU3lB9dNCs1(+7|)Y9m6(aqCg{-dk&Z%5ITPI(B8{ZQ6|cz$STtOupGc^2^Le5e

      m2{o1k-{;|)lxAJfR-0sxx21}-BDLU%CDu*w#L_c71j*pl6%~+7 zLqH{<`Dwdtt$}zq-h*M4VaJ4jcsgaIA&P)gpmqVD(EzX!#yX2xq+om<9)i5IU}s}% zQ0jQz+(njH-n$^H!m2nyZs$Pw7O48$Xq56h#iOjr?p2BRxRif-xun$oS@U)tqydf= z@rcFjCvf1XT${uvt(*FUj71TS2{VAd17nZF;|A>MiIk2fJZEMyIvZ!p2GgeQQDghu z%tSH^hb`ZBzyu#s{y8A^4U*T?&=;-~FWQF!%DOWiWKbMZ2;jT}9(N#*ImzhHLK-d> zITgETackWL4|8-w5<2EmU2_(qjkJmh477TAcbbiC0MlP`IxQ zR(Jv`tZ;GqX(gjlm4}9;Q$tYUkm7Yv>yruq|8x)@t$FY|**Nb5__>{*HzsAx>L5d! z0ncTw@;+BJExLy`fp+j5q`n=>D621=?oKb;Wtr-}A|E_PAPT!3p`qXtF8+0BxI**L zg2L&2bsqsaM-y@$Cg$mbpZq+$WRnKPhBb-dZbI(LLzHf~eEi@tF36db2c(x;$SO;q z6O3wiHjm()w}4+UEp8ur(Q?&w4j7}Tod2{OgXjfR^dVP&X6OHQ;2p);*Itv$m=iA&)$R&=J>I6F~+ z4M~Pmc`YnxVXpy&PK9>6AYK>T&zTvV9g8Ue;oL)n(1C6p*(V5Q)Ins;1VLf*B&XF5)czrsdh zCE^XRD|AwHXVlCp-Uvfq;iKw7PskhkPJ(U0L{q|$)H?V$==IV-cUa*w@hot8)iC@+ z&E-O#}HKIYP)Fh`jD`G2^YTD|D&hOj#9LMhx5YwOYXr~_;E?Jnm>hF=RwOQ z!r+p6xO}nuk#c;GaPtu>UMytUKE)@5f7xc^Z9;xU89pq$Tu~8zupbUkkcQl08PUooH{Rd{k~93CgUv@{3D2&b1$OmP6x@46MBHJSzGN8oxz zd}q%(8uabkj+305{Wm?}94cf~ewnbYe;>R%QAES(S%kbCOYTpYgYAYdn=qmrWqmKB zy39)?t4x@=ERK?8!Mm5kS-6}ZyG>46T}Sz1`yE8`#M)sC7|BR$KvSL zwL;1AWZWWD!T*QHw=7psjt>F{))^a+0UAdK;D*osz_4Rlbqi6#B3--*i&vp(QjW!c z1~8;JNL>u3G9h&#z<84o))C$Wi{G_YH*Ery{zFxaR}1P_ELH{#zz!)df|9kGJg)-( zNMMI_2Uc*rP6)Tp9cQhIhLe|ag%rGI0R{?q)lHxTVJ?TRqm8sH9s74d}v{T4`Tt`I=3dJiMS`b^{A$!9gj} zFD$CoQ}+%D8>-Dz+>p>#oyQDH@A!m)>N@H^@St6#)dE9ZzS$nmJ9*vmGP_y#hRqJ` zUIpM)nRvbM%c_~wJ43?M)oE1Sknrg0G1S}OTE2Qh(w!>AUS0!C%~OcI2aq4jv!DvD z;*kM~R|kZDt{w+`b@-Z^hZ+a|8f1zeA3E*{fc>t=+bAx`W z`kd!uPy`DCY#fulGnFXi?)cgf4RJ*!^w=+Y;;RpW9)I(VhPd3# zcz1?ekay0?Y6c~XTnlzw!0Jnn+l^Z^_EB531t{8r4?Afd2z=@JtL56o z>o03$str%5STU&)%gVO6Mx68G3-yhpnQg&NzVjHjBo&OSfx*E*kGTvyRr;l_7}jU% z!26zyKu>wFjvuNr-&W`B2EUS9&Zr;Ew^hOPA!oxK3*7Pho0B-H@3z>+xf<@&I2O59 zidx0C}!E_Kl9cR)*nMM@DBxBpR;x)SatBGKc#04`tAwiEJFli=JbFEa_N zM7Vs4#7pqB07`BGd2f~%f(bLv9FSIgEFAp91N2dUlQ8%P9bEQEUKyw12H?V(f#VO# zi-4c?4hh98$5D7dShvz842_K!4nCpLEFSvZx6Ua)tO1iv(i0ifqkf_EiKNU2g8p8{ zpn%4i_y)U#wo3e)<;Amp0?)@pFa>S4vsJ>lmqrR*D`Hq<@IDe65(ZYpJ8le$ z;H^jQ%8^S5a0?;?3&=3+V!Rb5nz$Idc0^97XTjVPRRPUR~q+kkMM0Dh-%zfNV!n`aZ7wh#rFN%)s0b&uUQ!P{uOXx z)4}g}ysl`N64uB>)3yZ~`CIdwGGijQP=^&E?{44!_@u@i4_oH#-+rQhj15nSYW$OB z|7Pk3&_L4%HskESc^L0@G$5S^+MUlWgkuZeyBShge^^%9zL7Q6+hm5^`s1Ri>WWa> zo38IX`3-F=qAc4tZI5b9XxwALF5v!JVP|f8GKCqC90B3RlZlQ8TdP~Di-ai5P z3Qk1DA*Ab<9`Top6w4UOMH)OqvD$ij0r#D(aVmxHZnE!xcQa(`fb_{A!{;@_4K;if4El@wpo6#`r{iBDB|Y?dD} zu?CIK4%D>FRNgmo4N%qI$`_eCTOnnutE{x#?W)`?({)!jGj|rRIj}Uc?Ci}Exy&8& z+)eVVjc4Q;;8!}&GKCK-#p2un!WRumrGeqAZ75|xS~~cV=b-`)JSxil3jPqV0SAFO z`51z*^N(7GX}}H|lEdIC9s~ems82dNkOogv2g!A`od8(f6vi`YMp!6FOiZIw#-P}l zX>hoY?nj`%jpKiP2N(jvlz~Og91i<#};IU!}aZc6>o2NXPpz=F?0h(aw@8B#?ub0d()!0 zlm~C68dxcgL?K-dLdk%H1_bjniSzHa$Z(pyuntdCowL~oq?@qxh;xEZs%Sons>f8? zI~JM>H1{Df$v4ug0ec3?8IaojKf?l(%P-4mdu#bo{Akb=!X>uB8u))tXm}+_`C8Q_q=*giA;qBOHI$fHQ>epG{^n;ZhS=+J}UpXVc(r z*4XFL9sSbFV9rM3%|S9t6Z)@#J_>wE18~_E*wO*%nSo)pl$cnNxCji^!0C%W3@P|Z zFfcQ2!xpf#<``=7;3_XDc|fvJT^f*<3?Ms`cE`0nt=DC?pftEoX;^ME)bx02f$bo= zsMA9s#q<_D+872dGcs`awUqQgLwqb1(2uNL&DPhEn{}C&Cvs&%v!n>qY}+gvT}(85;w3TX^x`Zc+*) z{uQ=a`k2@f#`&fD12jLY0oTEuP}?EE;o?S}V+$Vx2Em6rqkvxDg=-nqIPGQp zKG8t7k(;Mrx!Ywo!w!NKggKn%LI$|)Ynt3u0uXx!H4Q7pFa=!m9QU4m(&ZV@PZ+pu ze0f~u%>;fQiSP6)lITkuj9wi2r{{ZFn@t~2w9NwFb!|RSKtJrh1JXS{xYSCMtI3br zDk}_256T5~XKyMEVTR4%Q$f0oaiLV`)(lb>;YMHjLXOG*!80R;@hjJwa<9Nlu!^Jb zAF4RwDFpv~vFU|lWTPAnm#+iTc|VgB)k%MVcjv*NCk!x2>Q18OxwJ(uI>`4!;G-os zndO%N>s_#<6o4^uHx*ncpd!eb@E$8b$O}krD9wX11~3V_pCEn?Y{5APpynBW8k8w` zKU|a}b$3JE5U2|(SLkqG>*IC-AO(Q@DA)>-3chRzP|^#+s?E`(-wdv0jTwmrC-Ia7 zFpnOn5ib)_02BwpzRiXt-N0Ups`K(q%2H{c(=gYD3}+3OL@(a@=-y6gRP_4qXI3?Ut?T5RmTVBY1>_`9^z@PVN@T5<@6TFcuHbu`wT=WcT zOop8vYp^FY8*G&}u_emh*dWN7w#fC{3+0Qm?VxLKJ9881CO2blu5IMgMqBdJ@q8s{ z*+Xq}ZAnkdp1JnGKT#{W>UL7ly=VoYV)=^>{F3nVixcsFA>pOUu=~MF9j>Y@>z6_U z!q%74Mm{j~pN*j!&=$ta(n&w@7!>~bQVebsdS4o=dj&3!GQhG`@h^jd^kvYi!6iNp z3;j|y%!(|%B21~x!M_SCYbS!<`JLJar&)oHe`(y?Ksmz7$R$C)L=6Qm#DELq1i;1j z@{ildy=xj10bG{0wUE-4B89434hfUD%yks`lS^>!A8aG+pUYv+q~!uGIBAq_G3VFn~PYPWd4X zG9;%TSQgol2X7oR=xl&I8_N3Jb@fT3&G3g6wlm&M5_RCz&4RT-)5L;SwJQbbRV9@b5#0U?S(@0dGDL9ch6=LqB1IAI4J!RwmIl}NeVFTH#^s@V_s zAhcbScNA?9BSIGyqT7wmeO^}Km;Ua1KxW_grZB97IkyP3#%935yK*kXe(+Zh9_X(= zATx=I9(9OL#F${QD*lqH*gm5bjh!#6tIw!Zpy`;`%GyB*Rj}Amxa#~#%VEf3&+W3z zId`B3h0=UZ^I|@iH*~#i@t^BVIL*6Z-`HsjYxvs!lWmvfogP|Yz8GRZ7hhHoVl&#p z?8M>c2^(~Vh!>sK`Zc7;kPi41UY1$RpKl21QK3sWsi@a%kzkz&zn8NB*Djov`e1z3*kIY@i@XdT?kPaoh+!0(MVz z4^6EA=TuB**jA7MfHw?=FIB(*OrLtJpen<3ywzg6_@z6r7ugyxxcRY%kSK%0VLHzq@=Mc%*Iq57X8MGGzM4qg2l|ay=TI>|VOHHN z+#~F(`w(vy%3mu~Pks&V8AC7#Z@!kGcqW)?dF{!_7vbX+K4~``s+tD8+Yh%~r|fth zw$|ny>8fW>vQ2)eQn13gdC6FkhJc zkb*2xIAbQ9oB|%e|KnN=|KGas2j<&hvpH}^fe&JIw)BUYa-83iGZlU18FAw2Ce?@d z{rNJp0=+&2w{4juWhdNzxw*gzsHYwnPGoZf)-|H(r!iGuG zBDe^h^#WN(WRv$xi-qTR-ZTD6^M_tG?8%$V-%+}{6B*+>k@%#1S!TN6m@^O;O|yl# zW*}n%l-Pu;J9VSW|Eqksw7O`HrLxBgz8d+0?)CKeo&RZ79P?k$AXnL6FLu1bBjZf> zR?AMl>SCjB0S z-aw9149To{55QG5%L=GGbGOobEdh-g-EhH-44>ab)@;~A#Fw^N)E7|}IQ|J={3+Sd z@7x?;0o`HlEgofcxd86|%O0vZ@J}*)lwlTkIQR90VHj``40Q;P;lh9?=vDcnBhB47 ze}tbFYb`7c8Dru!MV+e!qtiD|E3by(0;H(&Ya$D}alr^b8hW>oKn91KO`UtU5IJt2 zcC!4zo)L_>n>N4U`J0zh9XIQJs(~5ZbQtGT^u-?GEPO;Wm3#fR(dB{t#6$QhC=@-?*gULt!5ks%QU>s!JfV|u% z&b?Cj_(dwOqQKnEn)mvto%?!5;C+@a`FHsT&d+r{+;AMuxC+R_K9!`0fq2cyR>0OO zG-epDFv)a>nM|?HNB6#F#@63)c6=BMlS0F+-AXHTefKR3cj7Y;x@be}i=+*_6` z=)SU`K4A;YvUFGFADII*k+1ZR=-u`kf`KOTMxNVdiMdGKS5fd)Jl~D@JkL1d;^k5D zSFdY%`FdI5`{$Z_D0W#-*a)0=z{7+0HOKFS4bJUx@y~gvDHR11JSJZ4Aw=S^ctEAv zN;I~bCN-y?AxrxPU{|V4;J_g`SC;k+Byh6yXW*^K^I7;t8gPNb9}a6`IJjihuY?N= z&sKNZ7g&+_az7GV;FBTXpDrF~hR?wKE=xiFfqn$=weUY&{xrCjM>ych82RoU`Lf^e zckkxFvSA?t(aS>=gN$mjiBugo8_W+RoPUJ}`;{9;`_tjD&wycj!QY zN6u;_W}QOfNN}XS>xQ@YLUVTjR($pJCY8edpXV=5llmkCZedVo6U-tFddN^FHpSZ+ zUSIZEZ>TaVEV*`p{S(XRXN|76^R|3qQMfS|ma6choCWsL&*tBz={*+CWx0(ZPJ);` zC%W>3&ur_W)TK$Ge1R}(Pa$YD1GCVbS2Zpf6cnV>Je)>%ARR6Swi8?`5<(d?oQH#X zHUE{zHidL30Pe{FC!EOyW8nJ;&nr)}Eu^07CYrFRm#x(l4Z(5RrH9vo+bp%ya%Nil zs^N}L?X(GwvI+40I%ghz#}Q56*)X@B5^SEoP6Kf+ z5qd$a9USyahX-Y_BG%^OF`s&n87)9v!dvx8j-_zItcAe9RfPpsLLi*zFfXVeGuZ*O zOeHDG6vbh!tPaBmY8Wcc#^~-!&$f^;mR8Zd|RO3Oogv?q`#Sb&-WlrGC{fW-N2A^9WF-XwX77Q7$3-;AX|drc>#Q) zlyeU!jEr#hffJd-+l)!e|PB=Wo|hv zi-PZGM#IM|!lscA3J!s?i$Oj`nmzzHywf7A+nWg%qj&ah%Z@3{YvSNy@NB!nzS|P- zazDNed=juBEv2n@BMQ+memVvFX?mxH_EI!>sR$MOMq-1oZr{l{@5h0|2zbJinEowR zVuW6XXB9k?n1$yp5QqF$u7+m`@yWFU6F5gb||jwR`I#J-;f z_pl)hLa2v4HRMG?DETeCmW5b64zZIVG(aeUFdqUmi}IoDbrU$r!1HSm@^cWo0-odG z&i4E#mp_TXeof%WZvsNc6Ap$`+F1*7Ei?X@JuZ9VIMZVjCT35Zn7uS-c`g#t-c8At zmLS#-VYm+Liod0oSHOtv@b)%v(Wx9R|8zNwN_hU=QKk7$Al9)0vD5wl_AH1WejKqg z|JQ){dnV97K$;tf+ktaktc4Jr#=uDjkPW#|S`#P-;`3)szPHTG@OA|Q2MB|NPD5$c zVtv(OpntA50rxUB0v8Q6K;*Xr*^?)`E{|rt@b-T_EE|tu?`= zMeTwf+l$cNx^%I25m5RQErr&ux9z=&OD}?6X>E;yZBGQvAp!D#C)oSD-~V~O=lSwH zlbLg7d*_{ZX5MYi$1du97uDEBVUy5J8SHUoNE>Gr%-XZD*0{2`(p~11vq+=|kvPSN z#D#Wy>fh(U4ai{X7aZkf z6{XPWKvkt)RMHlah0ep^xu?=1n&_}U(gTjlFdG4`3d)$EjPRedU^7_@%F<`nuP~Lx zSDMP|E2H-6>pvaS{JyjeUv-yUy^=l9^D^YOe2{&QfI`_Rz&e26Wg92%Qyg@OYn zbFdsUbUv>%l&^(27h1mJRiEqJlDuG)3xCVm_tL^tsYY zGfK!HObaXnXhE3WHl7q5=rIEx=97YuzJn7A8i4nrV?JdIh4-c?^8ktpwZZ!VQ!Yiy ziYBN-HC7eJ^SkNUwNEq)EGx8sbC<=@4`#6Dp@@MGA#+4cm^wOQ=Qa z5<9hsfy4k5$YRhUq(SplkiHkfA_x@_*p?J4)*=l-7>2PVmPJBPK^Vt}ni5ORq6*$7 zz*_>m1IDg?7>Q3y0dGVgHi$NAJ9w7yO zkbg8=Zbg6vXo-h8&WrxfN+E4j0QJZGih8ECgw74;418E?B9~#qwMgujGI(5v#C+i^ zg;qmqAH4O$<9g9#`Am90hqP4%I3#UMhBgG2J#J63mWu&nQmLvXfu~`OEJ>t2`TFH~ z4X6N?-!8M?6=#hrRnHk`D;FI(T&#tGJ9AU39M~4k;Ffvo^S@G zz8Heo#So%f9D00YHOFuP?>u35NVKpiBnHodRFWdZn!rO4UQCUP{6I^Wz^DhappA40 zFC4oN@(^`z2Q=Y?z_ws8wB+>v{v@C~3)k#Kt zsqL;gSbx{t7j%rLN^Ypy+Jdwijuxe1A#se_K4WA`sfN4TMvMLaJS%>e=ko4Jv{8CP z6&B-sm#!mBi?;?DeV#3k$A+RyM&5yFG1Ql7Rl^&`rYSjKM`Eb|5T9Jq%|8SHJTjC3 zBk1?V!+#>Ym+9gkN4gYiyp4udk=P;0#h8&qYgiK!C)@oAkWh%(L-D~ETLM@-GKj?* zzfAl|V)P*;q)MV+7OXm5k_Y3X5*DWn4Y~99rKs7B+SP#Q;}G6FfY`Kf#Ht|uIfU;Z zG(zZr@IHiD(TJV49kJIF$b_KOfH!4DKxQo;$X~Hii}o@A@dZi4QH^9;KdncsD9npU zk8mmhgIno=S@lK8v_po)$qSM0hDRHe{+6mjt{&jD!hk%C-2E@QN}8 z|01*~Gn5@tIwx#B^jc-3#>o|kG&w0ObKCC)vS#Zi;&u~qJ1stAS0Z*^^?=8F_tc_B~k6S1K zE0FGV(&AfwYE&j=0Sm<=G6_=p%@E?ZG zxb+7SD>#zWG!_>L-Y84VnIUYfG5_wu8p(}e-f3W5gnObBmGu%?45}8jmI3nW7dA#G zW!xNLxLR0&$NaKnrVEHdyfBi^RkbmmRCL@X7ial397?0bPN6+|_LwAiqQ!HBc*Mg( zSWF80(#dPkCM<;981tA)STq6e`vH>um{1*)gw4VmF$FkB_%SA9Z20h_j}j_G!#`UX z6TLUJHQT$pDz}T5%-Uu)~8ZMRhxGC|F@YdK2yi)k**c|+UfMesZ zB#etqnpF{~Xk|S2%F>~qvOs<-?Dx5!Uysz}w;}Q55FA_L{|t%l{1%2o9#yc^v_N{R zdNP44S6CmbWlsihx`Ny65-N7ars?gso8^WmSH=d$Q-Yw|fUU{EYq%?`*6{j=k^az1 z;NpaT#m)=)*NCR|-V#bYE9Ar(@aw_@ar(UXMxFywM(O8WDh(z6HiXg-IkBEz|Ghil zJ?+ofupgHDS-%{XNtV;ZmmEXlzlCFQmY9kW9ndhe90=AQAMn2J7hYN(D`?cQ_=GS` zJ(v1EPIyk8g|7+6)U)t6f=4}e+_hm@J!$KP^T%DXJp}`3-H%%fU|1guDdQHDzcwsu z=)QCCb_^S#b*+EDyQ(;FLuOUAB=Q08S3c5b)L`2+l_}tLo+K2(woq2ANr2o}2S=YB zyv9h0slun@CgCi>Gj2BS7INY|J^_CsY>(GQ3&VIaJ0&cu z*M&4PvJ$su39a!-_#@$8@zcgk1=2S*VI9&^;shZfA;qXVm1;!dx|2w+XrVY0DPfYK395T0tk-a=V2LCDDWUWU_aw#QeZs1w>B~3y z2^U394Rt6=&Au*{kLB(wOG)3}ct%2v3fNz}C3Zh^VXZh81+nyULF;s`0%oLDVz^bU zv8RycrW+XsTw!p^dYl38ufr()SJzedbZ!wWt&75N(iHpUVHvl*6=gY{8ZOkM!a&rp zE(6|ufv?<1H(K)h;a}Z1T7U14+~v?A{qOy%t&e}S1z_9Suc{dj6g&xL zwI|f)JQ`3m|Y9MuWOp|`oduG}-;{9Ein-VwX17A<8s)Ud*CB7r9 zOGz42=Oc)RH4cDY6dF?Us6{@(Io5~|2v}1(uF!`xHrpQrqvjI$>u%ui#fd_tCPzET z=W{m#%OJB-c2&y)DObe+Xfu3BuYZcnWuwrdSvuxvAJ))~#x^C?dqPOk#${g{!LVnR znicS7h3~3c4)KGqzJ7u;qy*-F8|=*QKsW;-Qdq8y!!^Q2?F2mM*a7V+jOPds=%DMo~;X%iVZDhCBVZ7KunQW6fPO{J>sLRZ>;$e2DT zY#u)qhSM^BLdZGYI8I|5@m>~w89xbsC5)Y*r#6m1He*6KB@1Cf!Uu%nj5Sb6D+wQE z6fU8}B&larIzW19^%d=O@3QT2AqQRnVKS1OANQ?&u3RRG}p=Bl;#_w&mWg6 zR6FF#^W^B-8#oT{;^lJk)|eotf^QcDkVe%OEk-DRcSh)=SKJUgoC=*Dk0n0slRWi#Qz zy5;zM!25Z7!243WuqgZ9lIPVUo4#q1XXrZNZ1Z7Hj>*-8)86O8eX{;>=D%?&=lI?T z`OnQGPmqO}s9$5zHQDmig<@L{cim0j+Or;*ktvF7VIZ5ctND)pF+@6PXQ6L;)AIfT zntp=FE3i{IklvyDKQ}A|aGlee^dbc~J{>&XNLdR!--fX>&<5LL5;aI}m6xe)f0%Q<5$m!qwSFwe`VyOL(g841Dq9Ju??sG!=1`w zW1?*Uu&W|e0)fCFwM48|aN*p8tznxd3F~sF-`~_$x%q?mwf)aUqwLDRgkHK*^PX98 zG1is0v0Fi(uiQ*@PnCbsZdO~%@R>z@iF=xx`wl7DuCZlUui|%^Xn_73cM|ujJ8wrO zmjg`KxWa(n>w_s*RFCPI z-$kPEK`Pc%)gl8Bh44wKNg2a^?khD>_bf?{EYxjo^7nh@W2>chv8DG@OSmw1l2H*{ zII1w=?z|=3@Q9J?2d3@iKrd`aN(6jlJ3>1G4CrA%$MiVSLq#cu&J%2t*~o9PY=*N- zKI1&Sd2;DeymV0#lY5>_u+U*t6=sytn-^oM&l0WX9Z+r8B0{jcDl|b#at;Icw;6+c zvc;tDr9g4FR(uT3-hj974v&R^oh6Og1KxK6)aK~YP|bY2V3B?Rf$pK!vY=wvo8Z%L zjwqwFOL17qzKVml3LYm45l3aTO}ClmDLBlrZfCH0+VgNUUdwg! zb;Tq4?DEUf=MFR;goDs>F)`%I6Z$7Z{BrxPd=3P_{RG_*AH-8ZB{wYdY@lVgUVBpE z`5fsBNnTnZ>(Q`FHY85diF2qWRROPmXw62&M7=nNUbC(XbVx+%K-!p+cw4!Mqn6mh z^wFRe1MSgW^QD-(^aCT6W{6EX{mxNsEko^TDx54vXX`_+6*#xq{fOj{@25(9a8mXWLLoTMs@x&Y_HF1m+ zO+4#D87|j%{V4joepC2?r{?rp!na9D9b+4&j4(G< z8rZs&K~7vZvfYg)+6VHFVyH9aD9x?tXQK5_{L$|0fya-cOnd3T+M}b5M?vFvyGEOy z5d<(oUf#PE{dd#pBQE#Dr|=}&WfE0L^TglX)TC5bq!>_YUBaW&bhtx!d79Ra74};b zj{f`VO}TwQe{?}_1Z^KkIclFY`*z~d%1uNeN*QJk#2(edp-PC<(i zgPI0|#&^ql{g%z{erSO@+Im&HsT|rI{!oNx--nApQ(_;u{UOe@5A=U{-c?5TGAPkR^&&7Pfd0#oMn{}~-uir55+B8nHD!mJ#CIJaylS_V zC4?h`-6S?RDrx2U%~t!JA|EuPY?ByLO$u!)YiI^TiujWQWvRM0mSOG2xzT(&H@b^Z zVz2KSuW6$A`Kv>lGPv4ett|BXy3((MJ4?c9x~UFSs*eGm|AX%*`LgqCtVz5~RI(>L za^=E{vH>yrnEe)-gv2MRkKHms{4B(dNhPi?`a{Q}>_X>**2M90KRb0F_k%Qf9hzhk z%c@_M?mBQ15N{Gq)jvpC>z;v05@{6xnO|+nHgF105<1*&(x>>g`jN00mVTojHC&4i zc)#|)3X7c5Jpvo$bC7yw(>s#=!A7!yKl21>L}Q>_`B34*;Y2;{XY1;q5ZP60Aimq0 zXhvdDb-+7e7=dI%v}c_Pd|t&z+Lp4KTril7zbth)E=!&JVJB_;T`}!^c`r9^vBXw^ zO3;{Mk`xK&u|8G|pi+r7Hb{|1gNwF9w>E>)H32raABP&CqiB)A3KwkMK2l^k0JjU` zRt0sQ(vyla6k+E{&L031LHE94HkkJqEB9der>;2nDB)glk%6E_vfKjRrlD^4Wd%Av z3UG`&2Dm&sFhQo!p+<@9pyZ$i(RI}{e~a-xQZd^JOf+VQ=#{2^mAfcWq$)Ba00*mm_ge*Nqb3S)B8O+0Z-I3Q@V|DvCH$ofqeL2*fm%80f7G$=r;kf}F9^&Pw$_eA{@GXQ%m>CWhv zE6$rsP+u6Zr!#yiy`8+w2lf&-SX)uU%n|}!zLgY6wgtQyK1ZEP+^Be#)&gXKI)8%!a`)dAROny07Z2OYab^-9B*s!xY$B09C+;{NrlETvjXdj71EH5F=H5(CJ2)9idsA@?U-kYVdry^}i$?fKVw^VvkllAzJ7msK;9rq*%7KKtk zKd!8Nz+r>kGxsy8CnwtWnS^pRx&Lo5VIM-RiMD07Wh*Y)>S1p3z&cnYt=Y7)pQhJ5 zL9~MQsx|@*83q}f)Uub@MMd;D*gu2(=sYmb)|QNT4-UQz|8E5UUmJX>9FEAqOJL9# zcpQOZ?QT#oO&i`-N^vv?tWZR`XbLw=wgjX#+eUPbhd+CQdXnNgq%0ia$4p}G{VP?g z7|#aTUc0o>R4A&LN2|VT#yMN0Wu}#)ol#_LkxERDZdluoA?Kh})^Wv!bcqv8X|Cqe zQtI;4k`X87ZIv{UTcz+wg&%CIxx1xV1&T~kqZ(3&q=|SMBR3{!wfjt3Se8qeQ?Y}Nwi!T5M+*q^YJhX(xKvI`+7fMtZgo_~^M`I; zT(2AGn15QjIN>Y=Vxm56hlJ@S2D>G7YY(-=R+@WS>d}z@pM(F`g8w&y|6=feKr`Z< z7Z~wY2BrrY#DF%@CgxeB8*?nucMz^+O)j%YKhII~nmm+#yuDn6-AH4RG~pIW1^Mbk z!7RG6!1Nf<7)k}RDcPP{npP4DJZ2y_6$Dp`*IRX>-K-mc@xPGUZ zzJTg+F4}X`4Tkt!yhmUQ5-}^J6->hGgoOo9sUr)^2M#{2=Bir0i$~fdj=pv9FJLV9 z3qKc3Uf9qYxS_I61MRhpo705fMdJH|U=dC~*N!x!8aYPX=SS(`VAx{B6F!s<1VXf^ zA{wNDT>3A1-5RdfO|)hdh}>bVjOY;_Gsh{AO4dh3Z9N9w9eBnJ;J~Ij6`nX*ny8c= zH5)sLGA%pMa?7F2J41GfKL_M}NVRP>b4f>gGiqU7;G)atS6Z%|oR3LE%q`!vrcNJ~d@=Zw0JwZ$}S;k?n8FZ|l3)_n) z*@wLo$jm_x#bAE|7H8-(NQMl+0c-*6558_y8zW9T0oc((Z+Te98gaD+cFhk)Mt2X^ z1gG04Y+Du7V#MDh8FvLV15qI0uyP}`@_m3#RzUl4BQ(z#ZaH5t^gEZD4Xs%Jiwz5g z66LagO8TAH5aA*tVUd0d>F0`#7QN8F4E85tG3jr^Gxb|kZQ%Q{I^dN)AtM>XX;%|$ zri@@C?YzQcs6}){mxf7CqEm7QZU}oz(!*WFi2Vk_(tAN!xg>n6y>na@?m?M;S5>h& zIa0ziDGAR;hCz5HgWuB>S{TNuIh-ee_8ZjERWujU6D{Fzu=mrC zK-#(Ornz`1AGrZ#_*|;^s$!}TPp3Imi(pnbp@(u>!d8^!bqQwVVpVPAanLQ8OYe?U zy@}Y4)m6nQEwHfOrN!04?$VgVIXd3l8ag-ho-mN7vm7k|2-fRuz%5oU6h1AD9fhl*@Ur0qGH=gPnwc-;yg;w^YdU<@stZ(U2)crf`s?i zCz4!hkH?87gzE0*PH-nYvz6A)lOBU|mNN!ojdG^*q(`s3+j+!eq`R9#4CS3_@RN#a zr~Ha(C8C3+{PL-ao|B$zWriJ!8kN1S5)rdh17PMoN+4jIa~<&%f$+1TGt{FAEg3+I z9`fzJx?pMp|2;DnehLJGS!tn;NVky_8O^VK*N9PKIzF+s$8Ulr4lofa_W1pJoOP+ zciw3y5GQjFnoGnQ_5&z4QP~+RXA;+Mh0Zq|f_IN9!{8mVtJ?uoeza-QGTN{ga`|Ac zW9=WgXhVvR`^#<~@QVw!NMs09SA^?bCr*2;?BKd`Q8)_Tx#n6s2~Bd9VUETuxB>YWk6Z7VICj8+!ZJ%k(&pz>a|G-)VX}F}m=W`FQ*7 zcr;!uhA0zUd0b2n-dB?RX*1sacQf9DUOBVICs}kfziX|9BPG6QJi8?QD-YV${wr4E5m9n)WCuI+5%cb;Vx=Ckeao zlrP)_019e#xD8sD8|S>|v4@6z)9iF#;P8You+hNMn)#xnF_L*2>uTg=J*+2?58VbK zFD~+){lxrspMsv;4*qf6X_$)qcBCI$m|O@H&3;ydU9$@7t`acgfx2Pz69=65?whd4 zS1Q>7O(g|uX|?hx*RflgwaZ5yh3}R#`$%%)F2S2d)9T7*&g;CPDEMulgeBF^b&{38ts_qnFLDliT zBVNRy`#WZK-2B4fjqh(RE?9zpm#3Y(mIRFsBBWnk(z-$?mxJuTFToHoRTk zyr}upxLP+EaXcCEe+HZ`%EL}R>{+BFk0BQ#aS*@;BC zVd%?WtbpGH7&~?XhOH|7rBMojrw))ZnDyt~WCGK)gi=Pgvby5;eqr_BxKD6}ZVT7N zEr$R5-SGpCa-gd`)I;TUH{09=H|11(FQuG4u=Hp@X#QiB#gdG4@1ZgM=2=pZ9EHZSz)5oF{MPCEQEGr}%V1^4f7z&fPRlgK-Goe%Tkjz8L z^n6VFBJGA?{hvtJbUbW_mz?pii_1JXm~YT(w9xiL>h^4HuiHM_9oaeRivR8g!p@60 zqT%NIw%&Zmw^h>fQ6SLN6@T#ukm)Nc!KiIV1E--YHv2qyP*nW#M=@;N$=oLZFd3)Obr%r|9bh-d~PX+>Pi6vp!4w z_1FjgA24%KaxYfFwXSRlNn5*I`v2U13zSecqt%4O)I%tGl=N{-}OcyCh#HR;^H}1{Bj|i@N zwb7-JGtl+DyO5i~X@j*73$leN<4wN))z-rP<-Y|*1tWBt@JDY(RhwmXe^bEQD+y%_ zvqEo5Js<@JyuV3;W8n-uQ8=|QVb+NE2Urp?qzvprV&*9vjCY=@DkehMoS>@&62Cr` z-=dt$aG4vT#9?KK>obMoJQ7QVvG=7Uw}Rk#yBpl6bicX3P=cpv3~{hy=h$ovxGoFx z@5{AUwS>%(f#;8I1C>d-ndH}Rzy_I%IBd3Es{(oG)l)?6M5?P=qUPv9en@r_=Wp4} zdh@soN^1l7D56UG7RswPN1kECh(SiY2)ZILO^R0~Mmz%Y8zUxxS00g381b{#p#2R| zEQ6@&Y$IGV2rol=;u$et(yO#hqxgbjJEhj@J}rD4F2F;{=crfL&x z_a}lIsA}trjVSHpJqqr!#2%^v-$~|`<2)m7lE}f($SIrtE}^PpMB6d-?-E)J_F!Vc;?Wl#h(B0@STBSHOA&hj!g>g#aM&`$#z8&>9p!<*2G=#VFbzZ?XM~4( z$_JhXeQ{(!mfUgETTRMngJnF`d@_@cZvI+*`5M#+i-?RtjJ6td*W&`Dww zCAZ=K*^++v-&7*H6VpJ~Foh8}N{m)ft2i9+Qh}`O0oN~X()0jGq)7a{nrQ&nOPU5I z`;%&{M`@I12jBzd2j(mrWNQZeY8Xy+D)=6e1>Fhi@I&V0PNo5+f@z=LVF!;{MgX*$ za6`g|gjUck*C%XFTkd*D{HJsWyy*&Q!b1=w?+l=s4`?=A+e@B~8;}?ua?Y^)=Mk4Z~0% zad~xWt6BJTakQNvgr(=X2{OUa3#_!2BQT?&i|M#oTrI1k_fhp2Hd37XgBy-j;NEEQ zB4|Nq@p1qpAVaO$B+3Dx&LEbS2C-zQMro6{i9INLx@%qHG^gU#)UtW}r>%RrFpkyG zB92(feggZu!nsv=YDtVeXAUq0O#rXk1*6xhKxW1{&zP8u?q(n&3PI$1 z=I=UTdJZf88t|r#5a3mG-&NudTN_Z+o_3RU@i{EI^tTav9MUHskoEgrGz5507NirN z74L!Q5|+fR)KCIg41WTRO2^Hw9l-X7Q4Oa+EFg!6=u$LLP$1yF2Kh)l;h-AS(ABEI zVop&@G#Wn-E8YLyRKVL7Z0XSdwWZU+mIP?2USSencCZFyzxjfLH2czjnr$5>BQw$V ztAzB9K$WM#kvJ>x2VuS&%y-ahgZcH4|A5j&Tvv zRvf0ZqxogS1dw-z#{^jhCJ&ZW0-az8f$bBFR^mG&WV7IBh2^$S z@ehK2`8;sbeiG#9?}bm7FCX*BAi1=b?3W?8U(g zuo-tJ2xnH7R1z;j;+@QRvcRM8yE|z$q`w4D#C(qNB+4VXVQ)J;8Npd**b5Hi!Scya z=6C>U^P&AKLr80c`0|h*&h}Bvfu5`Yi?iET3eT=e!Iy>C;s2k<+E&RZ`*(pu8w^cE z*_en9!8M!D1Gk%r(Wk17=>Cv49$c_x5&V&mK^(7 z{Jp)ZWh*Gjm#tguGOC5n)rpZvA69KzTgsoV`PM=639HpY|LOvKw=m@q{g~QM zz?Vwv-~--WpGd-|3FCy#kI1R-hJ@!HStchF%5cHED9E#kHF17#j&HB@05BA*oO`9E z6)1bTi}CCYIVbJ4p^0;xkMl^Iw?oA@gNwDg@c3Y^=13nMdgVo&M^{07m^i$Kirk~O7|J@OmLJn-h%ra z1e9|lBKWDzYZo3}pGggk2zBd|wKqmcPI}-sxTJT(WdX*6T$ou5yusy>ZGf$xgq-yT zyDadB^OZw-Kt)(~5w87gZzLYtj`5U$?zoB*IwY>*PN}MvoPPAHt&-emGvv41^jJ72 zz2G3zp6TqA7@LuY+B<3D-MxL(yL&tF3D+K%bR91@AACXSdtoT5d2dmIYq|Y}gD->t z`gfZd*TFRiB+WgK)E37DQ64cwlq)--&gAj(@MTP?N)zaCpWxNMW7V@uj44 z;#c{9n z;OuDIp&G$)Xrr(Wj9Kuu%duBlWCU9`@OLn?VA;zD@c!8*ytM8ZNLch}7Jf$9{^(q)$1j|FG@bg^FN{1op8BgKjDIXQ`Rr=Mez69zpFRdR@nE+b z%dud$SPcMz_Q@yw<*|wQL*cE*s_j1y{!dVDTRn2j4PN51MmMQOBuyo^M`AkWZG3g( zoL-#e+UNvNggp{n%k|>%wHqQgn0iAdc1jy6B1Idc^u07q`Mrav zgXnK9Ggi%M^-#+3&Q=et%z}Rm+Nn<*Sv(T|Hi(3+e=e|p1SgW4*r&H4v_8VU-qF^h1t!SMK zWvz9QdOr?BzKWz$U}OHsU7b-Gtbq&<{dbK8MGK+I0+)eLtODLXYo2TV2F(mQb1qO0 zCB{(Mvkqhw->G16Es`Fbq|g}PO7RJa(bPNYB)O)3U5#6tF~y~rm`BQK_7(|sYZL9Q zPNba&J*3Yj;OjcTVN=$7b>_IcRpztL=Fr?*pZp1r2pa|ZR z%i@N-)bQKx3hrJ=UGOQm{lJK91ODiJ;n}|=*k=s!pwf63Hf54416!!iYZ*$1r;9@} zu&I)gRW0EhlWu@%MB-R2os@#c&P|8mh7ThB!NhUgRx{CxbCeRTKY~a6S@#wNqggIeR?{eRcc!cI=b61#!$u!|12}$7F)JA0_P-VlC4e* z3=6$ar(+~UKa*h}@;(Z7Ww5LdlX;mu_%o=CKx_`c6`x z>3-_>L1E{nE!ZQBdG@a|!tAFD?>?J?Ey6d?K7ccX37fUlA)ipTc@u6DzS=x3^srA} z$2Sdm8zq6Yn}I#E+7s|!gg@D}a8qT6J%jpfP&jVq@NB_v*HW#6LbAhz#|RHOCM0hg z{NKSh-72uNEvI>zYca2a2@m*%Hyv|ukKl1+j2l1vK3~bdXNzvC-+^=M!FRA=IOr)L z7HUZ5_N>h~@aj#fW||0Wo==wUv}w-g&r26)?;k}t1Q zGVnJ5{T1CPwuNi_-Www{SJ8xPQL4;#n6Cpgy(xUUMQg9&Vz?A;ad%WJTw@0L3H)&{ z;dhCm@Dp-#6-;q;yb(4LEJKrK05dz&Hm!&Fs=YR>YFaCX%lh5a#B&l`n|Emr^zt6u zdTl%w;>iLTgS010rn@u%`^zJj-4`TvPG3`^t%CbTQWwBYa2Ugo-Fs;euEf&hGV;T= z%H{eMZ%T!Z&#%k%;reahRPja=O1sMjA{`M^pZ`XRDY)#OlgjwzdySKSBGf4($5$8} zU$eNrAf1v;GKs@`zzN>ZBu91ANAN!4syTItNe<}-n_X(x4js7Vnc?#ir?1!U)!Y9*HzWZbA`{gbGl69tq;*&<>n;2x@-iPlr4i=ZC9x zq;3P$4TZX(XoU_Bv_HZNP*Q-B&B0cP2=XoG&wRnjL9|5l*?B1qNP8-^9R&-ywPMItD`ArLK;N5W@<;m;VCcpQe!@`+u6^ggp z$O2m{8AI2xNhS{ue`zeZVZW6$aeC($8i=+z+`Lh!0IDH+Z&1%J(1-96y^tP0z;<-xD zksE9aY{^ea?gf0{->CfrwE4LZ`J4rh6Ba&a$4SEZ=cZsz2z$OV{AWL5lJqMFy$42w zr=L%c^$q{;;uyVKB6&@Ia&cJr$MZ3GhH&Ni3EEhw#efX4ntKrxq%VT*?L~>wU_tVp z0w*8I8!H%U@<0H4sAdY@F1%86|140Ra=$k3Z=&qsR&wRg?|pliT&*QcaW3FuxpV-m zOXMyVVM8VF*fx^8R-{l>TceP%V}bpWFQpVu{M=rnq~Fai zRpaxKd`{~jbIip^KBM*L_~_Cbpl=W5M0X8O7mlVP$})g}?)9m9$Y~MPvzvd_e5eo8 zZ}!p5fj$QBw*Bgol@cPm%lE!*RBS=Odx{0sCb;8R)e-?3YimwRxJ3@$HM_Y)p4^PKE5L>}=-oD$Zvxw-7uPm6;lq+w8X{7W&9AY^H%i`*hsbvZ!2O4;%dL6*p_Rl~l;^x4F-D|KE`c@8f=tlUp}s6_ z=tw9l=)1BG>2LTWFcSX(Vm#*J$_Rtj1t*T&t{wEA^qT;LZwL2E%T!38l5uEd6gZ0c zy)8pEP4Lc!vcGiRD=h;MDglHJw;ZN((EEn}DlGp{`S0*g%WnjUdbU}KOb~wA2?z4u z>t~XaV!|E03){k$DK)H>ErpMd=$6sMag3&tW-6vPq+vkK2>dl-gSXnZpupRE^1(3sS_tauSslg)v%>1Ic+Ps zWGR*Vy=kYSTK(QHed-?Sju+e!&<-DW8~_I@*w%gb+a>n>g+<|=%o(_<1=1Bb<4boz z?DuX0?=@nHyI*1w<$a-HS`p)JK=HcxE`^n!LwrBj`=n4uw}J(?gL~Uq9<*VF@0lMz zYbtuHFH|=7%whAqGuiPJhcazW*LBMBnk~HPTmFiz7Hs2`oVyUlH^kfL7lzq#Z7gpR zF{-kaz-4O22r6Pa-tsN*x_)ngPwruvOHE;5?(Bw}$o00Urfw?z^~CZZqfyF*s*hY-il0>E1zY z5L=JK?NyXMd*I=t(>c24bgH|9D1 zK~7xstvllQQ!R=Q@Vg5oW(|5}#Csncdh%{Uyts~dNRKjqKDdS^bP4xmQ~-<2w#eWE zG@$wh``UTm=u*3I3boJLj#zSXhQmCXg~fZP;cj8~-spt2(j|%MffG*;7kFWch;s!p zBy=Njh0wlNi{}YH?o9xuZFp}+a&7Ae9ya{3>&!opnErp%BQ|Tn^h$~S1&&-!+3MJ7 zj^m0iH2b#PG&g+)TEA2u5_g;aYBKfW@V%z;-nbHd_{VV0O@&Dd({?wN&4LtwLa zh_dRpi%d5udo`7RSD~p_ZhEsXf#f~-oMMNxUf+j4uDW+h>_{KV;lEP{GsM1|A-jjS49HA zg{&V*`->EJfS}IoF9Ivn1+Z_t*~c=b-f&a9dl!rcWh1c(F7g2w*a&k+06FH{dK*nF zbL}!yXSYD}Cmh@2m-o>aYXF1Uhn-M%&RcH49If%uxBqIwK1w9uUN9LgbT|M(FegR$ zV+kODITkR-_$d3p9rWGh5MOi<^zC$vqOTgz7lb@GLgZ)fj1bUw*LoP?x(ihP^ullB z0e9R6_m>_`IPH@U=zQV*i5877+>3qk{_@_Kd$hiAPl{zG0bwx3w+%oTM?feD@w2|2 zMRv+3zloqIdttdc1dvy9W@iz1;av|EqAfho7mC~egTUfmTnu1HCjfzNGK)DA&zvaA z0x%}P1csQv}I($ZX5TayP9itKg>PpHgaX|_dQhj z^ulO2p_^1V)5+pjfJt4|5~5+}NZyjn=;1dWMB--l+<=`*#bX7OM$b!V}@cFzJ_*4nFor?{v@F9jf0@X2i-!O=vf&>0X z^Vfo#csRMK3tKL^sXHI8+=jqs{KyB`*is#Q)lN5{0!M!Ne|?gT08753M!umI{C=7} z2nj%JLt?BCG#0_b7QqL!$mv|?AI-T9T8%$)M36_0oW$@IEYcYH@|QAwZ+rOw*u4P@ zmgEQn;iMIvAmRHopywpqGKjG!VeB60HL4bz&Ae1V! zOm9ss6XBa?3>Q~(x<3rv$0vl3efosi;QZ^36K0tUYr@lHex$pPANzE{O_~zS8mIXt zhBz5w@|@@_2tKpzOVU;(hjC9NhZYLvxHB;lUb`r9b8D6mT|dQ+tsRSkeO~jV;C!4; zcfu9+63MFtzlek|293VM!FO^0^^R=`?UX?|ddLCiGno}|ZG>mpDYlK&b6!WeTl?7> zRq=?MT;P>j;QH=8mVqj`n~`hHgOAhEx9rih{nq9M4U_=%GVGfK)qTEf`1iusH*S01 zhns4X`P<&Z!x`4s%mpr#O5PqAo&ZPnWZP|!_EJlb7~+?4dWdCyJy;|oTxoDcLTjxz zhq!(PQ>MI=5EzLquK>YMBwgw{chkt7FY%JmE7S{u-G63KLr70L&3uC8Jg}DjN4=ihUEp z1JBC7K(N)%hl6G%1RAa*EV9s6jc7L!0_uc1F*LApg0mrZRaqN(CY&8HHQ|!m-U3)K z=Gr{{>8u=E_>nYPNfN;qK#mu+iQp`2@3_?EWZK4<-h@o&T5lkwJ z;2SSrLMd6W)E9wtP_ms9*1!HF@Eq4)Ux#hN(!Xs4J;nLIeUCpD4!!YKDpM-6hVs-v z&x&aH1_t?f;fOmNFwY>LEL|7S`n+AIgsS~nU}t=N|E`k!mKZ>A3MJzg^SjOQ&I^z1 zG>>&*U3zLq{}vRgW&G4+?5C*Lg4(tPlCDDTRHQR54Y2*M1T;;*T8QL~bVAjE6Z5}U zgNF%tx|5i`6U#9|P4KLMXA;AQRnP|zhu+B#foD=a?9Oxeop?+zKKAs%c>KsPe7@wB zOvJ8(cp*urgQji*VgnGSL;4kXR|N4~2s`eC@3Y|6bv9z3gs^)eVz-kR0yK*@Lf-c| zh0*fI<{cY3q@#rVw^MUYKM0;P5J-9Q`}R&cXE|bj{1al&K7?4;iqZTR zSHb6TgcskAD|>exKvsp=x7H)}b%;BD^Q-^AF>pKw;+H_&S<1j6p9j&|4V=~j znJy2dIiccjGbg`WW@h-lf`J2sK}zmJY1LwV)nbPKZ{9WmjcNosvH>E09>`ujIdpk6 zE62P4^^B7bE|;BrVL8v_d&`9w=S=>%+?`QmvgHb8MuW+*E97|#fvMOYXleip14G^9 H&K1T0A6N2` diff --git a/boards/px4/fmu-v6c/extras/px4_fmu-v6c_bootloader.bin b/boards/px4/fmu-v6c/extras/px4_fmu-v6c_bootloader.bin index 21cc353f8ac88793327fa90bd661923b7f37cffa..85f65a9822f2ee32ab75e030778a8498179a7158 100755 GIT binary patch delta 23643 zcmagG3tUvy7C5~3IcHvgGJxm^2xsPi0s}e<8fNA&GaOzTsCn~MjiNQAH!sG_~7Q+lq8Zi^O;RBTEzh zA34K|k+{K!#Ke9i&KW@Bs{YpAvX@(XSG-&%c5&yW9piK&rp`coUfT7?^R97s%OJ7M zkHjHRug8yCt2HQfuboDzwGa?OsoRerWmU=gBj+TP%k?=pbDtyUG(0aa#R9HJder;1 zgT%((Gmghf&r6zAU0>B=ofu7-L?v{pNj)zmL0Z>hlW2tZr2oG6ITjDTLmjaS%9DIj z-p>9{0-HL!Nc8iMlzsW@ltUL$=>TTBsn2MF?!wPI7+>2xP?AZ11)k2^rM}cM@kqW&q@Z|TstY=Os0OssPw&D5*{z4UMQ%DKU@IWcItxOAo@xjk8RB2!MMK zfSXI+pMv+N&cO3|shrG=$<*h7{PMf+Iy)px7)*c)A`}ow0a78{U@SBc`#%jr**_W+ zjZm&Ul{!*YNEWP~o_2e}VO)==WVlf)GE#G;aj&3QqY+J^XvH`R<631aLM)o4Zc3ky zSggAMwaj)A(`Vr!we*an)Si{p3|9&nsc}ZLs1E0_rDvtATvC|e1Sxw~vNA|~P6~Ou zgBPUsT(gKO%pwh?+o9Yg$iD>f1&A-?#z1Rbsd47BQWvEC3TeMWd;{Ve5R184XW{RH z^fM&<3~?XCeYxtE!4V(_n)&$e!ES^?IE0Z}xFlok!%Ih$z(VK6)Y5&9r>h(A_!viQ z?b8jX8xThj{pZGwy)m^X8yME`84@2jKC=N&zUfApzdHe+S1C#Wqw_F#-Ho!ZIblSr zsBlV`+wfUcA(^(la+LaeZ_IkcIkdm`sy96KNe#5Op;uk2D0WFGF^^RG0vbVDrgWs^ zeB%bl4tf6yb1u9j|6~dwM5KeI0TLXR4a)~hHZ1!t304)}(-biyir3pBo0IqqE8c;` z+fs%N*CBDQutA|^2MIYBh?gL3F0@h$tyBTd)n-=}hHeOF702w#CQ^(oE)zqB1vXlY zrspToo;+?*PCd$(n8N)^3cTQl&}3 zMM%u;zi<#Kzj+d8Dw~u}Dl@{F(0oCsT!F+C;UiVbQKu@M(y}d%vI=*hOrNW&Ft16*qg0m1xhhfX!(zdJGRx~i*-WRLZTU6N zh(+6Hc`czEWI{uRkk=g=uBD4qVql=~&d=oV&V#7QYNlEN1!pt+Y5Mm{W@1xA8d-Bv~m=Uxmes{gUf(EH_cqRG+%N(@&`(&D0!_sQTP;nkrl@biK!It3>RY0(+c zcLvgV`H`v?mjA_u#Ak$uqnFy>=x37e?SyoZmLstp-l95RXqd%M=F@pBK0m-D%ODqc z7UaZrJk&s*|JtwZn!wKtmpB0FzjYj1hV&li_;5<}zzug~eK8+V0%c!AVw}Vz|I`_^ zCm(WwQsJ#L+~V{7FuLJKT7DH@K&><5kTUzaw~XP3@_6TN;mYO__8%qxUI>m336&$Z zT|x#tF|Q=XR%;s4skWVhrC&ObTLMU$Uf>Efz5rykLX1R{yKr`l?RYCr!;>?NvnA~j zx~FF7Ne_x1=lX|)jG@L~tlvP3q&%*_)A*)jVCV5PJ9;$*+tXvK0Uak_-NuO(b~?_? zcr4V_4InrGtQ)1IBUrqDAmsfjI0EpL7QH@(2{r&6Q9b9L`mAShG}B3ozW%SE`(5sGDGNn;a8!cr3md*S!dM{bkQ)%F2yo** z2zG)b1X*%R$;_aPVXa&E-Mj*bGM+EyHM%MTEv^a_@h?cVMp}F}U8LK&(f7vSg-%tU^qGI$zbo zcv8_ZDhUa0d@M8R^shj)Dn;Fl8GBPuc{=8=3w-e4@k0IcS zANyg477zJFcU}|2Bab><>d*b@&6->?ESunt*HU7?5HUO}{$jtiL2qOEt4o*JxW^E; ze+d$^gwo+NRYUsO<_C*tQ6;=PT#wHSuHjtH6=^fj2ug2rsaZ-K9YX2*otUFneeVu= zzw~8P?*%6Ecb^>SFUx7P6&*$5IbqBQbKGW02jqc7ODJ4_bjbU*@cf8uyjD0gVg~LP z`r$cQ7^9goo)SYLTu)o6`ihN;FaeeGvYoV;EXnqec5gVZY?JNG??WrEY{=&+@s=QH zW|y4{$?7}*kR4714A4`&Z?Btd@Ul{MQxdG!*8`;g*#4GZ)y9zb+zEn4$|kB5vx$&v z=pTG{*jS*T`NG7JIEm^68EV}MA4Wal{o7)jVqJYQat zlCI!EU_LUG@065#nTspLcr?f%@|!2~!1xhL~;fxIpYt42+< zcLikpre>7obh3PeM~wjxkHAg$g=UZ-H-Oj`i3FqrDRTW&pKJqI z)`Jwu7E$7o0IFyB!R0S+AT23?aZe5`wXU-5w;r`!wZ82xhta*^8&=Hlry59W(28lx zU^82w8RRLaSbkXU_tz0eiAe#pC!% zZULzc0rAY(5cKwiU>|Sb)*dp^uAnynoFuO$)ppw*x)BSwm}oOM!~oF0`@5ReMFblu z@%m?ibJmF1qMsWnvBOWM8AufXW`!{+Ie3q-AZ0xMMR+l#c;se3Vy)J@i?87mZP(ol zv{ohjo-$s$(m&uX2N^?FO4-#-v!w}Y29|rRAHkMH7Oq^#XDhH%c$XbRrG9YqAM6PX zv9MJ)DJJy;A}r8inGZGr2&IBc7e~cNM0^nZI^|dlq8kxO37vSGWgiHJS{Cvrz%D}QT+xJ zK2J_+cqgvkW}+{mdYprVTW&b7TcMtD77$%9CdO@CgpIRt;t)E{dO_NSLf+SW z7o<9fcS8IIQZ|IVFT&G7!)%y80>oSZg2Y3C^PZJHG+dDOhV#hsl|UYe(SWdBpP4bW zbdQOF6QRR2r6}M{gU(0?PeUQn!Agh+J6JCKs2_#1g@9g*9}rTqwDxikQ|7^h9zXyf za=@0LGz7et0Ot-O4eXYs{dX5LH3xt|SOEMpPy)-zgrR>d=trasGU_sTr2%lUJmCGz zk2xK$fF&jaIMk0=vb?Ao8Gp4tWmZ<$=3C``#+*gA2pgz>Cd8Q|;k|3+ zVq3#)hkbS>C!VA=t!8L<_M%0$sFFxq!bD?aX^xQ;lvk5ZSL!$!T>wfjvUtEL76jEp{1hFZKJJn02u_epQF3tIc)2o3o)S%IhF|ciHe(Do) zxY!JgVdMizmN!h)C6L&16kREJgd{)p85~7YTsXCF&ex5Efy_%va7Gv79y%^ci+!>f z-7eeehI!Se8h2JNwNX7TN?16K)!YTq&}6BO(#DoBFcH{C>x5n7j7v$T`k1*o2@a78 ziY{e*RL;W^Q(AA+6cTW&j#;XcMne@DJzegTS$?)1;Hy5fhV!77j;z*fGcGwlcd$I9 zX-P{UF+od-m6}4-x>lHMcqYbjG>%__ za^^3jq&%@j%X9n%IMAR-PzOl8A<%UgyP9@Lnp49bDC?d+qGg_*8FAqd9V29nA3sT6 zvcZU0(3fZ;iKZm4s|Be@y&ONOXI{6pwp0FfH5O@%+d%$o1(I$BmClaw4;F3K++O>2 zgFHjm4&vzm_GB1c4VZg_j~bx8lTDw4D4y0mRQ7Y@?bT$vP12T{bq&@WjYVw9;IF&s z+dEgmxg$rR7qTYs_Vbcbd8&5^C@o08^x8$e`82(nC^2A(iE4|5B?i@&1DYbLEoG5Y zV)F7EIFX`3n~*oC)gtB1kaC-hAKHOKk(kpAM;R82_Yn5jpaFgm@Rs{oUJXi=swQZC zGqf&@7#?k**LKKb+9Ic4kd%3yim0{=5;IrE7J$MrO~kUZ&`Zesy9DvvJB?u(n}v-7 zdZ}tET_=MR%K}Bz1>tWKQ>n*;!i|XuI8sndGH78L)MP2r*B_BzMjTzt0La&>LsUCBj#^zA?+qTWU*+?dM zTRFSVfkR#)#IDm9V;!Ji-g+a;bKMk8&~SzLXUKgmM8tVmlomlfe7Jqoj5e4RTt&3ns6yIr_g=f#@`jFWy?l8{=jypr**2R`k+69>9cb5;=bX1UP z1qDJV)@?PCu1L3ELR!fCVEFX&8Cie8Vzdq z+6R+!EysL!`uKHmW}=NTcb_%mu_GQ(wwk*wt9oV@tYg;6L|V24 zl$%*bT@qVx>Ob8xCDw=yN!HtLHRK9O+_U z_J3=Ynub;?0COH`j$CID_T^4q@WE#l>pn_Y(YrYgWmo(q;_}tnLng%~jVtHbP6gdo zvCb?S>59K-*NrSK!RO}oB<*Z$?Aae3(J{OPbLXU7d(^gj)28k)gTu6vsUk z@=o#_f#wyUob&l$J1Go#4}rKB#)=q}YK1_sBsF#s(E-HHVEF$pB#kO2C~6iRWp@Z$vF5%(#3ak3gykW}*SlzET1WHeLB# zo7XZRCyF$yH;U^W==RR1SBN|&^5F6Sd15?P5PBX9?1Bkd(R+s82=OkMuEFPL4KQd} zl|)(M5Obe#Hn+aw`8d%UEpsxScp#pTx7ati>zFj6>XZKq;*+b$3u)A{YdSmw`tl$eL+mlNp8Tx|?5dV1(?g^>3& z9HkCOj~HO7YCxYwV|}KR(nmRw{(=i-oO7M(MRBKkjcDI9#%?pRJ`>-CMLR9mf7yPf z=L{V!`0nNGWXxv*4erOEdGDD!ZUWqUZ7B0y7io{uk8q)J_P&b4P!Gw|r`>tv@Ts0t zXsEob+kvLHS`9G&RV)z9SkPaEydMQ#bR)gJukcfL=$3ojvC%Xolp4|Tb-tc$9bM6Hv@i^MWi)#7k)!(|Qah&Vh#>kVxwJAD$ zT2S4mwU39k#~<#!)*-j|Wgjl@mecmWjKlVE)9#EuT(OoIP$>PhKK8J#Oh zB^g$(fn^kFH2^xl#+ZGGS9nIDgRNzvF*0SqzRiPQ33=}fyxS8AwEy$KYe4gqE{}hr zcRjrsp4Wu8lr^jI?)Rie)UeG2k~rF@swM1m1(YGov%ECPgv834khcSr8ey&3%k2u> zrnbdc7bw{YbKPhRKciQX52om{?!uAtB$|cA%A>kzyHX?K=oHXAPAM4yEWKEw49nJ< zfP_Tas*iKENx9njCtrn57DH#7ASTaoB7Xjk3jL%=>^UNjI>6415iW zT!Q~jR}zbS5u&UIMRWi_5x3uXZbI`ONoF8GZH2hiO{f`Z(=B*M$m@_u91!^0dlb^3CiL_=X(j(a$VShks2TF}asXt0z)qsgX^`mrl-$9R6hU?oE ze{Ne=Qr2CZcurF1!TxK*x&=~16*Zu`HNiyfBqt{aonjmT7)}d$POARVfi1U^w4=Le z`NKrYp9uz28|JLzOQi^yUzGVkc!taM_95ZPneTfQION@F9rB-P&0PBmh^o_zR`eFc z9$E{cum)yi=!#yN#$pxD?;aWhLa`=u^`X`GDyTLkN1FG+IX)jo9rBLzslzFG@}X^X zeQ7gQPtplcd0C)e1LS!*d#q}0G`Pri$@d5Tg+9Q&ZziuTb8KNyBXi?Rq7yg;g+O;}B z)qLq`Hj2-9%J0qdJyxkx{=~ zA~l_pqVhNqtpX%mbsC<@`#kJx+frm46YxsGT2QUr4*%Z@zVJZEyCw8OX<1+2QwVhB ze(!Am#$t-6d64F!Op-Mb^CoLhcX~DTG}1-+s9{Mtk1QFvl(BoNWw4zaEuxxPUUi`n zPuL(WG%gYCj3RS`RAgLUy`mRG&VH$+>Z%KINn?y@9gU}?)J3NxLrjvvA+cJA6r}}S zMJ&$QDNW5+=t+(B@U&MNI`dZ-(p40b<+&FW+;m6FuaYt3&24>jx`TUk#(t~)s*NDR zRVxieX7+QHNRK=5RIiJx3=1KP{!}_=x~}pZ@V&uf6H4=Yr}pn(HjKz^Ir}Su-n|lM zo4}gIQ#5D23K}gmn@D+AtwFB<$3652_>$z2h2Q|I;60DL5BiUwJfr;<<|-D$ahBe{ zxEM4_%y{yz4F5-k|JC9DVc~xbFtBKe=&Xry0^C>ThQNts*xa!tXQkY^XJPxw2KSYu zxf&argVK+|ZU8)pHA`%iSyC@FOPVCXB)ZbT_aVfl7AHX|;Ymw^eMIT7qCJZUs?E2~ zt4t`-iuQbM-&zbIUn_=igc)h)FN!bOv#3V52gY?J2nYH8r@^B@GWxyU&BTu+@ZQ@fxi9DU;N&02Ly)CowK_clwYOyfXzt8PjA5QBk_ZNT!+#x zw1SrpOM_mG5~D%dhysH(7Jmi{7%V7z3k+^SiMAnq?Ro>W!8D z2Ayrc?E_QB`JZfpRbYxn&zKmhuqnY&2-6mcxsOy#1qGGVk_N{e1D^%&(?g%RW7+TB zN&G+DaZO~iemg`o3}9f=`n`2vx+YEp#K~i-@N7|A10`ja>>dwk0M~<}IPKBL)c>b=OxSSwy>~Uh|%mO`Xp0Knu2i!?M z4Uq}_$$u48)C}knu=oH_=Rl{r1&gneQELf)W1Z4~Ys^+KM+N^2%{+jHj1`No1!eqI zP=>_9QAH^?K#D#LPAE>F=r)?C$`F48~1tklg2Z3b$U}VoHvY@DxhI(~!O&oNQ!q)kD3pX-jB<`a0F6H|>c1~OdggsMVy z6J=re(&QZ`r87>#DM-SJD8uWDP4Ic21B4+;CSl=>`|J`B(y7X-!jvY!@%OQq??>q$ zwo-LOECZdPj~oLdX6S9^=7{ML4@8#zC}la00bH2VTgg%AL5Z1i(scX0xuEx4U7^P< zf;_Sj+#g9mK%L=OOY~jWKBq6$;9p!EXyKWmoX8!rSE!;m-tbc_IEmm^O3SkRm^E zsiZEkl~{a7_;ltdJVR)ksmG5Cc$QYXe4q$mm_6{*i`+{^d~9Q4;~rCT>na-!lr+kW z#f5@-Rt`1^&&-;r{Rn9Mj!WiYBg&yp2e`B(boNx!z^=9(B`G6>?`QRl+}Hm`n9_*~ z0(n>^@l`QGZkgbkojbG)W&c}3JH~gAq}4*)gB*A_-1Fc#W%|Gr+x{LEEj;;P$>P5b z5YsT@$wDFT-ano-@Vp27#`1W^lO!kl7y;f4Jb8NQk21+nrgi{n^Pq860BH$^$^sk+ zOM^2AE0d4JV=YM^3JG(P@fBh6oD}RjI&Y4Qvi~ErzgiFC1+!LW5evDzLl| zI!rKNQ6Ukik`NXFH{po|+d?2jp0eOc3NfB!gtY{h!JVqLs%Zmo%!QSVM+3Bi#1}$b zHP*{70*+Ua_g6zi)rPd(lPs?lE2u?W|O?MM1Yt0_o1>httr->{s-#tj=0cj|gf4!tCyfhfj9-ZxrE zOspTuCZ<#qK5f<8XmZ#B)I`Lu7XVR%1x^VIfyD%1ql5$l-jmHpG&M_28>#^TgyQ)z z<6`?2yshEgY6lzib_5EgG*s1$r|z$Q(DR>g{^&_!J@t&ocIQYd(_c)TqGq365)^Y;}xU8 zy9SBff^U8{zAj`en2lS7=NBxC-|v_6Vgt%f>D*A=)N>{}u>($BLSO-h|14-1rYN2P z4*_t@5DFJ&-~wUg!VLR>_g}z3!3`u}ga4fVpMi~n&LRYUUmZ(KLGOehV+Do=z9ee! zHd%0-*!rTUgMAkmW(6=z#>H&`Mv}wTA*JAd!0rTN(b*A zZmE^4>2WhKw}dGa1|y1S;})!s0?tXpc_x%&wjy!#A6!#u1nYVWoLwbv zq=pCfrq66fiAjc_caiY$!}n0kN5X3l|A|uhh2I`tkDnA)KJvPZ`3Nb?g&~io;7%d? z(PEq{JoD%n`)U7whm(E1w@{wEg&)S(@eg;#!m{T0z=l3na~Z!+_SuLaxEOWf`Z}Aj zc?Ia*2?|biA`aZQ43oQxVX(U;b;AlVO6GA>W8bq)x;z~aAR5~E>Zrn#1-yj#6v~om za8n9;dk21S|JyEU#?wcWtmUAK)BwR&f@TM*1i^cWCcb8mSt}NCiw{Va9cQo0xhQTU zY^bE$VNR3=-5S$*ig=v7@ONog{w4SHRK_P?ZOHu*w4_SeVfc@fedsO#b*tF4>4*Z@ z(evrm}Lj0m8YWRTg-69k26QUO<;w(YG zSQ}a7XOgK7>R`w_UwCM73N_0oR4>+HR;XV*17qR(;*7Ws|A$}^JYb9ISXQah88b!@h!OSG%OF`btuk$2S}TpbtUS z$Azg&X5v)gq$pM%CwTsnkhpYe%$EVoA(psP$ibn>=WP)xmyUlt0c^&gzj+39t7*60#6?1E zikpGhxarjBOdCChvn4ij)(WfG5^HO05G3`fn6=vrq>D3caOgaB<~q_&ZpQ3v>+omv z)|6)w_zM1-JJLGan*5C9o^1>LfLckLz2R8{5AG3oGXVYU7DNVm{9Go??Vy;6^;p!wiy)LFU+^4C#L%@5@*Z0$^8BvCAGt}we?g2VvQEK03p0- zTZX?CRFw}+O#w63&BnbAls&4HxSs^QW2LZ_1x~ILV787*SGEyxjK(d$Rv8DpkGGKA z6(WVITFQktD<=;--9q^9WN>fnEmZJB_?>)`O;|T#xLppG0-txsfWi3aK&^y#>}|jY z2fXSa2KjEldm=EZ!EDo8H`tb0<<9~G3)DixhCfIHHrpjcx0U1UkQf6HmMZyyizC2? z^we7;lZr-_fZl}8_aJ=3hZY$?*}Yo=?-gECQUugG4jd%pTHieH>;57DpnYJMv`~$> zl#KmLV%iBOXCy}hq*+n+m(Hty)?2wJmswA_> z8a|R2-L*E#GWayKBm-dF+pq2-QhIFHZrfX?cX}{&poe1i^)Pt1^`=W!OqhACP_ry< z4tOa|=fDGLj}06~?%iYMY;g_sujI zd%ysZWy=EZB_!_eA3O_1!}FWM&1EC(fA?c>zAQE=AZ1(sHMbn%7l2}a0z-`- zk+L4b-yq0<4}n3D`P5BHu%mRPBAueRVo@~v&Y}UYzF)ybv)m#gU-Wyoejb{o zKr@#UcOix^(6H6Yh7V21mDhrE{oZ=%j_~sGc)J7m_E28iOx#eUvViw|OKfw%yE>rh zqC6vLPK=J6Ux02kI`(;#vH5R8?mb3J~HRY*pG2OIsG$3s#;#ZaM@>%5!z5S?Bim zph%j}X&=4v&xJNyGhK zIyfG(%x;wWuyD_lX4rh!JedY!^}Z)LdwxrTjk0R2gv!hMo_lJC?^ZA6i$jrCs&uZo z$VwzELK%5YW?K|5vnfk1j`+n#jo0vsQboxr&0SKZL?*~W>992msEJS&si)+}!wnTG zBe!*hxap6hYxJ>{Ci$V+a5V#~U!es`eAh?sDL3HVNW52=wqj!1s(=pGpE-y`jilIv zC#YeI40w&OYg-#IkM}4cr&!p%V!RzhrO}rq>ka|ThJ>Ra@%IfUJZaHNC(fY+y)Enj zKj~Y(t}yM2AmP1xl1MJK)8hodl@Yo^-oj7In%;iGqmRDd83!>NeV_A$hl`%({J>+N zI~!H{vi2_71Fe)#nP(9l4CPbYqv$%}$&S`LPuM+%=pGlr5UL(ToM)v0OCp^zZX98fWqsPGi6VX~%YM*0?{XnCok6m)geZrF&9qsCp z&4ZI4)y8#Stp=N|{=HTLaSH#a$s*P=A3>?H(H&3nx_H7<0ZVYOCPMs? zo(-mouWP>L-z;4qG4;(bFUr>4Jeh?eepqWh55nYlBp&xW__`}6JdZ`&`_>(f;GuI% zv{vO&sG>8J2Qx%PWO{3~_T&vJ5{VOiZ%U~^1S$$=nw;+_%ops#L?${4CKaj5L{=3i zMn#*Qq^n`A3`cV(O;H_M#d|%pLUrLdTuNd=Ia^nF+=G>p>wXIwLrOAEy{#C|Xn0ax zA!(k0TRT(U)*OJFH7uRELcnNo+MMED~?yb&*Vf}@a~ZffGr~p8ClK* z4--AMb7w(T2f-XNdJ4qZJq76<5dbExhuvMtfqjY=K55PD?p`J1a1H?*0fHa**irNd zrxJW2<18ml$67-PXv{EC6`kao!h@-EcTw^ejrf(ngC8dC3FUPX&Z2C0|0FMJ#W~m9 zWHuOKMM~)^xdU^O!vCLh!hxSkGtYFXJfX>k@cij*qzoxtX6I=*-p}d)$e#Vm zgXj->R1^cZDM?{w_a4(dt;$1XqCt6HBSe+TVJf(siLk$>HCXQF)NqQTxIn)*AyGbnDSyxDE%l6n6uA@n$3GhgV zhCxXW+=71Va~SD(}y5{76|B6CSbyY z_zb89f%>XIZ_{=R>qC!{1s&E}pk1o1D$c+oD;Zu`cABC@rEYi`h<@Tj8G zE)Bjh0C$APfZuWBJp{o@3Tj(bo;->eNp`gwv`<*Tz|&vb8Y{&m)fN8T-369^Jn3(4 z(me&}_=Q`qJ?F;bKk!6EeBJ1Be+x8&l|wwN3MgvIixO+F>lD##fSb(pf*~&6a`YOW zb{ESF3l8)sbpGo|=krctZfXW>iB95>WqyQgu+&bp4+)`7(0ee;56c~GGSB4m)f+hzN zV9mip-NC>tJzRWN62RmL-Jdi$Zk=`b66hXA z>1*8IBUh10t?T-h-!Fq{iY)8yTKVRM#j^S~PBy32*n4U`gc#IlY~1N4V;=SYHfB+- zI^mfcO-5M&`@jmiqfwPv*sjtSwEy@kEk2NDfnU7EVxP26rt&b6Ad4g1hO|Gqfxj*K z(W#R?*y?CJ)p*;TDh_8NxRim7;pvivXNw}UMP)gaA3oux>JzK~q>pe>;3`cCW?Obr@=j*ks78-t3)0(aA24F~6gn!f( ze&?=89{NE#KWkvatxLdFW5J+NSNQc^fbXj-eC+;T416>>Zoiy;T{6e@p=XnLIUmg@ zwQ{hF5n7Ii`&BjyHota%aCP^B6xRTuODxFyTOf40IK%dX)4HQ1gSFx`A*v z?7U}!$NkWR-`$}br*{hF)$HRjE^YUfr(_0$mh990;6aVjPL4#N1f0L}zLit0bQp|d zzZoMvzo`ePf0I4@ru)cmr`EiE)4c51Z~U5Y`em}iUva;E(+FvQ3zvPk%~-7DqSG+@ z_Raf*E7g-@45f6>-)P|`T4VT45&8DbOhNx_qJ1x1wcC4S<_&cuB|h4}0^F9i@MuS8 zBDueAhPz%nFVEr^@TjgBhB>hxc??nW$c>MkyZHzm;*=8pmJ&1i*Yn%pG#mFvkFVTR zuVH^vtN~cU@G+fefc78xtuS(_1y4~yHhHJk&6bdCn_}z|B?&#agqRhzAbq6*HB5YJZDi&d=8Eq5MC8t zc`k9n)8q*PkutFsRR+98VdKFNURy~HNri9-rkz)97?kySEq-r)NciEo35ENh%I-g^ zf;DAFz^m)W2EX?ekbTt+cz3{i=Z|ZdaGA%VZrW;!<7sD7HJ*U7B$puI6I`n#vjZ?^IB#n9dpm_gYer7~M^MGlVbz+ZYj)+7<_I{2R)Hc=0`2p! z9k<+S7~c|!Xj2~m`^k_FqJ%R*+OtAn&3I~LNHDBr=Q^N+zK-vKB=6<5;p$DG%KoyG zu^a%#ea21Dt>3BTOL(zT*`r`2@9)9h%2G@3qTj-b9Rq;#*j+&2qJz1zw;|w_Ny5Rk znc(_7MCtNqg~!rp0xq78|5Vde8F_;=xz=MzC=`O)(^_Em7i!yluxC2Yvs38PVT z;)!wzM>5&BU7+4)IV6Er01Ew98fvST*Q5p=oergI7zI|IF2X^ zW2SSkuA`ibZPDPqKk{NUxI)t&R6*ZHIeSbo=P2=Oi4tFxLJxbN4pHLU@KQlmRcwcU zatfuy-OZo~LX;A2s3~*9+DF7iPJdA1SX~48$M;&ue-5MXbID5+t8<$7+qh;5oaGe{IL_%#y%T+zNM} zm7hYWcOYfYy8i?_+%zA2Sx|$NaqE#XA3_ZTdIM7Khxj~%Kg08y|9i#%ZRG#=IR)xc z0Hh3-5U!T5r|Zetk`@+q+2Q0@74lvM_2Q{pQVl883nn-u-m0-BGwJBoZ#6&uibOhc zXv{FgXcrfSyrCeePSHQQ8SSG*cf$X@@c&4W=uS!l!Ez!cCP<7{zC#Yo;MZVQcAx7P zH%=pMe;IE3Yz;Ez0odyUV}N1P9rH6Cf5L0$l%8Ix1qV9nz}^nq$k7ah!SlQ zERA8mN!t#BXR4X7Kv22T0xXO1zLL1=xaMiF&T&=ww_<5ZD?fa$^v%1WeecZkcN!-i_^hFpv|T@Gp0#gwzD8YA~N*aZLy$82t{DQKSI8 zb~l;4^l)cmYEarZ-q=M*sTw#i!Tvl5_d!rjW5f*d_Ll-DN2j-)23Pm;X_6gHLs06<>yW0ixrXzMtJYkKI$?R;LDRG7k-6O{I zxtNJ${tubHYlo#hD1SZV?F*0rs_6^YK!y+#Lh>DF+=!DMlnHRF6ZFw=2y_s*&%!ej z&p2dtSd0nXMU1vU(jTS4Onfq2yfIw-qj2#Lq4;`*Q9S5S0v5jOz+&-#svZw_Y^3Y1 zk>+0wm)`{?t_ANl{$99*gMJ}gVq>_(28aCpVJv*B0Bj?SR<=V1*eL`uc)1-OUM3a5 zH)ut;!g8pv%*pDe7LQ1i9|T{W08}_Adlfv8NChbWOt?H+_0ToK8t;elvpc_ROwKNE zCm>CS_fltBpA$Zf@N#eiSOL$$)7D^SX??*oS4L@_=|0zw(t#tSL_xPbGIAbF;M2ju z3eN=R7EJ5g@i8EB96{tkG@cgt{FgymO%8|+tCEJe2%^gmQrf}%ae*alSR5(~d0%KD z^p!{_>Q%1sJlKE0nnV6ef}2fOo##Lri_Q6O%dznRu zQnCeWpw;y)Bt5ybstKhlTQz*`k&u`5B^JwJ4mBWp%%lhMWw7>;5w4)ow=kShaT zSCEcMj_Zt_QOWCJNRx$q8{=k7^*;eN)^zB2+<<{sf*@A~16zN*tnW&$YzCa0A#Mk~ zDH$diq5-;I2Qk=Y!$bVi_unBJ1iUGJL@^A22@ik{TkOeT``rd1d()^95dp|^;;D#i zpSdDo3{MY0-l9!h!lyoz&hRN<*7JKC`Ui~$nl3DQg2G#ySWRExio4W?QZ+UtE(eo~ zx@Co^VLIGG_a-C$S4Li4CW`h#!H9qiD z6{@$hOu&mI;f?J)btxqLy!~EE9TM0V_cDI(PDwcX;sokKP>^2SNWBsi*1eQTtqBSr zyfm8X2?^(3nvl$GM#{n+NcsLNNO=!P2=QQrO#tHs;*faLFX&$W{E>%)M}Wt|CsKkR zg2Fvs_CCxZsY3i0qWPF=CwTqEh}NhFYuly0TVPf+DS7brEV&bdDW?V(_JCBa^2GDE4&tb*0UUT|F6 z%I<-g7m$@Oq_7#-fQ+p7~)jwM+Z8x-&8>ITw~bU&#JCT(!2{BIkV?d$@YuGo)K#DG+BPSnZZbY8 zl*bPjPSvW_^MiM9emJB}YRN6!TboH0`Gm)6lSk);?;2zVe}k_)-Ea}#!f?;fpx(Dp z+ED%z+{;P)Tc$5a|c8?{gCgv!2LFI ztv><_h#R~?w-uI~+@Nzxb&lhb++fw`wOTnO!2RH=6-WOqF-JgRK~QfCl;8B!C#3u) zD37$qB;Bc(;u_!C9zC$#AKSRAfO4Yxqo#y*;ejo~?SspoG(dDUTcFP0n%@Mg2KnsL z;4%8I+uwO&Qsd5tO%J}a{aF8KE1nSB_?qdRjpUjpqW5pa-CNgl!=s* z0qK>7t4vr`)>l&gy`*-?h3~H`-~ax4#8#gd4KRFOGcoNG0KCv?5aa&P{zhmx(5I2ZW6 zPk?g)h%azv&jhQw-@8%ZUQ5IALh);f_@c1%H9fWnue`?Pn?nKbngMcD_IVGVM6LPo z8K|gZ5j<+za%3e~p{RpF@2CBdA4Ke?4if9sD!+>C^gZO7CdvCkxcyo_MfD4LuP5PN zVb1Hb@z=upug}DLkNRG(#CWT)baw`RT6lT)sKm#PBc1V9d<-1ckBdz&*ft#@$LQfU zG;WUY_ub>bRl~b`=ECrm3^+vR9G?Pi%l~vPfdB8D_ygmusF^G%$KlgIoh{(|k>mId z=1Ymbb`L%FOq1dx{Qew?S%zNqdq05>JIOoYmLHGnK-&GofoK4{Q-!^I<_<}Nc_ot+ z1q(Mykk#JOJjYF$?#3qXsB{ zem6aIm$9rnsYo03xlg*2GO*pN^bNlX>1Mf4;n{79xR}&K({fM9;1E-4cAJd1l4_{? zD=Z5V4m2M1N$_1Tb&jQ*wjiIv`(C&-!yr#6$00^!)w~DA6*WsNRGzV0Zu~hBjULr- z!HBpouOst#&tn0<>!*!TWQ?uqjv4<8H)FrzT*GN z|LOc}=fe$0!G&ZIq~QUDR|kN2j45WAt(9o>;Jm^j)9psG#M%M6_Z1^H-<`9ggR?Lx zGRoX7H$&HV-ZC)*R3FTR9i|?-&l`8{EmJmhUty_F+yblYy`%6A&jFmsm-~kHZu?_` z0Vnc?pW9{{c9FV&k>%?Iz8mp*?yDZ3sgCyKad==GADpoaJ0!Mz>Ju0Ta7egGml6O-7 zy{zQT=_j9;aKM)t+yC=rMsPP|!Lzzw4i_ArtLn7PH6!u;e)!lMe65J6&RW3_mYleW zI_=+(-U?rMK;i-TAIulPXFb{uch1P?Jjn-32S4XI3obB|ZzrnZ^Op!dhk0<8u1^i` zC{^~K&wuLr9N`oI9lY$xry$t!?>GU@ z8=M_(kPN9Rj85OxTGj_jDwqdz@=!hTCsnm;LHr^*G$cL?6&8bs_#GE$!#vR3Z73^t zp4_02x&Hee_Zg{ALg)qtS4=XqNR1Y9rD9Wpjp22rr~j`ut~Mr)A`H*$-NGIm%2yL0 zeB1#G7rx{(9BnU!qnuaHS|}2aq77h4sfMHtt+5zA&>x~m8Z+$=T1}-uQByvSE3r1Q zl>YIDF*%}%@S_QaC{Zv%%iUfNuIDq{B^u)<&%X1{`_Am{?CkE$yYIY@qa)(A83XpN zd*-y>eD`(Zhxg3lBGqYSafg)IyV81V9;sAU%{sUF5d}>L<$S8UW{;QVPsknV(U!yP z`sX!{!)RXgo(AH%6zledVqj2%;1)1-!ol@|)u+gJh@M*gYX>xHvLB!Zyq2M%f(DoG zyF>pYhm#BB(QX8BgnY->2ak@0*$9OFk*XCXFfSr^ljpM5ku(QdF_SmlS*(p2FqI#z z-9C#YL<6Q$TNz?>_8Ch^K-tZG$LAO^q?a#A) zYBn#DY@XZZ&%v;(pwp|g`eiFz>32j+HmGqY3nqbQ7Uj*LkO_;ZhW$07J(*Kid&_K` zFR*CPSMd|o()P_sn143{ysAonj4iId01rtDsw?(WeF7Hgv0RyAf$^n z(W;%7^b`TJ)IxHbTJKe&?s8e|3R&Ua($wlz=v^|;c^>3LZI$M{u#@xJNaodc?jOo! zLRfblPf$o#KzuC}US)wBX$}M8c6rt!4M|HeM~?kLQt3KLu=n;kQ+lJU57r+D4Zcib zbvF96q}bUC$Ef?W)!TjOlu4FQ=fo6!hDdMmi!p@0WC=^Wq3WNg3N^6J5u%;XhRZn7 zH~Hk^X3Y}ykhp%cxGY-x zyFNi2<9`m>hITj)=x)a#(n=gA!G^;a3AB2Z<1AxLrp>HwETggn{|wZ7PK`H%yGk`Y zv5c6!$E*E_S`<{KFxs*^ca?N#@zDv4q;UD&RSMX(u?z5yjT=7)cggq1FVapH82^DL zvhQz>=c0A>qHWQqEff%zH~}#|v?d;k^(pSLn)pRSW)OF(nX!pN8p#$W2Ca$p#yK4p zHaB*OUBl)S_u}h=Fj3MhL-zg0?~y3IdPkLwkR__iX4RIUg3-Dm!W{`q2A?Nf3F@4G z)^eXylI6PmMJ#Q6k_?M7A%s&^m_|@S9)gbq,{88j*^*MR5x(P3U2rZJo{&zDV( ziv>iQ%g1{0JlMX0hX}OfGGJ*D0Ly^%EAnLIp}^kuJMxEtQD8g_XDN~NWkhNL7J)Os z1%MZ5hit9_hIsH!pxsEMLGV@k5e>Av)Aij~ar8{(i&)SOgbqQ-p>R5~5f#2nq@%}( zGLiA@)HZq;4VG#0@GP#^njEc9{gAU4SoO!Hgriz|tlQYjV-;5!3L%?TE zf~H!i=IK~o<|V`mL*N?Vch|(mU1fg*&4VSW delta 23602 zcma&O33yXg+5mjcy*J72LX$4gbfZ~X=n82IQWhm7?d=kPds3Wl{_T1GJkPn?+1~S> z_q^xbPWIfOF1V=XOBCjWZYtN7Sc$ZW7Qv+beuO2lGO=QZDgApSMhqfxvKNU920Qz! zUhV8(@oHRUJg*lq9dDfzzR$7#k%PqN{YbnEH5&Y8iAlNOnk_L=@Dz2yRi{Q72WXUm z5XzX|jM$y<-0(Z^7Zgz+RYa{Zl30jT=!8>VMmgn^3N?f1iDJ<(vxW zbfC6cFDhxX$U^5)@ZM8x7L9b&AI}5!>L@D#t`^D|p^WgKXTfT=lvHL-Zd`1xOs+Op zHda%2P+{^CQ{|<_$-GHCG~1SJP3CuF|M_HI1=n#f%6-Uxelpz6q8u8VXn}$QMpL*P z<3E32MI_$<_wjHyi4+xS9T$GW@B}SEPJul}%Jd?xP_f62;rpiVLxwjRwQfIazpuos~a&V%O*kS;^& zffT|>bp!4~o?J73xMf6T3Lm?b9VTR8==9F=P)U7UHDVxW8kvL!YmqM!{wcow-!?SwPX#TtOK>=y27H~+~7zb?#YWBD-%~BvkgNZjhx!>Y2G&0>#PZx!`ql#4%B!Hh6HsK@>z z%IRTYB(ToeRC50r^}HuX8T%p-yA)Dwxa^XQARe;m_9 zW>Gc=^w9%}ZNuW@J`4ae64tP7NJJ93KH@8GlW{0R!{Koe;yND|XM5Q^j}zrH-EvLG zjbbAf*L+gk!L|`3hCDYyBLI>Jah|W^25Us3>;&rU0$7lywhWhJvFIe~jEJUCZCU8o zDbum=$go%&EnW-JdbMssh5k7MH^DNY>dZ}9kz9XmBO_)?<0~}W16Eor2o_oJ`#e|l zV5*hU=hkA;HF)JF!n9cAXY@tZA|B_KUNP`?M2qGA9E%#hFjh_ZJ2oUn`VR6V%e(o< ztpLA21u)g`O@?bKe3#jD$s>)Y%LZI$eP>)bAs9O*CQ; z!TUmZUjnIIF&Smdg@+PIFUKP`X(?hSrjnUQ8H|`G$t+a^#fz6{(H;gMz9?xps+o|_ z+IJAUM0h7AUABK1Vpj|Qh#8GH3b$hP)S4I}PWga*O$?bW1$kEl1)dc#H1d(lVQy z$YpU@+~H+L${-hs>mVoo(jzV8`Ou)Yr;wW!F3}3#f4g*K8On7#3c_E~yuZ4lnku-+ zN+|m}65}OiCK)n@W6q?k7^W*swoj4Ou&Na@G^bNRgV@$gnDQyPlcM>v&T7R*A4NZ~? zKkc~Nx?eJ=U_m$O#A*tQG#<6OdQqeq!>FEEeQ?oF8yR;Ag~W|8f=yCt0~Ra2A@fFru^`&F%@`l^*oH!V`$ zFQEH9u9=b!;le1Mc84A~&Byf8bg86A*M(_uX^XaUdpQLx&*9uOPOYmo(4sS7*Tfrm;i3Y~H4c@tyrr(`dBe^h;04+`v z_Q$6wpOVO`P_?PG3=rCB;mi26Y{MYKHNZ+d=97(NE)irV4rXz+9gI5z9k(*#NuP#8 znY4IEP$oen>`!wso+$9e88mnVYei;tnL9^uslXDPV#PN8|%h)lihZmT>u&Y4}uxXXc_ z`v$Eoxx9wEwsaYRVUHbJ~|(cK{at_dYqSk35HwFF%IFe+#tQobZaI1L8&E%uu-g zsE}vBPl$PHgixyK-Gv|t_5QsPo!SxWlY2RkwhNL+am=@o4hha0d~%`xJ$UXaT5 zaxK;{z<-b)H_EjXJU=0{r@WBzq?gfye8N?4LgEbX5P-!U3M~@96RJ|v@N2@;srh)m z(3JW#E)ycs3aZ!pWn6g+a$6O7YqB`?_yRy-WbmlT3qM7$&0Omj5K z0EATy=l)cgp0&C8tc02sz>&Kp_5gEng*Y6AarEl6_KDm~n5cG%;g+_KIE6H~T_|_J z83o(2+Y$2I3ZSf8&g-s;++0|KmxUQ4$J?$3WZdR&PDP-@JcRIVC;~^YOTMM?aCP?7FMc)@HnWVGC(Z!;M}|iT4MV zT37K0t;hIl);C=<0TXZe819P}XmRdF+z1VB8`?~^!DfQoGbs%>k4qT$?M+HgiRl5V zk#5>!8gLHLC{)@=3AhPrZGHA*(&bionhS`|2~bT8H&m)qFsDyW-x0{*Z^IfN2C|#6 zCFr>x%BV?b(XTsVqMbp{@527{#9@8@o_19^p=?V0MffZ|ZP*Wff_UHs0BEw%mtI7@ z?iVy84EU-rOH+}w!H+an>mT%@=2G~ZE>Jyy@Q-NnT4{c+U7`wDh5ES z^CP|fIWm_Sf=pYD-xF%IqbceAW4pB{G2Dd*_4kdEpc>moi|_bo@oh-^eZwqjUfmuI zGG+?DsvT)q@o|X=6GE4s9a9Bj9T8K>;`6l0x!4(a*I1qriw5yNSRXKl%Y(y6)fPs) ze^9uq=dfG2KVu$#Nq8e;tbTd`iM*dkh*-R@ljym>fBNCS_m4qraa-i{Olat|a5G~v zUL#~?j-@H_s_;nW1cnhONW$*S`>1-G@Kt7Jraqzq38-;{34c$tH!R@B?I!vnYQ%+T z_iYzwafNudkTB{ch7zavgttcB2V*}!YIMXoT@t6U20i~0WTVI8PGS6LJ+*JtvH7DX zVSHS8Eh{|}rtFzRz)&W_RzaqR7Ehe0Z7Y2S81|@_n$Jt`AtVNb@!49N!&k)Ra7@L} zw}1JFFoimeOe}gh3$cc_Sdo=&X-?px9dXMKE~oou(+8I@?nA)E&Eak6u%zwzT7Kue zusm*ge97YFz{_)fbDWbJ4EX(X&`(y8Y&RCJEu#e1^6gD}JQCmVRWH|Z@(PlBX2wm` z_*__aO+H1l;lDaowUs<`PHF})|LQv@oiKE{HE5$L+L4}nPWnXSSV+4;@9sqUGtvnS zBms7t5oexLvyGYY}q^&66IS@iR z@)R4!QP4x3ECw9OD{{Ek;A_z1g}qzdPM!mvw_voz9cyxgpK`Ls5V$1oA8@IY)ty+Q z>QJ@qmW~?|xS|#nblV$JwSY7z7Keo5+(O(eEXz$xRECaA&l{5E^7F@~Izx(_I!}sx zC%m1zVt#V~u%;pQjA5YSos;&Ukmp?({9d@f1@|`*+XB1=o<1RmLd$4_ytfm z?1p)6Cj)eydKj@;kjVC|YBTZC8Pn?G`SfhPm`?BMWVO-ScAFUvxsC=YL_sq? znvPt+e>GFp(FK+)K^jvK5ntTNX3XbL*9nDVIUD&bVn}V<`4V2w|6AcdXRe!?@p)bJ z==9uh8(#T9@`KQRW^|^)M^`W4f1Mf4oB21bCA{3x~YMl)zkRnckDJxjb1!Ot2@mAn`M!am!(zEe3Fr|#2cf`v{i%^L;y-h z@xh+Z02ZRh6btsThFLEI^}aAqHEwTNf)o=S@Qe+p#{A+O(o+cZc1T_QlrCDYt(apL z+rCkMy>MwAY!{o*DEnyGE?#=}W1>jB1lvW@gJ~uE1#B3Roq6ZsAv?;#)MSTpI@3qT zM`tiTDt0Hoy5-TjuGZ~!RNr}ODK8ie8ucHTGPIS{MQh_M3>e92 zmzu#;-b1|pQHilM@#-=HT%4s(y|cSAIWt zs64c!rNb>@AFWTRQG>`KrvaGSEtwBIxq!-=Yq#`?5uz zt-AnHtrxosjLsIE`2iR0mGvi?-r`h_QN1zppId{g$<~^xUuM>|Sc}vpVn+dY(?#Fe zy$ZCD@rryQp@_4o`L6z9V5>l#Ec8vUThu>|rdJc|1x%*>|EYc|K+&Aoq8BM(Ij6&N zEGcV-_q#B52HIfTjG_j~E%Hh=7$&y?^mvljNoxWg5mqPLp+c zm;}H4uVPoi#Zc!T1&iD08ipIjnOn^3yMYs;^>!Tcd=t{wq_h`zggo7$L02|M&&4_2{b(iEZ=Obb3 z?p8#ek9bg~8ON7^^%~YFQ)CT!TBLFJ#19xJtQLYLGD^8cQ3*y=x7Bo3x-p5mdqZay z88Au`Osaqa)QGi;ZL;;6s;6<^JX%C%lvCsodhSz?R6odentMxD_01|>&#ae;v}_5+ z`3L7IoN+Vqc|koPXDsfsGt_0V1802a%HXjf)j9y!RS_zIL|~BGVrmpzH1}A0)cUc) zt_c$#Y3`_A|6%fq{+HrWe)XRtuUy-D#H6@9!dbMoTS1?%UQbNk)qmEmS6eFa*|~kG zyIWiP4l3D8!z-~~#qTiE0R5M)H13wGXj=|f0P0p!Nyzi0kXfuB@zI6q_4DON&Yb`# z2n1?K<5=O-ag%f?YeTdA3ewXROi?7*AnF>oQ(819~z1Pxq2sB5o=$R?~rph0#b zv@OJhZS3e-VkeJN_|Fq;li4V4Gp`3}R6glEy?$K90=!^u8dG?lOt8>1UR9D^Nw1%W zsXlYOnzuu>9dil6?wF|wQ<5V9df$2sCW#G3eJ=(6f)(P^AWerneSsm#6M-U28ncBw ze+yCT<0~RHv+J$@q}Zrglp(jpdrU{Rac`et??=1`J^Q*2(XY6Pcm<1xM#MFputMzLl zd~(~JVh&6`2MD_1{w}^R?8Sht3qUza*TCr+p4*M>Yk z|FX4;F?w-2y=>(rFjo_M1JWjxCtIsT95>$@rH=;-JQ%8{%$5?S=m&z;Cb%1Q`t3tb zB8Jv)p!7EVvmwt9J|huDz+AW=Ot@lM$Ws6qBiJINvqDnCa{{D{I8el4%JOgam!Uhm z*D%})k;6n{Jnm=QRz%)#L&)=?e~)y3!4og8=s!*4y(2`caudAok=7c>mrZa7Fo4BW z*?Q?YRlV`x-!ab7Z;&|{_wX>;P4$)Z99+LgO6}PrC3cNozi9nW>!$eb>Ev(G)Pl-b*jSy$Od)NA=;J5k$z0S&J0lMSL@exD@L5(1M+7Uw_BJoIjQQ6 z;2(J*&o0om-jg0PP+=>kTuhhaF$E54%rFNU^Su*gJDuP3qxf(7jnVHsH@(*!y-7;z z8s0;THd>y0`oihH({!ZJGFcBxYlZ)RNj~KHlmC6!lh6I_InkwArvljCa-f_youqwg z%m^nMYa6IKI@HS4yOl>tJ9|--e0rzV0CQ8T0oJ7it60dR3vPCyF}8u?qZsOpKT30p z`Ob0@I`HgKlw+$HSaEcy@i=Jw0q0QDlfnST$g6rcqW^9>E9i7RaSD&6okmfG zG^@XIQDZZlv0_N6bqYJD=x~>Cbc)u76}CI0kN*4mZMkhge{@c73~d`oKWZC0^=|6X z>UG5TLgh{!7;#h&n<^nvb8mEfyj5e-ZI3s80+v|}&ZP~j^c&W@`k@8tX!~{Tx+-Wh z@R11b-jC*jZPYe!_amHR8|eS&@O9m~S&;kNN2I^LkLK9I9lAdHgRZU)qAc6MwU2b$ z)c`4Lp@G>Ybeab!a4OoNoAcL)xI1XZMjr^t9!SI>y`y5MB^tEi9hG!1gHnxDF9IJX z*ud?XbjlXAm>+Ev-?xL6O1r5tB^u@0jAE0$npU1)Z?WAg@?k5=H;NJU zq|my`rdIIZia*&=p6b%tN~~QwBc9LVhPa5|vnh0g*R)Xl?3&1yY_6e9D~mk8vf_&{ zXGy7{TlSVA?bGFcPi^QY`NH$dENQ$#)cv-BZ9QUxKF>*8NSgJ=RPZ z_zSB^Bbr>wSqv3E3Z&|3AG>!i6e3)8E8HKjq?(XeS|9R^4j|2t!Tf>(pI7m*)&;Dl zaJ~zTx+-8SU*Axp$dsLG)b|BTqkXV zZmqdW=V)MVKl+=Xqj-_Q3Ma5`FDbGJfZGB0b_I2w(vyml6jA3%&L031)775>Y&h>} zR_?~~&zy;12PTAj%}EA=n#pnlImzGcx~f3uhX77+C4iJ?10l#5>2H<@2PGRF+2jZZ z{e!z|ARnphh;UZIVXH)IRF#O>-xRCPKV4bXTb}&11;)KAg&)CV-Fzvcmh!T<3r%P@ z(P->+x-k(r6c(m9P}Aeyt^QQ)s9swBxMidj>no)Qo8d7F_C*({x%um?1!O^0IVn-3 zX6D2I4r;uQSOjUUCJt~Shj*EGj%7Z`zlyl|tCQAkmB*dGDoy`vMSp2*tDr<> z%!+;*d>*yP*c+qz2EHY&Zd^SHu*Z__3_iKyyr~@ZMS*xa$*a=a$j4$3FL9Hl9W_lZ zC(spJNP&?cT4sCg;c8E_#E}r?PL0~=Tz4J1p{Sg508oXMI4hdRe_>E4&5X^^+ddnhI3+3B6QZEMNjB-Y-2U1wQvk7#YSf%6}w18V_PfgJMP z^^_T`R^}cK+WTDZYlFiLC^xb@$JV!gPA{dGIhL)%VR>WO>h|l))=@gib&#>$k$t3s z7T&!(K4lz zq)jis+ZyszNNY5C&-y*vd|FP&t{Qq|+ z;zOh*)wr^X z-XN75m)EW6$B^@`RM~aSiFB!>jhW8Y(^AHw(~<$F7HyO?u^Xl6ScQ+mxNw(r|1?Do zsZkG42c?)AV47K`BZwivXBU;Viz56 z%>|4p(^Z|!AH02em2RMG_G#(z=NMjBJBfZ?4zT){&OzauVnf1Es(c9t?SI53Yge0m6NR$e z&bi6BSk)25!M9w}&RrMHB}4hxI+X2os*-EVs1iJp=2UHhN#TGVs%QyY5QOjuCgfyQ z9prV;C9In<#r6#>x2~Gnvh+5f`1i3m)sM11=%n@%KPVUzeW2G)i=3|GP3@60A|H$b zEjG{I25@1$-U_;6J=l*YpEBL~-dx&$c5j*6C4wAN(u`P=5UkhmT}v!cH$J7sF((KG zMg@lgh2l>jVZwuHX^X(a#R7FAebqqsvs48IK|@LHsMB!-v1f#p559vx5#p<6VL@10 z^&H+WT&emIUl%%OK7vmQiL=V^W#REz%ZAu|38BG7y-c^5)q!=YCHjE2(+ zfk);TRBh&(c)&d6KzhN1!RxN-*u(KaOagWY(yOpz-s83nPi@>;znt=J?BB4g(WE*a>D;)p zd2o~wdpF*0^$qkhzIc5~>&8t;-*q##h+dM^LTu(CPg4iE*Oswu4Do`3>86PfD_B69 z42jAG8?UM@fn#AJu&4o+s_J05fTyM%iKcd`ZDSoFfE~iJ`O2}$g9?ss`AeN0w%-kb zGAR?)w&VK`*6laRE){b@4f&q4~oVDS>)G^bH|pK|Xc~6$|Fz z4q^X-Wy9a`%Q>+HXt8@^U0dI2Wy&QaJ}IOv)Z=Bsw1w%4H4tI|@C#2a%*JM6*TQUD z&~qt7SaVK*hwJ#kpMiNo&`1a(z%DH@1wEGo4B7o5ZUszZ;-e>s85!CPDlH5*pHJf& zfKiTwZ3zelSc&3N&~rL~cqZ$PV`o;s!)PjQ$NJ^g+=7t|#%Wtgz_OM63|jK01NA@PW|!=%1*g zJ|Xh44S2cm@?&qvE_{I43?cjRbck@Mc)S7^3c}-~ZBP0CcL2nWB_Fw!OW@MEdEId^ zm17}N0IVxl@cU#c&lbc|-dO5zElnNkFlatrL2t!2sWoR4psSXj#9D8gou! z8;Y(>hYA1K%W%!dBHVevJxF`9ku=0G1wD=4tFDWZ+E&oll4_mFeJQD7i9P`anxN;O z0SIlPNi^9L*6Kz2#qUWa_A@u-`e^+o*f8I2L77vmAb^C;OJ7O})2_OvgU?95$1v_E zunn`aV{naJenXgGOn9GjQ0^%Q4eoImsMRlHmKob%_8iy z3^%g{td-$$9^8hD4uS@*fqk>ML&o{S`{oyr-w*irbsry$HdxxPZR?gtfjefHkhUlV zhlGiX+NiEUL0n`?duz}IkjNMk3pSkj$wfBMmzsxhBLES_Le*kzRHdI8NnN52g*=Z5 zFDy={f?nax#X77LIv3Btv@onXJN~l&1HPI+VvTQU+=dGq0UnP~QT_CY%Mi#_+i`#= z9^JP9ev}dPoRx%cs-I7J$Um&*ol>Rq0vH3nkl2~STaLg`jzHCA!lEU!k~kl49ajGN zO-dH>sGuqhLyv~3S}c6MM4O)gw0D}H2a!c*I!WYf$Rqifk&z(sg*>MK-gi2m;st0= zfcBI^($aKA$_YaIyM?Js?~h#*zA{Ti9K;`G-f@wT z39&7{0!-7>sZsQ39UsM~v`1Mj;4_QkTU!J$J`P{^L8)}{Vg7pwb)CM6GVgE4nmN`H z&*`n{&n0u!+;vy3b&hr9bCPQgANn`MLqnUST?WKXeT$lJ_S!{b1cXEYpIRu~|3nI& zC(L`ohVzAsPmHI|NP_Cg#nBmHsnl@#B|c9}P+0$D)`&Xke;31$tHSHC`$zIVo6;j>c4`N(dD_fF&v_OVohX?tf^GSV1J zkeDQV#xKJ!2>CUS+j)l7_iwu3mJCt1K2XO@E_Y?l!ARFX{r9vYv==q)ya>BEB?np^N8 zujhCGgRtlIJQm1rp*T2SF%>Y!FSE+mdOdXk;*y2PuW*o85r1$A3I8l|T$C6C(vB>L zb;!bqdb-qCrMj+^%4vPqRwDhcz8Fl4f0ZDlg-fh70yP_e80C*@eICwl1Q51(_ecv> zNS~g4a7i2p_W@6PXlo06v!eXZ9S=zh0fcG*q01$QA^SYJ{_C(rBIUosm6rb+CXlHn zB{D+lr~%38tH#NK|EY1nlM9x`KiU$^>oEYPkbW1xK#kAG@&)Y&O$nD{`Rw+eljAFX zb*Z>WPIPVM>5`$Rn96K`^6;RlhlufUJ-hhVO$Ylh{azoMEpA30pVtywj>LBchg2seJU0!3!Wv)0Ro#uQ{SYYSWr;H4*B}DIk0G?P z!lZyQ+Xk=OTyl8W44djt(4Ze=$mzhlS3qinbP*DS|A`a9GDze^2ym}dYFG^SA_fYpVx5FlM`?&obPy+(s@OVUG zKX|w_`T}zne1%*&;PQ|(1?~aQSKwfUHeP*1Vp8ROkx^O^<8Gj^mC2VB7JfRY*@*p< z6lw2PuzivAL!B%SCQn<*5!18Z8%zJv7b%-@_K<1T+5BXRLpfH5^Co3}(;D6KHAFr% znEu*F$+?SBd{gr5k|=ATmF10~t<_q~AwG`*vn8gJ&0k9lIGbPf%iSz6W4m-$R)Eq0-!vBI~$|hx%kPxBAY^BHm_!SsfCGOQErVr`AudOZ}gi_Bsx` zS!yDzszFbDaF^>)>4>v`f%RU>9d+eEDDDRk_8!?sQ>(zXf$2i)D(fGh#1l{qr(9FG zQ!W#n>%m|hFk8>MNXx~3Z5Uf!5T=N-rj8hR;^;(S)@8Al6S zp2-A;_Te*n+mD~X0U@gz+{~e0s|KEbw!wG1pYp|{C@W<#n~}x>IbVDu=D9&+g7Q3K*N9LI_b_)s+^>Q1)wof4t?*n=RSsL(Z6*Ph(~gdnaahj?1xZp zjPgRboKal05jw9s2;Y_~qu?8|sXGBweyC~EGOF7HxqLX+zT%HuRG020xpscD4YF&M zRA&|dG4v7DZEziSFNLvhy?D}H4HNQVeWZAmo&z3^3-uSdw=MG|<_N(N+u6twfM;?E zofA0_MGKJV^eebGe>~}aLTMZL^U+8SKqyygquh!JWj1>#TU113bt<*(zfw_1!JSWwNmA*?3#FBgM@qbGwDo>`SMh4jDBCVsTSx#-%7XR^XV z_N|iXaS;I)0h#};<@wb3l4GXhop+PbD76@&OmP-*2|ajU`N+>&@vg62xaskc|8}9# zmtAU6rG&`9BA1H{oDmwzm?mtStb>i{E?{6J_kYI#!B(`hm1BA$-JwZ_Ft+qODMiZv ziKD?L@W>?sQX@wTF-I1Z#7~w9M}Y0(#Yq;_7XLI3^2r&70?w&BRFopDlpD&Y}(%l;XjCG5oG|KTD4P*APQm8*5SaKRCGWYm|f4%bBvj~)h` z1=iB!mnDsXOw({@Gbig|-JxRWHVk-KsptDoVM9~U<2vEwA9ot2q8K7nhnI{j0TO2a zUW%Rfm+ZA&CvYYMJ;Uh73^?!uw_#Z?QL+P?Y6@0Qjq*9?u{)X-i=1R3l0`UpgTg2a z_{4&h&}6QtijrS4nk?|XsBaoh_wMkez`|x6>FqOnF^$C2b^w-*)SF-vpE!7+k7Yri zlt`IxCB_b?$=d9>fbJ8e>3{+I?G}5a|XI9b41m>5-fODKd>i@7(xw>ne4a!VfQ5Wx0aP0?2|=7P`ht$&qd%m z$VM=yhNC;zRyNuQKV0#K13s^a?o_wVZT&27J`3evUn0j%ARR=xnTT$1;9&>S{^%k-c<=RKZ|!OwaAk=jq9Vb~ zyTcbx5J5W<39_g$4uYy>!u~%eg3KQB)cHUE#R3RUfw5x;pxC0)Um2nhc*x!r#Q`R7FG7huzu zl@OMf?Zi#FC28E!U&^@2&?$Oc=B8wNKB052wk}MVKasBKWMF_-9Ld19Wo{hK&(&(Q z(Dvi%&U|gJ%Qn;}ydZh4oSLoNj?|$?}!C0rUjc~32zpgp0M5LIA zWP|1__3NgH%P8|y5(0DL{FPHy-ftapw1Yi3>UY=i-;7c2-&9`eUnL^T^tzgV>w4ks zTP4em|Hi!#{(hxIWSD=u-o7>Mh2y{dGhFu3^QH<`ugt`nw{JbLY}YN-3!2{)ko)-y zZsB}gZfv22?)#h;ZlM&m#v-cJJdN;Xnv0;jbxCJ-C6}0b23!d;LS-%QU~q z0os2qBhWJ4$V>a1f8(N-mf*?k#ACpFe{~)N_2OtoKeC6yzu#>LjT?1mS+p71dnT+s zJ)_l&-d(5UV%q{9 zy)fa0$u-ZyX)p28Ef)}&*$xWL2+q{*_bdq#qg{lawuV)cjjd9Np-CY>=l47kBwtCc zx@S(!A0k6)*py@dKzkiHzm}~l5{GR$_VG*6^ipntPp0sn2y_pl`p2?zX&hCSOi*b#B>>`fx0>>hqO1=M-0_6 zCpoc7EDuP0{S>iA;&_yyYKxn$hnX7bAcyQ_lN(J*7nKlOO}kMweFqganqtpVaB!Fs zUjaw?wh$%mh3AE2qQw7!D>05!;?8!k6hYi3#WIMR$QFaCDY_Eri6MEmq*rNM$Q4gC zk!ukHXQ$+rl)9q!gS@_-g5y9{gN6EoR`46Wxjxl)RZ?wyxfx}id{Dt%mDqz@;ixF{ z+HugT#zPZ=GxQx4=AIW5) z+qdek-hdiWF|i4V(bhxYPEv@}wo&v|7o&Zl{4QKyEboWwx^mH#nwbTH3nk`Cj8@U0 zfTc=>^703qzqm-#1K`pF7e_tQM8iKR&>-V~S`YTROiHs2@Ii^I;n?<7uy;d%G#Iy3 zr^4S69H5fGmS{L=8hL?fLKzU(OmDNn0bxb}v>I_!N?l4j1lBaB)Wz3MyB$YUTE!tW z`a>xdJeH?}9K@`^VPEmP&{?2oEdD!$4My?ddS=`?S0Mnk2du4Kx1X;c4o-ce_~-iE zB@UA!lic?e?w?sn;5H0x=Sf#se ze_;m|B#LS}1u6>J$V8{23D%APe@p=RNIYSun!uYXCWhv5iUwlT{W+j?{dZF#Pe-_= zga4l`feQm#5}>6HbIS$o!cX zNb4^IY$(g(s2Xsy?ndFGUxtJe**_2nDZsHU%IPSJ z?Nq~*ob(N=&{)B7>y5Uc7IiqjBx;6PtLAg80nc<`5VGzptA-~of4}F{iQ zL@@=3CKc`mAR6#sPS@}O&jLTNz#=_xPSi=h$G0hgnWJ3gr5Foo6!uDJk|ui@MD40N zA}kuKn)iENm9TD@TY)tYxo}y+S-*kyq=3+SgRpDUa9d*sX=|hf9A06tw>Cp)pf9CD z4!E5H@F42u)sB%B!nx&oeGg7nDv?zkB>TrLdpQ7_d5u@Rhp;KVAk zXrL*<@0sI&3Ouh_(CZwpfnx!~wJ=QMiK>Ag$H``N!@~Y?+y(f1nocrkGT?Cl$OCZy zW5C_M{~a*Ni?Ar#)I7?H>K+;p7N3UUFyZ0QVaGlh`k-r^uy%7=qAmb=4tzh#zvIN? zM8Zebcp>k@&HCi0eJG3J(!uxV_pBTo@)oFjz*Zj;dN*tGRKXuz7C2Z9orw+LT2XbZ z5Y@~j7t%-7JK%U+1%G<$*LIpG$B6{pOGdm`sD4QwwfqE}ThQ8JBAyg>y`;yPLfcD^ z+Csk)XF9{dxtsr&zkNXN_gEuXAT1DFz8UtirH(z)#+fL8k&|(M5&wTj8*>y5#s^q2_QO9eM3#Ttqaqrd9!h2a#U)%FC^B@SN+^zmfuXxf4p-R9FX0 zaUv3zNyFhFqTh2Nc(`=rg>ra$Un&6kFXYJ!$+$0Fzq}0Wt_v3|UY6fVNwTiwR$TPc z=B8HC-B1VLxek~1T}bBs2ab}Ym5i@nA*RU4VZPiJJtwdHLTd!K-?qV_|E3_qhqz^h z7^9Tka!uGuPQ-5F*&2bI-B{cZ7wPv*27w|3ryGRz4auxCD8jjrS)IZUujWki1~E7Z zHyQvHsJH{3G~?UJp9Yb?q^O78s2AoWyED z?9yhH1hS(D|G}}jnH+w$kD>&0?-VwP6CnS<;gI$=5LQgT-Y&@v*4*MwtDYQIJZ>lY zRgU8VxRne%)ZR{$gVURb4o+`|nn-(G(sjMs`tDApcc(wDbx&!EbCGT5yE`LbK6b%r zOWiXFRIuI48p;yGQ*a|dtPb0uqP2#LSgACg|08gD(gRnXfHt`$~7z!`kLWZxs%4G>)l zLIq4N#L^WT;SgAdAieyM%C;VyKD5~2ptlw5RvTrkDf82uDE87q| z0koju5Id2~)c^=coaPn2+xDsLpsyJQ6Y^9AKLAhIaM}C7;z$*uyC}Kc64Nzn?dxl& z_u@R~S_j1T?w05Vt{0DLsEe&L_C}1kARU+)D_R+)_m!Z{IS1^%uMEg1%W~1}Z|%h5 zL4R$Yv~+sAn^KN)w7Y3#9$YaPU_Q0y0l#_+4+_28O}39A-p55EJ~w8=*NKB37s@t@ zuh<{=zT!3lbj7fG?C@o?J(u4rtziTKb)^u2r*?r_vN_e}?-`4MohK|EX^LrYzPxGTZtgX6B`pE4MI z6^P=*)L1o8IrCdd)gTwXy~&>Z_GV<04 zXLMkgTNT5&&%mJ)uy{W)z>yLcb2X?xL9R5b5lJ| zY1u9@4JE)PCUZnqN21(Ic3Z#aXGszMH<>&D>w&?)x@K|@fs;5tq~Hz!)m6Y|S_^3| zBtx5Ud-q6Nen{qi4@sVB5Dwwb4jL}j7R@nPxv+GRI9yAorK909NQpb(Tz@w; ziQ8zR+!U42ZA7%5GE~=gwQ6eRJ+z+DSZX8mZ0(NPFKTN$B4+&TikR^eq#oCA3&9yA z;Z#bZmR}_c0Rg*C?EE{x;(>G=QadD6UR(D4N5}puT*7#)Q2&}1KP4P|Z7K<(`1v)B ze&W5|nQX!&j=}F)2yqM`H-YM&10Hz4r%o9CdM1t#X1tz)R|z$*=i+g~Yp?646@>zx zr@h2=>hrvF3U#Kz|4~IBkK|C>w&s=K(4r0nJzow+9gf^b9U_jdrTz#aL-dhDjwJ7U zVes{7)LW7;<&9MQsxa@3IS_UC;TyB?lw+YcYT#ev5 zZ#N}!Wfxn$8*ZCg{_ci2Z!Z#e8Q(A(dvWw0V^wcrxjy<6pL93fyCul_Mto-O#b&uL z#=XxJanYxiyF&)Mm{h;dWV}71o_b(%$%5qfT95f8k@cyHN_y!Mwqd*#OW`eGO~Dy`+55$XSN6PXLb;sezl`Zoaz<;-+`odRGy z2mnZU)G=SsuZ@oJr53^2xoNB~x_^gBadE9W8UUfr5~cH|eG~U(^1;>?Ur>zksbT@( z64r;L1Eq?4Ku~87lqR9u7eV29ua9Mnz0t-_*A5sD%12_0(D!D#?Sy?(@}fQ(V-4Ub z|BwR!oBkIU;D^?D>AP=0_#Id?0H}*bgPD$ot_Xgl7~cre9pHxr{4ic>;2w^q*u|Ia z1V`KLLpZ7j9EHIP4+Htwd&2-6O<8qzht0I|B2_%G5Lf5=+^vbG;ZFo~-st{R zv&I|k!CrZPRd2$BT5q&F-8`9qFqrP$1Rx|45T-@=Snu{y$}7K(pd@>7kvak}RDO1Q zDR=RGHx;2Rd8aQDcm4-UWxcozz>rP=mRw0TfTLi{*%PIC0LEyTrU)ZgofQXs)V8Y9 z&$$XN`TIo2qbuN4=-CX+1 z*%N(KObrBV;Nq(;mOJaRaxc5;xpvnR+!~jGt8{(frlKd7#M@kiIx>Kffn43G0E?Nb zEkeUimps2n|7RIjAKO$F#qVwVy4QVR*%%)Kx7Th>%Qg_$0{bv=YeVVQgl$ZqqQ+%F zQcPwbNP_#rZjdOS8hjEB;1`U|@HI+Z0z=XP`Uf$Kt;A$V2u@?FfyDybUe{6T@4Qwq z+T`@ybI*PEzIWe!ALqPtet1#aSSuB`#gx0T8Y!kAlc!kQSd2swGLO0d5J7;DhI0&>YtC%@Y;>Iaab&Z0-~PkOxV>_senHYF#k zV3!5nHOMkH05Fx{EyV^i@I%exMit)iDc~jTETL2qLgnA+lmsit+E}zLj>nD~&w(%R zgEZ_fFmgy!_b*M&Ad8LYQ`-Tz{0s)_Lb= z=XYMTmxVssyW*l<2y-dhB1|*$I&Xew{X-abb}3|k$iWN2NnQ}DS7kA{!O~us<$P1V z{CU04g=yvPA&)xH?+=Q&O%u|KXd!z~#tv}i&4>p}h> zJ)&ix&kBiG46Yb#m#!#hS1;(1wJg>t%ITnh+E3H9aHV`P&sT}uA+{tofE?!44izwS znR^+)K(!OTJnh8Wtw%L-o1%Q2T#WG!tN$M)xiqP)jWfUnOe!t$Qui@?eHcfA+QzsQ z)>38Lq_Q$@aUno=T5y(tFP|=kXJSU!f;15`z*P+4F}O7JBTemCbIiKZamHR1EO#2P zN>|1Nr{~goe?objpe{}ETz5Gxj|y};Kh8~gu7vV#LSxDW-;G#VR+3PvpTO8o#Nd6{ zQ^~E@B73kJn(LUS3zJ$UcONg3BDlp*fwYL4^Ek9_De9}EmD7e(K;c62(DB*6hnGmC zs3D5Z=B`QQ4=jF?nVFlkE^%N|`FTpCf|UZy0rhi1nsnQn|FqSp+kTgpw*oUM2fKO3 z&TenLvJUWiqF+&ddcrFwA{n+hBRLKH9?LU+g`5LVr`KQ5nd!QA@0y070GIg1mn8qo z-dg|Ag}U)BDHW+q>vOI%7Wt+hk1deSmU?*QjnI58myez(D8*!1afw!4A#;B^Qi5hQ zAu#uySR-M|ZNCLa;H0utzI&p~dc?cSo;d>C-`rhx{Vk#Kkhj}@01g_XGj%zz;3mw> zPI+lhKCh8i^;iH)+R;6349KrQqR^V#yF-jl_;2Em=_1&&L59>7Hifc8lw z8z)r9;)2bbG{u$IxNJJr>ieV&v23MG{B0o(-Hqi;+>ZJVP(8{H@P;ZTuI<XJVOuX8XDpzm7z#!UgVVYaEKWEv_ zlJ|!%XACibTUvbw@_J&AdwdIgcfp|w9WsW6nFRkU7jz`GnqMO z-kEu4=AD`MHmB1`+0Ro)E>n21&_U^KiDik!m*c-kjEL2WG_})I--@(IgT%M`W6EOx zx18Z6NL=MZVssx8%e_c^y05jT{PotJrLUKZow^IsmN8lpQ)eK)AZ@#!-ZthB7$lzP zN1_7CecO*(3!+gnYr`m+fq)Q7?%$8tr%Tr!IWM7HU9Vkd?zQK93F(?LEa2Tpk9yA7 zNo?$Cu~(N}kkrZA-r5CPF^n>aEHtW4z97ZJyUqnB(Fo7+|9S4UFBp1;GGZ;jlY9bi zhbBT&0nJoXuh9g}1=3p>Ut2CfGO2Gs>Vi$`O)eLYeQ_OG^SLm3AbF3RDh}iaHj!Mm8^qGRLPW>N2$~MoEM~7&~xJqQ!fJKW&v`Q z8Du?8it|TjalGI3^5>7%qr1=JDZWBT8YK^TO-tUi-5v8*o;*J)-{E zhA$hCj*$8F#`Qhn^(Pw`&TtBe(~eJXz!Pq}Q2Ork7#7M)G#n>-2u7hg*o)2J@g_q=?P9)0>X<_1Ep+#lF zB*DZ)W&W|yYKz7<1x*d%_156#cs|X7w;=JZlxD>{khor0rO(IPAQJr*d_wTm6VHq!#pc3hS785X?LEkDrYy!mzdzqCZCf)s7qib6Us$< z7EpNtEHnsQ!b}`lO1mv)`tCxrNn+vzfL4_ut*RuLi?txJ(TlXhN@xy=AA6w|?RhDF zl1{Xl&0?qdOGt~Ob)?e^K4n|%S5YVI5G=ZmIzt$gd{v3q1_+T&b{+nxhG%%cr(DQa zMhY3qC_E8T3HqTPW@KKFQYZc16TS}V?AqUZRO_DkbS>1nu18h>u?80-F}v^kqpvFG zQCd|HVmSzG6BZBqFyO^Vm}8reh$QmA&L`v*uS<2t)Z$K*?sL`_!IX*0l!ol#nEw-?P(C>(tuuCA#Mf{P?o*uAwAFt&u_AF|Nm zKYcl6_(Ln7GcDdi>GZW&RC=%6M3@#k`WRh~CC7^Og;xw#JEBFgFTG3+Zx{<#{H_g& ztZ$z+vADxJ--5+Q`{STPZf`97$HIG=a3&WhO|AvXD91J8Cp7T@f{ z;tM{R_^QO{l*Rg5QceaKAaQ~u55$KhERO2$cjZ{;p+;EcY8d`w5U#(A*zi!qsvvz9 z!uJr4KsXKI5QLN{#O7>3tTQ#9%o9rXd*=9MWyX6im==TZ%sxz8IE-zZ0$wOAGrz zO6BE8YFjw|7b_B<6Jo*^&3vp)#;>>XC@m8FIC#2boGbPOty1Q=JNjC}`DudfEH-@N3b&SvC?vG31Z9O=Vy%EVqPovNbEoFEL^vU`1uJtTREpVW2Ht2wxWsmaAq|*}GQw(U%@iF|7 zf)XC*R>0F}->iam;hk`Gta`QtTtuqFL5mOhuwm5_dBNMJ;pcH~f#3`uk*xRC@pvc4 zE8SR0i^w;nz~Ndd&P8qTAB@hss`nyRI1;a>u{cE-6=9BgsUI8aO}{%aC%G`t04?5> zgf$WIVXsMq-c?O%4FkmF5l{(Jkeq^At7;#FflTTEjaNj)Cp9+Akq~22&@ag=a8Rd&lVaY6L5j> z_sD#lBZNn#MGqTz>M266z5UnCjFH}!-0b&63FT2Sc#=>PrNeiHSED9|Ztydm9G`4; zyC`v^&=!@3O9g*a7TzvoMUTM$5=x>ICXMq~G&Am5vQ%it;LmG@Z9e<#&2TQS1&N>Z z!>J`6>=#{mO$?9RssL1iKebt%OYl+)`=T}M9zRZ1@N1mHCr=Dd(b?`b%JmV>w3Upz z7(ugsOM~9Z@z)kDvFe^cx_t|g_^6;5K3&-|$TiO@ro?8UYPcS+6J8yz%Xwq)C7@uG z+U8Vol=zQ+l)BG>b@cKdTz=12zOR2k;tAh)z{=-F=N43rooxYc9uQ-UUDGX6rSib)H5XW(|@2Iwuv!%(+A zCG3oe!|w@AF`CHd2XHPsHaMfpi8vWqgX^9WZpI|w-GU-^d}tz&zM%mFe@=;^LRoB* zK{}CaK;ohkNT+C`c)SH`)UfG&<-@y>POib6Tx|6r9o{9^P>^o+3A~;5G+rXyjLTY>>Xq@u4ajX#WIUV7tH)-+ zP&N7vn>-Sn^YMwq@Qa#mH5KQTdDq;B34Wu@x#k6s#nvGBma#v6s zAC>#VO{Am5@4aYOP{}qE-regQsy4vA2vDegs7yViSpExPV&cStvA$&M9ay8Gzylc@ z20gw0`9%Uc^}}e~^oskF(x%F;E#N98Aj6XuMvR z2t0wTjIybkW=h#A21p>oi{MNlGbsuKN%Lx!criyGF|>q1xkX;%9UNK1m){Gi{TPnJ zS0&1bx6|UggBbSE5|aX8W_oY9~siBS)7%&oN=pW z(sz+A*aF;G>p9^IZWMmy=uPe<#;*wPYsaU&0-$UYBPRG5F%CkEFSJZ;RX2w~@i^=9 zX2dB(n}Bsmc&VV#jTr8f@J?86KoSoQh7yGsztELD zj{0J=piS8W8NYgkuT#e1bHYH%C?#jPsEy$VJ?{vaBgf#Eg~vwfsFG1f*NzOKV0#x* zmoQlT#xGE51;JQ62UXsplhqr^C zcvy+*W|AK8>Tp3X)0 z4|M*?@2T=}OZ}e5eU_zcgWoe(n3z5RPZgd`pNR*AZ`0!@yfv`*Pmxxg7)nQ42z*BX zz8&Dz4K2S)WV<{m0YRW*Wc;;&s z`scz6jz;neadi1Fb4D}K7eApR1*bl9va*DBt0=5lQD^=_iq8{UG`x<#2*iSd zStF8q{2(|OJDavh>eErv%DbkFXqlsDMqE5dhYJ%jvc}0v*BKE9!iPGTh#h&IEl5eq z<@A$s<~5t@JLKQ4#3GGx8yrQge$T6|ARq0?m{t6e`tIs)8{}!)b~vfL*qvr{HelVG ze2AC!OfY@Us~jm^!(`VR@2(*0Dqd4&);3sj)CFQo8h_J8-`%<#Sc@EmUU)E*w_T7} z_H<7u5hkErdUaJ#K25J6!Ue4VwZKnuL(+>Ksv^=0TkMdSy!-~8NYSSuH6$Vucr(1Y zOZpG>5V54J8JHCgi{*VV_YG<|J_bDJ2VoBeQKhyCYJUl87n+_3E1*|jmWQ_mPq`?u zc^!(7wu=%|DdP%3U{4XT>@2i`#Xbq*%6pB02k zd3auB0+TD;&KgymQ%bLygQ;$Fq}pm%^tWxUyxm9!cyk4}#*Y0S!OyMHmtZZBVBT6I z$LqQ%nvmgA@oC8Yi=UkHFexpBMY1JKZG$m1_oC%rK}^zd3SXOcO%OMtaYd0B5Q>59i;GN$yE5Hby zBJ&S)%o19L5h81WErUO?Nwy}b{At`h2e@GK)}vq7&q~ZKIOe<8%dd$v6M@Oxb=HhW zkC?``n!5^?cTX=|!>o~sv}_^9nfvCj&IsrPTPakINiU~<6kBle-(Axs&WH{1mb)$$ zY43iUD&QO~2EXU1pV3yYUeKe6tX?t1Fn#_x(uTw6|JEus4XaTACC* z?+XjMJiHX^&P%!MW+M&jI5+PbR|4Pd%GsFCX8{u$Q{eZ^7V-_c;fLC**UXiFc=6Nw zBcu*sD@@CpYg^A9(Vtt2xXha(=)9P`>?t}}4qrmb?-@1N zX;nASRt?`_-BC2C%b1o~j#7Y)4k{PpmDg72o>lr}#RmQx5M9V5LA)1_^?MQqcSz40 zV-nj0TKuHFVO{hlz$oRp==)WPd|NL_J8ml4h!X`+jX60uywppc7C4F>H` zR4S|(P%ENTZSUX$STU(at!|U9x3*d*GPG_jrPDp*_l)Z|!kSkU`#nB5tHdI|=OEdC zfhruKDA_O!SXUT>-eFZJIj<>VD#QQZh%}^xkf>R-n}LKQ35mw_5m>~Tdxr>2-Uh=plz!d-orYP7lf{LadyO-7YpY+36fI#g z2jh;0#RD9=YjG9$}#(VbYd(Q^G)?Pt2r&|yOGIGv63`OH9r>&fT# zKX=bXklWve(%*NI`Y8PfCmLhxtv(FpkUVwry~huq?mmr%$;-R!XiBTa0OMcF!Gakb z;D|pScon#5TW{H645f+>)BJ)SCQ`RTbd6kHtFYZ&br_}FdRHDEsyhPeo;1NZRP}`R z|8vFP51x0;JBi28PF_^WN3QtJMUBxpziSLWDcl>U#a{|B<2AM{s5|R$&yCA+TW{v! ziY_^A>rFds8#DRd$ivmEi8hkbPwwRoYfG=b2yy{vOb4sYT{x1cSQE>%n<9*!O&*AJo)-KM;2Lh9f^o zM;be%C}W4D=D-k;0|dHUXN)rH#GBQ+-cFsa_r>Lec)ydPK$JUZPocxw0M=^jfbBfd zI4;B}9;2l72Dc#*j zAS3EfM#SaKrC9UIRI+=e@_+1J10JdGS1Z>*S!dJ)HKg%diZrsIwsj@v0y|n<4Q*@K z0cuTK@qp)g-_P-|&0xdEf62hP8j)`xjXAls1oF+_RQ`3DTrO2=Td+nn`cE?ya|alb$-v~{`(U3>+K5Mrm}`x=CNFMr3;PXr}ilF z+e~HUT}3f-B$|WC%A>ky8><#^SQ029CYFwXExkmd3`VgASUTZk-;*j-}9Mw32<0wk4(IT_thnB~>1rzgDcB zCk53~Uge!^6SY;{3daSVWE=q$P78SsYWIBa#yjzvkzKU>u`=wVri1mtiglK(GARhg z7o|@NjBthC78)3wxxVeNL;f+Wq5mG%^wn;#3ad5>03aX9Ok?MVNd0Rg8+V2_TQw84S$%nPkyUUuX-Q+z%Di5quxuC;I zH2CZR5WJhH3|V(PJCDV}OU^krhKBw^0KH(}-(94_|LOZuST!-m_CI|G;{2YM`X+3w zFW4`!_D^qcr88DjqDZM=lR5Iq5O+(gkw|~wM$A-JBXdUsd9Ui*-WP2^dbXoUiZkdN zmaN8F!Z9sbvHix9)s$9p?PF|rFMJ$a3R~R-U9TTbcm+*(A=vIFkfjYr@bWK(7U5Z1_A-nU9+Tun&4Tk-!pO$gJQ_Y7JY=1B_;pYLM9(eb-#PT;SM3Mofzm(E_RFOV4s4eA+Ypo>K$Q zavEOC4|qzXgfc(an*7=K8o@-Qgb)k{R)|v}E{3=mVk^W}i0dJ)hxh=*2OvHN@wwpg zUb_Xj9N>MTAml=bhoDaNd%D0H*e)$uZCePlzGMXvNdCZ#^!oKusp-5FlBW~Vav;Lx zUqYHZ&jDNQ#$w~BLC==H`r<*)tAYPbeJ@Y*dp7!CE-UZteFlLZt>4o&xW0tqX&$(_ z5R+ty!@S8dsQq#U^(@kc_^7D(oW~c&EMjc#l`=TajRm5Ld8+neBhFqYJ!)Ji+89Op zI;q(B)XJqj7;^SWrM1_bNEbiKm~y%Cw3J+RS~7&k8|)INu}dKug^!NFIa{Sk`3gNL zu@+K$q+!#4bs}wb37MX~ew0dI9+IMSTjx))>*i10XR%$g5<<9Up#h}Lr>jAF+<_-~ zoVuC-6H@hX+3YFWn)9&l4T()CrQh>~Z{LzA!nft@t488SlFpjVnZ?tz&T?aB zKMpb@&D^T!(p^<`+Fh1G&(%Q?#CrXs@9%2cNs~~<6 zm_0&KM9l0Y;sObOTS-Uq~8Sdjx5fC1@+!z0QO$5WyC2#k)6~=u2of&OyQ* z7Z}QOupn5C@wiynU>t*Mg(l;3>e{ARYBgWpyBDY~fxjM0-`)G?e$Utep&&nZ_RePi zEmhfgP&&)_DGm5Tn5sU!1EpSU1#>z_RB4Pj(T7q)z$(RvbG;}PrkGb0MZ5BVb$R0JFv(Fc!q=O^L33Ba|Dbtv2;WGP~p?67G}J5hXP z`kU_B!?Mql)&D2Iyc?<3*Yr1Nt^2GWnbI!&Y!xg*fqCTAvHof+8!+n^NX&zzU@~Zy zq?QyAj0}7RJWuhTaz$`IxZ?T0xgwj$vHp&q=psN(t?Bnr{a{f5J0LN#?i8BMZNU!^ z^QUT0QNL%Su(RO(BxF5jL?Q-pDH_!lg&j+3k{_H2CT08vEij-8pI?}OFA6Ufrr~dd z{e=_DPDxJzqQBJ~Gbvz~M&bqOR!vRK!dQZpe({^8kGNAriReV+a(^@ zaSG0H9uCBB2N~-^6Dj$rkjYQBeGL{FB(9Lsc)W`~fW#;IWS~7j;wG>?Dq#-TrU6eq zj6GSKENHl1`J8RZYr8ORSVXj8o#IibAoLsuc--)*Z?-r zj%!v7rHHQO=K}E`@o(~^Qxw;4M7Dg zD6_F)3#hP>mg8e=ogp-hj<4~H%84=sB@YI9ZP1PcpN*)TYfVF+PrnV@l2^Q0bv^YUID(#Rh4M_yT@% z#+3FGZhhE8j!1~Pum>F{+`6#Ij*r|1x}#C4FK_RZO>3omY+iwAXDFXyyrT1jJ2Oo0 zIAL=e!n&OWB4()F(BFfUK#=%{^CNd5$Vkt$2f4YRf?hOhzIT&1s@HB~VN;c}C)|s| z=6mbiMB>I-1-@Ko3UpV1@AuJsbTM;%2 z{uhU7oXNfRg|_z^3wpVQr(Gx9>0x2cPT3rZnMk$ix~{DREsK7CE5SI4pKmG<>zR)M zYIN9TfI{xa)sS&OCAIPynj^*DuXa&i!FWdw6PPuX^#y-_Y^D!+7*H-UCU)UoI}t?K;XySHWW6(!MZUOS#Z*HtkoZjMn#Fruz2T09+VS1 zixa2PA*gE2|s|JO0mfo8dx zXF8Q`{{%x|{Pb1=L!irTJPmGvGcE&W&!2N6`lD_o#emBo0cLjYGL3I#50;At_JUfF zWcKCp8w+Vzl<}9ZgFMje_D`mrqXSjaZ~wJ0*!h-}Vi>FE+U1Z+2FXJO6jLr{v3Q)` zN~DAxMfolg%eL+)BBf=!YzpVmcv6LIE2$XR>RmXSe*1IiX%>6URq;Mziy=&bfKL1U z(10qH&q_;dB@O7n=j~O9Nx9?DBfWLf6>1!4`IJLQoh#H^HJ77$(R?zYQLTlVMVcK& zWSW?ctN@CaZ1T*uzq(OSre26p-T=F1_Zw3uk@g4hs6V(dqgQ)(mDt z-JB9u)WlaM&S29j!rFi~nJI;#PQKvi4Ltb|DlaO0uUjF%*Z#ZfRE*>z2*m*Xf@WdN zuMRx<2CU+RVN5SqO~H0j6SmTM^e(rw+DR53EIQ?P{3VG|%>$_c_JlboElpG@<(G}7 z5_qcW&c{iBcnmCMo7_Q$j&@dbVH$~F+Sx-vIxQT~WBZu6>x~2iZ$sj7dzy%Y3JQ~8 zAGF^&W-qv-qF@K?QFc)vp3%-UFPPodqErH5wbYx=5cB{!e`t<;oN8$}rN)LO2JO(w7^R=|$~IePR1gztZBg zlmhrg7ZljWy(?3?ncz#{nuFVr=4Th|Z&g1zw6a;P_QunVcU{Tia3)BXk!u0Bw++fb4(DZaJKICrx)d{@6{(glJ)h99sFL9+eZ1`+|SB zFzv?!-HZ+GDLf7gvAkf)NxVC!Adz43%N~9bG>GQQ-IQE!jcTpbtPHI2>!evawu=t? z$q@^x8Mzw=^7R@{0~OC#w`OX(02$I0**|s^eebGH9QIKvKf}B3&X2IGMt}&iqv+c| z5Pon+(Gw5-V&KC9E>oE|C39pidOn_)^I?2^s}4>vvX-O4r|J4i19+fmc{6Zf&-E$O zkMR=&P|6<-+3yv~B&=WF&C<7k-3Fm#9ogNmV|=#T^+@*bV88!zt6-nOJsIxQbX|Q$ zW-w^TIqmaY??)*oW02Os&t3N5vPqU9kBDQx8H3%wsl3!b$r*mzb>z3xtKPY7UUKX= zepTT86>`E~b-i=j2=BfQz&_SyEMawFDVTfb_JczB%n9L!GP?U~TDXl?8Gcg)zjHfX zm^U-dwg=qU_8gghOBKwBK4~c!8aDE1OGg}W(l&$7)z&LB_<20qQ3BlrPgb`fWDfDp z0LQo>Ez+?P{*Dp9lGgH@`5Ugt`z^k4TeXV&O|c4a3E;WMFn^wJK-qo zv$vf4Tzyl`3KM2&a&(}t6)%Gk z2W+C?98;ib+GL94X-E7@oQ*Ohr#e>ELgvd3Gc}wyH4l3H!t1kQCfxBWb+iQ-gIsmz z%$kYKK|JPbt(52;U=n}5e8;7NWpT8RxCKoEi%aNb0!gHvbHdeGS$Mw?Ia?F?8RYa{ z{sC6N10ZLR(w_-Mvy(=?=C4vbvjBLju=H}|7W@f8m0hA8B7p3E3c(@ z6Lk+QRCU_Qdta#ad#(-25>MZe>IhH|2!r6@RcB3PQqi5?>VEnaiFEL=@F>J+7J&NB zKS+vG^iM8EGr#y=;J*j{A1@YN@hQNfjb+3~B}OCPB0u2w{5qJC+3Wnpg;Pk~Uj^zu zTSxDvK_^7(jW+S~I;;aeFPP$Ba1D(30ZebGR0-3Y2u@n+lY#e$0mTzcjbWcj(+(_L zvYBiq;M7VBFfGOhOCwiCHcu{#TNzoKe&bpvH`oQz$pB=E*kt{jp8$P`WR?Zwb_L3JXHt!4I8>+ zt@}xO^T-_jBU6;~9F%xG(4WWZlAARF(`%wN){+7i@RWi>rf4S_CzhV#B4Z3LTM>Sb zVGyVUlrpF9nCl?kiEX9*fX%n*j!E+H!TsDarP=BlitxdUD6rWb&VL+>tx1~@jqz# zz8$9afc$^_p56h{K^1-R2Jv}))Gyz1#)WjU12O?TcfgSj#3?($`z)l9c*ZWU4Z@O?iS0B;O{e;fcm1mJ5GM)8211uA^sPK%rWUG#XMVI#fc2C05~0Dc=l zr2ZRXe*nTxzZ`&AAAneAmwy-qosaX&ct#`JA_M9a2GV%B4HB=D0-zUP8Yu7-6jwM9{Bv1p|zSgAT}(I4|Nhkmmi=sL-}I{7IFc`qTKI!xrMB+I66+RbY}4g z`n++F{J%2zlIfb`Jn%IUIsd6SB6QhvE_Tbp(UJ!77uwt z%20!v9Cg{jQ_UK+HQhpq7C1I#9jO-1N|aH99?glomI`phx(?*G9;)bscx7NWW~Ojf zENX>Ik7{(|p%hJyLIY9dDa$yE+Byi9C9Dl~D=-HKphZY{Ok-Q$Ov)yf)i$A2wpGp7 zAECtuy>TUS7^`A%GtE1yE+M@#c@0Nt@fK_rW+I1x+Yy}@*%2|dhSvk;HC}2rsPA}P z?{U!W8)!-x^t22t26bC1sPyK04Ll3%SS?`xL34TU)m+(B5IZ4m2kLAkogp1r4T!u1 zF=*2Q9oZ{fdQ3yPC87VZY#bttd3-`lGHk63pLBVlY0%T=W$rTtu*(T`k848b`mVal ztSDIxqi|k0{P_4d1Xf121?kFrJD#CRDDYh5PoUN}p^-NPJbyQyFT6Fs9FG@n&o{#b zhb+q%_?XaRnT|ILg;izvpzuajRp@(taKh@TAGsPzTp{?Y5^$1`ut1L|2qgLU<_0ozA$@OIm-N}gtlZ{Ca>Vi#ljd$l7y!gj%H8v zO|Adpr=8c7H&wTwGn9u8)pK5$Aj@FdmiAA(5) z_ru@(NRtQkH}xZp0pf;!9Z1zfBL~X1d@Lrko)V@mO2RF|)A0ZC(N`DADBDN=eJk}~ zw1UdfKDa8g*FWToR@*|fqDT{Kz~VKin&e~gUw#ZJ4pNr_sSHS6^fT^6gf)c8z~T?B zwN2|lyZ&em<5q({6pPh<9WXKSOQ7SdCC|&iB@&nz&AufZuMxtnGe?_iBH^T^96<$d zn1Jm8{&F2?E|@F9D``FLh=qW&+^!&auYe$IvyQ_vh3~AZ@asZRO=05C14LStJM#HG zKshmRH26Jof8aVv9k>=AsEHT;QDX$h_z{bBp*ueZFF1|e>i2B>ToT-|F@j~WoC+Hd ztcxFws0}#&RyIs;V6AM!fF~Y&-)pth1B1faS|b%RD4ea$V+K6$d$%szlKoJBz7?gp z9K?U~5&t%6wgFFE5C8uH7aXa4y)~4#^O{9vR-@)kixt|t2E~_U;MIbA*;MNNLBaS; zDz#-$Sp3XL3ViIhK9ik@7bEuOa>SNBi`eln`q4ZKs@NJH>5zD>U-hU-KtamtFuaGuc7w^$rYLy;ggM6^V2D1=R|ZZ5e3sU7(#7>(Z=SRwA*-ch7~= zjN)tdtBpn&-s%3|Ty}VV$qsrJX%-h-i@CqMaN3Jbcrsx9^Uii@k70+20)^HN(=$$# zQR^h-dIlh0MN$T!f=^v_X$u1-klym&CBjV)Ly=id&??oQcbx+DtX>) z7Q*2iTxVQbVm(v;ogHkzHEOukKsEt}C$}bS$h}%w%zHgIfj%CCwr4uFN%J5scQWp6 zK^LWM6`9STGLh=R*b1Zl@?xugqslsBqq^W&A23_7*Ivart&O`I1=E36paQMtwZAkf z8#kNOPVH+E@K){wI28u9KAu4AD8m~F@jvDL%oNvN!4KFxeSJfYnfv_bT%Vb)U%K(C zN}^8V?5ZW>8nGll9n*+&u5Q@fNUGT!XygZ%eq&<6=sG|S5Iy41@l@$KO))Iol>QH0 zzW|-(!2*A@#&}1WvlF~QZrLM#G~Q7J(g*AfcTI4M?rS^oMc-+%jCM5Kt+UN_EEUzV z7dw~sR#Y|L~!+OOL6*w4!|~oqED2OnWME znSU|cVpW{t1+r;PCA=TQCOLBunpVw;9A>pF*O6}64|CE>`z~>?;w-MksJo71m z-vIDPb4=2neywruD`DPO`Xd^*6;ckg`=}|lz3P>{uP7TM8s9K6&b>>JhO_Zo7jG#V zB8TM?QJ!stO1^G>OJWS<8t9N-t2ayjBDIw!VcgFTWgER=DOa>)(F#<#VGK-#(s~@FWh=M-u6gqZA)ztaqoKl zNU~M|N2lxn()4-e_{v3!WkB$u!2=X4&37ufA0(AsF8pwl{qTpIL7VzLpARs6UNhV| zlgS%$!S7;-Ju}~#q9;ezo3golpJ%Ku)U66xFFjIw>enz7_SMk;o4?ZNOI>2=1{);S zOY;q^PNlH|buBcM_YPkURJN!3CFbrXNLjX2SDWs2R zZUGy^fZfaXBP0w>8;)$S2A8Td+oeYg3>3$rq2CHhk%Qn`9w-FnO|R#0e=0mZI3NQv zDJfUm6v8v9dRR_pq}y95 z-Hv!#ce=5Lqf#pu2!=Az=C`gggk7 zAfV#fqKA)8e{MGp-XAalvb@i;MewXlu)Wi#;H?esue5{zgr>hpN

      Fc+$R=Z<%D5 z^8kBA|59-{3hI0Wa{4_8F2&)oO(xfcCoLb;B2H>qDvm%t7vXIBJ@;B9I0!ea#FG@~ zE!KX|O<0Y@$H42UYCeo=M^;v;W!@u!jkC90XZ)=pvbt{{?&xFNYM&d}}vlnzY zUFdiriOqoPO<*w}6sT3HaFt8HD$UmCc^S;rNW3{fW+}VxI;fz)OVkgSVS&Hx_dMS} z#NQJ0C=%y_2|8>F5`P?&@zr21W}Lc>U?t7b)#breThQx(Fr>KL?|Hl*S(((kj#pB9 z97YpLg$t9qMHXFMx2qo5Yoe4oIT%z-Z^XhsSA`9`4yA|@nFXJV2TuvTtHACmM6Vu? zD}<@5AEBmug%4J*#W#ht7ym~_*!0!HS1%^vBH@=8AH#aVyhcOOKH-Tqt8tTXZO!rpuv83@!KKjA`>o@yOo4Vnz!BrzQH47LK?sQ?3iqtq1Q3(rlCir9iVr5Zs7X z{N-@V2H$O6Y!v`f0LV`QwGiRr zT!VkOX9H+YeI3X8LJVci*EV*@gW*=tTf)ZmalqWazg~wm!nf<=sLVm(#`+2c^Ep{d zPYRPZOb*{afOVibh1+m)xUt#?x4T~5kYzjMM>_DzeGWY4Q|`LRy-~3#aw_5?r%)r) zt@J3JHLh7_skVqM5!S{AK~kL#U;Rpbhyj1u+J0h7hZcgb@;=B|5+HdFkm6Psmms*6MUyj0!g6HK?_%$J^euT2m zlLezMfe+#2`W*b5u)KaO{$2R6{*g&$px4`tdm1QPNEx{y=<`s6f%`GwbC?Yy@=xjN zW?&5AsuhvlCC}y-lDkx-P;HASOxifpR^&@6!MT6346}YEh1e6DQ-M-z1~NJgd=8Ja zJFPR+xGlz-)x6gf^<#`Rt@*v!$dX$wH6P52u6ip~Fq9frng%pd>{WG=!y=+{r}b^q z-fm32*G)0+b~AXV<+f8+Lg>igJ!BcWjE{hY6NRu%vOKtK33_aE!!9dI!4K@R=&X?q zyFvUzSIExjgPj28407wNK?S=kW^1A4G?;d~T|&jC2jNEYtDDl|ynSG*12^0WJQ&ug zEv8Mar(+RkEI{H?}!O)RKgJCl)CQBqwM#_g?=JY)M5x-ibBt0F?X$8+R! z{|p7{+e~Zi-@>(*gJ>unr3o2 zQY!a(UOgGn?1Nhl>Q2f%g4T&)!E+1Ioksh+ZdT^={LTBY#J>4mVMsf3elDn)jXbh} z9y=EjV0MEGsZh!54@*qEtXmnR5iusiS`&L&QEZ*kiblD`8;KT#t?CdQ=9(^DT2~IuguLd^Y{x5LEQ>;`6dc9BahJDCL&R3;c@YBK(NY^N@GzmKju(SD3Y>0(T4V zZ}}Ln5oW$os4RQ~Y&Q^cgm>SFlWhp3zIfy5@R#5d6JGeZ3&X1#@J=7xgPpwfMc7DN zwx%gwILW+&|FIzVpA?C8-Ry1a|kS2`58NwW4`lErX z{zhQRj!y*V-M>5L!Tp-c?aBed)_@hix;Kcf}WLLO%CN_maG?cv#=?Yw+GI_bJ>vO+lC9yJ=eP_8aVC zQr%9I@lJdl^-y)eyx8{|kNPC|42~+Npo=a*K80t00GeTt+n-|>gEH#&1Gu7YVF8tA z?2;R=$Dxr44Hu0__ti~g&VpquzP#C_yo55rZBO{-FG;pO`})`_Xby94^C+{^0dUi< zxTt3TzXU=#| zo4&J~c_p9=kfOq;3NPrw1;c!3@Pk4E89+CSI{!f-vfVjpXZiQKhcU)3+W4mHYd5Dj zYSela{ZqQ=5YDUU#a?+&yt$8zSP6o3gRc+#qX{ZXpE`g7>l+3rP+s|+-~bw|+y8)F zthd+0P;9Uta8qnm!4NWiqH+kCeB>K8_!=N%BY4B$^jQJ#QGX z`HwL>Iy4I7f%c)q!tVi$IY z48wW*Ts(M0bNn{gr<^Vazsf~TtSZQM8F;0O5Q)tM-}*qUM0KlbQgX^ElINX%*mJ52 zIdIp_l{`E83pmNM9e5=2d=@@O23%g?`)BZh0S<|$`s8qn;Dy=_Yo!^9AHuitF2R>V zh+)398MPAA9y#v*3GZ9`5Wv3&|3mo#xO<1$;9?i~%p9<}5R>!_xFw80URMR4wD18s zZLbQRK{)vLXX&)P_P`rJ9bDPT=gY|FyO0HmdGL8HY#C}G`vhtF6euc4j{3iHB2FOj z`xE4=SvI()5ejbBsoPr1d%+qG<6ur4rY9V*vRwlTJ8}jiu>=ZagVXapC-mM8)!hYH z@!-jI3Yqgi&)48<9Dou8_%0TFaDj|0QlUq6WnxpTmEpBzU-kscBSMnuE3KcK5?;_d z-pSkexk(1!-3dvN`A|-!HQ|N)J2bt^#5qiNFvN)vljnFxe&CsHotv^CF_E!-lhpOib*+*=EmZR#gwm*v1G;Ou$yU0Wo5cg@V*lwgrO z#lF!{v@q~*@?q|tr+ENz8BgEyG!3Mey=gKzQ8Ib^$-qcBSu+;h^L#jvQjEk9P_86H z%=&a-Kpf^w5&e|5Y?n#-r1Lgd9_8(XkkH6N^C44SYX+|b!n+GaEX|L@KJw83sdB?W zXjyn^22gw~RJ&#XYa)w%o}>Xv69I7?5llh!yguObY#ormOjw_bM}7es5@bY`s8jgc zZY}o#oDat#5SgITOo)IJZN|zfGF$CHuY&5$;fpF;NK(~_I*Fjq{SMh zm~Fb};Ri@zq}^2oX0SjWbsu)ZzhS9B*{u7|OzP0#6WLDsa!%O%W~?5%(G1LBUJJ1& z`dpnveFMm1u*JbwcAQA#_gn($+T&p*!SQB#48`xX)|r&;_$~^sGs!N=itDUzz^5$L zLgZUI4A+j|O2HR|$KFaB-weVX6A<%0@DF;;%Xu7?Pb^~?0)-sd|QZq=Lh_zaP6J<;YN0+MpovOLNY1%_GBb{ zg(74U`4ZnCj4^|}vQ({KbI;>!5f1Ii0NdZCJ)4W8O7ogHxQjd8Dzol1#X6jeH-l#Z z)}nf<#y*`A&v=g2c@JwR(HVN7eanSvIB|H=O;QP-Z_v6q&eDu@3vDo%)I%2Ezpgn_F zL(*x8ZAyi^(GZl7-Vg7hAx?lW`+j&U6S1MA5nBkM1;T6yRS=+BG!^pRH6V5$Jii5D zY7Y3qz;g=Rqn`crqNfpX3-y1ku@xBVHD=KqMQ~sPaI&17`!;{%#v&N3i zT9C6S7YUXRl5Mj2fDMG9atMXqPcN$itgVQRw7`ezs)zD_SOl0Y7)p;>xaiMgR;+kF z-#j&CAv8VpDRAXkg4mKjA=V6W&0@sPfj~ouhA;wx0CukMWkcmBgJA*Mj6}~5CD2&N zBuK<97KZQ7&T_2;&mRcn)j#jYDa*&CEQhwPu7yiQb%;G_AId)i>34+Z_s^5PdE0Np z!qxp6LEO&@)PV^0M^J-770K{2TF5$}$5!F713J83s5_7p`W38<$&g#|{|(p~xHNg~ G3S$6yHoMvY delta 22036 zcma&O33yXg8Zdm$y*J72LX&PZU1+lu=mw+C^#39p$IA{LsAwg z-~wD!XkA!b5L8H^GZd_?qK=N@BrHy8VW^@6TF@I>$ZgU#|9euLneYFe|9SpA&&fIW zp6xy7yyrddcCP&#)#0L!wNcn4v{RY3xH6=Tvj`^b`JtA$vbfUirj+wYl=UKUoDYe! zdz-tuR%I|i(5}%g>-tfTC;9MeDG=e=bFx&*|Oo`1hLx`MN7G;U#!_3jv$Y91i zex9|KuZ02(6kxL2_%-Og^kJiA%TQ9Z2k!(s{fG ziIary6j}|becU0%pqwb584pI*%M*IEahUrFsxM7kSLsG<7{!3 zxKj1hcx$<6&yHWHweDRw6UUa(9;=zYyVz`k4Jw%Yu1EkcvNTMSU`65zAJQpHX$=ye z^yy*m*vw|J!>qT8dNQU(e^tT!GaabI{uAn80c_aJY!ZooK^@@?O5GWP*he8mH`w)< zJ-n1-xPW)Musmesh{*v>qcZEtO_WVti3cQAH6`$&<^*f6yQ-LN2(cvcBnY2{sFidH z5+CTzf_Bp&v>d+@GM}2<0?j%hunkyz#*YC+M#37l0f|T=|C9YN7b1HSX&~0J92V85 z7;$$KF2Q1@ARCfmqeZEo)~j{nO7+hfxN(+oE<;wNfHqzpRfw83;?m;UpcKdTJ z_(Pt{eJIIF=`*Xa80Q11F)iNhW%Rk$Tpni@T`}->M2n%m42v4xFjh^;ej5@){RjEv zl6L-aD;A&ZON3!``x4+k3Esd62CB#xKl!T6|z#j$;T?p%I8s&}JiHB9*l2(9}On;ni=6{Np}@I8cM z5LzI71fet^9y2DwOF2RYGgvmGRT zs8`#O!%YvC_!-{+)^=nW%Jew1gKwq@4%M)X0}_+m9;|8WC9pT$5VxS_>?p*Jy6G)v zxCrj-O{D+5J93L)-4#r<`aIVrp$epFm5>UL&4*pJ$26o}#kas}j+XMuWE@K4 zT!H#6fbJ{AFf^e9kBa6`Hsj%VVy1Drq~C$NHbyjhkka7#K|;nr{jb*VphZ&t=k53E z-;xX}*gkbSv68|fjYq7mTo`J`b)`1$iPZ-e{=AX#6jDgs2oP_Ql6GKmkuTu=dLRyv zj}|}gWpujd0^T16N;sN~=T$rw8$NbN^AV-;s4uB9hcJ7Uu|b zv^nPcK5VEl{qDjV$&CRiXp!y}=0ztxTq}_cplVQS8NjY?N#i)kxAU|WX;e+5Ex)^} z0fyD{N);vE8DO{_uo;j0Wywq%;E;G}AdRbPVmztngjFt%_iH#boEBS!@1my+iH9dz zyg+bGJS4=$q_Epg-GIJeJ3JU;8d3=xDB%4lK(dz$FUJf6uIflk0nQd~$E3%G_doR% zL2T6ji3Ffw9-ECn z7KRLsn=b(c#d(@6uM5b0o`%bB%5PvewHGG6}#(jQ!m zL|(Wybb83Y1~iScN+|KXFgY$0za=b<)8`%;co8rkrCoHXG?e&TA4)su#Cm$wS$DvD z#-F}sACQ6bemU%_ET@q#IgZ4C3(axn=!yXypggo32-Y7F@V+I)sz>3If>}L{x)dku zQfJ{CLbH1Em~Z=W9c`uRDmN*Dd!mAq?V`jR{jyrp>@DX{+hw~7deF+BHWt88J{2nGr-ADB{-B1|=Ugs%-HEaWA!J0(K z-O)SvZ09uwN=y~b#*e{Pp+9~KZWkseq-Qqv->%;b11F1snyrAHqi%}k7kR+EY2_jn zqIqB+xA~X>;Q370nV`)U`f(mRHY}?Xwug+2Vk4=eYB;l<;Sy!B7bY~?`80?5d7MeP zvY^Mm3fB_G4S4`In8AT{NK1($g^`IV2G!|Q0}@xBLV865#o--Ts|LC{u@CrVyG29%IE2BonJv8ze4X4f{ zB~JU_gAzt4p}AkeC_^Jv4~<-<;Z(sAhyPPT`JWQhNcMk9>?I|HXNHYkxXw@bGIAiP zLs2SBZ+R^DNLfnS=40n1bW8!{y`zP-;~PVbq8)m!LCT;&5lSI&d0uvMpX&f z7nJzHDM6JqG+I&eOFbp-@sSk)ngJuYEPRlXOU>~KmtzgU9SqTw#uxgK#%lcoz0_PH zf71=Zgg9DQp~=>c@%h}p0GlGSP&QS=Oesgj0L&A7NUwj6Eb=eH=bHJ`pZ8%6eaz6L zgnFxeaBxH~<;w4cSA8rY!^;w7#IMofuLBsUb*V`KWfu9ayX6o+2D|xZIO|FPRZhar zYKI^{h}a@wxi$`eDs0w{#P;JKYfocr7nbVBMcN^gZD7QOenxy8!lQyiA5C591O9WU za9PieKKm(ZCLArH170{WBB$YjKQA^+L3x{^N8cz$Z$#)!i0qP2s6`{ zK_#sue34!lMv23ujwNXT*%cu&BmMzr0O@v1RusvRwH)xqoXT(bYMHz=gL@6$4tT?1 z3#uDQy5IXl5EnjAhg0_b42@vTNX9z^TSjbTd4L?8(PD)1cV~n?deJT6s|;;y&OpbX z1K!8|niT=>0>5j-$~2>y)m*dmP0oQeIy*3885=lc)*nF!-UKu#g$F9pm02<6p| zrW+C=yQd{sdQ^gpL|C&mgq8AeXkQSnWX4B-*_R8P1)Jq@F~Cs13+r`E2+4XbGVgda zw;0Ei|2lUx6MNwkI!f4?HEJSTN_$ik)`#noEq0OH}WzEq)u)hsbg6iy7t>OrcPRC zUQal>b~(Nn@P64G@V?S4EFLwhWQ%%W-M0>Tx~>%tJ|FgE8(j`O{39;hC+m(kz0Ikd zBRV7Gztj(`Cfg@Tzs#(2Saa2dVpBGE(@o#qwF+36v5HZ@Vp~s&G38=hR#46Y=cqMAh|_ernbiO zTLE}H!RMki{ociWNW(U%5Nk9Jp^-|*Hpr7KL{5$8zx|(L(}TrOvq~s142%0dpkJEU znBNrewg-CM=^UYzwt*gDNK(A;iXloz++0>c3eA(KG{Bey8ZK*8a$ zn$Af#CQ$co=*%Kx9+ZMru+D14TEzz0dQJIq+%=aLkr`#=I=`-&m7G_2!hf%aTOVyE zVujxF&d4kd^YsTwVER) z#pR){+_mir`eNmJqL`|DR=ZwpDZ}UHbS3SoukSjjWZPoPuwKP)H_|YkZ{5SV+wR=0 z8C*7SV)2Cm@1KOoT>a2bS}WJjlOMTolHfH!poWmg3Wvu`5O$17l2 z7akmwfWw8kV+@Mm9#Dk|Wx4aX{s9Bm4b0iAfllD9l?WKaW`wo|7|^*4>YWn!C`I2z zf`eqr^Bc_T;Z%`NxJa+hE1i$$&l$$#T!cj&DtvEH6{eTb>*r#s%N(ud?NDv|9D;n? zD>Uov81{ERaCz%7h%Fn8`c4WIbt}Z>a4H78UH2I%1pFy!%ogx|5TMpamxgL);F)vu zJqR=pJIpgH`n_>J{rZS9N;@BimF%rJaJS%TqWrK|Mq733X`X^(7VEYJo2RW`-=7#3 zCWdTYviVs;0CXx~l_NQ;A>d6Ms9eYB7IiD4D_0M4f9Nw+8Ds~%PXGv^n$S`Lf?2ei zL0=P1K=`p&UWPP(bW7Hdg*7C{7U_UYlW9H8os;7W0dJc?kDY9Lt#44T1UT=#7?9km z25Kq8=^D-J7jB@)P4K*1T5BM0HbD$v039i}b<#7-JEK9dYMiOx zAagRF*dW>&{e>L|*YB2+I(AEOEhE=2T>ta>shx_E1)a2Zw={HzsWU>S^lg#C>Xp6? z1C5?=Wm>E94ih?0N*C9TMQrHXS&YNp~71a=wZLD==<+J2zVdq`_TQT=RSB&bZgeB0N}TsDC12R>3|wN z)P=^_ddiOuwld{j*-_HY9uy{@+H5tzf>mjNL@9%evusSBL?v$RVkD?4)Y0rwIgN;W);}5z9o1PE^FhXA5xe@(u(`f@P_YHztao=q3)IoZ>)LhY&}RQ9 zB0T#(nFCrCThF~uaE7g?`;)`hb?c@>?r)!v{<=PyX$yAf{^Sp2>*z&kww`OB=(ec= zQr1EP1&nDn_fV^Vd_gxCuMbjj;6#mnF%a-VAgZhFr7u~+`9ywu8QsaCBqP;{z@h+3 zG5c^j;^G#|ma<`d6d!9G6>bziw1c>+-BgwsjxudVvCdveD=)6M*zOnkxE_r%iXqjc z(7Lj^da$O5Kig53s%>o<)~=lv&8KmLq@~~6)_a53I4FL`(ojb_x1(4q3%$6q^qU~L zNnA=h_JCS-c}c(b>)xN`3ob6R4C7^@l0E5>D<8fr>k*@m+wP(|7V>Qj6h{YaP#^x&8u)!j%4c)#(#4m+RHJqgtFMM%A{?gPp8*fB!Y zUsz2V(SRhK4;4P?PtwzVcF!ItL`ZE7#1C4MOh_!M4tPiQBakwH#| zGtZ4iT$NhvSEbf{Kwgjit{8W*ypxNcE3s9eJ~X5lB}L*ztRE@{P^rWk>ZC|Rri->g zx7JLhYa~#-pZe;cqiB)A3K!6GA1SgBfZGmnqk_6f=}E;2im;0$=MR91T>3~q8_ZkI z$~{>Axhu{+h`85WWFY7m*=_-^qp#h4Re>%J0vzLx0XEJC?2j?D@0di$Dmneg$w$cQ zA0$@;`AB6)gxnIcTP|9|%0iZKqz78WKsQQhOdn!Y6Mh)!DmxFy+&^<`3s&G487`@^%<+`M(xY_g%sU6d$N z6&VpQ2TOgkErPUG69sc3hi92@rez*5xQeKGtK-+z$fGV^m8O2aqPr-vcHL!Aa#Er) zVnsI%%F-%i?2J%-5AWhv*RGxbv&WL|41T%dqNxORg#o8A!Kc#O$jf|SEODKs5!FpB zA<*SpNP%Q)z?<%~2dgb-iIy?UlN7emweC7}Ls1zQ0HAoE%T11)w|wsF`CA8SCh`v? zs0%+a9cmuUrTAWy3LtNl?@(gE`;u?`)|$c(B-Y-3U1ynpA8Bp2o{OKP0BM1#0_Nn0 z>xt7?t;`dPKsNHd)*EX;nW60&wyyOvJ1M=)xojN{G9k-WH(p=1j?zi)gN*I2>=PBV zaNu4KrSA!Vu~R`4e(?*bC;yxzjU#m93y2B%s)EC(@M3N)?1Ca;yf$9a!_h zbr%vQYeM(|4BDT7caLD6oQ`)2%O{T-mO6m6WU#!1G&ih7Fd=+4X`rehP59enjV%>v zQ%dgD2fU@yGn%ZY`@H@AT29A31Cm3b6wt?)mG{`KKs|H5kUFxXtzSqeN0amaFD5)i zs3pm|z`9`3Wos?0O)i)Ri=<`i7I)M1veiT-Xsc=>(2!w}u}KZPiE&g!Pn$$L7)KNM z>0qPXQ8M5?(EBRJwI zQKWB>N{mmfS<#Il=YUk!a?OQwNh6KJUG-^`0c09@J!eE73V9DXn0m;G>i7Ywv3zVz#k&D&!D>>c z+&)!ROmtiMATP3fIBbzv$&@7PLMmAo6}9pB8>SRIVFK`F4>%Q`IN5MfDLZO1v=XJ) zs6fMAyE6A2p&fq?$f3%nrOa_1e~>?H$~gZsFIW%q!f)mg<#~Zhp3Ng{ZXw7Dq^cft zOj6Tu5M2yh7Cc)5r`=JS@7+n9n{EquUmifb(Zqs@ z2J65`qs@Z$Z~#zwEYdR`16oq~<;|j8BpM~gvkrYJ*(;DZ0n*<<`umEe8~H{g=A0zv znk+-V*93afFNK}OV{HB2kz_%khhnf*0YlVx6@*I$;Go4@Kuvt@swPIvJqfd>h2C

      kYlO4#Gq#D$4I_3+GVU4}L8CxMV&w*C<=X(Atbq38256qiyz6`^ zv)eh}l-Y>&zgn>{u0*-uJ4wF{XGXZlNLZxbK>E361=Bh7F9T{uEGpeic%puTstH_0 zmIl1iXJjNpIPFq0o5KdMfp%WwG1MZeq$~ZTC($W^CR*56k`{iY7_k>2RL%m0QX6vn~3Ow!IhH_atL`N%aW-RDvzR25T&cs$Li8U&NV2|bk461E_)wFxHV zVpUD#vDYm;RQlk;LZBKgORI`g8eqSDNQ+BgVn1r8_7Kw!Af6v&_JYu~Xg!QR;;c5K96AvU5SWT{_GLNHhG3 zWIZN;7*BX)Bq}zY@(fq9PMk{#dVV@AIUak7+f$tNlOW-JwMitG+U0Sgk)gT=xs%*U z&lIJl^^_-5IoTNlu|_%3dCH?#KIlB`G0^SxA(`c^YVf;?YNq^(aV4UirTp>-6dk8L zqm=13C~8o4x=KXMQgtwGM<{`Salv)iQv`Cy6?zJI*fYv6p;Xk96BRN<@k+5gE44T_UpVzu;fRUT~khi)^RPpYlAf90h%?R%XEe zlgd%NfO08=>{$Y1ueo%}Qwa<5adoJ8m7WRWN^A8c?j6fqi8(^%h;6Rr2*4Fw zO!IhPI|A8YcV$4%jFYLQjG-$lz= z*EmkkYk=q5Q;etdy2ciw5u_yJ`~z$D6u%{<8dzAoRprr8Yn4UaoWi}=r3ek}Qpn;Y zoVe83IF2Ji+P53V7JkQ3bxqgH#ZjSW+~s0sXp8$KG>4s<@!!@%N6^hR_nG=DlI9o| z7Fuwvx|3EW2#%@IwsdErhf!v>3q|Q|r=boRHPw#m>WWg^!aP`k>#im$eKp-ElNSEk zoY~p6N~XuT1Xu)U{(7@|yc<#I6{cyCGa=k<8!Kis(P@#KHI z(a6hgwWw06n{lq&O$N>gJBpb)Y@4V9uIV1kKr;9Lo&hpj;jVg)=?L`%CK!UVrRPa0 zQvMN+2G_&cZ3LuRjus-0%rA_dC=-r!h0?fotw}IVYW{}@(Xv`nJFD5CKfmC~q-{ma zE*+oRM(+)n={jwF%#3~c^A&_bg-TYuAC_#R>>K`=rB-H|qRpTeRrJfS)}#s=qvt1Ip~iwDFO)R2r+9V|IC-_f{&<`$V@z|Ac8PXR zFz(!`e~je#svtm_yj>tH>BeCRd^cyW>U{AZ^3yA*U@GdS0AXJ9Gvn~^@YFu4#= znEj#%yCxUzv0W!{CICLe=tuWB@q>3@TQ63!J(@}icF$7fbFSleH7gdn$VMcau=fUq zQ5w*R`75ExOi>jkZ!?-K@Vv0A0H^r2`x9YfGtQL8icU-;@r)gSWkdBQIM&AZ?(1S% z5R4^K=B&in!6mH0o(a=^vM2>+z<$SJFTA6o{Pkg-6r}=%V5S%uN^%ll<$;Z}M;ta4 zMoIBmh76pHu&N+zvMxal-#G;xthncFHqHNyf*)>9B%s zs}IR2Z4JpRZoPVg7Ar<@@QdTPaioJV4-?W3(l~Y^?N4sfgYSM1_WG9k9(S5JG%OT! zHrxHtWFly19GNU?w3AHLGNGv=&PK%1HGN zn=IgPEy0vQ;&~4`0xVi8@+nvy3F9*EJMIBUbd%e|Na7RuhbW+MG zJ@b!tlQsZrFticYC4+=4uR@V!I^D;9YkA?F+l9+c z{KmZye1D}-WSD=u-??4z!inGh9xVIlMN=uOR}ROTcWytpZ0Bv&3!2{)ko)xu9^vkc z%*Y%I-Ssss+(s`Lep7_Kb30SWo|$NS7j$v&9-Dqk6~>5nB!H6M%ApL<&C(zEZmIj9pl!XDKM+w zM{ETUV5e|%W(w8|A+xk&Pf93FYy(WwmWVW5uSR9Q`1Ax z$B;Hsk_cE<;pnVv{Dkn+EN!#}a(dd%x(m4poHkhdeIfSYlo6AB-AgTn-3xyU3JnJ6 zbJ!of8B|T?rQMEz_m(8gdpIk!N9u5seJV=Aj)y1UEaAI{6DJRNTVXfAh|;kOi5aJH zFy3~W`0yfeYS8HciQk;gZ%|HSxQsPXV!txP^@T!l5s9V3@JCXT8$mL?*A9+Wy5HPi z0q6UD3~|?Er&_Iy_`4)5dL+kI)etgO1`a;DHB<)aW{h9I24~7##QU@9Miod#ub(FB zDpFn55H(c~l0>qTc#X>@)|%okDJ^y22Z<`_yC}ET6nTyjLwgyq6?9Bs=M;aI81a3O zmdJlyovnhGT>7rw<0oUn(Y=;aOkvky3Gvb6^S)F#G zD)UAwJ^%oTsJV0wVjqX_cL@KS9SpW$V*cF07rhWS%tLGd!ugzhW~XXqC06gC?m!);xiJXRqRk43V5kN)~FuW zuWr(G4~S4m{IZ&<14mAp29El(YOF`YDa}@x53+9=F&(6A20UgMPIWr?9x>tLL)zxl0Xd`lgXvuEuqnp%4b<2P!%!e`VRdSwNpQ`Lwvh>8>FI7Vnc&X_Cf~{dSW!^cwA?AK zmhGYUQneW9D9-uO4M!?)Zs2VSdJEt}4N-ng3!<5&$X;)wa|XF%E&&W*yBc`>%^slX680A9BXMz2+Y^o+A# zFf!@w^?*c%jh%5LdtA&|GLc72-?zf@98$ay@D3j!z^mx4>%_bErGR3`88_J%U&5xd z0=+u{>5~x1{{2200=y?1(h1LsBOs@Q4dWJTC;=>uKZ9EQooOJ{;D3D8ol!YICK zXETxQ&P#UE?6&_j+t^P=W~6P`3F;k&D$j#ka$4XI#QZRrZ>LuT^J^jhNvGn&7?|3m zfQ)0b@*Q$O-`D%oIfBN!NNLc^&$+%BT3ZgKXSRP;pFFCfm9+jszYV2XoaH^vDq8Fs z*a)7-=OA@`V1%WvXo_ouWshl+>#DT-7%5TI85TAdKy?iamOno*r)WygtDgYsMibN> zMBI7(SAHGboYVS6$Eu_uE`r*MLzH$fzpS4C@VM5bm+9A*Se{x&E*;fsf?+IOxjZ4%GdP(Wad)l9-N-1zj9rxJeANZ99le@z1({VC~+mq~^)Cj&^E5A9#;Lt5e@eYH;y2m9d6fqtw2i&L846t*r&!B>S3 z;s2k#PGr3G-qpx{Y;*pAO2Uu)+B-tEGQC$*HbPuTV30vlOj zh6BIBE&sRQAo8qZjhx>**0)=F6!?uL&fU`d3N&h=i}CCZxghPfqR~^GPxDBdyH&;4 zgQK;&@I-Hp=5QAsdhKPLOJvr%dI4;sNUwY4<@zW{XS(#SBtk5AK}i+1=|JQfkHlqC ztb>elpzm-|a%&0T!oz*ppwtL>#{f0`*8S_ta3Zzf>_y8))l-tJC7~YY{=B)ao^&_Z z!4K}kMP024+&{r1Zdl>i>J?(53_vtwI`o{p>>I5Smg?fb;GG@9Ac|YSu}v0!+nw?h zV)Gj|@$Ax|zZ$bThII#>R2BsU&FTd9!hi^#aMPQGHLEfT`UbFmlQiD|6M^!ZAf*}G zXa;74T-2Eh{KBmP0&`m6H@FLU%k{rGR|lYU#m~azRhc$f;19nqyY#4v@b@BIMcRCf zxNX}ViKsvYF4q+f58%f{@kOcSqEM^(L16F=S0=NVLGr0 zUw&6gJ%+Qtb~B!rU;~f!@0K3cWOF4Pp0Ej0Sm(8WEvf7|Dxscqb%xFZgS8+M_NT?<8BhE5SAfZ`e+$d)J-H)_ivEViSWOPAHvx=?Gg)b)V^uuVc#eB35%b~ z!Y>FrpPEK>_=S$A(x~tJLg?}lRGlQ`EYC^)*HXlOy9}{kEl2D)AeXTm3-*tt05IsS ze8Pt1qwyz#V|lghm)^exrM{&D$K7zXLUznesu3|&$?cMumg#F>UpuuEXSvoo!T({G zMDO4_@rWI3BG(u@Lq@ksYbqi|E2H$iGGKGf1aBQ|G&iw|Z%l``<9oeslx`GXu|Mv6#bbm` zXoO8@hc}z;nfxAUmL>tDr+>O}`Z^ap8F1zrSF5zo@MaMOwD`@Ul`fRE!bR%+)DQV8 zl1c%}{#SQ(dS$Q%%6$BPYbc8zhAJ~%nS4?eNCsJgbwz^h%_6gFj`Y|Vg(ed&EuWMa zO|5;8B-hlgtZ{48$GQ}wb4eST-9=+uW=8`5jr5qNw&swuNK?1AMp|rWm3W}DjZUQ5 zQ~Xz`k#xUDwJSoTBS>zIG^Yb)9&%#MZO9M5pU*-JHEo%1Iw{Rhup}D9!~bJwN$@%o zp)ao`nI6*_)wtecmVg87{vO zuEQzhjy!AreZ`Xb&eSw8y$&}4jUL%M#G{H}Ja2*n;q0o|x8Za97 zdFB1@yDPX^khpOZ9*RpdXW!-R+ADkFs=H$#eHe;)X^sc z6D=uS)ez1xX_-J5!0@f5hozv{X=yNKRWH&XNQ&n+nkWxN#k3m{t)~o?RW0?JDtQO3 zXEc_o5ItM9z3Q8)s-}=>zqmuD{S2YQ{o4Yt$w@c~ym+Xmu9AI&;FxG04hFr~A*dk? zgMdn^iXS*$^jsYd`xsOYswNhW;0&Q_%`n3Uy$X(Zytl>2YHsu52tQeUz_ysn@tjI<;`pGWW_lv-{*Z94maZT;Pc)-c@$NR zsN`Gc8VXepBDjz>)T08!26@xxUF-jqD4xo%NNM|OK&?BBgPU}sv%ebt-xEGuI|{!m z{A=w@{JfC){Ib|b`sJMH0LHL=)T!atu+VKWHb69fIiz30;~ z5>j4BxAl3ez&H(N`+l+-dA+}Ywh1Ke09^G2j=ImA(l^LalQ}@*f|DQwi0uPP3&YLh zhjBZ=7@f=!{Z=DLQ;N1euc8m}Od6P?)4H8TQ$CoYpR#6F(;W$0!2+9;P)(FUHNYtm z9n{|jLWMIgL`QT$U1E%8!3U({wD8Ld8n~PyTQ?3D3X|8(rn-BD*Vk>p9wGiOZ^(#X zus~?|OA0m%7yt4oP8V|5YpD->!XxX~VTW*j{kYIWKKUNr(dRuO2{AU)uw9ZHmRZJ- zYpSu#&u(H&fAQE5(BmQTSz(n;3wK~%v!zpadW9Anho=Y%yOwI|6*BBbJVaP#A33b1 z_rG)CxLaUj8_w`D*IZr&t4#|>?bGltLccvdenkIAd?kOx8ttgvigRkgX|bR`=yV`V zsa}})DChzG-Y0>NtZLc^M+*{X0cN38KWGC_SHFPY7RGJR!>Y{RP@H)xz*~oue0`IW zf$IV&!02OQQ@FvmJ4FG%c;+$&R|m!ojm z_So?dPZr22q&-)-?*f;6Ka(8QP9Mg5iI3<5!qtt5wqIcP$Y4r{S4_a$2qi$?1yGlP z#);JUr;jK-2JY4vEQzCV~U-eHUEa(UAn15%fqMAI2v(hFL9eIVy^;cL?B`9=q8&Zx zC2*CXDbKXdv?f0%xo7f$f1~D;(B_xIuoumEn6U6g8`cUxy*L(^32|F0!*BQr_oH9j z>wRxPcyUYG(1HH{V))?I6vGB894&$PGlHr6x(3wKdQ7lP{$d=l$6l!G9%%+mjp902?Fw zvpNjW4ASr9=d1C>NItvqpeg2ZB%j{+OG0$%EzrJ)a-zG2rwa#D5oPIsB(r>~4np>$ zI(G7}n+|qi`rR&?+26(Boz~kfSt&uJNxqM)gHj3t-cl^6Ho|Sis)h*AUt1it{BRD9 zz!Pe%dOq4w2WD$@rK*X5bfZrXw+w6fYCg2E)@tTCYYP~2yWo5g3b#!H>9TrTI>q>e zkG84tP2sC;*|tvjJW1fz1PeHmo8{njvy)3AB1FyqEe9&Vy4LHh>CHES+0u)59CP49 zlDDr9gMcP^-|rjcpg;l6OaUz5ms#a&C2va~`P2dU36Wj5F_%BMn3$1rotGrWfV9aa zuw!j3NC6!!>Z{V4mc+7xu4^li{+2%iBk>22^f4D#Mp&>mIHTp-UZ5pL0O6m#yQKvx zq)$mdxHt+t&HUcRz8VL-v!YR7J7-A?0E9{ap~WqSW$yJJ^k0X~9V-7F{%QHGAhJ&} zDUlI^?dCQ(YyVL@ksJpjgNhmAMaGsXHLQg#h3}l`=2<20XA)c|(l|FRB~EdBe`-ZmHWNvr=uGE-hcSi9n^h4y2GG7K4ISvu2w*`eX}L@qlb&aTbXlk z(+k8Y@bQ->LG1V1!TpWc=w?eylDsQ4OeU7SAP4s7fTg!N8K6V>GTnN(a3i$|*;^C%}<<~g2}2I~GEvP`xuz_Fgcxf9LYZ74WGH zAJ}FXPUXOR{a&+>vg54Vr;^+5H6VC3^CN4gSbjCZekw|>}q}Z^9-+YWX z+YRN>n3+O|Fa~D`{4LucgOAyO z5*#dT7kz`f>f&kCT(FtwVaVM?zn2r1>>d|;sqteE8@~J|^8-o`X-Am}?FiJ3j@|L_ zm4)wiYjL@7dv_wJKSN$iPk80OWyKNF6^ZG%0+>j=JB5nZN^CE2$^k%;~@Y*!Xu9R z2l}+(5&ooHxO-N>`op`on-rJUs>1;g>KrjL-L!AwzD+n-@9+p@$VxPRbyffw@tuNe@VxCAq=uPo$0ubT}2n8X2*0-(5M)~A- z5ENxEEmViVWQU&_ji23-@=0;^zNMU~wld1~8q%ngYvdn0V-ZqLx_f*DtX8C0qLnM(&*ug%I+)FNZ!$K>5nec!)*)T0GsV_Ri1q7 z4AjLMB--kG<=`swd{sL?$Be{xdXe}~_^1iEtBVbd@bRDfQqfs>-_VPoLM{9c=5GZ* z@^EtP7icQEQ85GV?}orP0Lhoz*is#Q5>MBo3Vyllzu$5rz>*KJk&mwhKfGoOLIMzj z*kJI1!XbE?f@{Dja{AW$2Xj>alM{Lh^meB(c)gRx$XCRaX}g=td%*4uvtUk+$Rzx+ zq804^J`HFtn?PHS#0O8o*geq8T_`6WIK5FJbCGA;;EOi++6OcT0UG9mP^!=Zy(P6w zgb!OVTwKkW?lANSpBNtd{7F-$^Np=1O)?kOgb$bbk?s*b_W6Q4G$oicPSYI>aWcf@ zImuZNd}f>H4PTTT#;r~cEfh>~=VBzhVouWf#w%I?} zgCBRxvE;yq>*%|-X!`E@nRS!^7}4n)4OQI1|6ky18TY)e!5y|d{+@Sde}?5vQ-KSm zlDFIXN5Wy7XT9g$+&{d8e40$gr9vzh9cajgOBSGYE>xc1kG0Vye(&UdN*e|7cp`g(boqO~-&@x&f&H*150Cu9T?5NlVMKH6 zH-sPSbha1aG}r@yhAaMa%(O)#+KgnqTLB#jheajJEV7dDW>$-}l*mx=Rz`czo6|({ z3Fk$OOSt5oHy!YuJR=>}(r{nmo>$XP!3~iFxG_QAt4Uk;%SQjFEL9e)9CrT&lQwwx zM7NUBz28TV3IW#(guOgOnGZKnDmysl``&gko=gS z4ER3WiE+Z`5AxyrQ&Ef$WJI`?2&RuY@I{tSpp-0F>Z?E+=(;`?PQUdGUM6I}y%LuQ z2j5z zKNRbPllxE3xCFOcC~!t6F?~OlV}zRESpm-^hOc>|Mu-o;vxw9;oWqI=R$bxez=qc7q3Slwi?1)qY=B4 z#1Noav>Ea)Wg~VYy#EV?>5!fY@!VX*KD>O%aum4r1t~{Bouna=3`{}U@5&P?(5c{vk;V#0W!Tg;|5F2toJ!bKeXUD8wy|%zS zZTMp7=Hr!!y;%hwHmhJ15Knm$v19(90r5@X$op#`ehb9Cr3@U(c@VSufs<1}JB1mP zAq)mysKm$2$!5!q3_n*eaDXt#U5}x(YO%g*G0?7$O+d3688}WiK;$n2+3P3ITprDO z91O*5uzxgAcsy>sTaf~c-OtmC>Y>>(trQ=+m{XfhdM$PlqdP5 zyp8>z7i{YM;O6SrL(jZa>Nc8iRy3rR!n-V}fKrXZ;dy5vCh1++*G}SSh>b8L zl)4*{HxcPZK?+?&q{A@Njr|5AbQenRVtnnBp(K<3Dx@yh#QxM$;rL9WKtb{TR3~&| z1Q31}>P(fs8wyP*)~KT`7epltRR&|Hp`QIEMG*sTnTRiVW03aonpY#$Z5GDOxs;!njV}iV%zDDVx$~ zAr@;cLM@X`!1Ostq?Vi&E0+`|I6=yu6DI9K=frM!cMaZMgZOude}`De%{m8< zi{h{F;#Y|KA@0vrwhYYx+0oo5{s{CS6vRP{l>CnpcKPs<5yi03dC_%rzx~)2adjwgXa>%0E47I4di1LQzuWGl-FzDH& z5zQij_CYI}^J3C;tza{mgl^O4kQT;j$)uNkEN`*@jJknR$kDH;`w+nCh62f3AjCG= zwfKWdj^ToyQeLeXgQvnXmVa0g7BMu#tn3S7`gHzjg(?LXA|ZDm^$3!G`!vp!H_07T zW|$+P`JzU?3JEFvhl-RF4n;bpVZ)GI4?*69g^2+S17t+R%A1f-ERv@!$oI^xRXImi z;ck@ab5<3|nh1nxk-&EiKPF=KiexWJKiW#wBUW%5peYA;b-0Vb`D{ z%i~1ZOqY~xxt3?Z!avUBwGe;@^+C_IV5(YDs1V#hawA2orVCrH$)Qa7r>J!rOkfpa zU`tgM;6f~{;D3%tu?0Q(L0YTQOfJ$sujeM0OfEflU6Lc!Ua4h-hrAPuSnhrcBfKf* zl;HQRT+W;%3#HXnVIgJk@^yr1VP}BR=2&v9SeJiUZ?z*@csGz)qJlS!g)Mx?hJ+J= zgVyB2C6!ApSa>gx2*BJMNPy>e@LponBs_yODJ2OO8k$AIf&q!}H!-Osya5SU1Bno0 z;S*m%C{7l!@QV)%NBxYj&C6&Ng`~#c`OhL_6IKTXT{+ezs1az%aaiaw8A|;gCj3n# ze={;+LVgmG-%dmFFOtdHqf|zi=arNg?)=HPT#fcHFq-LuEJqzD8~OS{Bv&2f?;DmZ zbq_=G^rQTv!$xBXzj>IJ`X-A1VA%a6>KVo|xq+Oc{IIAb_3M5$hlCuF;gk)S4SGfg zC=PS!@a_peES+$UFNvBm>V=kYE}FaQ`rLBEMK#mq36|?FPZPsMLAeL`ccMn&U-;Ij zk@#)?Qj~hknqVHh|IDvy#_#8GwD3}p9A&r@rQdR}kn^#qhi3z?R@ROx8FafWFk^z^ z3n0#GiYkfVMp>%>ibwd*luPgoepK{)yp&%ZJ(2SI`NPpK<4OGFm^56&KN7Pv@%|CwCIo_vI8_ZZqXi8=JywgAe0gkk{D9xm zptG{vmB&_CwT~n1!R1&;;t$5oRYd#Q<^_ec5Xt*vb@(iw5vR@hZSW=7o+!QDsbpzk zxDTZtbYLyL<_A~M6P^el(LT6h8p2HqBDQam@P0d&MdF8^KJWW186 z<8|5h4{B{P-5*X}wOseRlfb3bcg;oMaBs|Wha)*`vsaPuD8D3Li-+;H`03;R@ZtTm zh1y@SNp`&Dn(#^)C)o{i8kFoK{r>LwdAnry%zm``=h~St*I)SF`1!H_^hx%2-KD3$ z`w8@G`MJYm@ksu$;Tci=1L>UfcvTC_{RZQ=@ox@)%ywmfNxrWO-V3x83F%%YIihPz z!#r*ZKoAS-AXfspNH_zj*v^LY^~H<1IsyTbPu zabd+!_H`uu6-xZl6|rw7jay*BRte!~N;l4q zww`LmX?RM8VZNw7PWRRfJMBhMe)pc&5mA60T=T4 zTA(dcu58x|6*fB7#JJ7WmD-@E1-9NMG3huKrVRu=qHhGOGA$^4j8^-6(1QjSa&%~o z@IDoBuD9H2kMoF9d^s*Cpcz$ zn}`k+!gSUQGTd=<5zz56_*ZBfTww0VPjn)-SY#qTvCgY}&@wbj!!4|OKm`6a-Ql2x zg@ahXZiUqRmT~xboNLZ^J68!(blp`VGNliQOp2VtuhK&PU=4@&vYf(=6||5rILqvC ztr8Zac6f%P^RAMkNUm)9qc3_B(%LnD^eJokw?;?Okj{hCUtq9ch_jrpPGfC~?kvIM1Jd=g*JQr%Ve-xWWeHw#c%c zP3Ke-$3x{WgU5^>r-h}2Y+ju_BEKp47x-_0|49LcTL`5M5;R6RXUrOwQ|6KyhyGI{ z{68hAG4lT@!SgRB&o)mMQ?0jLc}1% zq>RT;@NcG!h|~qkni=;32?1Ri|5-}f#F$`uGn-4m6B$%B=d~c={efFRsFx4)yQ&H# z&|{J{=!t?+0Eaz5`U`qgd?GtC{)Qj30nY(H!5?{(-I}hagxC2Zb{t;7zrfDGv-xH= zBT5&%(YP5#L}r0n7w~R25$pL#^~m|@15-FX^eYMCT=~TCtRC1b5<&=S7XUhwqbLvN z@HXr#eFMQIN;nfh?8@@IyLhQ=GFP%(z;gx`cL)wI@Gqz*!y(w9j(y}0e^$4i%i)k_ zuXUaZw~w@rZ+_Pp_v1)wM)RSB*rMNEDlVK8Ty<8;Jd_$%oB^Y`;#YRB65>%z_g?E; z#&>%$b*PtO-sxrVUds)qq=-Q7J6^4c&4U%2rG?elXGLlFzI_(0HMU{D6{OP3d2mQj zLYH4_O@!PUYnXYT#bnL5v{~y5dR=^##yIknAF&q85NPsRR9vF+ z#QTs|s>UoMG>J%y_es?hq>qU_qs>bES!A@ps&f^aknojwuMrst=}+?|TJ6##KfwXQ z>zsr`ozS~@uBJoO!${Uw4dRIj@_~b(vl3$l7oYfS=Lw& zT25H6Sl)J(0Uk(waYcmgkk+6TQCU^Z5haP%MC+Pn#L9#>`BCX9cqczSeMG!p#CrkJ0f1Z}l9Xv+1Q}nM zUVuG(L;5280Uw?*PWv!uORR%KEdPV82S82o$C(fR-JDCdOW3S5DO)%u6ySQ=e_;@6Sw2(oQ-0R*FSFMmLFor&u>y!CEeAMsj`+=3mf_qpk<|4|E#pwX73=*WHKl zabA&~VlzK|Q9O!3sWW&{JgIMUv#8b>;YiV46i=~^hiNya!dekX?k8CYdcae55a=Jn znVyEF+Ke=I^$?!a+{KfGmBr1ASKilrK|BPldVR`fa>6YA59U`j4l7%R%owSgI0Ktr$*cWz%l)xIT`{X;4CYJwasy zp*sEmzh~S8z}~OMjT&(=a8mq}K0zvNKPgu06Qxu;DZ=x?k?1aqzp1>GB~*& zaIDPlVZB(Z;bgFMWCBNEJCkJt-q>)>Of96(1apuCqeXgTliQlYi>$!EUk)OzVs;V- zd|2X?hDVe1IaY3`sDNW`A7B<7T3K!<132XX8u23pq8?E;8Lcy`W34F}S|Nqr(<)Dm zNR743(0*Rc8;sQvK*(g6Dn>r6nP)v%rfm5X)SSwuw(C^POsjmB+{zmH4{|bXBJ2i( zHIjSTN?R|=NteWtr9r>psge>k8`y z%QH0Ho>>VfZH+C@tgNsuwn+O8Ipx+cD`)^G#G1n4fA{KT)`r`5+x$wcaGF-NnxNhJ z<>l6h;&5xiL_>HuTb7SO8m#tvo*t+G%GD)nZpWImtW>X) z;`ijTs(VA!H<_y=)G@_CcWLaSHT?IvhQ~t7bJA3ulnQXC=n}?98&0v_zF)XeqH$Re)O8^Q$L5 zA8kGn%Pq(8rN1p2%fw&&h>qn4CT7o26wz)ag|$vGsgO5lO`nNLc|wbt({dL<*g@fP z0}}g!pa3&;H|-KtZEQ23JS_WExcq#2qHkl(%7onde`VC@@R zgqQYAF`nU+jjxFE{q zZGDlTog)3x>&yFQ()3!Qt>TA`9$qLfbcjse%m%GM(QS|#(rl7!6TG=irVG_T9ujhz zL0n<6FnNICR1GR15Pr`|kcX9UK36sI`ncg{dVQxfx;=c>MNyvDC5vdkC^8ErY(D6g z(*!Iz2h9gPe~1t-ywey`R2`9t^R*(4=WunQ=4pb*v>1qM{8NCy)R zja`N07Nu5F99u3aiLU%cirev2uajm6Jqyo}&JB??G6*b^6iZ8#<tlHnpbQ-f(k7tnUJ!H$ETUxM1o#8}|qgPtFP1Fj5?aAV*5`(6C5kt%+7Ud-^S zCesFn`?qvjJH6rlq9u6A!ck0aJFnCZ=d-3M3v-I;4T~_A_?Xto4?F(--63}li zV?!PAL3V?#2x|Zr^EMhlch~N9e`}=M{B--n4}YB zzIM%qFm^=IoyK{1{z7d(GMR*3ruk)qo(8{mLrgKHUV>R}Z`n{ydj+Yf+0YJMP;Mp0 znr#Ns73ua1co+062$H4ylwbxRw45L{K#^<;c?mp(Cdr1B(x-6mB3eME-6y`RTacV< zKIyyD&uxe`5tWUp=bQ7ARuf!QDtXvuPnvkxwkJ7ZuH@`b#8N@gkb zqtJp=|KXY|vIeYAvfOqlNq=|yR06rSfO_^skkM4EU)Cp!tynuGDxEolG|{jSH(SM~ zVU;pKtw)=~H|Y6GQ>HBW;M0l?A118odnp!WS3DPX`AXdpqwGhOGv|da8Qos7!6X>y zis#fDMwS%g^9y^Eb~iTm9*hd>9A1pI=fzz4b^{F?Iydht*C?*nm9sUI8xK0Vk!Cnv z`O5pW!;f}UY*;LP|Ki7YA*2e8mVa*QV%uXuJ=X_P-Z6gud>vkIT2P|tk@ z+7Plx5WkBj20fz!_2LV9srwuXEuAonW+x|2sasH)ce8n*0E9ngQY1cJsiv#ap|zDz+Q&ZHT{8Qu&dGy8tpc1e^rH6U})_|N~?V)=$SNV z0BRsB40?P%I9CdSo+H5V5v*XNQK}sR!4h*!IZ<`S%x1X%FC>j9A}DGS>?T0rSc0NH zA1RAiQ~wZRlI4-Z@(`)^9@-f<(A;?`z8Lg4_@&dQ+oA`DY(GGlJnccz1(2O-TF(Hh zDA26VAZ)aw+q<7#C2*KNm{SZmf7QR|2Hct?Qkty9L#Sv8}#gR7UNimU)@@@(25r?W+vS z-4S(5E?+2S38=N)faHlYk$g48YwpI;MkIgWZg>RZbr1$-422h<9J`*AG3`_)rF5q?ON^nF4^$*J-}zCb31^#EMCYvX2g}G2k#XKdOjaS+C$=_dRUqo8rUPO z%XCn>2nW(#bfS#&&bB@j+tz15?>uklF(J$I@!eRk(Nf(P9cO#b(ouYlL2Dy(JnL_8 zJ@NcspTFZGgZXPa%KVFyv`6ViIMFy;f5kDVhotEtVc@Q`ZJE%#?81h`dGz!VosxUGy2(Mn&O{d1c@C?et`;8503pD(#a*7ZLtPL zgQlLg&v;$;=$uao20ah}kxMrp z|4BUF*d@jpxD*q7)jMVrYL(92qgI2SvHojTwt)hrYgj`Dx2r%c32Uz{`Z`3x5-Vw2 zLwx~K+X@Fg3I1QCi`xHGGU`c*5T$5#OQYufDCrks8gHXU%d{NQJ|GD(8V=| z>?54aJqjIeEfoymDPG%lH-0tfx#RsyZ#eArU%jux9;Y;U+>?D9>6akAE_8&fTZ{Mp zReV$l$BI8mOZyacgj}wIGK5%`l_VLFP+1f7bPnFto4wK@!|h6Iv}K8$ov_e_#&EOy zWHZ4Hp|q!9G$*#_qUIS0s@fRuJ*jzOtEiC@=%-9hn_c0cWxAHK6PFz#912KHE$x%SA~`(#wRTuYkw0UJ0IW*zj5^C?4b@}$Gs>HQ_m)PC}w3@Q&iDsn-W zn{4yhLq+g@Vo#8}ljKX}n19K+=;{#YFNB5{?)!&}H2CL%&#&ff4b)AwPD)UjKQbO} z9m}P7UlM1A@(w2kJueMR*;;4*t0=dBe3dPpx1JINN(qGL_(wxrFmbg(y2DpT&X%hs z?sx=aSU2$6K)fF5wy_`-5=I z%V@$70S%l&_B))zYY1<0!3s>kd{ckh{0o*(ej_LGe~)_pNsd)W2Qa8ggPxapp3A^v z_!cgE6f~kHb9+>jbJs0Ib|IP}Qn9K@$IA*>n_2@nI#Ya>jo>n#8T7mXDK)3z20b?4 zsFEOfNdza{X$0p61%z;L5rQ}!;zEcEA+|zng}4slI*1QLd>G=dA^tiXv?3N@XMo9x zgOCd$34$sev^e0y(jl%`Z(9z_y<#olZ|{waOzo9ovFW@Rk*5{V8o)jPKm=fBMBXCs zHriTf7~}W+7^nkv%caospMfoNf}X9xEhVM>{m&q^3Woo;flWmeM{~foMHod(BIb;i zfadeH)U!wv;iKY`avohi@-fEdu9g7TVK56yW@XjIMm(WbeAuvDuradCTCvcuvU*h? zhMa?9an%(k(k6{Dq;)p7iK*pnqCPrFZx>m$U5rqJb|MDn>=vibl<7!~jgUGZ4x4+; zi8K{O&w}XF0satl=a9)Jw{__(yLRd9gBIHrD_QI-7Mk^WngZHNu#9)%=^m%HGQ@3^ zKUng>EKTKkAb3ME6iV}X-U%FB5l0xboP!l$m=Lwr39LzIqqUYRpyfjI2|IVi67cXK z_@PI^fhdnGgceW-{^ybZLry~|&tSWSwH3=ifTa&ED*`POGoC!^ ziK-;tC^*x=1t!R*79~L`{=K3E+lZ35!hPig)fQV8RVEax1=~z@|9T8zrdkN%FcVTQ zE{`wXS6-vp2lM(l0HXWAv*0!&8hoBPA)l-8qjD4hA?zasdiX=&-T=o95Pt()9lIZrDEU+h(B`TN=XXNn*u!8M2E~h zLXsv#NsbxEbr6+#cChKTJ!-;vvZbF6N_&xVQ{`ZT#(L2DfidI4FIL{dPn$h@_QYU? zRSwQ!m^O>dG*U4YOh;l%8i+M|E(`w83V!N}VSjKXaesHkf=@xv^EMbeRSjT`QTsfD zU`r$}B=RPo=W)Jac3(zblL|IAaogo{vB+Pt;6&|Ga4r*$@TGh4<%6re*VFSGI2Ry^N?B{@D_4D&usrMJGCzt zaxsmGjr)wrt!u!g57VPegPxoG*@trQMc(t!MD;-s67D!9ZZ@n8>RcRTk`uamt7#xa z+fS6i!oAPWUf7$E<9#FKoVc`&gS`rxzqzQmyz#F4Ko&5_NAIRpkbcjLfKg`LNm8O!c^m%e!RLy2 z0}QzvBtw}!UZlBvU)k>{2=9TJi7FunkQ>_Y+Q-GwS6@!_8OHZ!<@A{jt`7hQt;-4&)tuG zaXE>NwctR~c0D?WUY^h})7su@o|SpB9^(wPT#`ZqwoF&u?;KLj}e&uhHGGHS|cP>V6# z=4w1$cHUwQcs78EVCeX2K6MOLjjphEEYh2m_k$azceq;_b;n8G1UygjOD*xTSbq(G z^jChJB^ykh?_1_ma|3+9@?`wpK`AFRpzM^c+Ulm>vr&niK2HVzV!0Lv`FF}w=={0d|ZGz~#;;p$v&40whG7z+?I@RU%3 zkHnHw!Qa6NZx#|h00LG41dMTNx57!6qpcy&N^9Vz;nxwtW5fC$By(qhrx)_ z!4F6Km_=LD>teusOT0$6`ojw8nOm_g0vIV8q>x~a$>Q^Xhd_wt$qfOI185#y1K@5Y zm6T01&^Q$b)Jd1wj1rUd0nhY7{@=?c;T?Q@#Y6Zv{;7&u+{3#o{wIPqAoy${j z7yse%BAm;6mXEQ$HTd7zWMA(qkS1^C;<$S5k*=6#BxLv)jvA}FjNd1RWLN}Yx8n{0#&A5atxl~lB2GC(1{97 zn~%$Y0F45-I1qdSOma*Y{Q=%9$%A>l$d7zHF<%FJL~>k!!;#_28iF1in(e`@IOib9 z)=7bMFv9|}gbul{A>R$l;_Es&5TP$=zOuDT8V)uS1^>e1iP*=#_IMM%#g{x`!VdnG zCx~0YktfvQg+M8(PU>*bvzY(a6DibKA1^+k!C8EwbvBOVE3Fx^or6cge0RhW+pupd zp0E!(?&JSreQNkHuxeDb9Iz5g>{~EUlp63b1AKbrpAzQ{MmD^YALZ;2Yf2FEyz?w!^r ztvuA`p>}x4@Jz^ES%U#;c!LMv>ACA;6Y$JF#lQaK*yvaMSc_Qg^U4+}c=P!@Tln@T z$3GDVc41J&JP%6IwA&$%RiP<%HezFEQKK`h^cZl6Y1UdQEJ90+wXuO0m2J`McjSwg z=2}5gY&&}$si!n!cD`l!^Eyk)^9fu9c+-Yk=3A1V7hUtM!GEJx;%u~le`>|J1JCny7+AH|SC1Z2+%(B#3u&)bP_D~(&O zRT;dVv#lg|l|Z4YmJa@%r=~p%lO?DbsrV&J&Eo?YHi4JND3Qfpmdk-p%Cld=w41*fXe?ttTTInhbwI66f}4|_|I zJm=B~a0qRCYh+U4sN#EE>hC^OP8_jXgIe%vRuvPL;Ag-*soH1rjQ5kj3%q;8hm}a1 zl5uc(bO)j4e;4fy@Xms=zi?c6N@vkNy~5JwlEQR-o)LZ*Y{D?908d(aBZLSuj8O=E zyKkxi;@_S^^2wlo&$4ELFB=jb8W@rgq98qY030M^E4k7;5mg_GHl*JvQU?4Q7M>l% z;BHuCltG~x16N&Ah^N9Re*x2l3OFhRgiZ@#4uqW$$cD~WvDNa1qekS+Yr(mLp6>?k zxTumaGD|BGs8e#NmwjC8wkb67%7Y>U!iyqIEnrN*UzyM; zE40pPMPnWi6;)?tGT?L;w92iBrOiw7S6?_~JOXdz=j)C0&L8YW;WU@iyo9sma@y{< zjlT0;iKjW|b;`KM64CIj^%qOM@h`o!#BeFhdOo4V9A?p3BCKWsL~;vs27CxcD$}=+ zB10M(khtZ{67E7nSg#Cqg0I1=mgt5~F@pWpl4*V0m|)Jd=q~vZ-d7y~H-chIfmJ48 z*;JFsVz5DVub(vXhySE;x8r@coEi_PH{khfaJvf-DEz2PXI1pl)Cv&TF`a2yK?VT6 zv=|(KVF3EiT&55=nP4(nI$fltZ^4e;ynUIVKlMeZ(c4 zjIf4teAwz~_$|I*bsE0RKec+q)P<%(kf*8&2pY+`@o<%f%E)b9C2YPcK}DTRX_6k9 z4;~xfH_L_;e`4C0^858U~n4Sl8~4ESzyKU%QVyUiQdZ@0-oiy)PM;(ja& z2!os0lJIzQzuo*zBhu7%n+1w73k=iYG7EC19iB?&yzAs`WNW_giTh7cnJ}=mQDflw zWR%*O+HYTOJJe|IXP39RK5=J8MLD}Ai$H3j+O<7bs=g{kw`&ilCxwzJu z9I#B|k#K6z&ei|?iTm*=TmOb*VH|XBj#4Y!GDTE|{BVXK3r}y2QlI{v3Ww_lzBk2G zz)}T;GmVaSWu}X^IDv_Z0H7j8slX~?g@`DVgLDy;}My>h8a z#EF&7(>Ro65Ke8p-+YOqvi6_5S}J5KK8IbUQ?$Aw8rUh{H0rFRo8Me#8!wCO0nA%U z@V+EtBJW-sYs+#ZxS6Q2UAyzMIti|j`BK2A?aNQ^41ZV0YVFnEY8Ie)TKx1f<=;ye_iW z+eQmLR-R|1Zd3ghK?lFmvr;PnMFT_l$5t}h_f zCHrK~6G@~6xEKNr*B40k;R*CxXJDq|-5XiB(PX3NR#yiU+3$r>dv@+w3IAiTx-7iF?D?bSth1yd}xT5q}lD? zx=~oRdT5dL>QCH?sI(u4{xLA@Ft;AR>%#j8MiuARwJO|s6w%o4Y1ONrG~2-3Fi_VT zBgQ7x7kuUF2D>w!^ree*PXPjc=F+LpyYToA++ktgG&)`1!7jn_NH?p1Jv4Qv$m%t+ zsCGa`W>$WrlQW;Vif7zI>w^44y)x;Yjz3(Vjue5ur*k6#VL{>>cg=xkT!n4BJc_aP zvlSE&kjkiP=ZV|wstPCBYOu`|-*J~jM!5tO<3I%#p^OYcsgQOWj79LTymux}fq{>N z%`0^f$kEQS9!w+QbG!U#7`W)c<{V%We{Ccs@E+LK_6z}sne$VC@Y!#jw3}}!DIj@$ zHboBwW(L}sAw(;nNpAwIITAjygG!5f(i|g>%+hBXgtzRO{cXjWf-;OWkN}&}Abe;~ z00WrRaoT9Vbj6mF18h#ZU54 zFO0Ae9)A1a`QM5F$Rhy)*a2WJQfhy6T>o-{jhF zTxQPb(sJK&55e;RS3p?bkt9d1h6qm-8hu5Q?qJlcd4p1TipYLAwAg$xu`Gr z-c^x2?1OY}p11bak3cnJK&M_`@XfsuPpdDu|2I7sMcCq3fZ;R6_M;b)I4NAsOKR1^ zAw@QBJlya3wOS9Cw=|py*x|1R6qzTvsi9JeAN3Osu%@tbYy-o9a4aq=d&F7*B~Il+H+y?w&~@4gI`eWcw`B-cizVfO7C z)A*uwQ*8PYy7x<(zk$~2Z_2{ozLB}^HiyazA2K(v_EukH~LcpN7x#N7m;nK3tFFFG7gq2i7N! zzd=$j0xbsS535n7-_y}dSo}y%T}f2lM!4lfJFZx9&J{~ui{JAOpZ{WxaU|4;hCph9 zLVuUv1ByjZV!MI&gsYr;{hpV|Z6r|Y!-Y<>vT2(!mZKd>)p!ER5}m39Wefl5i<6#Q z1FBD<^9DHZh$cHA&2Y{L@_|7l3L%A-wuD&z+D6f=-!GG1^m}qd@|NVPy60C;Z6*>& z6{xprKM;fADTwB5vR#?K!qJ0Dt@uN?XnbJzYfK)rBWYMI6p#-*$rDnblh0Zb8T?Q!$6E zR8BReBmK_x<$w}Y;v_zbL>vYpf0~#%M}at|Y>J+xg;gBoSZ0j^AM%lxqQKjhcB2aV zHpmZT8sH{m73A!O<(u>^=wPQXRB2`nL8Y2QfiC!!q9mv`Gr`~OrG^jra* zSlcbJh7{@pGY%4N)mW36bad-x%}>|hetY<^=s3ivmlXy*!2qdF(LcEu_0qySp=TdF zA1xGINojBoWg;a+h>TjgOA7n`S|BUC-}##hr;)b52(^8#hTc!Z*BfY^!6uxk!CE3_ zQY-)$JntWbJK`JpKXjOs~H#9`s7Ah0L8T}FdI!SFg<1bFG8&c@WBv~irFn`|Z2fI`@x2RmRI zgj5xT5hyhs;v|xvJ;k{?X|hB5`p%+a>*vioxL8gOH@5MxCGsZwr22D<(#Y5uiP`8`mgBXFUE5=Uvj13t4*6Q~8t)Okp)htDeP z&!6GUD5*D2bN(bAI!;RD_t?V27XbjD2nK;&40$U|s6!+++tp}m^y z7aG=8G(1Ef{VcM!gh29h_>?C0*$j)=Esq zgPw{{@>+=XVH%(t1E`n>aaM>JGqYH$-}4VY(9Ileh}dTFKk!~4gtynlE;`Ey!KFPpinY2aPB<iInpt>k@jNmUa{m$$08y5sP< z247;46kr$zTt?mrRS}sjX!~3tG#+o4s2T$Ozc{7Y5&i;lGz{>L)-!SM>0(^MLl#ag&5T5p(&RB&lL51`Ih(* zMKA#-GyyvF`42ML0hgZNxnBc z@C_MnRNWZvH2b%xRsH^-T_skOO0=3QK>aABr7y$9b8@h_S8_;;gd2nW##hfg>IxnQk_%sI2^)K6>N3<3bq*;br^JjRxqtD0tIlhyO3xL82Ge zvk6t0{f7%@yy%2~daQc^3@u;l>x~qsPU?-%I8j!Wlhpf{AM%wXl^#Uw$F7=;<)Io# zXZhb6(Z&a%$^s`SFsjbGJ_Xevzl%?>)f-Jv>Lpgj>fmTNC2nK)+3Up}?7r1oTKmNU(klW%tz`hI0E~s1tYSJIHNC-6;oR>kFEoM$+9rRZd2r8IoHk z+6|z+b71xc?juNru zGaP^Oso^%{KBOoF^=}#&1U5t8^BsG{T8K-XjQi8Di{htc+0DdKLF^F3LieOqw^eB! zu~lV0IRJ-f!j+vkr?qi^BM*LrfB_oy%da;o8n+u&PR+|P@K)-Ca!L%I8+ZyZPXoi@ zQsW?8GXI+~u>;%=Y~Xe>bhG7P@N3uKjK5yGx>G4qZFoZYib;(aE`g0~#5q52-rq=? z*&gcT2bXSZvUzL`3=Rf*+@a;D;;+?Y5=8^=yN&^#AFedqQsnFfpV}Mtm>&(d zWTEu?_J-R=_{Pmwc4C#-Ym6M{Xt-TtTjGHICE36`cf=cF6VAasN|d$=KKX+Lm;Ivn zl0MdQQrxEJ?R#L2_|*b@>I4nGXpo_yHdY9iDO%+TWC+`+a%VO{Q|c?63_64ZDVcV%mHS1 zVBP%pu9EK&K?<3=37)s%lMy7(-4W&8F&NXh zC!cbl{U?kG9sEbzhuenM{yiU2%4~%`zHELI3<~7aPeTIqdpq8Ja#G{&M~n;J-EneY zv;|LyX?)%I?j~|85YY!W;qhO(823r!^X!7_6feSuN(>ynZxf`j=7=b@d?zZawu=n; zI0_q6xvK!Bzv=kFHM7C+v~fr6j+n@hHw<>bvEB-<7Snd50;JMOOM09Gt>}q&X462J zUfVn*#(=+bYgG%e;=zU~edTznhS;7ZhmqO?7Vc7kk~6@|(r{%4D@yx|%YG1*b}9eE zb@}^0To2m@K4oBb&jS;CxJ25JYe~PWt}xwNt0NvK=Ol}5oX7JoU!+?Zu}QR5eR?el zMSU^!eB&C8KG!A}Z-#i2xJ575D%Dm%vmN@<{^4r?-40Z|#N2)hQgyp3DvWo!D>jMr zt}C0E+mEd|xGcKl+;vqhbK5Y#R;=E5R$L1gZq^&8auLNy5C_zp6}I4duOvB@eC`9K z`aEI2k6aI%iK#DYK*Ajca?O$h9zt{jU;LWJ2Cvyv10TVq8P zTP5wLwG3NQrO?W&wpV>!Rn;Pyec440W6A7Gfb5Kv)N!TuBY z^)8IR;xGSMP38J_*WZs{=V#Qb!MFau-Vnq-KIrKOt2pp7AfRW$N1p~g!}!|zH284S z`}K*`i~;`3`b_+H-d(R7_1!@D2Vr}u!+5vfvt>|0&h%b#p`JP%@U-(&_Rhr5@$2@E zg3oX4-8-L}?&WXpEu-SRCk*?n7;od>-=8t%*;8z~#G%Mz(szV>B|*Od5_%Z0h1*sm z;qg;QW4IL`jfC=3Lem!O=HoND*|A5G>K(7sY=D^2`q+M`@ zjKlT7@ZR-%@p;<#D{m}{{18A$AQJ&=^%-CE=4AXcU-M>c;wtg7$aG)6PHEvHG#KTG zdKc*uyO6MqKlY{?&*hzOCSntR_S*p&0nFotY*2H$}{vx4ZkL$(W4qJ8j$vj>&P@7lncU^?MB5Vlnur~{*|{= zYyzP>-`P!^0)`7E1({D7ZSKM5VLlXiFQ1eQ4R<_s{=Ix; zyLH+w=MMD_V+=jC;SJZ9ZdP`}pz+EEXZ6q#tXI~Lz0$rU(*S{35rTAsZvfnm$xswN zRcHuu-!K>g<(1wF4-G@^4&G-M>g;s@ip}=JZc1Km9vaL5e6uMun3>2oEbuZ6#zw{s zz{_2E{^k59FHw2rWH#`S$Vy4tLtZ(~W00U0s4L`r#7+BZ!P}iv_un;>l9Zt7I zlC5>iGMrhAIhqV-vJXD|h#!>7=Er6gwjcXJY!j2ga2fNDabQ*zdJBl%bJ|AtV@=+^ z=e_Sa_cZ68=A84~_kG%0M?G!_W8MMN5;%4ciX90e*poq5443;2*MndzAdxP7C;b%h z){DGIlw$m&jA1p&KU#+@TSot=0beHpf9I(>!=wf_F$z!lN)3~~#1;H>&`T0nDMCVH_O!3yWCv zkZM?uts8^mNMt`6G~)mh4FgzvfZI)>Ze;Z8C-a2xGh6#3YtJM;!6DL+jV#fSt%a^g zf38PaZEy`dT9B5hE@*dqu1R@qMWL^42d_y&nA53E!YnCwd-B?<9x4>aC0$5*$U)~r zGkZy>Dq)Mk&8Fu31=VZlpWjuP)?j!sduqtkVNEEO44vzFXAD7NRha;`wCY% z*g<_Z#gtd8nEI&xE1ovS01Q$63i1EUs2z(v4$fZoIq= zVDJoxnxa^#(_Id+4^KozB3mC2+(fjmfpb1 zPAZ9;j6Eo@(vGeI?*%Lb0}v%RYTOPs2Xql{rMrnetgRSNK3{MNPIXY!b0BO|@;Qx4 zeN?`4iTN~RWQ;}Wa?Yqca)|_)&A26$PO(2Khk&M!;Y4t}iN!fGAD^l___Qt$N+dMC zO6}cwUSEu}PTdvF*~96tuK$}X;l_#9-RAS>w#|1Aj1TZNF#~b>Yh!9+@oxd4&h@^^ zNgrlcc6D-=;n?1XjR8byPOfd*VKz{Pn4&}lyp9lc(1_?}qOXscEIAIrm4kuPVzX%b z3CDKPGJAJ|?JVeD-C0}*mAi}Ve07KCfTSAcrbxyCNf;5F2Rui>p!}@MMvTKgi0)!K z2tG1!5;m{Fo?%N=UPia~m_UT`X-|P|a88MkOZIB72eEfMv6W|}SDDHg(B#DB^Kk)$ zV^O&mwb&*Fz$s$!WqH#qz1_19lePBb9=t;sJh>m_LH1Ka{HhtMKHY_U>M_0G3dhtX zJSdU1Ad^tr88Pe=JY^-B5zK}-o>j?Zdh2vCH;-~>4mlUEv-RtcSzGH7JRMSQD7^C! zkV~%6Y`p&HV=`Z_oK+Y>mZ3N*DIV|&VA(Zkp?Lr}*pcBFxa96TSo|a@4BR^7VAdVD-5S&ig|>5wAj$T@VsXl|S1=#M%ZT4s8IQ;ZFMJHWRVw zjbwRbI{==C5GWq>nx zAx9vckZwo=fSQrR$sScW9kZSs&@|k)SQV$q3#aMxeo0wju~_JCe@Wnk-@<{hbEt2J z_!vw$XkkS4ELs~VqP~DRXM)E{CgQr1uViHnyXgkrJxOl_E?6?kiC6{_s}G^qLf(h4 x3heWLKHSUv8Mc7eiDMGdr|C$x~$T)%fx+~5Ac|MNZ1m*<%? zlQXw>-kEvlz0G<58r64|YCA_^PUxlbZOPS0n`{wG+8@SPlB<)ewwW@2Kw{J|5~ul) zxMa9{u;%6N!PPG(R44L!5z~p*`H^_O^^Y7Rwgr%Q6KZ@DFiT9@8TUMiiGfti8TT$V z%GyJtEQCbGnbz`v zxjMDZT-{Pf-9W{u%T3ki9!TX);=XydRBI}~69-PG@+x>vf>G{9fz#6EX6 z4jE06a!la#ZB@~H6U37tHi;A!ZJiWJVMswskW*yQ=~Ar*sHYPZlu4v1QkN1-DRrLD zm0wv+ zGlcl+1WP<0V@|ZjM=}=ki>)nui*>%lKt5A&jz4E*yHGb74cmz362SiSd#E3wFfM@f z83^Yg^g#$?q`C~TP$1VVPO^-tPUGXZ&_nho8yvVO-kz}KNykwK(v$W3bNlAO_$>z< zjK=UW5-mrn9C*q#H_H3nX&$n#kyj^LvA*Ap3f)dU{HNgmPj17<^%Vd}rLbR~o-VH< zE7HCu#)`CzCB^(H)sXEel8urWLblOv@UslqJX2Dk6X7am|Ey-2t*(uf<5mwYPt#$XZ`8cVX z_E^pIjpb$&Y+V6L#RI_cRWX`WD-yr*A)T^{)*$hOPY=7wW;Tm`X1!I^lTkkKkqTyn z=|g??A5mT(3nPJj&Zd+2XVmw$9A)i}LhOSO5?|K zX^G(Z2|+e$jxE!Na^CNznvq7*W9fFd2k2^%b}hi)-Lr zR4j$+E5cW&&&K-cbDD(jM~z|_ag9&t8>O~&_$F6rxI3(j_>NR!!SC^0$(`v|N}pek z#qog)R}iK}A;joQtR+0oFTY^m?T8llh4L(Fc*9sVm2cXR_(5ndpHaDF#r;++wujOH zl|m>Lo}a^enJ)Elq|3CVT4`t%iFXal#H8VLON;}FeN#hekig<+{?tgUmay3G$KsJ7 zBVP6~`lw1$<;##PQgwfU+2| z%_pEb= z;ThFfd|qf(rQmmk4wZKNx^O9!JQh@U;`d59T6`%?jvssu|w zNzBC$3Ew9c;e!Gmos1_5DWmmRC(IaKm=qJTI`Vl9cj>{Ey#67i-@6=(If8BU+^CeG zrt_{!T1*noj?QPl4m=B6;+R{oCykk6ti0Jyi`N3r!7G$=+NILaV!9vY>~&&2z2;jt zti@n%!yX=q6N7RNTj51)!fS>Hf-G6}J;XLcZQp>X>cJsu-088ai<>&LCMm1?cqtZ3`H zEWTXJ$#&9Wo^WtXGVT}tK4$*-fBR*vy|>8X)gZy(RT zkc-44kV-taz(La2hP8dg+}ucs4<#n!w{r(pqI{3DDDoy{_^LamwTg?bhO)09@hK?r zQ*Ug`tjMZ)3;y*+T0Aif%QBt}>v`1Ok%HL5D^iV|6Ressw(&I=rMH`oaMO6C&7Olx z&Pu3fKbOaEHN~9I;d@{!t{UFNUG5w?VOEPVD4`GM=kZ6nu^vxNHQp=fQ0&0QxXRA& zBxL=$ebD-)gbd^~>bfkwj7xCQ8FxOky#(c3&p{5fkLZCP);I?0luR#e6AOpGl2BW> zyH?U7Tm(fl$9X(8(P)wM=vO!Du2i6`*%0o9PE9fMa>|@&AS(Jj4;yueV`lV7Xpa%P`&WSB9A&eB3fIEF z_XBs8oh?r@xR9n=Vq%Z-^H$trr6WtvcpazQEdj5Y<8;#E#{q0uw^CmAhH1=6JZZKt zBQ-hey?~v=yEPo^!7MFq2$YpM-K)jL=rlZI&`G!QeZ&g&Gu1Q}vjid4oR~0-4O>jV zyRb%b6PiMcj|f*%wfJixCT)!}FKmTzt2)$L2G-mr;l;G%S-r>VJ77FRJL@U&TA1N_ zfS6A4%QBdAu$IJA;T*2Mi}4ho!$8DtKRd!Q}l%bGTY5ZrUYl*!#9m=7~jN?;c+cRI3YL zaZ4TcacDd_bZ_(3J(|`DOUoGc8inrkPe(l!(!l#EVbaC#!i!^b@lN4?#@-+EmJjJQ zoPIeHmkQd9T%09XG9IDgL&DJvLtSM^##K6y$EqlJGKW)7E{crlpvmj9YAA6^h~XBJ zTp2Y!`OfiAYB=>IQsQ{{9VlUh5;?a@7-eX@>dx_NG@L3@qWwQ5l7%^$$@op-!OS_C zHBuIT-Cf!-3it-2BkcW9dV9rahkpG56YUCn|3`3TCdUckzD^aKvnnGczSu3)FHBCT z{JEVHH-yPv%IQ=?uOAATni486EI1PC*!#* zk}eV6(`46a!a1FqNd!Y_VRdI|7aRn`*MYb`JUryCuaH?(9qD}7n5OX z6H2e)pucXla8{c(r!u^fU*nkAfZs#9Z>89#QXrbR6zh?gH#~(i0DNP^coI7~rl22s zl9Ao8Neye6FfgTnfCI3F3=Xo)DDfL%mM$sg1kC#g(w-HT>29|zlQOIDq(`lB{O3}v zJ)@K0BN!~`GjPQm((mAxsPXA|zNmArY4rJcKDYDd)WoW*ZWR~JiS8{tT{e=6tImab zo}j94wU`71ZwLR1Y3~50-yWcuHwPHJ!+Omnt0HZm4Zd#;w?9vgFJPs_^2YNp8TB1; zv-P~i(ZXkQXdIr}V%77Bj#eJ!qYL$2q}t`6o==1PMn1Z%#cJj`YY*RCF#zO_)E7j3 zs_?izE9FEGX{^=}JeGE;xitQY8$=tx_CbASYUVIVntHhwYZx(Q80m3~TuVVZaag#l zFG#y4F?wLSxw_3r{6YGo5rr0s8-$5j`eivmva$%Xav1sq(prJ^K9EmAjk?J zv%M0#hdE175SfaXXLU~DYGJbpL56#(wU5A7It4C8uXPR{KQ*29WsI~eiGFfj5FwwtY1YFGgyVhSQW%<2Q7Z?r^VwCKJ|~XsCji~EbP=YeoZIRD8x&`k2#t6 z2Lb0MC(RkgyJ6n|(oLaJq>O_R7YK#971$#@nY#%4gzs}F>SqU$$OlFk{oA^Uvg7wp zKKS?P60-ZEXJ_+_ctOzSO~X$LOYO0CG1@brU zxwg~N+X#t4;gJbio6}#y<#9~a$h&{}2|orWJQI&zEJUoKBVJ@>&$o@{Vx0-A_O7A_ z=FxkXGoF1YR zm6X6*zP&Y((UPW?G%(E4w0z%|fdE8&%ZP42S$G5t3Bu#-RQQGyvL?P9XGl2jh z`ThVxovQA}8daC7W2bc3Fq$iIsGy7fu*yLWj(fvGy`gw=8&Wxt7Fee6Vd-f@vpn(i zVW~m0L#{kc3YA3Orpo2ytszZLMc!T){$*Ibcr=W*NkjBoqd??8CGCO}ej~hVhIj+S zuOSwW#it;MVmKGD^su{8; z%&H7}zlKcG!7_+R2TLIy>0lwGnl!s4yJ|itJf4{!Xxa@&I43|Gzeu1n(@>068;~xs;(Z;ZVHA;MNx^R-E7uk{&<7% z@FdPgUW*t)$5y_K*Yp2Y1WuV7W@dfS5Ia6IKhlIxK9qVVG@l)tt?<)zOZcm`vAmgo z&05A=fGFQZ)2Cxs=*yt?GBY2wVv&^^GM1F_+KARK1~f6$P~Q`?_`^5sHp>dVc#Kwe zn*lV-G9xb=TSfCJM#hq8j4{(z5w;QmC=(@y`ocq4C@U!yj!ZJx3SnihTcn!QTrpaT ziw$}OpK8J{t`V7sKyQc8Gf3%T_1dcWX0hWN_1E`4*Z|aiGa6?f57hp-$3G(H_;Wz* zQ|=sF_PU8W59*K-MPDXPmgGGjdyq2Ig|lzmJt7L-o1W@a&SnPa#MmsxPsPV?=bvya zZRly=+CUAQrXJ*lhRGWBAGkAglr_X^6D$mK z9iUZ0)$K*M$*MOQk!C~@+Si4mNS%@Zsbg6iz4ogHQ$MXUZ@?mrd*%3a*n6To?0uNw|G7Q%1Yuv&^()Of zhqXjqCUzBZSKRcCoohhEnXD)jW|wj{HQzHh3N%%yn}xpV^~(ll(ex8UcLft~|G%|# z3eZqaap*+~NYwF&tWV0C;r~q-I|FU79Y#@u7(p|IvBjN^CS1BA`gGKtGR-8u z3=ABwWtkFd*z1rc-Qpl&D6n}5BFI31!>9&5yT@ueDP5jQ-Mp+biwx+k39?i$$!f$} z#SYm9P0b^CU=b}MGs-J*ezE1Qj7epO{WpiW4T)x=$}snzV9a=eS}2;HELXS^<`nWm z?ex5fc)-q3=fy6Z^_@G5$A)z45TH;+mI4Fm?(TTeaeEiuDT5$ zq^=%(E)f;h{Wl0BDH zjrA&in~?_izjBY|uDMHI$m5DY8BfK(Wad|Lg;08f#dO6$=g0>QY zhP@l17s5=$wt^lf_K^fd;50!YL2+q^c>^$v@~Nlk4U?*t;3W&kGQ|R(Hoh#kn%=Mo zQv>EiHE)L++ZK{FwyjpP!H&aTXAtyS8?Y{h-)PkLQ(z)mEj|LgZrD2z9O2`UrnHO9 zzAfy1H%x6vtcupm!}AyFhmhGUHks$w2E2-(enVU}rCow!DtFhubz|1!MBQ$$OSI}X z&^+Z)VXWI4X`Z%zaSJCb;Dl^avdLMp(RC`2E8{sUD23BPb?X`31A~ghx+g{?MD&TO z8nVOQhX90VO>`9j!7SR%aH1v>5WWb=s}UUeBi)keV`2J$p@|@sV92zA=1$7-sj&B) zP&0Fe?Jt25;tK2Adpaz+RUH)2EnTO1!vljGX)~z{%*Ppj-Ge3VX zC!_pw+l^8V)K_~5x*>iG-xl`91!bNFT6W{LCl#I(NMAYmJB#7F%QViC}aA+r;#F(&*{>p-`O(VxvyK zb;K^n(E5!Om?j=4+9)I8Dk{U?*ZpvORfN4ofH8tCGCDg1HKa#FC`$kV9j2`C%3uY$ zvGYlWTP<>!FouT%jK_+|Kim}deh}Ct%_w^4nbm{GY1}+Uv?>MX%rUl_etLdQexel+wjwd+5L*~v-)Z6E@@1YsXtDq^gS=d zv@3lZL!F*jWzHGpbtZbTlqstKd}?;TId-!&wkN5N z7HzaV|M;2X1IOuTc@5Y=Yx+0Qv%9S&}6f( zSvQ(s8!A1Bq0Z!kH21(Dlc;~WoR`=MiaBJDDYDx`VhA8u-5mMdNiE441+#4H`|5!|!1HmtDS7=Q5Jzh0NyhV%#L z_s7w;q0ED}i8F7eAFNwX%x+Zv%%L#{^>7}N#cJ-4O-!_EEV`|UM#2bTuq$p{qu;o} zJqRsO2Rnb&uCIYMgCC0U-}m9dei~Z5`614;4Gn&{|5x4mxsdzYhorxO59iw=9lAgK zW5rz@Mme^jOCRdCssU2gLIcqo-EAJCz@BV}ZchI?LbE|`Hu}YI*b9LuX}48vx5R?X zyRDk;XHdG4>PKL{M&dquHXV2RdCT+FWBCL=$ygX`6yLL_@nP-e>at6ST_bT9s7M+K^LYpbz#?VLnDhZ~_L0dH3DGOuw^pt6m2 zWXYOIS_uVmBIhQR=Z@l+Nq{irV(O;`Y-u{anf-iLEEv{!F8!NIQ-7W5h73 zl2}8l6mQ6Pf!1H7t@%pVcp!2=23nz`M3KP?P=>zbBSn@0aN8j6R8XfWJ*hZV5p$a4 z`~fggFx?YmBYBUoau1e&>PiM16fOCVi4uAi3QZ^^J?eYF&2Gu&sv{@5Zl zw|Kp^h-|1D7bS{RZC)JUV1;jiMUd8N5&$Q1_%HL#w=4$MRgtjxiInwQ}nQ$QCJw|bDKkXVn5{c);q;9bfSEl*4Z?6IUfgI}&VZK^~AF~D3*^{Mn# zAB&^4GzoyM$wK7i< z$m9!se;H0Pp#13GJlnvA`Tdk$=3KcRM_7!NPjvpeay_M!+Gv_i-6ck^EiQ&=) zZE7>YcnL~R=}Aq&;{oqANz3WDCqWQ+$sg9IRD&wQ3M8}mGpVmA(fXN$iZ#Xm|6;;B zL|f9W_ge3L;Jmd3CZq%$Ps*j0>z5DG^vWl|SZV{v2wY@9WROzFu85xwdfX)1BYfyw z@B(TAO-La0GCYSP&zqr_YT&dCzXV3>p~sO{&D{YCsz6{{6~)mU@Ii4kqA}JaS<{f# zWDV);4}JCo^(4jhNCh~~kD2u11tnW$n`)qm5Di#AI48kdVUMv=Qw zsx+=@SUrd#=Pjwa=aLKQ(#IRKUG2xEtYya~15Pj5Bx&L|NwM(?KZSAe4r#_LMINcq z2&uhN+}z7h=TB7xll|bxK%X12_T1KO*VWCbvn;PkwdUFQJGi>pCecXcS!s>mD-VPH zG9UNi>0TEGSAu&j#r#R2Q+OJY%}|!#dn2?EMr|)14NBFJ_Y>*v>SDr~iam6qH6N5x z2y_B=b3Wv?Nj0RTHQl=RMo(QTzxVq2HM*gmdB>&m<9~oaJfUpl57_CzC5F1OlUi)8 zDn2gtX~^^E$n$dKc{TDBBhMjC$U8S2^45i?M7YDSHr*rFZ_OeLBdb+k3Z5?e|9dg7o|$op$3?7cqxBv>mXqu<-wjk<}`RLuJ< ziiHsUVHDDQfLOA)7>Kh?h>Zne$U^u-v@IpX5wV#@6gRT^`d}53E!GEtP*y@>86-@w zWZ>z-9Lq%fnDC6{DRq2V&CpwqtGW7)Z&HzVEJxpX>(5AB;1^MMwu zpV*36J{A^sl4MGk4Iq_lfJ)eO=+Nv;JasCtP`5c1o@80JsFWQv8O{*3cwxBXhFw{5 zlI;CQ!*Zyyc?EMw$M5C$oAQ46i5IMUc_I4FaW#{|bv!$Xu$^VV$&;#jP!&sE*&tXL zxB~cZ2_JJOXuff$bKklX!O0-(eS>IU9bl;e!;796Lcu?TxZ3!=OND3d9Gp|%QO3t{ z6qv|a%P+}n#i zMzyEH@7*DE)jT+w<%+=li^`qUy;^)0gn%SeUm@sfjVUy*2Zag-ZP>`mdT7D`I?Enm zZEY?-BT7<+YQbtS$`8bTZO2o>KHn-H9s|B}g<%jAt`C zA#JGze-21HA$_Wr_#+{)_y{p*PBH|%tZ-;7&)E<8=Y zQPm|p9J|SOCZ!(tp*+86rK+wN4&LRHc5b?9E)~khH=tafOO;w*L6zYtG^gqiObRFTPy;?+ z76hJLf(f};RTud?43>iV(-)M%*6mqQUqKuuqG#)PQ)l#?=sROT>MgK$K>t{;2h)<+ zc(=q%J7&7^gSmY0WOIebtx5zR8Srl<0l^-R#9E?>`ml=<-w@uNUpN+|t%%tQ>1&31 zAE&A)@B&Ne1V@bz5j$P*%zqQ~=fYicagp%LT~ATp`i1-M?!%jfnfENf3x!wjsQ|^w z#d}u9g}~tkGodEsR3n;<{jbjduL=vt`r=KzzD+B*OW(lFk3s1_!- zTzF*RK$9U4^@vuUx;GY3hCt+{dtuh%< z<_;gy5?*^1#DskCK0SD2jNlRGV-^zIyLh2ToE zP&(RM@AnRcZ?+S!sd}*2kX@E)K;k`N1pXK4U_qE0#*orLYIY=50I7;F3X|=Xpr$I z>eJdcZASW@EAb`t@)QSAlZU;nT_mor0Bb6-fP#Xjm5+#Dus|8%)BDqKxp3kBu@ig3 z3XXTY(_n`)_`YC;l#S{;@r=Ci9E@3}vc2z-7}n#-mc+bdfh9Z-QX6CMn{Bjex@E zgjQ=IP8Pnh&Zn*gg^XnnC%qbwbD{&5TJNTYj)CLKv~zy1On7~n9=8ggF3V(B24tMi z+ZPrtFU!Geg!l(?ZE$9TyN%zwILHIBojm+AkiIZX4>*jSTW$(@!IhD40pQ;O>M?QY z5uzGK;(I}*h2a+SW4R_Ea~W_x`M~Ioaunx6-oFMB&*T7+%NcYUO{GBOR$22K>Aut# z;IJ)DZ6s_j3l?DFVESx9FuIa{0q4g8)uI~-bv0Z4-g&p^ATduj03D&m<=<&)5maahoU@_fI9fR-v(tF^f?X8`k#Fl-Df3@t!TiJ zZms3Mk~FjY-d8|36Y~BLWIS0kaUgrhTDMI9z}r%p{lpcyK32aO&c44oQ1*1N7>?+h zzLL^sU3AX|BanPo>7<|BtHG{(2%a&rHunr}z%6z>8}X(X%i*12uO`G~B=pkz@oqu~ z8sVQ{d`MkB5q5*DO@u>};c7w5pd;hl`vNZ63&OVs4!zPY8Rw52dS62RAfVshdw4k3 zVClT{La#gqj3}do*B?s5VWIP(4*Z(1`cLMuPY=5R5E(?s`85~lq~F3K~)+?9t$&dhhTYFTR0k4-f?~rcqE+wOSTNqB>9<) zXkh%p-eUmoo81rd0<-SWX@~=c99;bT-V$N>;i5nF zfO8CJZ=M22r0g4R;19 zfH&mvD=2$LC)Uijj(JLN&3r1AtK)uk=UeAnGoF&%^ZD?une1#5*gWEGR0ZaT!t9-4`d#8^WR}C=LaL#Qi;rA}@gu|f3c~)W!NSjd! z`;CP|wy#HhQEKQ(tDZG*=`p0g>W>4Dp)bOE@PtmTCWrL~@cWS4w0>`2fczaC-X-0u zLi)_yy~`7TnGbn4Nn0H7&WZ}ZaNZ@|3n0`12t95&4B7AfJn$>*g=qQj@TBEeBa7h= zj{4I_faw7a`}U56IR$)yBfb(2(%})|LkVfiFi3ofE4Z4Qw%Ga)fFXEMqKx=2SX>mq z;1^kCQb3_8!@s)a5Kjg;e*&|L8aS#Gz!|wABmnuF3xRCIIIcV+Ny18%V@=w5;NR+j ze|>8BhMTg0t(H^sNTiOiP?xysHUc?Ra@tPf;33rnz3Xs<8--NCo zw!aC?Y|z^uTp+RU-(4PihB*mVFs>4I`#xzp#6d5D-3E=kyg*{o+w;dyf=t?^Un^(ez#2EDvhGvIC~ae=wH6GY~DCb8??)?nzr=D#f8ZtJ8Ib zGQVbxb$ks*{wCAk1}HgqHimCaomUoPEw-|}5oC>eYbAJ+F`&A`bgKDliO~eTp9ke0 zmbu`F8DLQ_xM8(e6CAx#tlOy*JFs4d|w;2}4{_LW0hLGRye zK@znFKQ=Wx_j_1s3M{)}Fmvp1?<*g3@*UU_<=jDc9*45ucbD+d12nY;M14#bTi00s z040%tVmRiW&K+}`;93&~Y1wQ&=_V~d3asrO5(~@GxYT1P5$eHls^&0SSgFyj5HQ7sS<%rc{sB}egG~4 zrQsd4K#3pt>6Tgp-c9__|Ml49>>WWJm&-Bxkf@dv;3K7i^CIZI6Slt9fjQj5Le8Ir zqQ{GD095t`$=W7>sfs9tk*L^w)RV1bf&ZceJwF%FfhV8knkx!^6ePT-C7t9_J3+)6 zAFaECJHj3D%v4&=9QEWYXE;YgtWi#L9`)#zcK|vKbZ>i9e$5#*+-ghcru>TAD@8j? z`Q^7M`i^=EmAN)3YEbsODn-mvtst%(pacTODc62aIp|*-&O`$zUO9vo-tXJ$Bh9eg z^6^JK4=RV-jp9~2E~*@|SANxwbldtWMT)Hy8TOpJQe@eG!BfSaav!;YY)5}M>UmmO z2z@=F%!B8{$}CsTke$!;*|tcPLmK{5_fb!tQsp8YECD%&a_ajpJ@pZIB);2CAkN_K zGgXRP*bkuG1m&4XIit8{6Lj9N7v8N>#=tvdQ+ETX{7BQJWz?_>a`{NEef1x?s3Frw za_#)HHps45Qr$TK#K=q3u+hEW^B|0U%h{uzI+&0T8l%OF^nB3IpJ_bH{nfHaVh#`- zvE3~k0l1bM-93c^W~vB@-v<=jYd;?KJfyS@{rO-t2Ov}`wJ{z=lropymn$lwa=Mk; z&Z|@m63hIrOSUZ7OHmZgGda~Fr8K$JV1&f*1GJoV-OlNG4Uod-3OsYzHMtCpBPAKa!u`v3$yGG29?r{?yA3HTuzG{b#pqoqX zR`bjb5<~q|nj55DhD9=523|b&Kpn%V7 zEzdd^D~YEAX?T!suy${^grDDaQfDAW~YwNI!Esgo9Sje<%sD_w~`~EDV%H5Wv&ST8YZB< zj$4nFN4s8^vNezdl#HM+aWYTKt16wG^x^XMY$Q>WXAQPihhyAPy2t7K?uSXW!P+g?KB#T3AT!1E76VLKhFXm_PgLD1!h)IbeS4~i!J>Z1 zWWWBo-J3etUQxDpKo$dj)c)qavp|H9jbKgQ|lcc6DsGx_x2$r^!uj zGU8M+;{OadN0i4LwRsjQ$@n-pELPL!+N1KS&P3%`oVj?J7Hh|G@Jr^n+ers89ww?6 ztWnsBv_HB@7rt9v*xP&Bhuk^hn3!m=S&ra}b|w>CQ4^d5Q!Cw6Yg)rS`Oz+_l^knk zK9yJO#4t@@k#7im@rwmeo(AZ^PC&XvrN1z;Xy9KD=uv$bULj8M1ciUYr} z`mfwaxH7kyJI5`8=K^=?ki7<$S_$f-N_yL^?pfF6RBAt^oH?}Q;2>!O))9s_Vg_Vz zG9EJBu=V~yXvl120qF#y0Gos~lmKh?DCaEC?|m0onlEWzp-~BS-CKHFyS_QWS zguwJ}JzUp@T^^OrT}Up4TTVJI9~?_R9*)X8${mNhPg}UC^M>LB<#NzTvfXc$Up;By zx)OnZB+NT@-d^l+FDU-q9lk0Yd0Jx|<5~?SOY_(=kz%4!4Vr(bUol0UN7=_x5a_}d zKQ{fb8Mm%DfvPg*clY7nj4__yR6gooWg^S;yW4*2S@+j#Wh)Q=#;uFIzfdMJ%)i}# zy*6vz;otrqDZBKvsfyJrv$5u{*X~%kZVzMzF`Xr19V zMa*BXF+?36=5X|KBW0*`-i5ZMLIdUX`v2F|xY zUNyq3_1eTuzFc72XppVH_sM`b2fe$6C)a1=w}jU9&PivwIGEmL)DH6?P`rA}3Kr8j^xe!)$b6d54f|o3>;++>L{d3~JbA18&obVnGd5^vt=N*=^Cg!(&9uvQJ2bGaIt=`6>Je~W4i64 zq}udi8_GUR9AGqC{Q-Etg@hDdP;&in73mmVUt|AtNIIT8$Wv zu(VEa_Gn3KNUWcAJ%OgQihXGO2U0p%#g2zK@T0(!vG_^&BrIzzeiz0Dqj+~CGwGDO z7=YRZYQUcBPd6rk&DkjaxiLQlI#X=}VZXi+Y?d~3eO2Q{N#j_=?Kh2feF-&oz%YP8 zSk{=;X^PmHGvMgUA7x#TDbqD4SVZCFu%bd-Xn_I`I~DJZ2FLHuz);C(|v$U4abd9q#o2I)iO1s)fiSquKm_;16iBE+_ zDy$7HET1{_@`tce6Uj;)S*MGG7k(Mpi*tgaV@>)f7g@=QeUx@2zdA?&c{eyJ!efvP zlt!oJM*(RBbAkxB0^vD3^qlFE^CYl12_^sAa$yiGT7vDvU&2>E+etopfglEYY*Efe zIc&EYrsNa7UWPz{2gNEn6+v?&l>WA|5J{vH^-{siQzcl9e=d6i&z<^ z!2Y=}5g5JDHV;L4OyhOm>(iZkE_NP_JVI53> z!@u;98uZQZK?I-S5EgTX8O{uzMj`K$V0BLHO_;NS%ZDM>_^4Jb$8-9jBdgY!MFUL< z0q^g@hrzs;17MW<3>*t6u7`2H-&r&C<0RRfUf9V$!fu3*u)wIvh$jJnA3^-bh*$pC zh)G_QMbQE3#hjSlkpW`33jY1`Ns~z)v3PN6nCd5^Y7U!Nm(+!ITCNoE)*iw+j1$j5 zg*RMyl1S*slRh_m|6z+hWi2=dFkB|sq5|Fvz7boFx(|zk!rfc61**`GZVL}i%RCaB zK>MibS}m%Xb8e)MX>`J+tSbKamapwJPp+#7FKsbmM)-bk5f* zUtw;yVA`2S`9i{@J2S@h!z6^gIpN>ndq7uREqVfQ__`+?lnHqXcy8@-8tvVh7yx(>;nn3fj4{sUjKBAMiGWiRxf0bbJvmz`hPgGP$}di%=v` zp_uy4zPtUchiA5*Txz=Ot?h@0$JOKFg!WfWZ*9is-pL>6I zeb+39@ln(EP1{F27qBzzy{o&vqO@ZZfA0$8^{A5F;8;6gPdIP9u85@HwL5N@;NOO@&U!jYiudC+rs4dO_KgG(BE@0_@=O1c|@c?~K(D?A3S zQ1JGg9j-PS!2c2037Ayy@+vikz29^R%bV_@yL|s6bTw)5--L@zDXPYx46ej$xVNQ^ zFtx{m0=r`Z^*~T4-Qi3iLnGfnnCoD{zUTM;Gbl8@pkV^ue};s^FO)%|JtPEPC}oDd z^-yE$9>x#MlyH7)F%=gORNFRFU;Bkuw&hVBe&MriU>fySgoOTW#Tk|@h@Az?cE)zZ zf~AW~;#hEUSpk3`ah6Y*y8RPdNw5uo4|{7u?}L#hN%kHPH&O*;SF@7aDKR~B*S@lL zc0Vp~t#yL8=}w7m;`;HpriSgc+tuzeJ_P2rC ze93;l?^2c1L zV6}_X`yvSWDw0YD|B8>?jk$G^8Yut%|E@8={BEc+-<8j&*8^)|FIK3laUTLv6OL9%iV_V$X+{rG*gc4Ftv#VTK^-{X6 z(}^_A6(2!X`mO3}SDZ-4oq=1cTO@lQ%HQY2nro0Bdn=!X7;d!YzviSgKf;V?5D(A$ z(1Y;lhzJ#~dATi1N4^&z1Ln@}{W=79DWVvC4RGc}gIF_EUHh%1YLW}zUSVxVzr7OO z>i5QhRlgK0_%RB(W0JM>mU_Z`{fQj#lgl=NrEXtnlt&fEcuv4|4O{&umzC(mmBPDE zT$y`?OES;fNb=giX7BfI_Q}9? zkrb)#h~=1^e3(D*Ow`h2Gf~nUQUVxu{afiN+$Iy{p{UWlMnvl=LtTAOyQW^=N9!4l zr9Mi})^Dr-vcA46YR=E@s5w7D=yU&eFX+W2oK8v9s*7Z+ARy^ux~Dqe3tbQjAQVAB zmGu>tL-DWlV%#lUdsR#Q(b0xCU#({K$6dcTZhC0 zPiW4@yM@l?H0q)x{IfX^pAhiw{IR{mG5e!;Q~QXSYHc8jd}?ffT==KxE)EN!-L=$5!-r~Hc=%eM(Ak|COfLpdjVyTD1J#Qq&1h(%w!;|@R7q4)s52cB;$(O&}IO85?wyqB0s zaWnCa9&xJidzTB|*A|Uh3iu;fiG_(eCMz;EQHzVyGXisSyP zG&pWnzENr0&XMaVo9tUn$y~+RcHhS9CdX$U4a$N~TkbHvYBcua*j>h&{^Ux1?8koT zW~T4?5bGcFsktAU<^DL&Zd24*zgq4I8|-3A<8G7j`j|%Qj%j5}Qr~VrT}9o%M8oL#Gq1wg2iM2fv) z-^_iLy0_io4~cPpRXhM(#`=-8r(AIh2^PSOa(}+~)+qX20VG{LmU7ee+fDBBMkC)LEm!Ovgf31V2)oe+=mk z@WTRr7#}rs3rExK;)`~IqpkK495n)tBH%@af&A>PVE~S%uQ|ERW_s)_RXU~Y>r}uH z*Wmubqlu;ALcGowJD6_P_+q`-Cm*coAAP6R7wgG1Pa_}Tosr4L$Y(JV2K5nB{;WidfiOa#TXQ)U|g*=z%(!x6ZZ!hkSxKN zWyzA+8FT>$eQg=C-)+0OKi1^*-1F{d&%N*U-t*4+jim{D$EZ#h)&KR(z5(wQ6gxC! zC5z*exD0lzl%Q6A{3u(Vc~n{T+er7AkhTwKH`Mk^P?Sf44f3bKR=FqmwtOU5B3B2y zCItP<>oUDTzB=;pB;;|gI^4g8K$0YG2rG^#Hh;UTq`Zc(QXX9=g%uls98}eL2#nwd zuoeItaKKBr?@91{jA&uEZ$9|Y&~hPy#r4*(y5jGx6f z&&QtWIGo4zJP0=i=9%NELr85B0AV?Nr?}n>d{pzKAqHRh0??BWmZNZT1kQiZH#q6*lHQ`3CgyriR*)6hBP|ey1f29Bn*>)_DQ1oBMrvdy+l|?pXv;Vy z-`&(A+!i4ximpe4643~|-!6H}5b#1u!U06xzFHYW^(?I^1!Adc%A2X0I=cCsz_1D? z!^==*BKG}9m`WjKC1$bA6H=B(meibgI)*VETwM~e;s{mN5K=4=iwpkY(;7J+eARRw z3>ay{76dn#f%uU${1k={?dYamSUAL5RoUgV^%coUSZWs|8rj{m6_#WDbKWG4WYiR4 zjjuqX(*U*1L|Dw1GlD4t{1kjUN&XA~jAoRnnJ|nLZDrIt5NyMg*4l}?1)8z3;Y&to z2mTNmK`O-CyDL>S(zw^or@sMu$74&yFuR=O;laE00EiQPVP#dAmQ4l4g88GV z>**NDG~9xJySv%r%V|z_4U7#4wE*ZV@rm0c-|L=oU;j<}WQ!E{n&pcuTMh@;!rA*9 z{3dll{I4!^lJ1L6ai2SbX?iaQFe zXFbQ9$)f-#&N$}OKG0O3^t3uZff>gj$JaFJdkdO*pS5;m(HwTB!$KFayB$Vb#2uz7Sk@<2#dC zFh8t(F)R6=R&p;*V)h$4U9`?5!K_UP;arvAT1topvJNumB4mUoiOGrlB*?scNvIA6sG-|{?R-{uw^Fc2qh_1#W23-Z+ zLo`nh=OA9;`YN=$mWZ9Wei_tM4$D1wYXuQsduNaTgX`(kduB7t_Mmtdgj`6Z_ts;} z`6i;hx1dvZJpbqI7}VByx@QME1MzxS6WnsB*m8)>KH0dRh>tx)w1Rkk@jmDwk>>KD zJ@4&)_rRJpQdJ#GxiP5b21Ebo4Ff&plh!&uC*r=(h`8+(UWkGF+X&uz5OE`D2WTg# z;xq=0V<&G+cOuTu;atf~{<%pXB{KG~CZAKad}S%?^DU(V{wKZ?N-wcR{=H&47;^+Xk0GqGF40=VAm^x2>s1areD~YPD)YPOzriEB*$U1jyk4 From e1ffc2cdaa670494510827f65f508c4bdb22b57a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Thu, 16 May 2024 15:51:04 +0200 Subject: [PATCH 34/34] commander: add check for 5V overcurrent --- .../checks/powerCheck.cpp | 30 +++++++++++++++++++ .../checks/powerCheck.hpp | 1 + 2 files changed, 31 insertions(+) diff --git a/src/modules/commander/HealthAndArmingChecks/checks/powerCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/powerCheck.cpp index 8b40191c4212..0b23a949aef6 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/powerCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/powerCheck.cpp @@ -142,6 +142,36 @@ void PowerChecks::checkAndReport(const Context &context, Report &reporter) power_module_count, _param_com_power_count.get()); } } + + // Overcurrent detection + if (system_power.hipower_5v_oc) { + /* EVENT + * @description + * Check the power supply + */ + reporter.healthFailure(NavModes::All, health_component_t::system, + events::ID("check_power_oc_hipower"), + events::Log::Error, "Overcurrent detected for the hipower 5V supply"); + } + + if (system_power.periph_5v_oc) { + /* EVENT + * @description + * Check the power supply + */ + reporter.healthFailure(NavModes::All, health_component_t::system, + events::ID("check_power_oc_periph"), + events::Log::Error, "Overcurrent detected for the peripheral 5V supply"); + } + + if (system_power.hipower_5v_oc || system_power.periph_5v_oc) { + if (context.isArmed() && !_overcurrent_warning_sent) { + _overcurrent_warning_sent = true; + events::send(events::ID("check_power_oc_report"), + events::Log::Error, + "5V overcurrent detected, landing advised"); + } + } } } else { diff --git a/src/modules/commander/HealthAndArmingChecks/checks/powerCheck.hpp b/src/modules/commander/HealthAndArmingChecks/checks/powerCheck.hpp index 72ed92839101..b81fadaee062 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/powerCheck.hpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/powerCheck.hpp @@ -48,6 +48,7 @@ class PowerChecks : public HealthAndArmingCheckBase private: uORB::Subscription _system_power_sub{ORB_ID(system_power)}; + bool _overcurrent_warning_sent{false}; DEFINE_PARAMETERS_CUSTOM_PARENT(HealthAndArmingCheckBase, (ParamInt) _param_cbrk_supply_chk,