From 28d9c6da588819f834e30151f40b6ea40286de67 Mon Sep 17 00:00:00 2001 From: spdis Date: Mon, 25 May 2026 10:31:55 +0800 Subject: [PATCH] =?UTF-8?q?Initial=20commit:=20SmartCar=20Framework=20v0.1?= =?UTF-8?q?=20=E2=80=94=20=E9=BE=99=E8=8A=AF2K0300=E6=99=BA=E8=83=BD?= =?UTF-8?q?=E8=BD=A6=E5=BC=80=E5=8F=91=E6=A1=86=E6=9E=B6\n\n-=20HAL:=20GPI?= =?UTF-8?q?O/PWM/Encoder/Framebuffer=20=E9=A9=B1=E5=8A=A8\n-=20Control:=20?= =?UTF-8?q?PID/IMU/Motor/Servo=20=E6=8E=A7=E5=88=B6\n-=20Vision:=20HSV?= =?UTF-8?q?=E5=8F=8COtsu=E2=86=924=E7=82=B9=E6=A0=87=E5=AE=9AIPM=E2=86=92?= =?UTF-8?q?=E6=B4=AA=E6=B3=9B=E5=A1=AB=E5=85=85=E2=86=92=E9=80=90=E8=A1=8C?= =?UTF-8?q?=E6=90=9C=E7=BA=BF\n-=20Strategy:=20=E4=B8=89=E5=8C=BA=E5=89=8D?= =?UTF-8?q?=E7=9E=BB=E5=81=8F=E5=B7=AE+=E9=80=9F=E5=BA=A6=E7=AD=96?= =?UTF-8?q?=E7=95=A5\n-=20Debug:=20=E6=96=87=E4=BB=B6=E7=83=AD=E8=B0=83?= =?UTF-8?q?=E5=8F=82+LCD=E9=A2=84=E8=A7=88+cv=E6=88=AA=E5=B8=A7\n-=20Sched?= =?UTF-8?q?uler:=205ms=20timerfd+epoll=20=E4=B8=AD=E5=A4=AE=E8=B0=83?= =?UTF-8?q?=E5=BA=A6=E5=99=A8?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .gitignore | 7 + CMakeLists.txt | 32 +++++ bench/bench.cpp | 128 +++++++++++++++++ build.sh | 14 ++ control/imu.cpp | 81 +++++++++++ control/imu.hpp | 24 ++++ control/motor.cpp | 72 ++++++++++ control/motor.hpp | 6 + control/pid.cpp | 53 +++++++ control/pid.hpp | 28 ++++ control/servo.cpp | 57 ++++++++ control/servo.hpp | 12 ++ cross.cmake | 14 ++ ctl.sh | 87 ++++++++++++ debug/config.cpp | 20 +++ debug/config.hpp | 4 + debug/draw.cpp | 88 ++++++++++++ debug/draw.hpp | 17 +++ debug/tcp.cpp | 25 ++++ debug/tcp.hpp | 8 ++ hal/encoder.cpp | 64 +++++++++ hal/encoder.hpp | 26 ++++ hal/framebuffer.cpp | 60 ++++++++ hal/framebuffer.hpp | 23 ++++ hal/gpio.cpp | 43 ++++++ hal/gpio.hpp | 17 +++ hal/pwm.cpp | 57 ++++++++ hal/pwm.hpp | 24 ++++ main.cpp | 97 +++++++++++++ model/best.pth.1 | Bin 0 -> 140663 bytes model/config.json | 33 +++++ model/deploy_README.md | 39 ++++++ model/model.cpp | 13 ++ model/model.hpp | 11 ++ model/model_heat_v4.onnx | Bin 0 -> 120667 bytes model/model_heat_v4.py | 100 ++++++++++++++ scheduler.cpp | 289 +++++++++++++++++++++++++++++++++++++++ scheduler.hpp | 10 ++ strategy/deviation.cpp | 72 ++++++++++ strategy/deviation.hpp | 6 + strategy/speed.cpp | 47 +++++++ strategy/speed.hpp | 5 + tools/calibrate.py | 43 ++++++ types.hpp | 195 ++++++++++++++++++++++++++ vision/camera.cpp | 56 ++++++++ vision/camera.hpp | 9 ++ vision/element.cpp | 188 +++++++++++++++++++++++++ vision/element.hpp | 23 ++++ vision/preprocess.cpp | 131 ++++++++++++++++++ vision/preprocess.hpp | 10 ++ vision/search.cpp | 122 +++++++++++++++++ vision/search.hpp | 9 ++ 52 files changed, 2599 insertions(+) create mode 100644 .gitignore create mode 100644 CMakeLists.txt create mode 100644 bench/bench.cpp create mode 100644 build.sh create mode 100644 control/imu.cpp create mode 100644 control/imu.hpp create mode 100644 control/motor.cpp create mode 100644 control/motor.hpp create mode 100644 control/pid.cpp create mode 100644 control/pid.hpp create mode 100644 control/servo.cpp create mode 100644 control/servo.hpp create mode 100644 cross.cmake create mode 100644 ctl.sh create mode 100644 debug/config.cpp create mode 100644 debug/config.hpp create mode 100644 debug/draw.cpp create mode 100644 debug/draw.hpp create mode 100644 debug/tcp.cpp create mode 100644 debug/tcp.hpp create mode 100644 hal/encoder.cpp create mode 100644 hal/encoder.hpp create mode 100644 hal/framebuffer.cpp create mode 100644 hal/framebuffer.hpp create mode 100644 hal/gpio.cpp create mode 100644 hal/gpio.hpp create mode 100644 hal/pwm.cpp create mode 100644 hal/pwm.hpp create mode 100644 main.cpp create mode 100644 model/best.pth.1 create mode 100644 model/config.json create mode 100644 model/deploy_README.md create mode 100644 model/model.cpp create mode 100644 model/model.hpp create mode 100644 model/model_heat_v4.onnx create mode 100644 model/model_heat_v4.py create mode 100644 scheduler.cpp create mode 100644 scheduler.hpp create mode 100644 strategy/deviation.cpp create mode 100644 strategy/deviation.hpp create mode 100644 strategy/speed.cpp create mode 100644 strategy/speed.hpp create mode 100644 tools/calibrate.py create mode 100644 types.hpp create mode 100644 vision/camera.cpp create mode 100644 vision/camera.hpp create mode 100644 vision/element.cpp create mode 100644 vision/element.hpp create mode 100644 vision/preprocess.cpp create mode 100644 vision/preprocess.hpp create mode 100644 vision/search.cpp create mode 100644 vision/search.hpp diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..e2b639e --- /dev/null +++ b/.gitignore @@ -0,0 +1,7 @@ +build/ +*.o +*.a +smartcar_framework +bench/bench +.vscode/ +*~ diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100644 index 0000000..abbe9f7 --- /dev/null +++ b/CMakeLists.txt @@ -0,0 +1,32 @@ +include(cross.cmake) +cmake_minimum_required(VERSION 3.5.0) + +set(CMAKE_CXX_STANDARD 17) +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -O3 -pthread -Wall") +set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -O3 -Wall") + +project(smartcar_framework VERSION 0.1.0 LANGUAGES C CXX) + +set(OpenCV_DIR /home/ilikara/loongson/opencv-4.11.0/loongson) +find_package(OpenCV REQUIRED) +include_directories(${OpenCV_INCLUDE_DIRS}) + +include_directories( + . + hal + vision + control + strategy + debug + model +) + +aux_source_directory(hal DIR_SRCS) +aux_source_directory(vision DIR_SRCS) +aux_source_directory(control DIR_SRCS) +aux_source_directory(strategy DIR_SRCS) +aux_source_directory(debug DIR_SRCS) +aux_source_directory(model DIR_SRCS) + +add_executable(smartcar_framework main.cpp scheduler.cpp ${DIR_SRCS}) +target_link_libraries(smartcar_framework ${OpenCV_LIBS} pthread) diff --git a/bench/bench.cpp b/bench/bench.cpp new file mode 100644 index 0000000..bb6f2d2 --- /dev/null +++ b/bench/bench.cpp @@ -0,0 +1,128 @@ +#include +#include +#include +#include + +using Clock = std::chrono::high_resolution_clock; + +static volatile int32_t g_sink = 0; + +static constexpr int BLK = 512; +static int8_t A[BLK*BLK] __attribute__((aligned(64))); +static int8_t B[BLK*BLK] __attribute__((aligned(64))); +static int32_t C[BLK*BLK] __attribute__((aligned(64))); + +static void init() +{ + for (int i = 0; i < BLK*BLK; ++i) { + A[i] = (int8_t)((i * 13 + 7) % 127 - 63); + B[i] = (int8_t)((i * 29 + 3) % 127 - 63); + } +} + +// 运行足够 reps 使时长 >= target_sec +static double bench(int M, int N, int K, double target_sec) +{ + auto run = [&](int reps) { + auto t0 = Clock::now(); + for (int r = 0; r < reps; ++r) { + for (int i = 0; i < M; ++i) { + int8_t* __restrict ar = A + i * K; + int32_t* __restrict cr = C + i * N; + for (int j = 0; j < N; ++j) { + int32_t s = 0; + for (int k = 0; k < K; ++k) + s += (int32_t)ar[k] * (int32_t)B[k * N + j]; + cr[j] = s; + } + } + g_sink += C[0]; + } + auto t1 = Clock::now(); + return std::chrono::duration(t1 - t0).count(); + }; + + // 短跑估计 rep + int reps = 1; + double t = run(reps); + while (t < 0.1 && reps < 10000) { reps *= 2; t = run(reps); } + + // 按 target_sec 缩放 reps + int final_reps = (int)(reps * target_sec / t); + if (final_reps < 1) final_reps = 1; + + // 正式跑 + double t_real = run(final_reps); + if (t_real < 0.5) { + final_reps *= 10; + t_real = run(final_reps); + } + + double ops = (double)M * N * K * final_reps * 2; // 1 MAC = 2 ops + double gops = ops / t_real / 1e9; + printf(" (%4dx%4dx%4d) x%6d rep %7.1f ms → %8.3f GOPS (%8.3f GMACS)\n", + M, N, K, final_reps, t_real * 1000.0, gops, gops/2.0); + return gops; +} + +int main() +{ + printf("═══════════════════════════════════════════\n"); + printf(" INT8 算力持续压力测试 (每项 ~10s)\n"); + printf("═══════════════════════════════════════════\n\n"); + + init(); + // warmup + bench(64, 64, 64, 1.0); + + const double T = 10.0; // 每项跑 10 秒 + + struct { int m,n,k; const char* desc; } tests[] = { + { 16, 16, 16, "微型 16x16x16" }, + { 32, 32, 32, "小阵 32x32x32" }, + { 64, 64, 64, "中阵 64x64x64" }, + {128, 64, 64, "宽中 128x64x64" }, + {256, 64, 64, "宽大 256x64x64" }, + {128,128, 64, "大方 128x128x64" }, + { 64,128, 64, "长条 64x128x64" }, + { 64, 64,128, "深乘 64x64x128" }, + { 32,128,128, "扁平 32x128x128" }, + }; + + double sum = 0; int cnt = 0; + for (auto& t : tests) + { + double g = bench(t.m, t.n, t.k, T); + sum += g; cnt++; + } + + double avg = sum / cnt; + printf("\n═══════════════════════════════════════════\n"); + printf(" INT8 平均: %.3f GOPS\n", avg); + printf("═══════════════════════════════════════════\n"); + + printf("\n 模型帧率预估 (INT8):\n"); + printf(" %-30s %8s %8s\n", "模型", "MACs(M)", "FPS"); + printf(" ----------------------------------------------------\n"); + + struct { const char* n; double m; } models[] = { + {"TinyCNN 40x30x3 -> 8ch k3", 3}, + {"TinyCNN 40x30x8 -> 16ch k3", 8}, + {"TinyCNN 40x30x16 -> 32ch k3", 18}, + {"TinyCNN 56x56x3 -> 16ch k3", 12}, + {"TinyCNN 56x56x16 -> 32ch k3", 45}, + {"MicroNet 32x32x8, 3层", 5}, + {"MicroNet 32x32x16, 3层", 15}, + {"MicroNet 48x48x8, 3层", 12}, + {"MicroNet 48x48x16, 3层", 40}, + {"ShuffleNetV2 0.5x", 41}, + {"MobileNetV2 0.35x 96x96", 35}, + {"FC-128 (分类头)", 0.1}, + }; + + for (auto& m : models) + printf(" %-30s %8.0f %8.1f\n", m.n, m.m, avg * 1e3 / m.m); + + printf("\n >>> 稳 30FPS 上限: %.0fM MACs (INT8 %.3f GOPS)\n\n", avg * 1e3 / 30.0, avg); + return 0; +} diff --git a/build.sh b/build.sh new file mode 100644 index 0000000..92ab485 --- /dev/null +++ b/build.sh @@ -0,0 +1,14 @@ +#!/bin/bash +export PATH="/opt/loongson-gnu-toolchain-8.3-x86_64-loongarch64-linux-gnu-rc1.6/bin:$PATH" + +SCRIPT_DIR="$(cd "$(dirname "${BASH_SOURCE[0]}")" && pwd)" +BUILD_DIR="${SCRIPT_DIR}/build" +REMOTE_IP="192.168.31.21" +REMOTE_USER="root" +REMOTE_PATH="/home/root/" + +mkdir -p "${BUILD_DIR}" && cd "${BUILD_DIR}" || exit 1 +cmake "${SCRIPT_DIR}" || exit 1 +make -j$(nproc) || exit 1 +scp -O smartcar_framework "${REMOTE_USER}@${REMOTE_IP}:${REMOTE_PATH}" || exit 1 +echo "[OK] Build + upload done" diff --git a/control/imu.cpp b/control/imu.cpp new file mode 100644 index 0000000..443aa81 --- /dev/null +++ b/control/imu.cpp @@ -0,0 +1,81 @@ +#include "imu.hpp" +#include +#include +#include +#include +#include + +YawTracker::YawTracker() : _fd(-1), _yaw(0), _unbounded_yaw(0), _gyro_z(0), _gyro_bias(0), _ready(false) {} + +bool YawTracker::begin(const char* device, int baud) +{ + _fd = open(device, O_RDWR | O_NOCTTY); + if (_fd < 0) return false; + + termios opt; + tcgetattr(_fd, &opt); + cfsetispeed(&opt, B115200); + cfsetospeed(&opt, B115200); + opt.c_cflag |= (CLOCAL | CREAD); + opt.c_cflag &= ~PARENB; + opt.c_cflag &= ~CSTOPB; + opt.c_cflag &= ~CSIZE; + opt.c_cflag |= CS8; + tcsetattr(_fd, TCSANOW, &opt); + + calibrate(); + return true; +} + +void YawTracker::calibrate(int samples) +{ + float sum = 0; + for (int i = 0; i < samples; ++i) + { + int ret = _parseJY62(); + if (ret > 0) sum += _gyro_z; + usleep(5000); + } + _gyro_bias = sum / samples; + _yaw = 0; + _unbounded_yaw = 0; + _ready = true; +} + +void YawTracker::update(float dt) +{ + if (_parseJY62() <= 0) return; + + float gyro_filt = _gyro_z - _gyro_bias; + if (std::fabs(gyro_filt) < 0.03f) gyro_filt = 0; // 死区 + + _unbounded_yaw += gyro_filt * dt; + _yaw = _unbounded_yaw; + + while (_yaw > 180.0f) _yaw -= 360.0f; + while (_yaw < -180.0f) _yaw += 360.0f; +} + +int YawTracker::_parseJY62() +{ + uint8 buf[11]; + int total = 0; + while (total < 11) + { + int n = read(_fd, buf + total, 11 - total); + if (n <= 0) return -1; + total += n; + } + + while (buf[0] != 0x55 && total > 10) + { + memmove(buf, buf + 1, 10); + int n = read(_fd, buf + 10, 1); + if (n <= 0) return -1; + } + if (buf[0] != 0x55) return -1; + + int16 gz = (buf[5] << 8) | buf[4]; + _gyro_z = gz * (2000.0f / 32768.0f); // ±2000°/s + return 1; +} diff --git a/control/imu.hpp b/control/imu.hpp new file mode 100644 index 0000000..9a28230 --- /dev/null +++ b/control/imu.hpp @@ -0,0 +1,24 @@ +#pragma once +#include "types.hpp" +#include + +class YawTracker { +public: + YawTracker(); + bool begin(const char* device = IMU_DEVICE, int baud = IMU_BAUDRATE); + void update(float dt); + void calibrate(int samples = 200); + + float yaw() const { return _yaw; } + float unbounded_yaw() const { return _unbounded_yaw; } + float gyro_z() const { return _gyro_z; } + bool ready() const { return _ready; } + +private: + int _fd; + float _yaw, _unbounded_yaw; + float _gyro_z; + float _gyro_bias; + bool _ready; + int _parseJY62(); +}; diff --git a/control/motor.cpp b/control/motor.cpp new file mode 100644 index 0000000..c64a8bb --- /dev/null +++ b/control/motor.cpp @@ -0,0 +1,72 @@ +#include "motor.hpp" +#include "hal/gpio.hpp" +#include "hal/pwm.hpp" +#include "types.hpp" +#include +#include + +static PWM* pwm_left = nullptr; +static PWM* pwm_right = nullptr; +static GPIO* dir_left = nullptr; +static GPIO* dir_right = nullptr; +static GPIO* left_in2 = nullptr; +static GPIO* mortor_en = nullptr; +static bool initialized = false; + +void motor_init() +{ + if (initialized) return; + + mortor_en = new GPIO(MOTOR_ENABLE_GPIO); + mortor_en->setDirection("out"); + mortor_en->setValue(1); + + left_in2 = new GPIO(MOTOR_LEFT_IN2_GPIO); + left_in2->setDirection("out"); + left_in2->setValue(0); + + pwm_left = new PWM(MOTOR_PWMCHIP, MOTOR_LEFT_PWMID, MOTOR_PWM_PERIOD_NS); + pwm_right = new PWM(MOTOR_PWMCHIP, MOTOR_RIGHT_PWMID, MOTOR_PWM_PERIOD_NS); + pwm_left->enable(); + pwm_right->enable(); + + dir_left = new GPIO(MOTOR_LEFT_DIR_GPIO); + dir_right = new GPIO(MOTOR_RIGHT_DIR_GPIO); + dir_left->setDirection("out"); + dir_right->setDirection("out"); + + initialized = true; +} + +void motor_set_pwm(int idx, float duty) +{ + if (!initialized) return; + duty = std::clamp(duty, -100.0f, 100.0f); + + PWM* pwm = (idx == MOTOR_LEFT) ? pwm_left : pwm_right; + GPIO* dir = (idx == MOTOR_LEFT) ? dir_left : dir_right; + + if (duty >= 0) + { + dir->setValue(1); + unsigned int d_ns = static_cast(MOTOR_PWM_PERIOD_NS * duty / 100.0f); + pwm->setDutyCycle(d_ns); + } + else + { + dir->setValue(0); + unsigned int d_ns = static_cast(MOTOR_PWM_PERIOD_NS * (-duty) / 100.0f); + pwm->setDutyCycle(d_ns); + } +} + +void motor_stop_all() +{ + motor_set_pwm(MOTOR_LEFT, 0); + motor_set_pwm(MOTOR_RIGHT, 0); +} + +void motor_enable(bool on) +{ + if (mortor_en) mortor_en->setValue(on ? 1 : 0); +} diff --git a/control/motor.hpp b/control/motor.hpp new file mode 100644 index 0000000..4663c5e --- /dev/null +++ b/control/motor.hpp @@ -0,0 +1,6 @@ +enum MotorIndex { MOTOR_LEFT = 0, MOTOR_RIGHT = 1 }; + +void motor_init(); +void motor_set_pwm(int idx, float duty); // duty: -100 ~ +100 +void motor_stop_all(); +void motor_enable(bool on); diff --git a/control/pid.cpp b/control/pid.cpp new file mode 100644 index 0000000..c467986 --- /dev/null +++ b/control/pid.cpp @@ -0,0 +1,53 @@ +#include "pid.hpp" +#include +#include + +PID::PID(float kp, float ki, float kd, float target, + PIDMode mode, float out_limit, float int_limit) + : _kp(kp), _ki(ki), _kd(kd), _target(target), _mode(mode) + , _out_limit(out_limit), _int_limit(int_limit) + , _output(0), _integral(0), _prev_error(0), _last_measured(0), _first(true) {} + +void PID::setPID(float kp, float ki, float kd) +{ + _kp = kp; _ki = ki; _kd = kd; + reset(); +} + +void PID::reset() +{ + _integral = 0; + _prev_error = 0; + _output = 0; + _first = true; +} + +float PID::update(float measured) +{ + float error = _target - measured; + + if (_mode == PID_POSITIONAL) + { + _integral += error; + _integral = std::clamp(_integral, -_int_limit, _int_limit); + + float derivative = 0; + if (!_first) derivative = error - _prev_error; + + _output = _kp * error + _ki * _integral + _kd * derivative; + } + else // PID_INCREMENTAL + { + float inc = _kp * (error - _prev_error) + _ki * error; + if (!_first) + inc += _kd * (error - 2.0f * _prev_error + (_prev_error - (_target - _last_measured))); + _output += inc; + } + + _output = std::clamp(_output, -_out_limit, _out_limit); + _prev_error = error; + _last_measured = measured; + _first = false; + + return _output; +} diff --git a/control/pid.hpp b/control/pid.hpp new file mode 100644 index 0000000..9785666 --- /dev/null +++ b/control/pid.hpp @@ -0,0 +1,28 @@ +#pragma once +#include "types.hpp" + +class PID { +public: + PID(float kp = 0, float ki = 0, float kd = 0, float target = 0, + PIDMode mode = PID_INCREMENTAL, float out_limit = 100, float int_limit = 100); + + float update(float measured); + void setTarget(float t) { _target = t; } + void setPID(float kp, float ki, float kd); + void setMode(PIDMode m) { _mode = m; } + void reset(); + + float output() const { return _output; } + +private: + float _kp, _ki, _kd; + float _target; + PIDMode _mode; + float _out_limit, _int_limit; + + float _output; + float _integral; + float _prev_error; + float _last_measured; + bool _first; +}; diff --git a/control/servo.cpp b/control/servo.cpp new file mode 100644 index 0000000..43f156f --- /dev/null +++ b/control/servo.cpp @@ -0,0 +1,57 @@ +#include "servo.hpp" +#include "hal/pwm.hpp" +#include +#include +#include + +static PWM* servo_pwm = nullptr; +static PID* servo_pid = nullptr; +static bool serv_initialized = false; + +static float g_deadband = 0.03f; +static float g_steer_gain = 1.5f; + +void servo_init() +{ + if (serv_initialized) return; + + servo_pwm = new PWM(SERVO_PWMCHIP, SERVO_PWMID, SERVO_PERIOD_NS); + servo_pwm->setDutyCycle(SERVO_CENTER_NS); + servo_pwm->enable(); + + servo_pid = new PID(400000, 200000, 0, 0, PID_POSITIONAL, + static_cast(SERVO_MAX_DELTA_NS), + static_cast(SERVO_MAX_DELTA_NS)); + + serv_initialized = true; +} + +void servo_set_deadband(float v) { g_deadband = std::max(0.0f, v); } +void servo_set_steer_gain(float v) { g_steer_gain = std::max(0.1f, v); } +void servo_set_pid(double kp, double ki, double kd) { if (servo_pid) servo_pid->setPID(kp, ki, kd); } + +void servo_set_angle(float deviation) +{ + if (!serv_initialized) return; + deviation = std::clamp(deviation, -1.0f, 1.0f); + + if (std::abs(deviation) < g_deadband) + { + servo_pwm->setDutyCycle(SERVO_CENTER_NS); + return; + } + + float scaled = deviation * g_steer_gain; + float out = servo_pid->update(scaled); + float duty_ns = SERVO_CENTER_NS + out; + duty_ns = std::clamp(duty_ns, + static_cast(SERVO_CENTER_NS - SERVO_MAX_DELTA_NS), + static_cast(SERVO_CENTER_NS + SERVO_MAX_DELTA_NS)); + servo_pwm->setDutyCycle(static_cast(duty_ns)); +} + +void servo_center() +{ + if (serv_initialized) + servo_pwm->setDutyCycle(SERVO_CENTER_NS); +} diff --git a/control/servo.hpp b/control/servo.hpp new file mode 100644 index 0000000..41b3bc5 --- /dev/null +++ b/control/servo.hpp @@ -0,0 +1,12 @@ +#pragma once +#include "types.hpp" +#include "control/pid.hpp" + +void servo_init(); +void servo_set_angle(float deviation); +void servo_center(); +void servo_set_deadband(float v); +void servo_set_steer_gain(float v); +void servo_set_pid(double kp, double ki, double kd); + +inline float servo_get_duty_ns() { return SERVO_CENTER_NS; } diff --git a/cross.cmake b/cross.cmake new file mode 100644 index 0000000..8d7416f --- /dev/null +++ b/cross.cmake @@ -0,0 +1,14 @@ +SET(CROSS_COMPILE 1) + +IF(CROSS_COMPILE) +SET(CMAKE_SYSTEM_NAME Linux) +set(CMAKE_SYSTEM_PROCESSOR loongson) +SET(TOOLCHAIN_DIR "/opt/loongson-gnu-toolchain-8.3-x86_64-loongarch64-linux-gnu-rc1.6") +set(CMAKE_CXX_COMPILER ${TOOLCHAIN_DIR}/bin/loongarch64-linux-gnu-g++) +set(CMAKE_C_COMPILER ${TOOLCHAIN_DIR}/bin/loongarch64-linux-gnu-gcc) + +SET(CMAKE_FIND_ROOT_PATH ${TOOLCHAIN_DIR}) +SET(CMAKE_FIND_ROOT_PATH_MODE_PROGRAM NEVER) +SET(CMAKE_FIND_ROOT_PATH_MODE_LIBRARY ONLY) +SET(CMAKE_FIND_ROOT_PATH_MODE_INCLUDE ONLY) +ENDIF(CROSS_COMPILE) diff --git a/ctl.sh b/ctl.sh new file mode 100644 index 0000000..809d3b2 --- /dev/null +++ b/ctl.sh @@ -0,0 +1,87 @@ +#!/bin/sh +# SmartCar Framework 控制脚本 +# 用法: sh ctl.sh start | stop | init + +PWMCHIP=8 +PWMPERIOD=50000 +DIR="$(dirname "$0")" + +init_pins() { + echo "[framework] 初始化引脚..." + for pin in 73 12 13 66 67 75 72; do + echo $pin > /sys/class/gpio/export 2>/dev/null + done + echo out > /sys/class/gpio/gpio73/direction 2>/dev/null + echo out > /sys/class/gpio/gpio12/direction 2>/dev/null + echo out > /sys/class/gpio/gpio13/direction 2>/dev/null + echo out > /sys/class/gpio/gpio66/direction 2>/dev/null + echo out > /sys/class/gpio/gpio67/direction 2>/dev/null + echo out > /sys/class/gpio/gpio75/direction 2>/dev/null + echo in > /sys/class/gpio/gpio72/direction 2>/dev/null + echo 1 > /sys/class/gpio/gpio73/value 2>/dev/null + echo 0 > /sys/class/gpio/gpio12/value 2>/dev/null + echo 0 > /sys/class/gpio/gpio13/value 2>/dev/null + echo 0 > /sys/class/gpio/gpio66/value 2>/dev/null + echo 0 > /sys/class/gpio/gpio67/value 2>/dev/null + + for ch in 1 2; do + echo $ch > /sys/class/pwm/pwmchip${PWMCHIP}/export 2>/dev/null + echo ${PWMPERIOD} > /sys/class/pwm/pwmchip${PWMCHIP}/pwm${ch}/period 2>/dev/null + echo 1 > /sys/class/pwm/pwmchip${PWMCHIP}/pwm${ch}/enable 2>/dev/null + echo 0 > /sys/class/pwm/pwmchip${PWMCHIP}/pwm${ch}/duty_cycle 2>/dev/null + done + + echo 0 > /sys/class/pwm/pwmchip1/export 2>/dev/null + echo 3000000 > /sys/class/pwm/pwmchip1/pwm0/period 2>/dev/null + echo 1 > /sys/class/pwm/pwmchip1/pwm0/enable 2>/dev/null + echo 1520000 > /sys/class/pwm/pwmchip1/pwm0/duty_cycle 2>/dev/null + + echo 11 > "$DIR/speed" 2>/dev/null + echo 0.03 > "$DIR/deadband" 2>/dev/null + echo 1.5 > "$DIR/steer_gain" 2>/dev/null + echo 400000 > "$DIR/kp" 2>/dev/null + echo 200000 > "$DIR/ki" 2>/dev/null + echo 0 > "$DIR/kd" 2>/dev/null + echo 0.6 > "$DIR/mortor_kp" 2>/dev/null + echo 0.2 > "$DIR/mortor_ki" 2>/dev/null + echo 0 > "$DIR/mortor_kd" 2>/dev/null + echo 0 > "$DIR/start" 2>/dev/null + echo 1 > "$DIR/showImg" 2>/dev/null + echo "[framework] 引脚初始化完成" +} + +do_start() { + echo "[framework] 启动..." + echo 1 > "$DIR/start" + cd "$DIR" + nohup ./smartcar_framework > "$DIR/out.log" 2>&1 & + echo "[framework] PID=$!" +} + +do_stop() { + echo "[framework] 停止..." + echo 0 > "$DIR/start" 2>/dev/null + killall -9 smartcar_framework 2>/dev/null + sleep 0.3 + echo 0 > /sys/class/pwm/pwmchip${PWMCHIP}/pwm1/duty_cycle 2>/dev/null + echo 0 > /sys/class/pwm/pwmchip${PWMCHIP}/pwm2/duty_cycle 2>/dev/null + echo 0 > /sys/class/gpio/gpio73/value 2>/dev/null + echo "[framework] 已停止, PWM已归零" +} + +case "${1}" in + start) + init_pins + do_start + ;; + stop) + do_stop + ;; + init) + init_pins + ;; + *) + echo "用法: sh ctl.sh start | stop | init" + exit 1 + ;; +esac diff --git a/debug/config.cpp b/debug/config.cpp new file mode 100644 index 0000000..1e6985f --- /dev/null +++ b/debug/config.cpp @@ -0,0 +1,20 @@ +#include "config.hpp" +#include + +double read_config_double(const char* filename, double default_val) +{ + std::ifstream f(filename); + if (!f.is_open()) return default_val; + double v = default_val; + f >> v; + return v; +} + +bool read_config_flag(const char* filename, bool default_val) +{ + std::ifstream f(filename); + if (!f.is_open()) return default_val; + int v = default_val ? 1 : 0; + f >> v; + return v != 0; +} diff --git a/debug/config.hpp b/debug/config.hpp new file mode 100644 index 0000000..043d274 --- /dev/null +++ b/debug/config.hpp @@ -0,0 +1,4 @@ +#pragma once + +double read_config_double(const char* filename, double default_val = 0); +bool read_config_flag(const char* filename, bool default_val = false); diff --git a/debug/draw.cpp b/debug/draw.cpp new file mode 100644 index 0000000..fbec680 --- /dev/null +++ b/debug/draw.cpp @@ -0,0 +1,88 @@ +#include "draw.hpp" +#include +#include + +DebugOverlay g_dbg; + +static uint16* g_buf = nullptr; +static int g_w = 0; +static int g_h = 0; + +static inline uint16 rgb565(uint8 r, uint8 g, uint8 b) +{ + return ((r >> 3) << 11) | ((g >> 2) << 5) | (b >> 3); +} + +static inline bool in_screen(int x, int y) +{ + return x >= 0 && x < g_w && y >= 0 && y < g_h; +} + +void dbg_draw_init(uint16* fb_buffer, int w, int h) +{ + g_buf = fb_buffer; + g_w = w; g_h = h; +} + +void dbg_draw_line(int x0, int y0, int x1, int y1, uint8 r, uint8 g, uint8 b) +{ + if (!g_buf) return; + uint16 color = rgb565(r, g, b); + int dx = std::abs(x1 - x0), sx = x0 < x1 ? 1 : -1; + int dy = -std::abs(y1 - y0), sy = y0 < y1 ? 1 : -1; + int err = dx + dy; + + while (true) + { + if (in_screen(x0, y0)) g_buf[y0 * g_w + x0] = color; + if (x0 == x1 && y0 == y1) break; + int e2 = 2 * err; + if (e2 >= dy) { err += dy; x0 += sx; } + if (e2 <= dx) { err += dx; y0 += sy; } + } +} + +void dbg_draw_cross(int cx, int cy, int size, uint8 r, uint8 g, uint8 b) +{ + dbg_draw_line(cx - size, cy, cx + size, cy, r, g, b); + dbg_draw_line(cx, cy - size, cx, cy + size, r, g, b); +} + +void dbg_draw_rect(int x, int y, int w, int h, uint8 r, uint8 g, uint8 b) +{ + dbg_draw_line(x, y, x + w, y, r, g, b); + dbg_draw_line(x + w, y, x + w, y + h, r, g, b); + dbg_draw_line(x + w, y + h, x, y + h, r, g, b); + dbg_draw_line(x, y + h, x, y, r, g, b); +} + +void dbg_draw_points(const int points[][2], int count, uint8 r, uint8 g, uint8 b) +{ + if (!g_buf) return; + uint16 color = rgb565(r, g, b); + for (int i = 0; i < count; ++i) + { + int x = points[i][0], y = points[i][1]; + if (in_screen(x, y)) g_buf[y * g_w + x] = color; + } +} + +void dbg_draw_edge_zoom(const EdgeLines& lines, uint8 r, uint8 g, uint8 b) +{ + const int thick = 7; // 车道线宽度 (像素) + + for (int y = 0; y < IPM_ROW_COUNT; ++y) + { + if (lines.left[y] > 0) + for (int dx = -thick; dx <= thick; ++dx) + dbg_draw_line(lines.left[y] + dx, y, lines.left[y] + dx, y, r, g, b); + + if (lines.right[y] > 0) + for (int dx = -thick; dx <= thick; ++dx) + dbg_draw_line(lines.right[y] + dx, y, lines.right[y] + dx, y, 0, 255, 0); + + if (lines.mid[y] > 0) + for (int dx = -thick; dx <= thick; ++dx) + dbg_draw_line(lines.mid[y] + dx, y, lines.mid[y] + dx, y, 255, 255, 0); + } +} diff --git a/debug/draw.hpp b/debug/draw.hpp new file mode 100644 index 0000000..d8670a0 --- /dev/null +++ b/debug/draw.hpp @@ -0,0 +1,17 @@ +#pragma once +#include +#include "types.hpp" + +struct DebugOverlay { + bool enable = true; + int mode = DBG_OVERLAY; +}; + +extern DebugOverlay g_dbg; + +void dbg_draw_init(uint16* fb_buffer, int w, int h); +void dbg_draw_line(int x0, int y0, int x1, int y1, uint8 r, uint8 g, uint8 b); +void dbg_draw_cross(int cx, int cy, int size, uint8 r, uint8 g, uint8 b); +void dbg_draw_rect(int x, int y, int w, int h, uint8 r, uint8 g, uint8 b); +void dbg_draw_points(const int points[][2], int count, uint8 r, uint8 g, uint8 b); +void dbg_draw_edge_zoom(const EdgeLines& lines, uint8 r, uint8 g, uint8 b); diff --git a/debug/tcp.cpp b/debug/tcp.cpp new file mode 100644 index 0000000..9e24d0a --- /dev/null +++ b/debug/tcp.cpp @@ -0,0 +1,25 @@ +#include "tcp.hpp" +#include + +bool tcp_init(const char* host, int port) +{ + // TODO: 实现 TCP 客户端连接逐飞助手 + // 当前为占位实现,后续接入 seekfree_assistant 协议 + printf("[TCP] 占位: 连接 %s:%d (未实现)\n", host, port); + return false; +} + +void tcp_send_image(const EdgeLines& lines) +{ + // TODO: 发送 RGB565 调试图像 +} + +void tcp_send_osc(float ch1, float ch2, float ch3, float ch4) +{ + // TODO: 发送虚拟示波器数据 +} + +void tcp_close() +{ + // TODO: 关闭 TCP 连接 +} diff --git a/debug/tcp.hpp b/debug/tcp.hpp new file mode 100644 index 0000000..d68e008 --- /dev/null +++ b/debug/tcp.hpp @@ -0,0 +1,8 @@ +#pragma once +#include "types.hpp" +#include "vision/search.hpp" + +bool tcp_init(const char* host = "192.168.31.20", int port = 8086); +void tcp_send_image(const EdgeLines& lines); // 发送带叠加线的图传 +void tcp_send_osc(float ch1, float ch2, float ch3, float ch4); +void tcp_close(); diff --git a/hal/encoder.cpp b/hal/encoder.cpp new file mode 100644 index 0000000..f73000b --- /dev/null +++ b/hal/encoder.cpp @@ -0,0 +1,64 @@ +#include "encoder.hpp" +#include +#include +#include +#include + +Encoder::Encoder(int pwm_channel, int dir_gpio, int direction_polarity) + : _channel(pwm_channel) + , _dir_gpio(dir_gpio) + , _polarity(direction_polarity) + , _reg_base(nullptr) + , _mem_fd(-1) + , _rps(0.0f) + , _last_period(0) +{ + _dir_gpio.setDirection("in"); + _mmapRegs(); +} + +Encoder::~Encoder() { _munmapRegs(); } + +void Encoder::_mmapRegs() +{ + _mem_fd = open("/dev/mem", O_RDWR); + if (_mem_fd < 0) return; + + _reg_base = (volatile uint32*)mmap(nullptr, 0x10000, PROT_READ | PROT_WRITE, + MAP_SHARED, _mem_fd, ENCODER_BASE); +} + +void Encoder::_munmapRegs() +{ + if (_reg_base && _reg_base != MAP_FAILED) + munmap((void*)_reg_base, 0x10000); + if (_mem_fd >= 0) { close(_mem_fd); _mem_fd = -1; } +} + +uint32 Encoder::_readRegister(unsigned int offset) const +{ + if (!_reg_base || _reg_base == MAP_FAILED) return 0; + return _reg_base[offset / sizeof(uint32)]; +} + +int Encoder::getDirection() const +{ + return _dir_gpio.getValue() * _polarity; +} + +void Encoder::update() +{ + if (!_reg_base || _reg_base == MAP_FAILED) return; + + uint32 period = _readRegister(REG_OFFSET + _channel * 0x100); + if (period > 0 && period < 0xFFFFFF) + { + float freq = 50000000.0f / period; // 50MHz 基频 + _rps = (freq / 4.0f) * getDirection(); // 4倍频编码器 + _last_period = period; + } + else + { + _rps *= 0.6f; // 无脉冲时速度衰减 + } +} diff --git a/hal/encoder.hpp b/hal/encoder.hpp new file mode 100644 index 0000000..9af02a4 --- /dev/null +++ b/hal/encoder.hpp @@ -0,0 +1,26 @@ +#pragma once +#include "types.hpp" +#include "gpio.hpp" + +class Encoder { +public: + Encoder(int pwm_channel, int dir_gpio, int direction_polarity); + ~Encoder(); + + void update(); + float getRPS() const { return _rps; } + int getDirection() const; + +private: + int _channel; + GPIO _dir_gpio; + int _polarity; // 1 或 -1 + volatile uint32* _reg_base; + int _mem_fd; + float _rps; + uint32 _last_period; + static constexpr unsigned int REG_OFFSET = 0x0100; + void _mmapRegs(); + void _munmapRegs(); + uint32 _readRegister(unsigned int offset) const; +}; diff --git a/hal/framebuffer.cpp b/hal/framebuffer.cpp new file mode 100644 index 0000000..8e39459 --- /dev/null +++ b/hal/framebuffer.cpp @@ -0,0 +1,60 @@ +#include "framebuffer.hpp" +#include +#include +#include +#include +#include +#include + +FrameBuffer::FrameBuffer() : _fd(-1), _buffer(nullptr), _width(0), _height(0), _screensize(0) {} + +FrameBuffer::~FrameBuffer() { release(); } + +bool FrameBuffer::init(const char* device) +{ + _fd = open(device, O_RDWR); + if (_fd < 0) return false; + + fb_var_screeninfo vinfo; + if (ioctl(_fd, FBIOGET_VSCREENINFO, &vinfo) < 0) return false; + + _width = vinfo.xres; + _height = vinfo.yres; + _screensize = _width * _height * 2; // RGB565 = 2 bytes/pixel + + _buffer = (uint16*)mmap(nullptr, _screensize, PROT_READ | PROT_WRITE, + MAP_SHARED, _fd, 0); + return (_buffer != MAP_FAILED); +} + +void FrameBuffer::release() +{ + if (_buffer && _buffer != MAP_FAILED) + munmap(_buffer, _screensize); + if (_fd >= 0) { close(_fd); _fd = -1; } + _buffer = nullptr; +} + +void FrameBuffer::_rgb888_to_rgb565(const uint8* src, uint16* dst, int pixels) +{ + for (int i = 0; i < pixels; ++i) + { + uint8 r = src[i * 3]; + uint8 g = src[i * 3 + 1]; + uint8 b = src[i * 3 + 2]; + dst[i] = ((r >> 3) << 11) | ((g >> 2) << 5) | (b >> 3); + } +} + +bool FrameBuffer::write(const uint8* rgb888_data, int w, int h) +{ + if (!_buffer || _buffer == MAP_FAILED) return false; + + int copy_w = (w < _width) ? w : _width; + int copy_h = (h < _height) ? h : _height; + + for (int y = 0; y < copy_h; ++y) + _rgb888_to_rgb565(rgb888_data + y * w * 3, _buffer + y * _width, copy_w); + + return true; +} diff --git a/hal/framebuffer.hpp b/hal/framebuffer.hpp new file mode 100644 index 0000000..9dbb4e8 --- /dev/null +++ b/hal/framebuffer.hpp @@ -0,0 +1,23 @@ +#pragma once +#include "../types.hpp" + +class FrameBuffer { +public: + FrameBuffer(); + ~FrameBuffer(); + + bool init(const char* device = "/dev/fb0"); + void release(); + int width() const { return _width; } + int height() const { return _height; } + uint16* buffer() const { return _buffer; } + bool write(const uint8* rgb888_data, int w, int h); + +private: + int _fd; + uint16* _buffer; + int _width; + int _height; + int _screensize; + void _rgb888_to_rgb565(const uint8* src, uint16* dst, int pixels); +}; diff --git a/hal/gpio.cpp b/hal/gpio.cpp new file mode 100644 index 0000000..b328554 --- /dev/null +++ b/hal/gpio.cpp @@ -0,0 +1,43 @@ +#include "gpio.hpp" +#include +#include +#include +#include + +GPIO::GPIO(int pin) : _pin(pin), _exported(false) { _export(); } + +GPIO::~GPIO() { _unexport(); } + +void GPIO::_export() +{ + std::ofstream exp("/sys/class/gpio/export"); + if (exp.is_open()) { exp << _pin; _exported = true; } +} + +void GPIO::_unexport() +{ + std::ofstream unexp("/sys/class/gpio/unexport"); + if (unexp.is_open()) unexp << _pin; +} + +void GPIO::setDirection(const std::string& dir) +{ + std::string path = "/sys/class/gpio/gpio" + std::to_string(_pin) + "/direction"; + std::ofstream f(path); + if (f.is_open()) f << dir; +} + +void GPIO::setValue(int val) +{ + std::string path = "/sys/class/gpio/gpio" + std::to_string(_pin) + "/value"; + std::ofstream f(path); + if (f.is_open()) f << val; +} + +int GPIO::getValue() const +{ + std::string path = "/sys/class/gpio/gpio" + std::to_string(_pin) + "/value"; + std::ifstream f(path); + int v = 0; if (f.is_open()) f >> v; + return v; +} diff --git a/hal/gpio.hpp b/hal/gpio.hpp new file mode 100644 index 0000000..569aca4 --- /dev/null +++ b/hal/gpio.hpp @@ -0,0 +1,17 @@ +#pragma once +#include + +class GPIO { +public: + explicit GPIO(int pin); + ~GPIO(); + void setDirection(const std::string& dir); + void setValue(int val); + int getValue() const; + +private: + int _pin; + bool _exported; + void _export(); + void _unexport(); +}; diff --git a/hal/pwm.cpp b/hal/pwm.cpp new file mode 100644 index 0000000..029c5ae --- /dev/null +++ b/hal/pwm.cpp @@ -0,0 +1,57 @@ +#include "pwm.hpp" +#include +#include +#include + +PWM::PWM(int chip, int channel, unsigned int period_ns) + : _chip(chip), _channel(channel), _period_ns(period_ns), _exported(false) +{ + _export(); + setPeriod(period_ns); +} + +PWM::~PWM() { _unexport(); } + +std::string PWM::_basePath() const +{ + return "/sys/class/pwm/pwmchip" + std::to_string(_chip) + + "/pwm" + std::to_string(_channel); +} + +void PWM::_export() +{ + std::ofstream f("/sys/class/pwm/pwmchip" + std::to_string(_chip) + "/export"); + if (f.is_open()) { f << _channel; _exported = true; } + std::this_thread::sleep_for(std::chrono::milliseconds(10)); +} + +void PWM::_unexport() +{ + std::ofstream f("/sys/class/pwm/pwmchip" + std::to_string(_chip) + "/unexport"); + if (f.is_open()) f << _channel; +} + +void PWM::setDutyCycle(unsigned int duty_ns) +{ + std::ofstream f(_basePath() + "/duty_cycle"); + if (f.is_open()) f << duty_ns; +} + +void PWM::setPeriod(unsigned int period_ns) +{ + _period_ns = period_ns; + std::ofstream f(_basePath() + "/period"); + if (f.is_open()) f << period_ns; +} + +void PWM::enable(bool on) +{ + std::ofstream f(_basePath() + "/enable"); + if (f.is_open()) f << (on ? 1 : 0); +} + +void PWM::setPolarity(const char* pol) +{ + std::ofstream f(_basePath() + "/polarity"); + if (f.is_open()) f << pol; +} diff --git a/hal/pwm.hpp b/hal/pwm.hpp new file mode 100644 index 0000000..2f86dc5 --- /dev/null +++ b/hal/pwm.hpp @@ -0,0 +1,24 @@ +#pragma once +#include +#include "types.hpp" + +class PWM { +public: + PWM(int chip, int channel, unsigned int period_ns); + ~PWM(); + + void setDutyCycle(unsigned int duty_ns); + void setPeriod(unsigned int period_ns); + void enable(bool on = true); + void setPolarity(const char* pol = "normal"); + unsigned int readPeriod() const { return _period_ns; } + +private: + int _chip; + int _channel; + unsigned int _period_ns; + bool _exported; + std::string _basePath() const; + void _export(); + void _unexport(); +}; diff --git a/main.cpp b/main.cpp new file mode 100644 index 0000000..55c76b1 --- /dev/null +++ b/main.cpp @@ -0,0 +1,97 @@ +#include "types.hpp" +#include "hal/framebuffer.hpp" +#include "vision/camera.hpp" +#include "scheduler.hpp" +#include "control/motor.hpp" +#include "control/servo.hpp" +#include "debug/config.hpp" +#include "debug/draw.hpp" + +#include +#include +#include +#include + +static std::atomic g_running{true}; +static FrameBuffer g_fb; + +static void signal_handler(int) +{ + g_running.store(false); +} + +int main() +{ + std::signal(SIGINT, signal_handler); + std::signal(SIGTERM, signal_handler); + setvbuf(stdout, NULL, _IONBF, 0); // stdout 无缓冲, 日志实时落地 + + printf("========================================\n"); + printf(" SmartCar Framework v0.1\n"); + printf(" 龙芯 2K0300 智能车开发框架\n"); + printf("========================================\n\n"); + + // 1. 显示屏 + printf("[INIT] 初始化显示屏...\n"); + if (g_fb.init(FB_DEVICE)) + { + printf("[INIT] 显示屏: %dx%d\n", g_fb.width(), g_fb.height()); + dbg_draw_init(g_fb.buffer(), g_fb.width(), g_fb.height()); + } + else + printf("[INIT] 显示屏初始化失败, 继续无屏运行\n"); + + // 2. 摄像头 + printf("[INIT] 初始化摄像头...\n"); + if (camera_init()) + { + camera_stream_start(); + printf("[INIT] 摄像头: %dx%d MJPG\n", CAMERA_WIDTH, CAMERA_HEIGHT); + } + else + { + printf("[INIT] 摄像头初始化失败\n"); + return -1; + } + + // 3. 调度器 (内部初始化电机/舵机/编码器/IMU) + printf("[INIT] 初始化调度器...\n"); + if (!scheduler_init(&g_fb)) + { + printf("[INIT] 调度器初始化失败\n"); + return -1; + } + + // 4. 启动调度器 + scheduler_start(); + + // 5. 主循环 — 低频监控 + printf("\n[READY] 系统运行中, Ctrl+C 停止\n"); + while (g_running.load()) + { + std::this_thread::sleep_for(std::chrono::milliseconds(500)); + + // 热调参数 (读取文件) + bool running = read_config_flag(CFG_START, true); + if (!running) + { + motor_stop_all(); + servo_center(); + } + + // 打印状态 + static int last_print = 0; + if (g_print_flag.exchange(0)) + { + printf("[STATUS] tick=%d 车辆运行中\n", last_print++); + } + } + + printf("\n[EXIT] 正在安全停止...\n"); + scheduler_stop(); + camera_deinit(); + g_fb.release(); + printf("[EXIT] 系统已安全退出\n"); + + return 0; +} diff --git a/model/best.pth.1 b/model/best.pth.1 new file mode 100644 index 0000000000000000000000000000000000000000..32c0f81ad235a13c670a892b27bb6520aee50211 GIT binary patch literal 140663 zcmb@O2V4`&7w-`eP>O&Jv7)Gmii9Re_N-zTvBZX5L=Y6g469gBv7llFyJEwx*t?RQ zwfEi|_TGC%eP=ciHe9{$`u;%$Hm4MZb^DYkceIlqQiy4T9axTZ2`AX zTkJYsi0J3x>5&i--8)LqnuZH;Bs|Ka`v4(2CcbcY647%&bWE@ALPTtQ9O*vLtFYG0 z%`MbYJ}{1i^^VY*>kld1C?+mUXoH7iWnpc>&;qFO)LMjEpbsC=E3A&E)-w2tptWip zY~mJd6>P@-3)(_%!KH%>VYz^yEu0d?MrJK&Z8Tcjyy2;S4bLtL=~3oU`rcLABFf(F zgRKOu1NI(lm8^9PE|9D(s_(Cupe?S^mI$@}HC>fQ&*-ptZAqivytGcr-b%6FoDIE| zX1$fs_f}TWmeXj-kuaykFy0Ts?>wB#t zXsc?pZlR9<>~&xm(N;6+)JN;C?6f-Tw1%P6nyga~eW$eqt*1t-3U$uwG!t79@H{q;i|w8JGfk1Vmc!0iP887R1h`>F7;=KwBkBs;dKzs|K16O} z)Hg!Z);3Tg8nW}#$Z&odv-8tL-)U1p+f1Vk4zw-rb(o>+o~-L|eb>DNZG=V}8CpJH*T2h_-UftssEkl)qm+nf zmK%K#@hdm_3fdTrwx9Be>#xX-SmObEY2%c=^$$)Gv|8-VEf`$?U(I<*rj@J)g z5VQj{+JX5Pxyg}W%<$F@QZfby+Y8zu?4;NyYlpIvlBn->n4lf5(T-4N2aep39ZAN0 z`e;Wg`y9pk9Bt@x4C^yl-{)9CJ5Hk=uS^fQPowlmG49(}J3-m^MAr8tL*J8G-&6E` zPZhMO8f}^~KaBcj`7zD7Yd`IDW!E!U*E0=W&thHA)^|Ne(9YFp=PC0;?)rE6k#0a3 z@}stPz7ny3J%tMq@hd+T3EIUPZANIZywr>D8{I!|^;lv&WPj~aWq-?9hAhYa6dAHY zks&Mf6Idl^S8KFu{z1vjkxXMsfOf5tvW}gY^@bC(ft{F*`hGVF+RYm67G>tiqc>#9 zR-<0MJhj`Dy>4f{?lAPall8hw-|KEco2Aj}O2}E3E9VgMD_717+6x-(MWeGFfv-rz=H-&{kbSh5mAzdF z#%st`?9DCM99I*0{kX=m21^WdT|a>vf;L;Dy{UZF$1{e!W4L8Z@YUW{67B?>3);Kv zq?jjb@3E6|U*G2gLHkgneUxw9-oM8E*tl0e?Gt6MPuaMi$>X-ik;`L!&gNhk_X|Da zrJ#MK(Z0?%Zg2g#-xw2WYu_pf@7R<1o{bwLva zU;9njYff;gp#5$bx8cJ6LvdmMDKm%(?h^%40Ii0YqRj{U_2d#WY%}Hs5Ob!_+h3A` z7~@=s1$zB-h$X8kkW8%5>w$%^B#^>rHN+Zi-Wii;r+=o24YnBJygi96Q!8+G7&BZE z^ah+gt3sRudOgk&O9Cm1Rzr%R&0G2nxL+?iws|DQQDKZ#krM1E1-2x{4C{p6fGx$U z5bKOyk1dTQfs{e3A!X6#T@~_S@wHCMp}?5xMar{-6x0eBGpY-E1GOTnLTV-Sda5gy z1X3BThEzeDcfl}Ff3paXswgzj_3MDQH*sSJE9liQ#uq7ZM~`&Ffet&E;(=|(6Z9dqm|lVK#5iORGE`VVhFfqM!!kjNb+njiL7;S+_Pi!@sqK_vDXGbU?y)c&3Hv$VtQKWAq)+o}qH-`Ed zM`1}I(P%ZK588i>AUA>gVyp28R3wHSp%_6wjM+(!MQ=FCajXhYa)0!Cq!vp8A!s!u z9l4|>m!z`8 z75p@eSt3tEkNjVWJRL)U%s{IlGtnA7r+ND`G7H;`r|3s!Gra;a2jk!a0-1{*5pKbj zxD2yB51EHGEUER|9+Hlse!}yyB#;GYHDn=L<(ingbt8+g#TZ_jEM{s2JOkrkOMxsw z&(5!9GFi&1@cb@Aug5LNl0a6V)sU5F^Ue0xu8yq2He;YaS~)q0O7Ew{kB?c4M0n(ASe>F}(t)!#FrcAR>ChZ1wv>La`=q zYe*yv_4qwl63AY(8nO>)4y@hWnF=@s~c7_<2vLT{MwVOE9nJ%U~jJc=cO z97C%i$I<4UUU|NT-QfvrF~)h3lT59^ox+&mPNO&A&af)Pokg$5ox_qq&ZE_k3uyB$ zum+sb?(iZijIrM25<5zPy^Jx#UO{ibUS(B?y@p(V0>8tD3U$=8=W zW(OAcfgcidkA?%&<1-4Om-Ng;+cEdTbFa z3B(?)hB%;ACa)2eC9fk2jHrH|q$oQ`K`n+cqZUVRpq5}&NG*w8Pj$kQKuV$25NEW? z!%`R*ue^VS&UiomP3#9U&&h@LxEI4t069E^Y&)m`F4jDvDJ8r zUZfH`LIH8bSWe%{SU`#*eXC%NB7Li3sGqSLmIP7_t%kUx{l^G$6Sz9I8jrx6)L=&_ zMo<%Dc9K2N8%}a9R)r_o6TKd(!jeF|&}xV`TIDN7xjXd1He;X<@nw1i&<|q zk0pULK&v4Q(dO+A{{d!c+z2JcTtCv79j4$m!I*KIqBn4xu`1*Sqt|nrV@V((Xf>n- z+EABYyTe@W?-IEsN)3ENBG)FZ*x?F(Ym8YUYtSSAS0cB;P#|s5YDhb@M$f5Yci0}= zjHl>NIxxKg!M<_`Nkv9SEFi-zxG=86@`kAs*08KLY?wM@sGo5cED5A5S`F!jR=FtV zZ4bL+i!nWb^k8ZQJq+XE!UE}uo}J*r$t0Xr;R)`AUXP2wl0YKSYDjOi`KFt@J&eLO zBVcV$63z4qU>}U->Gs8fJY6+X=Eb140IS034n(iVC16P)gV1WoV6=JD^)cEX4#75Kpcfg+^a@}i z#vxHSn_*ZmOxLhM9F8@L4dMt4_536(31lQ%4H<GE*yXQ!r+@spt*3R91z! zH1vAhG%N{ZI$8~xfi~|NYrq+85ND#o80$-Bv7;2&*%&kI9P|e4TvmnHdFb`nbSw#E zK3WY~fHv>veoF~*FVf!;t}!m5zE6uq9h3`+u8j#fifpv}9+ z8mPZpnpUFFK-Vu#wQG}A>|h0bHOA~^vIafUe=SX!7z$)9S`Ar;R+&6_P0!sRuE#dx z3Hp-_Os_y}#5iP+l|VLO0U2(={=b%{%~+#Ynzmr5pYK*I31k~u4cU%1A3ryFcVL?_ zKY;9HdIf(M#=-sq*^Qo^VE<&2#j5ZG>(J|gB9;U~(Q1fxQlMmsfmgLo7b##j|O#*R{8k7LZR zC(s+PCs`F@PodXiPh&|SXV7ZMS+vUJHNvvwJ%<8gsuwxW4pLArV9cl&(Hp3jSQSz) zqt{cfU`ZfX(Q3#ww94d_slQ9!>nJqP^~vk+O>VG*74&S3S@PaQkMv*3dkaH>+(xS* zchKf-&wTQ25bt8E@f3Z?J$8fwavx(keIH-}DT?%ch&77zeT1QY#*eWikSAz0v5H_ zB#V=Pqzlvu-O}?TN6V)-vdhm zsfAWUJkjQxu3>|y!WLt?H}PU>1>GBCmQOzD*>v%eOxY}3}h(B5l2|$}S zU09hu4C1h0n66=i2w0=oAo3XM`E{`*ka}n}BnWLje(n-g zAKQ%izN7)uEBFmDW)p6N-Z0_DtO_UG1ic>E6iWhWhE_v@(dM0BdBTPbVsmUU#`%#D zrdHruV9anW(Hn5BSQX-0qu1j!SQ1DZv>MVDZQeE3fHT@4wnK$6wl-oO+PrIQJ}g_Dx}m_B>QB0}gA~*r7&B@ZdIPm5t3qlx zdOfulmIM-kRzo7u=3QeA)ZZ;ly-{eO>zAg0020LxR?wp{W=m5a^hp1;H1)+$ATek) zq#s&k^58W+cY_#GxHZN35IW^V$v@Wp)BF2n63B7?knN=Zo3VJ;S`C?pR++&v_IDYajzR<8o4qPAy?n`h zcC-S&0ArTI3(+I~R|+q}P#}xZYDfm!yiJ;KzHQQSU`*- ziC18aB8gXGsGsvHED2;aS`Ar)_8&vYP2)^#%{PSFWGy>HF@$v(v-7+jz2Q7>U{!dY zH=@@wH(^O2o6%~>7PQJ2j&h^872EO={mC|VfP%OkV@BM8-ay>Rs*tz~y`H!mO9IJ4 zt06kHc{@eJiO#oE6j76p96%^LP(hY3X5>BS4dlJ73d#G>>&g4EB#;AWHRK@LyshFt z$Sj!;p~M)h@+61ZaSHGej2ZYSdIR_vt3vQ`^m_0KED7W!S`9gcHgB((3;ta?pGK)+ z0ETo{smK|2ykY=nF=pv}4m}RwS2~}^P#_o3YRE;jM$fBavv>*H@=el?Vo2`t8#-tYNur*gjpyP(SAzSQ1D!S`E30R=Gar?G|rgOFq0exy|GX z{2h$hEme2XvvX{ZUzV{dJjeIZ>v<2bB#?(_HRKW6d=t*yEFEAa0yW=ZuP zJ)1CIfIhG)obX5Vdfq223FI?c4f%pLvyCvl4ne(-lj2 z8zNe~4H0c<8RbNOw6arftZ~x^Yy{pI>Zj_1 zCAE#85MR!*Q?xV%@Zjn(2R%El=6LrZtHSfDMz4o)Si-vx z(c;~QXyv6KK6*%m(NybVOFo_tsmJ6BUJ%B?o_PBqdU>j*zoyy%YZOy$h@qa|2upY~ zB3ir|5pAd)dscJl@?4u@eLl7?X~x6~b}+`lrg#q`dNx%vaIP)T>uD{qg!dq# z#d{FZ4j4u>=t2u26o2R?gs~srkv3SxezQi}V!nV9`fZeRq7$6w%) z4pm&rt$Iw`?EwvVr5BOuEcmG*oznGFH5w!5*&#F z#5RnC$dY)ag#CU}`TGn{BFLfv|0YtAfwCweSA^qHOglb;43Y(da|QWE6M@qnB1?w; zS)w9|vSiqwC0=B>EE(}={wNJPv4GDempDcuf zxhI6(I8MgPf)u47_vw-EEcYZ6WXZ%oOH^c%ESa1uQRac%ix-(9OQz;Zlo{#eff<=9 z3(}MV#Yp6goF+@A|5>6UGi1rkT#4~WA8b>*-16 z$)fas6RF62S+pQmq|8X{DS|AN1&eY8`9{MsaEN zNFQ=eZauGT&CN*m?Krt03oa@Jxp^ReeeOvv$&$-|mZ-=TS#mX3qRa!i7cX*6mR!%3 zC^OQBW#kQ6kgXIbMj~hAO<8j5&k_~6Elcj?N{mM$XXIU3axYh+%mMwkRph=bd7zZ! zW~AW@El=`L7Crhmk%~N)MNe`?%8bOGBFIx&@GMu5Z!|0;pUaXLf0n4oOIh;j&k`^4 zT9&-|v&5Ucl_l@~Eb$@lWyyy>NaT$CC`&#mCAk^tOFql3UzDx68Oc75Ctqd3H>Dsq z59H75JxPu%`Tl2#iu{lzKXWC@Jdk_wA|?gdPPzcv+?}*yB$$z=vcOC!P>e**NOM_I z@Xrzzv5+N}xf0`%$QfxROA6&mlsTaPOpFwkCDuwwZblkDHuEGlvdH$|L@Ht@i;Com zlo^RVMG$*g;E*fGHyW0ajJmEb%5zvZU0XB|gMimX!X3 zM9#=EvZSn1!ZK3-c>*aXx0YA7vOk~l>%${bL2h^XL%WJpl-n!iw&Mv^9PdS3<@U(g#q>9{LRoTw+F!wzwagznr6oLWqJv~|lTUtFZv01pLp@|85wEE*;eko>B zO#hc(JR;*rzc8V@;mu{EAbXSifB!|ry4~^W2Kyb7348px+ma@A4Bf`-|9(sNu$buH zvHc=qg+@Vs|L8eC>G!dp4;uiVpk+6Rn6Ss62ViFsq#r=f!9qkF`%5*Ag5dv=`)f2Y z(Si^Y!N!ox-7CeiggyQ|25Xagd4E->mS>|N?tdG=oJ9rs_7hJ-;HTZ(z-&)gZqftZ zh0TXLyH={J-gqT8IXsVBnox!6c9+O{ezX>Syst1Vc)KcffBaR~x3gNjVcLr8|9*tH zXix`QXUHUa@ODG`YNN<`cWzI)0(LZZYbfp5Bc7{0Z>Bh}O))XR!W}AvB)CpvSGickWcEbLj%t zv&BU5n8iHq?B(fVmr@heR}XBb_xYb(xygZaz~}{ZbU;(uH`PLN`cy}PW7q%f+}D-Hk@{q%F)54 z8q~}%K3u%V&HlbfoSsSdAb7q`M_KK z)4`h7+yQWAj|08KZ4%$uj0Ih#1v-sSH`;I1D{6oJk~nGEN3lcgDo|hdii_Or3e#JM zz-_0KTzF4|@}?ZY|ISD%{DKD#&457lkNDG8-gY=SihmWXM!ouU19C+I9L6^BhP2`+t$ie?SPbfn-Pw636TVqNu1X=Q<&kd&smKEm)j$F%C zX;PT3?rF-8dwQQc*0UcM^Xf2HqkTs@EYyL1Z}0|IU7+-G{Y>th(;M!>#;T&z!C28Y zXf;?>jfd!UGij5px?QV!`p}T3%f;dM-f&l1InWgm&&9PDE^<~ikBDW4KI7WCEa1L( zSj06h+?V=iZsw*m7sWm=D$!JT2f8QyKKJu(6|q9INwoH=qp)moAUC9_Mz?C03%8|Q zU%K&)D>W}-L$fUHU|^58VA-({KlsTuShsx%m*t%Xw@h!r(D6RNUfCzVO{(7mKf7m- ze|u$DRlKrQje;uumshrTpGCY=;&?u`(j>mqqxSsJ`H}p_;Zb}{$wWRYr3=sa;}7Oc zser2rd;C|v*MHQ11h?*gDfnT7E4{WVzob2n^ykOBkK+Cra$9U;9$dFnE& z6m9gOBdj>MK%AO+LwwZj2n;WC2<#h8qzRTC;A3ln=5(Da`n0$thE{3E%`N>^O#XOI z*ZR&~u~GA+z?RMH(4ZS=XgO{q3|j(X2wcT zZSjILIYVf-?IE;rL@_!(WIEUT=Uy>n)foEb)GR1e(+3JIN}(S0En(!aaLO=_&3{oVvCrS~1O6l5x>zutn6 zW`BT$hfBobl~ci{fHgf`!%pln+D1PACst0o{eS1%m{d``E>yU+s`wvX7|ym!xL(2c z!SeAc=+}Ij+Be7>`c0_G4J^=49pAi?JbyBk-~ZQqya4%a=UCmj| zdIV|7X;7qB89t^CS7;j5RMv~Ai|?*7y_kaWWjYMU>i z#Z^V6&Hc;L$8$9_WB+D2xj%|`T{as6niru?5e1}`4eg{aGfRq1n$4j1+l}VlefS~H zFI!Vrsnz??=p*ZN+8bKaR-?`XWb72vXYA!d zJ}psyXu3f(TUVbS9od7X$IehMzP3^_q2mC`zAw_2geaN*3>iuHlBC>kp~#5@?_G-gK;Ej@Yu| zQE||fQ*e>iliJsn;bM$4zijgZ&3f;LYE)-^FPVUPdJ#|u2;cQlQFZ>MTPt>bNid*aCTndwbe_?8zt_!3cDuqfAd+q$d~nqa!SLzp~& z-HoW?f6d1WJmXuRZ6{86V9%GcJq}e|yQuG~Jf)q^5)6-9E!tYIqSDz!2;SKO&TcS~ ze7>)P;UBM2cNZu1qZ>6LXLSLIt*?bcN?H6hA20lje{flIepk#zSi5o|Km3+Ef1|!V zzo%~!OdyS5N??)07;f6d1W z9OM7b>la?A{+IQud1Xtf`PFo2`@AY7T`{GzM{eV)x5-qyv^WTkJNMH$4wYeNtOIo4 z_Kkbj+?Bt1CX;rW)r;4@xiY_T zN0pWIK&%-*c#jtiI(HcA+tib;-<`~@oo+2%8C{Pys^JBe+(A0MMO6yytE zwS^aL*U(+1o{D?scY_=KtR%PnUujTuWhtYAv*bL%R60|yG5vIJ88|mxN#7Sb0NM4X zfW_1?;L)(S__F3LsQe{BHzc7RKf3%_&bj79x_0Az+OTv(owXY-dlca6wVAJL+hPPgxXu*jwe$nO zFf%^jRTdX+*A-5GoX$O3Ux~VnKMa*=BDI|vMZ+iGrJrN&21e{JDFxJAFZMoO5X6!b zp=;M;bk~#e(ll#3^}#x>QsvFjV%gS(`1%`~fzO?~Qu*X-)M@D%UAfgE{PO{6beYan z>NRv8oGCX?bp5cGjvlv)5|5RjZ-CSbYzxwz%aYFIJ&38!13qN5_V0$k~%9<;=TE@{zIo`2CLuJ!+#kNXqG z?_sV{&zR`K_Y2L0=R*b9UEmbF@H$5`TtA5)uh*1*K3oJ_n-@~wjx0wLHhJ*-4_HgB zhqaOl+PxNsC)&yL-*@}dtiR^tzJ>Aa2Rp&V-J79dkq!KSDi!$lr`B+duR8HRYL(!t zEG*1NHR!UK_)SX#q$)qZfsN`dm|j07rmHW}@1tJA_A&+OewQP# zaBLXlXyT<=*$Mm;({s|0wf!M-?p7LebusPY62B6xOg0NtN)FgH1a)!O@674 ztCb@TiWx{J-77*f7D;fs<~S-i=ZM*_CW@!7r~)%K`0{DZAJ8kso6~CEvvgYRS~1~V zSz77Y8Zf!k81_whE`GBc0gZk{zzgoJdQ`$Ra9oteRUNq(Y!gfHW71kfky4kr>;Wgl za|2`G+a91BE#^Snlcn^~`BX^n(^B#Xo&nO}4)p#HXYN|vDDb&gQ$F9^lM``&{rnmB z4-JOTV7uIYRcaH;@81x>FjgR2e$GmBW zd0SysXsRy2BSX%gLQkJA{p;61?mO7}6WP#>E}J`!R>-k)CwQoiHI4q`>kJr~_y&M6}o~F|3Yb*k{4_FDdw`{nlSIx!7v-;9fi^o9s zOUu=d94m?=o@n4?(J@^A3PZ#!FLyZE@&VUs(|9O#KA8@EaZFs1RunF7~;$MLc_TJXg}EIKAlbU03&5b2zne5_CKw>D*>d5ht9l zFMcVxSeITWhx_#Tocfz<6I$`62VK&yhSb60df>6bgXrVzQt@$0z%#KG=Qye@tbH*raCopIbs6%8Tks&Avz@A?5gRVU;rm|D-qH!4 zw6}sP?)Kc!XYX{EN7NB5PbSbW(M!~}tvXXDN1eLGD|<+>kAbX78Dh1?6S>!sFQHVw za&*w@+4PlEluBhUayOo5bB~Yh`%frU4t%IJ<)j>78|3#d@u# zaAEs4!MhL}7@Xk(hsw=_wEi#E+i!KD8(T~hds>x;m$Q8!(}&{%9f!jGn3b@9{s2*P zYbe)0&JsFLt}0%aM$rTAOKDheB3-bpF*H6}g0rSgA?E8U(ZY5S&HNAtl`g7uHTN78 z%bD1zeV^IF%iU(QL}w!B|Km;dt?S}@C-(Ta^+x&r$;+_+XmolsUnxG0kGSf?SA9tM zwY`)1^oHYkuaCX>+tnlazzOO6i}6YPj3YDnA!H)&p3;?1+#b#koiT`?S8Snt{WGoL zc;#>N-`lYNNQ=sX+UHWl=!MQS(b*if@Q&aS zU9G9el@W6-a^P3NF z8ON(YosR{$r&*=s`8z#WOaGex|7ri>{XgzMtX)g-wmtfScyp}y_Rtq@=$XoV&DKl7 z>Tx(dl<5SI+Lz`#mN`u=Yx#2RA}zVW4Zm{pzM4U^JCU@{26x(X!g44w`eat$FlXKF zhNtPOy+1k6W~Vv30XAyr76FIP-k^46yu_>xg`^zcG&;5JGjZPa15jw!NqVhLWv*&? zAKJ;qi(m1u2fbiE60%E}bEo?xL%K;ZS~X=m7g}Wv446=jUhZuI2l|bLwMDw{9z&W! zr-xhV3cI)Bmxr;`-)}s0Z2g%oa=Hg4F6PjK?S_DR%`q_Evxww(@GPxy1f;6FGdZWH z-^BuzHPmtDJ}9#{7}5%+(Q)o?#Ny+xii2JahoKdN>9)@`A*4kCKEC=m7*pdSq&Hka zhi;oJmL6us)3Bq|wDVFh8?YMI75GX=7WC&^+h$t1e2bwSDMbUOXK*g3HMs%B7fmzDI~#-IP$p%$$_?izP;!xma0U_8BS(h@q? z<#DXHn>CTxt@#x~wV3v{1wX7V^sc%-H z@W_;NSXM+@c_Ix4gxFH6*vH^tF+&Wq*+R4K+3*dPU8GlV?=eAjTzoil65YOKp;&*x zJvu4I0vsx4tJB7np;acI<2F>5IJ3Kh#i=biK_|DstoPg+DC@NbdRHC?+cuZuty(St z*E%uOrTlDN;mw8U+35Ln;LdEi;Ycs)U3yfYZKq9~b;f=A{`Cr|Hg-T(jq0YftF{}B zytf+a=A^>>Ze6$nSJ%RbA6wNehP)2k61IxwEZjk*h3?X&n8NU&Y6eXBM%9;>+eo!5 zKjcQ&?5%E>;!Piq$Qbi=qo$F`k)5Y@&NXwR4(z?e+!kk;H;JR5ht>-^gtnRUm3+*2RR?crl^=*M}d3%^% z+%}5t#Lus8u6aX$G*s(a#uOJDeACg}i{{WC!^`uLp*5uMeO}PwUlzilbt<}SLO-!Y z&2o@ZFcU_I8$^rOcx(Sis4`8E5k#JvmqP}6$V zxP_Ny!uP|q=!-Hp>DOQf-u+7u|6@MBK1MvD16R(b8Qbmok}pm{+n7OgyZRZov+^!o z;dm=<*W0}?d~`OvoOYW!jT;YXx-Q}hrwM^J+g_>bRz6BsS5k=|zklR@m{+5TQ*8Oe z4)bW~13&4Ct_Ao-5vO5x%6v|&&APb^Y1 zl~#SUla5WD2lW;`hEbX~aM#X(ABkV!9}XPP-LS06FWGa0+crHLQfjZzIi(gCZBBiG zF0HMkw>>v-V)^^@nv=8WF}o7%e!$aN=fcH1OImX87Q{mFO-EpU)^g6`eqERocP7xf z=K)%K{Yh%!yMcpxWqF6TK>PRTNhjX@0dwc8=@ZX7qDkU#czL%TzjRVIm^>;i9@`ZH z!|!C!QTz}HeOi%k`7s$XsSjN}e;k!AZBwuL9t&o~lGYBf;>(vm%w@!tmm0gfK-!NN zTUFXEVg5Q&XT= zvX)-%xdlQ$J8=`Pt`##~CUO}MEFojGFASVnl+SJ#&8_MmN24Ev!>kqC>4ud3;812T zwYfZtLZ%grczA-dRf}BvoDTTiwK?q)Qi^^pafI9KTbTbbF_t#Fx0!m?OcetHwumV+ z-RY*#q0njmP*~j8ntt}$2m4YALDd@d=?qOlo{W0|^R`~&>ZhLt2j3t%w~QTp9MYDm zzJx>JSpiy+Y`%2g`_AE_YU6CI6?8s%mvk$DW zv<1vL;iH?j;V0bvIG%f!-BFx$F`G7yDkZtxEXKQb9}8zjR?aG6?N05UR^nbJnn(^e zd+Fj^2h+)E-^7W>IzZ$Dm9)6T6nbgbQ~LSP6S3(233Te_Iov2;9UU-n6^p zPT0^$DqgS^jO;d*b8Xj@dlr$&na?ZFTVGsE-)`*)W<67>n7u0N=E!ldyg;PbV9p6x z{$MXHwt61ebx(!kE^D|lt`BsDUHZYs>sO)kgT6GS>r=HVAOU84lQ?dABE7Tv8=Z;Q zC-(W#l7)i@ny??y;N!pU-@Fa)Kil}t;tzjr$8*=G@(0qwdDF)+{E8Vde0-;5KH$nI zKIF_KK5WuV{$`hA_90x-*kULPAH_}T@my5DF9XLr zx^TO^yhV1t2b}dx`s?xI`^Ddl|E^tAzLM`8dNHsdKTus(nlf}0-*8fh>gQ$&QVs&R>f{r(zC=4wVDy*azCQT(^mWso`GFx@@NQrZ)q3C~)WrNzqB z0L!EW^xS@tPT3JkJ5@O$_V}=sjxX#40UKs;bE{mX)p~8C=~K2r(1XKb25nAj6y6VK z)~I2t`Vq}q>aVuiQb*jpF9;HSQef})$?7o=i|~mqMR>az&BZM-=iuY;Bw8b>8uZ=o@n^Z(J8GKS~3<1z`t{2~DTUi}y zZuXLclyog26^-o$hZ{72=jVFrVuBp_OLcnFO5@ekY57I4uQU~It<9mXTv50uZl&QL zZou|J=iyd^lVVtyB~2&OV9D7u_!7GgI-9Qtt$8PS{&_y7m!}`#NQdFbjI(~uWaG0uBEFhHZCKXJw3_I{sK7@fM>%sie@1aV;J>tD- zj`aSUv2e9pWwBcK?l9WF6ZfWTRes^ZE_7PYaC+kOG_hB89rd_ab*TKm1^|w#XTO7NmH*y@ngCKsu!fH z=-c-%ph>6Iw4cX#daj!}->OP7{d6vv-mP$ghQ3}0Ht$!!>6EMBek`0@=-h*PP&{B8m(K}ZT!pojEe9;2; z#r~7Z(bg3rA!11(ep>rMklxyc>)U%JUEb1_TA4M3Iadb3^a!=|KBOu?@bY@G>7$bL zme>s52ffxUn4=YYOrDpO@WhO^Yf+6xs>(u*n*qsZ{2!x*>9qHQD63`~A0tYv< zmI@Efrr%snijSse(8%Ru#cMAn(Q$V#ijQrxX!O*s@MBIFCb%_qowvR*u0M;CbE%O!E;{Ww^%rvPtN(N-E-sRJzYPo}}< zb`aR9EZy?Nl-`}Ni|V#m(GPQ0gD%L6np6TB;`^FDXfPF|8WA+=`DD&)T@BiCWl?cz zdmd(_E~4C*RJC>Fc{=F+I+|FtE+4AxM_)8(3$s^=;#gG$8s_$nwk!3PHas_w4(nbO z4xZajOK2O52}!rbEA>BBv7{O2X=bN*Yzrfm+>Zmr^U z5xP*wXn0#ZKD>w|cACk(Z=OMiCpCs=7H?sIYq~hRPXhQZpGA*Nw&za|jf1g!w}^|z zH>c&xhQpe;XRtQt3vE4WG*ve_MxVnJdgN_)m=oL#GOpQD^IrGFJEK#f-Gbd>pvP=( z^QSC0VS5N3`R}Glz5T><>nGBAVHZH-wN*@bWzVS+CSW?GCTH4o48eP3Uj4W!+f1P+7%9>rp*Gv&9^OY&T*fIqMOfSP<8S{>7 zRjL|q?J*Nd?Y<)(3^0?v?6ae$d*0H%Nvp*+b6!(*_q`C`-GQ1u$byE?EhM)8Zrp#v z#J?Ute$M#2@gIrp0N?5i<%3SBc;A*Ap>&B+@a%jXq<&6^IrnBkeO|ML26S!r4S_2A&Q5RTidg<7WN=vt};%bM50CTOR$ zp}D}_|2~(?Si$q3Gv7exweQ5|x@UClJr6$p*hgApKoQ>kPGM?E45}M=6{`2fUrYo{P)*iYkqigV5GG=}A!ytuJz-T8aVD)Q|MoTsPv zUVs~!FU2JlQmON<6k0XwHN4W!6{luBg__;lz=h`cT|w<*y6D3dr1?>y+;g%;takl5 z?H^Q$KYF(!J-*u&CRFOpS?wQQuCj(#)xkn zLZp~zA1S%d4j9$#3_ZJOq?D50fo~I|kxr78QJrQ=Bs()NcF z;Z)IQuq&iF4SBc|>_V$ZFZ}?2$8i+Q%jZDUn8R@2ZxsF3)>JxBStG^u_^kHJUJ41F zzi|y7_Lpj`tj-6`tj*gWSP26<^@J+x9r?ALUV+;I0s5caOwV`eM-Q*v24|-QOWKD! zb*szP;(xA8(_MdT1qI9s$=|0W)+jyN9)D}W9{=|FhVuJ+AN+j4>o=co{NKLMPcB}J z#@1O@r`z36+y;m8+_`q`=vSL^us7?7{8`0O>wc@*-}PaSe;bRt;0XOjeb@lrW^`PO*Ofe?d3W`rTMmwgN^Ls9qf*tPGV!OoA>Q``v3%OdF|8eaN zSIcRS*cZR68gYFaY@X=L#TPp!j%eElUUzj7kGcu;R-5Ng**s8u>+&OTNQFRM(f3-; z{8c8j_N*(uZ0yEY4?9hJoqo@GTV#Uu^J3D(5}}Z^dZD=Z%wF31D5X#L*@)NL&7f75 zEaoECIMP{{9CQUbK8FpnRMgLT3=Gw3XxpVz>7EdKKA^%hC^o-6=j34x;qLD;!^LtLX43Gk^{lDOStC#`sLH8hVL0Nv)FRgF-XtorpH2DDg zgO6~+ob@zgVoCaTZL0d#<_grJ@LJm8N;)^g%@tn1Zvd_B??H0T2wKgzDfD+q5?7D( zf}dFcJ?^a+o7?Z9`=7m6r(P(-+crqZI`nioJux@~&c2xno8g1*p(FlguJC^DQJ*ew z^ldkoW!^(f=<@@w7e$J_nvR4K$8)${ zrB>7T*KdeZ*L4>6HroLY>=)4q4yo#GN2iDn#}A=im6OC5Pa9IN2O;!0e*RmfgD>6Y z?G8y#-_YziN%YEo6KR!nh}OsZwmMFnFZ#AJk=8z|3;wTK!|X(Bs(G^rR``8~XV15A z-MYI$+UgPFlZxA*^#C&%&}}BooOfUCTy8ui!>H&!eyhBnRjsPo?XO?|`1#cT%j-Yk zd=ajA_fqhEI#tJ)NK;$6n^8dw=KR~-gG+sFxv&@BP;;Y&F2(5+H#^K3`tLfnY# zy_DCt;}%_B{O$h57e6Qa-TtL(!};9j2bJMkm8s&?g=L}hM*J*g=tz1Yrl#n7^g9=X z-#@hQnH$(;&kpsbxJj->*`XNwiZ%sE234jY*4sz!k?&oZ- z-&ZgHQcpd{G?=bTSfy+JwYgZV@hN((Nhxq~@X}=(dz`6N?or zDQ2B5522l{A*Ns=1io_>Ti1!APPcq$+0;pNDemWIWiJ)eyq|ODzE>7ImsqUpw|Xmn zF3|xdPg}v&I<;T@YE!{o#fSUBim8sA_5Y#mO~bkB+Wv7QnWqLrNCPr77^2wgT%uB` zTvXDeR7yny4bni!6qT7ILxf0?WcaRg(R4|x|tAbQGYoA-~B*`^8gc=2XC6O*iA#% zqF?Oym;<1`EFG-`EITb?9-1G&!%7Q%Sa?khQ_Tf9<2fAk51b+~%o{uIND5xPHsa=# z2y;TkaqGH2qQ4G%i-J5lnU?xy<~l46o6@Gj%2ZoCyV{L~Pf8{QZN=4}bWfvSlLS_M z&%%z!t17eqiXmr?T_;i3FR=-mt#C_7B@^9}CExd6g3`D);-aZt9bBx8?Y+_*n=VN+ z;FDaz|Li}EDZUQIYwOlygv4@;QPGCnxoM1G=F*sBvr!w+W4AN z*_{t;t%$UB&L>#|XP}C_F)Fmo{<}Yp*SRzFUm2PIy8hFiX`%z)kmToBVrxi;g=|a7Q)cf6bYJM+{uC$7z;;M0fUM_%dyEovyJ;Pyf#ceWudn`m78)3P-DPp__ zaofLzeHk_ZWy)3Hq+KQ#ACt^h4Nn)T7#=56n{7euha_Goeot0tQ=Bo>3LgFl;zlGU zlJ>%PMDl0v-~C&A>FiVg`2PPF{69HlNA26JA+nm>;OO_H&x>CUXt-s}Mj{3*<|G(gW`@lv{_T(-gM%T&K7xCPn z7qwia`xwq@z&K*;aFjb#8v&2wmw-sqkZa06$7MDKLHB7HE@JX97`f^=CpSWo&iWoi zqHJFhWBQ7_y(pYak1XPp`X_Q9mTux~@=Lhr8|%sRtIBZ275~0}>Fy|ne|-P{KjHsL z|3~~ELt04eb%dt%sZ}2`x8RRp6Q~WUBmSsv%Ex=5VVS4C?D>#_Tcm!Ivh6`w zer+J$6g|X~e#UJFdHH%@{lNi{#ejXX|LIGyo zh=kI>eBA4B5lMRlWX_(=jVV=UV%=}5C$^qszWQfTI)UKBU*dF6a{?S%6%OBuq@g$_ z0*W_W0h>kJ*~`4uxa-ewe(LoChzr%l-{(?A+DCNp+|>I_=G90{QfX!vw6%E8gbub) zdoX>uO^WxAcID6Pu@qgr{~Pbi9b+FyPDHJZ5AkTNFS_F-QeE*7#OyN2V836)C1gBg zbyefVo}HrSBmh1e&R{ncOmSzonrP9dFJ$}VQ^WA$V!HWAqqQaE} znYW+^X?)y{HNV$^&8!9FK>U6f`TP?bCGa$kgSDZ>>L#XZc#{S5!bO&kV&MMdy=dK# ziR&9QSdD`}@&kW!FJ30FyQ%lc=L^=bZrBR=knoQoI1@Y-CGfn5@5bFrTgZr@vuNt~os78_0Vf9?fE$VOXv__TNk8(j z=inZ=f3pBrOdP^gZqESMZSLS&wMyWJ9GU63Z zo8$uT*R+z%NO9gsbux@gkfwQa@1etG2b+BsO1zuPWi&RgWZP9^$=i$w_DU)WOV3>; z_bnU%d~o#2PtHvjaS;AR%2Zzc0VdAC{cz(Bn3HM={adwQkH=|NIV%a`j4rZL6AgZlMG2%Fn+kdz?_k7?Vc@aJ5aPaG z!}i9rNRx-6u9-W#u8~Aatm|=F)@QaG-@rThOnfGD7jonCux720fg%ZLvxGqIkFo4l z#6cLpbS9Ggg;Rc9YcTOQ^HxDE~ zEow=ju^!Al{(DNIvp5V03xq;9CzM}mfyuHL&|USeXtXzn2OrvS68R=<%v={7wbvA+ z9Uh7LyNau)6;H=~H6~D$^9x*>2GBm6?eN*@Fgh-JgR!$hfUdV=(}x9sy|W=-rO^lL zQZBN~qjE*Juj=wU6y`wsj*}wy;dhvcUn1m<8_((`YKUe?EEe2|gYwYhkaBAi5i380 zPutc*_|Z~);~fZF`CAaOw2pgyua~XYPsAYY6Hv8e0eI@z;f#nr><@Q=L%utidO;EC zyOax0>;*2N&5l32e-JcC{30o@o|Bq|@0mY|V5%+!WM5ecu2AbGG5QYy^n`7&k8#hJ#+|P zeMcS>qi!)DvlpTx8h&uM-5Q1;pNV284#DL5d&D$u155Ay3nT)&*w{@beB;Fd*m=u@ zPTZS__c4qe*u%)FNF}K7$_BX7V>4S#o_KXDgQmeVsC;vfgp0ps%BTV<<;`UEuk}J- z$$;k2Wo*INY501N9lKERnDl7PgME=RAsb#&VGlDu z@qnD)JOzz1Z^E*2L+o-~fk}Q0g8~JP#di;Eet(Ia3ejPeYsb?!4~1E}f=CGc{SG@b z6JQ^oM#fJ`h5LbhBzD#TcHXB3$4+b{*OwMU#kXKiDooHoFPDQ}L7b?lb}s&CzXk!G zPjN^333hztJfpu#l&yy*6f>H zb=(NzveO0z4OfP5f^JcIWhB1(p~2k3kBUNWwSd`CKz}_OC>$gSx}37$0qKY54-TUG zzBGKPq6|fq!J>^#+3@qK3tGf>vV)7_!0g}@$T*wLK8tT*8>GBAF2s#^I0xe!J{1O4 zZO4e0^FSeg8sv1DKqE~Q?N_e>vwgd;SxcI>J!>S(yhC73X%HF?_=t7a1k9Oy3B|%5 zin>21GAYj?Olfk9fa~Ysaj6^7;^@X^$F_@ZmlTNBMVf$b<~o=h^_X?5Il)`49@47T z&H7+JNgTZb40Vmb*YgC?_c(yY&VFR_!l`8MR6%cBAO-aX;oP&9LtNhLQq=hDhnve* zf%-v3+>^+$*X{23{DKL5AE}BelaGR~=5TD7H&~=uk&eC11Nnq8)5$ZXQLwSI4y|TS zz!_8PA@Ao#tlkrcI>rgu^mr)j3{vA|m4dK#<4+0-s8ZLnIxinA=&$L z9&FmVm@_dehh^6_!Kg6aW|y)9p6ECYo9Qb&5N#GU-y zo-2CMc^5Km)7knN42LwI5q$bBtm*V_>^>`S5WjL^TZI>UTs(w6KbXU8f=tPaq53#5 zbuyF>4dtiGWC#X|fRCQ+>+bqd`5 z)#&R#hG6c05I29|*%qZ(G#}05HHi*(Y@H!`>PAEANO}II;y760-X)43a02CTsbYe( zGORF+CefD^iA0P(&9u1y!%{zx0i#k-wWu4%bvCj3Yl?ib@_9Bg<}G}_3t5u(SZ?ts>BGky;g$vjaZrI1^=kHJe}Pz!C)QOaICc z`fPzAK6xz1J-(?y#|2);dDa22*ggutQkef99M6oJ2y#(1#K?FFpV$2t)P8DU^ZX}J zr$r4Yb8j20u3FB--;2SsFRDab$PM#fb^tGrDa4wcN{~~30<2#@;s);KPvWui;|<;<*eICVF($9)Fp$i}CYc;VL?;Tz7!s9$FI#cw4Tzp{nuuy4$4TQ>WX zKZZ68ABPgfuIRr{l1YdDVY;$U80|`gLYjrit#%k0_J-AMUyt2sX^gCTgn=K^*_)#Y z!c1xwq_zO$dWx|vrul6CWJmImH)q|8+(5H&A&yrwgw3MMaOyLGAv#ldz3@L8v>(oo^G*aek4{Cq|N-Bj7qQ{_Ny(n{=W7 zJRaL2dhHwn*>>bbMJVVBj%e^;8YoxvSW1A}`uirH2!yhp|IG7uX|*Aoj!2 zTEq?i&AK|R@aFh_7$7+x=U*8B-O~YOE_Sghy8z&u3|QM)5g4h(;%Xa{YQbp)TT0aF zvb{4|r*=QlyfGd&cqs6ne|obQpLSvNVR5)0dYa3a8%$PuN5KdKaW+V!6teG3B5Qu0 zWeR3Fpm50md;GEmZ&?=}{dFCTn^Rz`D-XA`%GlBa4RFu(63L0F5UsXR#eLuNKze=_ znHZY`FQq@TtMgCep!%`&lz=^ql*L%W`Dbip*HyO5)trBfmxwnEf}c- zbBlZns%F)2>*fHeuuj+q?aG5iYL#T0;!gOLqynFXIg5mKbs)XK72@NKATF;5Plb#B z&8K!;n$;hqA}02)>p$_S|31Gt>3`;z9~WBDzQzqSb*2|xKH(&_2nwc}LWV?RRT5p8 znM7R!chMNB<e1Ruz_YS6elUC5E zu|BkIX*PXzE{uj1O{I}_`{|n9QPkh>Fr8v}kUsvjj@n<^N6iI}_M}A!<-D?Kv&?qt zMpEe?%V@fGS_aiRZ%X&>-t;%$dSU7Kl1xFr{@3-N>ihTntVx1~J?g*Eu(LMEpwmiS ztXSniwmf=5{?htROtjO;)+hq$*;klB`)Kf9XMsKD**4{cd&s>Z3ecFDC*ag4WQ=7W z`}Y1kmmeL-rdlhDEVc>HU;HZDWE~8p7uI6H=@9Pq=o2E%+(n#N3V>(@Pn7CTkUrz2 z>e9Y)?o{JVwzEnKm6B44Bt68&98!nl4W~$>=R)#s_;mJ2Jo<0Gwy)MI6Y6U}0YpZ_#}U*9;7YNmW~6`fF8O@OBbDm~$BU zv~i^Pr6=E;Gl<_^nuC`QKY`+mA1wavOA@qR2K_QCuvhC9cHc@TD+7K(qmjnn&;Q$c z3;%ywzonoz{x|ivKdGehdt<2Bd?&hbRjiO-Ih1Zc^qDRW$)n!G^r+;d99od9Vta1g z5qfcS2<>qiO0Q~3&~+OR)1Itg`a|&?-SBZV)%a#fGg6G``&VOVqS92l%~6M13f!=V zy*qU|sz=4EqUqqzr8N4y7`@$*M}JMf0p9|yLCThWv{}xL+V9q(AMeWBPEc~CI~F~r zL02_tVLkp`e@Xn0E&sTFK`;4l>i@s`$1DY1Hp$O{(6l?ecNHSq&QvpwSk%Mi@-Cra?C?#6TJS+vvhG2k=X@FKK~#iGeCwL9Q|DI zwO@m>xKC{BfLFp=c@$UF7mBuT|0sH#t3!6&FXXoV^2IM!tKi(LS@>dIE>uM?LPOh2 zWQ@mDyfr=(6?+ELuht%9Ktw*0Vp}*FW(8XBIS{rtWQGQZTV|Evm2JszIAR>E|P5dZ6kZLzv#+KUKB*i|SOWz@ZDZ#zaZGQxJ1W!V%NFj%4<{eyS zpNzrB9%9F%`6Bzo65Ks30~PK9JXxtr{#rJO_x_v!H9pdCdtQ`Amx`H2Mkn}6vqV0~sEXB&4=@^{AcEh9CvRTk&r38+`-HVlc{faXm9w%8pXTXke ziI85nmxvqxA)EKaks}Yo;Krv1&{8l6PETJAIzKCLikCFTbcSHZ!j;&#ek2(VFUbyC z1~>mip_uwu`2BVeTU@Kjr`kUPGmCZXm6i-O%7_E)`WEOPF68h=7-F4!C~K{Cg>`X4 zc30+FTs^ZIUq#FFE9>2{RjUm7(m-OhSDu@&t&eSb5Cf;z=i=3;7W}}1atOEjjt;js zqOE`dm;K6v2~!L4yo3a9a$ZW7)uh0cW#Txrt%3a5af$_S;_S%8HxQc?2R3Oku%W7q zz5B8XCjJb-1KrtZ?|BS!ewT2nr@J|$#ftFSMUJ!mEY4QuN0IMs-(cq1Ml5#{@P=y^ zd=PZveubGNHB^`OA3FsVV{2f_sUVWd&!del38;0?5;Y==NSw=Yyw|J-2^WuISpFJsvn0m9I6zKqpNOHi zC&Ac#CB*lK6ZU_IhV2POp!FgaGgap0@ZvfQbeF|#Aq7Ns#5H(ku$qKzJ&30R znwf3Z17dG=NYtvopXmOMhCyMqP&@h~Ufq|Bs+S7cAyQ3#|6Yp63M)jvTBouR4lcM~ zKNI`2@>s>UTGTjD3Hwh;g1OCNkZ92-Wa4C8T@;SxlFw1+^a+^X+rrXwtnivaQ}qt> zXyUNHNMuNBkvMg;}{oi`>KpMkKIt?+a80Q&m#Fx=l8 z!gkhW!-3XZT=>xzHf3Z((TWQAR3*ZFkMBdYeE^A{Wt^9z2DfS8ct=#qrI59gM{p|LUUD3_tvUvs=KiNr+FPn-_ zJlnbSIdLpk$UO4m7O^QslC&T(4gI$^a|b^hL^ZJ<=HYq+`n6s#`>ksHm4vhKYM%wa zFZ!F!;9(0f>%FQl>)S7)-!6cE_$MqmY6jP1WO%uQlOS}6HybeFE;QF|MHSQc*eWdr zl8-|~snG*@rPAHdqqGyH4oeWXbvjILDnmJwBDAqT3l*aV@P1BlQ1dVZ&yS<9P2mw+ zpN?$8oHSOgaa^>)_ck0CljBnjcd+J*#SE*P!L3t*zg6{~TjHJqj{XSRF2_jvS368- zCa^&94vxs43(-4VQR0d;P7t)1B2g_~Q%qy;RyC6H!w=b|-2pgI^*IYpizRDJq?!L# zb@aQu5Qm8=(>0@o8R?X1*qS6=t+|$B?e)l(n*Qy%fWE_rk8brNKO1ULJhN17g?c9#oyQC*2iuD~3 z;q4DgP-~wn{^c#qk2H?pSGS)gD_YV?hw@xlS9p~*r5^#uh!*zi{6LJC&4dAfg1*Cu z*@iKwAaDu37SU+5cp#`pXwmn(#*qsqj+dH=5lR zxopiKv%+NI(`s2EqsNJCEJ+4(=L)PjrV10(3o&)mExe;V7}OMJlV=V4VDvj<^m&j@ zWYhJ?p*PxC2lX(nd?dad93#8~RqWUo013gT_~5n^+P!N-HMW84oIDoZa-KN4*Od3$ zeE`pVw8Gxeb@=+JDipqd0TNfz;Lj*OZqU2YP}VvQCZ=i9CA$`a?e}U?#cwNAD=x+} zMgAEZbcXVnaeEH&2YmtS=f3)4KI|tV~cAP@w;}7y;qMD=E0{!u%jBu zSp1Gnj0r-ws6HV(<12X->WkR(1{9JLAT>)KPY+wj>?ORhW$9gTco~*_9;RaA_ zp@$FqH*%ZK2cn(!WL&aLfuGu$%C5wlgKgzXqL5{dF4hrP>G>Bd(Vd8`Hy4nw#RaV1 z)gSGJgXpC+KP<4D&PHVDf?K{R$vZk75e81 zuL>aZDw1adZ^Ou&y8s=8xkl;X#4PPBxinw|JhuYytDUnFyl3On5RZ4%TkZ5k+ubr2Vxrt2)pKU%a-HW@&Yh^0|t4ul}?N(p-lD zz3)ZMRuMSFMG{i&ZWB#WKI)XefdK8L++XKELgTxE`2J!co7v#Vmiw#V!tlgtuj! z=im-hE7{4$ep?6EPTT~?@k<#eCuo8i4QOc43zvothNFuQzyk9z7#3Ycq&L_Zw%xS?)kP8bb6-E}oA3mull2fiYZzQJ z`A!}k@WZ*ggguMieHcCM9Oxd4hkI7hs4?su{D>?ilU?43F6f-$p1B#rjLFB*Y1U^b zOs|1ezdgwJ9v@*ZxDW15NrX(Z3Q=y4G3AbIWMMmR!KSliP+J#9x^F0UsCKm)J zlZVl3A5P(MB}pn5KVNiGy$H)M+#YkZ(GG z#6}P0o1cgvZOUa7UwD>;%gS>JN@t6Nm?2nSA!Gvj_~v1VQRrb^hz|!`y{;@etUW0d<=dU~uL2 z>VxGL#L+JoL$ZC?3lC|UQ#hVxJDwreUKisA*FwXBN@*cn^oK?Bf2^KOi5S zPNJ#J2DD4wfqh@1ML$MvfGP7%5xE%|T<>pLo*Qkz-4pz*E5-bA>E!DqFti56b);}? zhXH@&tAG!Nj)W4OTAa{oi{FO2B3&nBwf!(>(%t5GYEuPND{O_SCpwtdULFsJ9)PL- z?{L_x!(4>4649Bzm6S}lMb>9JQ4i}E>_K@bPHC{kKNF?kVL%Z(yucDv$~7?}-InR? zN{82L#Q4n(!{PG9<2J*`&EYnL>9cQD7oj9qi+48gBbV38;E)%uiQTPVME7bm3@>rT znUWfUzeXOFixg`BMMT% z>}(!vP8)6Ae6$G4M|rWJpGRO^S2t7oF$bQ0x{cD7`>^r*Wvt4Igr_+fBtHC2_1J!I zE@_7{>ljyn7YfdR*SAp+c2|Kf{&8RU-zekD{^K~HL7rFt_|2xD0hYL)gLs`x9A9^v zSh^JB;MmeCGVmBCH4MSX{r*5jYPe3y1IUhGk@t}!@WuKe!_Py&tLZxy^en^^W0fK5 zWIhSHB?e8g6?kXmdW`vI1mjMe6|~(GqSa@zAxm$M$n0D*M15QUyG9_>pHsrRc2>ZotS=&y zXU&jqI3G8>Y#~1SQCO2wKq9I}p#EZE_H~9DE?B=Au4kXX?BYE3z+x|%X%oqGl5Fs! z`#I9t)s6!;zpQ=}eul_r?f}bSy`XVaik8mv7czSGSIS*k$TXb};0NKjB3GQpyd?+Y z^`vrg&}9j}m=%Z09pm9e&pMQ|`@*7AE#S}FF?cR<7Rp@-A=k+b=KoS2PP&G$&hk#& zBJB;0-5c1UK@U()?j?+PD)^xTBe~W=eJsvy7dsWTn|tQBhRh5|Vu@E{IHwW``ev3Q zonDmzVbv#~&hZzgnNWwy;?58~>?cd|bcI_#?a7TJcX9WZdqmT%8SH|VW0qgDC|^ez zr{-OOhh>FWJL3pue5w=mE{z0xZ{@#dgti(iCI6H^w)~&`H=B$Yn#o7ftQ$deOZXys zcAW#Yj$cF1AKXEGTlUdV#qD&zOa%3kUQXZD@29rW8|m-u)-+eahq{GKr7xU(=&gd~ zl=t$WPd+T7m9gG5LClGg5ni-y#S|K&7fIg_-bNi%?5N|#eN?@3E&bWLg8pudq`wY? z(Dw_XXx@>nRL?eqeuo&E(Y%k^jy^~?7Hy^xCL8|d&wAFStoz6Oncx@wZ}_vsSOfHZ zyoEikh=!!ytC;fC-I(WUA=)=%2oxWww6Xd47gJxkh!Bl=F!M_a@jG9^irwbo_PS)w zYvHx(ZSoma-vm#1p21vr@fMk@nK9Y%`#vXsMH?HKjNnz%1Os(L*m3;^v6h=kmX-vH zHpWJ9J`>VyRHLV(-TqQhR-z&)ifLsH^M{Z!aD>3((~N43AyVaifBQ}63=Mbv$Mp+- z)BmRav}Jp7Ws^fy_|ZcC>j_P&vV9l-t~G{+j$`OMUzKvZui?wpG5p4p=kSHyZ&+;g zQqf8!T;|NSW6u5t)P!y7>P@ftXEZ!$cS zQ3ZVT5N3=%L)VTO4sTwkqH@AY%HNmeBNyIbi>!-)TOP`19ns;Jb&jINTcQ*~%b#DN@F^ zcB((kvz4P`t@lv*5pQVj;ki_`=r_Ew*i4(-ggkD213G4<8J#(*1m4ZaqOInu=$p6s zbp2NeS~Eq4ZlI^=^&N9*sp%a$4_495w!3MX^HcglHkkT5O`uje3G`9k09%DIakRr{ zv~A|-OxQek`rq{%O*Z-SkLwroq5r1-|1*Cq=rsQq{`kP2aOTo}hn09{;yLk3SWz&J zo)gYkyO+&zb<-XBjXvY(mFerrgHPd@d@O-C>Pu%~ZvxQyydr2lvj7)M#QnBK>}`+@ z7&&Oum74phMED~9N1ZgzlC50X8^$}-qt$h!HH`BrCv^e=Jp~EU__kz6KHwYha<4 z7!?<-FwNeWUt@KPY*Bedv?rCo^RD+Sx1tK#M~E=Ob_9OfqmK1^Leb;NHm2CMhaLt%vUdFi>52$xy8D$@VX{7nK=?WfFlQzHd5)+#nlom2Vlvke%xJrirK8bLT(*c zO5d#SCyp-1@NMyS0pEVNY1wT-xb>?1&505?ymbW2iS0(0czbl5pu~0ki3Ep}_rP%G zTkKk^!QYV@k1c*5@#Yr6TRbTWDvO=rljByR>u{ab6eQx>NBT5);}|fIKLsb(X0epl zn)KJh&nPAT2sH*px@Oef@B!%s@=?ImtG-S+m>E6TsoUSM?vWNz}7j$O{@&E^z!4(9Zzz zu$>BT_?5!Yhek9MFTr2O-VlY$p6qn21etnZF0q?)3?3aD10LNbG=H8Aq|TFvn0v{1 zSaA~7s1JhZ`cWM|i+l}~i+${d2suli7i-VOr{4qFGg8!^<%$Efo=i0Oe z!Gnh-5HVexkDrncPU0`%e3>2}HDwt8c*Gzk|G<*=l#27#+V;G%!aOQTjqrzn@gBY$ z$|vLFv0NGR3xv7;-8)gXcp%gbp9_z6mf?s<4GjI9 zj&=h7_3d^X{wWxPZ{ND2w|YI)gk^!2@)I;)*bmO)F3i$-Ha}e9FpY38!1<}i;AMDt z^*+5*_~N`YrLHkV)FE(6vJ0yY`*g6=YOSIzu}U!hu{5u6*qaaC6bltUBZ+Cm2bkNp zAHT*rQSV~{*VeECRHE{s=JqU7lm7-L4Gm(-=Z3)_Q#~;3H-|Nst1xsUgWvkX8HQ13 z(V|g@A1s><4i|FpWv(4m=E_pFRYRzL#eL2_uamUvZeU}ovRFp-RJ!wIE3TWR4Kb_& z_s@I>k+afa!K()J{-w?$Wh>BT#X>BuP@!vjdWn-HtA@q;e1G3Knrk!@3hOu1wblFS za$`5jA4)*03kDc5%bCxAa~vir3?i*ouSmkfF#N2q%$w)P^009ge?qky2UiGd<1=~s zy(bkkm&Ec-n`YxHuNPQ`Z(*(eL$=D<13q`zvcdJAASJ69bnIt!7ZEA6E(d1Z9X>|NgE#6N0JJ@U2LXUS4-IHv@dx%__hOLl`_Mr{$sUIO_ zox^a%{xVqpZ4>-!p2)6X`Cwb&*wcSq|H)tQ@BRr(L0^{;`~~IW3V3N;fM}BTByxRo z7kPBDOti;SgUPLHV=LEiHs58_$fJ}MfA6zHOI6y&iiwH+>-tZBN9W&W@vQ_MTk}8o z7}hn_5-Fu6cw~JXww@wjxmpL8yG20F-c#^QQ6yUMs2pB13+{Egji}Xq2%nW3fayC@ zKtuEgv^5sNp-T&xw2>|p{dEBDoY)VlX(resXTXQm`#_|*E;KH-LT*t7xmCOkAHP(E zZ7Wkr%D_}2Ya)*I9-~n?iFp87EABO>Tl|;^X0rxg&9FEdgA{BL~MDfd3 z;M^mY@NVQH$Y|PSv;Of#R5QPTdbGtk@WIhCefMSip!7un(waM+$*l&P^uM1nziZ*J|+Jm=->!@7>zWArD)-?Q*DYWaaEWYq^q3uclmhY>;$TgW1T;-QKt78$iGJN2 z$1Xn##Al8npq3~B)6|X$fs&>0;m`pbwPY2X+MNeq!z$T~7#?R&D1ha2gm<>LmgzN` z63HYb{Io3#`YT*v;K`E^=cR#jw=@tjmDyxzwk|w*?}Ap_g3039zUbW$%|@yhW1NFE z(B@w@tG)Vc2F|}oa+b`1eEoEIF!?9(v@yo{xl7oN=7>%cS8!cthhm$7 z1UUS>Pp(Y9LXKsvg2C#Rykt?W$baKKI3t<^4+MYFO^eZd?9=V2W*W|P2EAe_qAF&l zyq?t$^JPu7p~P9^2K!z&6?#XGfPkDXY_)ENwzqn8lhj2nKq?9JHWSf~Ii*~|5KVlX zTE({ZiBsL1;%GWA0dp=Sf&5JdVHRJB)Vxxr7%Aj<2b!|h_DnYSTQ;W6sumd^eT&=I z1TaO}M)Lf8pO7&&ulm0GeH;9J zQtXGk-HoVtZ9V=_dP)Lw4}sj_2$=6v$SSRq!LWBGGzaN&pWTFWnl4`flc(``t^N^Q zRu`j(Oq|hu^kY``K9jtje*?wzUWk^JnSx{0K~xE;V9$RhiGr+_L6npX27Ba?*K5V8 zWWZAR*q#ps#bKi5PCaapZX(`(=gGFX{DsNiCxF&VZ&u+{1AY}Y_^#CoEH4XOQ&^$E zK^owaUwgr5tpplZy<_oN*WvTh10=*s2R^>P%RD_UL72~5a9YqIx5iwXL4!2XSMFrwK#rwAf)McvGuy=;jybZv&z~)GW138X23+z zR>2#1`uJS@Hp&IAt!w2@{~1hH4>m*V8;W%Fp{eXW#&X{A`hWWe4L&T}{ZH3FtN+Pg zJGC+t$GW$Oj3#xEjb9~1-wGCxds$^aXGTM03e*vUr&!vQZ6a$R@JXSrzsOGoKSp9PqmPEAsTyc+yojia6w{lHl3*;PCQ7)~J>8w}0-z zl`r!D6#rTYzNY^M|1QorK_sdspu^@~wpKce^|+Xjfz}})A@J)*!Xu&aYXY(P_LKPt zzU}1HW$f^~3}QCPg_NlaL##U}oIa?5Z`bU=&$TMBK2l%kVfnD@b28}`kF56nDtOjY zOGu@!8M~J62<8{;MQWX`Y~P_x+|K8H+-2Wx*55h;#05PiP;(lTea(X*bBBP2{(SU( z+RoKKh=k1>LPhZd+sGU;9XykFkn{yd$#AWQq-W16Jm0wx_a~iaQnQ1IcV}yLz|>k% zYx{X3U(4X^S7oBwHvl?)3rL^MZ_($mrKEn(5m8U+a(r+t7>|YnF0jmH0fXz<5fc^W z?;C~H7l*T^BOW+!jR?ywOyDAQF0-{mp0bEkSyWK=!t)x}Shl_e*L}5$n4EQolU5&z zhVvwF&t1qazmGwS-v=;L<`;SItP2L|>LB~(ifE1DRaSj+I2t}^X21Qtk;|50$GwiC z%=!;Z$t9V+NF2pV9ki==c9~;W3uQV!Gm+zRMAh}yWQCJ2>A&R$G0&<=jg2XJ=^O-V z!z7{b_7P5{rH`%GnF(2MeTl*hZ+!MJo5+veg7fk-$ky4<$orLp!9kew4Lu{Ajj+;! z9q+tbUAI~T+<&Z^!v8f7M~V_i1UU@-0YOl|&OlUh@EQr3CSWXy(YVY|hkUYhX7~0? z0Q-m9q>z4QP2-lqn30v_rEw6M^Tr>fja=cR;s#MmeI+@wK*+oC3WWofl5ocV50_G4 z!7e8a!1^`8__a9$n|cb#p~nZHU{W-6B&*`l6OGJLQQW3trWPA^T$h*)P=%fDr&&|( z59{|T62Nw6VE+CPjB}Z6B&Fgj5f!y@d4XE+{ZSpsxc7-U*OCO61Mh@p_t{rDKUCjObr6`A0i4p-Fmvc zr2Sl2M_=WW*a5~Yq$?PI@4m@$La$?hd?uS+St07Xv>dZfOd+>72Lu0m6pX0rXAPP! z2_9=A?Z?idtIjrdOPE#7EjmUXOiUte{!UE$+d)$CP@icOt`{=jqhQ0qN`_n<#vO7=aU}bJGl`2QE7v=N36-p(^ha`w>KI5E*6Hn?t*zPIqb9G-7{ViMG_YbhwXhx zCU#Tu^y@U7E+LJ_C4aKS{A|)yu8&R*d+>;lnP}V0?&_@da{RViDcr}i<8aVqPB@qF z5SLc!CHfX#!1gR!z~J>@$gHx!!TI~JreiS6&I`6F`Q6BT{CA1gNvy$avE^)l!EgxH znGM%>q_8DvMP%53Z4lKr99O3=f_j@Xn?p9@?!}5Sfva7 zs;V%0rY#O=0TkDp534$o$v{sZ@?^LMW;ico>J`)ROpP?R&_Inz_opzKOF^*Yv?&zL zaR0miA2}{LB6FbN9~Z9wguDLTKW-)H8~;uJ?@`}Ec_9lw{^u&HZ5T%t=g*-g0j6|l zRTv%R9Zq-6_oJm+5p6}R-ifHnMB-*5Zltu_y{XP%E>E4IIR3krxmP+lX zXV>hcIeWtC$e?iQ;hRjY-fp22O?Upy|C$A7hX3RB@4wVPo~NVrB9wXzhiN>&gkh~#<~mp$u$inoA|}D_*FWF z*+xrZedG6P@6mUefkz026+b3dj}!QnYk+66YzX)GAPgaQtE=_mh{20^Se>d4cnHxiLSf8FH*!~fPsM%1D&n^32)ZO+W9GzNr4}7O>0aD`o|Pxzijq2R zzV`+rkM6?qo`ukEeF}O@YQeNmvq{y$8NA2C zp8P3W1fJTVr10|_=FoOYre{MZITWf6!;D{$o{O%`)HlUMW%hVbhb!d3jgw@!#9OA~ zTQ~9l?9Wbqyq?!4r^2Rt?c~~w62?2^5L_5Dip|z|&+N=O{-6C9d^bMyKYsrIKkYwe z|1b9+#qkGd@vbHaJ2($bsTP}eZv)ScS_I>l%HzEicS$Jl{@TR`5W?@^U)3c;+^sZv z{%`~?YnI1739}$-LyK_h@sC7y{&Xl0W?|7LAv5`OCgwlp{~q65p|j2AlBxn}FyedY zVGadcgxWaj<2YK>7&l5(f1#81uJVAURGxP@xDxt`3!E#KJny<&f8=gcIyWpuE@snInjT zM14LZ`L!NQHTCGZX98Nh^bUR4Rzng`PJkJ70&Gb-%oNydpo2FgMgF4Qke#XuZS89K zanvc$n7^Hz^U{IUu8+vftMX)r(Eu4={t3mW>0y`M6S}Vc1PT;((Ef$>7|x!6F7(4a zL)ozBLlU|fIFhZ#+whWlCESeA6a{Ow<3S?Nm(89L%h~N%B>x%brT3B)x`r$r)U0*nC9mK%ZY3Gq(GSHxVsN9fIwZGF1GoGvU~k03 z*-@DwR=t-qjGP4ai{vr6xR3O%(h`Y`PhnNdAvk}qkc?AaMT!qfVPxV(=v^HEe{^)9 zvgQEnmp_cz3h#-jRxS#2iOc+ElJW zf7z$w9#bFUH>#fI@Uo+yqesKn#0Ktyg*CHm)+0JAK@r!*Rg=Vr{urQi9_|JkpPEp*`9_Kb$jUJArrEbJB$fup28Ie7rq;QmzX_!1-F--#WOc#@bJ3t>mmj6uj__Pb`4BF9N>oa)aB?znB1>@bTsOFq0ct-s+wuC3(>5?a8q25+3=~zoG za4$M8w}qCh`S9b_G0c=s!IL+2;QP~BT2ycjF!BKm%@-$PwbQV2FbXsLi~wGW!H1nm z=qEe_qwj^|JSK+7o8G{J2Ld8vq9`h=I|0p4M}l604UF%|BHO3u;>p1qxX;BOe0 zw&f2r6Iq~H+j7y#l2k|xxWc&n<%B&8tMTTNaX9biRoo@HlWDTuOTUfX16$nOP<$KT zCFlu;xt|PRcuo5htEqUHWw^ zPCluC-F$!T!E`xzrgH%uUAI!#d9^TS^k@`n_zAkony7bNGAE%Q3ii?4;Pd@Da^_$J z_A?Xt*ZmX;lMG@mZK~&P=JX24z*Tx=!8=^49zz!X%7#rHd2ny{NN&etBunM>M4>bN zVe#o?oEuvQg`1GgnYE7@%sbRn68<_T47R3Zp zpnlaXP*-{aZ?ocw|MN09$9weNNDnaU#@2%2s^jpjF^hUWd5AkldBMdZYg|6(EN0k* zLge0;obtVAMC!0AEXcb_vmZ`|1>=19%*{AfaZU@Z&n(3vs!zh34OEYw70pqyL^ zRPUY&eTRpO2=7z@5eNIjreSPKG`wydAsQJF3|H+6xfKN&aPGJ!tgTc8h4V>J-tn3o zmw$)ry>{^#ypdEXcOesazrF)(t}KOc5#`{sA+Y zecbN$<(P7NB@TWQ2MwYkvayRL8#k(egWh)d{ro4H_bvz34wT}jYJ0TMI8XPkoq={= z71$*=RN?yMpY)U15!UQ@=T4Xl*wI<)7tYr+psT?|KQz8(oHxZzV(_m2)6fsS2`E zpFsQ_dB`l46uJo`(0JEP7<#xL%GQk`X*T{Op8vg?*Rvt|N3qaC?Hc{F#Rmh{XkZOj zODxuwz`H+t$n^U&z)AiLH7x&vzqa3@(H~!OosVibmAWDFX>JUjWHPY+=y6aN_+j43 zMo>{##_}oJ;FsS7)|Z@d{_lBc=;2Q{Zn6Nlxd`Jv>yg047OYvoVoWr8fENx$Lzh7y znWw!3%P%Fsr*3oT_e7Lvx5e?(@=@Z|dN^Zh0ak`1F)UY{W|bU4xsT^Cr{V>To@WKk z>tbKrk307h@W#7E*>ccshyfYXJ(K_IRlua9D}FqeL(w! z9NJ%vCE2Vi9Qn5x<~B6IyO~JZygKRdBTg85HH})Q#bev(PTG=x1nta)knraSoqAac z?Zfj)!N2vQJDG~$GA$H)#GhkKQ4Vp=i3imu-*AIalQ>q5#~DAq(Mc1^@%TJnDCFEw zv5?=V{-Zd5-Ut}kc?a6{-ZP5cLOOYQDqdUi5N}Dh)2W)d;A3~0rfUw7VMb@UFYDIg z?&QtYs})*gir%bL{U8(G478KF=Y>w<5k7F$^9=TS32uw#W+i!05CnbW{sLPsdX*rY;t4H_pQNx%S+%@qAY7st_~2 z&Oyg=4YI!>2z&K~c>8<--ODxLfOQ`PjyXk^EGee_BLd;XiTSwL;vC#+Qzwt^9Kw9v zV0u$w63@6WfJOXwJIe$oxa_|K3$E@!-$wTXq599D;4$kU3iCbS~q3jY7Sn%_oa6@m{r!oeYuN0BL=O<$CqnlJ(wE-#~ z-=oTzr;(fQK{x%|g;%*;^44<+aGk1PxNHLv=uU(xzCSW;>MnS?K8w@gXI-EAHel;s z1DI{6illNA&VD-%4_yC9#*eMRe5*NdW%NqA#OEcl?){|spA1BsnVdG`Xqg2Ac}8^ zg^alOp!eXdMYHn~Oc-H99bU*`lgTlxUpIn!1v!YUy+`49pW&ja53$59w1_I*j>i!r z6hWk|kDbfiX)^C>%})Q$@5(j!++PKzuI^xL9oli`U@^*_DHUk)e8Y-~if~$2ok%TN zP4+#@fWZDH>cECeg5qTa3=jLmJLUiuPP_t*tGi5!U5Y=oT>1w6+okp43{k8v}sAm;f9 zwk%9YS9yO$oxmy3H$xTeKbw<%AI{?4>#is}XaF&$wb=abENdRY-4u8Z-EllNb~&z@X^m4)%%ZQkr}*o!B%5%r9-mG< zg8gMOZ1@FPzH<^w>&ixo-dBpTE$7k@UZ!}+_8RDX3H zSH!$vzKkg*W)Hi`+;uBpNA7)U;}Ol>ajz#Mwzxo(-vjbw=onW2xd-~?t+ZyQ1k_8K z!?M<9^zEy{?Pfda@a>kUXP^dN^Linr=@sQZ#6f%GI?k-i1n2CL1nbnvn3j46jkg{G z)!!;?gs=ezKVKnzlkd==MY>?zEg=8q`T~*GKu*RB^o(O^UQi0P?`uQxntx=*X%qOG zdjR&fEQY>)$BEww4P?rt0R-m2JX%hE$I7tsu61PdN{(xm$*t%Trhv(nZ=~nQ1>Cvn zH8%Y_hP#H%q;Xl>&>>U?bSv#}W<>zH1?Dqb^iE@bmnDYW+mHS~W`J^84BcJvm|3cP zo331_%xN4);yq&$ra#rjUsdn0?rJ7(^^hk~6>2a%RU5KvMhkac$U~j&rF1&q`z@v#B_(K)0rj*n{MMotWmv9+&j|Xb$>Gl>i&gUF7u=_q_-{_h+4(_NkCc_|M|FttnRGj5@Rbtm@TB76Q4@4=_kg&A5(+r6Y04D zWpJ)JjTJ4u#8smgXN^1rw{|O0^286j+Ky4xeU{h~_5nkz{b;8q&)0gR!p^_gh(}8f zQvVuvOg@6%L{F@~F{}yvP(LS1E&$Y&OUC+z={cO`^&|SxC_e;pEz+V0E^J zh+O_jW@u{Dv4szC;k4)ITc3sRrB=a>*kG*QbB83k?Zh)|4QfTt!;W`RX!vW8)OdR1 z`x+IL6KlZdwmST4@P=&IQ;7RNJS2(QCz(CzzG(Nz7b<1$GG)p$AvItr`Muo>X8*Fm z>Wyl!$R`4=CL~g?$f@`vzl*BP)5HN~0ZLk3!1iaM#AF0VNfBp z2fy?8YfttHimzOY_fyj8p_V9o<}?qc&KfWJK4K<@JS!qFTn>aAx8i5Nba;G76WBA> zJjY-M1RUeJ?5EFQ!uJD$ZOd2VJOg`hFD~c%Hk*Z-)IYy!Ym^B^;4dA)&Sm zsudWDVovb>!R-6^a-Tn&_&S4efkK^-FLD zD)By>ocd@yJKh31m(D^>p$^#l<>L9jd7PY$4W<~S!Ls#BV9i)bY?7~{TQ%Q7|K;1n z|H5)^fm}4$FYlwj(jK5^Vm!Xy+r{+vbaL*3!w|dT4L;6!#bnhlgY+VX`0qRg>n<2D zsWvL4rKpD*Jx@WMh-EY)MUL96OTZ2Gb};U$B0H<^nqbF$e{al2#;*j-M_=I*6GE5-xk^$GKP`2L-S4opn3fRD2?nPtQI9*s#6R<6sU z#&y@ok&UHPoLR~F#z}#z#XWj5Vz@}nJ(-~MQvB4dOuJuP!xBM1x6k7bH^=)N^KOJJ z5nQh#Mq|Z9ZYy_^kb+`VSM8-Y>sis)#|fnS$RonJ7QqLV6CgkNBw2qXlRIf_LB}Rs z#@To4nLt}x_^T?0Yr@1tZ;jfx6TJUnlA$FmV}CHy&itlo1(K}u;{fogmS#p6E`e)_ z*J06s3a%gZPneUwnS}L*(QX|fs5VUi?cyvv(HKf6ovj5O?_Jo_zZl)dSJCbHge z3Z3yI3@6A917>s-e<#_%)aJzi+$Wah1%yUn$_eZZ{qGvLA;9x8Z@=nRxK~bnZj!2YP$R4u883lCm#qIRCIC zPHJ-Cd+a&TvO^YPn)stzCRi3kb)V@`niKuuSxx18^-0C4%#Vwqt5NE#GxSyf@BSd zeSQTkatp=&PqlP!odSNoZVW}y7w`bL3g0eI2Ik2XoY5)-(fUd7?5Hl{_G7sGg(EH< zs|p_ngM_*E2XI5V0p6O`hK)Tk*z0dXwIkwSx4HnYjNMK5EqwwlmafEh!EG#%Y8QUq z!gEF2DRGeF*>&l)Ou}j2@YLNHJ0aaPq{hBFPH?ps0p=BmzzVT2A9-C0KsCf~*}x%xu8-OcdY@;li#Dvq48EeAi7 z+n7Yp<5yDyq=C12w92VwF(qyoKgo` zpK9m*p;EZ9qKYoQd=T{JTtdeM3Ru&%6(1bPWY#-ABXtV~$qO-a{8nWFPIE@nj(UHp zvNs9>#m`}%Kkq+De@?%7D8Z;`zHd2L$T1=5AkWy-Ti^E3&emk6SYj6)qh8F^o3zl2 zH!lhM+RsC$LO-3OZo{Z6KLD*m5+ENs66)S~8qKBzB`+R2Yk~YS8g_P zHiy7Yv;pyOA&J)K=U34xtfJgiYOZ$**yn%fhK+gfAuSZF#@!}c?yMj=oky5}=Z#dn zAp!RP6Tt0)tK^gCF`iqr4X)hN!6iyba5(8SHh7ESxQqlu=^dge4o&EC^f>LDJ`XD0 z&(ojt?!x3v26Vx}r+D&31RCZiW6>#ToXsl2u>n=~n3*E+`HOqpgu?m^u)G( zyTEwk35+g(f#d#$;;Z!a_@b*CJk*WWQBvPRo#QQ3RWpPMUeiLah}IFmqi;!Aa2dGeq%jwGZ)uIJ8_-Aj(88QW z_Q6RKEi=HKOX+}-J9^2ISTmmODnkxS<_Z?=Xb1B{UEsgi9NI}URg-*A3k6fCO4ASE z8gf9~S`5U@0--H%e&6VXc0C{NMx_F;5t8xnNBkWsN|Vd{`MLiz)YyC<>30>F95IrZW^HCBJ|DoZ3s=xBt!Dh3&;(%fUDC8M3>-e@ z!r+xpocjA}tc*;C@9EN1Y{C!j*1iOMQ0Sw9?pHg~bK{1qu4WrX5YSCqN4jf(9$drV60O99=1%cHxW^N9qb<{D({;ovRtOe9# z?0w59J#Bc9;>_numg3GQuVA6(a(MNV_iavWKwtBncsM!~cL!uM-y0X;XF)RdmR#e4 zoAlvos2RN8mr-GzdKkk79f{%XIC|r5DsDY+l}3ITMa^o9F;)9J4QNrtpi#%*$4(LH z`%#3+Gqgn+-#3BS23xLYLowzQS`r%2BQz*?z>i+LU~FnXnP9dIuBGdwUz%;;T7QmzkC)STDe`1xwzx=V7(i8DAD#9) z10LoDVD&_6&deqVA6zoQa~HK}QOiXfnjr(C2nq6e#WxalZv;-;FC>#*)k0!T9DVoq z6@BE;Ps3wXSdnWoZCKSqFsG0FGW@~0)M#VGG&7@kPfwpeAi!!k?*_ZZf%F z0lrBJ(F}Xg?QH~%E#&9xuM8n;bSebDEJWk8i?Ovn7oRoF$6J*-xTq$GPJhAgN_xVn ztVurpz-N{gvXdFfNg(HQK`Dw{Pi-ifu$?mx?H|X%kJE)lIx_R|`@@cBB5q09vrMmIllo zBQX584ivS6$QJp_^xTPwRPISHk*N>IxTnX+l&&7?Z2AyH? zDwIhY2WzV5;G}{utp3&x7k}rV+n)#;^+FdC9F$>iuoWHuQj*4eQ$%sbmy}DD!t64C z+S$32@8VQKM}Hwx+Lr<&G}q$dSOw5_e!?lu>gHtc1w+fXNW8WF6s_MYC+fJXgZAs{ zn3pxv1lRakVaa1j+;yc1F3j*FqKQ?v0<+(WqZ?--;jECcgNYCH$66uZw0=nIKHnl>we*h^&a zER!JezBYmug*MWz&5z)$M>OtuI*b)Rq=ep6lknw)l`!V56w)6;{*Gb{5pOI+R-YeI zlLOZvy~>2_^BW|>kPtHdsw#Uc_y?F;1Y)jPqOfLyrbylM8yyopnfQ2HQlkYEMAEBn zl9(~G@aMBlkYw-{9kq*T$@~)1>7NLZI<=Tqev)T2tHNkKfYm%huq?Tp+WtF7N&854 zB>70_$RmDtw_w;H zw=K#JbJhf)T<={Dcky%Wq1j~MQ!~#buw&XX=aVBxwh@$hPJmGFt)n4IW|jAvgT2cO194)zRf@N6|C3m);T}bxx3l?Z4BZ zY2kRd>c!7jHEW21P6Bu9cOh*H>v-e4ls!eIO2AtKzSzF-;vM! z((NXXc6EVEUtJy-JJ-jBJz$;Aic6eerR9Ct z-Ptj$qv1-nX+a2^TC$ZrP!`ReviD`hcZ9KRf>^exC5qiRXFFRo^*C$1Ka!m=;KAyb z9%k)l#_{aVD7NHh8v8tIKD*U2m{n*G;*o5jtgeJJ`>kj*`*P7?_M-7g_CZ=W>uMCm zjy>YV=Dj$~uD!gG^_Y8{9TAnt#=~wlH7k@Au>08NX9rl-3Hw;&&anBD`Nx^Em~Fd| z$c6+SVZ-|(*?m8DvTwJaW!E+yVi!)0U;~aPu`7i8+1){L?8D?0|H=P_23>Z1$sf;u z{rtbq=l{+>&iQZhQ{ULualfqH=yrt^IGW4nv@GutCiV~W%r=-_4xLKJ*_eRMS|gAe z?S!{Cw9qJ(W3c?5IY#L4GxTa5Y@MXe{k{}NUpY9#x4B8&ts*|ZX%s~NEq8&@^bBNm zUuUvP{*v9z={PgHjQiXAgS7iTA#djU(iD^1)GDNu24={?nJfEf#b_6z*uZn{=Gfwa zS2Kv*9V=RS_a5y_35JVh;h4Jj8dvwh8fywX;M$`)T2>p1%3q4<@WM{gJ}Q?)HuYiB z&JK!~H=zkXk9Xa+??3$rRsWa6{>SI{-{h~l@SelCv&X4_)l^vP`vaD4tj5cGA7kRN zt8`<7Bdb+6l{N0kW!4?`26dfhl=D508$XoeH`)E7?yTi-{-Xt|EL0I9TI2jB9DuZK-jVVJyCn)DVn;`2H7 zRPIPC_XlC@*q#@xGAnD9wssl2chpHX;Ph&?ahJE%YMRD+EjiAnHkz^u2}5k(>tObY zaD-K)a|$bZXv4P8?q-iBeq=u#GqjRT_Fy+y6|uO}ofZDk;rqI`*!vvEYPfH(YSNUl z;!T>d>_k zUH|x>zh572M8W^~{QjHy<^L_eVGf@Y{@?H$ZVm3`7T$9g47M23s{CT+R8%8zmiC1= zarc1vRzx0Lh{7{v>E!5=Xk7H?5|KRp8qGtauzBVX^%!FV%!HT1veM;L;?sP7XD3NU z#roia7y7tybTwwJ3Z^2b34GW79C+Pu5d1)Z!AIc`G;tJlsyR=8l@vmZgrw-i0>NX}s&KNVm7-;5Ytm@|EY}-xf~5V>!WGfc_8qCAFCtTz95v z>n$MpcMG-EOcjv&7|_%EL4WC;fYRT?84un&A@@F-8kfF;GqW{u>lbI42gc`uRi*x**0__PrOt>|lPjah<3(e-KPQ z{GK|ToeH)x3!(ABQT*vGE8@hB;6Sb(ooUdFCpUzF<;)~nVSE_^ERwjdGbiEtqmr!Y zx&gY=Vl3KyJ55R=rlQAL3Z8khiO^6ViL@ua{Bwb`nROJ)7Rs;-I`|x7$8t!DP{3U)idX8S7wb0R^ zh)Qvnv2bG|O-?=qI&3!BCw?XVZI8L5n>(TL$SLyixDn>_zH1ZJsUWicPC~o;$WA^# z^6J!e^vqt2{mG~4m$BVs(xk=U{0gCML?Xm`rE=THN^&`|7a&c#2VQNkKo<*f{FZ$k zS0^6k`F(Mu(eVtGZHXn{C+{Ua<8|@yOD)cMQV|^6A3`7PYUZRWB-n`Ly;w2Qp4OTM zLc@aNOzz(hxH!I+4i{A7fNddpamJAJog6_XwmZ;yDtuNzIvCwv?t?c+Wa&Ve9oiQZ z@;R_&C|7#|h0HBjxGaMPy*W!lzu%`TVonJQqF&G$N!~c>o-!nKo@d?!U4_SOzmYi@ zho8O$QSEveyemH!pUYa}!Cy*P7j#|#pT~=KyfufZo1atj);RjNqyQgY3WlRbL7=w0 zmSIo$psn$ApawQv`~nYjJ9r5UMp)u0H*?NXZ5$J*ww0$^ekbc%M*?$Jj~;3mOMEsS z!i%x@Aiy<&Dz(WHGBgtPI=(RJ7VA)q=drDMzlQgrc>?5lq1*N_uJ+7tvZ%5SL}BMp zt7|u2Jbn|Eww}cAf|L`86MiVAsrBcJ#yO@b7E888mKOP8%`!keS@MgBS=AoXN9 zsdZ>&TsL0A=PO3SMAcS$r$iN}-mn9$T_Nx(J(-(-XBzW*aTp#6Hz2L!!*Gs4H)k{Y z6ZyJ-BZ}8QWR~@Jnw!`I4B0tpm~SG%4i>GY+B$sLY`8h!5h3hf6?=-F!orXJ_ zmmsFXpO{NMf={Wzkeq9b_QHJ5BqfDgU>A(BV`G?=ogr9m9SEv6xsjdceHK(RiRANA=K&^0iSlQ z!yaM+W4zkPNQG?DT{9J*I4EQEya@W%VG4TJ1;fWG0UoffBI)fy(pepkVYUgV@iGH- zV}Lw$9}d9}H6UeR96ow;op+&YLxGMf=)|sq+52>e3O|<*xLJ=rr$1qDY$+pe(nYj$ zmFSc?w+XeoL8}F3uw(B8#`A6~S39T)QGQayeEwdp%&i7HcvhWNu^IOE=U}V;D$ewX zI=<=9KsA0g;g!YDrd;yKtKb#XWbG}yIkpXS{pH!7wi8T;@i|B^NGButnW8>Fk2ciz zAa2`Ofx{MtYO?KGZFc!_X6r)3Lw;=5MM1x zhsEaiF(6|D{<##1)yHG0;6@j7MScco%7y@*bp)xyXVJ{eNHpW1JYATw5#+OT;f$IQ zc{lMp)la!V|11c{ikJ7u@vYZjWSJQ8j2KQ%>n3At-$ha$HCAxTV>5j8QDqNSPG@6# zLvc*rOFGp#m4eDEdb3LkUN^lb(k>Hli`7BFrO%J4_v;C$GSE&o@EN|~-Y!OO&qcg( zfd79zNd^^F>rl>RCnlDB;qcf1sTI5j=j^qR^RNV8rdB}J-(2qYS5v(GVH7BCJ1KaR zI|F)RQqcYT18#q$E%V)18pDGNse{}H;=d&rD&|jv(OHC5?cNGku3V*K)ncG~{V{lB z6AhWypVBWwzqxBE&xzu20j#lX#kxsT;gPu^BX@c?DXh5-=}yy_amV=mSXc?B_V6A0 z{z~TY+%i}kn}#lpnRtGpEUq7J%3WNl1)2YpVdk$Jc)H#Yk4;R5Nz0zl@;U#=wN20I zD$92yd8sUxTyVmA*&vhOlWQ()WLf`7gVfB54nD#i%iYn{kI7Gb#NRC zM(n3cjs_F;7A@Qz*~tuQokaJ2>a?65gTkAs#7}7oH}pwd^zqtB?tADNa@M&IJ{Voc zaZe;+i>Q`*H@VX(v;26E$Pf*UiDdl$T%yy$^U=?78N{7Q!sXmeSc;6m*+$t zDOKUGF(zEw&x`2!ONDv=u!`C=iL+N!EvcED8hKhCj(3%VsKKT@umAyxO&JUG--a+x zUL1ghGk?>E>)#M5;X%?{|5zA%?hWqr3WW3-)pW;QEtql18WjbvAv|!p$RR%;mNfTL zF1cv%nF-EN2D}%p3x>gzIv#sThqsu6@-=Iss>HjDj%l)om&B4$e~odsOS|y$bQ^N+ z7vJkj@S}o^&D3qq8}9C7p0gx6OVx^k;M>PQaw# zc2gMt!GjE?SCNA`8L+%10*==P;OrYyF)E{*&P`UM*PPYxb?|g}zWg+Xnn&||l0z6M z702Zf3p|r54zFS^Led_-J8;I6Mz!XHf$bukyX`u)=#qp&zwa$TwE-W0MrUFmUY- zYJ@@X`t4leFwX)ext2g!YB#=q*eZOT8wYu7{*rem)OoMw7m{q14O7d^al^D}xGG}` zvu1=9HjleRG+;Wt_3SI$>uG~YE3biq@d~Whpd^IfTTYpFkRBQc184OLBAjlH-Fx^{ z`ZzsN&w4Y^IT?t`wg#g3GiRWrIvTVtuE+N0*XR{_FAUXG!qwL&L$Zk`R;${P2oyta zZ*kEQxqW14jv~2mDV59(I8J?~%W;;#gLfac(EfFRrNvt4^wFq6U~uf_<(ngRfi_xf#5Fk#cV%yn#C8q7upjI7cn{*I1bD| zPr+B^HzSPdhRe+xVdkAZwj zA2ZvE!#A40sE(E_w77`j{n8wCF^i)!Lm2)u{TRqBUk=ZCMxJo`1N0uRA!<31hccf{ zP*&EeVJAyd(JTTP8_b6wf%ztFU+X1>sI}KBF&V2ivT8 zH}CX0BBxie+$?WRG-nvDrA6&+hYMziVE*`&UCBfU|*=QQj1bV{zWa?!~-hES{ zEerE$^wm8Wu{s=nv)_m>J4*B-%mcN*A4SJ)Vc0a)g7`^Kp?*Cxc;{gVQ|Bdx1(~CX zAMd@o=`sYl^9kM=_kaoCcpKZ7cw+7641Ap%kADwjk+xnpW)8oT>J8->)wzoyCc+pM zw=Jhl(WTr&_q8zXYBrgC=L*SLdIF>TLg~0>DZ0n4llNL|wF$-@E<13g@mJFGS`VW_Euc7EiXDnI!0SsKX=Y6r zJYj~I(kQ;;BvA^FhCHFZc{fcnNydy1K=< z@SHDkwaS7tw?k;^$RYA^NwWKW3ZR^_sG8%GM>Zs!nyt!cpjMxu?k{nTl$J@|4>XEwUpRf zwNlXerH9^;OQ4&=&O>Y2Lzp;<{|=fu5xOhVA>r5}SUTfAG1T$Lj61nt?UO)L_{W`^ zVgO?wnB#AeJ?^_{36)doh|i&Xk~O4<8hy}8d~M~P#S zHX9=?Lm~z{iO=j-P+vU_lPiwE#H%A{ad`)>elUnHGL`ZDA8XOYdtaG=&zAUlferLZ zw9}^dtH|uKb)5R^waC=1f?e;YF!5WmAgW0Pi;myGqDn$POdJR9k^K1`@4`91U(If0m2G7i}fRxMDqdC0C9Hvg)K%vxn|fnnG4IyTg-;vEa5h z6F1)342NCT;k3;hM3L3_%}@chdKADz3uDnH|1bE)R2uGyh6x>9D+C&BDV`ONf`m(A zOgs_IJI}Xht6V`jpn#LFI%b6rb;%zwpX9tGa>?O&ElgRg-2XR)Y0In`nhO1d8(8REvEON^s z7mnJY3O&S)SvG`j;=_=)2*SWHA2{kg0UkV<0d@RqU*YhCG)Lr;Syv};kCq41j+>^q z*kug<>xe|3g@g=Op9g^(vbl|Qd%)(c0jz4X1`*F|5BXZmSi~EmUG_Ct)TaTu1L*)k z4aEKODIBvs2_pkTLDW$NPCLX!Gdd;68JYd?r11uguHJ%z#UD8}iCC;I+d-c0OQ+RG zfnc?+nsR|_sYoP{0hH1Msh4mSPdkM^_>!(S0_h^(NJ#SfSlhkZ$6 zX9)N)?j-X2dtpw+a0-^MC^P5-cBk{PZw*T?-d3bmJ{zI*pfX95oedFh4ag0V9Ffe3 z!j-w_h+nY`#(O@dA4kT}xl_lB^h?geh*6CwC+h_7(j_5l?-R!MaRDS4M`F0=Q^t0? z12z`+6SD#ZaF&^aU4fnu7`=`;b-$I!Y>0;bJ*^y;#e=3NQqp}9PwvUV9|LXl#?yI3 z@rNc3Y19!f<#fiq)dfQKn_}Xh9EdMpk0!ni(2rTfU)@_!t3L+ml{p|2dW0N7Q_TAI zjjC*@qM7!;sb_a2?ey6}{$5bWxo=LOkM2&)QCdSQe`UbX^D1Dv!|{!FAO0-+#D#5_ z5JiQEgS)jhJn<%E;&H%JmuFH(C*ET$dj}$G8bRh=ItZscC%tiU*!MaNkM_Az#d?A< z4zm1N7Mn=i5wn z_AvI++le5%=rS!oHyMacJg2cC4N*59gzqnLNfn=PeZdrRYnT97H6ylN`xJE|+Xj8WWu8BXJGs(Od_LUHp5+`UtT@UNQpboyca!YKmZmtjzL;wlroYY`qd z?O>RiG3>r+m2fcfLB(YQNsN@{5pP7wEttcnHpD~L#_?kjQaV|K$ zJ_^??i)qG^2C7rf=Pnj}pnfkMP;zxV5sN)QwNLd4BrcVbAQc59XC4qeeE~K^A0r-2 z7!K98;_`K!Fs6#nJ||Acn|l(dMN1by_fdc!ni9A{dnAn2i=m^8*I@=uf~Vi-LKIHH z0+|%dZ5)P6>KY&g#;{K#n$dI57IbNHC9YAjqD)IwzI*bF3i9=6bb2o~a2C{hdjJmr z&LlQ`{zLE3JYp2NlCr}t(PK-MM9Uu*68(`=FgQkxEcvZTB1c$~FZEAwU`8>~N?L`N z+{%gf^hKEYUIZ&WTd?QrUJ$fcgGtQ@v~Wl!uT=tw*4a8S;pNI3E;t*JO zUTSdRDYG(!k_-)o6iH;<*ST+$3=O0a zDH0)t5~abEsbnfCWQdZaP=xzBw`NJ9IcbujG^art-u-;n?~muNcRk zct9-eou^30%)d<)7dhdpjA^i2Ki!s5Hx*e zkzBt_)Vpf}x#16>jh|Jl?>SE#WBf?im5(&sG6(*&P7-pynQ-4q00B}~%#-vDaIVRS zo7cUI@s?MIuHbp(UFa#065fQ*YHuK6wHKMwXABt)VNItTdv65$Wd76cM}sA48!{0y~3a0W)kgR&3JyK0eaQt3$+zqlbN3i z$@{bW$%u$y+;`qfx<=KlaZ=|nu-{?>sx2SsRPB5^OJ^AO?ym^gxz8a!rhOpD6~!qd z7E_63nwaGOjD(3uaI|kRc6{POfTt+@glbZ|X@*^#N$x+lrbL>Fj_bbom1pcs= zK5WtaKm)9m-HIY<=HT~b6!B@TgR7SvQDFX<#MH-m zcAz=B2)tMA!t1eyM7nShooO-~t|p!VS+{bW_!O}0!Do8s(rdCwCyKu2*(rTA4E(NM zqi+<-uo_IE1Vh~1@sEQl zJZ^Siye1rmUx$-XXT>h~(Rc`YRm?GA$~$s2YYz1O*+L4pslaS{p09Hlu=%hVGskcOP({F#{zujpa83+HQ56h{2}GdeAqg!9fFfqlArwdmz7zLSEYZD zv&)_}DoooW)I1dmhZW;!*H21r-08xpg{sh1vlZTtyNF^9_dv;}l)Rj@2?x8EV)T|7 zv}Omzp7-Kt)E-a!e))s)ItjFUt%JAYB(QnR9aQNGBC#V(N%PP-ythP$ec?I_-i%y{ zHi{2PMlH{1*egqn+oa(}7T-7Y7zv_ttI5s_JclGBKp17Xi3a?sCC&aRz-3qC_~)sx zmFKkET-pVp*XyzE@)+DB9>%{*&!F$bPt2DfV`jte3{2$A=+vkA==^vqz0ZXZ6%_}l z{r#B^o*qM9T+%?xbZhcl^(4+MQ-ifibr`hgKZ!X<>MW5LfLi7ZxrN0NK0@xZQXvf<4QVaUrhR6ML0 zl5hKvLQ;E^qo470tFR}>MP+n z)aIDoc?D+dKF-J*{UQ_6TIie{OJaNc2>#V=BfHZcSs(k|2#ilL@GdI4->H7YVf!g4e%Awb`d@GbYl^p$ zJ&`8Ap<^6pl7(k>fx3J%lqlRI1Byq;c!Qb5IieEWV#KlK(Gu8DGoO~L9f70a;+(3! z2fox(2K9^&v~8{llq+?RqcwaV^xX*_uRI z0BenIp`Fn;`de`hiuX+g;i6i66(zu_-#73aa&0Vn5W@rL<8iI{W-MRGXQ~#QVY=Jo z;MKy9RBF^@{`s>fd0|cvJHdzq)ir?A!yfWGS%AeZnfS>?gd0&MfTE@0XnQ&j3%Z@~ zbZQxfX7cxj8o}xfi%3%JQOY)-WVHR|H;K;@+)#|=Eib_It0d07 zGL2_$U&NO`BJs+GGT!_9g6QjQB75eQfTaITa(CZ5y7$k)2JgBKoGH|Txu5o;Rn<=% z9C=Mh?+1aTX*R5!H;=wkFMw|!?a5K|#mt)BF=+Ndg|3Rr!x@SR@aXDhPzelyg!OLV zG42j|W|<1DYJbV(Z>?BHYuk>9muYivO*C(SqmG{f9rF;Sk1J4)FTGXgfBJ zUBu42oy5wGTFbue*vgjFIrlcj;|fLH<>+&7n9;^ND;uW@1( z)IC}8fCx50_7JP!yMdit8NnXju#2s6cVLYd#IOMmHn3HytJ&-W{;Wn#AR7>Rgx%w` zo^9~o#<~WvY{QEfcC=vvJK-P#+J>y+$W2_hJw^W5~TwXEtGFjK?tJ@#ae{wOHAex59p2&F9} z3{YogBTUtdrrudbr21z*9qLIG4hud+UmUo|!wRKgzDbX;YhHI_`n)2TwPyh+d<`K# zFH6yyA!*!s(*uv1L_yz=5j1ezX=a&rHl5qdvzJbv5`JdClceB5My82pX(oQ4abn|y zU*d|<(^`zY?wJn-RSQu}Lku&NE|JY+&q8l{3tbj}%*KtrUBq+EIqd5H z&J9>-&+n*0Y=;;)0Bi|#Ll3)NC?a`dW%1y9okrDf5r3{RjID<^6uw^4} zB;mR5x$HiN1TM{|oSU7(;i=;(T>gZ3Rz|dgWe@D*bYA;&!G4Rl;CaK?l1o9XeSi&D z&?U;Pxh#NV%Y(RErg7{PK?*y8uH!OZ=5jaY`*Cri<*-m!jxB82#hK2?Asb8E2L_hcjM)fb8yrG6yVL5fpXp2FTcIhy+qKhdzsX2QQ-Kc4INzwkrfz3>$* zcu>M_`S4xfk(MG@e*GyZiI@sXF50s}w+C2JpH9K%XAcC0pYF2hmvaSf5gP?+f8Vn1 zM@0qELDGU3enjvqQ&R9OYLOtq)?47=u$Y~be2pDZd{yu<&Ok7);Uimm=73;|{Ru%G zs~{-9_eF4j^fh)}vZcV>*H^$>g$1QrP6B_AIDw&@s-WeRu}$zO8$oZ^SwY&F?ScT) zQGzi_SglgBM@v4=}4IcjK3fUU>X$JfE38hPxLyL>~OP1Gk4s z^Lu`mQ2&b@cl7&Z`ZuH*@{TWs3ob_NG@D^u*u)~?S+mH7Fb1} zfLq;0aA3tU4EU?aO}zh(&oX_CnlRIgOjX7j|?pWxGnuO{;N!+<_{zBn{ zDEPc@6e`aN#H{gKg#97`)Vi!2;}?v?+du2k%;h4UTg_)0olPX0ts}Tf=S(6mqmF%I z&fvKD4ZeH%2F7~4gIoEdxvHgv^A_JqeV%>A`E3zo{=hFt9oNJxNtDNi(n*-Jdp1ry z=gpHBcZ1QM4584q9}|NU;n3u<=m0Lfe$oTjX^ZKT;8^zQl+{Ac?lKHj`T-3#Wiw1a z!=jAj#`P~oVU~#*Rwz{p)xTT>n{~3>la+ehg62x_e(%5uo^8dpYsbK^;2jM}I!5?PRjzNVc`xhCIKQ3I4a#Scb`Il*s>$zJJ3wxuNA)v(1`opR5F_-zKuMJGS9W zK4WWC?hqNbkrOTzsNlvAN6~II2TR4IQ0>fQu4=OyS5WXk$Sw~i6K+1EZ{G8ng->Nz z^P!WtK*f?eb!YRGD-Lbl50fS8wIuw)Qf46e9Q5>zCJ%ae{+G;2oUWKjHouqVDqIuD zuelab_B4R=5S&9#@q74w-z*GVG?y-!AIfdn9K|`*7enTltEoTL7oTk7|n}3!>pIL_W7Z0%gpIzuD)FW?{oB6d^Z+gT%cTU=1`gm*rYO38Rv^Kr{qU4b1mwS-%%m<91>I~(w*7TK zE>HBr<$l$0w|*yn8xz%Voo7mokagiaRTp!OoU1VZ>KK0BAB zZi}!Edn~GP%U%5iH;_6WV7{UXz2X5&vrmYuyM6XjpdAxhmtjbZ82kQg5Vz86Ka3WWAveDNM$sNi(zWv(kvr)^ zGI+l%GjTZky>S6P$^QbM3)R@`6{ESIT4M=4!84%8<}xGK`M|pAD%?$#7BF~umPEc; zieqbd#y&&&S>Q^x&t()oj`OD$ykF*>yF77R;{ofJpT<8^9XPXJO0aqKdfHbW%R0DF zp3`#z;@HnT&u2YnwdN}Qt9&0nzLCcX&2!18riI+fzyNg0_Tmz&9|{{X7veddCHt!N zI@qcV=X6WH;O&FkK)*5w%;a7Q#X?s?)BR+cJpVkL46)-@+_}f+>aOKvLT}T>s|9GR z?gVm53XnLM026ygVSDr2#yeHtFs0-u{-AR)G|~WCB2Nn!j#m=OL>9nx5lOE4%5?U5 zcqe+h*R#H}YQQv3iLH2@1p`A4;M>0pA`koo!IwZT)_M(COmt#LNl0+=if{k<*5cMQN(*e z-F%szL3LnP&!yH;wv9G!*GOICdblF53C`~p;z3?d=Kk$3>ePr+O)&u`AO8+|a#P^= zUjtriz6+>C0lN7_!ezzjKA}(GKmOIRa;rE-FpH{C>x?>u|%a)K?H@aZZ zI1U5IbawdZpRm+x4PFk~jc=|u^8>D0JZR|y2JO|*9`A=?El0?N{sF39J{7`0*3cQZ z%yHu2dai%_2TU5ig2a5h#Or2`gUotf4V9n-=zJ14tj$Fo4OhO8Jp~p~SDbSv9~Mf5 zq8k+o&#l-@o$qj{TDk(#=J|uc-d^0Cc~rQiBb#nFo(k&IOEK@}ZN4Y&f?b-~WI%2N z3Z521#Z^--ZfUyn}7aX!iWcmeUi0-j?Ufv#)M;vUIU z__b#ic6#iAOAk$9neJG&XpbtZ);fVzC-eDxD4r9)Wees_CNxK~4KrIl3j2;OgPHG+ z!1**i?)FAeaM3zRx)u45z)K2TrRP<~=p?)}IH3S>8 zVxahDC|0Wp;K+pMsCVQUwUT4Gkyq5XyBllh0V`>4A)gPH7^r|z)@#xJ%M4sTQJ3?X zX9K1(TVZIO8AOjx!{`a_R6BG~s5)L0`!tg+&r-`WY+q%^VG=^m8$ z0{uPpJ6X4D4K-S=1Wr>#xY%lCR{E(9^UY3|eVAQ{>&ASCt_E+E7;Oj&g(v8Jy%^@S zVkiuIKNq|I>W~533m`Q&0bfbJ66Q^qF8ubRnsiRn;~s?kMP|h~Zdu$#T=KFAHyWFP zafvrEnv)7@qOWj)wh80#E(s@hi~w){bMV`&8w}ss;Hj4)XtHe~4j#J#ww3CfeRm6$ z+WiElR6mDvbGy;_oHV;I)SexCcr#SSIm4UJli4swb@;h01ltlTab;y4oIj8Q7B&a5 zdA>h5=r}-HQ76ur8UbSt2;h*k1#U?ZC0BM-kj(H+u-9Cgb)2n52A(_f%&-L9=TJqj zhkk&z0b}Alpv2_}$6>|sad1m8f%{=(&tW(@r%MWIJhmI zjapQWzu_kd5e`G?;CEOtV;kA>>}HX9ptuypO80{`CB% zL(F#lw~S%QC2Q@MWy}|w{lv&p@*iK`g{Y;$79t`d|M~pi{;%ABWRKd#9HNSEUQ!x!+>Ac`Db_0l@I zypOWyM}vmA9ZVS`3F@tCP~BaG2CN>rt|$fvD$Hnh%q-jzpMXBB6ubZ6G{kdJ5G6jE zgs&=Rwr z`i`DwxJLC;Kz6nBW7WQ7V7P2g9u1m4NJNdI(ChTdWBAiwVzOwxHo zE-br-25w2@NHYqp7x6jP&H32q_m+-1d4$YwItz*XxjwJghh`U5&>*SfbVSK*Sao?G z<6in0+x=D8F9|tt{6I2(J*W>YpKIWd_c8GD+J?g)u_$_?iss)gqM0R`#BE0!#6C~M z@k_qoXnuC%HK&$5R?Z?<){kUF@1@hoo@nA&)JB}o+Y24*Qt^55b7Ef>FHGCO=bX;Y zv2OTb0GnpY&|Ky&jn}b3pM(hPwur~VSvD>|{O-6bT>Q(F7T#!+16|iEO!kft+>y zOB$m;VoszEy}hoO9Dfl6Vf?w`mueer$hNS)p0I@pk{75P@5ZGq{D>FhF0(yQA@`(i{Wz1UBc%nRj^K^ktq6%g?I0cp#RhWdJ!=%7ssuYAykK~!GW*a;4mkHhT2h>Y%m>$DW8T{4-Q+$ zWo8Q}`^b=FrQ!ViC>f?4O>5LSHUop?N-%WuBmA>sHJ(2-9MAqXAY${)>8P6d@VTIr zt~sj!>TV<1&4<$9!q!Z*3rm4dwNh+VzB9AflYv zGk?rOsa{WT%%6xqdlpayoikL<>Ne?DTa0V8tkJA`JM4B>0avx>M1PtEEO}6i@>Cgu zx5_kXPV*#$oJk(xm#O&Q6)Kx33lIR{sUEa6^24E`8maQ-wE3~^nLcNeGNx4KqxM@JOB z)q(Ne#p@OiN7G>)=6b2P~B zc`K>awfofLge%=VVm9i!9m1>T{lciVme|Ul)4E1@kxXe3`e7i0{LXbH@!MY$w{BZz zrL7k|ou7%SPeyU2Dk|8Yu$|nGj04SAj_@Ms25B)^$oo4Bv48(P=FR7G)K9RMsMw~F zYOnLw33FHC`jm3({=H!s+sS89gs9-Uu6y*Be>QENX$F6)_Q1Xq!*STTIV7@<&)8VA z2DzKL^!;a5{3qdoOH4)4n>viQ}jW2kwE${Jr(@S7Unlk@fR>8pt zZE%+OOTWr8=r5H49`2f`=(Z7}C+P@_nx?^oS@EPXs)z~(p9sIc31{w_>|&lj)q!IX zuW4M&7;6Z^;rZWzoe4K zyLD)V*LqmCW{|m48ZZ3ra}?%i8<6d7-gr3a5PneCp?N+A)V%c?Yp;S9{Rmg5xPtKd_eDx8wALpZp24cyAkWQML9fVGzrDe_gNS7)VQ z_|=Ex``@kLcJ~r&JgASl#fJEF-Zk7Vy@@>9la8$yCqiIHIf#t-3Z*lX$s~&~uzNcT zPJEI@nK~VAM%zM&xH$<9_Vf3%O9GuACz3{oR5}Yrdiz#D@VeZPQxKwKr?vlO$@5T)@c$r=! zkNt8{DqIS8!o`GfYzA#tzKvCHPr{WIdFU|w61HWeKzjBuTCmoi z_`O%BTRTsXns0o)>5@;QTT5Z;r{}^S53O*Ze>qK19|=k8X5yjYbFki8Pq@!%8I7*# zfo~e!!ap8sz(=PMX0(Yx&667XLG?5#Fx6;yIj#isnrDFWBoWAYsRp8|TB+`iPsG^-ZCo2WV{bJ>TB^e16*nJGMdy#OL_Pop!XZ_-YW&oH%|C7PMH z8r1Juz+>f1GR$Nvx-bVD{;WztqpBFm8Z2_L+*%VfZn$znljpANJ5Ca2mVo3h?((H(A!}iCr@eVa%tuu>Jq%#JeDnZl}S=R9iWx^rew!bWjyzK zBUJP%u%9)&phB+Hs&r}-`QWMmsq8b-*WOF6_1fU|1%1MZ89nr_?LGRt&jk!z^uWFS zHJ&|8QBr;dQ4oD%Rl39-mkFn1ed=^7mYYu#)=#!x5#a|xuLeogRZCK5vyEKU+9ZA<9n$+r6WS$cAT3)pfRUk?(wnKY3ATa8Vv~E$7osvqqEQKNMKo8>_J4 z-bcE~|1(u4nY8DtKJKIgq-exzKBMI@KHe~un3%@$T&P+;*Ly$HV*HG3*|HAy>`#H) z(HBU<>hrMS(Ms$4Vl&9fMiFA^%YlsBE5vsfsm3)VmwAoj=pj|%<+2o9<1z$Bo0p>0 z6BlG7BmSvFR-CbX_OI(7o^SD=`S+d+x)9kY-mr6yGpt>Bot!ngMQ{9S6z5Wv@6PB6^Q8}7Bt zgpKS?=FHs&^7ejknTrcr*<>4oi~ozX#~4J*#N>onmGTktaIO_zd%3;-qo9 z5hK=n9(HIO(r0NXPG?|EUkJk6N(c-_Fl0|Hu5kb*&Dl`MHA5KV*w@ zvrCC-wKA;tzf6YC<VtW+8kX$1Vtv9yAAT)L#o*A5_$5Td$~@&G{gzvfLv8D+ z*`7CKt+EuH+K~(;>obHOgxO@ciYq;yy^ZGB6wt3v=3?LSQ_S7@96V2118d*QLZs?C z>mKm|t5ezL!tbp)w1JqR>&ARCHh&dN-Mtxp)l9}q!m%{!-V5tcw;*h37|xUrSy7Rv zlhH8ZK6ToXPg~6;&}l_1mTo;yZ|~s!E>}zGsV#0;AQ>)9nD>zirftK0;oFISwgMLU z@%vA!1!WGdrzMpHua7dPcp?t%cU+>5Ck#Ps?hE>2swR9_Dk1e38>sb=1~q#uLJxxOgjmyH!F3ZCN;3;X8HFoP|Y?WvCB`gUHn+=I*`A zbR)m7zd!1QV!P`weYP^nZ8F01k9!+KlUCAJ-aFxyG#9@J3}9Bk6s(|{Fy`ugrd(GB z$})yS=;2tRR%{P%b03fZuAB6?*#S+GqWxq$bv4o=VlQ?vw#Y%SSS(0w-bY2xXyL5& zO_aG7L^nr`M9ba7>DVXo@P7MmGB92g%)Y4MCyQW=QO%&X`n5E8v@5D69;1F13RtD2 zN7gwjV$_2s;b})Z+@WrXGc}ennl*VeMdmJbD-`E7>7IE1Q7{hc@x&K=M*ZZ=r|{PD zH0*b&p~B}Z_6Cij$$RDTz>aj`i*^OND04MYU*(It8fCz;=@iql(iYzCb0HU+#6YW1 z+S+lP2(BCNh^L+fV<3uROX4LOE1HQ@OG5D|6N#(XR9y3+$690k7iP@yVsc`^Ug7&w ziNf~>9IeX($3WJ=I0(-20^e0a>fdvp8ZXX4b@^TNRbei*xigoB^ev(v!GhU7Ac@sm zl(FPSGamn4hSp^piT{Wp8Zx|@37sqg;bCcX*JX3cBiPVpi6W=umrO5?UPQm^iD7#! z?~@OqL}+7+8!i)cPFhUF4rpNQt_c_&Ih_s`+o2$8D*mx5roB_kgf|5)JRf-{<9#j# zJ2MvGnBG=$y)FqfWn9R)d6&pL0~CfUj)kY>FmX0e1LeEsaBj{$(rxmF`1uZzkE8mi zwy==wo8Lh6D-N`-BRS!zJ*}D-~cE^@wo_wM#MhU8k&j5(*U zHBW_P#rwqP$Tj-m%MlVW?*M%6>!igY<{;bN#K`(dLQ~3pvS3ROal0~|uXBzOxr?Uo z=i($-SYZR%a_>l{{!9#+@SWKd{h8=re?@jrpJkQ9`^99WGD+Wcp6ep`OOCgQLgSk% zA}4AFiQkVZRov9VZT_(w-8z>&r0r##369Gy!|=d7(1uzn(AvrA+d_Y_u9al(;h-)G^8R$Qbhfj z2iW|H2dfi%A*SRDwXHQm6%(Gz@iZB?J-o-H-Z_QNFAGSjM1{~YOPMr#Ry918n+<6T z1h~>z9~vx;nL7KC5a(UY#C%93OT$!{+CmAC71<7dhVKA5KBMMI@FMblnFCzen{Pet zfg#T7a$?GD#KNWZ`y|Pk(eGB+Zv`t6pv(<6nbz?N2c`%;D_^zij z7tO$f!{y-AS5^Gv{)NugJ3^MbrQvf=S4=T6hHc}GseSAeYzy3haT|~0v#W<_V(ed9 z1e8iT4a4PA`pIyehtzgM0t5~2Cfw9i($sl}h`B^Fvq=Rl*ml&azSe-BLpWlE70?|r z6~c9#J+V!ANLts9gtr3&)C3=tTXCLa%vh;2+IrGT1Hnr@wrIuce+z^87#k z^MC8}{x|>6@_)>~Ef|PqKec(WMIn1wJ1&v^rtQZbiwI{M0?gQTPTSd0xk+qyWGq|l zzK)GLyNfk04P!GsvRMz=6xKs0f<3n&mR&Y2k*zk}#d`RrvUE)-duz`THdg8od&2ev zn-!kGZc07L-V@owo_J`<9$J>gCf<%`mrJi>Yu6{Tx<`}QYk@KBVCf$A;j=(C-6e?K z+P9M(W9Q9=7p!IXdF^Bs%lES$ulBIA5}9mfpaW|&ZZ&IVwV2JK#jM?;cs5sL8#|>m zp8c*H%^ufCV4Iaf*sA^e*!I%cfAojqUvKaG*XOVQQGX~NC`#=$e_6R{{ea(#i?Q|T zC*j?u96F<-nT`{4C&s$@bOoQmAvy4v+^f!p6}vysf@_z^5AzAU&)*F-4rBv8y%$cb z@rRz2CD44MjFIu14!dGz$j6!B!u%4}8uP#~b%af>70mTDr-;GP z4!ZtzEp&P)f%}{mC|=3;*w?0mx&9vhIowMla-CqXa^gSdSH~&2BmVXJ{g3*?n~H7p zM4dQT9@&l(^ZAT+w>|hR@fq>|`jWi4*TlRPY{3ARv6xktMorvT;-SwY@MB9LTECQp zX|3BJV&_}onDdL!z)*~9+j@<@xR}C>@85;rC&pRVtDVQ>dR1J-9mFR~q|rv{8Tnk= zMIA-n!oj!xpi#b>DLt%#zD|mWNyNFcaQS8i9XD0=C z!wu_8)U{6;mMD&*BKEq%XZbvj?fNvlJF=cB-Z+A}d3Ox?`_dJf+6U-oS3Po5>*+uF z&GlE_sQl~o`ycg(Z`Vx%y$7Sn%>YT#om@;#4*n%y-Oj+}#6UQ{`w^oTl*?>*q{m!X zasoa_RTI@IiHwvNLfuzmrsLLrRusjEE?+C&5T6gmwvCKl*9DRkq5+bMHcW&2T{808 zW^#8<33;}CAGxKphg3{TWJW2O!{!bV68GjK{7OFtdc%6H$64-Ybg{&1uS`LB7J@pN8*X!&0QHTQq_Go058 zzQQGt%&oz(d~ZYgy*3wXv`&b>5NN$0Gq!<6Ai&v`f@ z;A^`#b+90PEr^uqk;UP*@OoP@juBr7M(^zK+Sz(a^v=U_eM2Y%zLtHRgKI?@vU^Jz zST9K@eOa@yX_YS1FFqTyeG5RXJqK(ZG9iC+B#}-lf~Uc;D99AjikWis+vOeT8DIg1 z+YFhQ**no;&sl1vkt|f|6Q^0-j@Alt`mpzsGLBj52_w%>hP;}$%qYbe5N~!w_dh3v zE4pTp*=F;EJF*mTQub&1-Aq77gcZT4mIuP&KPQve;D!7%tb*`65YKt%!inM>GPJUa zKKk|*q}7yBWLm0FaBdY$GCT*B>M5{EBnraMxI@gsqh#_8mTmj;1R8j+@CD&(!bS1D zx=s`9TVF_8d{^^xAsgb=bP#;fo9OB4P%<@$_jp9OQj=s+_){?gG&Ucn%2(&md8$>E z_l%L9JM$1`xZ$qu_hewdCj6Nn1RM6BqRT#YP;Y#LN;iCQFlRjt>GlNA8($%5bcLm( zn+l9t&`TX(ycBL%m7!U^$;^7wXljlT0pA@i#BgpY??oxY#MMv9rek{4=XGBf zY-fUPgF2i4fWyHJ*N94cClUXA4(elENZjRYa9(DDZK20#@AnE4{%r%gD=vdoj+5|% z&V3yH`j60ipq7ShS_MkcI`}mG0t&j~LHX$@h&N55wf=5U*H;f+OBcdS%gcE1kUjWa z7)A38ZE^L2qx7(;0=P-n(0Gk7cy?G8p9~+1(S@2g+hP-(?O6)E)f@*bPr#=aeL|T= zXOdoFh5Gz#)2*Wt@W#TYv>kcYc@eA3< zMtIyzgj;5zie!rgGil~X`q7Ruc_y(SF8vqsH$~u)>`*wFCkbEfH1HW8>EIh0XKnE2 z2{Dqfpb>5!WMQTlhMg%V_B&(goZVM&rmT=LQPX0Zx1qJJ;$r%!j#9FjXJ;RIh~Hj~ zgp%%BXdmfLH3wf|viAC!^D+>is)4WhYh}a#4R@j#w(veMfsY6NW~|Ah z?h|~^K#wHaNz(Q_YZSDerEgR^$f$kU=(6!SG1|_eyoWm(opc6Tb2q@p#gz@ERrQvR z$-3O)PAj%pSrRg$)1WGF92c>;tf6>}pD_Dc4f^@UVE>bFlK5jO79R-1l)PrzSrr7? zV=hsJuR6phO_PYVID)&0IQN3*U3DreF&U*}slEb(Z6|8*q((HVRt{rdwAD}%)e6wg zMqz(o0$%5t8#8aY(es%N5W9XYTnlQVHik+#XeWYalH|eGm1n1K+e?fz%)mNrKIoQ; za#9hsFmH}IY}{Q9Ff)T5AAX(Yt&E58-F|Rh=NZv`8VlQ_p6|rf{L;0c1N2@cGym zVV!yyEIG4@UxOxGc_jpthwFjo^SLBVa|bPWaslV2-XpsVvuK}j2Mw(m$tmik&`oDdk-+gUTN^ga^(M0`W#E`z6?`Au zLgI`c(HGm(X_53iQm{}9Y)@^02A;bWuCa@e70;xL&3-XTZR23QJ_|$lYl&>yM2s!l z2s(4t!K0nA;MdqhA{LE?uw`G#hHnpu@`DDN)anS5s-57ZmMGk6|C8LA&u2#2A7cie z`;jA7DtvwF(Kz*;1sN;sXSgx4U|=J~E+3@>%B8z-$HjoKKPU|56%YgURv(YGJy$MDD4dovxvx~9NG{WOs9 zRHY-t1>>sU=TKsH7@ah;pU=TP2)|$5fLPD3=j6jT<{1g-;|Gxw9Ku`1MLniLf7dk^~j4Dpx3 zeC!UJPuzcQgI||Z(f5fcMkpkqUSJ7n+gpx({RyC4WK5){SEBj)W7Na#0QQQkVbU~O z&?#XwI&ZLXi4IJB-4>Hom2^xA^G@V*e{UVR!zzpQ(-EbM14~>Q~R`f%zRXc zzch5YRb8h^$)of;Oc!Sy@& z`M`WpD4a~`u@7QgzVAXy@x_OISk=VQ^pQ(3Jfawi?403#O$?}O%EIGU8F){-jaJ93Mft80Vmv&M zs;m{|I`s=_VU`DYXpN;y&DTQSEiGotfihh3{x)r2umL7}jKLg52blI;3*{d#gDbNp zFbV;O8ME!#m{k8!xa3AGoY-}jn5f(*!<GR&o|e5L3*8SulnIdM6ZX?Vu)|A|K`_VZ1*A8tusT`NjOU#Ud^>!bMQ3O}E>?U; zw-GOCX?yv#61w)_5rW)xm9DM$K#U@A>5ra6|AdOIDHur zn8kCRZ2r!{Bn7~o5%(BJCp%nxM~xo%ri){lVAwrVOQ@^vgMYKEA$zq5XL2eDwz}tn z-6sM3T;PW*6W`GLCe!H}`S-YB#d&)0)fysU{|8gTGVtcy&vZQB<2hoy5L-&8f}cYk zS(lSR_J5FN0y{53kv*@ys?Ws8SYmdH zN6qoi-`6yh{1_Nk+ky29tQJu>B{H?bbM{d=bSf@-qU}X{>ueC7sMW~ z3H-4=xBzPGzu@be%G8U`bO|q!hP>C6jYs7~;O~SZRKF>QnBRFyPxu?53-1AYG2s|h zYO2BVfdrIExkaz2$Ii9D-z#5WXYEl~zWI>#*3dkB z%zYrICG|lE(lN_nB+7nz1UV~YVS|?^K4%jH@;*N%%qEeK$ur#|FZ^oe#tM#Br0f7*wlf!TRI;o-LaIN7aL2 z&G9&-2H_;_&R!fxcYyd8Nh)*v2<9G6u&(NK1x>eXqT`Du(`g+ek0H+Q73^Zo%Wn!{FuTopAZqSh6Ja5c9yb z7A}ss3lig(;{PG-&7-k;!~b7oDiku8M5#2$&>+vguWc%o3`rWKWN1)IBO1-~Jc}e_ z2_Zw+_w^`Br4nh5lm?|wX-(sHrYog*{($T&GQB#NsIOdw;;rdKb#X8BZ{nHVXFh?;W-&T{J|%H6lCbN? zLyS7~0S?|<0;^*F(c_{D)Z{@msoxcaMv^JSa$Pr3{iaF;HLIxqwX@W@JdRZ6&jRrU z{5`nMMo1ks4xTTm#HSD6(hCzKsiV^{ngwVw-5EI~I{gVg^DbsCIUBR5GXmjMTr0`u zc_2@0(}6@@!I0;fWSr0wJBsFkO0NeDs-D63;#N3q_DLdtIe~U&^E^@co1k1&^+f>qS#QS~=E`_1TODf-uW7pPdkVys-=wh%uR`*gAZRlQGF@ss9S@(L zM_AQLP!cmp_fmB_@LU&Mk1@^D6$m%L3TK=lF&;)=^t0Dfa8( z4R~X24QigNgt675aKcBzEx&vWK3xgmdjFckAm1z69H5Q6=IsM-&tjUY@t3*zxdB`6 z-KHWr;$ZI+2KM*saJt@h+-H)C#bd6JJxfoa!AG7?5wZ`jRrXNjjZ|>8dlc*F8V7Gh zikloo!>RbLdw67YHD;=PVGh12z>On^V5?^vjL|(#rNh3_pIv6a`Gu2^BcIUs`fKd9 zlEKf}Gti>#A^r769ZqdEfn|XwL1K+Iq#kDAQ${V^efovb@>&Ew`G%-G)`31;kczvO zUZHLU?ihAiS~zt~G+OzcBY{^Wz%}_3xSsJMS`*sHkHvD}XHZREtr|~<(|(h2;c=Lp zXM|2yPZRSXUnVQ*1zxI2#hlUt^5t$e*Dx$DG=3n9z2`=g;FJ_tZ@~M~_5quw0T+)(^E2DFX+oPorUv3PRPt%B%Vm7fep9a6X zQsKnY<>2jcNf3Qr9hRhxBf}ogA#+J7D7FIi416t~d7>cz|! z=?pr>Lkz9|mXPbo@q*RhgmzL-K-@0^zfTlFJHtwW*~c>8L3V=YN#>LBAs)ClaWX#_ zCUKiPG*I2Ri)cPAhq=j_RGasv9o==CesS``Sj|jS+9m}{w4XD2s<%PrE$`l(&*7o| zdtBSo^^g{!1lsj#@Gv<7aK9uZUYU&VeZuhV!36Hu;`vP8hqZX^>N#|D8y1|{mW-vz z>2&=nrTs<5~F2 z9^olTBUoP}3TekR&_-$x!1+2Xw`9ToXeJ1+6;qis9pOnUo=v~a4Wn;rvLDjQVKD0< zwH!ox?E5cNV=7_c<4O`Ok;By;O2NLJZm93b;VOG|SSR6!FQ?4_c^Nr+O*9eX-n)?b z=WjswJ#*~KizLUNEWps8bA@YfZzm?##aL-C%4C=2bL*bHAbG`EuxaTz@ajAV6@}-) z;XyTcJ2a9f8vUfiNEaqe?;$zS!+f7@GLC&FDvZ6q1{F&0(S(AJB!|yNZkXT6&sbB4 z=C~-#7?_988x!!tY8HIO#Ho+@Ue0lE27P{@1mm}()x?3z1g|#r79jD-OYft#1GyxuZoFk8Fcn0C#Nf>h`4L%q6g6Q)aQoZ^S z4hA)n1D{`#;mpOPWJxk!zq*gC=zT;*#ji2eP4bX@Wg+O{PP(`8Ij!`ugNidVaDjgy zN>{~@pnLV)_ZNRj=dyErC%6X_ulm!d^eB4bT0MRhF#vly8+wBl^i8HCuxVpQ$S!t|+AfgAsp`SY;^w%>KfD0@$)IUJV)5O{Ojwrg3+`b?VCiKEr7{y} z%YSa<-I7Tp^27i)bEPb-OYVb=)-Zu+qz-uWso*YIJK_?<2$dpc(6cLaad1T?9oyN* zI9C;7q^>7=JU&Zym2JR?>kEjIp(6WF>KOI0x<+O$d?C1z9{@*Igfb4zCqVmqJkAnX zj92m{fa-9=|?H7=2lY*(ZwN$Ixk1`Buv`RJy@ED-G0pt%aA8 zq=jFT?orLiW5g=+8R~b9g&cW4FD}{6g$GR+#21W*oV~ZG{wo>0ZL|hOH4&qS%Q&-< z6`1m?2k+h*OBb6Xh`w&-=iMjtv&aeV{XJ>&;@x;Kb7_J9E-B*eHOGKl--k9U?Qw8? zGWjHD3HGnz>7yoffgh)dKZ6h8aKJdB*`f~AeK-b6{j2DCDO#C(uXC6I>agWBrp&mU982^`+6K!lx{)!bU<49+?CTzdu1CFvQnU_rw zv_GO1o~*A0(WkRW$m4TZk_?a}=%|`a6`3M4C3wF+|^*5)e8ewcUMz%jQ|4`|1II@6+Hc;_s8?j%7G1 z$`Ze?3?Vt)d?)U6HU1E-!>c@R)ZNaOd>V-+AzD>vAKFZ(CGEqhWexm{rH*MT!7%t& z4?K<*p<$H^E)uJNf!I~FKz<#}-^B18%JWQYxj(&IdX*Mv_Q0Cu9JsYSqwVm7$tWMD z$GIG)KT8_|Zk)i(+1ZfZ7|Zx?Dnsr6*5j7w?S#2H8xIuo97BHQ`p)Oscl|A=9=hWo z|M_(q)IA^Z-bMQFP!Ej~QO4J~SIKyzP<21D-oKqzf#^%3Wqj!GYPeGA++iimU`Ww`}3WN zG`pR~r~TkPGQp%`pDJi{uSNszBmJXOL|ycAn-VR?L3`s&I5|{Lioc#@#@pzjvuhxh zXBe_W%`N2i+3Sq=_3`v&3!kGkZo{N$jkIZ~7V5qS@NTVSa2YX0xq_!Oe$q2~vDhDM zuIDj~P9u3a^8#$sN};Yf>7-6Zo9{zcapqgC(d-t_#dT<--8Jj5+vN~>f4iO@eXU1U zZONo}Rezxkw+8^s&L02@ICF2LWq3xiQX?pTyL=h|0ebF`RRxB zVx~D<+o6TVQfpA?vKVB1a!}e_g%qwf2kY~)5Ls3NDkHY^hYtf|Vi_o{+e!|-=_Lw& zTLcy_V?p|g4i%UL06D1(_3V}=@n0(;?}7;FIGQdv{P_;Zm}=64>yD$Mb_1}ySLcq` zUevD{piAqk>HIz|Sp7;F*X#3qy1+-&adF`T?8#Pt!XoJNWOX3G!xX!z3$d z{39Vph3)Gx^Ro(MUj0FjM2`|`DOXTm-v8{h{sq3gG@7QIsbI8LPQ~q`>_Bn<9-J1y@Jev! z{5-69#8TZkqHy3^2c2jrDpXLG5azTeqoD=wv)Nk&#m%qrU0oc#a;$^6H%bT-W=aSr z>24sQnsJbEM;1=kCXs({e=(juCGT!NNfy%&ci4!7hq8+un^>NE^`o zI-fzcK7}0e%A;QmKhW2yZ%MFdK zs~$49>Km|me+K<6XeQlv!*KkrFLe3Ez&lJb0UDANZ{pZm;Q;vMv{ zJt1VCf;rAI8;!wR4B@eH4Jzf8fJkFLe(Bsxu13zHuaru##XAW~LpNhZXg1W#o~6CM zN+h~V7yFke3?BV>?iN-j1eI{_COKRR!*J%tq(WL)=`c zKUl{sgbfOmr2R-FOC^?L!HPgQuyiG9O~}M4Pc`xP**toGd@6SKor0mI!OYdmGck5o zAbuXD1eN_M)bq163YfL9t;QFkI+nqot%-1>KZ|;OosCEKCkxt7p2gkS#a!Zp?NGBb z7vi>^fmB;p2-_G%@-uFt&!Nj?`;v4R-MtLAJzGc_hY-|K)5ZyFSI{{duS4M1S1@L^ zD{Mb>j63z~F{!FKfpTlaL0R!5t#hrSPVr}Pjg0}G+`b4lDi#2^WfFB}4*2tX;x#Ad z!>VJHW*w0vZ#)m;MR8AjY2c1UuK6_Nd^3DM9|!YAmZRp~8dD|q1?f8y&U275xs3)l zsmeKu{;yj>rS>}$sIH1rY!<-f!+@dluaLF(PeAesRSY4~#5P$Pwk7v4yRTeDHSy87 zqN$vTdQ!lpzLbJZf{E~Wye!NP$RTRZ3Rvp*j(CiTfV&mU(cDVCQ{)4~qX=fDHl`X@BrniJzYhcyi zC)8zIItkN^gxOMVs1ddTu8o}x7ky{oktbGYml%sVFB;Lj>k08Of6gyjwCFQ`Ik>Id zK-$%<@ppzAnWMS{IjErzKmDfiUmOLW%VhCEwk;;Me41R?F0MFYJHX71Z|B{Jp>S=vF)_R40Brvq zn6~gONx8WjrZtG4eH39a;s^j9&LN z^o}L4dg>ak|G$Tz7_$jQw68&*=SC)Td;y3?XyUOW5t!Y}!fj0k3>Nlsx700#vsC60 z|42_v)tOJL_AP*(ic~cGbcLXRg?+~}nY+3#ux77<&`QUUt{$;Nhv+`KJhqf(Ju$<< z>!QNo;y*Mq`WJ21NQd_@QTR7#7h0V@i(b>RNbp%b{3#;EX6#R;8DXXL=cDfki%-Js z<6H2%+HEFzT0T`9^o0nALhh2-Di9#K4K7PZ zlaxyvK)u`pK3KFNbvA*2%^XU_E23RMGPB^W6?N`QLKSbGoxOV-V`pNDPXg|96Zp=h z|Cx6D;$8w@Th*bFC<s|jo%B1OwddEVU;Bu~OM`nAyX`W{QsyN-pnY{19*>QnTVK9y8r;QSBI`xkc-*FO4jN3?JYbrIB ztRQ`>J*nJwAvN{*%q;b5!uH11cyw|Hm8j=)tIGm$r}jPaY~U5QX!~5O`S_EQIC%i9 zM(+m?<turNf;$AC@tnW&HsC3LfvE_ehzju;(8qT|?jNmzTa>BrGOMunu3@7*cSBfV)*oRJFeURlLV&O@Lq{c@Z(l8PK+-k5mR=M zcR91jSlPA0l%b_~+;nAA^ z!Q5%DX!qh~=+{cZi*2e@M=22hE!QQxEdr=Jw-gso9z%BjGREstav-(l0e&^w4oA=D z6X*3GDO7T#`eZy@u#HF0A8XNcY8Dk4iYFGUMTB2?p1EZu!NRnOO%dB32&A1X&{3n3 zj8c!qRhPo?;^gs-2DSsVzGW18nOiLS6srzePlF(8!9P4IUP685tc7=rX9#_VG+?h- z3{g6RD66uC)K9*J-CjOWx3z=%-^(KR*9YL*nrg0fKJRb+R?D-3b--0WAO9IoqqD}( zqLNL4L|MNPJ0oRb>fK=3-sg0$!l0~HPTQ8R+m1TO1jbnZ<96GJ_`G}906T)xC}E`D%Rx-{wU&^@qo zAQDvV93jBq3jS=0A>^nzmtk|6Ofa2};_qV_@y^9f`x3qp#dAoE?>o`x6W^fh=_fAr zf+*8EF#}@K9zgWBW?Ev_N>okEu{Jf4_{@j_0l$A=;69P=e7F{8E1uw5XNz%zEit^$ zrHOpcHzZLbV$l9y1}Z13faw!wI$g|=R;8toV`4hEYL7aexuFPO%OBCHDi`U3BX_`m z)jyKAP6V@@Mu@(84C*%t}Xn=v--phRXM5a z6LHx-edgKVC`_#{qest*Vcqp23@y7yh4W*n)50EFXi!c4_?~{fmKapb)kQ_+rPS5x zIvvhYVZ7|R1Dkf%{AiP-iL z{`37IRy?zPb7K&u(`2ll{ENbGm`9@0EnnpTEGds`ra@{>p+kcOIvoT8`?S`naMr7_DmC$*A@O z?AFkMkI6eh>+%`;jQItY%H7y>xD8&3?*{V@Up!N)1fK@`7&CDKYSVyqzW)lpy(uN1 zPOIYPbSdtyLM!RZeL>}(za<@$#8?BPUUXhm1;Yw&&}ro~;$#*?D<4e7I}7GR*Ql9% z9?cz_XLq97>`b!LA{l1)*b5yM>!J5QQMmm`mE3s8@1r|z!LEC;VDqbxmfyKRi{Ht! zaWG8UoZO)-o+FpCB5{qB7}gf8hjl1IT{WvfW5H;Y>du0TUvJRYu145CX(OHJ#zN07 zX>uvs1SHa4;^njx^o`^?RGume_G`K*SuD#8ZswWYdS*nw%nX!5bV<&2S-M}Zl+Ic( z11iEw$*gTA=+obaf;w^T*{UUI(#y?f6dn9d|XwlPt)SWLKVB zN9VPKVeC0^Zu>`Zuq};X`p;?Mq(gD^)t4x4!;W{jC}0*oYR%&B>nsIjW((=XuS!B4 zPi@jPxe6DG#n6jwMv!P}M73wW#G|cuz$?sExTkd=@4RopA>9Llj#%jtv*Fhl&T|Vd<`PZrA<;bm}A#_KRFN+!jZ=S4W)p22I0=3(dkueiilAPTIJ%VG z;9YrPxcpEwv>XjbE}@&|xr&2_-d=dscaQtXb7=0*kD{hb745G)Pk-F(r=L2c8!td zqfqfDm>LGm#i}vG%n-MTY1~*!76ui8hyO=zMYAEJGU_VVX{|3u6uFz|?EH;>yA}%x>+jJY70K{+%ow5PxPvG+&kL5X z493q%UlE$~N!k9p^npq{^FsDIDydq7K(UmDIGjf7&dIp;Y(7Tib<(6h0PfL#vdc9W zzlgL$=)rCDPUJA7F#ZI(<@Aw)BR5e);}_443IXql@ucR^1ekvQ75Bie2}U9o2%Zn+ za7@7={P=M+7c#hy1QZ^_lHgX(NOcU{{v%4~*Dr&eA0qLgs1sf)Gr{VIPVmfTH7e#` z=iZ(2;X8R}Ft0{dcre(IM$hZU`{f~2?Q$Hn)!d?cbXViF<_0=EWJroUUo#`leD?d* zQyRE^7xnv8gYz0o@V~YyXjoN54OHzo3*WKAO~%^H`;Oz-b2%8#zKn;T4?W0)iB}=- z?HO2jubi+{O#QwrLtCX%GBe#B^QJM_tRPQ@e#ziEwu@$O z8x0$5o-xEXm_AtJ1bJs`VYb3EqGr4X_aA>jJ3^;|)wa>NL{SGUP?OHYb=_n7o}5Ql<#q7c{wY1zdxk7EKSyka zUXTz671FVy1AKk&G`4LQg>~N((26%2C@;6ge`>ezRbL7kJv}GrG1*8)u1y8eDam9) zoC)-W^$G^ItKso$Tgax-HIykVglrKfS}RzLgBWU5|HSBD33SuV3#hl_G?BQd&dN+( zPp>GhLAP0^sO{#1X2&jJzX(U;$Gqcu({#}yFM*Cr|4j|_wxFT$WI$6Hyg>Mz!KqA` zxpWT3crOr0Cz;{fH(6jWu@8&J=YSEPA29n{MOw!Wlhs|nATu=^Zmo+(y_46dMCcN- z_0f0g`_>U0LMkADEP{0^RkR?&7;^Y~-6!jPU?6f6N^Pj75q%*S=tc zxB>QMBigroCy9?w!*jVQLJR)R{n}}3@EPtT8+(#r)8R>?4yO0*;qID@2RGF??CMY^bskb&!8;qcS$TjO#>Wx;oEW0nY>fYgzA$f= zNupp~G`Zur4*IIfh+R%A=2~o^ei56v8Ddr>>GDI|{6Y>bW|@FbKqM7$`9fOa)!~M< zB&2Bu(@&XqF=mA=!k1DQy*nP>rg-D{K@oPv&vtxWWJ2m5eI|w1KI4?7Pw-!r6)kaA z#fZ808Toe~sjpWDjk>!4Z7;87{=4Z#kD1NKcY3?2hV@J8uM~i7US(t-bDJg_WH901 zo-)QZZ@5)2E@ST0*}OacD?VKHfu7x$1LyXSMVZ!Nl6YhfDFb;-mP`Z@zv=MCZ31Zx zBOtqY4W>?-4lO%3VC;|2#Qo@E&<$6D1s)+ZX_gLKVcbB*gzYE6(Xa3TzxRq!9V7wa z@3^1e2H~{)bjVrMLY`VlvKyOs;g&rG*lnUsmce{jGQ}TXZkUVuDTU0fF|C-<+)pGw z^+AoFDE3z$!SV^6+=Agu^pmv^bV*n;PuJ>#&v-ZZwMmBF8Rq)ePny z-AP*$9cjh(UTUv0R;V8JimIP5!cA)>v2wf`e!cmL`Wt^@WWGBJZ4=i+u9hrho>gHT zRy7f?RVg%#e+F&t9Hw^nYsnJza&mvsM^dLU8PDH*2xob&Yi)Ep8S^Xz(_W3n)$20I zZN=rV^l>GG-QDKxV1bN_WTMQRg;Nw z$&+A8Lp~&45<{m~!9>MU5#2>on7213Ve{cjxZH07M)(!NqSenZVp|Ag9gt!lDddor z!r72MydAvx?83nJe%MJ|U|@6%<$n91K&p}|>1(5JoG+;i=^;*f6(~#td~r<`&YZldmY9*dx7E;J}-GP4Q9K9z@nBIJZmeUS5m$Z6^li*{!cW%Y|Wy2=c_QL?QPRn zm+N|KI!F zav~D{x85NS5ET_!zh$2vd#&L#>wO@FeQ8k6zL@9C2G5J;XSpEurVV8yZXIEltP5g8 zZ*5>ZzD2NZ%0X=2hQq9#MJoGGHjSNT5X(+H@5z?W3uHq)Q`rg1F|75vL#&Bt6nj{G zCo5W+&Wg&Uu@^RPW!o+#^J|ZTY#8iiZ>Zm51s^ilf(?nR)1h$ojqHBb+0lbN_QQ>> z^UPrnP6=lxY=~#Kt`6s&0|D&G%3xMiKal;{7RNhn4zqhhPq1Mx1KG&EvFsd7W#ha9 z+1uHEEZY#n{v035uALUgW`_i_cNZ4&obGt`mdYXao8)>{de;$FfeB*6qc5<%?C$^5 z?_Rk*+eSoGMC5-y{=c6e4?^Y7&(d(13QO~w7XOzFA-fB3=!69+miI=tx&CBHS~-^O zGsi7@{-|kij@B%^NXB?fBQWhN#jg=$Fzk;Yr~D$ds+A-?4R7gL`RC}LItLs3{pj3v z9zb8oYINux|zvp|)5fwzw(g~tJ8=^<5Hkwa~ zBds>_BHcRpkl;1Lx_mNIp?%tLJRKmbq?{w#x;a4)>((SnUnA;M!>ff4@m7RX_EIolXfjr0MVr{seZU3JYJpI^gsRD z$_N$lO9^35KN zdO~`v12Q*CLcpqi;mP-#*bk1!g?^cx!nq2$!f)?putz*k2p3lu3U7oqu)MKdIOXdm zC`ccG=aGMfO;$h2-k;}Tv-x3Rk7bci&glmo?CyhJZ1d0;_K8Lr`*K>O+3lyjY~9smW*5rz%x?B%vrTIC?A~iutiHP*tDi~P zE}01S2m71NefOOmG!9_(EQ8tSD{ix|=bSY2k1}N!I=8Sfi{G=a9*CH=hpCtiF7{@RY?3m2@N|yZ&SpKciOcfY^Yy)~`Qi;`74JIO)-$Q>&!>#p)gdeP@m5o| za91X4?K;Wqf6lLJ*s0@xe||jRf<+c)}5sTtp?d`6^Uc;Rv= zNxlT{56r;k)2XOu`BCt}?F|VF|Ap@~mSdr|7#3>j!<cp2BUV=FW<>0n=F0;HLlbpE{fiE0usJve`BksKi+dUe1-qB6EXUzkk4HnDWpTutLVOo@2FWa&-}hQ7yF=1kQUQG^{fmq>!b}l&5-2z-;;30 z?zPaDwUtOloE0$s?x>t}f(!q05w}$iVTV~h*&4eY`dbmM&+MkgR|~ParHiZHR*I@C z??H%BD11m$CP8yo!STXWRDAn_4p0fWIwO`od#ca*?0!s&|1QG6b0(9loKu{Zw-iX8 zm&bGMx9O2JmDps?cV6sWY0YUNbw5==zd9wM`PzIGnJ7tPD^s9Nw+G&2Wtcvn7K^`R zBCzU6JN5Z$0FgCwgojh*nD1TDWFRJ#-dNp0-zsmTQr6?R{q=gVZp8}5)Lx5T@*r7kgCCkE zKz@fLE8*`6l_T>|D7lA;`!@~>0$d=eMg^u{=J59_Nj#dJN?Qeg;ki~9ZZwr(24iC| z#LK72S8futw49>CRSwKp>#g9h`!I6$8Mt(g7&@=_gY*DNc<~{ExiRh!F)NAWJgrAz z{Oc{ex6lL+YNn!(y(Ig)_&BpC>^86(v@mg-B8YGONex?lVPtv+?l`;$ukYH- zGwp*p1Kk45c>0Gsw&WWIGIvR7+7kS%*N>_9#X)!N4V=_2iU#(3X{}EXO4yy`THh@u zXP((}@k2Av>u=|z3}x&*{T}nKaHFnL@LjMrhzwH{K;Y3wv)D5%y0$eK?cPHeLBa zgJkFO`PCfU_F5L~ZnX1VW>-?yrAli{CP3M*-LU^vB<%GLZ#qBvB4;X^*|g@y5LH{j z-^1BY$4{Pe7`|>j7U!{;+r1L5Zt5i)^&|MN>4@n;ujrwGR(yX)1OKY;Cw0j$;oG!R z^y8%2Z0W`p&T7Y1f!CpC8dh?@$wOI`L_3s`2U;TJ+^G{dXPCjsp5pMJ%9G62S%v3k z@;rQdz%{=4+=}V%q4K~u$Z>l`uJZ3&OZ+;Cy#8M5_&>g6Q59kN#6Nr=s)P6xS2rzb zTmm2^1hkZeIOiy1T-R}I6uJ1fgK22p&D5HX%C&O^omi`H*6zRkm|?mcg6x1U+}lMaIW2_C%Bjr9t6d}h=Qdjnii+JoOTL_q9fEMAoH0O^Fo^rv(%ac&62 zvto60{PtMfyW|qNTc<$o4WA_cF?~?~=s)Th>wq5v&fweXe5^X3N{UrCVdvdr;56DA zjyG0e#*;I&3F>fy!!Z(Su1n`8?E#JCUb?vIB3#xB2j`;_!kc4l(d9@c=or~x(Q_{> znqq>-#O1K+VG^S`)(WOozeMNK8>D}a8Myc8l6#hscrtSZTvz8^x;stq(Z?h*;bkoh zMQ^1ehS%{|ZX~H(eh$RSE)yGR33lj15LO&au68-O~ttvLPhXxtovSV4op(R-9oMEVZ-=J*-JRIgDb zUr#6!4T8rho^YT(n<&~;5JBfhL0#}f`euv_V_}#_<-&c5@4*`ArY<0+^0(>zu~G3%zrAm(%HecA#K|hN4bqHXbR57|ew#KSg zS*ZHT5w@o7r*<9g;5zvZalMm=HBw`l-c6ffuiEA54Ivb9kH;xEWuIqx>#spgWA3=uC7Mn>VV8^L!?s(-oTKg)jX>MpOpXuT! zy#Ww-vaTUZfqJRtOU;@$NoxSTeDJqjK4}pN+vYRZg(X;U`=;cb1l^r*IEu zT9O`_WDu9FCHF=fgXk$Eq3D>4m?GJaN&J4Lqg;bNRJc$48q4TXFK?{mv$Vmt7mKJrMETp1qT(Bni1{2Kp;|5$4NFm$1DCOJ@@@01& zB)pWvY40;J>&<@N+dCglwg=KndzARxL^pGZ?iL@0LR7|J*>V_$-8O&<*%(+)TKAEMz{HhK3U*wB~#$ zJlX#T|5lX48p1PT{On*xlLOT>Q@~dr^x5q`>v2rZDjaMLg?*pO=@!EixK`bSTzlAn zR~9~}4vXTTdoR!7=aBo4|9^9RW&*Cc-o+gGz5(z2qBt~`C8 zx~&bsY3;grc=sYy7fS-oF*0yA@dQn2mf&XkP6fNcEwn66g6#0N1nVCw0Mf)zjOWyz z>GH%yv-#(UzlV>qy@U6Q_#C;#7}~F9LykJs(FBj5oSRoB=Fa{{a;?|V6YuX+afMOX z*6z+EOuLJ!{)xnUo*14BjH5puR+GbX#|ZmGm7p+e3JzIJM$_7J+}yI?G^k?PreIZdF`ip_BKBwc36Mv5IcmknE^5{QA(C@i1n zPu1kt(ds4Q==4kqt|bJJ!PE-6ZCMX>I2{e6JdRwTj_!WJ4WNpN4j7)D~RutWrFE550n}BP4%2+kkI)o z-e9W9r!zv%L_Y;-krmu~>qks?IFW(<%VDE<5tr9qhpl`jV>)o)%0JiTZpI{Hz64t^ zvK4OS@O)FF5=`o^!|WZE5N9Su7bJ={S(j20v`_~%dcFxnbT@*GUn<0wB~g=qlr*fh zfypP2VV2KWT*-GUOoKjAt^3bSv*YyP%Zhw5ckWgalE?d^!i%v}MS(t?6$|PcAH(4y zQTFqfWu)+TH=L1C#G|$4u&CA=5{>QyH~Bu%+gi*m%9UsQW_CfoT^xLsNvH2`oF)2a z+aanrkUXEFjq)u!uwZ&1-0e@syRj!o+QYe+cxfV-VJEryJseMs z+@%`_N*G1&Tr3jw@~^F0I{lv}oHTnz{kM2?+wLy zG~~Peap{oU(gyvqwK#Nd4XBDNhg(h(qRM(XBR@Qwj&OquHXs&u}*09eljgp?@S0Dh`=}^REv?O*Dk5>u4vF z$S(LMSquKDQe=u*Je?ZBb9y>Eq3`+x@^j{EVjjJNjGecPQq$LDM$t7!@cTAq>n~$& zuhWKsg%-G@sD$|ZQGw4n&e-Z6ODz6n;4;>poVTzB?J<1raO5x@l8dK}%QIoe^I}?T z5Cgszd!XTZEzQ*T133>3vaY2Taw_NHXyqdMuSRHk!td0Or9eM{+%Rkh@%dmT1B zK8ew1DfJ*Q$Z!KsK={C&lHRi0oaI}P@6LRdakhq{Ft!p6Dppmkj@v52VP z-7>tF&_|z6-ciAXU2MVEk6ut)@8@*YDVBTVyOCsUnNItAgXqq+>3BL@ALl0|5Kkh; zuCnYy=H6Va&z%nP)y3$0Z5R67SVwn14xt9md$H5Et?9zqX6mM$gUg>>MBhm|xM^V+ zomM#&Ti5Er5#FgW-g^ogacMV%wVXk^#0Vs7Us0FkGs!4TTP*A2_lBN%%mi0SNJz}b zacz^CRr5zf>G*h<+IYWlj-vsDWSxhCk0$6Wa|oW7o5PD${O@PmBKTA>8t)hKZVC(D z1y}W2ka|j%&nV>5_^adCBy?@=ZV{8HRIre?Qwh52e$f*%+c4p94%(e2 z@OsHo^62d-#wI&LaPg!J&qU<=K{_FD<5w8`h;~OAqey(|afaJQjzgf<6KtEZ2Rt6< z(t&4L@ao_YpM4z!`OrMLvvWU2nTp~P=a1YSNx)@%$M4oQHC%r?8(Xm)^Jm(_vYHUg z_MC<}CAHkFQx_TEvDQTGdj>LM$I-5C1^IUH4qn~U*+_x6U zEgy|Z`mT^;{*P;6mDtk1ZWuaN0ecq&f%ETY%+Z$&I$EWZbh82`&(RC&v&7Kja}Mn| z(+I!6z2m-K)qzKmO`N8a15tYSt*K$n5LvCs!n9?7$=c*1uvaOAPo`hVyO#B^H)@cy zKdFR`#zo|(l5-<8Os)#k?uI1dDB$TQ?VhQn-6em67kGRn|*j!wgj*H9!1~vqsd4> z5)|^?7`3cG?nAXRiAvalyJu9K-KwIxT?;ozuA4y~R*k9fgHP5;)%K zHL|_%mN=I4I3h`*Ty!1b4@``5a7f;|8E4&~jUHiZ#uajRBy%EQuecf}^u^Nh(T6}Gy^1UEKiM>SlLmZ${)jZ!zQdmS91N_VMCVjr zqp<@lHs2dZ>b2E4w?z#kxAiVe!!FdP?>Hgq0qUln{?^9 zVB@zsdgcuepYp$nR85pN8Zr3h>^v}j!Dq8|wBWp&9UeI?ppr@|hBz-0a zLFddLsyFBqR{JWrAEWnwk#^p1IfnoLZ!ghODH=2>8Vc2YzODutMT4Ya zhGdkIQABA_+Dpr*R2no$=sI6lW_A=wnGul?8us^ke?I@f=Y4#C=*N!xIL_m~uj@Qt z=kxh^ko7T-ZKidv!^^S;82$bo(Jbl0IV+yf3a?9KZtZw#S2z|bCfZVs^8yq#QKb`( zJRmhed1U^DabWAO2u8KM^KmvuMC&P?GSd!QTj!F~Y7+z*R*JCfv@5N7=?}GszOnP* z3h%i71Oun;u$nPNB!$neWX<~khjiwns&yck=G+z>i$5vwPCkZKZ70ci&s4$6;2Sh@ zY90iyZ3OK*3Yarkg{^$=FCnvw{+i|p-a^BeT4_&54y*@}<`fRd}!# zSEmZWrMHi0KXJgLAHFnB`rLqvXT{O$MbmIo))Aa`ycxfXC|cX9lwfnW9fmKjW|!(` z({9aGxbnCUOpMmVwRYB^YdM~o5)=Rz%_Fh;U?Lgs@Cfog@(jts7_4_Y&a$W1!M3Vd za4aH(v^7M-&WL8v@)UuF-TeD>+Ig~TWC72yYopfBK2f>#J#_ZAvG{ymDBW9|L+Wki z>9KW2U{R@xaijI%nL-wH!!uGHeT03zP6eZuJ|X=Q24vAWd9twh67B{OD3*FkF1;`Z zp@!SAt$ZvFCVe7n6o%QWmCm5GPmX5V?k8_}N1jA>7+MFNrq2X(nKzQv5UKi<=msr> zH;%;(hryHogs7CedujGsKGn*4xDk$|;8WwuUC>?PwYLXI3 zRyERI!f@)d>s0JG=u(~)5w(xLl?AmI`aJ~{;a*pf^Lq}#C;K$F*W?T zpwB>wuQ1C~P5D?%pSuSwUv7cmvZWyRwVn)rF@@c|@u2f787iFe$ezhOm*Zh4ozNhG zLdPDnQ{6UVey9m4-}I<)MA3_%*N+H1Y?mNwa2~h2Tf?(msvzxVOs^Ox;_Rh-pU5m3 zwc^s@MpF?sdu=A~17fJ~U^V@;^@SjN^9lO0dllqf(uCfQ60${}qhc|2)*}DRpy#fD zXV_ik8I%v{is?=4((-n=BxO%McAvv5!^yZs-y5z6Z$w{fGd!-=MknVxl6_|#G0y%s z+>kV;1sZEm{mn9g&7uH&WO54Hx0dKHTzfQy7H?hBS zb5Q$27O^sjhgVO+$kd9n)b~a%Rck(vfy;kU_5H)tAY%-j!1wLEh7ZAMSAQJPo{A}S zBkz6!lon3nJswh=O-DHmxOz|EGdmYN%g@kTyw^dYR~|2m-NJ2b6up+Y6;7Fm)9#Ar z^oL<0Xgj=NZw{X!gWprJ_`pKe?w}-0;=jA5mV@jdpS{&DJOd}1{Q1uoCGn<*(ZWid z3D_MjXxqm3@k)V}SYCx)yY9lGaDJ{8dl)W}OXzWgpAiHW5`X{WwDoH)Iy>E>?e0oU z{_+wq^GpM=_*&ji9);KBZ=iP*KfjJu!q#2m=(yBbxb#sRv%sC)p z^IwvoMm<Iio&yUFhFj^KGFlT_5~7sM6Bg1^oL_LEyWtJTZTs{+TPR$?U4yOIDM z#nT~nMJh9ESS5I$&_@WzE+2$Z=9I}fRWzV=`8KvN$d+>%ArJ6Ex% z|0XRg(#4p`>g2fFBdR&)1!}mTw|O~d9tb<9KupvTe3qpTo=@aqz~2Z%ejLY)iW@{} zY7ue&kdNBZmvIywjnh0|Q^UQrB=%@6Y38H_*ONt1%JdigdNGCCz0Ab2&c7tGI0zjr zBY;S|L+_Qz_+|YB4h}r0FIQ?~)#ge}Rn#FZ4~lW`iX7^ETNNK%e@qg>CJ_7OyK&Mg zSM2)c36sCulL7u7R<$e+f303jHYiUdv&(Pd<*zZsz1jgkB?v4R zoxm>>K0(h$7xu)t)o9H3($7b$;(%%qR(Up|=gt9vWYK9F96lXlst|W49ifYtou%{N z=+T{Fr&xo{S8&PWRCMKMfkbu%?0B`7Jmhnut6$rpl9CV%PB;V0=bXV>K?fF1uSMVB zlW^|NQPRG2sbETPCAuiGeE--Gvd^C+>C-<8WFLK@lfpT?^5jS3E7^7^YBXo7k|nT- z38%SJ@^GjAX&SMb=ltL2_ud;C!1($;q+VV0Y0Of1Y+H!4{_wwp?h<-zf(T=Bz8Fb{ zH@d%n4zS@Ct@nr%3=cQ4g0whV6_QDn!}V~3DFX{y#?l278?7h%xw0Gi{#lnu2PWFJ zQ{5|4jX_fbF*eg&5a#&~JBk`HyY?t-y6y~FxB1Lmd;puVDIWb^oF+KE;#{cQaUy1=^y-5A%{ZbExEL;nl;Cv5$M|9CNqVPy9}@Fc+PvaB6-}{$ zK(Q6%Zl4+#8uy194-`|WbsOlkXSc|Ro`GQds~Z=SGBwDnm=P7vm0|sY0c$ zQP8$~6#hK4xmCSuTL{`^zx4+<|>zv;fv$p9ouI zji4`9h^fALnyelWromID;=QZushjs{I;O&b?)fOezeugk#uZB8444{tprjwC(kBRoy!?0`l9DMWmHoUig3b8Avus&5{^iTL< zy1uuM=JJfL>xq|1W!QJYf;FOaBR?+;%sEWGT#tg?F)6kqq#dH&r{I^^UGUIoC)O1h z;in5COzeaS@L1&lEJ*%J-#PZslHoFxdvXvbADzOM?f1f23Qy?4v|{$X)I$;|H5wH? zH}Xu54Nzs21V1G-;EnGakW;qh?`)>P(l;E*pS_OE##7eGPIefYdkVXLi{ripSJ_>A z#F-7f6LE29FO8l*kxnPtn2TEEqskoSo$VX)_R0xb_iUiCJZ%Lwv zf|VE$#c8Mg*jO07n%K0qzD+T;1 z5{W6JroiOJ5wgKD9WDE3V#nLluyNZgkXEb(A0me?QMXY<=M34Bcp7s;7TNwX%ki!dV>A? z`8-=Ahh1!Rf(rI4KzLs&y4>=_aShd^S+#1U%cLCxx)l}5;+?)M(4t( zACj=XRD}!NJAp2>nU4yy{HV>Qc5*3J70rVr$<3psJkwT+{AqbgQk>&Zvb`8TwO$nr z(R)Omf2S)nr;!Sq4LE!@l)nC@jHNRiKrBoP&)b&c3=4TM@jQW-Hm=6HIh8bLX&!|B zRfH`KUF>|GH?^rH3QgkMVZrQ|5W7GD{54c?k8?7ZkVg>JHv?7`YM@>l2QO|{z{{op z_Cw4?;P!H85NnKy#-AIl-cKiLMa#*_`cn2|fe1XNkE!wGcY>NkKM0ie!gKc~p#2wh z+#5lCx*S$k$&d~61fX!T5dN&b$R@qjfddvh z;F#)qc$uHc-$w?}rk^S_Y@WL{aTv#@M{XqPK~w0|oHvc@t_$dbmy^+6B^Iu06=B^) zS(wg+K-*hLWbUmq^pK#1^oBXn4-FDPkB zp^n{2xNmnnX{{IyIDhi_VEO{9V`*JjiDJ5prP>P(Dzku9(f?j#Akw_@en zVbC+02ZQK_XTqzHX(=SnV$Yz5BzNj14!Z za07d3F`tKO|4)XW0gd*JXtIuHb()@}DKRX&=F1ON81u_a3pt3^@3s+|0pWy&VI$Va3dK}6=EXSB@8)?rSPn5UP zAg`U)li**$$Y1Wm!paAEq}POYl=un80EaN3ZRS zC)Ryts5GXpF<7RI-JxXw8PQ2(iMR@uZjgiNA79bG+asv1{4?slbssoiKMb5?Aig!@ zxzC;NAmBy=ttwas>xR>?qDP-yyDJ{6DjcyTgth4~*2G(joze5}S)8-Jil4)VVtRHi z2JL)659CVHs!ls-nY$Xk#W&K=X0bN*uWQJ-_Qf!9Nfv}`eFtrmT42OK5e|t~!wKH6 z_2}yuru5iUv`BNM=S;Tp0>v;g}&0?^Bq6$2cy$JPlM{z$~E#SOH9$mUQjJV7>z`I_%Xw9b;kg_0# z)!W+z)TxA?AH5gKa_Zo_NGQzdc!B4W=E3PB$|S^OCUnXwke3_vA+4{E_j??quW2^j zJwBT3vG;^$*)d?hF95yk|Irg(PX!-^)bLL1O)_R67ApnwVf54-OtAe&mn{9qHjGl? z_hIMg$Iu$Od==6YDO&(^#89XgsmeKR=3@Lq%*n4sogc=u@7zq7QFff2)?2{Ju8juI z7mLv3#zL$MNTZ+5Ho)7NzHslAI#NaN>A`0 z#MATUw^_fuW*XC^i#8ATK$y)+xc_kgn@-n*WqvSCPfta*aT7LK-R5VM6Y%z~Vobj( z1zRQ$p`Dc{ZSXk82HZ78&7e%pusZ^(T4Jet!FqB(KZkq}tHi4l&9SSb1N#$% zklVQtQ&caJKlbt@z(EqvT4lig00&gA;P2k(UG`;$JoXkup=PcqY|>l9Moi*+7%zqK z>&y@E!Lg3#NElIvGqw<0n~C0odU(0$H6^3((6wpWAh*o|hf_VF^YLx8Fbc<({s@N^c#i7;9nVLV8;oX?Eq~6lJ~lCQUR4$y`_>b>y=5_U z`KybMb@K%s+ANjx5+>ufz960I92E4&;{@`7y!StfS0XmTxKbxrS!4raopRxB)f0S1 zUkUy>d?9fnd&r~WU|jfq9viW}Q_!)e7*cyD5wR&t=%_` z_@2tmv4h=NE+pUQEW1c96NEp$CH9jiLw3Ivw32obnCAd(hu477!rzTq7e>*mCdWyB z$!p$mCI!YkYTy{#L$?kU!y>8OnB}~j^C-`xgM605A(ZF-HfG@7pSm=5QUocP{tCR! z!~}m*SCZ?tR+9NwsCrpWwC+HeK;CIik4yaUQW<6;}vK&CqhNo zIXYwiSS-sG;rU42f@hyHVZZJkEcfYRIdy$}VIYgg)K6gxKX;ZBTZ{)v9jMeFDOg?p zlIUfZqq{sMF0+Z(!}8v^IA$xrcfe0MC3NZ4cKF)RLE4-fAnJi8&!~*TMQZ~zuqq)Ecg(MW z)W$?Xcc~5f94aD`Yc|t={h?$sf9A@6_yv96d*P!4S~#gXlXixjA@4T!Qt5hOL5r>s zysEWewbO4wS*<#$ssBML)4a*)YtN~0zYtAYQ!H?5;aT7T9%S#PP4HKIm|&=W<9d5t zYM`--e0AB+j`QWuH>Jehw)G)W96F%j57XaA zK}2ybxoNM;9Em%Dt=7G0EV&&{CcdE7)-Ty9xpL&!+`Ski;|~+H6i|j+0q>KSQE$Z_ z^8T$EP-YP(ZM%TQ(idp!Nj@JGS1tIR)=WOwOvl*)ZdkUM$KK4Gjo~>P$b!p_ps{Et z9B4d1Z?_!8wFZG8u6mi892(0lTvCfiSBR3t(o*W6Y=}b50XA)#GjOSRE!i+$7snnQ z0qqaH)Yv8j`gR|urB6eMYAt}w@`o5#T0p{-#$)ND(*nyZGu+1frXRy7{!}iqEOn?N!Q0YF;^-t?=u-es%Hjm~7%@CMJ&N>pIpE1D zopc2v6n^j^UaOQbqJKYZNsGh!Pf2voD_#6LL527nt*6|(KJv$1pAONJAUt@0n&DZT z^mGnPzGw^?o89St({{8wX%Ehe4B+mv9w^>(2(x}xL-^?|9Nvv(jYcU_Ga&Uuhn9U~arD~eu2Z`o6xn#5Bx z5%Tth!-@FSY-gi6M%|U*+D%W;+Q_W}5w&fwpsp4qCcUTf^;XP_Y$2W#mI)OrF43X@ zSG=nc1Gf(LkZ)D1;nBt<^5>l_b-a;)a!%W+cTWNYU3gC0cRZy%_V)Ni>>u1n{z}%W zh@kMM92{2}MNKjzVC|`J9E@Fq4|Sr5V^1AP*ro=>L5_4#_9xlaLs0zTGQpymc|@c% z2?Cw{F=yL*TpD`;O-J^_H4SlM&bviC-&k>q>z~5l0LLzQIti|y)q-z+YxoZ60-QW{ z1s+=C!OxoFK=$}b?6_l%bBpb<;c`2TmleaKvox?h?*g>HK1M6n^Z943Bhc7!7v|h* zAu)rKLHWrAJn?9hz+W?ltd2N}$x_Ck+AfxgY4S>faE)<;qu#xurE5CUKZ5{h0HVfX`VJ2`|1ppT)K}PcSe^UGM9%5 z%?wEu{YhtTT1%Zbs$zpv5&2^hjn7v4f_vpWWTQ8t;_F*PV*Ut(Di2_@`(>NW>pdm(6^@3j4sgI+sk2ilQA%ZZ%J*96coH3 zpy{8A+0&aYp#9fA5~Y5d7CnDQ9(}d~zwP=MM~2B2vmRn7?8o+6N1EsyUP^P!T5S@{Rfyik95S~nfprO(3Q|v&(aZ9Gsk-|? zNIbj}KUwalRX@Y9ZjlNN5#9u%TMMx7(o5WJ=0`Gr9ic_TVK&Kj2f*ooHV92Yc+PVe z)z{1e=SL^$jLC^a_qZH$>&81c_9LB2mA1n77llwhD*-=`UW?YR@1a8eR=9p>3At-u z53bTT=rxgb^uv-A6p1QF<+3gGFYiC;)2P9^q-#_%l@qkKjewv32DCepLti~r$KPFR zE(U5|##bSpShc+XJ7+`?A8DlTgc?!IE0z6SbQFDp#$hq35YXn)T~93OS+!M@#*Xslq* zcha+Q)4Tu_B|9GtrAs+iz&pj#mCs1*`u*==5cI! z`}^XEOFFq~nTN0V{osteE@C(_5yadJ$P)ifa@Cc?@%E-v>-A_3Ce475!#Omg@i@MD zJ)abuF2Pmy)6vV{hp=Pgq2Br&PTc80woFQP3g|&!TVK?y*Hi11nWBu^nSD362gl?+a z$@Y7iH2?TF+SemaXKEQz>qs;1!;yt_omnD$x$%(}BtL4L^+N=;(l3$EkDSO~hbTCj zVu_;;TZ8MrPY~f%h-p{N=$-t>RBX91s-|DT^K)zer@uYMTe&Zl{^=FoSUCD^|S};FmE@s*# zH!w?ub}&wfo0+#BVT_erFk@-4hH*%XV2<>AGkbQ0Fqh-@Gv}}EWOOZ8F*Vzxn8@?l z%&yW6Orr1tM&fccbGh7)nOnY`**-Lvv9#X6eBT+*T+aw#9{h;p|1X(oyuFTDlfIu3 ze-*%-2=ZeD?0V*^%W7uC*P0Oy_hU>0S20$fqZnR#&*c8BnFy^_ z%5GaL}YDDL%P+O`KUxmhcjjP%w2)8DSpFn{&m_dj_-GQWNY z6Uu0)p%A^uvufYxO$L{{(`oVOAN2OlGQpQoee{XxVw4}h07bq{#c7Mqk=(dG8}@(( zeXB~ypjbDlTxEgQukN#sheB|;SPZj6il|7NCU!?Tk+L-o__>dFBI!(F=RJt9@%Ct^ zYEh%fQ5Pq{jdUxj+-yMdHXbJLj8>C3;ZulqsJTE#xtA@sP{Y%;O4z&ElMWn{rFK%; zblwR+w)c@6`e`g~+;L6;hjrJ{zB+wyXy)1HZW*{DTpRD#FJLWe_<8#j8#;^k5@FT@ z8_mCRFzbVh;J48&)>@g*l}Ymq8UOEeXTec=`=QSN_@({d{Sf=_*N+z@^XsQ?@5%Kg zC~*^2#xobHUZdK=n|LAFkdaPz<@Cy>c%JcHST-e<^ZU>Y2UU|fS@&*Sx4eLnIVHl3 z8duIaDO_c4mVZ-Q>FNS;Xkj^|gTgF|OtIYY^o~9!avD~pczD$SY9~kMI%bk=ja)UC-E>U$?aF0hZRZFup`KIhdUc(c;^7$E1-r9sw;q^j8~o>=ZP0{n+ud`jZFL0G z?4BCe+1_osW?O7{!*=9+f$h{1F}p(vJMCKcw%aB&XxrZVc*oXf)nnVCr1Q4RrO`H4 zdYSj2WP|O)HAA+KR}I;o-mGYs>m6k`y1m1;d7*{%XRg=@;T;k}P-!xtqp;pSItKg*u5tqBvd6QxJ({ z{rdeczvBP9ziq~I9R5H0+xyx@arpQOSjEV5pLCQMNp}w}(LIB7PAY_CpC|NN)_K@u zu>`rYeW?7-6)yAVkx&05nLMXRnAGOQ6#MBhx_?rL_0eLw%jqm+7}{ZivKzC;YAoka zdIKb0Rgls%wv1O!!%}ryOr~Bu_jNPNS zH5HP~=FQ(|^qpAT!uxVVMxMf~E2VV$sU+rhv_DGy_CYP#8)$KK7F4bU81iyq@*6}r z%`y$Hd22RKbDPCwgz&l5q;GJ$cnlq|bmZ)XE78+R2J&w@lC9|m%=4^DFy=XwRt+T> zRVl%Z3pj#zgc$C7q$H;_^ck$)834^2z$g7zVBc4DSX4=1&}E3Wn9St5KJ0-f4>B;1 z0=fLanF}>_gQpuhv5e=H7Th=CwjF#&^BdoRZ}5J&{*rgq3?0W!UfRsn!dQ%4ZABMb z#IYB)T!2yG{k$mW1AOXB667lRV}5l$m?j)XdzqKiOYt{mUFd_L;@N_m=XNxjE}H~H zbvNM1kUuka$9yO|Yey}l&0!SZNo(xCPu_kW#Mx6-x%;K!+ygIH2o%16W}3A)IX;aV z#9hLx_YY!#Ln&D<76q+C4JcW?i`zeBPwU?_f=A6ucIA6-Y~wCq^w0tbpFWN`thkUn z7|;Zp(twJ&odHFrg}(UW#`(@sgT>AB`RwsyJm187vki1O&rk)t_pt+?=s3{G2%T|NnzEBb`* zkIcfPmGfckLIF3k`XQD3cL+>ut+})rCm`LzmC*|EWs9H8M2Ejo_%1$I5I5dg&{g}J z(&oG1ug2ho1V>KvPc?+7Kg0F%>xr$exnQ<<6UuE%f~;#u-|vrwYt^P;WN*Ux$=8GS z!SA&F?|!`7kxVovC6U<%4E-vjS$4*4zAIs-3#P1A7x7Ip;^@o zZ)xarV;BBI=j83=q>dKzchqY7$)y(`9qE9&A#r9PA)owd7ly5;_1Lel?7G7!6txHmHJ*vAOBO6=h7Jya%!$$a)NRKWe5tq3(IWBGH+CT3!2 z0mOD)gMtv?f|Oy*P`3x zVH|C#%H3^Sg>$`Rz$SPWG}pO69^bP&Y0`j?bbHBokI{nu&^mm5^Cj<cY}sU)7?bsOv#8E_f4SK-XRtJoa-l}fpF zA><{JNcCz=T$v0P=e&bSt3P0WYZ2l^3NwaOn2FnI4d{pT`Z^{D72W{27gT4wD|-K!wCMf%vpaNS?~)%dB*OdAJrkyWOC)dL7BB zScwPc*Mr@+BdFCjf?bni1zu(O^h;V7L~eU-BV52R`8gSMd%7;2HBSs*?HvMNkr!wT zWpuIoIkKj>1paJdm`P@?%t5JWoIfU4km8*H?&BUJ6Sx6$`F@f}axCc|iJ=v9)^K`T z67k3zFpTB$o*Yvj%P30!oxEl<>VFMAa&Qgf`6F3I9^8Jay zgYO`RyoGO|#HqPXgtqgA5OCC#dFonE#x$RTWFk+OiSS(;$L08d?G%I+{-M1t;qXAv zMbvYQVBe`sdZf>iI~}Kw5wH7UU5XDd&yvXk=a-;e`$jOWNR`WUZ-VT+RJ?DjNmuWG zK;QEHDM5r24qCqwOt4Bpfy-`k)Rgas4BcawS5%W;KEJ9v<`y-)3T(OW_Z#=m}Pb5-C7flCXK+9)#;Gvmmm>@qy$wF}l-ZWT;lY|ZDscu&vkD2N`J z23OY3rj~c~n4n}4rn@o^l)pFN@WOWbcHvBT_HP|$qFxLaTkpW%h-NI9*#L{YBr(HU z6}R_SVNDo{V-E-jOSNAbxWa*FYUm+%aQTF=7(L% z*5t4H46xa;2r_h98&fSb`MjqjKAbb2NVx>!T=t&8%J?WQ>0AOiN($V_w?|~_707K}3AVeoFhMX0?iM?cDb@NUxbhr71AGBX{&qD!-y4f+1us~!#|Ju}qt`K5f0$=~ zYdwZo9T9G!(s)jCTN#8-YJjtsM{rm4cy7?g7(>oxvtL8BnS;(7n5X{=!Dhv1&i2q< zIGm`!rKS48nB&_SSM?~!$xVY5`q`jxT8v9voJI3Z4apOar;{(Ud8Oa~H4@U$Cva28bm=3|CvS7}V#c;1=7(TB24ff08F!gH; zw9CB24Pot=Ha8L6rQ@mIoL)hBe-Tw(9l~7i>4YN^6|gT>mBbB-GP!Dc%(;Ej(f#{3 zoVe~7ZhN>I9Cj#yjB5?GyuFn1G5!JX)GhE(Uo?JHEW~0Qp$*e=*-t@kcrekBaSZGN z?Zru$<7oq>V!p)P{4)J1BgSp?&jsv@*>CDNT=57!z4$n&}e%*pB?{R>9nUE>iV zrr1dR?>le`g>x`Ub`iW25#kncO#*d^I~X+InJL=;lb)#Y=fD4XRK;`&EaGQ& zW(FLsn41NsM@=B2%mlc2IFee*i!O+T2~=bZE3c0{#0=fopR%oS7L(_Bn`hGc)plj*G(S&tl*j48flx z4PYZXKvvClrGpbnAn?Kgf$HX2?4CAb*tcLBBM9BHYAAQ5Z=4NS_VAAsP9qkm_N@bnyM~R}HTC>CXd5KV{B!CUv9V zD^cds%JpcPp8@B128no)Bc>!)K+Kg^dg9_@5LQe8do2%8Y3K)m&3aIb-p(W(5oemL z3~{u&F5JI08_P{rb5~MM!;0;)-0@sVW{r>{rY>p%Z@ogkgQ&(7=Rav|GPp^5WFxsP zZkEh$oqD+P?;d^dKul0=r-?7tNHLo~#bD;hYiu5G2EU~~VehszG*l)ASG!vP~MX-zyBg?ywU5h7gt8d=;T&EmMi23#>y zj(Kc%m|bZX!+Du!3U--jU|ppI>>l2Wf7?%!jk`^lnxEBFq4_JWYX~AM4;C@UzhsH_OWQFAqYWQFk zW|iiUx~M8*C;E)E9a7>hS@8R^dy`3`c^W5XDc7%_d{ljx!UBH zbka@!yteuqHt_xbM6-n$u09(2J}2UW?-z&%ig5A|&jB}63$2`p7~x0<=Ki)YP^_L0%lbme*t|5HH{XNg?GMAwFmt#o zod#-sirlFeRhV+v3VeHSliVZMP{V!-r{1T`nSX7@=;=17{h=DY>n7o4gGt<#*duUE z@eB?*`r<0j88|NeDep&!hQd(>|1-ZW9+)vGB+v6B`M>`&Kho@f`G+9^P3$b`J(TqC zppp|f(kS>Mkc%=TlIygroB2Dgn5Pff8=sdE4P%zxzjKr|$y(buqY|m+*owxcli%ro z<|mRq@{er!kN?l#|NZm-mmm0}wFYH0$1%8Eh>qWN(nfZnH!Xe_2VwHd1gFwnus~ui zxbYbeLo+Lw=yV)X3Pa%gN=a_-yC8t+9$2}BfTU$Pd7-zQL}~AbaZePOYW|KbWTl9} z=fGw1{`QECfyxg2QzJ=Lji%AKFG|d*_j&k!Q885&ngw~BE7=x`bb7!h=)s+k^|YF} zdIjL|CmkU9CzBPqqXVwhR!k?qI3eeKQSIH%#?H=QJmFJ{_T9C_Ry0-+vHLhkoEpFg z%Fh%MeiFyp5&AXB8k`cZ}DBsN1waV`v>ntkG}w+H&>&@W@&C(HSex_ zx}Ju0E&!)CSu$585L)7jNS*_q`PnA|ZNZVaZQ&u*Ow%V9MFv@=#Vmb&D+P>)UGeLc zbKqI1hwCkiG3G3Pf3Y(k2l>3Vr$#;1+u(?8-^IB@={jUiSP;Bnt;u=gOd=3B#`gi+ zIiqa{1)I<5!|A10*q~H<{v5))h^A{(XUQST^0`v6y$NuUQN}E(sioKB;q&+ZW4*)6!!*@1|R-A_g}>Z0;p0`tyhkY4d}>?s$)k@cfcbnju( zu%rylYJxGR1;J=sG_hP2i2jcJd^}7PhhC0>(D_f{L(evFc|Abp4-0Yit5qOkzcw_g z^rH3r0lMYFAiZxoR6Y@hCu!dVoKGTLpXv*@W){E%^A3TC z*G-r`>H)aAUm{A+=iz;BJI@^c3Qk++3dWLVy7$Lkn6-C2Uh-TH9--e!^CTxI{p1H< z?kho|YP4WvsTA)ar zGxyr;tK>P?uT=1eyD;AV^pr@xS0)>>1_(a;f@0%hu<=A91in|pq-(+O@61j7;$(;= z52R5&c@X7f%L6kw_L7piPIKu=i=ki|=~!S>WS!gUy+vx+!8*OWvR(|9xt=W{f? zKQ7YcGKk*4LLb$o6Th%p2>No0kS(<&q5UAI8#0CT{3<}l?;Wt$bR1@ju0+r1gS1C1 z2f|?#H+RV*Eca5!_)%NYt4JMk+n0fH#~#6n^l&V85Q0*kNxVTK1!ICw(!XCez|>GT znA^(VQ!SE3`YW1>UEGh`T2Hf&ixjwV@%m)X`He)sWsab2V=F8d6$hV;jqIGNS7hyT zUsyi)5yr&R)t8L+X+PsoGx+61ek*Aa(BroFnFg!O`)UwlNl-Ix$ecycid6jlrXLEO2J5C=QgU zV)(^ca<+UO&zRavrB(Uvr=h=~IP5-E@5>>;-|e}5?t>~RZRYdB%XH*$6uGlElO=w2 z@bCUJ*wWcUd~f!U_3hK(ZavSWeyxuc4$}09p)9!Hxk1k^iN%^F34nZlyv2DeqgE=( z)PFvKhY1=&qk|7CA$u2$ zwkCmXM>y1qZKI;MXOZE+$*@j~Aa#=h+io}V=HnD-vQlKmsR?oBcaot*r5W0yM{v&k ztFR;c6cuxgC;$4h$)0ga%(%{KOr2d%^=&TEPqkX`?2b2RT{_Ns4r$YjP#-*4_7R2K zV@SBfdk~coLHDV*2~0PFIW0mUI~0XG?#{&R-zUQyo)syy;T)v?d5$d>mq2Q|HXiU~ zz;~}R+=^}_ZUNGQ_wpQUoRR_3Dk?C#dw|NcUjv<~AK>0>4Y)IWjncI>puT%OK2>NY zg2gNF!jKlK&pCokhZmtG^F;8$;T#6f9}n9+b=X`T8C11jgU*5@aIRbiw~6-A>X~k= z^%GMpwq3`+?+&2(X+jX}a(eW-!pZNO3pUB40Q zH0<%u@of0ps)jrE2zbX?p?$<_HRlSA+VP z$;9Q$9o#kgFzmSXk!`jYpt;9dJTBEwg=ZL%%iFIAQq5E`RQ?ybi?9OytGC(1x7ux1 z4c!1s$(MrL54S+5$z=4ENCT6KHu_d(BJcQVX5aca(4OB%XqR9mwX=Q<<)?k|k+UMS z`F)|n^Oob?);uENVn!||Xpq#Dc$^+94ewL02`>NB)ij1I{; znS#eeMYvnGQGz9rJ}{y4I(!)&1IPT|(`_}Pv?8E}%yBBkjM52o$DlNG&+r0_ZI?#1 zT!@iYoGNPwyIKdQNtz!{G?>Jnv!%2h8}8)GXFzh6Zc|E4HAe1#Z2?jZ7Ke$a~x zKa*KU*3la^ju7TGnfV~Hw6W#uc{b-{FM@44B+SwR5k-B_x?PRK))DZNZsvarjgYMC zhKZYhLvWxb1`ofcX6+;Beo_}G&$U}5CeKY9$;a!zpAe&VIgC!x!l0T_`0Mj$ay&Fq zP&U1R6pSZ0uj4g}h`ywHNj>z;=^gaV(Fd%grV4DG)K7r^hR@+&Xia4z?%A{ea$6UX zgz?we%5QRfpKv#BT5^_W=BlA+ax(P`JZaOOH4Be5Z6fBMK9QkyU2w%-93Cv)!b00Q zy3?P}u^$nGgRPN}JtrT_1Nq)n^=5&y%x{!*)&=!F>q%^a9=4fXrWG2tIPs}FlnD%= zO1K{8SSs?&6eXSqILbKp?IIgytZTq>G4q2zOQ#E7%UukCo zS5wzE?o*T`q(q8@gd`PBoOSPt$XG~*Oqmj;NrO2JLUSo)C<-N_B1vc6J42=nr6NS3 zP{@?b`tLmN^Zwh;@qX{~eaCMZ&d;^))jHSSXYV!K3ukGhLEn}oPBleo!HMOW)2oP4jEz~>cY>9bIL z)Ju-Z+}j(BI)zi=i4c)eX^|++_B+1yJpeJ0=kZiz6WQ8u9F&%oP|Mbxz06!`?EDUR z$I}XbbiP8e_m;uCXa~qyc#t|DD@5PUJ`9nYg$66MSfOSHEZ?#at$w)Bm6LYkp{ZPc zg?4vHcE1eV`pAa78?_a*&m86Uo5+NQj0h63x{^G+okw==9srZpS>xSj#iGsH8E|XK zZCW>8o6A+}4OP{Z;Cb#iNpgBYxUAI>ncW*?WG|CB79Zij_AD-M=^7~Y=mD9QLGW-G zw+25;z)T-h3YM8Wu-@?^-JyA!POG1czN1zN>p~`q9>>^%UTQGrKg+|1$xpcN!4T|r zw<{=bRbvY--=d9=-S9FSDU?$-MwPcqiI0>MJpRxRYOR2Vo%l=!wSP&wo~Y;c-K{1c zgwou)?f`^LIe0d|C;0kT7sR#9;_|fm;GXSPNVoMB4*PZuin)E9FD8`HIXYj+m^XWb zQ*5h6>a(9i`Kk$EQj~`Mo}Gi#0i6qm%SbT_=FXrO*!2wX^|439WlRXs&Y^v8&5?$B}Hx504rMGW_mA^a@o%4YG>&-#< zC6lDopF;=l9`LS58kXz{p~^5BOdYoXs90c!z#6!IWHVF;mSW-UA+*TjjnL!tTI{E> z4zsP_lc(w(nID@9VBc}6He4z zLcLEY!it|SM{Oxje2uI4?jAs&Chloz*$SZSZd43Dp)_dvzdY&0RpA-44NL zM!rO7yML6ayEc4Ca3W8m_R=voxPII#X+-z)S?a!g4a6qslKX~>h2hTiL^r64Dph9+ zAAej)PuG1Ty$`vPJy*x0|Ayp(JMKfNjh+B}u0EjME6NK-Z;7XkMH#eig)P`>+$U;g z7liWFrPQqNL@aT&pz&sI^u61C(q*WLaP$0kq~cW~y?LjIJlq?EA66d}y~|%MnzX-= zxYsWF)&Fu`pqEb=y@J8^d{1@ z@FQgH%uA>h;t8(XR-=)HD!A@-Lh~Qv*eQ;WXtaeLb@rKvrxwm&x@dXew{`1qypspH zKPC(FwwSPuhaVH!!9&RYCIQ>7$saNv^~RH?pM-@!xqWdwWau8%N^;PzC%dbi93GaM z3?DvF_}=w8XxrH1P_JRE+)+31(&>TC5r;|Uuol#LZGb0w8nZuN*8n>wgbs@HfD19n z^kZHQbnLbf@-_C-@x>QFv?m57hC4VjZn;;-H&NXZO=6J&mz`cbeKz56tI6q zH}3g<2z>PN6<*%?t-v;IK6~S$5!P)=AsR=yHrjOs);Y6Cz2k}Y{!g$wV+nB^_#M@Z zM$>*t$#^zKhRs;r5iaMQ;Km$%AU%92%HI7p%4o<=P|0+FIbHL>raw2A`NLVruJ6gL zT`R=dxgT(1fFt!gQ-=D-J1~z21>q^X@i5?&K69~%Fju-*!A0FTZk%c^46kaB0qrkB zv6qx^>5*8-Z0CmiHqVA1D+t89?SY1t%}hYvJ)vLFd6d3TM!tHdq4{MKxHeB6A8HN3 z{3>_sbz>#?d+x%#n%*$T^Bf&@#suA^m@BL_`}8Q6Q&ZFo?y3sVN_(R0ROXkTQ6!%OpV?9FC6%ufq-jB@Fs z(OgBkXfRrN(#&ZUmP&1@!d$&e^wA(0FjBS$-;UEUty?>=>fZ^R)J%lZhxZY;=Dtj= zdO1el*or+a_lDK$?o+3JcBAv}jbigZPi6aORN@HbAEHYJcd@**hD`3=o^j3Agweip zq5OCv?()-SYj-@QCTm)-wO`8b@=ENf)d?=@4Mr+mN^jLRz}fbdct5xRe|-1}?T2SU zK(|w94i~T_c^7&7HBP8E_>9ne{diD|ze!-tVcgzzHm1k5Lze-u?A9+{T%U3SNmFhT zeV?w*c(jnM(7MwTaP{47%MZAFq7P1aq~o zl)C2Nv?V`iqo)N%t#V*z?XknaU@jMfwHJB$U61|HB_8X|D&fbxWNF#=X4E*JZ}9*OQXN%ZE> zbhP_AAG@U;01Jgu%*$%PIIGiil9qrSRC!di!MvWLlXcahdc+S_%2U?Y$?L z{f4M`4`&TD7ouv&6xt*FI5MeO_|v!?U#!oj`Hk1;^RgDwp4%HGu<9)~saS#KvopA^ zixI2!O$oa8*Tm&ZgJ?zd8JPJ@PPpR49bErCALEL9(l6#opceX#`szgEk11jBNHz<1 zMeo4mA*<0+&xAA?T_fR*W3lj6U*@H2GAY{W!;Ws~M{|0-g()-r$dd+c&%kv#5E*=o z7*1S8&k9G1e1jIl2w!cuY`>R!UvCr@YL?Si2jaMO(PPnQVkaR9e~R%tC)4|u47I3U z3Ulrq0;l_ju}5k>t!YtbW-80FE3Tg-hN7`Jgu6B@w@<|rhIZWCg~gP)SVNucR>5Uq zUmQNT53mDH!{e&?c8v(Y&BqhS`Wfqp{&G7q(|Hrv95uoEgyF1vR+6wxZ#T*E ze1g(li}9u2H^|M*C!w+B*yVN_8lDV>U4BE^q^7RyiAWFjL0Bm{TqeZ~^iW5u%7t)E zy^PM|p3f@=Z!=Rp8DxVc2(-KY7=3P}F7caPB_+I-E<;X7^rGfhXY)P-UtX zbLM<9JbphK<`p$UM4B^Hn`XjJmyyE#I@+{wR0~WPdy|_pK#6X7DNa6KhcDzSU{t6Z z8o^1jsVI?#czzHDar@UecUle6+&Y4YsEs7msEo{s8bi;G7>R>6)RO9*N_2{KFg`8q zk0d4*+9@=_B-G(@{;9B+f5yY2-BO^@zdgG<%m?KCrlM01MYeP76m)#Ml`VUGUZni_ zwD9ut6nd<(7c{jXnththD$Lh`a(5|E85P6MnH!2V30)a^m)>BYaRvAF(qODU1cRQU zKZKr_XNtZJ1dkWWjLV`5dgz@yhBX%A{8bSJ4R3DazDagC!P<<8j#q?Yg#?)QE*X7_ zhQhMgZSZ4m2^^WG2X_umgNVCDkUr!-{?ylJ;zp;Cmtm$DJz+BVt59N=+JW65^M*W| zBgce49?eYP?zLkcQ;1T{$6hsKnP_gja*IKLc zThrpPb0XO%RSXNCZUfsn+@5_ApJ0KSDs#{@0AKWeLoH30371AYvpp^wP@R}BI72=Y zsc{d8Gi*V7r%bxU;u?vXqs4@k_oS!GRxq8?kK){Q+NjNTfy2@T7=9oh{mUN%+V#eL zu_tL^QYiG`#$@hfhETn@6{2yku(u(>6}l*Ue{i8=A4ymJTU zR!)DBd!KG>&A1>O*`=%hnHwEk%2!XIpIXHLfdz}1C2~wZ;XU%>@L22Y`P`_<} zowVNIkXJrnH)S9`o8Caid{>70_74j_I&pdT*2UrYX@Ruly8={*ve0miAq<-`U8FST zqiCCvfKd&UhRLN4%%R0aM~l-v@z?uZwWS2w8IY$u8l|O*e`D)0tFhuP?r+rsO%v zM%#uMcpmKqBfkikVa|Jm3$*qkJ5UdFOp?IEZ3(x2@c3xAg|EqiXI=1>Q*^;2_72T+ zxQQ+Yw3uDvt)SuQC$t|?fy0OR;?vXd;5)?!uW5!?}4B6)Jf7We{eRx--uHiQus95ZQTaizqj42uZU~gbgd_&~;2XHPA7Kn?6&( zC!};uh5gApsNLoa zXy~brjmftl=XomWY?lr(+}ghlawo{gj=Hem(<5+Bxr$1??LcNyE^%?wz?_fj?BU!U zB&vKBczrnypW45njeQ3&1L_3CxVt;{yrzrJJueAw?$E;aA5B5gbPj!UQUk2-WkKJi zkI;2@9l1T@D?IFEDfBH+U{7`4OR^gc*au6d!081}Y=6gh!lj#I;KdaUC<*Pw##tW| z&D&iBCUd%z%`;!qqNa(oOFuVU*|@*J?7?2l?ze>4d}_}uPx2%YuU^p$_8Hu~7XiED zdI<@n`QV#(P#9-%ldk3FkTyNI1U`yA+0yJf`X%QiS@biInl36LW8cR@fz%52{?xs2 z!*?t0P%I(B`Tfz|Ivi~8EX1pY13`9<3hpUACRA6}hf80~z*>Dg+is&j&?zct-)AXP z^2L>n8rDp@E!#nJ_FTdNo4Gv^xcO4PxB9WtI-AM3;~TKcEhWl~;PQnegrUY9OFZ>G zRP;SKADY*Uhh_Db(Os<43}k>`WfSos@rFGR0ZSZ8|n1n;!?VZ%US5@ z|D5(q>;wHGW8u-*bWzIrk2KZeCpRC$hwjz3!}Vb+XvoORcz*U_l6I>j+wx5oz6|XS zW@pbreX}|1E$YP_2yD*|TfPTcYrMV#_> z0`tiF9_>t1q64;PhaQ=M?K=k(_XYY8eT@4)yC%SnI=h56`(i-LIGSVzc0mUV zO`L!240)j?%f8;6hzfxpsg|tD=+~N_>?0)s;|SX9xp^9}ott+%Lq8BS)Rl?t%NHci zk86uud1g{VE>`VRVLtS4pnA>SAaPh{FjLfJb!F7pynq-`A3Gk*@13V_Q{r%J$UA!0 z^&=fHQJrl+cMw)CRb`%BzK-J`8{ss^VVHE*muTeJ!jkl4tc>^}{1Vm~b)=7h(VAMg z-FX}Cww#A$a<|CqrD5y4e4}6(x9`UG0&dSP=}yQ!z+&YA zY1VPRAt=-*V(}(h+&X13w+!*XoG-peMB>kTp{B=Rf+7KBEYlAfKAWOAr?lF zP*<8Q3S9AotlZK933apB5w-U)>Uj}FsL7*eVIeAeZ>1ySZc%d;Q)c9hez15rrFDn% z$b*|2%$Ui!nGgIQkMHPhZpBQ3X_P=mx6Umh=%afRs2lrQ_}qFDel1E6EwG$V@(xag`#--z&#=XtHwj1$6ttme5HXQ_2w@~Y4G!9;Hmb%Tp2roBuAZu1^ zCDzUQ?58e=VeI-N(C278%E)lfYhyk@{I_GI<0fD5{EDR4lGF6@gm8Rn|Cm^0+hMa* zF>byb!-jZYM7<5qacEE!cHVJ@TMNArx_c^sUxo;Z&DKHe{2r{neh#Y5?~MJfULYIm zCa}w%Pe#xBKCE$}875~XL)xnpVPp;W4Ey3KR1O$|#ij3X)4B&ZrKJ$dBDTW#<2R_+ zj@4{)O*$rQ>p)Vh>&dEfuc3Tm2CmJR#eSW00BmGUV6|OL!TT9+aNnD==&yosPi`)B zOBzTUY!k>KHF+}5`z!UW*ah3Sv0VRYEIJIl4w{XpaGdNFFf&tSQ{?4Xzjj;>?8p>! zJYm76A59lMxV8hg9?B88&)aDM(&R%L1tIyO%L zg{NFDjyi6Ch8{{pDt9n@Y*851yidGBRepA!k_z56GT&M?Bp*d$ar7draQ5>KJu6$6p?^ewRSa4$%g zdWpS_bm92aa9n3ofbRq5(d(()numqsF~->vo?LatGK|^52z*fb6I~Wbar@mUz>gy~*x&0qt|cd- zQ_Tl-;np{Pmg4di83JD9)}jcy?E%-&OzgYcj+{@^!^6=n#OR``aO%k`qKith!kEpU zsJT;ndZxz?k!$5y*#7w~UKJQa^z#1fjW5~F$6Cy z-cR~?i~zS|mBP*3y|(e1YEg6TMsjcSP6#=u#B7tUf~wWe@r(B{jB(SawJNgg&YMj% zYGej143x%gUAQ$Jxw&|b?N1U-(@?ZQKrX%vz_W}RYu(U`8E?NGr`kV6wMVO9%V#&p z%PYaootwz9D;rSimO141nTX%7_MtmBGPv$e0lD*Cp6PjYoM@k)s_0U>JZoi~!Hqpn zC%xkqVA^sQ{C2vY8VnhZ$vwj8g6JYz(%-FMcn1+=gj%zG!gr&aiw89H4}f}~?(o*g z9K9^LyhvNsF@3>VRNY+;Z~HW&<;-K;zJc1@TCS6@YgHaNX4l{omk(s@`T=ZEoj*PC zm7B`IyHDc4*zhBOqe#1?K{7aS|#*=Vcdd9SEsRHvgd$E#v~up zbkF0~mRQlksszxj=*V=Lb^$c6NHYfq$urdr7T9|4({J1u$bGvJ71{-hHYLh3yJQE_ z+|f=Ddb$(5{InbErd_1vf%m}e#cC+XO(e>fk8-&?hvSv;Tr%izJG%G!405A`E(-4K zgu1Mq5ap#zON2PBc3Pi?VT#|L(& zyobB{tk@l;Tz(2%gO^qPAo%ue>btWi)04{$p!UN6q~BkHh!O56dA-{*@D z>*7#qvp<|)nugb#zL6)Tb>Puc3i4MPqMFSxte$>YxO8$k+|f>l5Bob%GNzcmzjgqt zX_^!7{$0RI*kFPf2>DAwHmVFoY$>$W@ z8-J6%I;jC33+|KtD(YZkwOq8YS|57bpAl}%X`-t$reN;NZs6R@7CZi^p~iJ9@y(Z= zw9dG_8xhrv_Z7)*gCc{q9m<$6a+On(rDdCK;SO|%KO)hTuE{b_5 z%MMr*ie0}AMS)v)cKL%3ShDdBg-nHC>(@h}DOaG%P2S|ne?Ncoul4_;UG7ZK6lZ2p z+$3gD`3$DX=Qi^*ax&ArU>S4fxhs=+GLVsZC}h$qO_&Ea#xa|t^qFwuIn2>fkxWPH zG0a<)@r?P+h0OQYTbK<>(ag=b`Alc$0LD2%lUaVu=vVz3Ew%3~;;PqL{!{%1w%uRe zfLmYRPcZj?dO0rOo+Dh!h^yfsddikHt5BK1IKMT5+`5BMUT=k^6NfR*zJtl9aYx8` zHUy&1y(gxd`-+y2x(FX~4Dew~0(R*5j;7h1fNgrm$YL&s&edF95O|t{wl`e-tQmR-;i5h{$JF8$F6A>C+ms%I+sF=syXVGIwm{KH;3-B*yYw@?)v7nh4%Kd zjC*~e1+CDsFw}Wz9y!t9qVU>mi^S9b#?4E`a>E>53zdV4mIkrgEk=BqX5lm?&f>j~ zh56Pk5f=Gf11($Y|C$te{`2~C>%0Gp`v0HTe;fYa)_>oye1YEN9b2z*94sRWnWd-3 zlgn?9Fn$JU?2qND%&RLE>~XEhs8?&xvVLC}=O?MmgeMk-4=V%MymO~%{X;KCZFMmF z_4RP#kNNCueIa{JTY(+%Ae~t>Zat$|p};WeoeM3tZp4?|GgsO7ZfqWRZ#Kj@fU&=B z#nkw{Wg@(cnT0=(5He7Xxjy3v+u5-LiAq_)x^C-;^GXLX!c=AYVRb#*l9DB~J{^xo zngiIVJyL}o65F$;BWJObI_9w<+RBV{lNUxd7qYr7qYKGer9$lkM_AQuiTFH5$gY=8 z!d?SZSe?&D*oMMDhIw_Hd0yL*l~pmtC3m~BM`cXe?qR|7*wX>*fm;c9bU+7oT5K%3 z?KNbTx~^knkCvljVku32C2g*DT8+88H<7`!*{q`6AV$`^N#yXZnvsnNAy2bn8Tla} zn6NK$j6b(O&?k2hR?eJ-DJ4bB!#fU)U$Y|0C?8>7Ec9l|+7G~wo_WES_*ZlikA=lt$UjsI`t2$oBk-x5Y5A6^6|7$w`e>|QM?|9sNdV~M@diVSF zFk@68uG@JDk15|`y6o3vu1HP9NBhhD92r9dbBHJCD6! zFJP}<3MTq7QLI9;5T#_4nZdPcq_*2N(H51LXfWg|+{w`b-xZ-u?=Qi4$3Y1Sn-@S; zQ#A8B-3u3~Ws%MsZ^1XS2dElsIXXL9m&qraCQhLT{y}XkA3rN{X-Ay6WWCWfuObg_wE1J{DFz(TrR^! z>c5WTp?UJ79CwV?^5^3y2;i@F_gUuY$9!EfzX2{a=0l`bHy08t9KOGBMOQGc`5QHyvqe zXka{Iq_G+Imca;P0|O%?GgCv;U*7`<^Ck}FYS>zACrPzdRv_2fSlp{lppcYdB@nch z&VRkt=J&H&Z@HVNtK*u5|7!Bz zkHGkP)c@UlJ$Xl%Htz2uc&%~sbaYy_kZUog)vn7{ulfBT!Q^Q#Sq^S3U3dq%{r5o@ zuU)gu&2#B8&)?Y_-@?W$YRBE7aHSKEwIBbl3jF%W^nVAp6@8D;~1YeVeusO@0Ttgmx<>gIPR~J01A?Ur&pvkqqkF zwvA}^JLnn7T=*MQ5VU<|@jwGHb=o#7pVXh$Hl%@=JFiP*Wq)02xO0Y2Ch$oyd1Mso zeayK^wiZ6AXvd2wW{;?9g^FY{icgB^BR{2=tYlJgCNHL#KjcBx&I z=FlFiV+E4Q5*|51%%LT7j?9-#+AeMzbA*^fs&&UuGFieW|A9lcOL#HG97;)A>m%qO z5VRJ4+a~ZyF^6I&_EL1`z}CVi6<6_MiaF$6s_!qEEaa174khMC?2=6SyYOO)IW(Yp z%@WC^xhszpbLh|Kr(iXY6mzI^$j>y%Z9AJsjudm~v%`b!l51Py-8SY(F^2+Pdd`qc z`up%mF^9&xp9qyqn)~udF^9fN*}RZU3jBDam_vVV+d@7m=FkRR^*}}L?y|M;?NeRL ziz(*N)lRNQdUMXU7CyOu1CJDQ$RK^#0?9FTH}Xg^hl*wAy_VcU`~7*Om_vFRB`R;Z zpRu*@YwN$IEomg?P=3eoQpqt3gL$NwLwy`3W=JOexAI6ahrH9=c1R}8LwKZ^LvkN? zbe2pCw(-b+;t-z{bLh#12`&EJxPA(*@Y_~(J1?e~LwOE*+50(vS__|4+`}Wq9QuCF zBv3N>mQRW~)Z{$U?+@f&UQ98EvSYuv|AE}smNXV~=+Ecp+aw+-=8(rA2O_y`XD9PW zF^8I+5}YL0);60*ia9h{CB$Absh`6m#T@#kv1;ib$df!$%po09-JgFTPw_}GhyL8Q z`nfz(%puDo^OeoH$MV*~w=aQDia8XN)9vA4!CyTVe9~6Liz(*NpvHOYCC5C&BTd8{ zDldAkAi0HXFSLzmBIZz3Qv1I9Ww^79EBxB(U*wTu4jBgQ50M;G{~C`JbLdp;)~A0U zi+QA&LmB-anEZjf&LhPff{zC4|3Kd0k^jV@n>@&{>ZJEy<+229FeT=+AAN)t5(#IiyswK-!$suC?&(Q{}qF{@t%S+)T`& z^Xq51nhFHJ61(%s5?vlC=Ft38W;K#yS`XuqVh$B6+1N;Kp%OD5Ddy0Pf!zEs?wPE$ z@N4^a6ps{hNakbNPRTL#$M8rohbHLkQIJf!kL8hK4&`5JP?1b#S@B3QhuGB-YLdyf z<9Osha7f>pM~XQVMhw^fo!`H+pzSMxM;hphNi@xQ&!oS*KlrHPmbO6+^u;XFe7tJB zWYji*kBVtD)aU7L$!HWeQtec)Dty$vg^!Ba)OLahAJrE~w>@7C#B6FiH-nG9 z<)h-A*MB}=v$(;THdhHlF`L?s*z=>RO7l@Mo7xV}^HIh2d{oS)w&T=%bkT39m`!bm zruk@;3_q%vO>M`P`QNOSf1`gGRz1~byjQ*L*M?xa?7xCa9*MS{BrB`?FF>Q+uz#aL w|N7hCfA-P%>y6Lc;aXoD$9??^1S$jn`nS}t_hh)oK7k;J`_=mY|N6iG51UGD6aWAK literal 0 HcmV?d00001 diff --git a/model/config.json b/model/config.json new file mode 100644 index 0000000..f1360e2 --- /dev/null +++ b/model/config.json @@ -0,0 +1,33 @@ +{ + "seed": 42, + "data_path": "preprocessed/dataset_al8.npz", + "save_dir": "checkpoints_heat_v4", + "val_split": 0.15, + "batch_size": 64, + "epochs": 60, + "lr": 0.003, + "weight_decay": 0.0001, + "img_w": 160, + "img_h": 120, + "num_classes": 3, + "out_h": 15, + "out_w": 20, + "stride": 8, + "size_loss_weight": 2.0, + "bg_weight": 0.05, + "resume_from": "checkpoints_heat_v4/best.pth", + "ref_sizes": { + "0": [ + 75.35844421386719, + 62.14570236206055 + ], + "1": [ + 49.79265213012695, + 38.633811950683594 + ], + "2": [ + 67.58988189697266, + 34.93575668334961 + ] + } +} \ No newline at end of file diff --git a/model/deploy_README.md b/model/deploy_README.md new file mode 100644 index 0000000..ff47092 --- /dev/null +++ b/model/deploy_README.md @@ -0,0 +1,39 @@ +# NanoDetHeat v4 部署说明 + +## 模型文件 + +| 文件 | 说明 | +|------|------| +| model_heat_v4.py | 模型架构定义 (PyTorch) | +| best.pth | 训练权重 (141KB, FP32) | +| model_heat_v4.onnx | ONNX 格式模型 | +| config.json | 配置 + 类别参考尺寸 | + +## 输入 + +- 格式: RGB, 160×120, 归一化到 [0,1] +- 预处理: BGR→RGB 翻转, /255.0 + +## 输出 + +- 形状: [1, 6, 15, 20] +- 通道 0-3: 类别 logits (红绿灯/锥桶/人行道/背景) +- 通道 4-5: 尺寸预测 (宽/高, 需乘参考尺寸) + +## 后处理 + +1. softmax 通道 0-3 → 概率 +2. 对每类找局部峰值 (3×3 邻域抑制) +3. 筛选置信度 > 阈值 (推荐 0.8) +4. 尺寸解码: 实际宽 = 预测宽 × 参考宽 +5. 中心坐标: cx=(gx+0.5)×8, cy=(gy+0.5)×8 + +## 类别参考尺寸 (像素, 160×120) + +红绿灯: 73.7 × 60.9 +锥桶: 49.4 × 38.6 +人行道: 71.2 × 36.3 + +## 推荐阈值 + +th=0.8: 精确度 62.9%, 召回 88.7% diff --git a/model/model.cpp b/model/model.cpp new file mode 100644 index 0000000..601114f --- /dev/null +++ b/model/model.cpp @@ -0,0 +1,13 @@ +#include "model.hpp" + +bool model_init() +{ + // TODO: 加载 TFLite 模型,初始化解释器 + return false; +} + +void model_infer(const uint8* image, int w, int h, float* output, int num_classes) +{ + // TODO: 运行推理,填充 output[0..num_classes-1] + for (int i = 0; i < num_classes; ++i) output[i] = 0.0f; +} diff --git a/model/model.hpp b/model/model.hpp new file mode 100644 index 0000000..827b2ec --- /dev/null +++ b/model/model.hpp @@ -0,0 +1,11 @@ +#pragma once +#include "types.hpp" + +// TFLM 模型推理接口 — 占位实现,后续接入模型 +// 用法: +// 1. 将 .tflite 模型转为 C header 数组放入 model/ 目录 +// 2. 实现 model_init() / model_infer() +// 3. 在 element.cpp 中调用 + +bool model_init(); +void model_infer(const uint8* image, int w, int h, float* output, int num_classes); diff --git a/model/model_heat_v4.onnx b/model/model_heat_v4.onnx new file mode 100644 index 0000000000000000000000000000000000000000..8927e5a8d7e24ffcd06c7313f8cb43c5a37aa694 GIT binary patch literal 120667 zcmeHQ349a98mHxG33nd|RvuOqC>7G?>Ve(e%B5CBtbhkf49(I8+9V`t0dF}35l<9Q z5y4v&Pvi+SyLh00ii$iuQBioxQ@o$|@n&{scV}len@!qq27gGhnVtLl=0D%}&402j zIa$G(kwB=rHn)S_T4uGKT-{)^mkwF?c$Vdl4wkk)f3P89=@gEz_0}Tmbk8?of5 zzPcy*JmH+I8aCnssd78{176lWEZ}c++g*;nZQ!SZj+VAHp+G~hSH_Br%z|!~HbIX! zT#+IEw<05}pob;f(+~-`!SlZDMxQ-m7?M{H>QLvdWjzshqtiOt;|~mHBd3F}V&jbn@;LUo=A1AKM<<74uzja zgHLvEq1z8C*2ubrU)}I$cO6^fi-3>rNC@Qa^VbZ?^F&y`)l5>Wm!0fssEbsNx1121 zT4N3P{WHSVAzv_J4YAWhpu0oX5U4!JtDeoVjcf?Ba&6A=M*^_x2jx|<^?^qA>>%ti zPu);3SR+G$diY!A)(lG@n6cOyFneotohKZ2*ZSCy2TY2YIS*w_7+}zw0|w;{Fx8d1 z33YoBrcAht23%aZBGYmV(U{3IK+k*GoVl6(%=CBOkh}^0hI%*X$55EEU7SbdReS2{ z+>;yp)v)&_L_8rd%_-Df!LT*qdS09lvIv8W^ZS7b*J$?+%Ig<&!zt;uxkd59pFq(9 z-zP~aLJfX6hurn7$FKLi(Gwb!S7fyf%CoV9i(CT-0hf2elpW{U;tigt;s$d@l;QRQy<9X>eeHDb!=YW!rDMRTQ~;% z2?c6Gp8CRYy(bi@_JrKRJPQ}9r(1Al-$8kGKrr)49E0+F{=CV75NMOvk_Z0G06iII z>n2-arSoSDJVkjjsV-1G)u!{z4xWLRQDs7bK%}r9NG2E#ug6iy`WwTA)eT;c&2BHO z^GzxQ>ajN9cUWyjg<&9ZgMp5j>ZxJFg~BW-^!s6bp#~`gIUo(9)YT zRHb+qw6x;2>nL6ikiZIDWZA7zz!e|*(;O)6CzQBPT^;gtk3Gbbaa z(wfo_rd8`CyIGxt7lY{>v`7yk6+^j3a&g7bM@KQ(VT)iXpb?)L3;s)K!56jFffIae z_F6wQ!DiY12o+L6auIz z&PTU*x*Bidk7dw_Khz*ky&vPi&ye9NGge$>#C+j^i=Tj+QGGEFN!>QEHmz@?DHI2# zceObbL20rG*{Owgfrf~Lk%QCo1&!{V4iIo^0H>k?m1XBJhQMF6w<9lfZ!7=O6g71@6!FXTk z;QQhh!uO=kQ}8|1X=!|ablWUaf$wK`M%Mf8$gCEg>I*9N`(yQ<5(vLcjquA32*STb zWx=1FNm}RCu^nP7$TYYmS+d~6<|l~pg&u2RlyV5)~`E{ zEbEunWh)|n`2Ukp>jzS* zm73{z6Qv9cHA67%hGq#V2B3_LJ8>B5kRGHC0i}Q@EY8%tg}d~A&N!l6dI>0ibruVp z%9eJGo;tU)ET;_&6GTy4@MB*~73*!NX3qkj3y!mN_Xh$&_jF&R*3H%jBQxEe8Em*$ zD;S5-#gaXhWrJQ{eOL(Dt$bDG;EJ}GgDcD?3c^@xku#VdO)CSBYSFN z%^2_q#N@(;BhiB&t)NYno8vpV9yoYTu9$6+O`1|e;>j~irxs|_u?A8Rm^g!}H7IYw zU=T+z*naV#ys@DMmXzl)8p*`HU3OBQB@n>khyV;Q{0b`o+PBwuwSW1@TJ2r20<;9j zJ=CZ9aN#dN3qK3L9W}0eNiHx$pQ}h4UMnyB9;6H0p2iwCeA(`mBHV=T1bqh%H@L&T zOWA>zM><#pbt!wl!mQOM9eC&}PgL*>g6f=X5a|G-x7|*(Czie*kUep#q79N!#(Mi< z*csMgLI=U1XrZ5w3KqXg?v~1p@fGpi2Tu`W?T}Tkx&c5zJrf&HEzLkd{%&WIT3B5g zri-C=RP6*={e2*O3@0q9sK**A>SB|MTG+UWb#yyHU+ghf)|=AG`lwOXg6t@o+T|=Y zT-w|)y&E0vP-$uDP>i6mg{f@$uDwOpzsPIjz`Zu$)L9i+Dk~2qJ!#r&BUuFDVlV5- zBO)qmUTjTSFGgi0Yf{7e3R9AjW@;g)O_+eGiqi&~r9L#)ebKb;J8E=aD*QLAJ0Q!I z14pP19fayoBUG0fp=!=uq$DouP}00Wq3RtSAQ7tTh()N+#@4%c$_Ulf(g+pmWDpOF zdn;JC13%*`ZmQg2_&9YK)d8V9S_xcfjGBkG$7zFtaA3F5nj(z)tAbHoIay&}O?|-U z&Fv^S8PK=BS?7w6E4Qhvs~Zohb=9e(F0lm-RT-Rx7FvXqCi*7h)kE9Bs%?(Ey(bz1 z^o60r1SL;WcM^qZk*iCCT+cP!x4TU4+nunzsC3Z8*Nvg;<7w!6bVFB%t1Q;$T|`!B zDoIoZyV{C=C`s+*w61TcLk?E(sc-AE8tPiw!3y$~ygUtc2iU<1%0?vuVY)Up+N$dZ zQYNV@lrk_iA$Vl^q24D=d?ul_Zs_FXJ;N!zSSh%E&H=9a7H83lM^>RIg#mU zv1&!1-(o8|MAgO%w9Ja(1}nMda2%xUh)4O;*vy~<&29@@Z;ejv&5A8KwW589Fr%A} zPKaS20%NFIU`H4(umfT&u&@BQrV5)LXbInHOo{R6AxVjm^s(b4bha2A8y*Ji-3l#Q*QCiW3~14kAin@s>evBA zV(2Vvr;Y{!J8aEiE#-xlJ{%{hHZ#YBqY@spjXO-;zI5s>oPRCsr8%GC3 z9G$GOAMYzn$0{&K1EDa3cl5Fewuu!!__b}RObg!q!5 z6#{#=z1W!f_#pCMn9{rno=X-wMlTXjS%5HR22(W2Zb?5Ug8S0^c83K2MY79FB14TW zKM3NN;1FMz|HAIp;lDr+V?q4X@L%AI9d;I6lp~1v&2)tuE{17{e{?T~iiT}2#CIWx zUyMWi;uJ&tWEL9J5WiT@0DeS-QpSh)#Yy^^;z4|^OFB7-Pij2{;uohO{!!2BlM0A` zZD$lg>9mL(7j81Z35Kl>%U#hm`w_rG>fh9i)5)4x?AGSY1TfWd`Ee!P~J#7Z` zq^Hnkw`G?Za5=#4nN61kQRNEJ{I67evV_+ zH&23rLw;BWX4i*b6R_;V1u{*70bzfd1Op3SHGQ$m=Mo7o8#$FFisj2$+M<2RKwqDG>vP7GXH&IH#bQeU{ zZs>=U&E=(J$d=16_@pNmd?IKQp^Bg#X+n$`%HS1?MV!?#B}O}Va8~AU7r!)v7UOkQ zm=|v*%*$9hkf%4nlh^>WCPRxMGr+@sIMRqQZi+434gJJ{PjZVa^%f@Ef+WTx$4G9Y zjGa0ZhZzC~vHn2x)ASg^&1LD+EaAeG(qq8mhvKA@{bO2!3}Jo}1Q`-(Br?(;7}Cfj zjvuB>E$i)-VP_Bo8D$6(iTxz+a*qIl3{%Gs%aYW^>h8icvN%~)`$Rp846sXVK1GIV zYo{C%7sUapYiaTWg`K9zNGojRzR;8%Kg1|9%8*~D1o!KJ>p7}Y8M>7WfCVZz-q8W! zx=(k>5$o59PmxiQq@s-B*O4?+3k7bGU{&$zlmOkArpQR^KBW6n;ox~%qR1%0F)Bfk zAuP&>BBMQ;{kEdq&VtoT{!X6HNC`;>I3$f-TfhFG8V^j8WY_@rrr>E1d+JDnscU1~ z3+|FxGHgXjs$X?~VK`N=3aUbv1U?Lj^$K%y#G=UxwiG)yRm@3Ji7{6_YvQrtdOnmmt&DN8YT^AWLZ`4HL3-xG-t_Br$1}A`^{6he<>AjEKLr z+tl&5nro(eC(WeMve!%lgGxLm4cJZ{9R#3k3?>bsWAyxq${~=1kJ(AK^h5$O)5q+Z zf6Q)O>3A!~;r6E|g z1dA7x9oga~3KINkrZ3#kchO|bk$88rITE$^Jk0*{M>b_^jcJdp z6up82#G{2wBiYauyst1dD@6y}Z5l*vK7i0j?pyZKV7sR%k2SvMi(&0aNXJM*V#`;bT);E9A1CI4c z-KSuEA*Lq{_K$YumI|`n+gf8ysj;NLv62EG8oGB7j0C{(650MH<|!Pp?S>_{_+Y5fl38VUb@ zGP-9TbgIg$a75d~6n&e7o&U?W776oX8-Ws$T*Ho$YuJ+{*DzjwU_cXq@`9lPd_KUD zTuO;RjttM=3-wGg2t_Fc(_d(31uP9RrY=c7m`l(oLLEUvmKtA)^lL_QuSC*HpxVoK zfIWZO>cmtCTM)m7o#5B7Bgd9-2-kjK`8A9M1o?s!Je~-kYf}6gk|@G{IQsZC>}mlw zZMT$q3lnca7F&*ALxmWW1KZ*-L$n}HTp;|P8>4~EM;aP9gl=*Ikn|9X07xmr#u|xX z!!EnbvM!jv|3hL+dDt$+BVoc#e_Mwn3#W*3xZ*Hy{1SSZ}|Q z*4qt{qb71oPzB0n&gBIBp+s;Sek-~grgx*zH!-4Ykhl?+=Cv4=2W|=*X!)(Za(+?v z_t;ea9$?C>f{|T^lEyUe?*Y11*iPauj3dL}6Q4xgW=j&n;+=)5OIbs;kh=$?+Ypce z=I*fpCHRrC66DiL@F-G(sqp-)?I2mZY&d8oC^v+uNm6dO2+-PsMCt|yISwTi3=9<- zx+7tw8U~ghySGqM7ScsX;`bv7wEio$!+n`TxsmK`LhAm)w6JI^R2^f`<=g;%j^=Z2 z7@=0-H+h)Ts1+PCz;PHHr+jF8EI@7u7Jf^k*3fiM$SWMlz{`jg(np6J*_xtgr-o1jOTgf>Ud(q81ML{WGl9b)In8UF%~*o=|n|%$x@@CJay? z<5TgS3#LMF`Ei}Qmi0v3jZW*iBdXZ&@biYk6Fcx%Jq@op-KU!nTd&Xc)zk-kN(d^^ z5TH0rv2G-5k0px3G^wn+GJcP+N=EmOBOhrM&gebKH`-WY!0FN|e1}7~X;JT9jhQ%C>eZPfyM_vu7Yd37 z>=M+_9mnP@R9w!X)catb8)l;;7>LpD3P(& z0sPnv5l($F4)mA={03wk=nZK%kP^U;9Y_~N$vohP5lm^of3&ZOieUw_ft6|531u6Y z@PZricjQ}CfZrhjey0lXgJ}7b0{&zc9P@x*ifD(HKY6KmA--e#oKh4OI zsL@|xMh?e;W#ljx5NTmxb+DEpKud~|LlQ-a zW8x4G0+$#EPW5_%5nm&FYGciqK%fqzBbFKh#KMqqM>wfX2)JnsBNc*)w;+ox$H;;E z$*@z6PJws@;s>$*pp|Jx4*b*y)UrqM85v1FFx#N3NP9_$Y#j6;IdXd%YuxZr z6JjcWUIo{QxWm3n*?|_BkwfvEX&E_$8A>v8lo5v;4-9*K5{Da8rkeF!W^hYGGIB@^ zmEv|swqPDLj2y|*JgWN()61fsRBakr{VgMW3^$A(3nOB1*g3aSD{X{U^lqfGMoxKutL5W-NE${?=i)vCFjUTN8#v8~ zc{CvPhK{47`HUP!s1;}AuotCKYnqXRxRW$xs1;-6uoo$e91en!!_h28j+ALmkg-N{ zV#^yMumE?y3PcvNLxf{Z3dGjbTucjSD9_}h2|#~3+^ z_0AX`-i#c@>J5$Qz=s${C1LVw3`*u1Iq)3{ECRv|af?(8L@Le5VM?U(@(?pg3tm=) zAwb1=-C~R!#mHjg(qZIKJtJdv%ha*D8gFB1(u^DiRH{iF&;y3+c#IsdojRHbz}gs* zx$?Voe}67am$qAJ7v+@r3A+G$Ti%!MUmfda|>&LqHSvm;7@3gA`f9Zj_D?3$yKfwdiLdUc;;0IO` z;S6#jATWI}ulWb_T7r=y*;C+&jI|Enw=3Rimp&s0dQ1X-14a(?hO`?<3E;;LrHi5j z@xPhA5HD6s1OB6ZO;ijkm<=o$Mh>UUKV7N<{G}-d{K+gh<^g}{(G2)YQv>*&T7K)~ z06(exFu-4$2K*q}=V(`MsQ~;6BS*1CWaMyJ1$qe?@{5cd#8VRVyVRgx!@He4BZq;N zKM6(-Q$`oq{sis(LYK8P@CTJm1AmQc1wukiJeRWWW5g#gWx^c@G;K>TawK~czzo=x zygE9-ABIUF?roPup+N?!%0H0cA5LO$?n*-Vq`jZ`InD;aJR=8g^nztzHh)p9%x?nV zF@`iFhqz9{|EC!_5;giOj2xv3BZt!^GIBUEMh<6^j2y-*5Ingq*?Sb`ipo&j%izW| z^Da0+Pbwt>IWj!4FVs_wr%eZ@D5YQuObj7`ghG-b-RVj`%u7%yLLEUv(u^E26@tXb z;UpM2oH!$g^T0B47z+rpKPPyI5un$k7&##IM+gTN)mffi!qNY;2M^%f@H zf-JTiBZmqyusC17=x?S&SSh+wOyH zyvBozEpO+FOdK*JhqUWQt&%}3SPc3Er`A}-yaImz3~P0rCmeRy`q+>sR9!nW=Yd1w zDk0P$XqXiIEJQT$atrCx0LaGN6uGRit!4rFmlLzgzzPKL}dm-A5kU5;kIrPrTOb7&IkcBH(ONu-Ow0{?jI%kCDLz3h%4 zL^6$J5~(Vto~1ofv0!f!XPo-d0{NL7P%A&t#L{Yhi4#U!ZAfi4LZmhmGlgR!eoBNW z1F|+f*jiIcIO3_E>W+jUa+uc|g<{kO>e<3E;7=$}6Y|s-hU-0{NVO;A7MOFw5ZJSI z?plB++>PKy?U{X1^koTP&-MB9CI>>(Js~d$?a0fU0Rlb*UJ9|s`7=@z@uAFer8WmQ z21OAkrA9WhC)DO-V?n8<$XjW*sn8!da9ssf|H^w*diR!8=v~uJNITHbg5?8;K$Z8$ z*KF6MQnO*}bMr2Hw%gR3E7PH{cz0kbM-G84)xg4G8cBr+-yNfq{86LNNvFHu-b}%l`_H( z20N^&o*Fh>C@h~iFEcjDFoAc1y9Wu4h+yhSE1VS4#ZMqMt`4YRN>G*P%RtNLSrQ1e zS-Mo$0fQ&&@k%!+cak5#O!2I zUVaAW18Jx^#ZaI8Q`9F?4zTHBHQaW{LGy8@=4~7|Y|LyfZUC4|UrNLQs`f( zLmvbmq7z!@G8CZC%v*m;5C>)Q@U zH2AlmgQbmUhA%7xiC0$OA_xLh)H^b@!56%YP&xP{FQ4P$E}xFL%clVKu}s0#xh=N1 zT-pyLRRd_#dwQ%8MMx&}6U7HCQee+6eJ%y7fQ?-K1{%sk2ekZoBA^9NWN6aji`~r` zhuUJ7W2yJ}{BE#Q57rjAv$L~X!~eQw4DA$-u=TRlaLS36?79HxNMFF8(^EZR1fROs z6Y)&xY-tymJUPrpa@sgbokdeRS=!aH{+dW_PV3TQXE39{0}9AM1>^{h0vk>hY_60J zaw!?ABJ8E5por@1u0kOhpbb(H7&)1_B0$AaLs}P?*ztC_Y<5t{WULU85W%JmUSC1RP&*Oh*p7~)u{nET%{N!D8quuA+ z#dmt@M1DYS8@}}=x6>ajTfn=%e43wnP67X)zySWti!zy3ANJzEt$!j~`5<@7gcalX zi%#IP~*%RIj01ioG6 zi0IBCIs8>`JjWlqd@(otrnU@~yOUniqltOoz8&RX{Cx^De)KQV@$dHKofnlbCBNC2 zr|v7``~Uqr-O=_vo%zAm=w0PIxj$!pO|R|UmV5Dp&GhnXJ@g+{VSe$h>CC>&?fj*W z1?kCmtl{e3Tftp)LM`QLwTa&KVHWfGamVt{4m*x2$j@#AhPo@7O+x3uMXj>yr+@6E zmS6omb^dRsagTR8iz@)V*%kDsrZ=TXM$ntT@A!9gkMj%a`4hTvyI1|%bU|n(H>}>p z&Fw(>x<+o{XI;3J_we*5gXeLP z+&`kbzPUcS?Ood`E1z&Nw~X4$z1w3HH_)-TY1*{MqSLqklRNRtRdlPJr_nFm_*L}x z&R5YR|6=L=)c57Hrr%2E+;a;x;F{;@PM06U%(>+py34WeP`esli*9eMqkrE>b5FKg zN(c7c$G!aa&GcPU&gQLW-bV8?&*S#|l}o)}QA;~N8_X4)pWRj6n_@_3WySC-Z>RQt z+Lmj)?hcBIoXkCU{0G$8-Gb$L?~S6byTeBBSoL&t{XCk!e&~<%*7+<|zSY5UDH zPzl$~QRGsMsaUu98QHznl|z#(e3G63r6sx*U6+xaudXSY0V^_AT{4Hu zpZIQ5f$LLh>JOPsKRz;++P-oPb==Yh`qVj1R2jdn{KvOnpt^ipPmh1UB)aJ2h0$NX zo=%m{y@DR~?FZ2Z=QH%q_b#K}8u{6VALebPaxc7$y5OQVTy#jc`EwCrrYUVo#s(bboWye&dH%Ke_|0;H0U&L%f!#AkH582UvBP8o%T=;HLG$v zebdE{M*rP=DV#EJB=ITZY}S-+ZGd?Ps1&HGO|uv^P@|eg368 z%dZ&tRr%oiUpnQay$_fFaO&+;VObUjYF-NJj?W=z6OC4VHGqC%$0V*{;tli#3r9u6S1%f}ywb*9cHWri z*hmF+&2Jab#eIGBy!vALoL{{3pbxC{gymUO!{1AyPb|D7x@yP0)g=;4y{;tGlhoj6Ysy}qHn&oys7YZ?}p+>xoDs6t2S(W_{V6$9hun`^5|iQO#o;s+Miv1_l|AUNu5_l z+b=nW4(>fBy0Z0H>V&zi>7|$FmRIIgM;o5#O4t7N<&bOMZXMmZb|!a*r2}`-tX%rz z?R%)(K7N`Cis}Hb=Q{D zxT`O}XT#3m$>tlwWo6chtYXx+A)6=O${`vN_xj{`;H0Tjy^&bHzp~xaX2+ z!6g9I_CgXwn)=NREw^_R+kY_mdvd8g-L^Je)8k9dHgF5Q z^XZf5>9yB0y?>p{?VON9Z~SQ@{o#+dF#8`4bC={kNp-s74f^-854c`)ho17(ErXb+ z-tNdZEPa}Gd>P_O8ee4oJmU$<*WFT4aPPO#5@r@3Uc8?!58uk$&T3$0tslrOfALZN z)#2aJ1%0wJ!7L&l@Q$Q2Z9-*zx=@8aRA6AgqB%rvO)ua;er&zBjXpyK; zEuu*MCb@{(!5P6Ke}!~$vgH&z)UyGVQw`LJ)E+W~E#UzIixucKY-$&S ztrid>D9l+y+ckPX>~~pZ*T2!9ztF!0L$b4hu;-{OVM4fEW#0Rrox`jOY^I-^^*3|f zXOHmTc=j=0pU}jdx$ho+)%X|r0!DaOq{3GjxljiG%dql4{se3@pHAY}mUd;XojHPk zWs#fteac+=vR8^3V2p!1aVY~#;=~LpTHSs#y{n`nKX=xf+$WFR#U20l70l1?G5o}L z9;NqqJ2MZweKGgd!>@2RJ^UCwHm?)UJvEB?vG}2;i}vj1vhI9~2F5s8fXLiQn6FR~ zzESPyU+fk9r!)S=*?WG%*{dGsx1XNNv^l1Tx?$W@W-0SEH+aW=^hvW{pvS+vnjiVj zO-$AFE16c?=d5eHow+~{v zluctcGM%}_&*$@Nwq^6q?E~rH<2Uhhwq)|b`&ZW6bKVlSz7`eF&e`I&b9 zwc{4je1~Fw^}BoNb(D}jW z^IX|H{px94o#j*N*~=WvNv{m!FT6RQ&#mpnX9lKor;c2~f5M)~=iNRc`uLign8>3g z)QmU3rjNaT15N!hjj6t;fw%nQXL|lG8@a9HRuR3V+OVP;MJNB*^lA2u%)%89(64lx z&y3`E)3^O^D0fWmR(g$RH2?0l0P{K5nXwG-#0@EVio5RQZ|Lu54B`Iw$OPue58vb# zZ0*M1Yx|k*e@7<&M8yooKYAB8|5hin@tC$v{Tt5ZZezh-`ldxphaX!rFV(h>7HkwZ zbmF+FR!Ff%D>5ct)s`ETJ(gcPlbjLr7`44LDmah3E$d{6L>!yO6r^^7YKr5j*G}uVgXVO~d($t*>n;aXk=yyvIiB zk~4PGH@tE@vvcR8O_6@Ta#Nx&a|JJmO%Ml~SbU{Muv5>W0~gjs>#`nZn9BbAlcOJ@ zmoyFJU;cPAy=;93|H!EO=@~OFWTK~KGB5p>%U>J1BKpIpOX&^A{6H_ARKfjl#cVEY zd4MYq%;!80yc&IDy@O}>u*}BgUr=M`ZQ}O$%el%yH$^M9Hl0$i>pkx4HJ9;SF8wPy zaN{F%|DKod=Z)yXtgg$Ycfa&L_u6-3naFh`nO(En@I5Y^%8c-z%&W&iwJ(*LF!2eF zd-d#pFe6U5o$t4?p8wBnA%2Yi8E!uNI&$w~1Ze*5k*%0OfP4o=k z+6{B(hxy9>Gr7U<9Yc?PXEisbWI@wpsulD5%m#XTQ4aIruDiHz_Lb4>m3`><8s4OA zYp>_Fop%m1uiJCXf~>dcj4Q`5v%ju?uKCk6U`#w#bvHNr0TRxo| zb$KQIbN{8x~0KiXv-cQx}F{ZVKs{X;^w`&kGrj?h}jT*o13)zDQ0=r$fk#%JdXOBoyR@e_Cxv#XM1LQ zm;1Q?uD+aJyK5>vYs*Nk=IM)=D=(YPExc?w_wfun*Qec`)F%^N+$EJ>`mZikyl-wX z^X}Qxn3qE z@5|9%t7lQq+)~WHHs~X+?xp9c>pvaJ96P@Qb3xI|ob#6se6NajjCcBCdi2Nu|9V9-zDaOYIiGj!8c7_I%~kO{L*v& zWR}m1M(ytxFqONn=0?6akE=X;ZM65bpEFy_UuSwg;-ObJ%x7l($ujRf)}9%?@Gkzw zyWi*jQ}AE9&%b?4L&aKV%N_Mhh3D_4O()G}yyyNDJ@)#qna97M%)Cx-XC^TPOla~T zZsc?G7;55)V0pibzvetE7n#|O8M>u}-aDs>*)yjXKfF^Oe`B}7eDKcyMj!s}9Dc%% zPni$T`h#D&XdXA})Ki$NzM9K-sa!yx-)2tJ0~L1Wf?FSFt{F9({>pm_y?ND}(Rt6U zX1ZX7xJMR6L4|3>F1R}L&aY z{pUsg)}ANvS3dtc=Q{sdy2I&Z+*vnf@ExC7%w#S-f$r9>H#g?NbNB%x+H;l_eVI%5 zzRPs6@1r;Gn!rQ`e98QD!vKEDugCFs1Y1@7{m@VJgExN1o!%;w>;3F+%&oV0_{NTd znUSCUm)Z0F5@yC1e{zDLomX_Vdct*8nJOj_*=i1+<2eti~dEtXX`lN7=jiaBvi7vQT>>^QA2sAEr(g(|V zdem2s(aYEOECYoog2DxKllCf-S~^wY^IsDo4G6JRnu%& zJGbnDR!mh!d%o+JZE1g7OLX}0uTtEmeRR8H7I2SVw32>(=VkOglNVAe+dNI@_4$Rn zaw5-tu_j2DcDFIJuYHDVx4HxUZtZjQF;(s9#~<3k6~EAj&VBt`y7czNT&oK#)MP%u zy`1f!-|CmmpYhXeT;=y)(xG`5)1Nfl+qA%OXZg(MSJ590KQ%g|ekRBKcr875(LnAT ztDi2oJi8Y_hPnquDlhr`v<>u+l^=8GSu^RGldquPfB7Az@|8Vw_W`|`F|JKb_s%(s z85_N+e7v_W*D5%8-Am_opd)9Fr+@mcBlE_x7rA9GAIJYV?KbYG0ZwM=_g$IV7ha+B z?yHW@_wr2_F1we$@Z}6kTY>H`r>CVyc1BJ&OJ;Tk_}d!%ondL6y&|J8Whqq7bh9&p zfl$OMxUk*e7_;9KX$Y~_GazH&xk0wtI@Ra*=2*s^JEF>c#^^EQ#)8*f3A`R;Lt!7- z1Nebkdvw6h_U&&uL3v&9eg{In8lN9*BZR;U7%h{NF=Nv88NiPuL}cU~W9bfB(iOF& z9r(8k_}jfNV<}RyiqVj>g)EeobP!r{_PDXIDfwpV(i%AKrwp*DUHVv^vO!&7?+SmX z3_>g~s$C0_S{jemSZZvGf~AIShWW!cGNxG3{Q<;&BWC(N8FFPXpBI+A4aipN){MU8 ziO-AnV@|C)^{f$NM^rU;T9la?itdPb-6oRdpqz%~cBVI^i7 zmZNSM^dn7CkDlZd!bT5{9BiO4ISy_k6CXW^OJ<6C^hBouHhNtTZo?8EJ&_GZmTc9= zoftf=9#CzlB*xlu7>zY*m|9YWX6Z;O9630Ghnu7djnqmiY9=vy`G?!+5t6Dh=?bMf4)J$TmJ0C`4jT)wwRH0cqk_tx-j^N=YsX`;Ql8Ty1 zj9%&CHhP4ls_c}Qq)K8ZN~*lUKt5ff6Aq^h21XLE?3<7anP^tUVKlZFi|CY(GBoFH zv5|$_-Cl==SQeYv*LMrLrE`<$1lg2r85VUU5C(D&vZ=yprb%6}CJDOq6JUOkkHn$4 zYHY|d51k=1yP20;BaPXc85SaF2^+M`gDYt+GlSMO2yDCPXsckTm+ccO_c1nX5ba2N z6UFif5FZ|a6EnSJ1yy+zvD8pQOL$7j9jsC@a#yF9a#uNNu-q#^?$R2d~rq$qb6kmy0FT5}9AVT&!wuXOzsK*iyMzLSK>jmCD7cfT~e4gJLV> zVhKe?=2tPLuSM7Uh|Q;7Q%zZ_a7j!-7*lcvx z*-504{V+h{#RijIqNGrAaS^%5>J|@-!;m$3+6yz|HGetI| z%grt!Dx#zS6An!VTM>~6Rz@reBtqk;TVpX1XcA;7)vK_&?_&1~)_3;!`H;<4IuFl> zoH-D%iS+@qQxs~l;Yt!bBeD;bRA?~C*{39s22(GE+{4l^kQJ6qtx%lA3X^@KB*BK0 zoW!s?a$(YN#;y?>PQ3&~_r*?vb)Q48lZ5~XrCFr1fi)JB;2DvrAVwxKBD+vYf@eg^ zu#yT5XzY@t0o6+(_pvmfZOqT7!4@6{!Jar zqgwDp2_-v6NrDZiUVY`lqyZ%hgLM`Yp#jxPpzc1+%u(8ncOTiwy)@&XQOZgZtXbr! zL(Cvn2unm31`RAiqFEW6N9sgGjSwQdSTCX!B}2V(7LBx=2spq%yjR!)%mjeA#9f38 zA4Brw_@2CoCj`(QH9&QqV}SIAE#4c_iF@n~Xg!Kqf_Q@~Of7O#xV_U2tEJ^bQNL?c zLFHY%mP)xc0b=V_6@L>p2P-pZs=gTDSHEkbzTjP*`hs%f)>n9ws4v{OndxEG1`n&V z@V<#!3-9aH8@(TEQlOqjZhKWlDY)<2NPKin>hEl@aev zRhf2EGN9Vf%Vi4h#vL8uUCr2_cMV4dy-C#9j0~tkp0N4~^H?_Cj(fpQM@LZ8Sj0~uZ@K}A#$bj&! zPJQFc0D6es*wSwDH%|iI^}i>@5Yq@;a$zxpmz=Hi{4cAk<*k6s9Z%@ea*;#@UBjM zc{{VAQN*PKyPZxj4K1en;IEF z@hUJs<1&eLz-3AXRCafHe1v!7%7E~$W^B;AhV?~ns`|)fN(NL8O{~6VWI%XVr@rxJ z0KG}n*PILxz6h+&=41f9uTyU`G9bTA*4=~*fOmCd0E@7RIUmuR+A`zHfbgb92C(oK z<1!T)KzE!NK~;25i9}KaM+UuRH1*M2_;|=~!3OJ9P<}`15hCP8?;R-#iWh;klODwc zg;D~mRE`qT5F2sJX|R&yXEBSCQ=qaYiFOg28^3L4NZ!zKBS(&?QkzC>Ry@ssJmml! zH8#}1S~OXK>uKWU1da{vGNv7D|kY)nHqG3Do^9C5bCMZG{frZq&KKF zQp|W8W91H$0vi>c)O^MU9YW-5+$E^KI*p7|ZJjq_)*jhN@RsW5jtnJuLbI91><}VP zqwYZU)M=Vwb#>Ak)Y_!5ARCOyu25xa&=sbI#SS5v&8^e4SY07xt&`rMD@+RuGAfxA z7GSc0=2~SvGU$*5ghkF)r;)Kb1!b@EM$B$O#uR+u^>arS6+EHYOk;Kkk*ATcpnB>w z&9J&U=?!YFn%6LJAy(e1i47B)&D5YPRCyYAMPkB&Y)grC1u>_MI)j+hak_)Z*q}p* ze2u#VWvkQ3SYwE?*Lfr6U?QsvE(7|xBhw3>&}^nLJA}y7s5?+Sb(&^aU7hp>wKgd% z$f{$qD^!^pbcJbQ5e!}ltSqRyiFE}rr(+9?Y$!6>9Yn?k9fD@Fl&|sZK-uavGS>V+ z+3UO!bA}-Ej8vo8oq}vMctW$8#_SLxPowTY_0(yaerKSpb+$AVmokqr*A1HgBH}qzR zY}1iONVi91!w#OxRCap(pvf&p7sz$fX^W=ya;7?owKbhFBu^nSvVgD`kzgon0Te&z uCy^P*GApChV%Lxhk)bppkH3a>gW#qxxW?D#kA!nFFS}xB8%wLMIsXUZU-l3H literal 0 HcmV?d00001 diff --git a/model/model_heat_v4.py b/model/model_heat_v4.py new file mode 100644 index 0000000..8be1ace --- /dev/null +++ b/model/model_heat_v4.py @@ -0,0 +1,100 @@ +""" +NanoDetHeat v4: 残差 + SE注意力 + 扩通道 +MACs: ~8.7M, 参数: ~18K, 目标: 20 TPS @ 0.44 GOPS (79%) +""" + +import torch +import torch.nn as nn +import torch.nn.functional as F +import numpy as np + + +def conv_bn_relu(in_c, out_c, kernel, stride=1, groups=1): + pad = kernel // 2 + return nn.Sequential( + nn.Conv2d(in_c, out_c, kernel, stride, pad, groups=groups, bias=False), + nn.BatchNorm2d(out_c), + nn.ReLU(inplace=True), + ) + + +class SEResDWBlock(nn.Module): + """残差DW + SE通道注意力""" + def __init__(self, in_c, out_c, stride=1, reduction=4): + super().__init__() + self.dw = conv_bn_relu(in_c, in_c, 3, stride=stride, groups=in_c) + self.pw = conv_bn_relu(in_c, out_c, 1) + + self.skip = nn.Identity() if (stride == 1 and in_c == out_c) else nn.Sequential( + nn.Conv2d(in_c, out_c, 1, stride, bias=False), + nn.BatchNorm2d(out_c), + ) + + self.se = nn.Sequential( + nn.AdaptiveAvgPool2d(1), + nn.Conv2d(out_c, out_c // reduction, 1), + nn.ReLU(inplace=True), + nn.Conv2d(out_c // reduction, out_c, 1), + nn.Sigmoid(), + ) + self.relu = nn.ReLU(inplace=True) + + def forward(self, x): + out = self.pw(self.dw(x)) + out = out + self.skip(x) + return self.relu(out * self.se(out)) + + +class NanoDetHeatV4(nn.Module): + def __init__(self, num_classes=3): + super().__init__() + self.stem = conv_bn_relu(3, 8, 3, stride=2) + self.block1 = SEResDWBlock(8, 16, stride=1) + self.block2 = SEResDWBlock(16, 28, stride=2) + self.block3 = SEResDWBlock(28, 40, stride=1) + self.block4 = SEResDWBlock(40, 56, stride=2) + self.block5 = SEResDWBlock(56, 64, stride=1) + + self.shared = conv_bn_relu(64, 24, 1) + self.cls_head = nn.Conv2d(24, num_classes + 1, 1, bias=True) + self.size_head = nn.Conv2d(24, 2, 1, bias=True) + self._init_weights() + + def _init_weights(self): + for m in self.modules(): + if isinstance(m, nn.Conv2d): + nn.init.kaiming_normal_(m.weight, mode='fan_out', nonlinearity='relu') + if m.bias is not None: nn.init.constant_(m.bias, 0) + elif isinstance(m, nn.BatchNorm2d): + nn.init.constant_(m.weight, 1); nn.init.constant_(m.bias, 0) + self.cls_head.bias.data[-1] = 0.5 # 轻微背景偏置,焦点损失自动调整 + + def forward(self, x): + x = self.stem(x); x = self.block1(x); x = self.block2(x) + x = self.block3(x); x = self.block4(x); x = self.block5(x) + x = self.shared(x) + return torch.cat([self.cls_head(x), self.size_head(x)], dim=1) + + +OUT_H, OUT_W = 15, 20 +STRIDE = 8 + + +if __name__ == "__main__": + m = NanoDetHeatV4() + p = sum(p.numel() for p in m.parameters()) + + macs = (3*3*3*8*80*60 + # stem + 8*9*80*60 + 8*16*80*60 + 8*16*80*60 + # b1 + 16*9*40*30 + 16*28*40*30 + 16*28*40*30 + # b2 + 28*9*40*30 + 28*40*40*30 + # b3 + 40*9*20*15 + 40*56*20*15 + 40*56*20*15 + # b4 + 56*9*20*15 + 56*64*20*15 + # b5 + 64*24*20*15 + 24*4*20*15 + 24*2*20*15) # heads + + print(f"Params: {p:,} = ~{p/1000:.1f}K") + print(f"MACs: {macs:,} = ~{macs/1e6:.2f}M") + print(f"20 TPS: {macs*20*2/1e9:.2f} GOPS ({(macs*20*2/0.44e9)*100:.0f}%)") + print(f"25 TPS: {macs*25*2/1e9:.2f} GOPS ({(macs*25*2/0.44e9)*100:.0f}%)") + x = torch.randn(1,3,120,160); y = m(x) + print(f"Output: {y.shape}") diff --git a/scheduler.cpp b/scheduler.cpp new file mode 100644 index 0000000..aaa69ea --- /dev/null +++ b/scheduler.cpp @@ -0,0 +1,289 @@ +#include "scheduler.hpp" +#include "types.hpp" +#include "hal/gpio.hpp" +#include "hal/framebuffer.hpp" +#include "hal/encoder.hpp" +#include "control/pid.hpp" +#include "control/imu.hpp" +#include "control/motor.hpp" +#include "control/servo.hpp" +#include "vision/camera.hpp" +#include "vision/preprocess.hpp" +#include "vision/search.hpp" +#include "vision/element.hpp" +#include "strategy/deviation.hpp" +#include "strategy/speed.hpp" +#include "debug/draw.hpp" +#include "debug/config.hpp" + +#include +#include +#include +#include +#include +#include +#include +#include + +// ========================================================= +// 全局控制对象 +// ========================================================= +static YawTracker g_imu; +static Encoder* g_enc_l = nullptr; +static Encoder* g_enc_r = nullptr; +static PID g_pid_speed_l(0.6f, 0.2f, 0.0f, 0.0f, PID_INCREMENTAL, 100.0f, 50.0f); +static PID g_pid_speed_r(0.6f, 0.2f, 0.0f, 0.0f, PID_INCREMENTAL, 100.0f, 50.0f); + +static float g_vision_yaw = 0.0f; +static float g_speed_l = 0.0f; +static float g_speed_r = 0.0f; +static float g_base_speed = 20.0f; +static float g_user_speed = 11.0f; + +static std::atomic g_sched_running{false}; +std::atomic g_print_flag{0}; +static int g_timer_fd = -1; +static int g_epoll_fd = -1; +static std::thread g_sched_thread; +static std::mutex g_vision_mutex; +static int g_tick = 0; +static int g_frame_cnt = 0; +static int g_bad_frame = 0; +static int g_empty_cnt = 0; +static FrameBuffer* g_fb_ptr = nullptr; + +// ========================================================= +// 5ms 回调 +// ========================================================= + +static void sched_5ms(float dt) +{ + if (g_enc_l) g_enc_l->update(); + if (g_enc_r) g_enc_r->update(); + g_imu.update(dt); + + g_speed_l = g_enc_l ? g_enc_l->getRPS() : 0; + g_speed_r = g_enc_r ? g_enc_r->getRPS() : 0; +} + +static void sched_10ms(float dt) +{ + // 1. 视觉处理 + cv::Mat bgr = camera_capture(); + if (!bgr.empty()) + { + std::lock_guard lock(g_vision_mutex); + preprocess_run(bgr); + + SearchResult sr; + search_run(sr); + + TrackInfo info; + element_recognize(sr, info); + + fit_midline(sr.lines); + info.deviation = calc_deviation(sr.lines); + info.base_speed = calc_base_speed(info); + info.curvature = info.deviation; + + // 十字路口锁定直行 + if (element_is_cross()) + info.deviation = 0.0f; + + g_vision_yaw = info.deviation; + g_base_speed = info.base_speed; + info.line_valid = (sr.lines.left_valid + sr.lines.right_valid) >= 1; + + bool line_ok = (sr.lines.left_valid || sr.lines.right_valid); + if (!line_ok) ++g_bad_frame; + + // LCD 预览 — 原始摄像头画面 + 车道线 + if (read_config_flag(CFG_SHOW_IMG, false) && g_fb_ptr) + { + cv::Mat rgb; + cv::cvtColor(bgr, rgb, cv::COLOR_BGR2RGB); + cv::Mat disp; + cv::resize(rgb, disp, cv::Size(g_fb_ptr->width(), g_fb_ptr->height())); + + int fw = g_fb_ptr->width(); + int fh = g_fb_ptr->height(); + float sx = (float)fw / IMAGE_WIDTH; + float sy = (float)fh / IMAGE_HEIGHT; + + for (int y = 0; y < IPM_ROW_COUNT; ++y) + { + int dy = (int)(y * sy); + if (sr.lines.left[y] > 0) + cv::line(disp, cv::Point((int)(sr.lines.left[y] * sx), dy), + cv::Point((int)(sr.lines.left[y] * sx), dy), cv::Scalar(255,0,0), 5); + if (sr.lines.right[y] > 0) + cv::line(disp, cv::Point((int)(sr.lines.right[y] * sx), dy), + cv::Point((int)(sr.lines.right[y] * sx), dy), cv::Scalar(0,255,0), 5); + if (sr.lines.mid[y] > 0) + cv::line(disp, cv::Point((int)(sr.lines.mid[y] * sx), dy), + cv::Point((int)(sr.lines.mid[y] * sx), dy), cv::Scalar(255,255,0), 5); + } + + // 帧计数闪烁点 — 验证屏幕在刷新 + static int blink = 0; + blink = (blink + 1) % 20; + cv::circle(disp, cv::Point(10, fh - 10), 5, + blink < 10 ? cv::Scalar(255,255,255) : cv::Scalar(0,0,0), -1); + + g_fb_ptr->write(disp.data, g_fb_ptr->width(), g_fb_ptr->height()); + } + + // 截帧到文件 + if (read_config_flag(CFG_SAVE_IMG, false)) + { + static int save_cnt = 0; + char fname[64]; + snprintf(fname, sizeof(fname), "./capture_%04d.jpg", save_cnt++); + cv::imwrite(fname, bgr); + printf("[SAVE] %s (%dx%d)\n", fname, bgr.cols, bgr.rows); + } + + ++g_frame_cnt; + } + else + { + ++g_empty_cnt; + } + + // 2. 舵机转向 + servo_set_angle(g_vision_yaw); + + // 3. 差速辅助 + float steer = g_vision_yaw; + float curve_factor = (std::abs(g_vision_yaw) < 0.1f) ? 1.0f : 0.8f; + float base_spd = g_user_speed * curve_factor; + float diff = steer * 0.15f * g_user_speed; + float pwm_l = base_spd + diff; + float pwm_r = base_spd - diff; + + motor_set_pwm(MOTOR_LEFT, pwm_l); + motor_set_pwm(MOTOR_RIGHT, pwm_r); +} + +static void sched_1s() +{ + g_print_flag.store(1); + printf("[FPS] 视觉: %d 丢线: %d 空帧: %d\n", + g_frame_cnt, g_bad_frame, g_empty_cnt); + g_frame_cnt = 0; + g_bad_frame = 0; + g_empty_cnt = 0; + + double speed_val = read_config_double(CFG_SPEED, 11.0); + g_user_speed = static_cast(speed_val); + + if (read_config_flag(CFG_START, false)) + { + double kp = read_config_double(CFG_SERVO_KP, 3.5); + double ki = read_config_double(CFG_SERVO_KI, 0.3); + double kd = read_config_double(CFG_SERVO_KD, 0.2); + servo_set_pid(kp, ki, kd); + + double deadband = read_config_double(CFG_DEADBAND, 0.03); + double gain = read_config_double(CFG_STEER_GAIN, 1.5); + servo_set_deadband(static_cast(deadband)); + servo_set_steer_gain(static_cast(gain)); + + double mkp = read_config_double(CFG_MOTOR_KP, 0.6); + double mki = read_config_double(CFG_MOTOR_KI, 0.2); + double mkd = read_config_double(CFG_MOTOR_KD, 0.0); + g_pid_speed_l.setPID(mkp, mki, mkd); + g_pid_speed_r.setPID(mkp, mki, mkd); + } +} + +static void scheduler_loop() +{ + epoll_event ev; + while (g_sched_running.load()) + { + int n = epoll_wait(g_epoll_fd, &ev, 1, 10); + if (n <= 0) continue; + + uint64 expirations; + read(g_timer_fd, &expirations, sizeof(expirations)); + + for (uint64 i = 0; i < expirations; ++i) + { + float dt = 0.005f; + + sched_5ms(dt); + + if (g_tick % 2 == 0) sched_10ms(dt); + + if (g_tick % 200 == 0) sched_1s(); + + ++g_tick; + } + } +} + +// ========================================================= +// 初始化 +// ========================================================= + +bool scheduler_init(FrameBuffer* fb) +{ + g_fb_ptr = fb; + + motor_init(); + servo_init(); + servo_center(); + motor_enable(true); + + g_enc_l = new Encoder(ENCODER_LEFT_CHANNEL, ENCODER_LEFT_DIR_GPIO, 1); + g_enc_r = new Encoder(ENCODER_RIGHT_CHANNEL, ENCODER_RIGHT_DIR_GPIO, -1); + + g_imu.begin(IMU_DEVICE, IMU_BAUDRATE); + + preprocess_init(); + element_init(); + speed_strategy_reset(); + + g_timer_fd = timerfd_create(CLOCK_MONOTONIC, 0); + if (g_timer_fd < 0) { printf("[SCHED] timerfd create failed\n"); return false; } + + itimerspec its; + its.it_interval.tv_sec = 0; + its.it_interval.tv_nsec = 5 * 1000 * 1000; // 5ms + its.it_value = its.it_interval; + timerfd_settime(g_timer_fd, 0, &its, nullptr); + + g_epoll_fd = epoll_create1(0); + epoll_event ev; + ev.events = EPOLLIN; + ev.data.fd = g_timer_fd; + epoll_ctl(g_epoll_fd, EPOLL_CTL_ADD, g_timer_fd, &ev); + + printf("[SCHED] 调度器初始化完成 (5ms)\n"); + return true; +} + +void scheduler_start() +{ + g_sched_running.store(true); + g_sched_thread = std::thread(scheduler_loop); + printf("[SCHED] 调度器启动\n"); +} + +void scheduler_stop() +{ + g_sched_running.store(false); + if (g_sched_thread.joinable()) + g_sched_thread.join(); + + motor_stop_all(); + servo_center(); + + if (g_enc_l) { delete g_enc_l; g_enc_l = nullptr; } + if (g_enc_r) { delete g_enc_r; g_enc_r = nullptr; } + + close(g_timer_fd); + close(g_epoll_fd); + printf("[SCHED] 调度器停止\n"); +} diff --git a/scheduler.hpp b/scheduler.hpp new file mode 100644 index 0000000..ae4c16a --- /dev/null +++ b/scheduler.hpp @@ -0,0 +1,10 @@ +#pragma once +#include + +class FrameBuffer; + +bool scheduler_init(FrameBuffer* fb = nullptr); +void scheduler_start(); +void scheduler_stop(); + +extern std::atomic g_print_flag; diff --git a/strategy/deviation.cpp b/strategy/deviation.cpp new file mode 100644 index 0000000..435a988 --- /dev/null +++ b/strategy/deviation.cpp @@ -0,0 +1,72 @@ +#include "deviation.hpp" +#include +#include +#include + +void fit_midline(EdgeLines& lines) +{ + static EdgeLines prev; + static bool has_prev = false; + + if (!has_prev) + { + std::memcpy(&prev, &lines, sizeof(EdgeLines)); + has_prev = true; + return; + } + + for (int y = 0; y < IPM_ROW_COUNT; ++y) + { + if (lines.left[y] == 0 || lines.right[y] == 0) continue; + + if (std::abs(static_cast(lines.mid[y]) - static_cast(prev.mid[y])) > 20) + lines.mid[y] = prev.mid[y]; + } + + for (int y = 0; y < IPM_ROW_COUNT; ++y) + { + if (y >= 2 && y < IPM_ROW_COUNT - 2 && lines.mid[y] > 0) + { + int sum = 0, cnt = 0; + for (int dy = -2; dy <= 2; ++dy) + if (lines.mid[y + dy] > 0) { sum += lines.mid[y + dy]; ++cnt; } + if (cnt > 0) lines.mid[y] = sum / cnt; + } + } + + std::memcpy(&prev, &lines, sizeof(EdgeLines)); +} + +float calc_deviation(const EdgeLines& lines) +{ + float dev_near = 0, dev_mid = 0, dev_far = 0; + float cnt_near = 0, cnt_mid = 0, cnt_far = 0; + int mid_ref = IMAGE_WIDTH / 2; + + int total = IPM_ROW_COUNT; + int zone_far = total / 5; // 远: 上20% + int zone_mid = total * 3 / 5; // 中: 中间40% + + for (int y = 0; y < total; ++y) + { + if (lines.mid[y] == 0) continue; + float d = static_cast(lines.mid[y]) - mid_ref; + + if (y < zone_far) + { dev_far += d; cnt_far += 1; } + else if (y < zone_mid) + { dev_mid += d; cnt_mid += 1; } + else + { dev_near += d; cnt_near += 1; } + } + + if (cnt_far < 3) cnt_far = 3; + if (cnt_mid < 3) cnt_mid = 3; + if (cnt_near < 3) cnt_near = 3; + + float dev = (dev_far / cnt_far) * 0.50f + + (dev_mid / cnt_mid) * 0.30f + + (dev_near / cnt_near) * 0.20f; + + return std::clamp(dev / mid_ref, -1.0f, 1.0f); +} diff --git a/strategy/deviation.hpp b/strategy/deviation.hpp new file mode 100644 index 0000000..8fa3b5c --- /dev/null +++ b/strategy/deviation.hpp @@ -0,0 +1,6 @@ +#pragma once +#include "types.hpp" +#include "vision/search.hpp" + +float calc_deviation(const EdgeLines& lines); +void fit_midline(EdgeLines& lines); diff --git a/strategy/speed.cpp b/strategy/speed.cpp new file mode 100644 index 0000000..70e7860 --- /dev/null +++ b/strategy/speed.cpp @@ -0,0 +1,47 @@ +#include "speed.hpp" +#include +#include + +static float current_speed = 0.0f; +static float max_speed = 40.0f; +static float accel_rate = 2.0f; +static float decel_rate = 5.0f; + +void speed_strategy_reset() +{ + current_speed = 0.0f; +} + +float calc_base_speed(const TrackInfo& info) +{ + float target = max_speed * 0.7f; // 默认中速 + + switch (info.scene) + { + case TRACK_STRAIGHT: + target = max_speed; + break; + case TRACK_GENTLE_CURVE: + target = max_speed * 0.6f; + break; + case TRACK_SHARP_CURVE: + target = max_speed * 0.35f; + break; + case TRACK_LOST_LINE: + target = max_speed * 0.2f; + break; + case TRACK_CROSS: + target = max_speed * 0.5f; + break; + } + + if (std::fabs(info.deviation) > 0.6f) + target *= 0.6f; + + float diff = target - current_speed; + float rate = (diff > 0) ? accel_rate : decel_rate; + current_speed += rate * (diff > 0 ? 1 : -1) * 0.01f; + current_speed = std::clamp(current_speed, 0.0f, max_speed); + + return current_speed; +} diff --git a/strategy/speed.hpp b/strategy/speed.hpp new file mode 100644 index 0000000..b004088 --- /dev/null +++ b/strategy/speed.hpp @@ -0,0 +1,5 @@ +#pragma once +#include "types.hpp" + +float calc_base_speed(const TrackInfo& info); +void speed_strategy_reset(); diff --git a/tools/calibrate.py b/tools/calibrate.py new file mode 100644 index 0000000..b322713 --- /dev/null +++ b/tools/calibrate.py @@ -0,0 +1,43 @@ +import cv2 +import sys + +img = cv2.imread(sys.argv[1] if len(sys.argv) > 1 else "_capture.jpg") +if img is None: + print("找不到图片") + sys.exit(1) + +H, W = img.shape[:2] +points = [] +labels = ["A 近左", "B 近右", "C 远左", "D 远右"] + +def on_click(event, x, y, flags, param): + if event == cv2.EVENT_LBUTTONDOWN and len(points) < 4: + points.append((x, y)) + cv2.circle(img, (x, y), 4, (0, 0, 255), -1) + cv2.putText(img, labels[len(points)-1], (x+8, y-8), + cv2.FONT_HERSHEY_SIMPLEX, 0.5, (0, 255, 255), 1) + print(f" {labels[len(points)-1]}: ({x:4d}, {y:4d})") + if len(points) == 4: + print("\n--- 标定数据 ---") + for i, p in enumerate(points): + print(f"{labels[i]}: ({p[0]:4d}, {p[1]:4d})") + # 换算到 80x60 + sx, sy = 80/W, 60/H + print(f"\n80x60 处理分辨率:") + for i, p in enumerate(points): + print(f"{labels[i]}: ({int(p[0]*sx):3d}, {int(p[1]*sy):3d})") + print("\n按任意键退出...") + +cv2.namedWindow("calib", cv2.WINDOW_NORMAL) +cv2.setMouseCallback("calib", on_click) + +print(f"图片 {W}x{H},按 A B C D 顺序点击 4 个点:") +print(" A=近处左边界 B=近处右边界 C=远处左边界 D=远处右边界\n") + +while True: + cv2.imshow("calib", img) + if cv2.waitKey(20) != -1 or len(points) >= 4: + break + +cv2.waitKey(0) +cv2.destroyAllWindows() diff --git a/types.hpp b/types.hpp new file mode 100644 index 0000000..8f5d947 --- /dev/null +++ b/types.hpp @@ -0,0 +1,195 @@ +#pragma once +#include + +// ========================================================= +// 类型别名 — 统一使用短名,与 Seekfree SDK 风格一致 +// ========================================================= +using uint8 = uint8_t; +using uint16 = uint16_t; +using uint32 = uint32_t; +using int16 = int16_t; +using int32 = int32_t; + +// ========================================================= +// 图像常量 — 摄像头采集 320×240,处理降采样至 160×120 +// ========================================================= +constexpr int CAMERA_WIDTH = 320; // UVC 摄像头原始宽度 +constexpr int CAMERA_HEIGHT = 240; // UVC 摄像头原始高度 +constexpr int IMAGE_WIDTH = 160; // 处理用图像宽度 (节省算力) +constexpr int IMAGE_HEIGHT = 120; // 处理用图像高度 +constexpr int IPM_ROW_COUNT = 120; // IPM/边界线数组行数 = IMAGE_HEIGHT + +// ========================================================= +// 电机引脚 — PWM 通过 sysfs 控制 +// +// 左驱 (DRV8701 IN1/IN2 模式): +// IN1=GPIO12 (正转), IN2=GPIO13 (反转, 必须锁0) +// 左轮: pwmchip8/pwm2 +// +// 右驱 (DRV8701 方向脚硬件锁死, 已物理交换电机电源线反转方向): +// 方向脚 GPIO67 (哑脚, 不影响任何硬件) +// 右轮: pwmchip8/pwm1 +// +// 使能: GPIO73 (高有效) +// PWM 频率 = 20kHz (周期 50000ns) +// ========================================================= +constexpr int MOTOR_PWMCHIP = 8; // PWM 芯片编号 +constexpr int MOTOR_LEFT_PWMID = 2; // 左电机 PWM 通道 +constexpr int MOTOR_RIGHT_PWMID = 1; // 右电机 PWM 通道 +constexpr int MOTOR_LEFT_DIR_GPIO = 12; // 左电机 IN1 (正转) +constexpr int MOTOR_LEFT_IN2_GPIO = 13; // 左电机 IN2 (反转, 初始化为0) +constexpr int MOTOR_RIGHT_DIR_GPIO = 67; // 右电机方向 (哑脚, 无效) +constexpr int MOTOR_ENABLE_GPIO = 73; // 电机总使能 (1=启动, 0=紧急制动) +constexpr int MOTOR_PWM_PERIOD_NS = 50000; // PWM 周期 50µs = 20kHz + +// ========================================================= +// 编码器 — 通过 /dev/mem 直接 mmap PWM 硬件寄存器读取 +// +// 基址 0x1611B000 是龙芯2K0300 PWM 外设的物理地址 +// 左编码器取通道 0, 方向 GPIO75, 极性 +1 +// 右编码器取通道 3, 方向 GPIO72, 极性 -1 (安装相反) +// 需 root 权限访问 /dev/mem +// ========================================================= +constexpr uintptr_t ENCODER_BASE = 0x1611B000; // PWM 寄存器基址 +constexpr int ENCODER_LEFT_CHANNEL = 0; // 左编码器 PWM 通道 +constexpr int ENCODER_RIGHT_CHANNEL = 3; // 右编码器 PWM 通道 +constexpr int ENCODER_LEFT_DIR_GPIO = 75; // 左编码器方向检测脚 +constexpr int ENCODER_RIGHT_DIR_GPIO= 72; // 右编码器方向检测脚 + +// ========================================================= +// 舵机引脚 — 前轮转向 +// +// pwmchip1/pwm0, 3ms 周期 (333Hz) +// 中位 = 1.52ms, 最大行程 ±0.5ms → 角度范围约 ±45° +// ========================================================= +constexpr int SERVO_PWMCHIP = 1; // 舵机 PWM 芯片 +constexpr int SERVO_PWMID = 0; // 舵机 PWM 通道 +constexpr int SERVO_PERIOD_NS = 3000000; // PWM 周期 3ms (333Hz) +constexpr int SERVO_CENTER_NS = 1520000; // 舵机中位 1.52ms +constexpr int SERVO_MAX_DELTA_NS = 210000; // 舵机偏离中位的最大行程 ±0.21ms + +// ========================================================= +// IMU — JY62 六轴陀螺仪 +// +// 连接 /dev/ttyS2, 波特率 115200 +// 数据帧: 0x55 头 → 11 字节包 → 解析角速度 z 轴 +// 用于偏航角积分 (YawTracker) +// ========================================================= +constexpr const char* IMU_DEVICE = "/dev/ttyS1"; // IMU 串口设备 +constexpr int IMU_BAUDRATE = 115200; // 波特率 + +// ========================================================= +// 外设路径 — 各传感器与显示器的 Linux 设备节点 +// ========================================================= +constexpr const char* FB_DEVICE = "/dev/fb0"; // LCD 帧缓冲 (RGB565) +constexpr const char* UVC_DEVICE = "/dev/video0"; // USB 摄像头 +constexpr const char* VL53L0X_DEV = "/dev/stmvl53l0x_ranging"; // ToF 激光测距 +constexpr const char* I2C2_DEV = "/dev/i2c-2"; // I2C 总线 2 + +// ========================================================= +// 运行时热调参数 — 从当前工作目录读取文件 +// +// 用法: 在车运行过程中 echo 值 > 对应文件即可实时生效 +// 例如: echo 4.0 > ./kp # 调大舵机 P +// echo 1 > ./start # 启动车 +// echo 0 > ./start # 停止车 +// ========================================================= +constexpr const char* CFG_START = "./start"; // 1=启动, 0=停止 +constexpr const char* CFG_SPEED = "./speed"; // 目标占空比 +constexpr const char* CFG_SHOW_IMG = "./showImg"; // 1=LCD 预览, 0=关闭 +constexpr const char* CFG_SAVE_IMG = "./saveImg"; // 1=保存当前帧到文件 +constexpr const char* CFG_FORESEE = "./foresee"; // 前瞻行号 (越大看越远) +constexpr const char* CFG_SERVO_KP = "./kp"; // 舵机 PID 比例系数 +constexpr const char* CFG_SERVO_KI = "./ki"; // 舵机 PID 积分系数 +constexpr const char* CFG_SERVO_KD = "./kd"; // 舵机 PID 微分系数 +constexpr const char* CFG_MOTOR_KP = "./mortor_kp";// 电机 PID 比例系数 +constexpr const char* CFG_MOTOR_KI = "./mortor_ki";// 电机 PID 积分系数 +constexpr const char* CFG_MOTOR_KD = "./mortor_kd";// 电机 PID 微分系数 +constexpr const char* CFG_DEADBAND = "./deadband"; // 舵机死区 (归一化偏差阈值) +constexpr const char* CFG_STEER_GAIN= "./steer_gain";// 舵机增益 (放大系数) + +// ========================================================= +// 赛道场景枚举 — 按危险程度从低到高排列 +// +// 本赛道只包含直线/弯道/十字/丢线,不含圆环 +// element_recognize() 负责从搜线结果判定当前场景 +// calc_base_speed() 根据场景决定目标车速 +// ========================================================= +enum TrackScene : uint8 { + TRACK_STRAIGHT = 0, // 直道 — 全速 + TRACK_GENTLE_CURVE, // 缓弯 — 中高速 (0.6x 全速) + TRACK_SHARP_CURVE, // 急弯 — 低速 (0.35x 全速) + TRACK_LOST_LINE, // 丢线 — 最低速 (0.2x 全速), 等待恢复 + TRACK_CROSS, // 十字路口 — 锁定直行, 降速 (0.5x 全速) +}; + +// ========================================================= +// 调试显示模式 — 控制 LCD 或 TCP 图传的叠加内容 +// ========================================================= +enum DebugDisplayMode : uint8 { + DBG_ORIGINAL = 0, // 原始彩色图像 + DBG_BINARY, // 二值化结果 + DBG_OVERLAY, // 叠加边界线/中线 + DBG_HSV_H, // HSV H 通道 + DBG_HSV_S // HSV S 通道 +}; + +// ========================================================= +// PID 模式 — 位置式用于角度外环, 增量式用于速度内环 +// ========================================================= +enum PIDMode : uint8 { + PID_POSITIONAL = 0, // 位置式: u(t) = Kp*e(t) + Ki*Σe + Kd*Δe + PID_INCREMENTAL = 1 // 增量式: Δu = Kp*(e-e') + Ki*e + Kd*(e-2e'+e") +}; + +// ========================================================= +// TrackInfo — 每帧计算出的赛道信息,传递给控制层 +// +// scene: 当前场景枚举,决定速度策略 +// deviation: 归一化中线偏差 (-1~+1), 0=正中间 +// curvature: 曲率估计 (越大越急) +// base_speed: 速度策略计算出的目标车速 (0~100) +// line_valid: 是否检测到有效赛道线 +// ========================================================= +struct TrackInfo { + TrackScene scene = TRACK_STRAIGHT; + float deviation = 0.0f; // -1(偏左) ~ +1(偏右) + float curvature = 0.0f; // 0(直道) ~ 1(急弯) + float base_speed = 0.0f; // 目标车速 + bool line_valid = false; // 搜线有效标志 +}; + +// ========================================================= +// ServoState — 舵机状态 (调试用) +// ========================================================= +struct ServoState { + float duty_ns = SERVO_CENTER_NS; // 当前 PWM 脉宽 (ns) + float target_angle = 0.0f; // 目标角度 (归一化) + float current_angle = 0.0f; // 实际角度 (归一化) +}; + +// ========================================================= +// MotorState — 单侧电机状态 (调试用) +// ========================================================= +struct MotorState { + float target_speed = 0.0f; // 目标转速 (rps) + float current_speed = 0.0f; // 实际转速 (rps, 来自编码器) + float pwm_output = 0.0f; // 当前 PWM 输出 (-100~+100) +}; + +// ========================================================= +// EdgeLines — 每行边界/中线列坐标 +// +// 坐标系: row=0 是图像顶部(远处), row=119 是底部(近处) +// left[row] / right[row] 为第 row 行的左右边界 x 坐标 (0~159) +// mid[row] 为中线 = (left + right) / 2 +// 未检测到边界的行值 = 0, 调用方需判断 +// left_valid / right_valid: 该帧是否有足够多的边线点 (>10 个) +// ========================================================= +struct EdgeLines { + uint8 left[IPM_ROW_COUNT] = {0}; // 左边界每行列坐标 + uint8 right[IPM_ROW_COUNT] = {0}; // 右边界每行列坐标 + uint8 mid[IPM_ROW_COUNT] = {0}; // 中线每行列坐标 + uint8 left_valid = 0; // 左边界有效标志 + uint8 right_valid = 0; // 右边界有效标志 +}; diff --git a/vision/camera.cpp b/vision/camera.cpp new file mode 100644 index 0000000..95ca3a2 --- /dev/null +++ b/vision/camera.cpp @@ -0,0 +1,56 @@ +#include "camera.hpp" +#include +#include +#include + +static cv::VideoCapture* cap = nullptr; +static cv::Mat pubframe; +static std::mutex frame_mutex; +static std::atomic stream_running{false}; + +bool camera_init() +{ + cap = new cv::VideoCapture(0); + if (!cap->isOpened()) return false; + + cap->set(cv::CAP_PROP_FOURCC, cv::VideoWriter::fourcc('M', 'J', 'P', 'G')); + cap->set(cv::CAP_PROP_FRAME_WIDTH, CAMERA_WIDTH); + cap->set(cv::CAP_PROP_FRAME_HEIGHT, CAMERA_HEIGHT); + cap->set(cv::CAP_PROP_AUTO_EXPOSURE, -1); + + return true; +} + +void camera_deinit() +{ + if (cap) { cap->release(); delete cap; cap = nullptr; } +} + +cv::Mat camera_capture() +{ + std::lock_guard lock(frame_mutex); + return pubframe.clone(); +} + +cv::Mat camera_resize(const cv::Mat& src) +{ + cv::Mat resized; + cv::resize(src, resized, cv::Size(IMAGE_WIDTH, IMAGE_HEIGHT)); + return resized; +} + +void camera_stream_start() +{ + stream_running.store(true); + std::thread([]() { + cv::Mat tmp; + while (stream_running.load()) + { + if (cap && cap->read(tmp)) + { + std::lock_guard lock(frame_mutex); + pubframe = tmp.clone(); + } + } + }).detach(); +} diff --git a/vision/camera.hpp b/vision/camera.hpp new file mode 100644 index 0000000..c2b5a50 --- /dev/null +++ b/vision/camera.hpp @@ -0,0 +1,9 @@ +#pragma once +#include +#include "types.hpp" + +bool camera_init(); +void camera_deinit(); +cv::Mat camera_capture(); // 返回最新的 BGR 320x240 帧 +cv::Mat camera_resize(const cv::Mat& src); // 缩放到 160x120 +void camera_stream_start(); // 后台线程持续采集 diff --git a/vision/element.cpp b/vision/element.cpp new file mode 100644 index 0000000..3ed27e2 --- /dev/null +++ b/vision/element.cpp @@ -0,0 +1,188 @@ +#include "element.hpp" +#include +#include +#include + +ElementMachine g_elm; + +namespace { + static constexpr uint8 k_cross_confirm_frames = 3; + static constexpr uint8 k_cross_exit_frames = 5; + static constexpr uint8 k_lock_min_frames = 5; + static constexpr float k_width_widen_ratio = 1.6f; + static constexpr float k_width_normal_ratio = 1.3f; + + static int bottom_width(const SearchResult& sr) + { + int y = IMAGE_HEIGHT - 1; + if (sr.lines.left[y] > 0 && sr.lines.right[y] > 0) + return sr.lines.right[y] - sr.lines.left[y]; + return -1; + } + + static uint8 line_lost_state(const SearchResult& sr) + { + uint8 st = 0; + if (!sr.lines.left_valid) st |= 1; + if (!sr.lines.right_valid) st |= 2; + return st; + } + + static void calibrate_width(const SearchResult& sr) + { + int w = bottom_width(sr); + if (w > 10 && w < IMAGE_WIDTH - 10) + { + g_elm.normal_width = (g_elm.normal_width * g_elm.calib_cnt + w) / (g_elm.calib_cnt + 1); + if (g_elm.calib_cnt < 50) ++g_elm.calib_cnt; + } + } + + static bool is_cross_entry(const SearchResult& sr) + { + if (g_elm.calib_cnt < 20) return false; + + int w = bottom_width(sr); + if (w < 0) return false; + + bool too_wide = (w > g_elm.normal_width * k_width_widen_ratio); + uint8 lost = line_lost_state(sr); + bool both_lost_upper = (lost == 3); + + if (too_wide || both_lost_upper) g_elm.confirm_cnt++; + else g_elm.confirm_cnt = 0; + + return g_elm.confirm_cnt >= k_cross_confirm_frames; + } + + static bool is_cross_exit(const SearchResult& sr) + { + int w = bottom_width(sr); + if (w < 0) { g_elm.exit_cnt = 0; return false; } + + bool width_normal = (w < g_elm.normal_width * k_width_normal_ratio); + bool bounds_ok = (sr.lines.left_valid && sr.lines.right_valid); + + if (width_normal && bounds_ok) g_elm.exit_cnt++; + else g_elm.exit_cnt = 0; + + return g_elm.exit_cnt >= k_cross_exit_frames; + } + + static void cross_patch_midline(SearchResult& sr) + { + int bottom_y = IMAGE_HEIGHT - 1; + int mid_x = sr.lines.mid[bottom_y]; + if (mid_x <= 0) return; + + int lx = mid_x - static_cast(g_elm.normal_width / 2); + int rx = mid_x + static_cast(g_elm.normal_width / 2); + lx = std::max(0, lx); + rx = std::min(IMAGE_WIDTH - 1, rx); + + for (int y = 0; y < IMAGE_HEIGHT; ++y) + { + if (sr.lines.left[y] == 0 && sr.lines.right[y] == 0) + { + sr.lines.left[y] = static_cast(lx); + sr.lines.right[y] = static_cast(rx); + sr.lines.mid[y] = static_cast(mid_x); + } + } + sr.lines.left_valid = 1; + sr.lines.right_valid = 1; + } +} + +void element_init() +{ + std::memset(&g_elm, 0, sizeof(g_elm)); + g_elm.state = TRACK_STRAIGHT; + g_elm.last_state = TRACK_STRAIGHT; + g_elm.normal_width = 50.0f; +} + +bool element_is_cross() +{ + return g_elm.state == TRACK_CROSS; +} + +void element_recognize(SearchResult& sr, TrackInfo& info) +{ + calibrate_width(sr); + + g_elm.last_state = g_elm.state; + ++g_elm.in_state_frames; + + if (g_elm.lock_cnt > 0) + { + --g_elm.lock_cnt; + info.scene = g_elm.state; + return; + } + + switch (g_elm.state) + { + case TRACK_STRAIGHT: + case TRACK_GENTLE_CURVE: + if (is_cross_entry(sr)) + { + int bottom_y = IMAGE_HEIGHT - 1; + g_elm.entry_deviation = (sr.lines.mid[bottom_y] > 0) + ? (sr.lines.mid[bottom_y] - IMAGE_WIDTH / 2) / static_cast(IMAGE_WIDTH / 2) + : 0.0f; + + g_elm.state = TRACK_CROSS; + g_elm.lock_cnt = k_lock_min_frames; + g_elm.in_state_frames = 0; + g_elm.confirm_cnt = 0; + g_elm.exit_cnt = 0; + info.scene = TRACK_CROSS; + } + else + { + info.scene = sr.lines.left_valid || sr.lines.right_valid + ? TRACK_STRAIGHT : TRACK_LOST_LINE; + } + info.line_valid = (info.scene != TRACK_LOST_LINE); + break; + + case TRACK_CROSS: + cross_patch_midline(sr); + + if (is_cross_exit(sr)) + { + g_elm.state = TRACK_STRAIGHT; + g_elm.lock_cnt = 0; + g_elm.in_state_frames = 0; + g_elm.confirm_cnt = 0; + g_elm.exit_cnt = 0; + info.scene = TRACK_STRAIGHT; + } + else + { + info.scene = TRACK_CROSS; + } + info.line_valid = true; + break; + + case TRACK_LOST_LINE: + g_elm.confirm_cnt = 0; + if (sr.lines.left_valid && sr.lines.right_valid) + { + g_elm.state = TRACK_STRAIGHT; + info.scene = TRACK_STRAIGHT; + } + else + { + info.scene = TRACK_LOST_LINE; + } + info.line_valid = (info.scene != TRACK_LOST_LINE); + break; + + default: + info.scene = TRACK_STRAIGHT; + info.line_valid = true; + break; + } +} diff --git a/vision/element.hpp b/vision/element.hpp new file mode 100644 index 0000000..90473aa --- /dev/null +++ b/vision/element.hpp @@ -0,0 +1,23 @@ +#pragma once +#include "types.hpp" +#include "search.hpp" + +struct ElementMachine { + TrackScene state = TRACK_STRAIGHT; + TrackScene last_state = TRACK_STRAIGHT; + + uint8 lock_cnt = 0; + uint8 confirm_cnt = 0; + uint8 exit_cnt = 0; + uint16 in_state_frames= 0; + + float normal_width = 0.0f; + int calib_cnt = 0; + float entry_deviation= 0.0f; +}; + +extern ElementMachine g_elm; + +void element_init(); +void element_recognize(SearchResult& sr, TrackInfo& info); +bool element_is_cross(); diff --git a/vision/preprocess.cpp b/vision/preprocess.cpp new file mode 100644 index 0000000..65fb719 --- /dev/null +++ b/vision/preprocess.cpp @@ -0,0 +1,131 @@ +#include "preprocess.hpp" +#include +#include + +uint8 g_ipm_image[IMAGE_HEIGHT][IMAGE_WIDTH] = {{0}}; +uint8 g_valid_l_bound[IMAGE_HEIGHT] = {0}; +uint8 g_valid_r_bound[IMAGE_HEIGHT] = {0}; + +static constexpr int PROC_W = IMAGE_WIDTH / 2; // 80 — 与demo对齐 +static constexpr int PROC_H = IMAGE_HEIGHT / 2; // 60 + +// ============================================================ +// IPM 4 点标定 — 80×60 相机视角 ↔ 80×60 俯视输出 +// +// 地面实况: 矩形赛道 40cm 宽 × 50cm 长, 近边距摄像头 55cm +// 摄像头垂直投影 ≈ 车头后 5cm, 车头距矩形 ≈ 50cm +// ============================================================ +static constexpr float CAL_NEAR_Y_MM = 550.0f; // 矩形近边 Y (mm) +static constexpr float CAL_FAR_Y_MM = 1050.0f; // 矩形远边 Y (mm) +static constexpr float CAL_HALF_W_MM = 200.0f; // 矩形半宽 (mm) + +static bool g_ipm_enabled = true; // 启用 IPM +static cv::Mat g_ipm_matrix; // 3×3 透视变换矩阵 + +void preprocess_init() {} + +static void init_ipm_calibration() +{ + // 四点: (相机 80×60 像素) → 标注的矩形角 + std::vector src = { + {19.f, 17.f}, // A 近左 + {57.f, 15.f}, // B 近右 + {27.f, 8.f}, // C 远左 + {49.f, 7.f} // D 远右 + }; + + // 目标: 俯视图中也保持矩形 (同宽), 近边 row=55, 远边 row=20 + // mm/pixel ≈ 14.3, 半宽 200mm → 14px + const float cx = PROC_W / 2.0f; // 40 + const float hw = 14.0f; // 半宽像素 + std::vector dst = { + {cx - hw, 55.f}, // A' 近左 + {cx + hw, 55.f}, // B' 近右 + {cx - hw, 20.f}, // C' 远左 + {cx + hw, 20.f} // D' 远右 + }; + + // getPerspectiveTransform(dst, src): 输出(俯视) → 输入(相机) + g_ipm_matrix = cv::getPerspectiveTransform(dst, src); + + printf("[IPM] 4点标定完成\n"); + printf(" 近边 Y=%.0f mm 远边 Y=%.0f mm 半宽=%.0f mm\n", + CAL_NEAR_Y_MM, CAL_FAR_Y_MM, CAL_HALF_W_MM); +} + +static void update_bounds(const cv::Mat& binary); + +static cv::Mat track_binarize(const cv::Mat& bgr) +{ + cv::Mat hsv, thresh_h, thresh_s, result; + cv::cvtColor(bgr, hsv, cv::COLOR_BGR2HSV); + + std::vector ch; + cv::split(hsv, ch); + + cv::threshold(ch[0], thresh_h, 0, 255, cv::THRESH_BINARY_INV | cv::THRESH_OTSU); + cv::threshold(ch[1], thresh_s, 0, 255, cv::THRESH_BINARY_INV | cv::THRESH_OTSU); + cv::bitwise_or(thresh_h, thresh_s, result); + + return result; +} + +static cv::Mat flood_fill_track(const cv::Mat& binary) +{ + cv::Mat kernel = cv::getStructuringElement(cv::MORPH_CROSS, cv::Size(2, 2)); + cv::Mat opened; + cv::morphologyEx(binary, opened, cv::MORPH_OPEN, kernel); + + cv::Mat mask = cv::Mat::zeros(PROC_H + 2, PROC_W + 2, CV_8UC1); + cv::Point seed(PROC_W / 2, PROC_H - 10); + cv::circle(opened, seed, 10, cv::Scalar(255), -1); + + cv::floodFill(opened, mask, seed, cv::Scalar(128), + nullptr, + cv::Scalar(20), cv::Scalar(20), 8); + + cv::Mat result = cv::Mat::zeros(PROC_H, PROC_W, CV_8UC1); + mask(cv::Rect(1, 1, PROC_W, PROC_H)).copyTo(result); + return result; +} + +void preprocess_run(const cv::Mat& bgr_frame) +{ + cv::Mat small; + cv::resize(bgr_frame, small, cv::Size(PROC_W, PROC_H)); + + cv::Mat bin = track_binarize(small); + + // IPM 透视校正 (首次调用时计算矩阵) + if (g_ipm_enabled) + { + if (g_ipm_matrix.empty()) + init_ipm_calibration(); + + cv::Mat ipm_out; + cv::warpPerspective(bin, ipm_out, g_ipm_matrix, + cv::Size(PROC_W, PROC_H), + cv::INTER_LINEAR, + cv::BORDER_CONSTANT, cv::Scalar(0)); + bin = ipm_out; + } + + cv::Mat track = flood_fill_track(bin); + cv::Mat full; + cv::resize(track, full, cv::Size(IMAGE_WIDTH, IMAGE_HEIGHT), 0, 0, cv::INTER_NEAREST); + + update_bounds(full); + std::memcpy(g_ipm_image, full.data, IMAGE_WIDTH * IMAGE_HEIGHT); +} + +static void update_bounds(const cv::Mat& binary) +{ + for (int y = 0; y < IMAGE_HEIGHT; ++y) + { + int l = 0, r = IMAGE_WIDTH - 1; + while (l < IMAGE_WIDTH && binary.at(y, l) == 0) ++l; + while (r >= 0 && binary.at(y, r) == 0) --r; + g_valid_l_bound[y] = static_cast(std::max(0, l)); + g_valid_r_bound[y] = static_cast(std::min(IMAGE_WIDTH - 1, r)); + } +} diff --git a/vision/preprocess.hpp b/vision/preprocess.hpp new file mode 100644 index 0000000..1c796ec --- /dev/null +++ b/vision/preprocess.hpp @@ -0,0 +1,10 @@ +#pragma once +#include +#include "types.hpp" + +void preprocess_init(); +void preprocess_run(const cv::Mat& bgr_frame); // 全彩 HSV 二值化 + IPM + +extern uint8 g_ipm_image[IMAGE_HEIGHT][IMAGE_WIDTH]; +extern uint8 g_valid_l_bound[IMAGE_HEIGHT]; +extern uint8 g_valid_r_bound[IMAGE_HEIGHT]; diff --git a/vision/search.cpp b/vision/search.cpp new file mode 100644 index 0000000..8c3242e --- /dev/null +++ b/vision/search.cpp @@ -0,0 +1,122 @@ +#include "search.hpp" +#include "preprocess.hpp" +#include +#include + +void search_init(SearchResult& r) +{ + std::memset(&r, 0, sizeof(r)); +} + +void search_run(SearchResult& r) +{ + search_init(r); + + int left_raw[IPM_ROW_COUNT] = {0}; + int right_raw[IPM_ROW_COUNT] = {0}; + int mid_raw[IPM_ROW_COUNT] = {0}; + + // ============================================================ + // 逐行最长白段搜索 (与 demo image_main() 完全一致) + // ============================================================ + for (int y = 0; y < IMAGE_HEIGHT; ++y) + { + int best_start = -1, best_end = -1, best_len = 0; + int cur_start = -1, cur_len = 0; + + for (int x = 0; x < IMAGE_WIDTH; ++x) + { + if (g_ipm_image[y][x]) + { + if (cur_len == 0) { cur_start = x; cur_len = 1; } + else cur_len++; + if (cur_len >= best_len) + { + best_len = cur_len; + best_start = cur_start; + best_end = x; + } + } + else + { + cur_len = 0; + cur_start = -1; + } + } + + if (best_len > 0) + { + left_raw[y] = best_start; + right_raw[y] = best_end; + } + } + + // ============================================================ + // 丢线补点 + 中线计算 (从底向上, 复用 demo 逻辑) + // ============================================================ + for (int y = IMAGE_HEIGHT - 2; y >= 0; --y) + { + if (left_raw[y] == 0 && right_raw[y] == 0) + { + mid_raw[y] = mid_raw[y + 1]; + if (mid_raw[y] > IMAGE_WIDTH / 2) + { + right_raw[y] = IMAGE_WIDTH - 1; + left_raw[y] = mid_raw[y + 1]; + } + else + { + left_raw[y] = 0; + right_raw[y] = mid_raw[y + 1]; + } + } + else + { + mid_raw[y] = (left_raw[y] + right_raw[y]) / 2; + } + } + if (left_raw[IMAGE_HEIGHT - 1] > 0 || right_raw[IMAGE_HEIGHT - 1] > 0) + mid_raw[IMAGE_HEIGHT - 1] = (left_raw[IMAGE_HEIGHT - 1] + right_raw[IMAGE_HEIGHT - 1]) / 2; + + // ============================================================ + // EMA 滤波 (从底向上, a=0.4, 与 demo 一致) + // ============================================================ + float left_f[IPM_ROW_COUNT] = {0}; + float right_f[IPM_ROW_COUNT] = {0}; + float mid_f[IPM_ROW_COUNT] = {0}; + constexpr float a = 0.4f; + int bot = IMAGE_HEIGHT - 1; + + for (int y = bot; y >= 0; --y) + { + if (y == bot) + { + left_f[y] = static_cast(left_raw[y]); + right_f[y] = static_cast(right_raw[y]); + mid_f[y] = (left_f[y] + right_f[y]) * 0.5f; + } + else + { + left_f[y] = a * left_raw[y] + (1.0f - a) * left_f[y + 1]; + right_f[y] = a * right_raw[y] + (1.0f - a) * right_f[y + 1]; + mid_f[y] = (left_f[y] + right_f[y]) * 0.5f; + } + + int lv = static_cast(left_f[y] + 0.5f); + int rv = static_cast(right_f[y] + 0.5f); + int mv = static_cast(mid_f[y] + 0.5f); + + r.lines.left[y] = static_cast(std::clamp(lv, 0, 255)); + r.lines.right[y] = static_cast(std::clamp(rv, 0, 255)); + r.lines.mid[y] = static_cast(std::clamp(mv, 0, 255)); + } + + int left_cnt = 0, right_cnt = 0; + for (int y = 0; y < IPM_ROW_COUNT; ++y) + { + if (r.lines.left[y] > 0) ++left_cnt; + if (r.lines.right[y] > 0) ++right_cnt; + } + r.lines.left_valid = (left_cnt > 10) ? 1 : 0; + r.lines.right_valid = (right_cnt > 10) ? 1 : 0; +} diff --git a/vision/search.hpp b/vision/search.hpp new file mode 100644 index 0000000..0d4db83 --- /dev/null +++ b/vision/search.hpp @@ -0,0 +1,9 @@ +#pragma once +#include "types.hpp" + +struct SearchResult { + EdgeLines lines; +}; + +void search_init(SearchResult& r); +void search_run(SearchResult& r);