From 2f9a3732da533986046d77aeb5c468870355cede Mon Sep 17 00:00:00 2001 From: ZGZ713912 Date: Wed, 29 Apr 2026 23:47:26 +0800 Subject: [PATCH 01/13] feat(docker): add OpenAI Codex CLI installation to Dockerfile feat(config): update deformable infantry parameters in YAML configuration fix(chassis_power_controller): set excess power limit to zero fix(deformable_chassis): increase maximum angular velocity limit chore(wheel-demo): remove unused encoder outputs from wheel demo feat(deformable-infantry-v2): implement RmcsBoardLiteCompat for hardware compatibility --- Dockerfile | 13 + .../config/deformable-infantry-v2.yaml | 160 ++++++++-- .../chassis/chassis_power_controller.cpp | 2 +- .../controller/chassis/deformable_chassis.cpp | 2 +- .../src/controller/chassis/wheel-demo.cpp | 18 -- .../src/hardware/deformable-infantry-v2.cpp | 302 +++++++++++++++--- 6 files changed, 412 insertions(+), 85 deletions(-) diff --git a/Dockerfile b/Dockerfile index d9fe2f27..e4591bad 100644 --- a/Dockerfile +++ b/Dockerfile @@ -87,6 +87,19 @@ RUN apt-get update && apt-get install -y --no-install-recommends \ apt-get autoremove -y && apt-get clean && \ rm -rf /var/lib/apt/lists/* /tmp/* +# Install OpenAI Codex CLI +RUN mkdir -p /etc/apt/keyrings && \ + curl -fsSL https://deb.nodesource.com/gpgkey/nodesource-repo.gpg.key \ + | gpg --dearmor -o /etc/apt/keyrings/nodesource.gpg && \ + chmod 644 /etc/apt/keyrings/nodesource.gpg && \ + echo "deb [signed-by=/etc/apt/keyrings/nodesource.gpg] https://deb.nodesource.com/node_22.x nodistro main" \ + > /etc/apt/sources.list.d/nodesource.list && \ + apt-get update && \ + apt-get install -y --no-install-recommends nodejs && \ + npm install -g @openai/codex && \ + apt-get autoremove -y && apt-get clean && \ + rm -rf /var/lib/apt/lists/* /tmp/* + # Install llvm-toolchain ARG LLVM_VERSION=22 RUN mkdir -p /etc/apt/keyrings && \ diff --git a/rmcs_ws/src/rmcs_bringup/config/deformable-infantry-v2.yaml b/rmcs_ws/src/rmcs_bringup/config/deformable-infantry-v2.yaml index a9ed5420..246e5c5f 100644 --- a/rmcs_ws/src/rmcs_bringup/config/deformable-infantry-v2.yaml +++ b/rmcs_ws/src/rmcs_bringup/config/deformable-infantry-v2.yaml @@ -53,53 +53,73 @@ value_broadcaster: deformable_infantry: ros__parameters: - serial_filter_rmcs_board: "AF-3CE0-2D2A-6CDC-89D0-CA40-90D7-46B5-4970" - serial_filter_top_board: "D4-0262-9E84-E715-CADB-9894-7241" + serial_filter_rmcs_board: "AF-23FB-EE32-B892-1302-AE70-D640-7B4E-0CBF" + serial_filter_top_board: "AF-ABAC-786D-1B53-99F6-00A2-42A6-AA95-9D69" left_front_zero_point: 374 left_back_zero_point: 5801 right_back_zero_point: 7817 right_front_zero_point: 7136 yaw_motor_zero_point: 56216 pitch_motor_zero_point: 10898 + debug_log_supercap: false + debug_log_wheel_motor: false + debug_log_deformable_joint_motor: false chassis_controller: ros__parameters: - min_angle: 10.0 - max_angle: 70.0 + # Deploy geometry / chassis-owned joint intent + min_angle: 8.0 + max_angle: 58.0 active_suspension_enable: true - active_suspension_mass: 22.5 - active_suspension_rod_length: 0.150 - active_suspension_spring_k: 150.0 - active_suspension_damping_k: 10.0 - active_suspension_gravity_comp_gain: 0.8 - active_suspension_airborne_torque_threshold: 5.0 - active_suspension_torque_limit: 80.0 + + # IMU attitude correction at min-angle stance. + # pitch < 0: front high. roll > 0: right high. + active_suspension_Kp: 8.0 + active_suspension_pitch_ki: 0.35 + active_suspension_Dp: 0.28 + active_suspension_Kr: 8.0 + active_suspension_roll_ki: 0.35 + active_suspension_Dr: 0.28 + active_suspension_pitch_angle_diff_limit_deg: 45.0 + active_suspension_roll_angle_diff_limit_deg: 45.0 + active_suspension_pid_integral_limit_deg: 20.0 + + # Chassis-owned joint intent trajectory limits while attitude correction is active. + active_suspension_target_velocity_limit_deg: 80.0 + active_suspension_target_acceleration_limit_deg: 360.0 + + # Automatic IMU mounting-error calibration. + # When all four requested joint targets stay equal for 2s, average pitch/roll from 2s to 5s. + chassis_imu_calibration_wait_s: 2.0 + chassis_imu_calibration_sample_s: 3.0 gimbal_controller: ros__parameters: - upper_limit: -0.436332 # -25 deg - lower_limit: 0.05 # 10 deg + upper_limit: -0.61 # -35 deg + lower_limit: 0.05 # 6 deg - yaw_angle_kp: 14.2 + yaw_angle_kp: 20.0 yaw_angle_ki: 0.0 yaw_angle_kd: 0.0 - yaw_velocity_kp: 6.4 + yaw_velocity_kp: 8.0 yaw_velocity_ki: 0.0 yaw_velocity_kd: 0.0 yaw_vel_ff_gain: 0.47 yaw_acc_ff_gain: 0.00 - pitch_angle_kp: 8.0 + pitch_angle_kp: 40.0 pitch_angle_ki: 0.0 pitch_angle_kd: 0.0 - pitch_velocity_kp: 6.0 + pitch_velocity_kp: 3.0 pitch_velocity_ki: 0.0 pitch_velocity_kd: 0.0 - pitch_acc_ff_gain: 0.0 + pitch_acc_ff_gain: 0.10 + + pitch_torque_control: true pitch_fusion_enabled: true pitch_fusion_alpha: 0.98 @@ -160,23 +180,30 @@ bullet_feeder_velocity_pid_controller: deformable_chassis_controller: ros__parameters: - mess: 22.5 + mass: 22.5 moment_of_inertia: 1.0 chassis_radius: 0.2341741 rod_length: 0.150 wheel_radius: 0.055 - friction_coefficient: 6.6 + friction_coefficient: 0.6 k1: 2.958580e+00 k2: 3.082190e-03 no_load_power: 11.37 -lf_joint_adrc_controller: +lf_joint_controller: ros__parameters: - measurement: /chassis/left_front_joint/angle - setpoint: /chassis/left_front_joint/target_angle + # Joint-local servo inputs produced by chassis intent generation + measurement_angle: /chassis/left_front_joint/physical_angle + measurement_velocity: /chassis/left_front_joint/physical_velocity + setpoint_angle: /chassis/left_front_joint/target_physical_angle + setpoint_velocity: /chassis/left_front_joint/target_physical_velocity + mode_input: /chassis/left_front_joint/suspension_mode + suspension_torque: /chassis/left_front_joint/suspension_torque control: /chassis/left_front_joint/control_torque + + # Normal ADRC servo mode dt: 0.001 - b0: 0.60 + b0: -0.60 kt: 1.0 td_h: 0.001 td_r: 50.0 @@ -187,9 +214,32 @@ lf_joint_adrc_controller: alpha1: 0.75 alpha2: 0.7 delta: 0.02 + u_min: -200.0 + u_max: 200.0 + output_min: -200.0 + output_max: 200.0 + + # Suspension ADRC servo mode + suspension_td_h: 0.001 + suspension_td_r: 12.0 + suspension_eso_w0: 80.0 + suspension_k1: 6.0 + suspension_k2: 3.0 + suspension_alpha1: 0.75 + suspension_alpha2: 0.7 + suspension_delta: 0.02 + suspension_u_min: -35.0 + suspension_u_max: 35.0 + suspension_output_min: -35.0 + suspension_output_max: 35.0 + + # Joint-local feedforward / limit shaping + torque_feedforward_gain: 0.0 + suspension_torque_feedforward_gain: -1.0 lb_joint_controller: ros__parameters: + # Same joint-servo layout as lf_joint_controller measurement_angle: /chassis/left_back_joint/physical_angle measurement_velocity: /chassis/left_back_joint/physical_velocity setpoint_angle: /chassis/left_back_joint/target_physical_angle @@ -198,7 +248,7 @@ lb_joint_controller: suspension_torque: /chassis/left_back_joint/suspension_torque control: /chassis/left_back_joint/control_torque dt: 0.001 - b0: 0.60 + b0: -0.60 kt: 1.0 td_h: 0.001 td_r: 50.0 @@ -209,9 +259,28 @@ lb_joint_controller: alpha1: 0.75 alpha2: 0.7 delta: 0.02 + u_min: -200.0 + u_max: 200.0 + output_min: -200.0 + output_max: 200.0 + suspension_td_h: 0.001 + suspension_td_r: 12.0 + suspension_eso_w0: 80.0 + suspension_k1: 6.0 + suspension_k2: 3.0 + suspension_alpha1: 0.75 + suspension_alpha2: 0.7 + suspension_delta: 0.02 + suspension_u_min: -35.0 + suspension_u_max: 35.0 + suspension_output_min: -35.0 + suspension_output_max: 35.0 + torque_feedforward_gain: 0.0 + suspension_torque_feedforward_gain: -1.0 rb_joint_controller: ros__parameters: + # Same joint-servo layout as lf_joint_controller measurement_angle: /chassis/right_back_joint/physical_angle measurement_velocity: /chassis/right_back_joint/physical_velocity setpoint_angle: /chassis/right_back_joint/target_physical_angle @@ -220,7 +289,7 @@ rb_joint_controller: suspension_torque: /chassis/right_back_joint/suspension_torque control: /chassis/right_back_joint/control_torque dt: 0.001 - b0: 0.60 + b0: -0.60 kt: 1.0 td_h: 0.001 td_r: 50.0 @@ -231,9 +300,28 @@ rb_joint_controller: alpha1: 0.75 alpha2: 0.7 delta: 0.02 + u_min: -200.0 + u_max: 200.0 + output_min: -200.0 + output_max: 200.0 + suspension_td_h: 0.001 + suspension_td_r: 12.0 + suspension_eso_w0: 80.0 + suspension_k1: 6.0 + suspension_k2: 3.0 + suspension_alpha1: 0.75 + suspension_alpha2: 0.7 + suspension_delta: 0.02 + suspension_u_min: -35.0 + suspension_u_max: 35.0 + suspension_output_min: -35.0 + suspension_output_max: 35.0 + torque_feedforward_gain: 0.0 + suspension_torque_feedforward_gain: -1.0 rf_joint_controller: ros__parameters: + # Same joint-servo layout as lf_joint_controller measurement_angle: /chassis/right_front_joint/physical_angle measurement_velocity: /chassis/right_front_joint/physical_velocity setpoint_angle: /chassis/right_front_joint/target_physical_angle @@ -242,7 +330,7 @@ rf_joint_controller: suspension_torque: /chassis/right_front_joint/suspension_torque control: /chassis/right_front_joint/control_torque dt: 0.001 - b0: 0.60 + b0: -0.60 kt: 1.0 td_h: 0.001 td_r: 50.0 @@ -253,3 +341,21 @@ rf_joint_controller: alpha1: 0.75 alpha2: 0.7 delta: 0.02 + u_min: -200.0 + u_max: 200.0 + output_min: -200.0 + output_max: 200.0 + suspension_td_h: 0.001 + suspension_td_r: 12.0 + suspension_eso_w0: 80.0 + suspension_k1: 6.0 + suspension_k2: 3.0 + suspension_alpha1: 0.75 + suspension_alpha2: 0.7 + suspension_delta: 0.02 + suspension_u_min: -35.0 + suspension_u_max: 35.0 + suspension_output_min: -35.0 + suspension_output_max: 35.0 + torque_feedforward_gain: 0.0 + suspension_torque_feedforward_gain: -1.0 diff --git a/rmcs_ws/src/rmcs_core/src/controller/chassis/chassis_power_controller.cpp b/rmcs_ws/src/rmcs_core/src/controller/chassis/chassis_power_controller.cpp index 1fb4fe17..2ab46819 100644 --- a/rmcs_ws/src/rmcs_core/src/controller/chassis/chassis_power_controller.cpp +++ b/rmcs_ws/src/rmcs_core/src/controller/chassis/chassis_power_controller.cpp @@ -126,7 +126,7 @@ class ChassisPowerController 0.0, 1.0); // Maximum excess power when virtual buffer energy is full. - constexpr double excess_power_limit = 15; + constexpr double excess_power_limit = 0.0; power_limit += excess_power_limit; power_limit *= virtual_buffer_energy_ / virtual_buffer_energy_limit_; diff --git a/rmcs_ws/src/rmcs_core/src/controller/chassis/deformable_chassis.cpp b/rmcs_ws/src/rmcs_core/src/controller/chassis/deformable_chassis.cpp index d7c69301..f798a48d 100644 --- a/rmcs_ws/src/rmcs_core/src/controller/chassis/deformable_chassis.cpp +++ b/rmcs_ws/src/rmcs_core/src/controller/chassis/deformable_chassis.cpp @@ -393,7 +393,7 @@ class DeformableChassis static constexpr double nan_ = std::numeric_limits::quiet_NaN(); static constexpr double translational_velocity_max_ = 10.0; - static constexpr double angular_velocity_max_ = 25.0; + static constexpr double angular_velocity_max_ = 30.0; static constexpr double rad_to_deg_ = 180.0 / std::numbers::pi; static double wrap_deg(double deg) { diff --git a/rmcs_ws/src/rmcs_core/src/controller/chassis/wheel-demo.cpp b/rmcs_ws/src/rmcs_core/src/controller/chassis/wheel-demo.cpp index 9502a303..2564501a 100644 --- a/rmcs_ws/src/rmcs_core/src/controller/chassis/wheel-demo.cpp +++ b/rmcs_ws/src/rmcs_core/src/controller/chassis/wheel-demo.cpp @@ -154,9 +154,6 @@ class WheelDemoController register_output( "/chassis/right_front_wheel/control_torque", right_front_wheel_control_torque_); - register_output("/chassis/encoder/alpha", encoder_alpha_); - register_output("/chassis/encoder/alpha_dot", encoder_alpha_dot_); - register_output("/chassis/radius", radius_); } void update() override { @@ -169,9 +166,6 @@ class WheelDemoController const JointTargetStates joint_target = update_joint_target_states_(); if (joint_feedback.valid) { vehicle_radius_ = joint_feedback.radius; - *radius_ = vehicle_radius_.mean(); - *encoder_alpha_ = joint_feedback.alpha_rad.mean(); - *encoder_alpha_dot_ = joint_feedback.alpha_dot_rad.mean(); RCLCPP_INFO_THROTTLE( get_logger(), *get_clock(), 1000, "physical joint angle[deg] lf=%.2f lb=%.2f rb=%.2f rf=%.2f, radius[m] lf=%.3f " @@ -181,10 +175,6 @@ class WheelDemoController joint_feedback.alpha_rad[2] * 180.0 / std::numbers::pi, joint_feedback.alpha_rad[3] * 180.0 / std::numbers::pi, vehicle_radius_[0], vehicle_radius_[1], vehicle_radius_[2], vehicle_radius_[3]); - } else { - *radius_ = nan_; - *encoder_alpha_ = nan_; - *encoder_alpha_dot_ = nan_; } integral_yaw_angle_imu(); @@ -392,10 +382,6 @@ class WheelDemoController last_joint_target_angle_ = Eigen::Vector4d::Zero(); last_joint_target_angle_valid_ = false; - *encoder_alpha_ = nan_; - *encoder_alpha_dot_ = nan_; - *radius_ = nan_; - *left_front_steering_control_torque_ = 0.0; *left_back_steering_control_torque_ = 0.0; *right_back_steering_control_torque_ = 0.0; @@ -857,10 +843,6 @@ class WheelDemoController OutputInterface right_back_wheel_control_torque_; OutputInterface right_front_wheel_control_torque_; - OutputInterface encoder_alpha_; - OutputInterface encoder_alpha_dot_; - OutputInterface radius_; - QcpSolver qcp_solver_; filter::LowPassFilter<3> control_acceleration_filter_; diff --git a/rmcs_ws/src/rmcs_core/src/hardware/deformable-infantry-v2.cpp b/rmcs_ws/src/rmcs_core/src/hardware/deformable-infantry-v2.cpp index 204fd938..297587ec 100644 --- a/rmcs_ws/src/rmcs_core/src/hardware/deformable-infantry-v2.cpp +++ b/rmcs_ws/src/rmcs_core/src/hardware/deformable-infantry-v2.cpp @@ -1,3 +1,4 @@ +#include #include #include #include @@ -6,6 +7,7 @@ #include #include #include +#include #include #include @@ -21,7 +23,6 @@ #include #include -#include #include #include "hardware/device/bmi088.hpp" @@ -35,6 +36,115 @@ namespace rmcs_core::hardware { using Clock = std::chrono::steady_clock; +namespace { + +class RmcsBoardLiteCompat : private librmcs::data::DataCallback { +public: + explicit RmcsBoardLiteCompat( + std::string_view serial_filter = {}, const librmcs::agent::AdvancedOptions& options = {}) + : handler_(0xA11C, 0xA801, serial_filter, options, *this) {} + + RmcsBoardLiteCompat(const RmcsBoardLiteCompat&) = delete; + RmcsBoardLiteCompat& operator=(const RmcsBoardLiteCompat&) = delete; + RmcsBoardLiteCompat(RmcsBoardLiteCompat&&) = delete; + RmcsBoardLiteCompat& operator=(RmcsBoardLiteCompat&&) = delete; + ~RmcsBoardLiteCompat() override = default; + + class PacketBuilder { + friend class RmcsBoardLiteCompat; + + public: + PacketBuilder& can0_transmit(const librmcs::data::CanDataView& data) { + if (!builder_.write_can(librmcs::data::DataId::kCan0, data)) [[unlikely]] + throw std::invalid_argument{"CAN0 transmission failed: Invalid CAN data"}; + return *this; + } + PacketBuilder& can1_transmit(const librmcs::data::CanDataView& data) { + if (!builder_.write_can(librmcs::data::DataId::kCan1, data)) [[unlikely]] + throw std::invalid_argument{"CAN1 transmission failed: Invalid CAN data"}; + return *this; + } + PacketBuilder& can2_transmit(const librmcs::data::CanDataView& data) { + if (!builder_.write_can(librmcs::data::DataId::kCan2, data)) [[unlikely]] + throw std::invalid_argument{"CAN2 transmission failed: Invalid CAN data"}; + return *this; + } + PacketBuilder& can3_transmit(const librmcs::data::CanDataView& data) { + if (!builder_.write_can(librmcs::data::DataId::kCan3, data)) [[unlikely]] + throw std::invalid_argument{"CAN3 transmission failed: Invalid CAN data"}; + return *this; + } + + PacketBuilder& uart0_transmit(const librmcs::data::UartDataView& data) { + if (!builder_.write_uart(librmcs::data::DataId::kUart0, data)) [[unlikely]] + throw std::invalid_argument{"UART0 transmission failed: Invalid UART data"}; + return *this; + } + PacketBuilder& uart1_transmit(const librmcs::data::UartDataView& data) { + if (!builder_.write_uart(librmcs::data::DataId::kUart1, data)) [[unlikely]] + throw std::invalid_argument{"UART1 transmission failed: Invalid UART data"}; + return *this; + } + + private: + explicit PacketBuilder(librmcs::host::protocol::Handler& handler) noexcept + : builder_(handler.start_transmit()) {} + + librmcs::host::protocol::Handler::PacketBuilder builder_; + }; + + PacketBuilder start_transmit() noexcept { return PacketBuilder{handler_}; } + +private: + bool can_receive_callback( + librmcs::data::DataId id, const librmcs::data::CanDataView& data) final { + switch (id) { + case librmcs::data::DataId::kCan0: can0_receive_callback(data); return true; + case librmcs::data::DataId::kCan1: can1_receive_callback(data); return true; + case librmcs::data::DataId::kCan2: can2_receive_callback(data); return true; + case librmcs::data::DataId::kCan3: can3_receive_callback(data); return true; + default: return false; + } + } + + virtual void can0_receive_callback(const librmcs::data::CanDataView& data) { (void)data; } + virtual void can1_receive_callback(const librmcs::data::CanDataView& data) { (void)data; } + virtual void can2_receive_callback(const librmcs::data::CanDataView& data) { (void)data; } + virtual void can3_receive_callback(const librmcs::data::CanDataView& data) { (void)data; } + + bool uart_receive_callback( + librmcs::data::DataId id, const librmcs::data::UartDataView& data) final { + switch (id) { + case librmcs::data::DataId::kUartDbus: dbus_receive_callback(data); return true; + case librmcs::data::DataId::kUart0: uart0_receive_callback(data); return true; + case librmcs::data::DataId::kUart1: uart1_receive_callback(data); return true; + default: return false; + } + } + + virtual void dbus_receive_callback(const librmcs::data::UartDataView& data) { (void)data; } + virtual void uart0_receive_callback(const librmcs::data::UartDataView& data) { (void)data; } + virtual void uart1_receive_callback(const librmcs::data::UartDataView& data) { (void)data; } + + void gpio_digital_read_result_callback(const librmcs::data::GpioDigitalDataView& data) final { + (void)data; + } + void gpio_analog_read_result_callback(const librmcs::data::GpioAnalogDataView& data) final { + (void)data; + } + + void accelerometer_receive_callback(const librmcs::data::AccelerometerDataView& data) override { + (void)data; + } + void gyroscope_receive_callback(const librmcs::data::GyroscopeDataView& data) override { + (void)data; + } + + librmcs::host::protocol::Handler handler_; +}; + +} // namespace + class DeformableInfantryV2 : public rmcs_executor::Component , public rclcpp::Node { @@ -180,7 +290,7 @@ class DeformableInfantryV2 DeformableInfantryV2& deformableInfantry; }; - class BottomBoard final : private librmcs::agent::RmcsBoard { + class BottomBoard final : private RmcsBoardLiteCompat { public: friend class DeformableInfantryV2; @@ -192,7 +302,7 @@ class DeformableInfantryV2 std::string serial_filter = { }) - : librmcs::agent::RmcsBoard( + : RmcsBoardLiteCompat( serial_filter, librmcs::agent::AdvancedOptions{.dangerously_skip_version_checks = true}) , deformable_infantry_(deformableInfantry) @@ -220,6 +330,8 @@ class DeformableInfantryV2 deformableInfantry, deformableInfantry_command, "/chassis/right_back_joint"}, device::LkMotor{ deformableInfantry, deformableInfantry_command, "/chassis/right_front_joint"}}, + next_chassis_feedback_log_time_(Clock::now() + std::chrono::seconds(1)), + next_supercap_feedback_log_time_(Clock::now() + std::chrono::seconds(1)), supercap_(deformableInfantry, deformableInfantry_command), gimbal_bullet_feeder_( deformableInfantry, deformableInfantry_command, "/gimbal/bullet_feeder") { @@ -255,6 +367,12 @@ class DeformableInfantryV2 .set_reversed() .enable_multi_turn_angle()); + imu_.set_coordinate_mapping([](double x, double y, double z) { + // Keep the existing chassis yaw axis mapping explicit until the bottom-board IMU + // installation is re-validated on hardware. + return std::make_tuple(-y, x, z); + }); + gimbal_bullet_feeder_.configure( device::DjiMotor::Config{device::DjiMotor::Type::kM2006}.enable_multi_turn_angle()); @@ -289,6 +407,12 @@ class DeformableInfantryV2 deformableInfantry.register_output( "/chassis/yaw/velocity_imu", chassis_yaw_velocity_imu_, 0); + deformableInfantry.register_output("/chassis/imu/pitch", chassis_imu_pitch_, 0.0); + deformableInfantry.register_output("/chassis/imu/roll", chassis_imu_roll_, 0.0); + deformableInfantry.register_output( + "/chassis/imu/pitch_rate", chassis_imu_pitch_rate_, 0.0); + deformableInfantry.register_output( + "/chassis/imu/roll_rate", chassis_imu_roll_rate_, 0.0); deformableInfantry.register_output( "/chassis/left_front_joint/physical_angle", left_front_joint_physical_angle_, nan_); deformableInfantry.register_output( @@ -314,6 +438,12 @@ class DeformableInfantryV2 deformableInfantry.register_output( "/chassis/encoder/alpha_dot", encoder_alpha_dot_, nan_); deformableInfantry.register_output("/chassis/radius", radius_, nan_); + + deformableInfantry.get_parameter_or("debug_log_supercap", debug_log_supercap_, false); + deformableInfantry.get_parameter_or( + "debug_log_wheel_motor", debug_log_wheel_motor_, false); + deformableInfantry.get_parameter_or( + "debug_log_deformable_joint_motor", debug_log_deformable_joint_motor_, false); } ~BottomBoard() override = default; @@ -321,6 +451,26 @@ class DeformableInfantryV2 void update() { imu_.update_status(); *chassis_yaw_velocity_imu_ = imu_.gz(); + { + const double q0 = imu_.q0(); + const double q1 = imu_.q1(); + const double q2 = imu_.q2(); + const double q3 = imu_.q3(); + + double sin_pitch = 2.0 * (q0 * q2 - q3 * q1); + sin_pitch = std::clamp(sin_pitch, -1.0, 1.0); + + const double standard_pitch = std::asin(sin_pitch); + const double standard_roll = + std::atan2(2.0 * (q0 * q1 + q2 * q3), 1.0 - 2.0 * (q1 * q1 + q2 * q2)); + + // Export chassis attitude using the requested convention: + // pitch < 0 when the front is higher, roll > 0 when the left side is higher. + *chassis_imu_pitch_ = -standard_pitch; + *chassis_imu_roll_ = standard_roll; + *chassis_imu_pitch_rate_ = -imu_.gy(); + *chassis_imu_roll_rate_ = imu_.gx(); + } for (auto& motor : chassis_wheel_motors_) motor.update_status(); @@ -339,29 +489,15 @@ class DeformableInfantryV2 3, right_front_joint_physical_angle_, right_front_joint_physical_velocity_); update_geometry_feedback_(); - - // if (joint_status_received_[0].load(std::memory_order_relaxed) - // && joint_status_received_[1].load(std::memory_order_relaxed) - // && joint_status_received_[2].load(std::memory_order_relaxed) - // && joint_status_received_[3].load(std::memory_order_relaxed)) { - // RCLCPP_INFO_THROTTLE( - // deformable_infantry_.get_logger(), *deformable_infantry_.get_clock(), 1000, - // "joint raw angle[deg] lf=%.2f lb=%.2f rb=%.2f rf=%.2f | physical angle[deg] " - // "lf=%.2f lb=%.2f rb=%.2f rf=%.2f", - // chassis_joint_motors_[0].angle() * 180.0 / std::numbers::pi, - // chassis_joint_motors_[1].angle() * 180.0 / std::numbers::pi, - // chassis_joint_motors_[2].angle() * 180.0 / std::numbers::pi, - // chassis_joint_motors_[3].angle() * 180.0 / std::numbers::pi, - // *left_front_joint_physical_angle_ * 180.0 / std::numbers::pi, - // *left_back_joint_physical_angle_ * 180.0 / std::numbers::pi, - // *right_back_joint_physical_angle_ * 180.0 / std::numbers::pi, - // *right_front_joint_physical_angle_ * 180.0 / std::numbers::pi); - // } + if (debug_log_wheel_motor_ || debug_log_deformable_joint_motor_) + log_chassis_feedback_once_per_second_(); dr16_.update_status(); gimbal_yaw_motor_.update_status(); if (supercap_status_received_.load(std::memory_order_relaxed)) supercap_.update_status(); + if (debug_log_supercap_) + log_supercap_feedback_once_per_second_(); gimbal_bullet_feeder_.update_status(); tf_->set_state( @@ -463,7 +599,7 @@ class DeformableInfantryV2 .as_bytes(), }); - // V2: Joint LK motors — individual CAN frames + // V2: Joint LK motors - individual CAN frames builder.can0_transmit({ .can_id = 0x141, .can_data = chassis_joint_motors_[0].generate_command().as_bytes(), @@ -533,6 +669,78 @@ class DeformableInfantryV2 *radius_ = (chassis_radius_base_ + rod_length_ * alpha_rad.array().cos()).mean(); } + void log_chassis_feedback_once_per_second_() { + const auto now = Clock::now(); + if (now < next_chassis_feedback_log_time_) + return; + + const auto wheel_rx = [this](size_t index) { + return wheel_status_received_[index].load(std::memory_order_relaxed) ? 'Y' : 'N'; + }; + const auto joint_rx = [this](size_t index) { + return joint_status_received_[index].load(std::memory_order_relaxed) ? 'Y' : 'N'; + }; + + if (debug_log_wheel_motor_) { + RCLCPP_INFO( + deformable_infantry_.get_logger(), + "[wheel motor] angle(rad) lf=% .3f lb=% .3f rb=% .3f rf=% .3f | " + "encoder(deg) lf=% .1f lb=% .1f rb=% .1f rf=% .1f | " + "rx=[%c %c %c %c]", + chassis_wheel_motors_[0].angle(), chassis_wheel_motors_[1].angle(), + chassis_wheel_motors_[2].angle(), chassis_wheel_motors_[3].angle(), + chassis_wheel_motors_[0].encoder_angle(), + chassis_wheel_motors_[1].encoder_angle(), + chassis_wheel_motors_[2].encoder_angle(), + chassis_wheel_motors_[3].encoder_angle(), wheel_rx(0), wheel_rx(1), wheel_rx(2), + wheel_rx(3)); + } + + if (debug_log_deformable_joint_motor_) { + RCLCPP_INFO( + deformable_infantry_.get_logger(), + "[deformable joint motor] angle(rad) lf=% .3f lb=% .3f rb=% .3f rf=% .3f | " + "velocity(rad/s) lf=% .3f lb=% .3f rb=% .3f rf=% .3f | " + "rx=[%c %c %c %c]", + *left_front_joint_physical_angle_, *left_back_joint_physical_angle_, + *right_back_joint_physical_angle_, *right_front_joint_physical_angle_, + *left_front_joint_physical_velocity_, *left_back_joint_physical_velocity_, + *right_back_joint_physical_velocity_, *right_front_joint_physical_velocity_, + joint_rx(0), joint_rx(1), joint_rx(2), joint_rx(3)); + } + + next_chassis_feedback_log_time_ = now + std::chrono::seconds(1); + } + + void log_supercap_feedback_once_per_second_() { + const auto now = Clock::now(); + if (now < next_supercap_feedback_log_time_) + return; + + const bool supercap_rx = supercap_status_received_.load(std::memory_order_relaxed); + auto supercap_raw_packet = latest_supercap_status_.load(std::memory_order_relaxed); + const auto supercap_raw_bytes = supercap_raw_packet.as_bytes(); + + RCLCPP_INFO( + deformable_infantry_.get_logger(), + "[supercap] can1 rx=%c id=0x300 enabled=%d supercap_v=% .3f chassis_v=% .3f " + "power=% .3f raw=[%02X %02X %02X %02X %02X %02X %02X %02X]", + supercap_rx ? 'Y' : 'N', supercap_rx ? (supercap_.supercap_enabled() ? 1 : 0) : -1, + supercap_rx ? supercap_.supercap_voltage() : nan_, + supercap_rx ? supercap_.chassis_voltage() : nan_, + supercap_rx ? supercap_.chassis_power() : nan_, + std::to_integer(supercap_raw_bytes[0]), + std::to_integer(supercap_raw_bytes[1]), + std::to_integer(supercap_raw_bytes[2]), + std::to_integer(supercap_raw_bytes[3]), + std::to_integer(supercap_raw_bytes[4]), + std::to_integer(supercap_raw_bytes[5]), + std::to_integer(supercap_raw_bytes[6]), + std::to_integer(supercap_raw_bytes[7])); + + next_supercap_feedback_log_time_ = now + std::chrono::seconds(1); + } + void dbus_receive_callback(const librmcs::data::UartDataView& data) override { dr16_.store_status(data.uart_data.data(), data.uart_data.size()); } @@ -540,9 +748,10 @@ class DeformableInfantryV2 void can0_receive_callback(const librmcs::data::CanDataView& data) override { if (data.is_extended_can_id || data.is_remote_transmission) return; - if (data.can_id == 0x201) + if (data.can_id == 0x201) { chassis_wheel_motors_[0].store_status(data.can_data); - else if (data.can_id == 0x141) { + wheel_status_received_[0].store(true, std::memory_order_relaxed); + } else if (data.can_id == 0x141) { chassis_joint_motors_[0].store_status(data.can_data); joint_status_received_[0].store(true, std::memory_order_relaxed); } else if (data.can_id == 0x205) @@ -552,14 +761,18 @@ class DeformableInfantryV2 void can1_receive_callback(const librmcs::data::CanDataView& data) override { if (data.is_extended_can_id || data.is_remote_transmission) return; - if (data.can_id == 0x201) + if (data.can_id == 0x201) { chassis_wheel_motors_[1].store_status(data.can_data); - else if (data.can_id == 0x141) { + wheel_status_received_[1].store(true, std::memory_order_relaxed); + } else if (data.can_id == 0x141) { chassis_joint_motors_[1].store_status(data.can_data); joint_status_received_[1].store(true, std::memory_order_relaxed); } else if (data.can_id == 0x205) chassis_steer_motors_[1].store_status(data.can_data); else if (data.can_id == 0x300) { + if (data.can_data.size() == 8) + latest_supercap_status_.store( + device::CanPacket8{data.can_data}, std::memory_order_relaxed); supercap_.store_status(data.can_data); supercap_status_received_.store(true, std::memory_order_relaxed); } @@ -568,9 +781,10 @@ class DeformableInfantryV2 void can2_receive_callback(const librmcs::data::CanDataView& data) override { if (data.is_extended_can_id || data.is_remote_transmission) return; - if (data.can_id == 0x201) + if (data.can_id == 0x201) { chassis_wheel_motors_[2].store_status(data.can_data); - else if (data.can_id == 0x141) { + wheel_status_received_[2].store(true, std::memory_order_relaxed); + } else if (data.can_id == 0x141) { chassis_joint_motors_[2].store_status(data.can_data); joint_status_received_[2].store(true, std::memory_order_relaxed); } else if (data.can_id == 0x142) { @@ -584,9 +798,10 @@ class DeformableInfantryV2 void can3_receive_callback(const librmcs::data::CanDataView& data) override { if (data.is_extended_can_id || data.is_remote_transmission) return; - if (data.can_id == 0x201) + if (data.can_id == 0x201) { chassis_wheel_motors_[3].store_status(data.can_data); - else if (data.can_id == 0x141) { + wheel_status_received_[3].store(true, std::memory_order_relaxed); + } else if (data.can_id == 0x141) { chassis_joint_motors_[3].store_status(data.can_data); joint_status_received_[3].store(true, std::memory_order_relaxed); } else if (data.can_id == 0x205) @@ -616,8 +831,15 @@ class DeformableInfantryV2 device::DjiMotor chassis_wheel_motors_[4]; device::DjiMotor chassis_steer_motors_[4]; device::LkMotor chassis_joint_motors_[4]; + std::atomic wheel_status_received_[4] = {false, false, false, false}; std::atomic joint_status_received_[4] = {false, false, false, false}; + bool debug_log_supercap_ = false; + bool debug_log_wheel_motor_ = false; + bool debug_log_deformable_joint_motor_ = false; + Clock::time_point next_chassis_feedback_log_time_; + Clock::time_point next_supercap_feedback_log_time_; device::Supercap supercap_; + std::atomic latest_supercap_status_{device::CanPacket8{uint64_t{0}}}; std::atomic supercap_status_received_{false}; device::DjiMotor gimbal_bullet_feeder_; @@ -625,6 +847,10 @@ class DeformableInfantryV2 OutputInterface referee_serial_; OutputInterface chassis_yaw_velocity_imu_; + OutputInterface chassis_imu_pitch_; + OutputInterface chassis_imu_roll_; + OutputInterface chassis_imu_pitch_rate_; + OutputInterface chassis_imu_roll_rate_; OutputInterface left_front_joint_physical_angle_; OutputInterface left_back_joint_physical_angle_; OutputInterface right_back_joint_physical_angle_; @@ -638,14 +864,14 @@ class DeformableInfantryV2 OutputInterface radius_; }; - class TopBoard final : private librmcs::agent::CBoard { + class TopBoard final : private RmcsBoardLiteCompat { public: friend class DeformableInfantryV2; explicit TopBoard( DeformableInfantryV2& deformableInfantry, DeformableInfantryV2Command& deformableInfantry_command, std::string serial_filter = {}) - : librmcs::agent::CBoard( + : RmcsBoardLiteCompat( serial_filter, librmcs::agent::AdvancedOptions{.dangerously_skip_version_checks = true}) , hard_sync_pending_(deformableInfantry.hard_sync_pending_) @@ -689,7 +915,7 @@ class DeformableInfantryV2 ~TopBoard() override = default; void request_hard_sync_read() { - // RMCS-board top board variant currently has no GPIO hard-sync request path. + // RMCS-lite top board variant currently has no GPIO hard-sync request path. } void update() { @@ -704,10 +930,11 @@ class DeformableInfantryV2 Eigen::Quaterniond const odom_imu_to_yaw_link{ bmi088_.q0(), bmi088_.q1(), bmi088_.q2(), bmi088_.q3()}; Eigen::Quaterniond const yaw_link_to_odom_imu = odom_imu_to_yaw_link.conjugate(); - Eigen::Quaterniond pitch_link_to_odom_imu = Eigen::Quaterniond{Eigen::AngleAxisd{ - -pitch_encoder_angle, - Eigen::Vector3d::UnitY()}} - * yaw_link_to_odom_imu; + Eigen::Quaterniond pitch_link_to_odom_imu = + Eigen::Quaterniond{ + Eigen::AngleAxisd{-pitch_encoder_angle, Eigen::Vector3d::UnitY()} + } + * yaw_link_to_odom_imu; pitch_link_to_odom_imu.normalize(); *gimbal_yaw_velocity_bmi088_ = bmi088_.gz(); @@ -723,7 +950,6 @@ class DeformableInfantryV2 void command_update() { auto builder = start_transmit(); - ; builder.can1_transmit({ .can_id = 0x141, .can_data = gimbal_pitch_motor_.generate_command().as_bytes(), From 27fa8d60441c0baf6108dcffdcd7d1ae5341b6c2 Mon Sep 17 00:00:00 2001 From: qzhhhi Date: Tue, 28 Apr 2026 19:57:19 +0800 Subject: [PATCH 02/13] feat(cross): Add multi-arch cross-build development image (#61) - Add rmcs-develop:latest-full with opposite-architecture sysroots, cross toolchains, and a build-rmcs-cross entrypoint for local cross compilation. - Update the image publishing workflow to build per-arch digests, smoke test cross builds, and promote multi-arch manifests for base, develop, develop-full, and runtime images. (cherry picked from commit 23d3469b55510a405daa109ef610607f601b6952) --- .devcontainer/devcontainer.json | 4 +- .github/workflows/update-image.yml | 377 +++++++++++++++++++++++++---- .gitignore | 5 +- .script/build-rmcs-cross | 165 +++++++++++++ .script/complete/_build-rmcs-cross | 5 + .script/host/rmcs | 2 +- Dockerfile | 134 ++++++++-- README.md | 18 ++ docs/zh-cn/build_docker_image.md | 49 +++- docs/zh-cn/cross_build.md | 87 +++++++ rmcs_ws/toolchain.cmake | 160 ++++++++++++ 11 files changed, 930 insertions(+), 76 deletions(-) create mode 100755 .script/build-rmcs-cross create mode 100644 .script/complete/_build-rmcs-cross create mode 100644 docs/zh-cn/cross_build.md create mode 100644 rmcs_ws/toolchain.cmake diff --git a/.devcontainer/devcontainer.json b/.devcontainer/devcontainer.json index da8c5cae..38ed67e9 100644 --- a/.devcontainer/devcontainer.json +++ b/.devcontainer/devcontainer.json @@ -2,7 +2,7 @@ // README at: https://github.com/devcontainers/templates/tree/main/src/docker-existing-dockerfile { "name": "rmcs-develop", - "image": "qzhhhi/rmcs-develop:latest", + "image": "qzhhhi/rmcs-develop:latest-full", "privileged": true, "mounts": [ { @@ -56,4 +56,4 @@ ] } } -} \ No newline at end of file +} diff --git a/.github/workflows/update-image.yml b/.github/workflows/update-image.yml index 435d3f46..78e039a0 100644 --- a/.github/workflows/update-image.yml +++ b/.github/workflows/update-image.yml @@ -3,49 +3,344 @@ name: Build and Push RMCS Images on: workflow_dispatch: push: - paths: - - 'Dockerfile' branches: - - main + - main + paths: + - Dockerfile + - .github/workflows/update-image.yml + - .script/build-rmcs-cross + - rmcs_ws/toolchain.cmake + +env: + REGISTRY_IMAGE_BASE: qzhhhi/rmcs-base + REGISTRY_IMAGE_DEVELOP: qzhhhi/rmcs-develop + REGISTRY_IMAGE_RUNTIME: qzhhhi/rmcs-runtime jobs: - build-and-push: - runs-on: ubuntu-latest + build_base: + strategy: + fail-fast: false + matrix: + include: + - arch: amd64 + runner: ubuntu-latest + - arch: arm64 + runner: ubuntu-24.04-arm + runs-on: ${{ matrix.runner }} + steps: + - name: Checkout repository + uses: actions/checkout@v6 + + - name: Log in to Docker Hub + uses: docker/login-action@v4 + with: + username: ${{ secrets.DOCKERHUB_USERNAME }} + password: ${{ secrets.DOCKERHUB_TOKEN }} + - name: Set up Docker Buildx + uses: docker/setup-buildx-action@v4 + + - name: Build and push by digest (Base) + id: build_base + uses: docker/build-push-action@v7 + with: + context: . + target: rmcs-base + platforms: linux/${{ matrix.arch }} + outputs: type=image,name=${{ env.REGISTRY_IMAGE_BASE }},push-by-digest=true,name-canonical=true,push=true + cache-from: type=gha,scope=docker-build-base-${{ matrix.arch }} + cache-to: type=gha,mode=max,scope=docker-build-base-${{ matrix.arch }} + + - name: Export digest (Base) + run: | + mkdir -p "${{ runner.temp }}/digests-base" + printf '%s\n' "${{ steps.build_base.outputs.digest }}" > "${{ runner.temp }}/digests-base/${{ matrix.arch }}.digest" + + - name: Upload digest (Base) + uses: actions/upload-artifact@v6 + with: + name: digests-base-${{ matrix.arch }} + path: ${{ runner.temp }}/digests-base/*.digest + if-no-files-found: error + retention-days: 1 + + build_images: + needs: build_base + strategy: + fail-fast: false + matrix: + include: + - arch: amd64 + runner: ubuntu-latest + - arch: arm64 + runner: ubuntu-24.04-arm + runs-on: ${{ matrix.runner }} steps: - - name: Checkout repository - uses: actions/checkout@v4 - - - name: Set up Docker Buildx - uses: docker/setup-buildx-action@v3 - - - name: Log in to Docker Hub - uses: docker/login-action@v3 - with: - username: ${{ secrets.DOCKERHUB_USERNAME }} - password: ${{ secrets.DOCKERHUB_TOKEN }} - - - name: Set up SSH keys - run: | - mkdir -p .ssh - chmod 700 .ssh - echo "${{ secrets.CONTAINER_ID_RSA }}" > .ssh/id_rsa - echo "${{ secrets.CONTAINER_ID_RSA_PUB }}" > .ssh/id_rsa.pub - chmod 600 .ssh/id_rsa - chmod 644 .ssh/id_rsa.pub - - - name: Build and push rmcs-develop:latest - uses: docker/build-push-action@v6 - with: - context: . - push: true - target: rmcs-develop - tags: qzhhhi/rmcs-develop:latest - - - name: Build and push rmcs-runtime:latest - uses: docker/build-push-action@v6 - with: - context: . - push: true - target: rmcs-runtime - tags: qzhhhi/rmcs-runtime:latest + - name: Checkout repository + uses: actions/checkout@v6 + + - name: Log in to Docker Hub + uses: docker/login-action@v4 + with: + username: ${{ secrets.DOCKERHUB_USERNAME }} + password: ${{ secrets.DOCKERHUB_TOKEN }} + + - name: Set up Docker Buildx + uses: docker/setup-buildx-action@v4 + + - name: Set up SSH keys + run: | + mkdir -p .ssh + chmod 700 .ssh + echo "${{ secrets.CONTAINER_ID_RSA }}" > .ssh/id_rsa + echo "${{ secrets.CONTAINER_ID_RSA_PUB }}" > .ssh/id_rsa.pub + chmod 600 .ssh/id_rsa + chmod 644 .ssh/id_rsa.pub + + - name: Download digests (Base) + uses: actions/download-artifact@v7 + with: + path: ${{ runner.temp }}/digests/base + pattern: digests-base-* + merge-multiple: true + + - name: Resolve base digests + id: resolve + run: | + set -euo pipefail + base_dir="${{ runner.temp }}/digests/base" + base_digest_amd64="$(cat "${base_dir}/amd64.digest")" + base_digest_arm64="$(cat "${base_dir}/arm64.digest")" + echo "base_digest_amd64=${base_digest_amd64}" >> "$GITHUB_OUTPUT" + echo "base_digest_arm64=${base_digest_arm64}" >> "$GITHUB_OUTPUT" + + - name: Build and push by digest (Develop) + id: build_develop + uses: docker/build-push-action@v7 + with: + context: . + target: rmcs-develop + platforms: linux/${{ matrix.arch }} + outputs: type=image,name=${{ env.REGISTRY_IMAGE_DEVELOP }},push-by-digest=true,name-canonical=true,push=true + cache-from: type=gha,scope=docker-build-develop-${{ matrix.arch }} + cache-to: type=gha,mode=max,scope=docker-build-develop-${{ matrix.arch }} + + - name: Export digest (Develop) + run: | + mkdir -p "${{ runner.temp }}/digests-develop-standard" + printf '%s\n' "${{ steps.build_develop.outputs.digest }}" > "${{ runner.temp }}/digests-develop-standard/${{ matrix.arch }}.digest" + + - name: Upload digest (Develop) + uses: actions/upload-artifact@v6 + with: + name: digests-develop-standard-${{ matrix.arch }} + path: ${{ runner.temp }}/digests-develop-standard/*.digest + if-no-files-found: error + retention-days: 1 + + - name: Build and push by digest (Develop Full) + id: build_develop_full + uses: docker/build-push-action@v7 + with: + context: . + target: rmcs-develop-full + platforms: linux/${{ matrix.arch }} + build-args: | + SYSROOT_IMAGE_AMD64=${{ env.REGISTRY_IMAGE_BASE }}@${{ steps.resolve.outputs.base_digest_amd64 }} + SYSROOT_IMAGE_ARM64=${{ env.REGISTRY_IMAGE_BASE }}@${{ steps.resolve.outputs.base_digest_arm64 }} + outputs: type=image,name=${{ env.REGISTRY_IMAGE_DEVELOP }},push-by-digest=true,name-canonical=true,push=true + cache-from: type=gha,scope=docker-build-develop-full-${{ matrix.arch }} + cache-to: type=gha,mode=max,scope=docker-build-develop-full-${{ matrix.arch }} + + - name: Export digest (Develop Full) + run: | + mkdir -p "${{ runner.temp }}/digests-develop-full" + printf '%s\n' "${{ steps.build_develop_full.outputs.digest }}" > "${{ runner.temp }}/digests-develop-full/${{ matrix.arch }}.digest" + + - name: Upload digest (Develop Full) + uses: actions/upload-artifact@v6 + with: + name: digests-develop-full-${{ matrix.arch }} + path: ${{ runner.temp }}/digests-develop-full/*.digest + if-no-files-found: error + retention-days: 1 + + - name: Build and push by digest (Runtime) + id: build_runtime + uses: docker/build-push-action@v7 + with: + context: . + target: rmcs-runtime + platforms: linux/${{ matrix.arch }} + outputs: type=image,name=${{ env.REGISTRY_IMAGE_RUNTIME }},push-by-digest=true,name-canonical=true,push=true + cache-from: type=gha,scope=docker-build-runtime-${{ matrix.arch }} + cache-to: type=gha,mode=max,scope=docker-build-runtime-${{ matrix.arch }} + + - name: Export digest (Runtime) + run: | + mkdir -p "${{ runner.temp }}/digests-runtime" + printf '%s\n' "${{ steps.build_runtime.outputs.digest }}" > "${{ runner.temp }}/digests-runtime/${{ matrix.arch }}.digest" + + - name: Upload digest (Runtime) + uses: actions/upload-artifact@v6 + with: + name: digests-runtime-${{ matrix.arch }} + path: ${{ runner.temp }}/digests-runtime/*.digest + if-no-files-found: error + retention-days: 1 + + verify_images: + needs: build_images + strategy: + fail-fast: false + matrix: + include: + - arch: amd64 + runner: ubuntu-latest + cross_target: arm64 + cross_triplet: aarch64-linux-gnu + expected_machine: AArch64 + - arch: arm64 + runner: ubuntu-24.04-arm + cross_target: amd64 + cross_triplet: x86_64-linux-gnu + expected_machine: X86-64 + runs-on: ${{ matrix.runner }} + steps: + - name: Checkout repository + uses: actions/checkout@v6 + + - name: Log in to Docker Hub + uses: docker/login-action@v4 + with: + username: ${{ secrets.DOCKERHUB_USERNAME }} + password: ${{ secrets.DOCKERHUB_TOKEN }} + + - name: Download digests (Develop Full) + uses: actions/download-artifact@v7 + with: + path: ${{ runner.temp }}/digests/develop-full + pattern: digests-develop-full-* + merge-multiple: true + + - name: Resolve develop-full digest + id: resolve + run: | + set -euo pipefail + digest_file="${{ runner.temp }}/digests/develop-full/${{ matrix.arch }}.digest" + image_digest="$(cat "${digest_file}")" + echo "image_digest=${image_digest}" >> "$GITHUB_OUTPUT" + + - name: Smoke test (cross build + readelf) + env: + IMAGE_DIGEST: ${{ steps.resolve.outputs.image_digest }} + CROSS_TARGET: ${{ matrix.cross_target }} + CROSS_TRIPLET: ${{ matrix.cross_triplet }} + EXPECTED_MACHINE: ${{ matrix.expected_machine }} + run: | + set -euo pipefail + uid="$(id -u)" + gid="$(id -g)" + docker run --rm \ + --platform "linux/${{ matrix.arch }}" \ + --user "${uid}:${gid}" \ + -e HOME=/tmp/rmcs-home \ + -e RMCS_PATH=/workspaces/RMCS \ + -e CROSS_TARGET="${CROSS_TARGET}" \ + -e CROSS_TRIPLET="${CROSS_TRIPLET}" \ + -e EXPECTED_MACHINE="${EXPECTED_MACHINE}" \ + -v "$PWD:/workspaces/RMCS" \ + -w /workspaces/RMCS \ + "${{ env.REGISTRY_IMAGE_DEVELOP }}@${IMAGE_DIGEST}" \ + bash -lc ' + set -euo pipefail + mkdir -p "${HOME}" + test -d "/opt/sysroots/${CROSS_TARGET}" + command -v "${CROSS_TRIPLET}-gcc" + command -v "${CROSS_TRIPLET}-g++" + ./.script/build-rmcs-cross --target-arch "${CROSS_TARGET}" --packages-up-to rmcs_executor + lib_path="/workspaces/RMCS/rmcs_ws/install-cross-${CROSS_TARGET}/lib/librmcs_executor.so" + if [[ ! -f "${lib_path}" ]]; then + echo "Missing library: ${lib_path}" >&2 + exit 1 + fi + readelf -h "${lib_path}" | grep -q "Machine:.*${EXPECTED_MACHINE}" + ' + + promote: + runs-on: ubuntu-latest + needs: + - build_base + - build_images + - verify_images + steps: + - name: Download digests (Base) + uses: actions/download-artifact@v7 + with: + path: ${{ runner.temp }}/digests/base + pattern: digests-base-* + merge-multiple: true + + - name: Download digests (Develop) + uses: actions/download-artifact@v7 + with: + path: ${{ runner.temp }}/digests/develop-standard + pattern: digests-develop-standard-* + merge-multiple: true + + - name: Download digests (Develop Full) + uses: actions/download-artifact@v7 + with: + path: ${{ runner.temp }}/digests/develop-full + pattern: digests-develop-full-* + merge-multiple: true + + - name: Download digests (Runtime) + uses: actions/download-artifact@v7 + with: + path: ${{ runner.temp }}/digests/runtime + pattern: digests-runtime-* + merge-multiple: true + + - name: Log in to Docker Hub + uses: docker/login-action@v4 + with: + username: ${{ secrets.DOCKERHUB_USERNAME }} + password: ${{ secrets.DOCKERHUB_TOKEN }} + + - name: Set up Docker Buildx + uses: docker/setup-buildx-action@v4 + + - name: Create manifest lists and push + run: | + set -euo pipefail + + create_manifest() { + local image="$1" + local tag="$2" + local digest_dir="$3" + local refs=() + + while IFS= read -r digest_file; do + refs+=("${image}@$(cat "${digest_file}")") + done < <(find "${digest_dir}" -maxdepth 1 -type f -name '*.digest' | sort) + + if [[ ${#refs[@]} -eq 0 ]]; then + echo "No digest files found in ${digest_dir}" >&2 + exit 1 + fi + + docker buildx imagetools create -t "${image}:${tag}" "${refs[@]}" + } + + create_manifest "${{ env.REGISTRY_IMAGE_BASE }}" "latest" "${{ runner.temp }}/digests/base" + create_manifest "${{ env.REGISTRY_IMAGE_DEVELOP }}" "latest" "${{ runner.temp }}/digests/develop-standard" + create_manifest "${{ env.REGISTRY_IMAGE_DEVELOP }}" "latest-full" "${{ runner.temp }}/digests/develop-full" + create_manifest "${{ env.REGISTRY_IMAGE_RUNTIME }}" "latest" "${{ runner.temp }}/digests/runtime" + + - name: Inspect images + run: | + docker buildx imagetools inspect "${{ env.REGISTRY_IMAGE_BASE }}:latest" + docker buildx imagetools inspect "${{ env.REGISTRY_IMAGE_DEVELOP }}:latest" + docker buildx imagetools inspect "${{ env.REGISTRY_IMAGE_DEVELOP }}:latest-full" + docker buildx imagetools inspect "${{ env.REGISTRY_IMAGE_RUNTIME }}:latest" diff --git a/.gitignore b/.gitignore index a233e981..37d2f108 100644 --- a/.gitignore +++ b/.gitignore @@ -2,6 +2,9 @@ devel/ log/ build/ install/ +log-cross-*/ +build-cross-*/ +install-cross-*/ bin/ lib/ msg_gen/ @@ -70,4 +73,4 @@ record/ # For temperary development develop_ws -.venv \ No newline at end of file +.venv diff --git a/.script/build-rmcs-cross b/.script/build-rmcs-cross new file mode 100755 index 00000000..21c987ec --- /dev/null +++ b/.script/build-rmcs-cross @@ -0,0 +1,165 @@ +#!/bin/bash + +set -euo pipefail + +: "${RMCS_PATH:=/workspaces/RMCS}" + +usage() { + cat <<'EOF' +Usage: + build-rmcs-cross --target-arch [colcon build args...] + +Examples: + build-rmcs-cross --target-arch arm64 + build-rmcs-cross --target-arch amd64 --packages-up-to rmcs_executor +EOF +} + +target_arch="" +colcon_args=() + +while (($# > 0)); do + case "$1" in + --target-arch) + if (($# < 2)); then + echo "> ERROR: --target-arch requires a value." + usage + exit 1 + fi + target_arch="$2" + shift 2 + ;; + --target-arch=*) + target_arch="${1#*=}" + shift + ;; + -h | --help) + usage + exit 0 + ;; + *) + colcon_args+=("$1") + shift + ;; + esac +done + +if [[ -z "${target_arch}" ]]; then + echo "> ERROR: --target-arch is required." + usage + exit 1 +fi + +case "${target_arch}" in +arm64) + target_triplet="aarch64-linux-gnu" + ;; +amd64) + target_triplet="x86_64-linux-gnu" + ;; +*) + echo "> ERROR: Unsupported target arch '${target_arch}'. Use arm64 or amd64." + exit 1 + ;; +esac + +workspace="${RMCS_PATH}/rmcs_ws" +toolchain_file="${workspace}/toolchain.cmake" +sysroot="${RMCS_SYSROOT:-/opt/sysroots/${target_arch}}" + +if [[ ! -d "${workspace}" ]]; then + echo "> ERROR: Workspace not found: ${workspace}" + exit 1 +fi + +if [[ ! -f "${toolchain_file}" ]]; then + echo "> ERROR: Toolchain file not found: ${toolchain_file}" + exit 1 +fi + +if [[ ! -d "${sysroot}" ]]; then + echo "> ERROR: Sysroot not found: ${sysroot}" + exit 1 +fi + +if ! command -v "${target_triplet}-gcc" &>/dev/null; then + echo "> ERROR: Missing cross compiler: ${target_triplet}-gcc" + exit 1 +fi + +if ! command -v "${target_triplet}-g++" &>/dev/null; then + echo "> ERROR: Missing cross compiler: ${target_triplet}-g++" + exit 1 +fi + +unset AMENT_PREFIX_PATH +unset CMAKE_PREFIX_PATH +unset COLCON_PREFIX_PATH +unset AMENT_CURRENT_PREFIX +unset PKG_CONFIG_PATH +unset PKG_CONFIG_LIBDIR +unset PKG_CONFIG_SYSROOT_DIR +unset ROS_PACKAGE_PATH +unset PYTHONPATH +unset PYTHONHOME +unset LD_LIBRARY_PATH +unset LIBRARY_PATH +unset CPATH +unset C_INCLUDE_PATH +unset CPLUS_INCLUDE_PATH +unset CFLAGS +unset CXXFLAGS +unset CPPFLAGS +unset LDFLAGS +unset CMAKE_INCLUDE_PATH +unset CMAKE_LIBRARY_PATH +unset CMAKE_PROGRAM_PATH +unset CMAKE_TOOLCHAIN_FILE +unset CMAKE_GENERATOR + +restore_nounset=0 +case "$-" in +*u*) + restore_nounset=1 + set +u + ;; +esac +source /opt/ros/jazzy/setup.bash +if ((restore_nounset)); then + set -u +fi + +export RMCS_TARGET_ARCH="${target_arch}" +export RMCS_TARGET_TRIPLET="${target_triplet}" +export RMCS_SYSROOT="${sysroot}" + +export CC="$(command -v "${target_triplet}-gcc")" +export CXX="$(command -v "${target_triplet}-g++")" + +export CMAKE_PREFIX_PATH="${RMCS_SYSROOT}/opt/ros/jazzy:${RMCS_SYSROOT}/usr/local:${RMCS_SYSROOT}/usr" +export AMENT_PREFIX_PATH="${RMCS_SYSROOT}/opt/ros/jazzy" +export COLCON_PREFIX_PATH="${RMCS_SYSROOT}/opt/ros/jazzy" +export PKG_CONFIG_PATH="" + +export PKG_CONFIG_SYSROOT_DIR="${RMCS_SYSROOT}" +export PKG_CONFIG_LIBDIR="${RMCS_SYSROOT}/usr/local/lib/${RMCS_TARGET_TRIPLET}/pkgconfig:${RMCS_SYSROOT}/usr/local/lib/pkgconfig:${RMCS_SYSROOT}/usr/local/share/pkgconfig:${RMCS_SYSROOT}/usr/lib/${RMCS_TARGET_TRIPLET}/pkgconfig:${RMCS_SYSROOT}/usr/lib/pkgconfig:${RMCS_SYSROOT}/usr/share/pkgconfig:${RMCS_SYSROOT}/lib/${RMCS_TARGET_TRIPLET}/pkgconfig:${RMCS_SYSROOT}/lib/pkgconfig:${RMCS_SYSROOT}/opt/ros/jazzy/lib/${RMCS_TARGET_TRIPLET}/pkgconfig:${RMCS_SYSROOT}/opt/ros/jazzy/lib/pkgconfig:${RMCS_SYSROOT}/opt/ros/jazzy/share/pkgconfig" + +cd "${workspace}" + +build_base="build-cross-${RMCS_TARGET_ARCH}" +install_base="install-cross-${RMCS_TARGET_ARCH}" +log_base="log-cross-${RMCS_TARGET_ARCH}" + +CLICOLOR_FORCE=1 NINJA_STATUS="" \ + colcon \ + --log-base "${log_base}" \ + build \ + --merge-install \ + --build-base "${build_base}" \ + --install-base "${install_base}" \ + "${colcon_args[@]}" \ + --cmake-args \ + -DCMAKE_TOOLCHAIN_FILE="${toolchain_file}" \ + -DRMCS_TARGET_ARCH="${RMCS_TARGET_ARCH}" \ + -DRMCS_SYSROOT="${RMCS_SYSROOT}" \ + -DRMCS_TARGET_TRIPLET="${RMCS_TARGET_TRIPLET}" diff --git a/.script/complete/_build-rmcs-cross b/.script/complete/_build-rmcs-cross new file mode 100644 index 00000000..18004636 --- /dev/null +++ b/.script/complete/_build-rmcs-cross @@ -0,0 +1,5 @@ +#compdef build-rmcs-cross + +_arguments \ + '--target-arch=[Cross compile target architecture]:target:(arm64 amd64)' \ + '*:colcon build args:' diff --git a/.script/host/rmcs b/.script/host/rmcs index 0b65f932..f94a7cf7 100755 --- a/.script/host/rmcs +++ b/.script/host/rmcs @@ -3,7 +3,7 @@ set -euo pipefail readonly DEVELOPER_NAME="ubuntu" -readonly NVIM_PATH="/opt/nvim-linux-x86_64/bin/nvim" +readonly NVIM_PATH="/opt/nvim/bin/nvim" readonly NVIM_PORT=6666 readonly NVIM_HOST="localhost" diff --git a/Dockerfile b/Dockerfile index e4591bad..ce3b6a57 100644 --- a/Dockerfile +++ b/Dockerfile @@ -3,8 +3,16 @@ +# Sysroot source images for rmcs-develop-full. +# CI overrides these with digest-pinned references. For local builds, build +# rmcs-base for both architectures first and pass --build-arg explicitly; +# see docs/zh-cn/build_docker_image.md. +ARG SYSROOT_IMAGE_AMD64=rmcs-base:latest +ARG SYSROOT_IMAGE_ARM64=rmcs-base:latest + # Base container, provides a runtime environment FROM ros:jazzy AS rmcs-base +ARG TARGETARCH # Change bash as default shell instead of sh SHELL ["/bin/bash", "-c"] @@ -37,14 +45,20 @@ RUN apt-get update && apt-get install -y --no-install-recommends \ # Install openvino runtime -RUN wget https://apt.repos.intel.com/intel-gpg-keys/GPG-PUB-KEY-INTEL-SW-PRODUCTS.PUB && \ - apt-key add ./GPG-PUB-KEY-INTEL-SW-PRODUCTS.PUB && \ - rm ./GPG-PUB-KEY-INTEL-SW-PRODUCTS.PUB && \ - echo "deb https://apt.repos.intel.com/openvino ubuntu24 main" > /etc/apt/sources.list.d/intel-openvino.list && \ - apt-get update && \ - apt-get install -y --no-install-recommends openvino-2025.2.0 && \ - apt-get autoremove -y && apt-get clean && \ - rm -rf /var/lib/apt/lists/* /tmp/* +RUN if [ "${TARGETARCH}" = "amd64" ]; then \ + mkdir -p /etc/apt/keyrings && \ + wget -O /etc/apt/keyrings/intel-openvino.asc \ + https://apt.repos.intel.com/intel-gpg-keys/GPG-PUB-KEY-INTEL-SW-PRODUCTS.PUB && \ + chmod 644 /etc/apt/keyrings/intel-openvino.asc && \ + echo "deb [signed-by=/etc/apt/keyrings/intel-openvino.asc] https://apt.repos.intel.com/openvino ubuntu24 main" \ + > /etc/apt/sources.list.d/intel-openvino.list && \ + apt-get update && \ + apt-get install -y --no-install-recommends openvino-2025.2.0 && \ + apt-get autoremove -y && apt-get clean && \ + rm -rf /var/lib/apt/lists/* /tmp/*; \ + else \ + echo "Skipping OpenVINO install on ${TARGETARCH}"; \ + fi # Install Livox SDK RUN git clone https://github.com/Livox-SDK/Livox-SDK2.git && \ @@ -63,17 +77,28 @@ RUN --mount=type=bind,target=/rmcs_ws/src,source=rmcs_ws/src,readonly \ apt-get autoremove -y && apt-get clean && \ rm -rf /var/lib/apt/lists/* /tmp/* -# Install unison to allow file synchronization -RUN cd /tmp && \ - wget -O unison.tar.gz https://github.com/bcpierce00/unison/releases/download/v2.53.7/unison-2.53.7-ubuntu-x86_64.tar.gz && \ - mkdir -p unison && tar -zxf unison.tar.gz -C unison && \ - cp unison/bin/* /usr/local/bin && \ - rm -rf unison unison.tar.gz - - +# Build Unison from source because upstream does not ship arm64 release binaries +# and the distro package does not include unison-fsmonitor. +# SHA256 verified against Ubuntu Launchpad source package unison-2.53.8-1. +RUN export UNISON_VERSION=2.53.8 && \ + apt-get update && \ + apt-get install -y --no-install-recommends ocaml-nox && \ + curl -L "https://github.com/bcpierce00/unison/archive/refs/tags/v${UNISON_VERSION}.tar.gz" \ + -o "/tmp/unison-v${UNISON_VERSION}.tar.gz" && \ + echo "d0d30ea63e09fc8edf10bd8cbab238fffc8ed510d27741d06b5caa816abd58b6 /tmp/unison-v${UNISON_VERSION}.tar.gz" | sha256sum -c - && \ + tar -xzf "/tmp/unison-v${UNISON_VERSION}.tar.gz" -C /tmp && \ + cd "/tmp/unison-${UNISON_VERSION}" && \ + make -j"$(nproc)" && \ + make install PREFIX=/usr/local && \ + cd / && \ + rm -rf "/tmp/unison-${UNISON_VERSION}" "/tmp/unison-v${UNISON_VERSION}.tar.gz" && \ + apt-get purge -y --auto-remove ocaml-nox && \ + apt-get clean && \ + rm -rf /var/lib/apt/lists/* /tmp/* # Developing container, works with devcontainer FROM rmcs-base AS rmcs-develop +ARG TARGETARCH # Install develop tools RUN apt-get update && apt-get install -y --no-install-recommends \ @@ -134,14 +159,25 @@ RUN --mount=type=bind,target=/tmp/.ssh,source=.ssh,readonly=false \ chown -R 1000:1000 .unison # Install latest neovim -RUN curl -LO https://github.com/neovim/neovim/releases/latest/download/nvim-linux-x86_64.tar.gz && \ +RUN case "${TARGETARCH}" in \ + amd64) nvim_arch=x86_64 ;; \ + arm64) nvim_arch=arm64 ;; \ + *) echo "Unsupported TARGETARCH: ${TARGETARCH}" >&2; exit 1 ;; \ + esac && \ + curl -LO https://github.com/neovim/neovim/releases/latest/download/nvim-linux-${nvim_arch}.tar.gz && \ rm -rf /opt/nvim && \ - tar -C /opt -xzf nvim-linux-x86_64.tar.gz && \ - rm nvim-linux-x86_64.tar.gz -ENV PATH="${PATH}:/opt/nvim-linux-x86_64/bin" + tar -C /opt -xzf nvim-linux-${nvim_arch}.tar.gz && \ + mv /opt/nvim-linux-${nvim_arch} /opt/nvim && \ + rm nvim-linux-${nvim_arch}.tar.gz +ENV PATH="${PATH}:/opt/nvim/bin" # Install latest stable cmake for user ubuntu -RUN wget https://github.com/kitware/cmake/releases/download/v4.2.3/cmake-4.2.3-linux-x86_64.sh -O install.sh && \ +RUN case "${TARGETARCH}" in \ + amd64) cmake_arch=x86_64 ;; \ + arm64) cmake_arch=aarch64 ;; \ + *) echo "Unsupported TARGETARCH: ${TARGETARCH}" >&2; exit 1 ;; \ + esac && \ + wget https://github.com/kitware/cmake/releases/download/v4.2.3/cmake-4.2.3-linux-${cmake_arch}.sh -O install.sh && \ mkdir -p /opt/cmake/ && bash install.sh --skip-license --prefix=/opt/cmake/ --exclude-subdir && \ rm install.sh @@ -164,6 +200,62 @@ RUN sh -c "$(wget https://raw.githubusercontent.com/ohmyzsh/ohmyzsh/master/tools COPY --chown=1000:1000 .script/template/env_setup.bash env_setup.bash COPY --chown=1000:1000 .script/template/env_setup.zsh env_setup.zsh +FROM --platform=linux/amd64 ${SYSROOT_IMAGE_AMD64} AS rmcs-sysroot-amd64 +FROM --platform=linux/arm64 ${SYSROOT_IMAGE_ARM64} AS rmcs-sysroot-arm64 + +# Developing container with cross toolchains and opposite-arch sysroot. +FROM rmcs-develop AS rmcs-develop-full +ARG TARGETARCH + +USER root + +RUN apt-get update && \ + case "${TARGETARCH}" in \ + amd64) cross_triplet=aarch64-linux-gnu; cross_pkg_triplet=aarch64-linux-gnu ;; \ + arm64) cross_triplet=x86_64-linux-gnu; cross_pkg_triplet=x86-64-linux-gnu ;; \ + *) echo "Unsupported TARGETARCH: ${TARGETARCH}" >&2; exit 1 ;; \ + esac && \ + apt-get install -y --no-install-recommends \ + "gcc-14-${cross_pkg_triplet}" "g++-14-${cross_pkg_triplet}" \ + "binutils-${cross_pkg_triplet}" && \ + update-alternatives --install "/usr/bin/${cross_triplet}-gcc" "${cross_triplet}-gcc" "/usr/bin/${cross_triplet}-gcc-14" 50 && \ + update-alternatives --install "/usr/bin/${cross_triplet}-g++" "${cross_triplet}-g++" "/usr/bin/${cross_triplet}-g++-14" 50 && \ + apt-get autoremove -y && apt-get clean && \ + rm -rf /var/lib/apt/lists/* /tmp/* + +RUN mkdir -p /opt/sysroots && \ + case "${TARGETARCH}" in \ + amd64) mkdir -p /opt/sysroots/arm64 ;; \ + arm64) mkdir -p /opt/sysroots/amd64 ;; \ + *) echo "Unsupported TARGETARCH: ${TARGETARCH}" >&2; exit 1 ;; \ + esac + +RUN --mount=from=rmcs-sysroot-amd64,target=/mnt/sysroot-amd64,readonly \ + --mount=from=rmcs-sysroot-arm64,target=/mnt/sysroot-arm64,readonly \ + set -euo pipefail && \ + case "${TARGETARCH}" in \ + amd64) tar \ + --exclude='./dev/*' \ + --exclude='./proc/*' \ + --exclude='./sys/*' \ + --exclude='./run/*' \ + --exclude='./tmp/*' \ + -C /mnt/sysroot-arm64 -cf - . | tar -C /opt/sysroots/arm64 -xf - ;; \ + arm64) tar \ + --exclude='./dev/*' \ + --exclude='./proc/*' \ + --exclude='./sys/*' \ + --exclude='./run/*' \ + --exclude='./tmp/*' \ + -C /mnt/sysroot-amd64 -cf - . | tar -C /opt/sysroots/amd64 -xf - ;; \ + *) echo "Unsupported TARGETARCH: ${TARGETARCH}" >&2; exit 1 ;; \ + esac + +WORKDIR /home/ubuntu +ENV USER=ubuntu +ENV WORKDIR=/home/ubuntu +USER ubuntu + # Runtime container, will automatically launch the main program FROM rmcs-base AS rmcs-runtime diff --git a/README.md b/README.md index dc365f69..75dd7ff6 100644 --- a/README.md +++ b/README.md @@ -19,6 +19,11 @@ RoboMaster Control System based on ROS2. docker pull qzhhhi/rmcs-develop:latest ``` +如需交叉编译环境,可下载: +```bash +docker pull qzhhhi/rmcs-develop:latest-full +``` + 也可自行使用 `Dockerfile` 构建,参见 [镜像构建指南](docs/zh-cn/build_docker_image.md)。 ### Step 2:克隆并打开仓库 @@ -67,6 +72,19 @@ build-rmcs Note: 用于开发的所有脚本均位于 `.script` 中,参见 开发脚本手册(TODO)。 +如需在 `latest-full` 中执行交叉编译,请根据当前容器架构选择对向目标: +```bash +build-rmcs-cross --target-arch arm64 +``` +适用于 `linux/amd64` 的 `latest-full` 变体。 + +```bash +build-rmcs-cross --target-arch amd64 +``` +适用于 `linux/arm64` 的 `latest-full` 变体。 + +详见 [交叉编译使用说明](docs/zh-cn/cross_build.md)。 + ### Step 5 (Optional):运行 编写代码并编译完成后,可以使用: diff --git a/docs/zh-cn/build_docker_image.md b/docs/zh-cn/build_docker_image.md index 88c5389a..768f977e 100644 --- a/docs/zh-cn/build_docker_image.md +++ b/docs/zh-cn/build_docker_image.md @@ -3,31 +3,60 @@ 于 Repo 根目录下,在终端中分别使用: ```bash -docker build . --target rmcs-runtime -t rmcs-runtime:latest +docker build . --target rmcs-base -t rmcs-base:latest ``` ```bash docker build . --target rmcs-develop -t rmcs-develop:latest ``` -构建开发容器和部署容器。 +```bash +docker build . --target rmcs-runtime -t rmcs-runtime:latest +``` + +构建基础容器、开发容器和部署容器。 + +## 构建 `rmcs-develop:latest-full` + +`latest-full` 需要对向架构的 `rmcs-base` 作为 sysroot 来源。 + +下面示例以在 `amd64` 主机上构建 `amd64 latest-full` 为例: + +```bash +docker buildx build . --platform linux/amd64 --target rmcs-base -t rmcs-base:linux-amd64 --load +``` + +```bash +docker buildx build . --platform linux/arm64 --target rmcs-base -t rmcs-base:linux-arm64 --load +``` + +```bash +docker buildx build . --platform linux/amd64 --target rmcs-develop-full -t rmcs-develop:latest-full \ + --build-arg SYSROOT_IMAGE_AMD64=rmcs-base:linux-amd64 \ + --build-arg SYSROOT_IMAGE_ARM64=rmcs-base:linux-arm64 \ + --load +``` + +如果是在 `arm64` 主机上构建,则交换目标平台即可(`latest-full` 的 sysroot 方向相反)。 + +## 代理构建 -需要注意的是,部分国家和地区会阻断对 `github` 的连接,此时构建需要使用代理: +部分国家和地区会阻断对 `github` 的连接,此时构建需要使用代理: ```bash docker build . --target rmcs-runtime -t rmcs-runtime:latest \ ---network host \ ---build-arg HTTP_PROXY=http://127.0.0.1:7890 \ ---build-arg HTTPS_PROXY=http://127.0.0.1:7890 + --network host \ + --build-arg HTTP_PROXY=http://127.0.0.1:7890 \ + --build-arg HTTPS_PROXY=http://127.0.0.1:7890 ``` ```bash docker build . --target rmcs-develop -t rmcs-develop:latest \ ---network host \ ---build-arg HTTP_PROXY=http://127.0.0.1:7890 \ ---build-arg HTTPS_PROXY=http://127.0.0.1:7890 + --network host \ + --build-arg HTTP_PROXY=http://127.0.0.1:7890 \ + --build-arg HTTPS_PROXY=http://127.0.0.1:7890 ``` 请自行把 `http://127.0.0.1:7890` 改为合适的代理地址。 -如果不使用本机回环地址 (127.0.0.1) 作为代理地址,构建参数中 `--network host` 可以省去。 \ No newline at end of file +如果不使用本机回环地址 (`127.0.0.1`) 作为代理地址,构建参数中的 `--network host` 可以省去。 diff --git a/docs/zh-cn/cross_build.md b/docs/zh-cn/cross_build.md new file mode 100644 index 00000000..226a3aa7 --- /dev/null +++ b/docs/zh-cn/cross_build.md @@ -0,0 +1,87 @@ +# RMCS 交叉编译使用说明(第一阶段) + +本文档说明 `rmcs-develop:latest-full`、`build-rmcs-cross` 与 CI 的约定。 + +## 1. 镜像语义 + +- `qzhhhi/rmcs-develop:latest`:原有开发镜像,行为不变。 +- `qzhhhi/rmcs-develop:latest-full`:`latest` 的超集,额外提供 cross 工具链与对向架构 sysroot。 + +对应关系: + +- `latest-full` 的 `linux/amd64` 变体内置 `/opt/sysroots/arm64` +- `latest-full` 的 `linux/arm64` 变体内置 `/opt/sysroots/amd64` + +## 2. 仓库内新增能力 + +- `rmcs_ws/toolchain.cmake`:双向 cross 参数化工具链文件。 +- `.script/build-rmcs-cross`:独立 cross 构建入口,不影响现有 `build-rmcs`。 + +`build-rmcs-cross` 默认输出目录: + +- `rmcs_ws/build-cross-` +- `rmcs_ws/install-cross-` +- `rmcs_ws/log-cross-` + +## 3. 使用方式 + +在 `latest-full` 容器里,根据当前容器架构执行对向架构的交叉编译: + +```bash +build-rmcs-cross --target-arch arm64 +``` + +适用于 `linux/amd64` 的 `latest-full` 变体。 + +```bash +build-rmcs-cross --target-arch amd64 +``` + +适用于 `linux/arm64` 的 `latest-full` 变体。 + +例如,可追加常见 `colcon build` 参数: + +```bash +build-rmcs-cross --target-arch arm64 --packages-up-to rmcs_executor +``` + +## 4. 构建环境隔离约束 + +`build-rmcs-cross` 会显式清理并重建以下环境,避免 host/target 串用: + +- `AMENT_PREFIX_PATH` +- `CMAKE_PREFIX_PATH` +- `COLCON_PREFIX_PATH` +- `PKG_CONFIG_PATH` +- `PKG_CONFIG_LIBDIR` +- `PKG_CONFIG_SYSROOT_DIR` + +并且默认启用: + +- `--merge-install` +- 不使用 `--symlink-install` + +## 5. 本地快速自检 + +```bash +test -d /opt/sysroots/arm64 +command -v aarch64-linux-gnu-gcc +./.script/build-rmcs-cross --target-arch arm64 --packages-up-to rmcs_core +readelf -h rmcs_ws/install-cross-arm64/lib/librmcs_core.so +``` + +若目标为 `amd64`,将上述 `arm64/aarch64-linux-gnu` 替换为 `amd64/x86_64-linux-gnu`。 + +本地自检故意覆盖到 `rmcs_core`,用于在推送前尽早暴露 workspace 级联依赖和交叉工具链问题;CI 只保留 `rmcs_executor` 最小 smoke,避免高频业务改动阻塞镜像推送。 + +## 6. CI 维护约定 + +- CI 先构建并推送 `qzhhhi/rmcs-base` 双架构 digest。 +- 构建 `latest-full` 时显式传入: + - `SYSROOT_IMAGE_AMD64=` + - `SYSROOT_IMAGE_ARM64=` +- `latest-full` 在每个架构 runner 上执行最小 smoke: + - sysroot 目录存在 + - cross 编译器可执行 + - `build-rmcs-cross --target-arch --packages-up-to rmcs_executor` 可完成构建 + - `readelf -h` 校验 `librmcs_executor.so` 架构 diff --git a/rmcs_ws/toolchain.cmake b/rmcs_ws/toolchain.cmake new file mode 100644 index 00000000..0a2b90fa --- /dev/null +++ b/rmcs_ws/toolchain.cmake @@ -0,0 +1,160 @@ +cmake_minimum_required(VERSION 3.16) + +foreach(_rmcs_var IN ITEMS RMCS_TARGET_ARCH RMCS_SYSROOT RMCS_TARGET_TRIPLET) + if((NOT DEFINED ${_rmcs_var} OR "${${_rmcs_var}}" STREQUAL "") AND DEFINED ENV{${_rmcs_var}}) + set(${_rmcs_var} "$ENV{${_rmcs_var}}") + endif() +endforeach() +unset(_rmcs_var) + +set(RMCS_TARGET_ARCH "${RMCS_TARGET_ARCH}" CACHE STRING "RMCS target architecture") +set(RMCS_SYSROOT "${RMCS_SYSROOT}" CACHE PATH "RMCS target sysroot path") +set(RMCS_TARGET_TRIPLET "${RMCS_TARGET_TRIPLET}" CACHE STRING "RMCS target compiler triplet") +list(APPEND CMAKE_TRY_COMPILE_PLATFORM_VARIABLES + RMCS_TARGET_ARCH + RMCS_SYSROOT + RMCS_TARGET_TRIPLET +) + +if(NOT RMCS_TARGET_ARCH) + message(FATAL_ERROR "RMCS_TARGET_ARCH is required. Supported values: arm64, amd64.") +endif() + +if(NOT RMCS_TARGET_TRIPLET) + if(RMCS_TARGET_ARCH STREQUAL "arm64") + set(RMCS_TARGET_TRIPLET "aarch64-linux-gnu") + elseif(RMCS_TARGET_ARCH STREQUAL "amd64") + set(RMCS_TARGET_TRIPLET "x86_64-linux-gnu") + else() + message(FATAL_ERROR "Unsupported RMCS_TARGET_ARCH: ${RMCS_TARGET_ARCH}") + endif() +endif() + +if(NOT RMCS_SYSROOT) + set(RMCS_SYSROOT "/opt/sysroots/${RMCS_TARGET_ARCH}") +endif() + +if(NOT EXISTS "${RMCS_SYSROOT}") + message(FATAL_ERROR "RMCS_SYSROOT does not exist: ${RMCS_SYSROOT}") +endif() + +set(CMAKE_SYSTEM_NAME Linux) +if(RMCS_TARGET_ARCH STREQUAL "arm64") + set(CMAKE_SYSTEM_PROCESSOR aarch64) +elseif(RMCS_TARGET_ARCH STREQUAL "amd64") + set(CMAKE_SYSTEM_PROCESSOR x86_64) +else() + message(FATAL_ERROR "Unsupported RMCS_TARGET_ARCH: ${RMCS_TARGET_ARCH}") +endif() + +set(CMAKE_SYSROOT "${RMCS_SYSROOT}") +set(_rmcs_find_root_path "${RMCS_SYSROOT}") +foreach(_rmcs_prefix_env IN ITEMS AMENT_PREFIX_PATH CMAKE_PREFIX_PATH) + if(DEFINED ENV{${_rmcs_prefix_env}} AND NOT "$ENV{${_rmcs_prefix_env}}" STREQUAL "") + string(REPLACE ":" ";" _rmcs_env_prefixes "$ENV{${_rmcs_prefix_env}}") + list(APPEND _rmcs_find_root_path ${_rmcs_env_prefixes}) + endif() +endforeach() +list(REMOVE_DUPLICATES _rmcs_find_root_path) +set(CMAKE_FIND_ROOT_PATH + "${_rmcs_find_root_path}" +) +set(CMAKE_FIND_ROOT_PATH_MODE_PROGRAM NEVER) +set(CMAKE_FIND_ROOT_PATH_MODE_LIBRARY ONLY) +set(CMAKE_FIND_ROOT_PATH_MODE_INCLUDE ONLY) +set(CMAKE_FIND_ROOT_PATH_MODE_PACKAGE ONLY) + +function(rmcs_find_host_program output_var) + set(options) + set(oneValueArgs ENV_VAR) + set(multiValueArgs NAMES) + cmake_parse_arguments(RMCS_FIND_HOST_PROGRAM "${options}" "${oneValueArgs}" "${multiValueArgs}" ${ARGN}) + + if(NOT RMCS_FIND_HOST_PROGRAM_NAMES) + message(FATAL_ERROR "rmcs_find_host_program requires at least one candidate in NAMES.") + endif() + + unset(_rmcs_resolved_program CACHE) + unset(_rmcs_resolved_program) + string(REPLACE ":" ";" _rmcs_host_path_entries "$ENV{PATH}") + if(RMCS_FIND_HOST_PROGRAM_ENV_VAR + AND DEFINED ENV{${RMCS_FIND_HOST_PROGRAM_ENV_VAR}} + AND NOT "$ENV{${RMCS_FIND_HOST_PROGRAM_ENV_VAR}}" STREQUAL "") + set(_rmcs_program_candidates "$ENV{${RMCS_FIND_HOST_PROGRAM_ENV_VAR}}") + if(IS_ABSOLUTE "${_rmcs_program_candidates}") + if(NOT EXISTS "${_rmcs_program_candidates}" OR IS_DIRECTORY "${_rmcs_program_candidates}") + message(FATAL_ERROR + "${RMCS_FIND_HOST_PROGRAM_ENV_VAR} points to a missing executable: ${_rmcs_program_candidates}" + ) + endif() + set(_rmcs_resolved_program "${_rmcs_program_candidates}") + else() + find_program(_rmcs_resolved_program + NAMES "${_rmcs_program_candidates}" + PATHS ${_rmcs_host_path_entries} + NO_DEFAULT_PATH + ) + endif() + else() + set(_rmcs_program_candidates ${RMCS_FIND_HOST_PROGRAM_NAMES}) + find_program(_rmcs_resolved_program + NAMES ${_rmcs_program_candidates} + PATHS ${_rmcs_host_path_entries} + NO_DEFAULT_PATH + ) + endif() + + if(NOT _rmcs_resolved_program) + list(JOIN _rmcs_program_candidates ", " _rmcs_program_candidates_str) + message(FATAL_ERROR "Cannot resolve host program. Tried: ${_rmcs_program_candidates_str}") + endif() + + set(${output_var} "${_rmcs_resolved_program}" PARENT_SCOPE) +endfunction() + +rmcs_find_host_program(RMCS_C_COMPILER ENV_VAR CC NAMES "${RMCS_TARGET_TRIPLET}-gcc") +rmcs_find_host_program(RMCS_CXX_COMPILER ENV_VAR CXX NAMES "${RMCS_TARGET_TRIPLET}-g++") +rmcs_find_host_program(RMCS_PYTHON_EXECUTABLE NAMES python3) +rmcs_find_host_program(RMCS_PKG_CONFIG_EXECUTABLE NAMES pkg-config pkgconf) + +if(NOT RMCS_C_COMPILER) + message(FATAL_ERROR "Cannot find C compiler: ${RMCS_TARGET_TRIPLET}-gcc") +endif() +if(NOT RMCS_CXX_COMPILER) + message(FATAL_ERROR "Cannot find CXX compiler: ${RMCS_TARGET_TRIPLET}-g++") +endif() + +set(CMAKE_C_COMPILER "${RMCS_C_COMPILER}") +set(CMAKE_CXX_COMPILER "${RMCS_CXX_COMPILER}") +set(Python3_EXECUTABLE "${RMCS_PYTHON_EXECUTABLE}" CACHE FILEPATH "Host Python interpreter" FORCE) +set(AMENT_PYTHON_EXECUTABLE "${RMCS_PYTHON_EXECUTABLE}" CACHE FILEPATH "Host Python interpreter for ament" FORCE) +set(PKG_CONFIG_EXECUTABLE "${RMCS_PKG_CONFIG_EXECUTABLE}" CACHE FILEPATH "Host pkg-config executable" FORCE) + +if(CMAKE_GENERATOR MATCHES "Makefiles") + rmcs_find_host_program(RMCS_MAKE_PROGRAM NAMES gmake make) + set(CMAKE_MAKE_PROGRAM "${RMCS_MAKE_PROGRAM}" CACHE FILEPATH "Host make program" FORCE) +endif() + +set(CMAKE_PREFIX_PATH + "/opt/ros/jazzy" + "/usr/local" + "/usr" + CACHE STRING "Target-side prefix path for cross-compilation" +) + +set(ENV{PKG_CONFIG_SYSROOT_DIR} "${RMCS_SYSROOT}") +set(_rmcs_pkg_config_libdirs + "${RMCS_SYSROOT}/usr/local/lib/${RMCS_TARGET_TRIPLET}/pkgconfig" + "${RMCS_SYSROOT}/usr/local/lib/pkgconfig" + "${RMCS_SYSROOT}/usr/local/share/pkgconfig" + "${RMCS_SYSROOT}/usr/lib/${RMCS_TARGET_TRIPLET}/pkgconfig" + "${RMCS_SYSROOT}/usr/lib/pkgconfig" + "${RMCS_SYSROOT}/usr/share/pkgconfig" + "${RMCS_SYSROOT}/lib/${RMCS_TARGET_TRIPLET}/pkgconfig" + "${RMCS_SYSROOT}/lib/pkgconfig" + "${RMCS_SYSROOT}/opt/ros/jazzy/lib/${RMCS_TARGET_TRIPLET}/pkgconfig" + "${RMCS_SYSROOT}/opt/ros/jazzy/lib/pkgconfig" + "${RMCS_SYSROOT}/opt/ros/jazzy/share/pkgconfig" +) +list(JOIN _rmcs_pkg_config_libdirs ":" _rmcs_pkg_config_libdir) +set(ENV{PKG_CONFIG_LIBDIR} "${_rmcs_pkg_config_libdir}") From 49d3ae0d307c1ea945f2d5445975ec29948747c8 Mon Sep 17 00:00:00 2001 From: ZGZ713912 Date: Thu, 30 Apr 2026 23:25:24 +0800 Subject: [PATCH 03/13] feat(build): add support for linking default directories to cross build outputs - Introduced `--link-default` option in `build-rmcs-cross` to create symlinks for build, install, and log directories pointing to their respective cross build outputs. - Updated documentation to reflect the new linking feature. - Added checks to ensure the target directories are valid before linking. - Modified the default serial filter in the configuration for deformable infantry. --- .script/build-rmcs | 40 ++++++++++++++++++ .script/build-rmcs-cross | 42 ++++++++++++++++++- .script/complete/_build-rmcs-cross | 1 + docs/zh-cn/cross_build.md | 24 +++++++++++ rmcs_ws/build | 1 + rmcs_ws/install | 1 + rmcs_ws/log | 1 + .../config/deformable-infantry-v2.yaml | 2 +- 8 files changed, 110 insertions(+), 2 deletions(-) create mode 120000 rmcs_ws/build create mode 120000 rmcs_ws/install create mode 120000 rmcs_ws/log diff --git a/.script/build-rmcs b/.script/build-rmcs index 2c24a7ed..a95deed0 100755 --- a/.script/build-rmcs +++ b/.script/build-rmcs @@ -11,6 +11,46 @@ fi cd "${RMCS_PATH}"/rmcs_ws || exit 1 +check_default_dir_restorable() { + local link_name="$1" + local expected_prefix="$2" + + if [[ ! -L "${link_name}" ]]; then + return + fi + + local target + target="$(readlink "${link_name}")" + if [[ "${target}" != "${expected_prefix}"-cross-* && "${target}" != */"${expected_prefix}"-cross-* ]]; then + echo "> ERROR: ${RMCS_PATH}/rmcs_ws/${link_name} is a symlink to ${target}." + echo "> It is not a build-rmcs-cross default link. Fix it before running build-rmcs." + exit 1 + fi +} + +restore_default_dir() { + local link_name="$1" + + if [[ ! -L "${link_name}" ]]; then + return + fi + + local target + target="$(readlink "${link_name}")" + + rm "${link_name}" || exit 1 + mkdir -p "${link_name}" || exit 1 + echo "> Restored ${RMCS_PATH}/rmcs_ws/${link_name} from ${target} symlink." +} + +check_default_dir_restorable build build +check_default_dir_restorable install install +check_default_dir_restorable log log + +restore_default_dir build +restore_default_dir install +restore_default_dir log + [[ -x /opt/cmake/bin/cmake ]] && export PATH="/opt/cmake/bin:$PATH" diff --git a/.script/build-rmcs-cross b/.script/build-rmcs-cross index 21c987ec..488054da 100755 --- a/.script/build-rmcs-cross +++ b/.script/build-rmcs-cross @@ -7,15 +7,17 @@ set -euo pipefail usage() { cat <<'EOF' Usage: - build-rmcs-cross --target-arch [colcon build args...] + build-rmcs-cross --target-arch [--link-default] [colcon build args...] Examples: build-rmcs-cross --target-arch arm64 + build-rmcs-cross --target-arch arm64 --link-default build-rmcs-cross --target-arch amd64 --packages-up-to rmcs_executor EOF } target_arch="" +link_default=0 colcon_args=() while (($# > 0)); do @@ -33,6 +35,10 @@ while (($# > 0)); do target_arch="${1#*=}" shift ;; + --link-default) + link_default=1 + shift + ;; -h | --help) usage exit 0 @@ -150,6 +156,30 @@ build_base="build-cross-${RMCS_TARGET_ARCH}" install_base="install-cross-${RMCS_TARGET_ARCH}" log_base="log-cross-${RMCS_TARGET_ARCH}" +check_default_linkable() { + local target="$1" + local link_name="$2" + + if [[ ! -d "${target}" ]]; then + echo "> ERROR: Cross build output not found: ${workspace}/${target}" + exit 1 + fi + + if [[ -e "${link_name}" && ! -L "${link_name}" ]]; then + echo "> ERROR: Cannot link ${workspace}/${link_name} -> ${target}." + echo "> ${workspace}/${link_name} exists and is not a symlink. Move or remove it first." + exit 1 + fi +} + +link_default_base() { + local target="$1" + local link_name="$2" + + ln -sfnT "${target}" "${link_name}" + echo "> Linked ${workspace}/${link_name} -> ${target}" +} + CLICOLOR_FORCE=1 NINJA_STATUS="" \ colcon \ --log-base "${log_base}" \ @@ -163,3 +193,13 @@ CLICOLOR_FORCE=1 NINJA_STATUS="" \ -DRMCS_TARGET_ARCH="${RMCS_TARGET_ARCH}" \ -DRMCS_SYSROOT="${RMCS_SYSROOT}" \ -DRMCS_TARGET_TRIPLET="${RMCS_TARGET_TRIPLET}" + +if ((link_default)); then + check_default_linkable "${build_base}" build + check_default_linkable "${install_base}" install + check_default_linkable "${log_base}" log + + link_default_base "${build_base}" build + link_default_base "${install_base}" install + link_default_base "${log_base}" log +fi diff --git a/.script/complete/_build-rmcs-cross b/.script/complete/_build-rmcs-cross index 18004636..34d609c2 100644 --- a/.script/complete/_build-rmcs-cross +++ b/.script/complete/_build-rmcs-cross @@ -2,4 +2,5 @@ _arguments \ '--target-arch=[Cross compile target architecture]:target:(arm64 amd64)' \ + '--link-default[Link build/install/log to cross build output directories]' \ '*:colcon build args:' diff --git a/docs/zh-cn/cross_build.md b/docs/zh-cn/cross_build.md index 226a3aa7..25dfb805 100644 --- a/docs/zh-cn/cross_build.md +++ b/docs/zh-cn/cross_build.md @@ -45,6 +45,30 @@ build-rmcs-cross --target-arch amd64 build-rmcs-cross --target-arch arm64 --packages-up-to rmcs_executor ``` +若需要让现有 `sync-remote`、`env_setup` 等继续使用默认目录,可在 cross 构建成功后自动链接默认目录: + +```bash +build-rmcs-cross --target-arch arm64 --link-default +``` + +链接方向等价于在 `rmcs_ws` 下执行: + +```bash +ln -sfn build-cross-arm64 build +ln -sfn install-cross-arm64 install +ln -sfn log-cross-arm64 log +``` + +也就是创建或更新默认目录名,让 `build`、`install`、`log` 这三个软链接分别指向对应的 `*-cross-arm64` 目录。 + +切回 native 构建时,直接运行: + +```bash +build-rmcs +``` + +`build-rmcs` 会自动识别上述 cross 默认软链接,删除软链接并恢复成普通目录。 + ## 4. 构建环境隔离约束 `build-rmcs-cross` 会显式清理并重建以下环境,避免 host/target 串用: diff --git a/rmcs_ws/build b/rmcs_ws/build new file mode 120000 index 00000000..2ec6ad5a --- /dev/null +++ b/rmcs_ws/build @@ -0,0 +1 @@ +build-cross-arm64 \ No newline at end of file diff --git a/rmcs_ws/install b/rmcs_ws/install new file mode 120000 index 00000000..4ed00624 --- /dev/null +++ b/rmcs_ws/install @@ -0,0 +1 @@ +install-cross-arm64 \ No newline at end of file diff --git a/rmcs_ws/log b/rmcs_ws/log new file mode 120000 index 00000000..4c7d622b --- /dev/null +++ b/rmcs_ws/log @@ -0,0 +1 @@ +log-cross-arm64 \ No newline at end of file diff --git a/rmcs_ws/src/rmcs_bringup/config/deformable-infantry-v2.yaml b/rmcs_ws/src/rmcs_bringup/config/deformable-infantry-v2.yaml index 246e5c5f..534b06d8 100644 --- a/rmcs_ws/src/rmcs_bringup/config/deformable-infantry-v2.yaml +++ b/rmcs_ws/src/rmcs_bringup/config/deformable-infantry-v2.yaml @@ -53,7 +53,7 @@ value_broadcaster: deformable_infantry: ros__parameters: - serial_filter_rmcs_board: "AF-23FB-EE32-B892-1302-AE70-D640-7B4E-0CBF" + serial_filter_rmcs_board: "AF-73B2-E8A1-A544-79ED-5BDA-D088-7F21-A6A6" serial_filter_top_board: "AF-ABAC-786D-1B53-99F6-00A2-42A6-AA95-9D69" left_front_zero_point: 374 left_back_zero_point: 5801 From 2fb4ffde28e7469ffecfa51ace7b3822b7583da6 Mon Sep 17 00:00:00 2001 From: ZGZ713912 Date: Fri, 1 May 2026 03:08:01 +0800 Subject: [PATCH 04/13] fix(config): update serial filter and motor zero points for deformable infantry --- .../rmcs_bringup/config/deformable-infantry-v2.yaml | 10 +++++----- .../rmcs_core/src/hardware/deformable-infantry-v2.cpp | 8 ++++---- 2 files changed, 9 insertions(+), 9 deletions(-) diff --git a/rmcs_ws/src/rmcs_bringup/config/deformable-infantry-v2.yaml b/rmcs_ws/src/rmcs_bringup/config/deformable-infantry-v2.yaml index 534b06d8..a1155cb6 100644 --- a/rmcs_ws/src/rmcs_bringup/config/deformable-infantry-v2.yaml +++ b/rmcs_ws/src/rmcs_bringup/config/deformable-infantry-v2.yaml @@ -53,14 +53,14 @@ value_broadcaster: deformable_infantry: ros__parameters: - serial_filter_rmcs_board: "AF-73B2-E8A1-A544-79ED-5BDA-D088-7F21-A6A6" + serial_filter_rmcs_board: "AF-23FB-EE32-B892-1302-AE70-D640-7B4E-0CBF" serial_filter_top_board: "AF-ABAC-786D-1B53-99F6-00A2-42A6-AA95-9D69" left_front_zero_point: 374 left_back_zero_point: 5801 right_back_zero_point: 7817 right_front_zero_point: 7136 - yaw_motor_zero_point: 56216 - pitch_motor_zero_point: 10898 + yaw_motor_zero_point: 39442 + pitch_motor_zero_point: 56556 debug_log_supercap: false debug_log_wheel_motor: false debug_log_deformable_joint_motor: false @@ -68,8 +68,8 @@ deformable_infantry: chassis_controller: ros__parameters: # Deploy geometry / chassis-owned joint intent - min_angle: 8.0 - max_angle: 58.0 + min_angle: 20.0 + max_angle: 50.0 active_suspension_enable: true # IMU attitude correction at min-angle stance. diff --git a/rmcs_ws/src/rmcs_core/src/hardware/deformable-infantry-v2.cpp b/rmcs_ws/src/rmcs_core/src/hardware/deformable-infantry-v2.cpp index 297587ec..297d0fe7 100644 --- a/rmcs_ws/src/rmcs_core/src/hardware/deformable-infantry-v2.cpp +++ b/rmcs_ws/src/rmcs_core/src/hardware/deformable-infantry-v2.cpp @@ -950,12 +950,12 @@ class DeformableInfantryV2 void command_update() { auto builder = start_transmit(); - builder.can1_transmit({ + builder.can0_transmit({ .can_id = 0x141, .can_data = gimbal_pitch_motor_.generate_command().as_bytes(), }); - builder.can2_transmit({ + builder.can1_transmit({ .can_id = 0x200, .can_data = device::CanPacket8{ @@ -971,14 +971,14 @@ class DeformableInfantryV2 private: void uart1_receive_callback(const librmcs::data::UartDataView&) override {} - void can1_receive_callback(const librmcs::data::CanDataView& data) override { + void can0_receive_callback(const librmcs::data::CanDataView& data) override { if (data.is_extended_can_id || data.is_remote_transmission) [[unlikely]] return; if (data.can_id == 0x141) gimbal_pitch_motor_.store_status(data.can_data); } - void can2_receive_callback(const librmcs::data::CanDataView& data) override { + void can1_receive_callback(const librmcs::data::CanDataView& data) override { if (data.is_extended_can_id || data.is_remote_transmission) [[unlikely]] return; if (data.can_id == 0x201) From bee50be6b185fd0f08cc75a0db337e447176a3d5 Mon Sep 17 00:00:00 2001 From: ZGZ713912 Date: Fri, 1 May 2026 16:15:15 +0800 Subject: [PATCH 05/13] fix(config): update zero points for deformable infantry motors --- .../src/rmcs_bringup/config/deformable-infantry-v2.yaml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/rmcs_ws/src/rmcs_bringup/config/deformable-infantry-v2.yaml b/rmcs_ws/src/rmcs_bringup/config/deformable-infantry-v2.yaml index a1155cb6..09c1c132 100644 --- a/rmcs_ws/src/rmcs_bringup/config/deformable-infantry-v2.yaml +++ b/rmcs_ws/src/rmcs_bringup/config/deformable-infantry-v2.yaml @@ -55,10 +55,10 @@ deformable_infantry: ros__parameters: serial_filter_rmcs_board: "AF-23FB-EE32-B892-1302-AE70-D640-7B4E-0CBF" serial_filter_top_board: "AF-ABAC-786D-1B53-99F6-00A2-42A6-AA95-9D69" - left_front_zero_point: 374 - left_back_zero_point: 5801 - right_back_zero_point: 7817 - right_front_zero_point: 7136 + left_front_zero_point: 7224 + left_back_zero_point: 5154 + right_back_zero_point: 4356 + right_front_zero_point: 5061 yaw_motor_zero_point: 39442 pitch_motor_zero_point: 56556 debug_log_supercap: false From 5d7a3053b874dc2f6fa76ab1f82e7272b095080d Mon Sep 17 00:00:00 2001 From: creeper5820 Date: Fri, 1 May 2026 21:06:26 +0800 Subject: [PATCH 06/13] clean: remove unused files --- AGENTS.md | 228 ------ CLAUDE.md | 85 --- code-plan.md | 397 ----------- ...le_infantry_omni_active_suspension_flow.md | 160 ----- foxglove_like_yaw_plot_from_script.png | Bin 499399 -> 0 bytes librmcs-sdk-src-3.1.0-beta.1/CMakeLists.txt | 5 - .../CMakePresets.json | 6 - librmcs-sdk-src-3.1.0-beta.1/LICENSE | 674 ------------------ librmcs-sdk-src-3.1.0-beta.1/core/.gitignore | 2 - .../core/include/librmcs/data/datas.hpp | 105 --- .../core/setup-clangd | 45 -- .../core/src/coroutine/lifo.hpp | 272 ------- .../core/src/protocol/constant.hpp | 9 - .../core/src/protocol/deserializer.cpp | 292 -------- .../core/src/protocol/deserializer.hpp | 266 ------- .../core/src/protocol/protocol.hpp | 133 ---- .../core/src/protocol/serializer.hpp | 443 ------------ .../core/src/utility/assert.hpp | 58 -- .../core/src/utility/bitfield.hpp | 273 ------- .../core/src/utility/immovable.hpp | 15 - .../core/src/utility/stack_allocator.hpp | 95 --- .../core/src/utility/uncopyable.hpp | 15 - .../core/src/utility/verify.hpp | 19 - .../host/CMakeLists.txt | 168 ----- .../host/CMakePresets.json | 25 - .../host/include/librmcs/agent/c_board.hpp | 126 ---- .../host/include/librmcs/agent/common.hpp | 9 - .../host/include/librmcs/agent/rmcs_board.hpp | 133 ---- .../host/include/librmcs/export.hpp | 19 - .../host/include/librmcs/protocol/handler.hpp | 63 -- .../host/src/logging/logging.hpp | 163 ----- .../host/src/protocol/handler.cpp | 236 ------ .../host/src/protocol/stream_buffer.hpp | 227 ------ .../host/src/transport/transport.hpp | 153 ---- .../host/src/transport/usb/device_scanner.hpp | 442 ------------ .../host/src/transport/usb/helper.hpp | 26 - .../host/src/transport/usb/usb.cpp | 363 ---------- .../host/src/utility/assert.cpp | 17 - .../host/src/utility/cross_os.hpp | 35 - .../host/src/utility/final_action.hpp | 32 - .../host/src/utility/ring_buffer.hpp | 277 ------- librmcs-sdk-src-3.1.0/CMakeLists.txt | 5 - librmcs-sdk-src-3.1.0/CMakePresets.json | 6 - librmcs-sdk-src-3.1.0/LICENSE | 674 ------------------ librmcs-sdk-src-3.1.0/core/.gitignore | 2 - .../core/include/librmcs/data/datas.hpp | 105 --- librmcs-sdk-src-3.1.0/core/setup-clangd | 45 -- .../core/src/coroutine/lifo.hpp | 272 ------- .../core/src/protocol/constant.hpp | 9 - .../core/src/protocol/deserializer.cpp | 292 -------- .../core/src/protocol/deserializer.hpp | 266 ------- .../core/src/protocol/protocol.hpp | 133 ---- .../core/src/protocol/serializer.hpp | 443 ------------ .../core/src/utility/assert.hpp | 58 -- .../core/src/utility/bitfield.hpp | 273 ------- .../core/src/utility/immovable.hpp | 15 - .../core/src/utility/stack_allocator.hpp | 95 --- .../core/src/utility/uncopyable.hpp | 15 - .../core/src/utility/verify.hpp | 19 - librmcs-sdk-src-3.1.0/host/CMakeLists.txt | 168 ----- librmcs-sdk-src-3.1.0/host/CMakePresets.json | 25 - .../host/include/librmcs/agent/c_board.hpp | 121 ---- .../host/include/librmcs/agent/common.hpp | 9 - .../include/librmcs/agent/rmcs_board_lite.hpp | 114 --- .../include/librmcs/agent/rmcs_board_pro.hpp | 128 ---- .../host/include/librmcs/export.hpp | 19 - .../host/include/librmcs/protocol/handler.hpp | 63 -- .../host/src/logging/logging.hpp | 163 ----- .../host/src/protocol/handler.cpp | 236 ------ .../host/src/protocol/stream_buffer.hpp | 227 ------ .../host/src/transport/transport.hpp | 153 ---- .../host/src/transport/usb/device_scanner.hpp | 440 ------------ .../host/src/transport/usb/helper.hpp | 26 - .../host/src/transport/usb/usb.cpp | 363 ---------- .../host/src/utility/assert.cpp | 17 - .../host/src/utility/cross_os.hpp | 35 - .../host/src/utility/final_action.hpp | 32 - .../host/src/utility/ring_buffer.hpp | 277 ------- package-lock.json | 625 ---------------- package.json | 5 - plan.md | 237 ------ rmcs_notebook | 1 - rmcs_ws/src/rmcs_auto_aim_v2 | 1 + rmcs_ws/src/rmcs_core/CMakeLists.txt | 34 +- rmcs_ws/src/rmcs_core/librmcs | 1 - .../src/hardware/deformable-infantry-omni.cpp | 22 +- .../src/hardware/deformable-infantry-v2.cpp | 15 +- .../src/hardware/deformable-infantry.cpp | 664 ----------------- rmcs_ws/src/rmcs_core/third_party/tinympc | 1 - rmcs_ws/src/{hikcamera => ros2-hikcamera} | 0 rmcs_ws/src/serial | 1 - rmcs_ws/src/sp_vision_25 | 1 - sp-vision.md | 167 ----- sp_vision_25 | 1 - sp_vision_response_test.csv | 343 --------- todo.md | 382 ---------- wheel.typ | 410 ----------- 97 files changed, 24 insertions(+), 14341 deletions(-) delete mode 100644 AGENTS.md delete mode 100644 CLAUDE.md delete mode 100644 code-plan.md delete mode 100644 deformable_infantry_omni_active_suspension_flow.md delete mode 100644 foxglove_like_yaw_plot_from_script.png delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/CMakeLists.txt delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/CMakePresets.json delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/LICENSE delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/core/.gitignore delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/core/include/librmcs/data/datas.hpp delete mode 100755 librmcs-sdk-src-3.1.0-beta.1/core/setup-clangd delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/core/src/coroutine/lifo.hpp delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/core/src/protocol/constant.hpp delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/core/src/protocol/deserializer.cpp delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/core/src/protocol/deserializer.hpp delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/core/src/protocol/protocol.hpp delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/core/src/protocol/serializer.hpp delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/core/src/utility/assert.hpp delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/core/src/utility/bitfield.hpp delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/core/src/utility/immovable.hpp delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/core/src/utility/stack_allocator.hpp delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/core/src/utility/uncopyable.hpp delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/core/src/utility/verify.hpp delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/host/CMakeLists.txt delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/host/CMakePresets.json delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/host/include/librmcs/agent/c_board.hpp delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/host/include/librmcs/agent/common.hpp delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/host/include/librmcs/agent/rmcs_board.hpp delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/host/include/librmcs/export.hpp delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/host/include/librmcs/protocol/handler.hpp delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/host/src/logging/logging.hpp delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/host/src/protocol/handler.cpp delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/host/src/protocol/stream_buffer.hpp delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/host/src/transport/transport.hpp delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/host/src/transport/usb/device_scanner.hpp delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/host/src/transport/usb/helper.hpp delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/host/src/transport/usb/usb.cpp delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/host/src/utility/assert.cpp delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/host/src/utility/cross_os.hpp delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/host/src/utility/final_action.hpp delete mode 100644 librmcs-sdk-src-3.1.0-beta.1/host/src/utility/ring_buffer.hpp delete mode 100644 librmcs-sdk-src-3.1.0/CMakeLists.txt delete mode 100644 librmcs-sdk-src-3.1.0/CMakePresets.json delete mode 100644 librmcs-sdk-src-3.1.0/LICENSE delete mode 100644 librmcs-sdk-src-3.1.0/core/.gitignore delete mode 100644 librmcs-sdk-src-3.1.0/core/include/librmcs/data/datas.hpp delete mode 100755 librmcs-sdk-src-3.1.0/core/setup-clangd delete mode 100644 librmcs-sdk-src-3.1.0/core/src/coroutine/lifo.hpp delete mode 100644 librmcs-sdk-src-3.1.0/core/src/protocol/constant.hpp delete mode 100644 librmcs-sdk-src-3.1.0/core/src/protocol/deserializer.cpp delete mode 100644 librmcs-sdk-src-3.1.0/core/src/protocol/deserializer.hpp delete mode 100644 librmcs-sdk-src-3.1.0/core/src/protocol/protocol.hpp delete mode 100644 librmcs-sdk-src-3.1.0/core/src/protocol/serializer.hpp delete mode 100644 librmcs-sdk-src-3.1.0/core/src/utility/assert.hpp delete mode 100644 librmcs-sdk-src-3.1.0/core/src/utility/bitfield.hpp delete mode 100644 librmcs-sdk-src-3.1.0/core/src/utility/immovable.hpp delete mode 100644 librmcs-sdk-src-3.1.0/core/src/utility/stack_allocator.hpp delete mode 100644 librmcs-sdk-src-3.1.0/core/src/utility/uncopyable.hpp delete mode 100644 librmcs-sdk-src-3.1.0/core/src/utility/verify.hpp delete mode 100644 librmcs-sdk-src-3.1.0/host/CMakeLists.txt delete mode 100644 librmcs-sdk-src-3.1.0/host/CMakePresets.json delete mode 100644 librmcs-sdk-src-3.1.0/host/include/librmcs/agent/c_board.hpp delete mode 100644 librmcs-sdk-src-3.1.0/host/include/librmcs/agent/common.hpp delete mode 100644 librmcs-sdk-src-3.1.0/host/include/librmcs/agent/rmcs_board_lite.hpp delete mode 100644 librmcs-sdk-src-3.1.0/host/include/librmcs/agent/rmcs_board_pro.hpp delete mode 100644 librmcs-sdk-src-3.1.0/host/include/librmcs/export.hpp delete mode 100644 librmcs-sdk-src-3.1.0/host/include/librmcs/protocol/handler.hpp delete mode 100644 librmcs-sdk-src-3.1.0/host/src/logging/logging.hpp delete mode 100644 librmcs-sdk-src-3.1.0/host/src/protocol/handler.cpp delete mode 100644 librmcs-sdk-src-3.1.0/host/src/protocol/stream_buffer.hpp delete mode 100644 librmcs-sdk-src-3.1.0/host/src/transport/transport.hpp delete mode 100644 librmcs-sdk-src-3.1.0/host/src/transport/usb/device_scanner.hpp delete mode 100644 librmcs-sdk-src-3.1.0/host/src/transport/usb/helper.hpp delete mode 100644 librmcs-sdk-src-3.1.0/host/src/transport/usb/usb.cpp delete mode 100644 librmcs-sdk-src-3.1.0/host/src/utility/assert.cpp delete mode 100644 librmcs-sdk-src-3.1.0/host/src/utility/cross_os.hpp delete mode 100644 librmcs-sdk-src-3.1.0/host/src/utility/final_action.hpp delete mode 100644 librmcs-sdk-src-3.1.0/host/src/utility/ring_buffer.hpp delete mode 100644 package-lock.json delete mode 100644 package.json delete mode 100644 plan.md delete mode 160000 rmcs_notebook create mode 160000 rmcs_ws/src/rmcs_auto_aim_v2 delete mode 160000 rmcs_ws/src/rmcs_core/librmcs delete mode 100644 rmcs_ws/src/rmcs_core/src/hardware/deformable-infantry.cpp delete mode 160000 rmcs_ws/src/rmcs_core/third_party/tinympc rename rmcs_ws/src/{hikcamera => ros2-hikcamera} (100%) delete mode 160000 rmcs_ws/src/serial delete mode 160000 rmcs_ws/src/sp_vision_25 delete mode 100644 sp-vision.md delete mode 160000 sp_vision_25 delete mode 100644 sp_vision_response_test.csv delete mode 100644 todo.md delete mode 100644 wheel.typ diff --git a/AGENTS.md b/AGENTS.md deleted file mode 100644 index 8c501203..00000000 --- a/AGENTS.md +++ /dev/null @@ -1,228 +0,0 @@ -# 代码库指南 - -## 项目概览 -RMCS(RoboMaster Control System)是基于 ROS 2 Jazzy 的机器人控制系统。开发在 Docker devcontainer 中进行(镜像 `qzhhhi/rmcs-develop`),部署到 MiniPC 上的 runtime 容器。 - -## 目录结构 - -```text -. -├── .clang-format / .clang-tidy / .clangd # 代码风格与静态分析 -├── .devcontainer/ # VS Code devcontainer 配置 -├── .script/ # 开发脚本(构建、部署、远程调试) -├── docs/zh-cn/ # 中文文档(Docker、WSL2、nvim 等) -├── plan.md # Planner 接入 RMCS 设计草案 -├── Dockerfile / docker-compose.yml # 容器镜像定义 -└── rmcs_ws/src/ # ROS 2 工作区 - ├── rmcs_executor # 组件 DAG 执行器框架 - ├── rmcs_core # 硬件抽象、控制器、裁判系统(28 个 pluginlib 组件) - ├── rmcs_bringup # 启动文件与机器人配置 YAML - ├── rmcs_description # URDF 与 mesh - ├── rmcs_msgs # 自定义 ROS 2 消息 - ├── rmcs_utility # 共享工具类 - ├── sp_vision_25 # [子模块] 视觉系统:自瞄、打符、全向感知、MPC 规划 - ├── auto_aim_2 # [子模块] 旧版自瞄(逐步替换中) - ├── fast_tf # [子模块] 高性能 TF2 广播 - ├── hikcamera # [子模块] HikRobot 相机驱动 - └── serial # [子模块] ROS 2 串口驱动 -``` - -子模块需要 `git clone --recurse-submodules` 或 `git submodule update --init --recursive`。 - -## 构建、测试与开发命令 - -### 构建 -- `build-rmcs`:在 `rmcs_ws` 中执行 `colcon build --symlink-install --merge-install` -- `build-rmcs --packages-select sp_vision_25 rmcs_core`:增量构建指定包 -- `clean-rmcs`:清理 `rmcs_ws/{build,install,log}` - -### 运行 -- `set-robot (robot name)`:写入 `RMCS_ROBOT_TYPE` 到 `~/env_setup.{bash,zsh}` -- `launch-rmcs`:`ros2 launch rmcs_bringup rmcs.launch.py robot:=$RMCS_ROBOT_TYPE` -- `ros2 launch rmcs_description display.launch.py`:仅查看 URDF/TF,不启动控制链 - -### 远程部署 -- `set-remote `:配置 MiniPC SSH 连接 -- `sync-remote`:监视并持续同步构建产物到部署容器 -- `wait-sync`:阻塞直到同步完成 -- `ssh-remote`:SSH 进入部署容器 -- `attach-remote`:查看 RMCS 实时输出(等价于 `ssh-remote service rmcs attach`) -- `attach-remote -r`:重启后查看实时输出 -- 典型流程:`build-rmcs && wait-sync && attach-remote -r` - -### 测试 -- `colcon test --packages-select rmcs_core rmcs_bringup`:包级检查 -- 功能验证以实际启动和硬件联调为主,无集中式单元测试框架 - -### 其他 -- `foxglove`:启动 Foxglove 可视化 -- `play-autoaim`:回放录制的自瞄数据 - -## 组件系统工作原理 - -### 核心机制 -系统不是"手写 main",而是 **YAML 驱动的组件图**。`rmcs_executor` 是单线程 ROS 2 节点,通过 pluginlib 加载组件,自动按接口名连边并做拓扑排序。 - -关键概念: -- **接口不是 ROS 2 topic**:`/gimbal/...`、`/chassis/...` 等是进程内强类型接口名,执行器把输入直接绑定到输出的内存地址 -- **接口名 + C++ 类型必须同时匹配**:缺失必需输入、重复输出名、类型不匹配或环依赖都会在启动阶段报错 -- **Partner component**:组件可在内部创建隐藏伙伴组件(如 `OmniInfantry` 创建 `infantry_hardware_command`),DAG 不只来自 YAML -- **生命周期钩子**:`before_updating()` 设置默认值和初始化,`update()` 是主循环逻辑 - -### 启动流程 -```text -set-robot → launch-rmcs → rmcs.launch.py → rmcs_executor (respawn=true) - 1. 创建内置 predefined_msg_provider(提供 update_rate / update_count / timestamp) - 2. 读取 YAML components: 列表,pluginlib 装载各组件 - 3. 按 register_input / register_output 同名接口自动连边 - 4. 计算拓扑顺序;配线失败则启动中止 - 5. 以 update_rate(默认 1000Hz)循环执行整条链路 -``` - -### 可用的机器人配置 -- `omni-infantry.yaml`:四轮全向步兵 -- `steering-infantry.yaml`:舵轮步兵 -- `mecanum-hero.yaml`:麦克纳姆轮英雄 -- `deformable-infantry.yaml`: 带关节可变轮距的舵轮步兵 -## 组件 DAG (以最简单的 omni-infantry 为例) - -```text -predefined_msg_provider - → sp_vision_bridge - -infantry_hardware - → referee_status - → gimbal_controller - → friction_wheel_controller - → bullet_feeder_controller - → chassis_controller - → referee_ui - → referee_command - → infantry_hardware_command ← partner component,统一下发控制量 - -referee_status - → sp_vision_bridge - → heat_controller - → chassis_power_controller - → referee_ui - -sp_vision_bridge - → gimbal_controller - → bullet_feeder_controller - -gimbal_controller - → chassis_controller - → infantry_hardware_command - -friction_wheel_controller - → heat_controller - → bullet_feeder_controller - → left_friction_velocity_pid_controller - → right_friction_velocity_pid_controller - -heat_controller - → bullet_feeder_controller - -bullet_feeder_controller - → bullet_feeder_velocity_pid_controller - -chassis_controller - → chassis_power_controller - → omni_wheel_controller - → referee_ui_infantry - -chassis_power_controller - → omni_wheel_controller - → infantry_hardware_command - → referee_ui_infantry - -left/right_friction_velocity_pid_controller - → infantry_hardware_command - -bullet_feeder_velocity_pid_controller - → infantry_hardware_command - -omni_wheel_controller - → infantry_hardware_command - -referee_ui_infantry → referee_ui → referee_interaction → referee_command -``` - -## 关键接口分层 - -### 系统时序 -`predefined_msg_provider` 输出 `/predefined/update_rate`、`/predefined/update_count`、`/predefined/timestamp`。 - -### 硬件状态层 -`OmniInfantry` 及其设备输出: -- `/remote/*`(遥控器)、`/tf`(坐标变换) -- `/gimbal/*/{angle,velocity,torque,max_torque}` -- `/chassis/*/{velocity,power,voltage}`、`/referee/serial` - -Partner component `infantry_hardware_command` 消费: -- `/gimbal/*/control_torque`、`/chassis/*/control_torque`、`/chassis/supercap/charge_power_limit` - -### 视觉规划层 -`SpVisionBridge` 内部运行两个独立线程: -- **检测线程**:Camera → YOLO → Solver → Tracker → `latest_target` -- **Planner 线程(1kHz)**:`latest_target` + `bullet_speed` → `Planner.plan()` → `latest_plan` - -输入:`/tf`、`/predefined/timestamp`、可选 `/referee/shooter/initial_speed` - -输出: -- `/gimbal/auto_aim/control_direction`(方向语义) -- `/gimbal/auto_aim/fire_control`(开火决策) -- `/gimbal/auto_aim/plan_{yaw,pitch}`(世界系规划角度) -- `/gimbal/auto_aim/plan_{yaw,pitch}_velocity` -- `/gimbal/auto_aim/plan_{yaw,pitch}_acceleration` - -超时保护:plan 过期时方向清零、导数清零、`fire_control = false`。 - -### 云台控制层 -`OmniInfantryPlannerGimbalController`(omni-infantry 专用,不改通用 `SimpleGimbalController`): -- 输入遥控量、`/tf`、IMU 角速度、全部视觉规划结果 -- 内部:RMCS 几何层算 angle error → angle PID + velocity PID + planner 前馈 -- 输出 `/gimbal/{yaw,pitch}/control_torque` -- 同时发布 `/gimbal/{yaw,pitch}/control_angle_error` 供底盘跟随 - -### 射击层 -- `FrictionWheelController`:`/gimbal/*_friction/control_velocity`、`/gimbal/friction_ready`、`/gimbal/bullet_fired` -- `HeatController`:`/gimbal/control_bullet_allowance/limited_by_heat` -- `BulletFeederController17mm`:结合遥控、热量和 `fire_control` → `/gimbal/bullet_feeder/control_velocity`、`/gimbal/shooter/mode` - -### 底盘层 -- `ChassisController`:遥控 + 云台误差 → `/chassis/control_{mode,velocity,angle}` -- `ChassisPowerController`:裁判功率 + 超级电容 → `/chassis/control_power_limit` -- `OmniWheelController`:→ 四轮 `/chassis/*_wheel/control_torque` -- `DeformableChassis` : Deformable-infantry的特化的ChassisController, 融合了底盘和关节的控制量输入 -- `DeformableWheelController`: Deformable-infantry的特化的底盘控制器,融合了关节的分速度和轮距的计算 -### 裁判/UI 层 -`Status` 解帧 → `Ui`/`Infantry` 生成 UI → `Interaction` 汇总 → `Command` 编码写回 `/referee/serial` - -## 调试指南 - -### 启动失败排查 -1. `rmcs_bringup/config/.yaml` 是否列出了正确组件和参数 -2. 组件声明的输入是否都能在别处找到同名输出 -3. 是否有组件在 `before_updating()` 中为可选输入绑定了默认值,掩盖了上游缺失 - -### 运行时数据流追踪 -按"外部输入 → 中间接口 → 最终控制量"追踪: -- **自瞄异常**:`/tf` → `/gimbal/auto_aim/*` → `/gimbal/{yaw,pitch}/control_torque` -- **底盘异常**:`/chassis/control_velocity` → `/chassis/control_power_limit` → `/chassis/*_wheel/control_torque` -- **射击异常**:`/gimbal/auto_aim/fire_control` → `/gimbal/control_bullet_allowance/*` → `/gimbal/bullet_feeder/control_velocity` - -## 编码风格与命名规范 - -根目录 `.clang-format` 配置: -- 基于 LLVM 风格,C++20 标准 -- 4 空格缩进,100 列宽 -- `PointerAlignment: Left`(即 `int* p`) -- `AlignAfterOpenBracket: AlwaysBreak` - -命名约定: -- 类型:`UpperCamelCase` -- 命名空间:按目录展开,如 `rmcs_core::controller::gimbal` -- YAML 参数、组件实例名、接口名:`snake_case` 或斜杠路径,如 `/gimbal/auto_aim/plan_yaw` -- 机器人配置文件:短横线命名,如 `omni-infantry.yaml` -- 机器相关串口、零点、板号只放在 `rmcs_bringup/config/*.yaml`,不要硬编码进共享逻辑 diff --git a/CLAUDE.md b/CLAUDE.md deleted file mode 100644 index e259a8b3..00000000 --- a/CLAUDE.md +++ /dev/null @@ -1,85 +0,0 @@ -# CLAUDE.md - -This file provides guidance to Claude Code (claude.ai/code) when working with code in this repository. - -## Operational Rules - -- **Do NOT use git commands to stage, commit, push, or reset files** -- **Do NOT use `rm` to delete files or directories** -- **Always describe what you are about to modify and wait for user confirmation before editing any file** -- **Do NOT modify any files under `rmcs_core/librmcs/`** -- **Do NOT modify any bringup config `.yaml` files other than `deformable-infantry.yaml`** - -## Commands - -All scripts live in `.script/` and are on `PATH` inside the Dev Container. - -```bash -build-rmcs # colcon build --symlink-install in rmcs_ws/ -build-rmcs --packages-select rmcs_core # build a single package -clean-rmcs # delete build/ install/ log/ -set-robot deformable-infantry # set RMCS_ROBOT_TYPE in ~/env_setup.* -launch-rmcs # ros2 launch (requires set-robot first) -lsusb # verify C-Board USB devices are connected -``` - -No test suite exists. To validate changes, run `build-rmcs` and check compiler output. - -## librmcs SDK Installation (required before build) - -The hardware layer depends on the **librmcs SDK** being installed system-wide inside the Dev Container. The submodule at `rmcs_core/librmcs/` is for reference only — the actual headers and library come from the installed package. - -Pre-built `.deb` packages are published at https://github.com/Alliance-Algorithm/librmcs/releases. -Current required version: **v3.0.0b2** - -Inside the Dev Container (Ubuntu, x86_64): - -```bash -curl -LO "https://github.com/Alliance-Algorithm/librmcs/releases/download/v3.0.0b2/librmcs-sdk-3.0.0-beta.2-amd64-release.deb" -sudo dpkg -i librmcs-sdk-3.0.0-beta.2-amd64-release.deb -``` - -After installation the headers are in `/usr/local/include/librmcs/` and the library in `/usr/local/lib/`. The `CMakeLists.txt` does **not** need modification — the system include path picks them up automatically. - -## Architecture - -### Plugin System - -Every functional unit is a `rmcs_executor::Component` loaded via `pluginlib`. The executor calls each component's `update()` at a fixed rate (1000 Hz for deformable-infantry). A component that issues commands uses the pattern of registering a *partner component* whose `update()` fires after the main one. - -New components must be declared with `PLUGINLIB_EXPORT_CLASS` and registered in `rmcs_ws/src/rmcs_core/plugins.xml`. Active components and their ROS parameter namespaces are listed in `rmcs_bringup/config/.yaml`. - -### Inter-Component Communication - -Components share data through typed `OutputInterface` / `InputInterface` pointers registered by name (e.g. `/gimbal/yaw/control_velocity`). This is **not** ROS topic pub/sub — it is a direct shared-memory mechanism inside the executor. ROS topics are only used for external interfaces (referee serial, calibration subscriptions). - -### Hardware Layer (`rmcs_core/src/hardware/`) - -Each robot type has one `.cpp` file. Inside it, inner classes (e.g. `FrontBoard`, `BackBoard`, `TopBoard`) privately inherit `librmcs::agent::CBoard` — one per physical USB control board. Each board class: -- Overrides `can1/2_receive_callback` and `uart/dbus/imu_receive_callback` to feed device objects -- Calls `start_transmit()` in its `command_update()` to build and send a USB packet (the returned `PacketBuilder` sends automatically on destruction — **no** `TransmitBuffer` or `trigger_transmission()`) - -### librmcs Submodule (`rmcs_core/librmcs/`) - -Currently pinned to the **main branch** of `https://github.com/Alliance-Algorithm/librmcs`. - -| Item | main branch (current) | infantry-develop (old) | -|---|---|---| -| Header | `librmcs/agent/c_board.hpp` | `librmcs/client/cboard.hpp` | -| Namespace | `librmcs::agent::CBoard` | `librmcs::client::CBoard` | -| Device selection | `CBoard(std::string_view serial_filter)` | `CBoard(int usb_pid)` | -| CAN callback arg | `const CanDataView& data` | `uint32_t, uint64_t, bool, bool, uint8_t` | -| UART callback arg | `const UartDataView& data` | `const std::byte*, uint8_t` | -| IMU callback arg | `const AccelerometerDataView& data` | `int16_t x, y, z` | -| Sending | `start_transmit()` → `PacketBuilder` (RAII) | `TransmitBuffer` + `trigger_transmission()` | -| Event loop | managed internally by `Handler` | manual `handle_events()` thread | - -`librmcs/device/` (BMI088, DJI motors, DR16, LK motors) does **not** exist on main — those device drivers live in `rmcs_core/src/hardware/device/` and are maintained in this repo. - -### Controller Layer (`rmcs_core/src/controller/`) - -Controllers are pure `rmcs_executor::Component` classes with no USB access. They read input interfaces (sensor values, setpoints) and write output interfaces (torque/velocity commands). PID and SMC controllers are generic and reused across robot types via YAML parameter remapping. - -## Code Style - -C++20, `.clang-format` enforced (LLVM base, 100-column limit, 4-space indent). Pointer alignment is left (`int* p`). Private member variables use trailing underscore (`event_thread_`). diff --git a/code-plan.md b/code-plan.md deleted file mode 100644 index a764697e..00000000 --- a/code-plan.md +++ /dev/null @@ -1,397 +0,0 @@ -# 主动悬挂 ADRC 方案 — 实现步骤 - -## Step 1: QcpSolver 扩展 - -| 文件 | 变更类型 | 说明 | -|------|---------|------| -| `rmcs_core/src/controller/chassis/deformable_joint_controller.cpp` | **重写** | PID 级联 → ADRC 内核 + 双模式切换 | -| `rmcs_core/src/controller/chassis/deformable_joint_sweep_recorder.cpp` | 修改 | 增加 ESO z3/z2 信号记录 | -| `rmcs_bringup/config/deformable-infantry-v2.yaml` | 修改 | ADRC 参数替换 PID 参数 | -| `plugins.xml` | 无修改 | `DeformableJointController` 已注册 | - ---- - -## Step 1: 重写 DeformableJointController(ADRC 内核) - -**文件**: `deformable_joint_controller.cpp` - -### 1a. 替换 PID 头文件为 ADRC - -```cpp -// 移除: -#include "controller/pid/pid_calculator.hpp" - -// 添加: -#include "controller/adrc/TD.hpp" -#include "controller/adrc/ESO.hpp" -#include "controller/adrc/NLESF.hpp" -``` - -### 1b. 成员变量替换 - -```cpp -// 移除 PID 成员: -// pid::PidCalculator angle_pid_, velocity_pid_; -// pid::PidCalculator suspension_angle_pid_, suspension_velocity_pid_; - -// 添加 ADRC 成员: -adrc::TD td_; -adrc::ESO eso_; -adrc::NLESF nlesf_; - -// 双模式配置: -adrc::TD::Config normal_td_config_; -adrc::TD::Config suspension_td_config_; -adrc::ESO::Config normal_eso_config_; -adrc::ESO::Config suspension_eso_config_; -adrc::NLESF::Config normal_nlesf_config_; -adrc::NLESF::Config suspension_nlesf_config_; - -double b0_ = 1.0; -double kt_ = 1.0; -double last_u_ = 0.0; -double output_min_, output_max_; -double suspension_output_min_, suspension_output_max_; -double torque_feedforward_gain_ = 0.0; -double suspension_torque_feedforward_gain_ = 0.0; - -// ESO z3 输出(用于扫频记录和调试) -OutputInterface eso_z3_output_; -OutputInterface eso_z2_output_; -``` - -### 1c. 构造函数 — 加载 ADRC 参数 - -接口注册保持与当前 `DeformableJointController` 完全一致: -```cpp -register_input(get_parameter("measurement_angle").as_string(), measurement_angle_); -register_input(get_parameter("measurement_velocity").as_string(), measurement_velocity_); -register_input(get_parameter("setpoint_angle").as_string(), setpoint_angle_); -// setpoint_velocity, mode_input, suspension_torque — 同现有逻辑 -register_output(get_parameter("control").as_string(), control_torque_, nan_); -``` - -新增 ESO 输出(可选,用于扫频记录): -```cpp -if (has_parameter("eso_z3_output")) - register_output(get_parameter("eso_z3_output").as_string(), eso_z3_output_, nan_); -if (has_parameter("eso_z2_output")) - register_output(get_parameter("eso_z2_output").as_string(), eso_z2_output_, nan_); -``` - -加载通用 ADRC 参数: -```cpp -const double dt = load_parameter_or(*this, "dt", 0.001); -b0_ = load_parameter_or(*this, "b0", 1.0); -kt_ = load_parameter_or(*this, "kt", 1.0); -``` - -加载正常模式参数: -```cpp -normal_td_config_.h = load_parameter_or(*this, "td_h", dt); -normal_td_config_.r = load_parameter_or(*this, "td_r", 300.0); - -normal_eso_config_.h = dt; -normal_eso_config_.b0 = b0_; -normal_eso_config_.w0 = load_parameter_or(*this, "eso_w0", 250.0); -normal_eso_config_.auto_beta = load_parameter_or_bool(*this, "eso_auto_beta", true); -normal_eso_config_.z3_limit = load_parameter_or(*this, "eso_z3_limit", 1e9); - -normal_nlesf_config_.k1 = load_parameter_or(*this, "k1", 30.0); -normal_nlesf_config_.k2 = load_parameter_or(*this, "k2", 17.0); -normal_nlesf_config_.alpha1 = load_parameter_or(*this, "alpha1", 0.75); -normal_nlesf_config_.alpha2 = load_parameter_or(*this, "alpha2", 0.7); -normal_nlesf_config_.delta = load_parameter_or(*this, "delta", 0.02); - -output_min_ = load_parameter_or(*this, "output_min", -200.0); -output_max_ = load_parameter_or(*this, "output_max", 200.0); -``` - -加载悬挂模式参数(fallback 到正常模式值): -```cpp -suspension_td_config_.h = normal_td_config_.h; -suspension_td_config_.r = load_parameter_or(*this, "suspension_td_r", normal_td_config_.r); - -suspension_eso_config_ = normal_eso_config_; -suspension_eso_config_.w0 = load_parameter_or(*this, "suspension_eso_w0", normal_eso_config_.w0); - -suspension_nlesf_config_.k1 = load_parameter_or(*this, "suspension_k1", normal_nlesf_config_.k1); -suspension_nlesf_config_.k2 = load_parameter_or(*this, "suspension_k2", normal_nlesf_config_.k2); -suspension_nlesf_config_.alpha1 = load_parameter_or(*this, "suspension_alpha1", normal_nlesf_config_.alpha1); -suspension_nlesf_config_.alpha2 = load_parameter_or(*this, "suspension_alpha2", normal_nlesf_config_.alpha2); -suspension_nlesf_config_.delta = load_parameter_or(*this, "suspension_delta", normal_nlesf_config_.delta); - -suspension_output_min_ = load_parameter_or(*this, "suspension_output_min", output_min_); -suspension_output_max_ = load_parameter_or(*this, "suspension_output_max", output_max_); -``` - -初始化 ADRC: -```cpp -td_ = adrc::TD(normal_td_config_); -eso_ = adrc::ESO(normal_eso_config_); -nlesf_ = adrc::NLESF(normal_nlesf_config_); -``` - -### 1d. update() — ADRC 核心循环 - -```cpp -void update() override { - if (!std::isfinite(*measurement_angle_) || !std::isfinite(*setpoint_angle_)) { - disable_output_(); - return; - } - - // 模式切换 - const bool suspension_mode = *suspension_mode_; - if (suspension_mode != last_suspension_mode_) { - switch_adrc_mode_(suspension_mode); - last_suspension_mode_ = suspension_mode; - } - - // ADRC 核心计算 - const auto td_out = td_.update(*setpoint_angle_); - const auto eso_out = eso_.update(*measurement_angle_, last_u_); - - const double e1 = td_out.x1 - eso_out.z1; - const double e2 = td_out.x2 - eso_out.z2; - - const auto nlesf_out = nlesf_.compute(e1, e2, eso_out.z3, b0_); - double u = kt_ * nlesf_out.u; - - // 可选: 悬挂力矩前馈 - const double torque_ff_gain = - suspension_mode ? suspension_torque_feedforward_gain_ : torque_feedforward_gain_; - if (std::isfinite(*suspension_torque_) && torque_ff_gain != 0.0) - u += torque_ff_gain * *suspension_torque_; - - // 限幅(模式相关) - const double u_min = suspension_mode ? suspension_output_min_ : output_min_; - const double u_max = suspension_mode ? suspension_output_max_ : output_max_; - u = std::clamp(u, u_min, u_max); - - if (!std::isfinite(u)) { - disable_output_(); - return; - } - - *control_torque_ = u; - last_u_ = u; - - // 输出 ESO 状态供记录 - if (eso_z3_output_.active()) *eso_z3_output_ = eso_out.z3; - if (eso_z2_output_.active()) *eso_z2_output_ = eso_out.z2; -} -``` - -### 1e. 模式切换 - -```cpp -void switch_adrc_mode_(bool suspension) { - // 切换 ADRC 参数,但保留 ESO/TD 状态(平滑过渡) - if (suspension) { - td_.set_config(suspension_td_config_); - eso_.set_config(suspension_eso_config_); - nlesf_.set_config(suspension_nlesf_config_); - } else { - td_.set_config(normal_td_config_); - eso_.set_config(normal_eso_config_); - nlesf_.set_config(normal_nlesf_config_); - } - // 注意: 不调用 reset() — ESO 和 TD 的状态需要保留以实现平滑过渡 -} -``` - -### 成员变量: 替换弹簧/阻尼参数(修改 ~line 966-968) - -替换: -```cpp -double active_suspension_spring_k_; -double active_suspension_damping_k_; -``` - -为: -```cpp -double active_suspension_Kz_; -double active_suspension_Kp_; -double active_suspension_Dp_; -double active_suspension_Kr_; -double active_suspension_Dr_; -double active_suspension_D_leg_; -double active_suspension_com_height_; -double active_suspension_wheel_base_half_; -``` - -### 成员变量: 添加新输入(line 907 之后) - -```cpp -InputInterface chassis_imu_pitch_; -InputInterface chassis_imu_roll_; -InputInterface chassis_imu_pitch_rate_; -InputInterface chassis_imu_roll_rate_; -InputInterface chassis_control_acceleration_; -``` - ---- - -## Step 2: 修改 SweepRecorder 记录 ADRC 信号 - -**文件**: `deformable_joint_sweep_recorder.cpp` - -### 2a. 新增输入接口 - -```cpp -// 可选输入(不影响现有功能) -if (has_parameter("eso_z3")) { - register_input(get_parameter("eso_z3").as_string(), eso_z3_); - has_eso_z3_ = true; -} -if (has_parameter("eso_z2")) { - register_input(get_parameter("eso_z2").as_string(), eso_z2_); - has_eso_z2_ = true; -} -``` - -### 2b. CSV 列新增 - -```cpp -// CSV 头 -csv_stream_ << "...,measured_torque,frequency_hz,phase_rad,eso_z3,eso_z2\n"; - -// 数据行 -csv_stream_ << ... << ',' << *frequency_hz_ << ',' << *phase_rad_ - << ',' << (has_eso_z3_ ? *eso_z3_ : nan_) - << ',' << (has_eso_z2_ ? *eso_z2_ : nan_) - << '\n'; -``` - ---- - -## Step 3: YAML 配置更新 - -**文件**: `deformable-infantry-v2.yaml` - -### 关节控制器参数(每个关节) - -```yaml -lf_joint_controller: - ros__parameters: - # 接口(不变) - measurement_angle: /chassis/left_front_joint/physical_angle - measurement_velocity: /chassis/left_front_joint/physical_velocity - setpoint_angle: /chassis/left_front_joint/target_physical_angle - setpoint_velocity: /chassis/left_front_joint/target_physical_velocity - mode_input: /chassis/left_front_joint/suspension_mode - suspension_torque: /chassis/left_front_joint/suspension_torque - control: /chassis/left_front_joint/control_torque - - # ESO 输出(扫频记录用) - eso_z3_output: /chassis/left_front_joint/eso_z3 - eso_z2_output: /chassis/left_front_joint/eso_z2 - - # ADRC 通用参数 - dt: 0.001 - b0: 0.60 # ← 从扫频辨识确定 - kt: 1.0 - - # 正常模式(刚性跟踪) - td_r: 50.0 - td_h: 0.001 - eso_w0: 250.0 - eso_auto_beta: true - k1: 30.0 - k2: 17.0 - alpha1: 0.75 - alpha2: 0.7 - delta: 0.02 - output_min: -200.0 - output_max: 200.0 - - # 悬挂模式(柔顺弹簧) - suspension_td_r: 10.0 - suspension_eso_w0: 80.0 - suspension_k1: 8.0 - suspension_k2: 5.0 - suspension_alpha1: 0.75 - suspension_alpha2: 0.7 - suspension_delta: 0.02 - suspension_output_min: -50.0 - suspension_output_max: 50.0 - - # 力矩前馈增益 - torque_feedforward_gain: 0.0 - suspension_torque_feedforward_gain: 0.0 -``` - -### 扫频记录器参数新增 - -```yaml -joint_sweep_recorder: - ros__parameters: - # ... 现有参数 ... - eso_z3: /chassis/left_front_joint/eso_z3 - eso_z2: /chassis/left_front_joint/eso_z2 -``` - ---- - -## Step 4: 扫频辨识 b0 流程 - -### 4a. 运行扫频 - -使用现有 `DeformableJointSweepController` + 改造后的 `DeformableJointController (ADRC)` + 增强的 recorder。 - -先用一组保守 ADRC 参数(低增益避免失控): -```yaml -b0: 1.0 # 初始猜测 -eso_w0: 100.0 # 中等带宽 -k1: 10.0 -k2: 5.0 -output_min: -100.0 -output_max: 100.0 -``` - -### 4b. 从 CSV 辨识 b0 - -系统模型: `theta_ddot = b0 * u + f(t)` (f = 总扰动) - -方法 1 — 时域最小二乘: -```python -# Python 后处理 -theta_ddot = np.gradient(np.gradient(actual_angle, dt), dt) -b0_estimate = np.mean(theta_ddot / control_torque) # 在扰动平稳段取平均 -``` - -方法 2 — 频域 (更精确): -```python -# Bode 图: H(jw) = theta(jw) / u(jw) -# 低频渐近线增益 |H(0)| ≈ 1/(b0 * w^2) -# 从频率响应曲线拟合 b0 -``` - -### 4c. 从 b0 推导悬挂参数 - -``` -期望弹簧刚度 K [N·m/rad] → suspension_k1 ≈ K * b0 -期望阻尼系数 D [N·m·s/rad] → suspension_k2 ≈ D * b0 -ESO 带宽 → suspension_eso_w0 ≈ 系统带宽 * 3 (从 Bode 图) -力矩限幅 → suspension_output_max ≈ mg/4 * rod_length + 安全裕量 -``` - ---- - -## Step 5: 编译和验证 - -```bash -build-rmcs --packages-select rmcs_core -``` - -### 验证清单 - -- [ ] 编译通过 -- [ ] 正常模式: 关节精确跟踪目标角度(与 PID 性能对比) -- [ ] 悬挂模式: 手推关节可以柔顺偏移,松手后缓慢恢复 -- [ ] 模式切换: normal ↔ suspension 切换无冲击(ESO 状态保持) -- [ ] 悬空测试: 抬起轮组 → 关节自动伸展到目标位置 -- [ ] 触地测试: 放下轮组 → 柔顺吸收冲击 -- [ ] 扫频: CSV 数据包含 eso_z3, eso_z2 列 -- [ ] value_broadcaster 可监控 ESO z3 实时值 diff --git a/deformable_infantry_omni_active_suspension_flow.md b/deformable_infantry_omni_active_suspension_flow.md deleted file mode 100644 index 5df8944a..00000000 --- a/deformable_infantry_omni_active_suspension_flow.md +++ /dev/null @@ -1,160 +0,0 @@ -# Deformable Infantry Omni 主动悬挂控制流图 - -本文档描述当前 `deformable-infantry-omni` 配置下,底盘轮系控制与主动悬挂控制的实际数据流和控制流。 - -## 总体控制流 - -```text - 1 kHz 主循环 - │ - ▼ - DeformableInfantryOmni::update() - │ - ┌──────────────────────────┴──────────────────────────┐ - │ │ - ▼ ▼ - BottomBoard 读取底盘 IMU / 关节反馈 / 轮速 / 电机状态 TopBoard 读取云台 IMU - │ - ├─ 输出 /chassis/imu/pitch - ├─ 输出 /chassis/imu/roll - ├─ 输出 /chassis/imu/pitch_rate - ├─ 输出 /chassis/imu/roll_rate - ├─ 输出 /chassis/*_joint/physical_angle - ├─ 输出 /chassis/*_joint/physical_velocity - └─ 输出 /chassis/radius - │ - ▼ - DeformableChassis::update() - │ - ┌──────────────────────────┴──────────────────────────┐ - │ │ - ▼ ▼ - update_velocity_control() update_lift_angle_error() - │ │ - │ ├─ 读取 4 条腿当前角度/角速度 - │ ├─ 生成 4 条腿目标展开角 - │ ├─ update_active_suspension() - │ │ - │ │ if 反馈无效 或 腿未展开: - │ │ suspension_mode = false - │ │ suspension_torque = NaN - │ │ - │ │ else: - │ │ alpha_avg = mean(alpha_i) - │ │ Fz = mg/4 + Kz*(alpha_nom - alpha_avg) - │ │ Fpitch = Kp*pitch + Dp*pitch_rate - │ │ + m*ax_ff*h/(4*a^2) - │ │ Froll = Kr*roll + Dr*roll_rate - │ │ + m*ay_ff*h/(4*b^2) - │ │ - │ │ 对每条腿: - │ │ Ni = Fz + x_i*Fpitch + y_i*Froll - │ │ + D_leg*(-alpha_dot_i)/max(sin(alpha_i), 0.1) - │ │ Ni = max(Ni, 0) - │ │ tau_i = Ni * L * sin(alpha_i) - │ │ 限幅到 torque_limit - │ │ - │ ├─ update_joint_target_trajectory() - │ └─ 输出: - │ /chassis/*_joint/target_physical_angle - │ /chassis/*_joint/target_physical_velocity - │ /chassis/*_joint/suspension_mode - │ /chassis/*_joint/suspension_torque - │ - ├─ 平移速度 = 遥控/键盘输入 × 云台 yaw 旋转 - ├─ 角速度 = AUTO / SPIN / STEP_DOWN / LAUNCH_RAMP - ├─ 控制加速度估计 ax_ff, ay_ff = diff(平移速度指令) - └─ 输出 /chassis/control_velocity - │ - ┌──────────────────────────┴──────────────────────────┐ - │ │ - ▼ ▼ - 4 个 DeformableJointController DeformableOmniWheelController - │ │ - │ ├─ 读取 /chassis/control_velocity - │ ├─ 读取轮速、/chassis/radius、功率限制 - │ ├─ 速度 PID -> 底盘期望力矩 [tau_r, tau_theta] - │ ├─ QCP 约束: - │ │ 功率二次约束 - │ │ + 摩擦约束 - │ │ + 若 com_height > 0: - │ │ 用 gamma_i 构造 8 个半平面 - │ │ + 若半平面退化: - │ │ 回退旧菱形约束 - │ └─ 输出 /chassis/*_wheel/control_torque - │ - ├─ 普通模式: - │ 角度 PID + 速度 PID - │ - └─ suspension_mode = true 时: - 角度 PID + 速度 PID + suspension_torque 前馈 - ↓ - 输出 /chassis/*_joint/control_torque - │ - ▼ - BottomBoard::command_update() - │ - ┌──────────────────────────┴──────────────────────────┐ - │ │ - ▼ ▼ - 4 个悬挂关节电机扭矩下发 4 个轮子电机扭矩下发 -``` - -## 主动悬挂子流程 - -```text -底盘 IMU(pitch, roll, pitch_rate, roll_rate) - + 4 条腿 physical_angle / physical_velocity - + 平移控制加速度估计 ax_ff / ay_ff - │ - ▼ -DeformableChassis::update_active_suspension() - │ - ├─ 检查四条腿是否都已进入展开工况 - ├─ 计算平均腿角 alpha_avg - ├─ 计算高度模态 Fz - ├─ 计算俯仰模态 Fpitch - ├─ 计算横滚模态 Froll - ├─ 对 4 条腿分配法向力 Ni - ├─ 法向力转关节力矩 tau_i - └─ 输出 /chassis/*_joint/suspension_torque - │ - ▼ -DeformableJointController - │ - ├─ suspension_mode = false: - │ 普通角度/速度闭环 - │ - └─ suspension_mode = true: - 普通闭环 + suspension_torque 扭矩前馈 - │ - ▼ - /chassis/*_joint/control_torque -``` - -## 控制职责拆分 - -- `DeformableChassis` - - 生成底盘速度指令 - - 生成 4 条腿展开目标 - - 计算主动悬挂模态力和悬挂力矩前馈 - -- `DeformableJointController` - - 将关节目标角、目标速度、悬挂前馈力矩组合成最终关节控制力矩 - -- `DeformableOmniWheelController` - - 将底盘速度误差转换为底盘等效控制力矩 - - 通过 QCP 同时满足功率约束和摩擦约束 - - 输出 4 个轮子的控制力矩 - -- `BottomBoard` - - 提供底盘 IMU 与关节反馈 - - 接收轮子与悬挂关节的最终控制力矩并下发电机 - -## 关键源码入口 - -- `rmcs_ws/src/rmcs_core/src/controller/chassis/deformable_chassis.cpp` -- `rmcs_ws/src/rmcs_core/src/controller/chassis/deformable_joint_controller.cpp` -- `rmcs_ws/src/rmcs_core/src/controller/chassis/deformable_omni_wheel_controller.cpp` -- `rmcs_ws/src/rmcs_core/src/controller/chassis/qcp_solver.hpp` -- `rmcs_ws/src/rmcs_core/src/hardware/deformable-infantry-omni.cpp` diff --git a/foxglove_like_yaw_plot_from_script.png b/foxglove_like_yaw_plot_from_script.png deleted file mode 100644 index 27f782330bdfa3e0823f29ea036fbf9dafe7cb17..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 499399 zcmdSBWk6Kl+Bb{^A_5{HNQ2VS-3BQo(hMajokK_}DoBcybazS3$WQ_TQiHU_kdgy~ zbi=zw{hxC`&vWkc{r!Lr>^*yStaV+#TJ!FSngZc9s%tnnID|@yvQKevu4d!lT>g0# z7yJd$pm7oWC+;q%=dS5wiP(zeSa$K&9_3Eg*}$LOaX zo?QxUe zf;aTPUB+FDZ>D7b%T4%wV5M*Go7w)i+l1ZY!+Xa6U)+cuTBDbkZv(l?{ZQJlwt;@_ z|90!~uO)Q9$zn5f@0WAnP_UB6zl13BbSD?TY&8022(#(+%S)2hD8fTd3!;oNV=Qtc z@uLc{aUu~48sefF$bT0UlJsEp7U9a^*N3twCRiGnsy6?7kg=k)N^ zj?K+?ITDP1NwQ2UYKrMB(TWJtfqbRAA26@~wdwBAH=7qNuS0BnLqkK^I5<|9Z578a zXgF{|!`>7i6_b}^$3o@`Cc5ZA4&)m!8w-~d+d5zJ-`Sq*YS*Pp^= zugliJLlEHg9N7GS9$y(X$B<|K;kxc8BpaUj5>|lscN{YGD<7<9$p_Ym$&%xJ*<> zP@auHyF+MLSjCuq`;HV*@TKHlc}vS&6ESaZ?{-&jZ!zIy!i4TCL*h7KgN;pLh5CaB z7xeY@+g+hhA>rhRq$DbHBP%PGH*emwyDBN+gWXjJah%0df7lCiaBzhCxw^S^_VxKe8nYKoRl^ZfZMCY>c>2_AO;b-#(aI{X!cbE)sMl&cEU&ApD=Q=8iyk)@SDRJU ztVi7i=UPK>q^|Dn2*0hZt#6&3eDR!|oZxJKtb1g5JiZIg%EhIkLR~{6dioGHv3{Y? z)8D_b!ca$N(X$cdC<0EgvXb9C{p7^AvZ^X#p{R&MP&K=xq(@Z8%F62ggijxQbZ@uM zli`278kL!TX}_`Q6(~OO=cTjgKQB$RwJl4!kw_x1M)XAE+2LM|pSHI4{Rxrb5vnRb zO^05)W6Y0{dYF?EWP7}k*`bsfMhq)G9H)Cew6{B9zzZv%9(h&a2bnN1hdC9M3RxW= zElE(yP#2W0Ak>~cVb(Xo;}snjY!O3b#>{&($c(ZE!(|&vZK2h6G>}> z?h(?eJ~cun6T!A8HUxM9|l}Tcqa+%?Fzv3pOs*-8mLCD#V^KEfL<>*qD}< z7Uiknp^8?Cbc8R<_}1nl-Hk!_x3F7f)>%{Qxw*N|lUR-gFYeg<6zDfV_@v`fIoY93 zrJOuGguy5xyLHQ>OIlTQY8(7JBOS3n2`6_`d`yxeGVL4FLFdz>XZ+cjk%WYVRxdlU znfmpen?*%t6?)5KRjfrEYW4|b==KP?yI_nt!b!==hx@f{bZLn25M`vdZ;xSr@s&u+ z$|&MEJ>I84COkqxxo>*Zp_Z#dUw1FuM2;{lHb6AUva+&5!oo<4(s65~d*?Szg~J3U z-D(XV?hVSWmESLQ?DtKAr!TtJJ|WA^E*>lk@!i;ymL1F&$}Iv7Xjo{-9%wF#sGEE@`lmq0DTFZLf@A&dK4GB+U^5(aB|}seQ&B@MCbDD2 z{V6Ca+S+mNHD5fw%O$5lW@cu#+@FmHMvVVN3kqflki!7(q@zf&PU%I{)uFW-IWT4WhGgynZ=YFF1|TU%R2Wo5e??{BL8G~!bUp?sH+no4+o zy3tSKGs_3(JJ`Eb2pRAr`Fs9?;7tEEgy;WHYx$>@VjtEJsscekK(Og035G(saYIN{ zl#}~WG%U-8>i&=ndDEB zR9FTE2f&KYkq6H6R$VJ^`fgt6{zu@mLPiD|3@fthtv%@8qIuv*;T3Te_ zv`&7t5})jjnivM0?p~)7WLw@^^N@&=K6+k^)_n5hODnOA3TTWtI>m9Jq1Q&rjJgp} zwCMTCwitLL#HjH<;@BLY$})Ru0=T5QJX9_F*f)OrQrMsq^TV2I^WM8RU4B`W1!6?v zLS=6{`c8y9L9U4~63er5b1&v57`Lo@#H6JmuTU7?fB5j?;o;#u{mR!ybsn2*RehDu z`?IX>IQqT|54ZRdcmbSk$b%r<&Dmgjs%B=@OdF~`seKw|X679XD*14GNx<|APEm33 zA-KRpu#XqI6izAl{Kh3bBKt7+S$0m&OAL&RnL%~~{?C)-H8ejz?j>^<@;S7hW^Jd2skDf-ZWytaP3Rcfa+w!q1dem zqrf8ffa#IcbrcyuUWmHwYA#hqXjrbqq=Upy&sLtMlbgY<5Bk!i5@iA!H8zbKUbrm8 z>6+CTfZJiU&=vO}!KTJQzut=vKIuweo$ecO_dgdibCw;tDb<55nbT6E3^J+J8;`;;p6)BqW4RNU6cJ*DSr8)7MJ7Fkh115ZlXp1}Jbw zafQTz@G1OxNCD)3JWBwq%^0!Z_V-m5Y>MhxkN1{wQ2UH7eX8S#DM^wPw51PEA}0-N z=bl+M#`ADieG~?65+9Z?(EToQ?k1>!IQt!lbk#Ipcoe;S7IT`HreM?hQF20;Oxy9b zZJA@~e07U!OF6WoXK@Y+h~kFiN2|B+qATHtOa|vYVFi0co)bhiypI8D0H6sc{I&qg zjI?=s__MZ9atjNKCje3o+Y(xmQ+;xnfU%$jUhF(4lWU&e`~>DUi&_fh$dS8s&*J;O zqoEbPM3rz_30QV|a$XI*cGhL0(uHVMK>YIf_N%JD_G72Orz?!T| zeC#{WJE1Cz-;4(*YRcA?JZn7N6j2{Akp&NKXWhg;-(q&we2+#+ISs0atj)4fXzJwT zoK}1fh z6Cti|G)BbrPj32lKX*tq;->JZld?eg*{FGD%wNf_%U!Ci`%zSi0Dzf0L0J?clv`Id zUgUqf@vT9bmQG~R7$P;Q0fc40$Dk zrQ3~y`E^wXuP{Sp22bDeWIF0LHjy^#G~Ft5;J?uprtImqexxvFuqb1B-}=|f(waE9 z%v8L%XPXE4HB@RF9xMk5K8dT)&CSv)o%0YgG3G!X%J+-`Y}1*gvIbnikXyG33O?8t zy-Qw#aXxjMOG1qasoG@ zQQO5&t_zQ~v@Jn9dnQHnWu`fZnh>_qwdcr{l=loi;UY@okA5^Z@{nrvse!?@`|j@U zLF_N;@7}#jd7cm#_h#!C;V&*3KE8_n)0;PMvhnaZY50|Wo(q+St0oEJhqbj7X%{Q1 ztFv-&Tno&~V)9rYmoqd>G1)nXIZS}Pt-rlz+*utaC?H(ZYj`1qGnl6;@RVuc=TFnB zF-0Y%X9vG#LID9BLqIt-G&FMZ^Qn(9V^zT|Ef0_OH`K8xd3UNXmqj&6 z*23a04xkWgQwzLg|XJ_+*Yjk@0^cNk#B~wypUhHFf z!J~v&7NhDsHMO*44GgHjRS171+>pRj4gHk{)o){Ua zDk&*Ffw|V9PQW%C8s{$;KC0y1nkWJ%LP#xa%AY7Y6L`tMp0l7~9~4!>;^EbV^`i_b5@Ndbvy%%(e&5A~Pr?&(S6DdS zWxl=UhmM$-7@&(!jE&V?UHR|Ghx2y*sP}gJ4jYF%(bv}2?yL+31AtP~rBmmzp7r_j z#|xKmDK)RdhIAk>`^?J956@cP_Gc?Z1;VxnTY7UTiSkdLHM0;BUj z#2e}(nHC5$sInpi;>+fI2PrA(pc%x*0975QnWw^c^p&e34&`W#LO|I<=RBLXV8!kB zLRLMLbMx~r$9>k~xggiUK_pU<;Pghu;2YyNAwnab4)02-&~@YXundP`z3Ccem~F}5 zErb@u03pKc#~y-#9K)i@zqh+*6jY&o>hgAUDlRVW!9-C-qn)z-pSN8b@+556nQ|Q* z7`PZIU|?H(-*0r$e)xyzofPwjPPH~RHmPPRKlG-BhRh#s2)&PwXX$uNE68HsrISfV z`hs3%e`C6-wd1ww7>Aa5i~4p`YeH;@?2FIyirShV`JVH0hMw^^BFnahoZFJ*POOiD zc4|iU`dax|u8-(A(2}w+Gn3HLsu~y=kTE0V63VH@B1T8D1oQ=4PWE zTgPi4THR%0dIfGi5k2V$TwAo`b%W1-yS;EseEi6)dCQ_bc^6-%(-^H3i#<{&lZNyN zHiqG4=_x=m_Gwte3N;%n4X#euHh*{f=1I1#J=KRJ3Z)n=4T#mvpX`4B@oZiA?->;p z0Wwyk(G*ETDlCG$y72M41%H3OI{hP0g-HB~ZK=#QvrJH1-eMvtNf#FvZ_?9mP^ioh zI%{YTiz*<>sOPV4G+eSRXEqwuAY(SY-FPgl`*vfKiZi=*{!JG0WfvP8+svp*z`|Ej z^}FKY2s!9pyhcD#n)7I_bSZd7e$<2OT&z!0(FrIz1jNTrD6g(!ewY|H2;m}sx`_mH zmpUbT0WC!K;;n=vcyLTjF-h|TWAZ0FL+JuL zE3&E9=GTi?l8`O^34Bwmrn!?wZLgrj8guuEeT*ikYe_#EJpG3wH_ zhpFgUzqfg4ab06?=4274#p*#d0w}oz*KUxGY-Zt)NLUt@M6PwNf%hC7%tt9bemqyv zK}Ya83Mk1__1-u=sS=|+7b}=2U!Y5WE-eZ8?Aa5E{d^yIyaqZF9=-34Ks-9HFCix- zeL=+1-;k*iSk6^D^NPSgo8Dx~cUu*QyY}Zz6_yy6S=%HlS+?P*qAhtb?>h;;cVb_$ zwI_$#8pa43P|!y4#O?to*f<3;B7!%5;ko2Rd)Ecl_1AvHgb zRwH4nW&3(I#bxHjW&FtRg1rYE1N&j}HpNKmVpw&tUz}LV(UMU6R;>-IGwRbe^-%3M z{Vus;%-!xZr!@&i|I2;qh@h)ID5MSwn$k}@q5TO8WG(r(k%gN1RP+5vTTU^SwY2%` z;9qf=?fOSvEf~W8)Vzf4gdmVj=)*#Ay-KXu09&gF`n?FLY;DyCF+0pN>tX3^q80pX zFOQQ_J*_Gl>({l&)LA-C2XZ>d@X*lvxVS4{zD3`OxNdVZKuuy@Q2PAD?G9R9d9&u3 z4;K1Z^(M8wp)metSKe@I#GH^$@+0W1O-sR90Gzi1kb*-g>dX)w9j$s414h7=z-^>N zxoQWYjTM>GP`JpW#|*x3Z-Ec538uIFme@<8MD9E;K$`=BS%IKN1gC0jGGh}+8$DK4 z>8-kCSE|Nn+;30$QDf)pVSK+a)UoWkNzx$gvKN4AcBw$O1$YPmi`O9`S8a+J+&yDU z4K&|YYcGA$R$jg5Ff0ri-nSXh;VO6Y1Sq!y9SKlrYHsPne2K}%FLh0$`TFELix+K}<#bW7^fc;d%tl%J67B=01X z{i&7W5j>is2~JBRs_NOC?h;ryJb>px2$7SOJvgjJI%1EE>ebne8l`n$?s(mc#yp4A zc&Jc@iq{Dd2gEt@!&KF194=>hbr)<5;>_JK(@*i|Y+#Cs@EeVHSco=K1}vtu%*_o^ zmsN^DOTq5AhnaCI4Gs+r{X%(8yUe`A6TT{YxDKB_=#V*k0F(iIeEgmyp)kOL)8aUF z0cZs(4DRa1q+8sEAw@;^j1WWRDR&}8FKTOJAsoHm4hdk+44`ul4QX*Vowx#ZKX9CV zmAh_@e_&wX6R7<8`P(b`>B9QwKx|*^NqhvzHE0M}ypo^pFK+tl8xTG|15-l`ponEu zod_r|Sil3^iI1rgp0L?_xQk$tD`;zj&N;Fy4UnIlw)P!Gl9{FSfW@NXGA1dh)Yw?E z5*^OgVB#h0A4Eh(H}=)?V*nn)>Z)bOOQf}nNp?@P<6>iDahK-bQaj$))}8{@;g*eU zSNiMF_qf?!OAN(jWsZUe+4c4H&1bVM5(&&hNShJLDe*(hw9cvt1JnETbaj7!|7{76 zJ6hVgplJXcUEHi%CvhjM6zhNiU2}EtzRDlh2&@4G&cT+E5TN^hAYPfxC=cfzd zo=s2wE?|f6Hbrg}8iYgB7fWW=dw5zQD;_y@V-kA56@iBChK*B9-3G9r9C_vXK$#Q; z1?~|1g;LsAlr_cqBH+d+^YrI4px$my=xUHPnP#PU6Q1DxC@w**eCwuvx|9PwxF8ZUYbmR zG!77MT)(W#oE_W&Q102$&I%UTqn+wE<&FIhEt&4z5t|FSgB`0cyBEwh=h{?~g?o7z zm;sakrTk+{OAGF`xgLUKeRMD)S0bu9|!5xHuXfO5M|0 zDA1~p`os`gioR3y+dKTDeaN5!ZaMveq@_t_$~DoG%EZ3O=E2qlYINGbf{}-Qapdk?7|+&xl#DAV0vDg?=(J-W?bbqfqL>>CV1?!@ z1G()z98>082Gt?ik>W)Uywd~D#1v>;E}x%n1iT9iyJQMbb5Dv`%=yWZObU3yDc*~T z?Pm$bFWA*3H)VtNkCo%^Jp(Mz&}Y5IcOT{X0KJKuC3q{u4Gac;AR>YZEw7_<3(%zP z2@K)WL$(8E zgi7DFoG9EHqU;tpRwH(jzu!XnVyhWd1vNLbrB9gKleSD4F=rNc|_m(@Du|&fYX!sP7AZymN)fVU7Ws0EBXG-Y*TA2oVsN{ zSBuMq&wvnyE~|?yE^kZ%C+K>*J9-Hy)G`@1R07t>>yNGdfX(xWDjc*lJQ`=5?gSod zpaX+m*S+zusGwkGe>woqbiCRoQ_?+KC0#moxLCK!WnLZ->XWQ&cO#Lf7b56o(ts%H zQ5chRJhSQbTRs7TM%?x=Fp9V%utw44FFL8+SBf3?eHd{;eO@LV4)WJ%5X^V6H>Jqm6iC9fP;QUksNGF8+NuUk`v2+>NGR}eh~Z*1(nK#uu5Po%;^ic{WnCQcL_ zB<8kwIa~zz_p_itS$D^C0YN?6h6;x}Aq;3&Ab1|O_iC)FU z!0agLq*fw{@O1wpe2`b@wBU!;ScRtTG5nM|osX1=1m@BkfH#a^tS}=bHYBl18IU7D z{Q!DgOl<5BgZR>*y39gVpY$DOU`Nq;=RBw#9v=3mXc|=n=LHD2xu1$kxXI6fpPezc zc};OZshc0OPPYWp18`XlBcomgdcUucv=Y3DDuj#357jBa2g?}2{eX!mfW;$n9hLU~ z21qcb?g1&MenI!iaDo?^vc-eLS84pYjJwAx9VP|Mg!6ES=kL;ng^bqz&e5m>i_~nx zBy5!GeE;3r19hpFMMXs!P!oYQNe?ZnPetwmIERsDj^hWHdDIXDVdFx^J7H$%qmUwq z)4e*T)5ztZ0yQD}5AlP%->iCfi^;Ry-3KKA^S zIk+?{D;}^$a4(-2nWK}l1J2I~N7~xkg%Q1;b*;0{KRL{N`Le{w$oTT>SJ}tP%Is`x zym=ko=coI%I|It6bC*{KhhRs7BC5pqH>Mg6mt@X6>oyv@6HNR&l~_|Rn_371+r~d= zTJm&faME|XS2PvLf?gq%=S%LTd9j@7yF08~qF?ovT{90$DCEN_A2j)&egu6Bj3D#j zB5mya1vTJewYb3J&l4Ws6taO&4eCn*7^i92iEY(O1>Ag~H2P)G($e+2z}bw{%r&$50;|ErzuWIv=Zqp z{FF1ZU(1=7Gj$DBHv0L1$*%WzFem}X6*V!{hUACotnmTrkO(AN{2TR-VYZ92E~Bm( z6Zi)-+htRSF=0AXMeKw;65lVkHSj8o=yeDpSKY3mfzwdiH|_Wmy>&oe<0=hu&GY&w zaT9|n>@D*3?-7^jvvQVgJW{#R`7%i3)vk?>CYie0=XcxZhzK*?+c?0D`MIas_iN@y zF<)`sjp6#!Wwkv={HLBv!+w3QIUgFNiSRu5GT2eW_ha>jwRQ zFl&Fe`EoXnp~skIJ?IDZV9=zv4=7_)+ZR{;?QP(&Agm`7Ox8J$rk@A)P60;#^NOt#SKn)`|%JeTFD@vrb4ibjG% z;9E(jK)m|08yg;TevAVTLx*u-DN9rnAWFs>2NVhA4e6|`lS3;{34Ukluu%u#JE5nB z(zBMn{Cu|)?o^A(3Gqt%=zNLd+>gSebg#IMxT?`yYt8g*Y~$PeA)%BIQ}lgc)E!mF zSLK?C&|CO-k9s#zu2avX_LPSRbnpgzOUx`X)4Q=LPN5;-&VvfTdQt;sWd^_`U-~p#y`TGTV|I z{XMrf0!q~TZkX)dfTBm-lM06kVZiL$+bB#X8E$-)phY(N9bY_yRqU>-%FD}t*|oH^ zjE#>6ft_%)^H`;&C=F3r9Y(yYVQ(C_X{^@GIxLF5ghyuQ`=i?;jx;6#r`U`cs1~=s zT)nlq07%S*8PMmffur(ZbWmjGE*BSJpnjFrg&G%1z-F+I85sH5=oiIRS@#bnJbrAs z?`=%W%qTg9YpRLmJ{V^(aYU@-2@kUZ9$SSJ4+B5Nstbx#z(gs^E@rS{{eJ>{$@9mj z+qyntz^GJFq@0Cgn#MTws@It%U#yQZ+I7QRHm5x+L{DMz^hhPZ=*r!GJB1{dNY+jv z{o?ZhF|A|E9bdgu3g`zX_7xmG*Em>)Rx?r|@q!a=kf@)aQ^v!dLfHU8+`mM)w{s+&bPkucDPKxMu&)eo^ z)!}V0iSsiu7)%d=xXlE52I%SUfSN!i$9GXpOM3x)>JsP<0#^Pu%DmWeK6HOspF@|IV~6MH@%JR{r_tJxrt?w19QBNb$4&2G&FUeMmY7F0#QmrlyF!GbjqNis(Pu=4r*?DzsO3lTOS>o0JgANB>D?D5>Y_Y+XT_Vu!E zHBus^%(?H}+?*GtcF9?k#?ZO>%7q~D`d!0H3w&-}l+Y*74PzklY{_?vB&yJO{CK9N zqq7CdtboTFR%@}ePX}EX04Z!rwcXVY-*Y0qneEv_+2EAKL?tV$CEA_WmsAHqqB8h~+ zEK~OqwLRfb^WPP5X6+O@#X~p}5kmWI{SME<@uPU>hv| znO^V>GAWL0nxq|q2q!zgaizjwx52CD?9|3n$0X-t``+E0lMmb}eBfk-5SoiuEDx;Y zHOQ|B-4`aj@`g>Q#VJ+UP2{QtJ~_zVU{N`Z-%h_?=?Lz`JhPY|5z*Bmec^uZr8U?Z395*D{$!m7@0jk+c-b5k`X)n z8FO34U$R)Y+zMn>Qe4_^r?_^p1LrGtZq7_iYIo=seG~HoQ5P4N6dz1&`xX!cE@DK0 zI)1db-VIbDNMpdHH!(cD4k9YCSZIEhi`E{f7?&xdTfzfOGyrc7o6#AA)k2p`QPXJ2wsLh(Wsx&qXXKDm$H5KF}y856?Lx1 zP45~%jbQa`?Cj8=hL;S`%6fkC1c8vY2S7OUD4nOzdG=H#;!HGBPsY23X$H)zvkx8UtvXZ^Y8d3M4U~-%E&%J&;=w zPgMgFIS?b;rGc&cb8(TX8~g%FLy8*f6N+_oD*BqOgiT{dX<=bA2!|UPIh1sFb!{b| z7gbl2CHGq8D7*d*f})#2X6x(A>I%hOFVEHRy;*toaUwDI4xH}=(W z+6Isq17YO>jhDuz<_rCnf7bY&Zqt6-0}=Ux8b2tsCjAjN2gg=e63BTM6?N%>*eC5T z-%&W&Yu)Y`P`SXr0q?x=B#Vu>+46Or`3A(weV( z&DAwWFgz;oL9kol>u7k*z`#@U8)F~S9qd2|e6P`=^b8yD25EI(f8i$(fkc(-^wKGy zfdYB+(ZI;7%_~R zxtORS!Z*Ie_}R$Kwf9H?XcE?n$AVlAc0fV++SZ26cYti_cZX65kRzR+2dM&^p+1lJ z%|~n#No{6)M>d)Ec8xINwu8)yV*};W63>&F_44YrK3K;=W(_uo4(=eBD&Vcj4t5b^ zjScO@4i0vWepF5}T-@Bqa@8RxY!V(8NiSZh4jiGvvNFuhJRT1?gQg>u{+Q?Q%(W&> z!O#L1)b6`{EV(vp9&a+|Z-wLIs%N}=d8a!xLE;tfY%OCu_$lwbi z?dgLDX&cUaHX!(@q@p5-d|*v0bAQ``i&6&dEcy*(I)sFVm-C^!)>&MeRZ~8mZu7yZ z+QMCv(DnJxQ^CALLkT@SD)YVyMYqb74`pulLdUKJ01@Dkoe9R>F9}?hnYlR_0A)KW z)y(sF<)x4K{Ffj9-k_zu{tLF4E7T_ozlC8M)$nx8XO6HN=)(qh2L?hyL$}aAm(kXJ ziYaYZE~&L7$W0h8W|y2pkEA0|K!~cCN?HI!084UBJm(u`I9fd)`Ga!bGc+=t*1vomE^^erABO22Q zwP#|l%i~`FcYy^gPAJ*bH8NTk*@*ck)H{&a=|Wc7t+Ai+%&PCw32wJ)w7t?yo02EL zm`im9GPkbQdp^b&vg7j&%@M6A9?#@?n=|Zuv6J?Ec6Pn|!}`7FX9_pp-DQZw*p4JP zh{Wf!MmV{L){orGH256Q6KBZ(OR#BIhN9F8xmw5W9`|;~3+yd;VpKWiP;J8}wn9z8x*wL{ z&ANpCL?dGsnIPnZMJTjJscI1)5)wwmSVPwz{$9;+tL*<;&G4#= znuKGe@wWl98t-l*`xhyy>?a>L&b&)K=ZmLMuOI%%!k}j>N#r>B>vGera-k7+wn_1= zo5*EP_b~K58>v5{*j|4_K1bMe=x9Zwy#%@&cI?M|ttK(nIN6m4cyg^e!AD?)g2oDR z&sgIZ#i)~4k6xqa&O*vZgJd%?8iY)*adVaf&-`9uv2-&{cf=j;IWW8358T;NV2IQf-;3#LMHm0RC+D+(6n_sPn=~9UDcu6vkfW~Zh5INs`q(8EPmnaC)^*I5#TyD697H%6Tg9Ko&r`QMid1! zO5mE~01^Kk$g`q1>k}F4*UQ_@6(*Y0w8={H3NpI--6N=?TAhq?*jso$3QnHvH=Qqp z3m_SQUHbA89#}Adb=ZKc`LWk(%6o}cP3CmRqgdTKr?KIZOE(w%ePUv#u8E%<5S)N1 z$Dd&6s^p_xp^BYdfX(B8RG%WqBYpRp@CR__g6Ky5_PG0GyU(W&8A_@^JgC7mPk;&9 z!oQ?z-I07#HHRAH(yTz%7za4NL{<9XEX-KfG#*hW^Y2h?9UlsaV$V+K?IITgb6mKj z-wu;?l9D>k01b+AVP#qJlLNjshKif!$3cC~>_43C(E&6d@tD-p(f?Lzdk37k%#|Bb z7c!bRsa*bTPwX7Hbw|}0n~iDTyyXiYqb2(fWM~lTD?XR~vR*jPx3dkh$+E z1-4|i5?7K`Q$(Z3s;swxguMx>6DWqNAZaJI-6K#t`<5CT#|!ss800!sJ4Df91Cqot zC!Z<+>+AxCPwhfH#A~Br{|Cs@fi&2pYd4n>%Z*%i;EuGdtiT0Q`5p^R0zs}RyZAff z0dkb>+P~J_EdS$fWA2lQhUzZ~$bFfW$`d^PRL94pML-3>zt&*oP6Cj> zt$AKrA<6G?LyCzsV!?R@SfXjUnwa?{Xw-X~K7o<*C!a$B1^f&Sp7LYq6Onh>u#p3b zCJT%HT|9Kg*xYofy0JX%7(|Rddw;d}&>q(_F`j_;!6=-&^YXnt<{Ul_NBSk+{X@%- z5Ck;LTAz!<7nI&*zdAB1@J#|*x%k{oGu8fksQtoIaC3GosbCk2$LY*Io78UV>&@B)n7d$mr|5NN-;>OfYt1*^9sdn%e zv)qbo3>P@2orj;rtZmeq4m+%sOpfMl1o3E9=giH8fmrnMbpdm zBmzr`b|O{yU>ikUKUbl|n)CSQ-Ev^TmY>0X)qZ0VP38KP_N@o(q^Gc8&3%xktCv_O zL1F?*rjM?9l6yLNM;4FDsH8O%M4JRhVQkThfWq(Cs7@R^rI%dC(fp7^EdO%+%P)lv z6NSDI#B~L%j$CNu1gpdr0lgb5n`I@o8M`Sd;q?>z!U6G|s5c2Nbgp zIE4m|WN~o7!#{roJZ0{Dl3h@*nVCqgEm0&{C!7>oPMsSBKKx0*fJN2=ME_45Vl@A&K5}&c!NWtWlqeg^p4IGM3K;UO>r%lA z?MBKaV&i%n-wm-PT*S%u!!=!PQf5ViKfV`ZJtBb9*!sjtM@2=IYQi*~k?$15V<0C3 z*Uk;<8+2SGyS{QbA28UP);T9u`T7L&g|cB00Bd6 zDehlao>(VX`#mzjnnXcsC)H6sqslftHFe72Id;Jg*6T~KXt$FQRMWbpaNLHyzU8Bk zKZXbz4bxsa;>y=gCYHx%JzqU1#!$QEn&7_0KArWq3KgEO0%QM<$siHVw~-i;b_Z1* zGM=KWoBA7L$*uF((Ub-^X^efs@ zoqwVR%iZu_1RUFzh9|sflmVBl(hn<}kjHO2JT8lDxY~h*l0ep!@!2Rv3ZHGzCO)hd z>vHn(S%oDr)%qV?spt1*yp*kZ3d2f~6sLZy$Eyt~1bC?7kzSytt_)Ja_mN$Gv9+8L z3x)5RRr@v5HIL|KMaUC?S$+DpgWWYAR#XpT`lp=k4-cU>UMS=pTrm=n|Lix8??{Do3eX1pSZAZ=O?}-?;c0f9yZG3`*GLk8ydTk?WmgD(WwqE_xm~8a@q!G z6)*69$FiC_O&dg$elABk__%c1pd#4q9Py^yEdU?AS@)(C^71#Tn4Bv1t-STnVJ~aM zb^X(J;v8wuhYhyHc0%=P2<(o@A7RSKWM4Y{*zJ?P#&~N!ZT~h79eqI1G?^i`rUK3E z=|UNPH(yX@@kCt>5cFpV)e6q-4cdmj@w{Sv8gYLY-}gI|wl3f8a!yDRqwJ7r?4LED z(bXhXW8q_ymF|fsa;Tr!2wIrruqO?dcpQA!!e~ae@A&vY>Ex$b7j8YMME=JbdMkOu zkZFa;%RQne330p~xIB};Y(t#x0n}zmu~~U0?XU_*)iIqi!+o4M%qo`lkkC$>lF4bD zyiy#0m_xNfaRLPSNHyLo39>gITkt;qc!SSR1BhW@?LzOyj|d>=s-%j?fuQX*p+Lu; zk$9f1Csk`71Gw8?pjdj+mtNH!S6?A1cL6GAR<^G}T-{r=uw?tzE15C9#u$(g2u-mR z^=%yCaE*6q8^=2+wlLRQ{qvm>bF0XSXr-x0l_sbR`B?;{{MZ)#Ep2c-ms{Wi>n}{T zg6Lh#%IOynRqlkc#$W|F4`HV=x5lvz!y;By1!H`2m3QCS2VrcIUN*-ViJ`{jXiA zVf(rQ1D}H$*6v;47~fo|`BQzvR=Aph9L0GwI+o;aJ=J#upaUHP!qSyd7J zXM&im3On3WfUdHM>os!{hdvMSN(J9c(30(=-O18aqSUO?KOd%~;cdEhai9ch(+k&Gn+4AI+ckna8tYsf z06>KnJEoK{4>eq+GmP&Uu(aO%>B%bawZFJ|Lp%(lsCgM4S^rw0!$_fC9j8!X)azLv zo?+#Yqy2C#qnM6$|Kt=lwUbo2&yilj20-&e((sGUUVVjdpcIyHN<(NoQ?Sx{=dH#Ub)QesosOa-dB?pXSx zwO(ld>D)ah_zQPtpWvIomLijT(0bmW%O;RL6lcR!X?#Ca*=>GcGUDXnO(HV6=#Bl> zKn%dI7@!6{K0Z2xW&m zLh^H`D4A;h0F_PY3*laLBDjyPXU~jU6H46&10XyH-yba!yD_uYag5hO zx4>7Kfc~NEXp?Q`ZYmCKm|csX{AI!8dOT8L|RJe9*}Moi%OjYt@T^EF;!JU`sGzsl+hiZ+Ek+Degc`K zaDe0(a3{QgQX zgYF|Q6cypc8D_5`xfvN( zOpdXL9jtoeY^htD4Sb3&KDB?sjd>T!<7MwZz7GJ65+Ok#VVRwg!Jcj5;NVbKGGFYT zXW22d|0wA{&=0yq_2tWFfKh_Tw*S#cNl9_D#m3m+a{NZ~Uvkf1$`6D}?X;O7cnW&Y zKPl(iP9bLOuu%8q)bBw>d<)%BrMd>X93z)rC;e(olyzS-(;+*i6vr}~Q*=yOlZB0q zfsQUo#iJy>WH2%wzkl#sL3L@i^JNK57O>v3uw*ujeTyjBHHE)6#UdV#c3{Qv+M&89 zI!1QPT~WQxaz!|2-FH=t3nzaSEfZPjKz_b|vg5A`0`CW9EbScQ71F!KP{md1x$GF90`Xb^Hc1|H#~PkoYb^w9=Au)|G*V;FeDfezP#wafLf$`c3&LI%@I5hwDN@yJmX* z6>md9v|>NnA=oDwip_j3lDZ{~gc0#hCc-?f&rTfs4+1_E2`Om^{DVUK!W|VX*ZMxp zM48B(SiF9nFwHAyb~0tnM}9%tj@b zLY@)?5|z$dsg!4D`=UzyVu5z<*ME2P;pXau7&O+2lUQ@n79>WEg zPZp}yv7?{AF*U#7PhrPTGqq)?Ue6EOuDy3}O~ox}=lqbRiyxjNvVo2)cgK9|CEe&w zX0L9!ejisXEmahN6IQZ(o&f*sYX!*9ANsO0?g0mho`Iowj1!Zw-Q{5YYW(2su|yQD zv)NBM%9voQEL+%2PaJR~iP3}eF7Q*qb0h>n85d3*EiA)yG1)eQ_>`2Ssnd~y*HVie zVh1dzn?;QtEX*Z{8`+=Oxd_vRIGHr6XpJ3XzU(+ZBG@$TA&l9R+SGVKEOF<-gJ4j1 z6OK%uA6rWoxvI;_`CEUxvx^S1Fh0xQS@AhqX?FCXa9w*G?tMfzS#!asPPXVcBc*|y zhhdrkKtsJ%xln~J`t|GSbT5wMo@?obU5ShM8rmeDDewo8s?Dl~jJjY!PDfO!+Usg( zJVlzhgpmmk4jKWxjKnu)fl)%j2QHG01iNGV?maXy$3xi`*~5Jq1rt`KU(rf|EwiXZ zN#YwsL?2gEc^oz-H4KwpWSZ~Pj64?WxNlA#NKo^Q`ntV71|%)pLAF0?@$Eknk^#K7 zA(4IQ%YoKqGy7v4c{{Ux(YC=vm4e)-(+T<>iF_FkyJ>s%8INY&vPvx;PpAwi-%ZPS z24)2~W>NJjP>>0KJwEPWs@LM(vr6HL&ny*r;t|Oe=qg10dSikXrkok~rtOB}6QwLa z4=s~4`AKsgX4{&u*Is3-w+2fE5e3Bx=_3->M0qtO(Jx}eKhbfIez&y|ZDf6lgk`w) z*H187BxT&&S?JoRds!?xnI;cZ#rC-19C`hcfSOnMK4M}k*B^Hj?&&bE2&5oozBqM! zdZ|jPUcgoUMU(J2c(2;l#D~s>x=u_#*Yw)W(YP-z{s2>4vO=659v81>=lCCOAl5ok zx#Fw}l2-b)#;dmO!lrkw^t7NJqX!C5Nks_jUqF=Ja!FN~bfa;x?xPU|xsUNPS{ln! zpM%mJe)|?aeNpX;L(=Znu|Zd^Q(<0wuT%Vaek`2ZWaEr6N;LeUSXccr*TpZ%1pid0 zMf=)_LwrJn=YYD$9khH3L!kK#X-Co$Ij@!5`oz8;8QEjko|AVJDfiTir)=yRFnb7I2jLCU(lH1=+Ku4?=yG2eU_ z9BNxAjzv(K2*q|S(UWsvM3(hETF{;t%$87|NbHTQ#tt&|1$B7Cb>rWN&Jun4T+9yZ zUAwL=&B%TQ$C#W?tA7K>j4m2;y;tA+?>@catCbwne9S;GX5TmQBtM99x8bmHP~5tK z=JQT&w!MT-r$}0w-jNsmroHithw=JXgfi>#1tLe}4-% zp*-ZAPO%XnhkfNHG>dp=T&3_00-VU6%%a z(#__~{fax~$c;nph@dRp^9M9S|H-Jb6CSz-nr4-lXcY?HuA^W)1t(HXEz>m*a&fnB zzI!PhX_|tknN4v)(%_rKS*NjO*fPSf-rX?r=+N+-Yy=z%m2zdL|KH>Lo!x(PT$&$} z!Et;A9flb`t<_1nn{D5x;F>PllAbJJGgpa99Mx2=sHk?|Xb?~HK>0<<;Bzv2ge@InER+K=X{hTyzWkH*3IKayXXN zy_OJc+0~L{9x5?XzO#uqm?^kX)IS5SaXE8{0={3&A|*Fx7;j9-UP-s z874mb4}pz3FjXeCGwg!GBTZMkP&ACL({t1HJNOm|6aVbLTa`#MRJ9PyYENO|2rtNd$692ArAAXL%fb+C3tqg zw$ER^q3E%Ki7tF^J}CMmta5ItUE;5N{(OQx{_*mu>+X8SD6V2H3fVG1>h8PpL8rNm zgQw-)-nylDRRy7$z`hnpGg~mgZCFycU)Z8tYl+>5R2)%Lk8Qbp-oqDQ`6qUEFFTl8 zsfJlR2v247XLy3&(eUL~VORvy#2WA1+knnl!O5w7s@zh(i9Epbg|Q5qm`tc;m zZcUW#$D0s!%HX`JHKu=wsc6>?&&4x4FTra+nVwD{FTF5f8hHQi>rmto=H^L#x##4K zUA#PY#EL2{R&O_e(f&bY5&JC$;n&KQhB)hB^$q@w;$AebjXvZVvU2*+N^&8T=i~qU z%=h7_Ijk1DQp&IAc7-R!(iIdJOsJ#@&TEX}qN+E_}7P zq%Xc|$c}Hl*>^;B{;d^F^}M&5`a5&`Z{BVto)5+qKNnWpz zF7;NKrP^6VGsL31kACFd26Hfy{oLnfQ5TxVhS{8^RW8xV4ThC+vk5Wf$}!J%#s3D0 z)$XH#A2asYkkX{Sp7p`<>!75De+5D zuGYFmBXKe1` z;o-riTq&KV-a#_l7XnC$85x|_K^Ykyo;qNqbb?T66hx!J&2;w$fsAkqPD>sYzv9$;K)b_+`}2+T=6>s$kSec;CquRn2ZgZhRp|XYGu*=9EC!<=Ppv+$SReQF{B1mw6&H?*Z?l0j z_zin!m^K3ADpqfvFkD)$CNKHfQ%<#`i`kZ$<82=^*I$`8#eHwP z@t3Fh*nTKFCAC{)2K8|kwCgh_bb9H|CfuEUNYF9x&k)W|94=X4FmI`V>X&dAx`?aBdo;=(SEa?+9~7TdUR5Z z3cC5HjUDz!?k|TLF@_N{q<+0Dke{@D>%87^FM#XC-LhiQxOXBPwKZ&YE)DbYf)Z~v zcx;-w3pIqcRACU`e59wQ@!Ya1bF88mMuJC00;*wF+nRB~!!`BH&jr`&1{yl&aujz? znujVg9+WR`2#%=cm&(og{?9%r6~irD@~z?(aiLyfuEOol59!H|6MOi&)_rR{U0jNP zeYEc(pbhWG@o{(<|L}GNp-k#Hg>^xV3D`S*sK^9kKLt?!iK{JRMhhAS5&d4dDGO`<`0*N4gf|0(G#w6h(e%S`QW}g zLw;czOY4*@@I4yyIN6c{$02wMEP_&AU2+^#g{eWK%=C35EEuK^^CZ+x!A?6BfQSN@ zG6(J%Tni>;KtA4m?|-JOZ`Nj9pz1fe>txntHggqrHHS{Ev+5$P_1mWG$3#EAvrLI3 z@OBm+ZM)7%=4fJ=9kSPPqR9tBQkljZ^M=n(UuOuqB6VPEFR11@NAJ1Kp zvVl3YNXprgRQZHWCr ziKxK3K)@=`#0Kv(NuHptwWgv{t5FsgMkLsFzPC#?H9!Vi^xBrlV=whQLSR z1@Vwgwe_j4sQ#6jPRW|2$V2n>9lV+)ih&R{Mx@wAS|~wQR5BOjAVvSjN_WlDN3SU% z*KX0>8fNq0Vkpxs3BMH**3zsCs_Yh(Du*|HDD$z|mzsPB7gp4+IJ?LU)hYAHnSLX- zV}oX;cb*X%Vt)!gXem>i?qFWvn_$V=V*x~UPCw)8~iw9U}Qx8nC3Z!@)iV4 zUxBY5i_Vyj)IVu;+o(qIEyUO^4&~B7Xux2xJK+pAWYgt&8iEBcoMF|i8NXBjo>px9 z6=-s0BI2p}kYZaf~G22I4+pb=0KRsrrCU@k)O_jak%jzvoKiZdyetuB8 zRja{i^ZboVbgSTPQ_5Vqnuv=l)bvA&7y2E#k;5o{w88rgYEkeMXj8^-JqerQN6c;ETSFpX?{&xVPMBqNs7 zkZ)d$cCDQMgRGpK&#a0sx9t~dZX(1pr>eN|W_9G_*5UT3uLtCgu8_V}xb*H8O)lQk%6MOV<-!y7az6wF781U^zy9ge}9);R0>)$bBxnd;~| zDLc4`5YsswUE7wYh~^_TE|G*rjb^H(`PR3@(kT7Ydui6i<&j^|o@-BHF6u;%{$Xd7 zVCW^D=55N>-1$EBz=#AcYQwg0&NqLa);I&oL5HmC2QzcPK6wQgK1$D%t#NnMgvS^* z=On{X-PoV5{0hHw@$o^Xvhu8!|X0FTMit3E(2dVSU1m~s{SR{To_o}_54*b zw(z=CgR=)YD!91;SDEKtlLv;m$fJ1VBQX`NNJoRqm};my&pXed0PID!beY$7cGEYH z*`9E%Z9Gh?befZT@-zc^TbuZwVI`pt?J6kSL-eJ=Rdzb;E*=?4$b6}X)SL*rmOUNQn8@n5j)%GD+F}A_bd_5JIbgwWuRx5+p!(ciBQ993gPUH+u)9%_AGoDwE z?C!x{rzNuNPP0Ji`gA~tue0!MA&KZQ$-lVsoe2??ai9hh0`pn!xnPrANF=dVYO0>+ zt5D9^xWpkGpO=V{_Z6wHF~xM=&)Kl%A9&!^BhXCzZ5ma_6A!~C3|Fc2lGo+sKjQru zpZIb59zTwgg^^Z{q}HCj!(S;AjRw4mJakWRN+`$xRoo3I;p5P`0XvjHaPVT$bl?cZ z{r-^a>1}L64`&77rf|LDo`E2qs@EEJk?u|YL=)(-Be$lk2b=bnb@~8$^#-<8((3cX z6#)Q<+dX<2Dr7pG*L?z>FGL~7!Lpc4U(VP-M^CleeB^7pDVR01^!=LveDGLg~ z=(w}}rxMmht(o@Iv+UT#dZ|{o1#+AocS#=qC2d_8(B^n$hc%eMek&Ti-Ft~xINeeE z`(h1wR;g8e6)Ry;fcxPOW-K$hWkqSj_*FGWJF@NM)6QvGm|yFvq{oEt^}iRx2YD1Y zJ^U~*YAkY)trr!rx`d$GyoUEFMlAUy>bacMLUlWWZ#HlR-As5prCNf@^$BlYX_xxQ z{BP8lGNxuu=Fx=F#i1zod?fFc?2Xg>0-WnK^VjSbR6|)^7niAMk2GAjekKb(^?rJP za4oCA=5SO(x$Go$bY;85is5f`v2&7t|6J|u;H@defgY3AuJj-H``LnsYF!w zB~+AiXgtmi5$wd9O&9xNwsq!tv)N1Ah6Nj+PQ=FW;ki_m%b>3to9YaCwEK+w`Y_Y< zquj>SN(8;DbVia9Gd3BVk3LBFA>bFyd@+ z)blF0?cYq08nkY`o7$Zk=-I6Ycqm{|&0>?2Sn|)oj4vSQLV-9G3-LvgwAgRIND-fi z5Ou#>!&rLkVZ3Ff7+~euHi+>haxu>MgHuK zAj(1gD+;Rzgy2-Lu*lr)-#iH5b>i5ezEa zz%!Yyzz^KgI$D!_WuaDTZ+;!?Ah%z|n!>Ff(uoOTO@2VRD=-;ra|}^7&1Jq4SYuvG@3kI5Q7p%5BAN8I2oR;NrfSdUjxo@*5~n} zFrApn+C$sZw;|7OhP60Wz0PtqI5r1+iJoegDI0rk=CEKt_GU0jsl1FMHQBntpED=(zB z%hC@lhD=F8I4s(#!aImg3iu|0zYS(!>w$%fSX!^A$VLI)RS27@qYiAjB!s2n0f-12 z$j9Q506|*HMhT0yV_Z00klkaqg|eHRXMU458B<%Z`V&4uDH|(Jv2uo|@}dR|LoYA< zIKL$;O+WLoI?d3E__O4yjK;Y0;$3w@iuwYd*jLN=Wnf-`X-|t?E`$_&jKjx=7#aWAAYiL9_4;LkzTfvXEX{Y*PEcs$_ zdEyE-yv;TLCWR?*0RU-flbEURKeammCi`X}&z4_wO?>*;@`g9Z&2_WdqCZQQsT>t# zeb*ZbmrAz)4lGnNi~me(?vZ79=#OI&LzN{)>RYZVvwgny`hSKC@n*SHCuduEP6L(M zcDfS338XRL2>%=l_2WDdhe#2wz1Ht78B|0A3(GDcw)x;*X$4CVdlMvIkwOs$l;56Rm{e=GFWHn}E*b zfy?4uwoIZQ&$aAWLG`#!9%3XGYivc42eOf=z(|^$R;UaS|%l7^|9tGhboT zo{Y5g9l$EWz5)PF=Z&PWG;A+>^zo2LW)+}v`C#9z={EkH6Tlwf9J-ybVHO8`=zk|x zO6Na89>?I`*@F0AZ>1wbmM#3s2jx_&VRp1Vnn6f5V8K4c`)fYZF5p2Zlbsx6UU75X|W-b zv@jT3nWqt|k}@ewyr3t!ePJ?w|5gNnKrHissBHuI z9I^Jj9G#u}n!XO7tJwk2l52BKxm4l44?>mrZ33q$8%LMfPv?=_t3w2j1GD#TJ`4Mt z#^gw}HLjEQ8PQtxiXTo^Rqk~SSNATL^mIF$Ekuv!J99cHkUnJ@`;Rk`&=ae;Ch9*h z6&ZjYl~W`R*sx`$>2P|VyeQ*)o)Ief29$UZN z`yggbNVqlf;Eqs;MvPSR>lq(K6z{U#Yg_4SmW%yj zzJ7a^7e71J;rw$m?nIIehV3Zf=i0oggZ8oH3N3O<4jp+rd?`cknhU_x2?_FH?Tx6% zwstpNKa&GKD`}ujZ`yTZMHZCLb~8&|vylbeGuEr#fUvXH4fvAg&c5zYNnycqHy!;} zh%I}cKLMz4M<&35RS-E$Zn7^_XO)fD5lq2Mc@dJsqu*W7d??2~$~!K#dZE(B(ga7cv^t3YacA+C(CnzhB3R2J1PHucNg23#y@B32T9aq25aqHN(#QI z0?=B7gw|iK-{K$Qh%D+=YWNw;VU3z!IO%1Sso>DAc4rZxv0AkoEH0fNeVJF`$;!5n zAxm)>gujtbQrekDP9zM}9-AeBHkr0^8+Y`-ZhN2#C1;;3dbH;Q}LniyAG{+~KnDJrn{UQxgXC+{iGxk59& zk%cyFhtL^fXWK+EhYF0ck##WW`)OG^L3018UdJ~cHvnEfUcn=Q zkV4@IP+4u$va zS@p+YKK@i*ets@OS8`}C&qxCJJ?rDuW9+iVvLnP+P?jU+q9GkY`!(Ag*nkvKDJ|K~ z>M8}l)#HNs7}Fk?7BBQf^P$1#|Kg`&XuO@(dC5Q^_Hk^254etxBccBBg}CEuy&-wotlep-)1AmP90#N zc34|9>+G_idGfMqaCp9V0{eLNxTn=2oWzmph*$ez$qZaIcK#d_^KmkG69tDXl9F97>%MkF zzhrx{Y{kiNgGs1%!CfCc=p!718p_7nva#biSK(2Le+C*8yN&b+vLA&Pk{+#<9mS&q z=!I?QOD)`dVnxo{BO@>pgGk4n-Nxu8vZ(QQ#i1Xf*^xDY-04!IkMjW`c(rWYtwMoD{29?+xagu*Y~M9oXxL)+lEl)+GC7pb6dEgs7>D z40mLlFFFz|Dir*1rzVPvbh$Nl54Ambx^#BD;xh%1j)J!w`?wPIQ%_bdRh;m!U#8Yh zRS3E%T#}Q$mYI$xx#Xv`dts)rzrn_Yoy5|0L>&buLUCr295M%;x`mm4f;Y9hCK_q;tkkM zhl`589G|YGGGNnGP0a6z{%I2GckKxa{=-bAtu%z={q{VEjwT zA=t6Ie-`8O=rAlrZW=b%a|xfRXW;rbnrZZg+AA#F6!_%7T3cs;EIxy^9C{3e*1Sqb ztYC-fb>|78PYDaKlm@#z#R(KU+Vsis+KgG2a>5M-1zgx)KLjOeq}r8tNZXMLOGd7n z{gIj)5*hgv3UhoC4=%=l%nHCBD}x_fI5{7@fK=Q`(K_%Eu&A%$#%_*pnSI>HUCW&K zkG*qUan70#5Ib;&J_-u~11)PrL3saaR# zz?)-c&spInxq0(27Ew7tz3H~Fut3oU)IW~}VD4bQ&ywlu*V)y@Bv`rr+EPN|A~d_` zf%CMP(kv<}>a6AeFNjA|EqCp2Evh3Q<)iF1u!N&?@?i||Y-gpjRwiB85jLXD6<}cZ zm_(7P#8n{upZAgvgK508wR1kG-2#TqTp>hH+uD2Oy%H81#Q1;0s3IyCufX}Co7Z*i@5Yh!p3Pwtv# z@1U{@DE1|3*#o8S-?1+6`&d_aYwpDPVd!}oeRsK-NIv94CTthR<|rgBF|Usz&5VZE zc4$j=#U~;nfKt?KQCm^=W#>42YeYRv`0f?z;;qLn;eAcM{D(1BrWCfN8%7$6mz^IU zjf9sJgQwSFef)R8nqZkzT{V06)ODQ;y-RIKJOEmo8Q0zg^b6H7)x0yWrU* zN7{;83>8(=K(*_u7sPpK#4*G&r|&0Cq>F9kqgMqY+&O~?2V))^%n?36z3Q^3w&-FR z-ELc6{v$861<$f<)Y-$rJGn4vMF3Lq9_PykzY~|=&t(_edNhtu5!WrezJvN`!Hk@a znAz+O{Vf;TD$nu!7a$Uc2v4Wt4X`G?_?)y-uC>;3iZ>q z!Xe?vRhphmI9o&^QC6GzutcGe1Qy*(lp(MBAFyz`q zUon!9EOZ*ay-qPqvvP_gE}vi>E{3+l%n$l*dju9NctQaI+U}B{HdGmbNwkAsTRE>3HM-g}6 zDeYzICgZHt`vd;Qnjr~KhwK5V2iHS!J)Q$DDFWFf;_~_M1D0_NYt7SW?stzI!ln%@W=aYI7m>>@cKE5PD^kFUcbu>%h2s%4 zcPE*C)7`9u5&*bevVi{$xgQ83VX?HJ__C5}+g*oh1MBH0wX-=e1PyFy`2N_7JUbdD zr_e-V2s#2ZKEfYx2HGZ^$Bdu`ud%uLfrWZQRugO=$HA?H1#^Ps?gh}r)+Z_tk(kpK zsPM(M2~tol0Fqb_0OOx(9`&6m{s4kVJ^%>7A2PDa&A$-m%8qSQ1$-goYPJA)W%KLK z=lh_jf%&(1NC)qrGEnsNmRuhw!g5}gcqFWKYYwvxmFJBNm+mnGKyhaGpg~+-K0w!C z`e<)Ok@#a9du7&n^MO+*x|C(Xx9ff>rjp_|aD-DFyW_57eEVxQ8;uds)?-WMOms%Q z6Mci0b*BcCZtlb~W_v)jv*7CSf#dYC!9n{7ez)L* zkDr^hJK)?7M)A$tGdu+6mUHZgY<~-!X~n%uxd|)>xgFg2-{bYhMHP!QZLQ^oD3RHZ z1Knv)NeC%qb1&hg==ylO@t^;Z;?SMSG9@4!w#G!iBO!ga%}0iLGm1#C-e4x@9XcxN z7IOKhKb13Hbv?u2^xN_9%krUN-jU$CwvY`YYuVbbRJC;1*9D|xJG$RYTt^J&v9?L^ zvXsfMiS0=X^Bt7>TCWrnwstK#asvXYPxdZVS8k=Mjl$rKE93UM8&NljN&~Axm5x4f z*jq}`E)Nq`cpL|ac=GrtrLy)k6&1#D4`Q5#%{|_!>|IWV<%Gm|A)h;Uouyw%DY(q? zQSB(7XPvM96IyDRzXG5$0#J+}D?mO-H>U}RO(vbjjD z-LP(RU>V4*ai67L;r9}L^JR(K*tQ8Qt~Myhe#8etS&^ciB4C`N#%hdEaibRXcICr;@2eZe9w**8FCYE_&Ub9$*#_cZ+OT%nrM%b3d}}c;86El%H_4fZ5)adB>^D!x6`L z_v!rTX}b8wsgL6NB5ad4+CYKfg7kB9)o@eJgZbR@zm6o5iG4p#Du0t9{x9idFLN{} z6r<6yHY@PrUZ?sZeFTeLxoC5md3>LBifw^UUe_;s9XRg#kB1yS&}1ta$r{mrHS6z$~0<#ZuF{lloDu#@#Azy-U~!^BZ{)>Q@mH^-W_ATYtLW z$!gB)VFk9p!qschJdui$w5ky0m_S3*3znHO-pdX(An^h;=e@e^WKfYr|zf zMXFH9oit|ew|L{%#)_#&y2#uF2s)Zr$l`CU#El*@!e|_dh4H>PW03>kPe<-Ag0}jI zrP)g-z9gr>C)05~LC$qu7* z-+L869$pte7d9UCI;nduuURO;(4)t6KY8al034*F;Hk zrZe^k$=X03YliZy^Wl5auQ^d0nXw_=iOfRxnf*1SFP}x>f2gPq{*{XQew0j;8y8jA z(y~51`}3wnM$hdddg9{!6?1LWqrKEAv&i4|zJL`RE=%xJxK$q{oXQD|m{Qj|wxADJ z>@^t%E6wOEw55`#Kuv0VL1Ct-jax?F9I)5R3FGo7OcpYbFPMvC>rz@|-P826%OxA< zH`6KPAfylOd>?GibhIpY#=x({w*58cVTn68+FRA|oHK9jS1GQQ2bZXbY1-(#aP@dD z-s-O4p`HBQye%;?-v2U@tVKnvySZ6$%FagZlfNj-atf|_Zf?GB%n$6nyRSOb@q3)9 z09S^QBRRKtC8Z|x={MTt`Hsl_L2h--VP1!j-P9ElYNwmHKaxv5n_fy6k9B58$IYiE z4tT66tlHjk^#2y9fsbr(@up|iBIjHfNYR`eDU2jKEx+(K-CN(;bX%M4UPj~Ee5n6e z+9;-YaxT5PyiB2s#9wA$LPcDp7?&q^T}B#p=Qkfa)fq*`hsr9pEjkoY0i*eL9}@FS ztjP;+c+muwh8sIpub^lJdv3HuE763a45UkGw|inG!xNWNo3~GCFmt~+T!K}DOjeUx zK)~##0Rc1iP1g7=kkb2eN)Nhfy3m72sKNp&jWX`QGg{M_FQi;~tQ;4nVw5KJ?BiLp zQl5HS}a)Hg2`v_Uq5*f-Cy2 zwU_XGaR^_z$sWW>t5mMVR4$X$X4R_^@JIXN#*&oiKci>6!y2V1RH6I!8;6yInD>4A z->g;y9UnC_@k*44A?7i%zELc4v`DApzNZ4k22#*E2CzPZU)SVC4h^izrg4IUe;(H_ zixCPN7@Ri^h(^>zAw4m%*cL;uY7q!5-o^rHB?DHe$@(bT{CaOCwEFe#y$lrZ_3pNx zh|HB~wBYkN7|+@Rw2lYIR(ylIOYgzkCO&Te2-|J{xns>+U(S8^{{kX;Pg&|9n%%{a zY@w<O8v)74B#;jYi+LHgswvo_eapj^X~h#l35W-?E$E^}9m zOkDMA7Zva1%o`8l=f|7_pF{8t8=hp9#t=okjF!5Se$OW@)q&{n7klVADY}dHl(?zM zJCj9HQHmTA+m45|wx`f?uTh@sWyTm(bS++1!q80n$Q^PAwZ)FUzOI!zw_7=-FAH%d z2SMLaq0i3A=`e!Qhg#|Qg*ux(kv-CZm1d#4&tiV$wUQC$b`h!}r;_ z2r~MP!y=&O=tSBvp_7(7#d4Cq9-42^Ar;3{^kwK{Zz4)S^nP3M*@0<|vSDbWIA|!riy>^r3#*p#*c^~V(;kS>CcHEeq z{ke%G<)GN+Adrr-V2!A_SLV^6-|r-VRDay-@L|uiM&l#fJ>=El*2@@|u%-~tdQ*rr zvdmfiRXX3rGM8&F9H|k1H2)OWrUAad--H&LKNt8#?Ve}T2RC01B{O`>Q>?;a>Zm+q z9jkD=wakQtBk)$Q)9ov7rR(h-L|01*!~!!rJ|%}%db?TUhNB9ezK|0VF}Tf}y2tRw zGqxaxecl4uQOfXxEk{33JQ}?G^Y_}HX+KBdxr)5fKkUq-QledwUCektKa0~|;j`Rb zKe2bj5(EtsL_UyT<1r?xy+nvDb%a9>9aNM9=>ve}&?Io)mxS$#>+LIbyhyhOaC}ks z>jKd7-+4<>N2e3)SQD1#6a{XO`Q2drK>li-8(_axGutw!0Eh$(a#ouEfl9|>lcZzFnUF4xWsc+$O&8R@N)B_aZvxXauLwCTp)i1lM!@MaRcAsyW8>H633prg;+i zw(Yn?=zIU|(GRm3^|0i>wMw_-GE2ekl{nEaWUEFR3mb54)t^wFAC6Rfv-Efp8 zqoQoJ>L_9wWItM>vOYJ-#$k7CY@vNfj$i}C?~lpPT3~>&j+_v(t>YLMMR5qt&iJj( z@6D+rhCj@O#IWz2lT{?PqV%|)x+mPLo|0X+)FYb}fzq}7t;dfKM7~lIiGBdumOg8xJz=Tk5wFVnC;boq2~+yY*6QPYvQ|}& zx)+~ok@FR??``2c!lIOa$@lS4KE99)pnR)7DNPs+eoMKy=Lj}K$K!md+W>SmyzfJA zfOR-(jM&qR%DiX#n!Q4p=6=^Mw4g9!eQsy>Po0M1Jz;8{j_hd6QS1DCjTM1Jy}KJ? z6;J9r!;oYmiwboj^{6+P1QUtFT0Rj>?^6G6RyZw5eHFm}4hqg&0zX$b_ufU>OyuG5 zRSdmLj-)U$>FGHvG@x^|bPn)5c|#UxrTgrYLIr01ZJMQ~^2D8bCO)~qG|Ps{3^T6l zYtQb@oP;1>uaq0n$-D>b*@*(9VyWfh3GIQrDnN0$MiYk}igo^p@-F>qlJ0unWQY>G zVJtvn7zSO4VoT6r<}t>iDBBAl=Q?e^3- zvBpY5kq=SlJuW)`td^tJgF~Zh&YV(mvHxra2_dI}}0|GLPqCgkp|2 zJ~I8F=e(b>WY^k}$XphENUmaUytPF(<^yJ;zL@J zqWDdw-S{+Tr^7`^ZwAbyUn4S~@A%ivo^Y4q!rc4Kh54*B{&jzjK@(kzxv;0n6MH(eDn=F_-!M)dO$iosc{9WHkLb|bk$lK*AKk;qpL+|(ME zoQA)EYv~lsMk|1$4(tqoL2q(@eUkjG;{%u{4*wke1X9U?7&sA_@#MfL44@-`)pa#5 zGh81GQ>7lAz$oD z>QLlZ00q={YFi01T=RoH@5iZ8;gG5R`N5M<$SIvK$2fnaAT%^K2g*P_SNW^?$Mwyw z+++fjMv~CePK>)v1|xWXRE|e%{Ij)h!srqu5gMx@V%fS>Nh5aRQZXGLG51=n z-A*YQY)tO#8G?0SeF&Dd+(34-gTw#R#x3j|f9xG4*B?s$c=&#-6vM9_6%tFl9nxcv z^wE2JPyTf?LV0_rlM&x`H@5I6#&Acqji5r=f6~nl9wRf86Z+M*126jMU+qmWbws(k zP1|AEXm8=H)K+cVFAR&;dEFvVc8{@+z*RdT{-I)q*R(cC#8;yu9$@NDiLDZGuv@Yv z`1a*2Nb`0}vWpzfM+)*_&Dx)q$f(8kvd>nYS#>mek%E)}5-&7B$4%gry*oFr-e%-g zv=)>w5U7Ae`(VOAr05}owRLHADN&5Hv1eH1uuM!G&@BM45p1R4FzJW^Pb)`}STsuBlJC|{Kw#m2=!aLg9b zJ@CHPECn3QV!IUmlOh+D)D^s!Y;9%6VklU+CPXRlNL(#z>08G zX4#*imh~`+_)ZvyJ61C5yOl*sYl2W(%7Yc?^B2!mML)9WyPOF{x|mo|scTqh*17fG zw<{ID46DxF$b|_Nrzp8w)cQfx3feQ5*o8QHaVcW;;-jq~?R4a_B^vWdan_h08mYCE#uZ^j8Wn;exZWvdUAWPE1U^ z23T=bFxUd4lUJWBGc$bw4Dl4G8RV6e{0ZM zJ#$!CSYSpVsW^bjoPjobC180v9n3Pm4(eU?qYNf8$@3vhSEQDsjwKQiIL)?@31}!( zxDOEx#`h;=qHt2LWlEw`);@dR?KLFZfp{lW1-o$=&6u|TdBzn-L#}8ic#_mwTE_Ox zIncdbTAs`pKD&KGu`L zoP6~Y-FrQq9oCgG&Pp}l;~xP$QY)6$>h z*7Toyi7%ec`vmT)4*ogdbFN}kW!zQWI3pyfs{Fgp<3>lZJ4_yp!G23rTPY*^p-Oe$ ztg=By&3SNK&qWs}ZeuZkwM&Aef%{aBALLrEei&OwT7*O0KK=W$HeI34inBG-uRBRa z&H`SO<4l0$`Jr37JggrxQl7OEqbm@b4u_tpq=N3KtQ*T$*XV5Wh+ z*o`}clxLRLMVf4{Dq(@gM)gEoW?R-{D8=agRFar?f^ ztPexNAX>=fynU@kBx_uBaZA-{kIEwvbW{$L}4(D#-kpfs7_-a=ABu02Je zbnUP0ndVGUMOab|e_QJ1I!e*pKO!_MTu9`ir`W_&9Q-pngbHJ&L!>o~dp; zW0y6`vwv`(++7&KigthU53QvOn#~N(kRzmd06Xq zX7nS6v0Ct?tIy950+?kC0J{f9LRWxUcey|5RjakeL#2=wE}c08lUrRjB-+Ib&?OL4 zQbL!LlY4fz09{{HFM(GwU{k*N0j5Ur07&lOUIJk5waadBYHM+%a-)6Xn`?Q`g*dumsn$lg*Qpvss1q)gEL6XNVS$p zC$IR+@vJTvA6sHFgI2BkPk8?yTTKq3?8YR}14lIIVQzV>4(m6kb&jJ;jTj&?jJhi=&WikiNK?N{g&eXnEHs`B}gKo@77c>Z{8`d z{}9vV{GGI2A_caQ{2+EqqR_tbM?YrQSBiOt)LOAc|} z{Grh#@Al%p@fLUZ)+itIC4D?fffdi@=B1|YnHUnoufLRy7jIikYtrHnF-0)Q?kEb< zlZ(2`*pQ$^)*A9wMWT%bFUsdSw(`YkrJU*eZ7j`<#Pz6dUu+kppztQ#ncR2M6wKWz z>6|#6@V~ko79iZ5=X~C?WUa*^Wn4X`)ner>s!#yn)qyr8iF z!}QkKmr$3J6?-H2Qx?`8arLP67xx+M7=o$O+Af!ANiks8SnR3_JEd zMSm-U);d{Guv_ZL+))yHU14T6ghlA-meq;>(dtubA!ZVrAYoi&M?dRZZmGBo|2|3o zdqLsNYevP4D94G?t6=l2TI_l!XoFlmADgUSfmH-fy+_twAC^EOe*Ra*m;w2y(OWYT z8R>Cd&FFxwZ_ehfQ|w`;$A3jFtG-#OGkqOjgpQ`MRew{^qw0D2X?d3(BRr{7&Ftul z8XnuL+G98PLc^;8(Xf_>P{#Tz=D(?4ZX-5Y7PBzv9|cK>-HR;X*svwp%HHtjf1xXA zBL4HY;sBk_2>wrqz(S2qA0?oCf>`DtKfl){b?dMhnTJH*P*G8z`J$tH4lJy!&(49% z#zCM4!5lL@S?>mUk}uPh3pp<)6*#YT8x8hpxcY$y>?f)Ct^?OIT2x;CAo_zGS|5<= zC0dlcJcv|*g@t`fQzH{vGZFnLU}Z&DU0v<5Qb!;dMQUzt4kEe)VcQJpRo4_|c(eA# zG{O{dp;}LTqmidQs8hzwPY!KhnHu!B2XVlTt zbc%@G{3%Y+2p%XClaH|CQAcmT!KOHUybo}>Z(F!-wY5k7XWWi!Nxock9jf5fP@<6- zp({%HpMB+Vf5PwcgLj{Cj^?q`sE4(Wh43I|mO&Hqh*8puf)VK0QWacx+_d0KETw6j}g@} zF0^GSX)NKY*#yiU=IHSyBOMNc4Re!lFtIw6nv?V#-Xkc_>JI6%E6 zqFZMJyUi^B3;oiySk(sNyra!6H_1^UCx1(FCqu@YTA7K!_|oC7DpQ_{P9kNr zy|JYRI9m-|Oj5FMy{~Ia@4skpvtz{R!wRG|7>?gao~sTlfD^4f+40Lv(Ur%Z_{BS1 zp6^>FhG^I}jTmo6ga1m5kw^p^gc7`wldpoUz9N!Sv&*i#@S`0dsvn^fmlqq7N_k&p zbr%*&EdDWx%?f5UkR)6n`xFru2OYip{^soEHK@&QwT}Md#{}VW6FH7DhqgeW1S2aa zCuo#?)mKu(cIU^&$cR#`yl^;ISH}TphcE8&vB|Q8B)O1LQNKt^4vMK5s1k{P1jo6U zm>56BcUxa)w39~gBjx(xmnnFeIveSmtny0i{Xg(>mxqik_9g2o5(L4Ca3>ivY(9+McB#pRF09{+o=bX|rF2-ECZ89?|hcc(Baz4)a( z?92Q9!}6Ph(9kICxOqAj6Pek`<#rjXONP~Qi8o$f54elleh|G^m67OhaYwX^Y1Y;+ zL_eH|iAkF}*_p+{Pv&?TX5iUetuS)oPljdLe5LSZZ$esH?XM&1$XSDv%;VX2r5P`N zW77Y3`l77uPNG#GCu5R;%%ILuqYS9!V@+?>cli1GQo5b}wf4MFIZFO3nVMD^Oe)m` zRS#+jF05H(-5)poS#bOzbD`x;$Q1;$&Ce6mY%J<*Nrwi`lIcCV1iuUvu~fEoIj8ab zMQ#k3=h5A-E0ucp2Oa2z`tdwTvmB-z4wCl3ep0pDi z-m!?L5$2(5LyfTYs60x@8ozH%L~D^+mrwgyI||Aoi@5tr|1o-q!4;dRoA?&DU#M1b z$Om8Zz^?8JR<2OudOUlB%nleIUOP3fD+k&NaDqLOYNUz!NJ&q3;gv@IUiB#^(AKEL zd9$MND&sc&r^32^9ltw_xoESO^|7v*T)xV@tCv8bto>CLR4(L*w{=J2v73O-9TM^1 ztwcvmYvTNU#&L@v*=%N3U?z=3@Q)vmbLnQQ$RbsvV^`t4D5lqfSPLsiFYY0b{DOjv z=A{-aR>ytCv@4F%-+&{|fOV^6?dj=R3PPieKVlfm+?0cSlhT!*uuATIM@L7jupa9X zHdfZL<>hd~_n`#*Eepp6SXjg)BtfAE{O&GZKM3D{CPBzX?9VNsJ8G(Rfp5#!>Iip2 za8|WsIh8YDet{#XYimc``L-BlqFOEf^Qmq;CRni>k}^Y#j)t62=Pq_#6o(PwCBtOI-!$8}S(@e(#oSM8}?`z7Lx-)=xH`2qG(@6!?SuNZKQEAKtlY*)Y_8 zgANDOgX9uL?0t6^w@u_=t4~6*)+4BM;eRO~q{c{`KX88+wp0QprW9XzOr3e2^-Z1*P6FD? zSCQ^Qs?;(g>PL?2P3f62(3<6t<#~@3LRFN47K%{2yGusItAJ3@D;QyKeCP~`hT#SW zCi$)=j#m>~sJ~(_FLNka(;KbWDU>Kxd5M(5xii@ zR-{~rIUpHlRHSUtI`D0IK>^#Nd89IQt-xN#$R&fm-lMsc-wvsI7}nnh=(owG5+~^_ zmHzJa*ZoGQ@EuPlTYZ2NxC!S!24D7YG_O(+*( zsQHd#yAbhcSnP~2tIAfxmJmw2_!-}NwIqYIfdY{;0N{JSAyW7`p- zV%s}RF*l{YTcATZKP9{0v@)l}zjgV$1eEkZKL^6{2?tKop$FLelR3W{Bjw0V6>iCD zS+&0O7Kq0WUy7l~nm`&GUTh5*{UvvPfVhQ*DTvyG%|ey^qQQDC*30zXxAoDEg#P#U z!0zoh+p5{vojaeUlDFfS90OQlDWaJrhMA43;ne>AM6wy* zJ9QKBs5;wI|4(Tyd5y~zVN>p@+j|*a4cnfbb2e8>Jz@(=Ws{s(J+qO&8fCOxErY*G zw9`mMFk6X59C!Xap%(|w+WP$cM{uN3Hi?L;$Tg641j=fu_g}aAK+{aILA+#P9=1;J z?g6VfXLTYr;_8FX>iz^8tccjWQrq_q&q>!Zk93L;gPT|Zl^qIqMQ2xZR+fj8uYP68 z+p1em2JZIT8S?Zf)r;98>eP37;@rhNC4lE|2poHh>ixMT`nCMfyrAaN2a3v@T1OXy zuiSOk8h@@dPPtk(;o#Y;sKtTX(e}cuy`<2)suX{KK^^&1X+=T$(!Mm5t7YJ2PRqXK z0BmR3=aD2zbsI>nQz>so-ZDlEpI*b~AW@{ISO$M?pPQ?&BsG$J+B88u_=Gu?{cS}M<4_mh zamKb*rEAm#baGEFMswo7^NKlMn6J;S`xKIPxIY+Uz)9;_19c0__vXIh*-(O%Rh8;u z8HfrU34m{5xBvJbVVDa9g0e?J)s9Wp?b}7DiYF(ZwQ87^Crlx(aLt+HcK{V_nKV0#yD(D z%wAyb>jvffEC}YRUGd~Lub#iq17!H;q&m*W>y5jjuPT}z7gM~CY`|BfNR18-fcn4! zRe~l6x@gbJcx>#wSUXApPN=D210q*($toFgkWG}tZu52(fLZMr%YhMy3IzZ2@ul`f zFD1=$I~}x{vHypp8Uh`Nb`hq6l9HUFBKRM`8dlud8>VlN=ZRE%3DbqzwM#@axXc6?lGtO$TI#M5UwvhAtQ} zfU5_ZUHkHy`T6H6wLk##4W=BT_ zKoh0a!H6yC2CQ~3IIdTHwXP6_Rq*iefUO-hR-zj?Bj08hZf_f39xZ)!ap7P#9^6$@ z0W5Q}+T0Rz3kxcMO<-e-TU=bkcT`eP@SU^F0iK;~8kJ=Y|3N@B6_b!422c%XRsaSo zP9@AIzMbvcw=LGyq8#rrMIKWvkzQ#kDheAIkbulL3c8_`#uj!h5fKqr5!re09u5x= zAI8D^L`SzmC)Gg_U4Dmy*2slyINGAn*{(sRteM=OA|*BZ!$y6f&dmb#H{8c}uDgJC z9@EgkC9k0Hj3dY|%tS@n-tF?ev6(Av(!77EVdbwKjazBCmN|cXop;GS?kN6=(fV^h z?@*8Y=ugVPhw-W56z(zT1z01IF-=xj4*E)fvK!#Bo%Z^JKyyjATK&1Fgo1(sTw>`n z(EP$esIf|m1KB{uSC!|K(PHJRuPUHvMM~7Z{1!;EL1w_qZ`m&Pdj%Ojwi`Xqkt;J7 zz1tmHtxxu%e)zZ?Eq;&{VALHUMfE`WCPYkrj zj$0Qnzw8Vp?bz|X%b;o29sx!tIZ8ATl4R4?0CT4rpOzLOox1_tcAsKO_MuRKK_Tbj zN(2FT@R}<4AxBeT)o4@$T2J90J7#NHSH7x%kNIG}8m?M>=wQw|cRIVUK3_6EI$-O#^=%2P>`Shr@A^8+#&1h>%fC&8(R*# zZJv7)$gl0f%xD!-dokySzK`shs(`L;o*p2tK1Amn^97cjwixsy>$af z@1~3)$7-5%@Vn5^M(5`xl$GN`NEf5ErY0w4m6fNZRJfgwx^x+SB_(~ev@DX*;@o1x zdA6kgN=}wEHqI#w1+gHnl7>JsCi8n|;ZB^u64Jhu2D{;8&Jx!X0S6-%oM$Gi51~t# z3ZSzz@0;&W=9i$wfR6qFxY|B+>SW%Ov##HoRvGeId)YK5DJk|UNwjCC{_gOt#AF|; zJ3m}x7p88Pyc&z0S-hyI7enooZIunzjg^bR9$TtOx|xyL{1cRLpIP=gn)b{>l!E<$ zZhI}+k|kqyW6_bYVV}!ci}!*$G%Dd3hpoQfy=GIZAnan1V-3d1YGqDJg?C8HW3QmO zIRyl(WR97Fn3OoE_ReB;p_bzmy2BN7@?jG|)vPq^n;p&PmfWtHTvrr&Ut>Rv#oBA9 zBqtwCjDXwk?YhZ1xXSxbfm^@f1~LkYt341g?a*4o-I(BNj=HC$cgRCf@}o-VPmZ z%yeWl13sdMs}JrIN;38{-q**e_9{EqX#nZ2nl>7c#)zzSbI!~|{MHQu*%Mb8u7@(O z9kG^mi*L-f)HiA&B*}1a!fZ59Q6A9?RF0UYg|sU7=>!`@4oe$28j&&mQ?sX`mNOKA z;J}Yld}6o$1nyH1)9aknn3`Pii^+p^j4>47|s zwY4?y)5rXLL`U@&UiVjg9vz;$=6QTX=RD4br84g?Jr{nbm3y4AA=+D-J4!60bas;; zcRxMe`o%FT9D5Hj!U$k$R=bRPf;8c6oL;2;Df;oD2LpnlE;8? zAS6xL?vspr>pl&+Up7Oj{dn26pT{1!jz780VKFkZI$Af0jfh=dSILcTo)Lm~e)ygM z6y)0KIAxPIDh{y?9Z5CIa!YJH0yp8+IXO=3Ws9A*A;-G{G)s_M?DAbG`^Qbj3EE$! zO^0qh3tT$~r}MC2$Y#b>j#8 zuEJp5Mj=a1+RfON&LYAa2dIv@*2h>UL5I z$%y0l(2W<%fmOEN-AzZO<3rs;Xo<&o9GwQR`D!2I(%wTX?4lsa(joLNkH$A~>dKs2VYt4ef&P8HsSCsDbPGlLlw7=Pj z(P{+F2qEOj5}^g|*M+cO=t^U~I<_>9H%aG;jXrqjNK`kxCdz=yRserw#DsS-EwLC>OgnD|U zE;7^6zPZFp@eGgs(Dl794;x#Ao!f>^25V9+_8P& z3nDCnRFwr39sm8T8X7bF=D&@m=(BKqU9#q^&FHm;9_0dW@DCR};)&?W>xyH-F2cJf z{%>Dja`dbU`~OWdaOX>A)dXD|mV1)e(^pGp7F!WR$u|NBDjMkT!x?WndyJ2$N>91o zKxM#m3?o3Kj@=u94Hb-|MVs@f2#>*+dH-Q-{ZXT|%H<)BvBbC&xErB0zCaI0^V7gA`@96=%DqoCHLpcCnS6!Uf4-Hz zliQ{yE1_J`sjWK666r`QG_c(_RhFsmht4ZZ9n0@W!Z^Si%<3>;-Nm6fghUZb5GHQv zMMRx?JzaVE1q5WyKs_Em6Q*M{U2R%MAry+1mYYve3(GwxRKOZ4^_Hc5$ty0t_zHb` zHev!NM_^c((ZlTp-!Z6CH9hNji?)q^Yi)P)o%@50*&685UsyMtKuQ%*Q(Zu|^bP2I z#IJZe*)($PqXQw`)`L{WUn=QrZ`z{(rDMwL{0GR>3CEK zKf-lIR$F>?A$s&@dd|4A+1fF zZx%1@8>O>ME21FsFT(`>Fx51UQp{xv0c$H;JMxdS6 z#iY>nG*=FXORe#@j$la%y~Ia&UOCbTS=mzTJ!0)^S}=8<-?s#AV)E zS@>ttwY8!UWi*yl{P_q3O0c0Jk$gqOg5kt~VA;n-c!7;2HCoE%{^~VH<$c>lmc3)} zi<=tJmnMuFlHlZ%dDb;@zh}ZNw0<*)sf=~u!rTwOPg};j2MxIH|ex>)1q5j*uHB{=y(*d*q%dkIDl^2V)}aZ zn4+aS=Op&txg9Pqb{~H$?#G1lwt`tr?c5!6uYJrrY@=DnDMR5a(+~Yi)*lNU1!;AX zQ9FlXV>y1BV?adhWVT&|dpjBk-#@>zvXP18V;qST9lEFZ-r$ukR4@u~F};<_@^8eX ze>L_070|kqv2LX=mkMBB1S3_SF1$^Ddx0DKV$rQD7Y)yFyPMPbQhi6o9M`3(2fuzdBkOgExD+h4R(^|x z(3Oz?f=amTzuT#kMUfEbjXmmmJs)SgQVBn_s1~bUe*nj+3bUbPOT_qOGIZgC%6?A| z4P?6HR>K5jJa~HY`4BRIrsoWfM%lhOCEuSy{3*ALxP!Op47t(#1UG)rT6!ecIF6Jg z7q(e0n!-V>G@9*|Nb;JTU`rX4yx_~`$T(2vJ6NLib_p{}<-X~qT3$QmzSJn*sN<>S%@4c{bB>KrmD##g>~&Vg=II;%0`=5y zp<|*D(Q?oA*M@36mTc}9X2YyCKkl&KVjpghQPx(~dscoz8=}DMvUeBpx8T0Hj;B_A+N&8MpJ6rqdl_gMu;4d$c3wS~yev3Ur4M}|j0~ym zW+#n5>*|&c-kX^#h*>BYY{A>`x%0R@$9ppMS_AhWPW~Fi=>!D_ug7Uv+xkDjxU04T z^x(7VdAZsB1~^JNPydqK6-@|?#x9OmD>!#3)JwnjS&jZQp@7|TbeIpXa}3Q76`1Cf zwL>yVF;a6Xhvj`Y?LF-}3GF9=g)tvJVf3m?_L;OGDhBkFm7FT)qa;h-)RhxU-WL0~Z>g z|AOnx*H#{MR&RDHLTak-9>c9VuTr)!CF{T{?}%8nm`cGgB!P?CAwODBy>xU%YhdA? z8xqJwC)pdRC2fe*Sh8Lfue?dzs_ngxde@P5+G`wM%1ERc+au)|8_v*mSVUR8SyFUD z`R3(+8gasM2hJ-K8Y!4YDG+m2Vj5>&Z;_fS&O5FF)$?8npaUU;TQ@;eJ@T$X@QOi! z^$=tTEq|o!Txs~oL(Ee3K1KV==w~)U$*>-5k=IvIE=r7{=`tQ3@D9o0vcl*=M+f z=Z-}!?#pic|V z^)~MB_J7fbZ5+)azF01@5vGIHT-fTWf$JF7BsU|LA<_52wp=qRS)i_$*E{u{cB123?ghA;KVzwU#qEn7{r42EcH4&@ zEjEJ`2aUsb(ONgn!x&e$k#c5&xueLrP78W6MwaJTne^h~4pVA>WL+-Inq${g_(?uW z)=CPwHNsxB9_Fhnwbt0#rC{F_pjq1#L16f7%)S)n8N2>`kj>_Ia6Ig?ziD=*aOaYE z(WukpG*VfV;ubbDdrV*N+g$=_l)(yh#5cumDY?T;HFNtZh9ei0{ws2b$>)GDTh+)g z$*&0G*Xv&|`dmi^kY(S)w3ubR>ICweP*U+^yM8K<uB(I{A2sa>FUAKmRr~#0B_M1 z61XlbFCRs-Qpl{6)0+O9bUH@)pS=dRvg>9CJ|e~Z!h)HN4Z)r{JdLp2bCXOmm1i!u z{HSynC{5Y1yMyGL*%S1AhVdTnLbfqxR(jtG&g$v>vLj(w=6$0P#~WIq8+!xIbSx@z zsI+>T8tr<8KJ{7DfD-w&_p1zhRi?e~%V|%@$N2XzW{lGY&hx}upaFy1aZ5aP$4b(V zE7e6ScXk3Dr~w&PUrhTCOZkSF5d_M!d!V&Irq;O3r+dFRJv^12DvZ|aZj=y&z?2&k za<7IdUKaq5p|%Zps718Jt2XYJ<&_iMJbLLDyhOCICdS2vQ!z9_$`F@_n(`x);p?rp zKu^F?L7eA7EZ<7HonbX&ghn(c6hiLi}PveXdXc$NkijHdZNT7^SF z46B%>7FR!^UJl2>U;9K-h`ryA6$dFO^iWqL6uoQLrHUSMew=yE4e4n(**&IuEUIhv z=s2N&TRv)TQdE%1&fob$(cDgO%g47T3wqq!j)zmH5p%Mqr9`o~lz#sm(@H^np*EG{ z5)CC+XfL)PsP6EWwxm+oq*MFu9#&aIQn0;c*042HKpsKZ=|93|s}OYeYj&U-fk#V= zJ>BlE5bELxAA$c34h6Q>rlqhs@GIMjU|6}Hz%l&W&}}w8RX_c-ZE;wuxTUPo4|-Id zRIQVy`nH0RA&Q9UzX)rk*Go05if$ufRlH>F3?yOR{dCWTE38y?t*=S7cRDswa1YSg zpFnS!ucr)LgR^Kf{xrrl-V>-L(O?syAO{yj7!${?)EP(;MZc%hD>Mx~3=p7*+09zy>Wi|j)s zsa~v6QAMbD)ab&&OmW4aY|#Z^VhE#&fW14*bEysngUR z+f~A>6xnQ+7vQua%KH%h!b=^_7@Tl1I@0>yvPu=V_1PGRi%UOUJ#V}=F<$+B{93)u zZ|G$$EYCHx{;w2VBW-(a5>t)3*)tIOol@D==; ze|={dNA8_}UqKUZYB(bUDwsJKKmUC1uaT;s86oSiSzT^_jmqyTQ7?PQ2)&K5S?$e z#^M4wa?;#<;_=KC0^0vRmW+He8+-?m*s0qD;|c0nmj{N!4Xi%)^s=@)wi3%ppQB1E zoCXxqY#2^el@M|d26sAm?_7#&QhV?btFL`p&pp)lGwYsyLd4b{K4RR7GLoy)+?GsqfI!lY66 z-G=chRz>gEy}N8it`j~GthDTXm37M!bSc^7^>h&aiaqpRWZ|bAacux^VvO?mEmqn~ zHYZNiIo8t|u`9Eh&UJ>8evx3?>;7WpM>l8IfiUZ|M*!5q&p%(mae}Ba%}}InI3Bh) zmzHH4Md5~o6NvtL-sWV6iE(b*Xk5wQcpvS~o38*Y3$ zBCtng$mffF{c4|`upg}BdGkgNErHj)2AVi#y7_!6r}w&n19VJcTH4TO|19shESu%* zsMIkKH*sZ9+JTTgSFPWqeN#{LY872jcC|PVZAnT@oG}B>KoSNNhAWUBz~=;tj+dJC zbB+2}*6!Ma;E(6dN&nE$Vf7#Yrm4KI0_^nCmE^Dn&`<6?#l=0utx>nS`nL5bR5{ht zh#;leP#YNSwCSG0wv_fOCT5a8Y77g)->^4t07GB6)Yc_}JN5f(0}=OoOr zp(u!d^p!-vfe)@zXNgJYUu0^Mm;K7Aoz<%m_9FOHcHKUPiMVrPo~yz>zr>t zN{gur_>JGOgs4^gbL!qnKAmt}OnLe=<;j7LQBZ?dV0ZThKN9Oy%38mh!;x05;JuE_ zIb0fhHE3(0g%}WX&@&|?aL#Em@I}6&kM}#h4f;D4uK1cf=x^=-$7METnl!7-wg(M= zFtzQqXcsH)zwc7Kn46eUrR?y9Ee2C^&wD~@vMcwV`mwXM72WFMiuGDhM=iq~47VV{ z6dS&|9d6hWC7!W=@ksRVR%eItO{~lv$WPQB;^$Ht@*q<#zv=+! z?q@|^-DA}kQ5gE?p7b=ia}b$%&s>1c;qQCTcc2HghraH>fnt96Nl3vMD;}KZ1uV#F zBa*S>_Mw+AGp8-r#(jvLB$j$hW7raao@SWL2R>{bTASkb3Q1}D+wCw6pQ-8o@1YOaQt_nng8$NMT4Uq8j2AYt2}Ju8mX=P@GScEwh@SPaFxw*7 z@t+3-oDN8IZXzRTcrSmY6_sqo&fj{Xv&(9YgeP=VRvr^7Z}F|l8<=md57Ep`DNi2T zL2!UZJworrKdb<5^rP|$`U)4F*<$u@YJ!m#DRf$y+c(LU+ai#3I0d~HOPHP{iiW?7 zK7vAbE+0113RV}(uu?}-{^Ghu|2+vj{paLCvU9XN5Em|;cKiw6&0=RFgWPswv(;To zqvg!Dwa6@tRA{P3)OS%iGwHRJqN?}=*`-}AUaG;lZ9C4EyL=sQzjFhkiJ$Iw_|?jEy=m-& z=xH@-Lce~l_sh$pd@jfJ_4S_{d>jC|_70tcn2s(C2;KbwWA52rpLWFqCf+YJof5dY z%t4w&2qyhD0KSovkoZnWbBBSsas`OD``mhO_qq98zLY7P=Tz)P%fqEcDO97@+VKRr z;jzY`7ZC>sN3~4%rFr$0x)=k|Xw4ybP$`4KJQ1nP>!2jx4IH*_Kw9;E3yi`aID@WSsW;T;5TNwzSLRF zJAQYa1t%RX$%-Csm>7|oQ|m3r@bwKrlj3drFSgGA@s4fR&nf9r+duG{y{B^Hv$R~l zjIx{Q+waUEc6HGw*TZ)ev9dQ9Elmq{)DDFvp5_`m)E+=I(oOUv(QG6Wx>i1JXieNU zza_yunCl$~8+zX<8Ja}k{KAIdJ3klz>^s5^QZKl)oO=x4I#RW=SRu{cJ*z5r`>fa+ zcG@7>)iO-MJ1`67<&541)4zx)%o&RMy18a}BRHVl#&MW+hu1^55d6=D>6Mktx@T3C zO0S)z8pGXl=uRZs$%xMM_gd?9Czyh{Y22xZ7~cP18=0&%QiW;2E_uO?Z>YRAQ+Zwb zua5yMc*U~cq|86cB&^@8R4TW)_IIEjtJZBSlk+`_3_wvUZ`|c!^37|9oFqP4^i$u6 z>QNzh2#cT8w$Kmp_`>zL2heLbn!HMzc^t7h#-bLQy7C*dT1m~4RUj~PYxwz;_7R)Y ze6t2W<%g{rqFtSbwEGgKF@}xZ-RlU&>3_;vD{uq8V~*N}81#c`hg+z%s`K^t5v-Qx z%be*I5ZM3tS^muCy5@|q&@3``{*1~o0aMW5m}q0>mA`*yPyJimw3Kf^=C`ufA6?-` zhgx1Os@*6sH)I1TT5Tk1&PMEFkY-}?u7sDGHB)6>dSC!`ffkBLfKSW(jhb1n?f3OR zC0@1a+;v91Uq~QFm+!zGpy%*+X?9K8-dbK=eBx3XLdAqd<#0Vcr;dQ?xcn~3H(w@t zV+u=UOF!i}{Iq#DTlukk#$(j*ixeLHtr>zwv9kSCmi@D3Y^M6H{aIe^N(%$dyenbZ zQ$L;i{R*NS*6n3IJ#jDu?Slg4=m%n)!j#aA7y+ZWF;yZ-w6Q>9SbF{7P_>F&&=o^E zYkx=Z;+ixQm^@Dav*H=R$oF_{uT3{5;|j7HuTKZ)si>*- zK_9p2UkBVX0kY%{DC&S@Ne?6-XbUp5+-&2%$dO4K23Otuo^^NyjTNc`|s|5Eke3G0th^JiR+R*Z}*l`9b0nC%Ok&?~c;!BgMH%`F_|F|K8jHez78&8b2rK$r>>yPW5gw%P;q+Err|6s#JqNe)FqauG zGO^2z8CVk2&}B2 z|8Kn_h`~y|w4r6}GXHB|){vnBJd)Iv&8^tE@)blBNg{ngpB%)f=UElXx9a=U_eXH! zt8@II#d6;{=zjmUr>J1y8o#)^vN}wzwxHKxyGl;&TDiq|?M)UvyhEQa+E~)}w`lf) zLucw?z4i+J&7Xbuj@=rYkluDme~3sZbw#gx>w%r=m$)rCvRW42ar}B(5#JY!*Rip1 zZ1oHK59m`(GozFCFX6RkKvUG!b{MCESKh~I9$vH3QA;+m->t(G=wL;F4wg5x6Wc>r za{mL!YWa52@{tSAib5sVsB_cu<0S8=iaFA&3QUhqDKBS^3g7w zHXl)|F9S1}{;6xdQaPsiGsMNhdoeZqMo`yv*+`po4$tbYj^gPCWo40o_J0J z5~kp*KVe4}bHK-9CM@~2f+211@`>I{W+WDWCk4N>U@OcMS>(=#RQx^DBJUwrDNBu4 z)zMmH$4r2xXPG`r)tP{9)!&Dmm0G*qk=CoHRyqw1LnsE~QiHz%+u>%s6gTJkjMXce z%z&rx+Y6-d8!Ncp`x<`(uZ51Mhl+$Z{7=JwTCKK6i!ZP6D;(h{4raY|qfsP3N?=!I zh{X$mnyb8%d|=n=7K0EBLd z=$u<8pejp&bCk~alQ$sER=c(Na^7P1!flvy=ab4$%pcd+F5%oqb=HwK0D!9sT!Jrv zeyU~0M)Z^I>nKv!sWY&YisVk%0=6cQBB(f^?W_#vQMU*G*G>g^ThDwqAo>OM*B~Ik z{bile>@2Qb?r-t9dk+V<0X$LI42{MB>I`Dd$LHt!LEh|tREHp|@=)J7#bI3hb4M@* zfEJC&iQ>I^CKMJb7yl>qyq~6YGu8d*4@d_07itI9nV9p+(QGm=yQ5o^6ZzQruw$mXD;xJJi@P&?> zICIu8$nHxqw1N3x7j$3}@emK1{=V1uWw`f}`PNTovdgf@`({D$F5}j5Wua~pvlfA0 zQLPg!DV^%}$w>{fEE#h6H6R z^P4GpP&?mALvEV#{oMza}5L)MOp;1!#v(fMX#SHT>6+%(|FpU#_z3{(}JLX*F5L#(3%| zH;?tU)aJu~3a78eS31ANbm+!Z_G$$3t{oIwVL zdR~&>3F!ESF+{?UxnlM*uqwR`X>LNR4&Je=XqFD?55fs`-qhveMxSH+9)b>W7`RNo ztqR}c!b38Y(Vg;h=)l`>FC6Nj>o!`{*4(x~qd|UNmKN+V-Lsb~`q`|PZWw^JZFC^I zGeGv7SI=RgwtJJ@zsFD1eM|Qkb|hxFw+9j-QNM*o_p{n{Hb<2B#Xw7i?U8XU!ith| zpJ*6w?l^w%p!mE?YEpCXo?Nu%%wUxNf)if{s=v(zmOc*_1CHY%lAmVUcI5i}CL>}5 z5-taJ_LRAinH<&I-kkPx20R&=;Uo7jDewg){a9PhFJZxdQ6RHFO1BUutEVdwA3k$R zZYwA6W3jP%6)yexGi6pk%XPh_*Su?;d@sbae_KD55# zFomH%c%#7K356#kE8ZJ*F?6;xDqn5lzNL3FHjt;IyH%nr~u0$pDjfX68MjBlh6 z66r-Yk;FSWIX$yUzd?&@?Z5(50f^Xuz_&^K2e7kecJ7`lE$7C#-@o4h?3hyR%Izyb zlVf8QkN$68(_LV~eV|Yl z7RKvjb{8KJ41OqbX*XrW{|`}b8CKQzcHt_ZG}0;Eogxj=As|S1cXuP*UD6#Y-Q8W% zos!ZhA+M0w5rAez z?#D^;C2C4x*C*Q8bh!hn?`qaE5(ay}(%CUH6pJO&zfZsO_9K5IpVb|Ju?_qE{8K)< z_@u0G4kgyUqkfN^kLtNl1T*I*g$=Cny84gj1qL9k+*EId> z4I2G#wt4GjtmoYqY$TbSHr-ynu zC_?`cLgL$s>t0op&ap966y0Eg-o@!%SqWavQfj%?b+e!r#kz^Ofv;sB>ikHJ3PXzZ zHP}ax^m1*_InP*rh%+N(VUw;($#iaiJ8vImvK!MK|Guu+QdzO`M1}NWH+Z)%ltwz< z@c*_~#GJvfQ?)_Awq^S9JqR`q6=m2NsB6i{hTSlca1objzO0ZCOXQ=oc@{m^jBvcp z3|7N#Ul`5)@D^H=wRs*9LC!GhPPIEe{;|RMvv|pR2;?QoJ{N10ZZ)kAbO^`|ir@MN~S)DH1^;W2HJ60It zk^I4Li*>4z82$I`>}<@Q;XjZ&UcP|H`iHN?eWFDco_L7z8K^xw)`r4H^^^& z1I-T&yBTfV{4W3l#ERLCV?JQpaE)82VKK%f_fynYR>HW`ZaOZ-RI++a3_e>6Qifiq zIi7KU#e?`VX|Or#cMYLdNoTHKvC*k%`uZ+?$6MeMQ<}=+SF`^h>f=UxloXQwt!#~H zB2&A@{mXMzzky%nT@Gd|j%5QRy==DupKN#XshXI^!qN1~WGt!qznhDGl}P+I$S%qF zDuA*;3XkBG$Y?~j$1OJ3?YWqe(H80E3LC=~&YOZVHEbSgp$qZpOT&?N9&^+;=iV_* z43M4HPGEuk`+j}!v?cA&!EPVy4dj#6fkJS>IGaezL=J83DbcRw3YE&Q?zC4{6S$SD z>VX>{#7CwrJ&lxc9etVZWs>^X*Z5yukL{Ip)<`ia+gXd%xX_j`a>%3;^mk)uv8G=6z>eG459}!=A z-{Sii*RQyTsmAs0To{O&{4_~s)o#sgCaG|Ob<@8~L@DATK1u@^$Ch<zK|eDMuKitAN{~*dlkVu3KEUPkODFc)$j@hqBN$4x( z(eyppf~Q_bg}f*J_De72my~D2(HA1T%sO&SE;ZdP6ONfIFoG zfn5HCAkV6%4--C^;}S7jsN>~%H6azF;L+0lu{sl1 zCs9aZs;e(^S(^2ZHbfB%4HJt28YY0=w3>o6Y^J2~zh}R0FCU5$ZJGdu-B?zetj=|o zLT8R=iO*x<^R_-39E#&QgMfAOJ2hh)3Us<%)LxpYH4nCWANqt@8@Ybp`BeKwo@$_KI_U5%th+HAtg?R<3lfcrD_i zb5<+&7)KLs+NG@RQ}|wK4iL*LjdCkMPfp};t-s&h|5`g|FD zqXjF~5}&cl=P=?IS@mNWDC~ebXsv(UjlOg?=r!7tWpTj5&0DNA5p4pR8_K3z<>3_Xo1@9nWF8ZWt?$7X>&z$v^}x7hQAm!gJzC9fgG)V@S!8_yaJN$;Q2%w z%%2VR==}ExdPSf335uKUJQY3iOGuLXqy*VnQkmAL3ZA4}F!0Z^BV9Yau|z>Yzjf7( z64#YOvvhB7En=5%!#LT*j)`H98J?WxQ?o_yx2$Zx_O=`lu--9jY`}%P>M%w?bvfkM z^|$sB=W{gjCoJ64z!~IsswN=`Lnw!=4a)GJ?$p9Dv9cWS3&)Ism)FmZ2;T-_Ca<%) z{ruQ=bgY*{*oQBPAe8D0-}c%zX^$L3>BXn0VXJ9X=9fcndok`b=n)RF3#5omqZ6Z5 zQ%6AW76=X|De!%h>XmYKc8Gx2v*zjo(pMYA#!A?gLZ_pUv z_ZmMwz|;c_RPMaRIg^M5R}#?4!RMGMyw)C5Zb{KrNJ}$@OEgnINJ2~u78NzXRXh+i zkxEHTO%j9|6S4U+5p`Xe|4Gk&wsJ^P!VZ+qV3}roe74AHzg-x#_NcG8FX0iB2a&S4|-8J(8an{$dW#+7NKJ(4zRV~|4ASBMlKLh|XG^zXUi zuwP^c@|SOje7#_QNti zPCJ55$2*W1^z_{j{1`EQ(+aV=8v=oTrH|asZxqo;^5-VA5hT(Lzc_i@1g59BWe%f2 zPvUbHzX}Ja@Ut`_S1lym7{^X4yf?6~12R%U0G zzwnPScz*w$dVhca7L8mR&n|q;zT-+ck@{VKV zz&At^YakX|FsWW^aqy2tN*m*UOILc>*Svj5oXy+M2KHUtTdBV|s$y9EN0|^{4q}A^ zhRj(gm47SPFB@4N02p*cHQiVyDSxKj zUoU8{SAsU1s0!_-g4y3+InB|4V0dkwlgP!r49ied>K+%kF*P-1y^<+ne74pC=Adz4 zgPl14LmkX2c+cDaBD^`zIqPg`Ne6dgfnb3c|MlrH5$`rtn$P6`9&|GD*6-go3+5OY z-C)24K!5ica@z$`j&5>qu%iK$CN4oK^d-Q+fU_-=zZ*Y7q%QHH-EzpUTijl3B!Er{ zm=#p^Y}Z-s{*&l5-Xq}o8>VnNeA?nI)b2mWmbSkkz-<$uW52DXoTo>vtlU-qq1;BaTRK@H4l=>qu3A%lMmmGB#rRf$YZ4 zuT6C~xhlAP%l}v!#fpCq->l%AoxgW{LGQIv&aGE@9UJ-UeK^cQQX*UBgqUm%D+PjD zdb9sKtY;HczK;H&zVCBtdl@N4yqLTHy3@5}3I?uh7<4iz$6{j%1 z+uw}8$oX@A&QaeN>-2SB-sY-4IE;Y=!(P^vu&3@OpgWyS`d3PExRaqnF&ugil~aoa zHOmoNX4A4>&FAvwio(;JV2w;!#oN8)Lvi0D-xt5w3RA;9t7|g+!Q|}hNbu}hjsqvU zf9D8)F}l{Ew+lM7jrY!IJ==accXe7qBowcC^eC1&+~f>HME+i$<>hip`^= zC{+t@^q=5f9@ik^pXCH5ThR_6auZB|tjGc$W@VbEgAt8+v~y{@4{$QVGkkw&ka_>r ztrA`QEXxbE&bXwxvH{Fpy^h!CGDB&#Rz5+AO+BpcnZCS5YjvEZO-6q7T6nq{s$oaf#Y*%y~>O@3Q+FiN|scRvsw(%#EOl@BEo zsc!l!V(6cy?bc6u8U1=jpCeK}RX2>_6`YD#_{Aw592Z6HC;&E{kQFVNz?}qR7Y}(0 zJ#NAF_V)7Ze>L`E_5$6Vded?skk<@^ejvvov$n^B?i)KN##ir0{G9C2UO*dbK+eAM z7`W=81=IEQ^(b04{#!tB7f&^X4*p(1tq!@jd;9w!7~Gp_-#QC3T03rC)iDS->>I{+ z3cVxHS~w}GF!kLe0CYkVxDeU!I%Woud8olc356#67aQeNqoAbZB`g2{KvVHL&&xL4 zCYmKR)7f^V-#S8i3%jdbD4dGcEkfLgRvu3B!&B7Kqf{yIBwLm>bKf`BdK{1t5~FsT z)dAT1nd$KL^);|>wL&Tuj{#3$Xsd=zT}f$sz{1MTuB5$v?HxNu=0tK@ns;CEbhd=%`4lr|Q?;MlI4;Q*pk5G7?iKmY%Jd(PL~yi{@h z;eNyS_r~Jw+4qOaMjC{`sMF=7iuqM7_KgHs=K{^={1oFhbmff=bsiIKYYU6Kf`Z=b z^MIv{2{U8EUY(7v9kINIz|mpuO@8p`g#7&d5mPf&w=p$7Uc}4m{)7+_s)}AcW-Eb9CrSwXsEA;T3o!myyBitKG{~#u6wU&EuOC@owfO$L$2yN zZRFA6)N|Ezbp`3PXT7iB%|g6`X!r#>hWr|TR0wKnd<>hY9D0sIpsfAoD6*ra_*8yy zYbRe_bDJUk@%exzQ1XPkP_q?Q^#iTkP^nYPQ0ODAJo8#(Rq(IcTEA7otF@o^go|FY z9kUA*$%fFtUg8!MT*X9pIuCmXg2OW73$B{{dSp`z+Utjyo7Lv^`N-zxe{o#Dg6Fn&8Ew)&kX zX}Hlby1Tvx%x=iDDlejk#0r+tS=qTb<)?xwhrD(5+X? zy91-D&)i@ZX*hk(xTI1)Z||G|4u>K?D95r4@kc(6Vm{secEqXrI5sO`UGn zt;mBWc-IdYpMIOmpPsoB5_?wn@g>7%%-Y!7Ix~-kMN!~U(_W4FAG#_~BGqT3i!I}@ zFBK4X)^3E}^iY&5?iSYe93lSBI%j9`x8-uK>iOtrsaXXPQ*0#-uZRd7zQY)DUf?-@ z)#0z|J7SutK5Joz__f0GrY`3%mty9jm9^k?o!BL5_p>u0?fs5051v@iy1zs3w+AON zRIMM`<)+Fj2u&>`{R-Mirs**gXXbIyu@1iWnyDQMzpoel597|B_Jnz+tNa#b20No% z5RiX)oNTJ$;(A4opovC`=8IIg*;n3zAN-N4$|WO^>~8#@||!GYgN~KfpWtF8w1w{CZcEUNMz6lhJqGLcw6CAr`3Ndl^-2R@jdH06I}OhEDAa% zEWzcFk(S12S;2oLtTrqfp_y1{WaA92l zThjp0A>i~9H0kef)LCCR${3?(qEYnIud%#5I);Q^uat-%Tx7um%bZQ>uZ!ZDrHu4# zOoXOi1ErpA_ogt1>T1UmdzFFQeX^KQMuwpGAez%yf{nwJ+5FYG0Ie76_S83m)~$W} z{?;OM7N9J_0>PLv^64h$HDBrFP=ZKtKSHvtb0BW)6QwXq^`{&DkA)i9`J?P<3P7ee*PNl~Xt2 z%NOPP+w3~CpTEBD#6p)^5U+!3x|2LRD7Ce<|3J2_`LG~L=lnK#1WS+O=8Ile)KEj^ zvk=f>!lUYv%n!h{7+@xR{LVq2{mYA{uBVtjH2!E%rWVKRynk`q^_&eJPc=iW(M0cK z!K-P$N2Dbf&`hI@<>|d%?G4#TM|xfK;3qUYE9ff-rCHTNuZ;_zZj;}FK8E4YFr8mF z^kJ6^xuRY4_v+YqSLPC8tH2fdP-2k&izd5F=!Y0cl^=N#9f*h4nThf#8@7e+tnP16LL;m))Xa?pyXE;JAolPpDRtC_4TVCt zB|`FX8-PPZg5Gtk39Wk3plA*QA}sgKAaKzA-}BR}TIFt+JvbiDl%b7tQE7UHJv`&B z!Ci-tSShsjkk87o7p)NJvGVi%S#{|KA?*LyLBt%#mN`4sGKLc3WHR&q{V(nDv?|!y=d> z+M7mCE^&~!r+!rV=cd2@;$Gv|&ed0Cgfl4h?VM|-YulZhq9pb=JjgCt5_-vMhLAbA{?g~A z?(r78xodsnQF{owN!(E=-^9@zQu&~8b;P2!7l0DA)2axVM6C;jRpTU#2@YuvD=P(Gm)5Bsl=V^uQ=lqwQaU zp~{lGKjFT)zp!dg$xEFM+7bhE{UPbl=`B!RVnB5Dc~n@$qCpEya4v@i3{F^%FFTzl zdBc7RJw(4k#;pcvcj)jJutWcW8+-ysU1$23AF7hRFfuky=XEYww9iRUZcS7Y#Syi& zJ=L%m7KbkX?8r_3;hs9)tI0@SpA)J)my0@hVAd-1yLi$xiW%J%R|J9Qu?ycU1`VC zu~$1^2LGQ*6NP5MK-se88;x9U9)!Kuy>=_Fy8Ubav_N>gD@REo=cc{Mo$q@E9rZnN z>=#!R-LtUq`i{mS2^yhDpJf=86jkz=oO8KqCSwL&Olfj6R$B^-dK)g>HB_i>P0jNV z3tojXGkZ6eZoNX{lkKP+Dx=U$aOahx89%=HSk`#?De>W#ecI*CXY&`;{2c+o4bO}6 zc7;@qCynce)QB-;)t6uBgU_poV3=|1Z_oR53J(5sG2FQZu7|!0>^4r~NXO!B7tcDa z@P@)VGnmgli}HnpUeDU^#{Yv2Q*onfaHbVig1YSilabDCMJ5uN#REpWKClXHbL!mv zX?l9(7YzSz3dwIc&zgejW=HcI!ZCsu*J_Do#vqUleTSn{8eJ%n*^hp-Nn8sdx zrSCSK4|2@eWX@pe2$cr@w2!rgkdp@avuT|^{1nz3I8f9HUnnUcU-@#j+}FDPSKJhp zm1pL&UQ$MXfysM%pZd{teL6o2QIE#pV+FN~b@8SuA9XLJA*xv9C2wj?qo<8D&mX^p z^%j2;J)7HQxon5Wcigz^#`U0GV-1u+tc88=7iabJJp;$X!UR^T%-vm&TF5p@6of^| z|7_Q<84}$FTTy0&MSV(cR@`4LkuqxKj%s4IUDG}j8u0hA;j-o!@-9Yk=p{XEFRKe2 z5fUz|8~>D-fNEHbp1WD06YT?=D|XKecJTx~~M z=~dKW)ua_sJAatzmR>7FI#sJbMrOx$b@-hw3z2S$8#62z-bv!%Wus^xl6v?79^WnY z=TYm*yV==(0zkIiO{ymvN4Rk#p@R!r1J?Q(<%fH7JG--~V~P<38maFLO1(wZm?cxK z`@ssmD)!Fe9a1Vt@@aFteqpMwqjvcO=wZtw6!>>sphnpnRh7hegIqaAxR)`9u@j7u z6j(GL^O~ENqjOa zVPVoQh*&gvj&DN`M;dcI_X%E1f~E%Y4tJO9iw}_?P!CXRd-qlP(SAzZf6}mlzlb8H zj_8{~{FIPR@O`lp8XB^(m;yI@Eb0S@pN%0$mT^ABHe;fIsm%ov26yNa9?*9%5MMS( zf9qU1hA5B^xEfu?mxU|IhzImEI38a{49n48ZXIAs@lzCO1gu7m{ae|gx|gQl7sv+F z3DfD|&${G?F9;_pbec{{&Q`9OQe0I#lB@lV$`y&;3Q!jE%w82)VckoJf8$8MQxEcW zQ~;{qKF0m~sj|=YN*<9hf^ZiN@w?M z=eT8I8NF!S!Ik5Ongov46=yBqc?eg z1ld=tb(bN&*`iNX?UIq5HM<(66;Q@K5d#q8O&>ms z{@oo1?qRPc0dedk``YOYQL~dh`^3U_1kF8|qIw!m5+({Nm}gQUGr9>*26^lEFf4}_ zljH|aTWr!~rfV5vX=Qexjvbwi+1E1F)eM|sk<9K@_gW--lT{PrhPfP@klcy7NlCx7 zW3AfnVz%uN7JvhNCNm>=j+eo+9hF^55PIudfhc(r2rmRudCa~<{&hW*Te3I>#8aRA zZbq!!tzwX|utHG|85s>XVx^dth6>80Zr{BzxHO{1hMpr0vBKPn672H*bW8(^(X+=bPgUqp(V&h zHz`W;zfVPduIH$mvFr1a3Qj)Fz9%6)t?GRBVQYURs+n!ar0UpS-Dh%CSJ5azQr+x} zf&D>%XxZ?ojQB;$(IA#u+@{0_1SX7EULRMT4|~EcK<_Y{5dE|xj(ae+aHpP#$ZCj( zQHsq6(>^fD5SA=V7>L4q^R;{~t@BnLZlw|IPhX1qYkmeC*ii2hgX}#tiSqk$v{T|& zyT5S+IC(R9!h)2nIGn+d_WOj`n>bvA|3ykSZ(|-X%GDUVo+13;UmN4?%KLfC7cXDD zkP-i&VnCPoqf(IAN`=BycbHCMpACe)2ctJe9t>8SZPmDDh+70MI<`Pqkzofp?s1C} z5m+HtA`UK3%2TMU+ZFSDSMG&V)r1Bc(UE=m7D`cT6_0DXU&j+~bRE(F_07=r;|+v^ zC6#O9g8lo>&Q63JN!Z;CB7W7F=)zK|v{45E0C+3>TkiMOBwz{qb#Q}Lxd{gExB^59 zR!Re|Nt4EXC;Za$Ub#zmdG|z+n^jxAgwOxwxrcR)ZA1)Re@e~sRVcOye!e=fx4iPX zu_VNpMO`k7mD^2sUpEYoNgQwRjta|;=MZ8_PupJ`0jBQ%t~u)J!e6nzEkyeKnMpy6 zNRGZ2duNHVtegTBX_+0D#@hVaZ=z}gea+;N&bY@?Ui6uZp+xxKPW4T7j{+Y>mrgmt^4@YzWso%-^v(B#;j-Sjuo3S{kEiF9q7k z5nvWS3WQnL{=9630C!aR+I4?5ma^!FMO}97PQ^$T)nof9mB$XB*y-oP4w)d%1J9VvpK20Y= z^mPT@7FCgS5LMBV4Y!S8xp!1xxa9UaYX&tkpc)KrfmUE#R=x4dA<~~ux0{MOI&bCD zSWX{$SPtbj9~ePNim^$ufk+YN>_ieqTP4;AN7SmAj_4J|p3fb6|V?C3$jgGR1vRlZ-a zsqS!aW^PeaANT1r6wlaqg=~6n?p=5P#gz~#BRBqC(TE)~;fF1wIP|@~mx{itxc!D2 z?_XKA3uZ(aBu%%gOkT2bUl?e$j@A6@C`_`xNtq%M561oiK7Ag?c@I3)dk9s>rlD4l z&fji;rTrRVotuQgDedS-JMNN;VXK`J5mm%<_6bZA+%e?JWaaEE9kd5B|s(Vr*F=1=0BY8dE2nh0KT1W+_ zih{@Y4X%>#$4<>GzKl{cmV@&8osLR-tK|{TuJv9p2!Di3{$~qbac{}Ttr+@dUEJ!8 z9keMhn0cqP{MI44(iYtV%oLd1fe9$Ke~s8c*NJwlplKMG0%tQo z{^(G;7ZgkF%pMbApotjoj|R-66RNb!9bX$+c5FK$^DQ0av0@ zTV>Ng0y+;M$KJ*LEle;#F*e*>SU?w=)KB)p3PY2+HJk?O^A$DxD=&RXn;Zz!aCo`{ z1$YZ5wB~xB@dCr{T-7s}p}_+U-V{ z_`oQ@oqKBOwMGvhe6`-$lR>81^W-j+(XQpUlL_VRFVLMEtQp3!~V>bM^i z${`UF|K8hTz0$BIc+E$Vya7A)Ft6`?uPEnH^@p)bo@o$W;6f^QKfPqA=tP)c?=HhD zOED*jCl)Tn>eKlx-Yyq&Xj_Q^@5}^(8f2!I-I~#Zi-{n{Sh*FnB+Pq9S=PPABc~Q6 z82nDJUh6j)(_glhNklW!dnBmnJXA@`zBIUx@xVEHHD6|H$A5#9`selrEjkwKZJ2~a z{^t|@$`AU!8P|#tbXB>-oTRd6Z2h(44X*}lh|EMI74o-xU{g7SEBVRy0CGAEXctTV zhMcQIrb#nMFeZohQj*I{Yq9}72;Fco8A&_Fuxe7d=&zVcX^eGJqOi{s8V{z8(0uB0 zO6xc~W>)poK8c^Q6*s9y$l6VGd`0RXFgwF8PK$ub+d=kMcKV*Cj<254s;hh^|6ysQyN4`> zE`fKp&hLDToS?wF867+&26k_{#*r8;pU4VNrihk~Fw#$=9RuP%F5vAtT7iwV5%09` z7x6nOqS6i3ktai$K3sVfU`XNIvts#q|6}nwH?z_4%)SXk{S`$v_(P{rGntf3%l{G< znyTK)59O||!C%Hkf`-6B$U>=R9AVhe;E2t?Pexu1zB*^|)Rm*GXYWjZia40vJFdOE z)=Cb1@V2#D9>DQmlWCh5KF9CFe+~QLaC7A=iiRWwgRJ^L*;V6&Pa3;+!O03gQVM?k z^1}gV3?tI8PbvjS#fR$$1k}&y%6^ZRQhI)Odwx$%_M1XbQGiND6jWV-v6It95B!@J zG~)}>n<|_GvR(sXHA^k3LGMzdOv0Bu`1|Mc@pYZi=1H8=YO8pgR?N68>)PTn=orcj zjEvvP%l{h{!+jtFX&f*_i#Hl`oo_I3Yyue*03R%&{g`xc@2${(sAuq3j%bk~-Y%=( z_a0wi&D4F^^yL{t)vwbdFX6cv|9_wVz<@R1&n#rmOV_@^t(yB;ljYv`RoiNmWSLvQ z5IFu13r$eU$H^Gl@Aww~W?!P}v~0-bn~sF>S0r3KehT=a=nJZP)J=?98L%{MpGk}= zB0{W3J-$1ty1^dHEP%WFdI z!Po%c6~vk9B)t|;X$@lDGpBDZbe~FIrr6vjjTYkWp@57hBf<|gUf=pRp zW_Q^nLJE0vi*)s@bYfyg$v^-~ekSf!)J%W;%*KO|eOQ9&vT z9F?p>W7X_LVefyV?y2gR3SWHpW|iYiBsTW+7NI3brIDM6hu+x;yt-H!z8Mp{H+V5f zjK5bp3j@4L+#uS&nzy6C4Ul{z9W+Q(o8Wqe-9)>l*+a?9E>sxtx&Ug$*wZwx^%_;x zBU*7Sp<#J4ZqS#>5BdNM_;5{Y;5+5Ds4+u5F_j5Q8O&-(#NI4eTvmw>($laH=D9S) z=pj~~Bt+auA1fTumE)Ve6cg0FR`U-Z6i1Lf3 z1o=u%4V(|q0;T*7R903c)I7ARem+huoJCGv_)jZ|$BDodZ(P~x;>T@Q(o25> zA0D-IvD`|-K2j@+w^0Fi0E7ZE&G^COnn?{iOKcBllcfFyi`SUW@7^a1^&d1m6Xj>b zpok7M%3aUvA=@BTe9v6V6u^y_e83mPmR{a2Q`^5hd4q&UE)gdvI$C8bwkbk_01VQZ zJY04q#~G@PH7-LzKA)epyT%Yx+|D9Cfl5P~rbDv$OdK^hxS9JJ#2Zy-#yvD;DX?Q_ zXMaNeOu{D4z`ib!P%>-OuDqt8uhjnF&SXPR4$Q}-;MFSb?|t!sXE?# zZ@1sRX=kdgyfdKke~u(pq24O+VaL~~y5FQ=`h!Uh3CTX^=^!{Amwh_sa>+{S z)=iKBPR&!sO>Nyi#^QG`eQyC(ueM%pGzV%xDV}))bFYUWuNy`|RhJoU1oGJP*FtD= zwc}~AD&#OviZ~ou(2~dPGkR%)8@lK~)&0X#Yfq=P5^XM}BxQnXH$SIQQSNa)2_QT# z&&eR^)}BHz!(j8GFx3bm zXNaWrDLzdw5l;$6>%n>TDbW<=iK^%dPb*~Qm}rCp--gDfkge9QtmHT1e{LU`VDk5B z(8@rr==X}^XicoL;S;#Ei@1M{EU9*gORWei)L2%v`!~qQim0flP#EABEkIQpFgQ%j z%wQ_pv{bg1eaUx)Q+h=;u4h5JJYXaSNXA>Om$(U@h;gvjzZRZRy*3Q9ku zXHWE_5ZS7Q}oESXQ-pYw{hr*mH!EwvsEl#`E&2*k(cnB0z zHrqLd`VMS>TWwt$yzN}>Zjz)5*Tf_MA{;RyLb|l1+USpmy?#qg&H)kw>=9!wKLoCF zQfTOSr7*-Eiluq!O&eTNDORJ1^;SuIq9DaX{$sA+pGE~iS6u!8Q!{b=h@%8~(^afp z6=)bx1M>5fk@QA}h)5`mZK&N4JQe?xa3`||$X&Y|xS-jOw+&gNpO8+~Ul7-nSpg?7vu}1s1h?pkr z%6(({kslqZlQSx~Sy<_uZ0Vv6|B=aHdf%KF{>%}4SQmE|sctr9t@9GUK{vK=%^IDY zw~SDZg=D2eLhBvgHjPjII?r6+y!e(XnKS(6gkseIy=1NyoW$FC&-M2EKVIKgfO4d+ zCpX4(6(16pYZ9^NZIE6q6lSBhH3==gapF9*<@U2^$W@++pa_$cLObi|dkGq-=F`8j zWNwYp3m9icr0KuMVq7g%DW<`S3gdm(E#jck`=MRPo!Ap2U2k!->OK^*P3F2&?3Rk;+i06uRx3AV$n7x@1fzP--ABt}tUHGdJ4iHmVZ3X0j(CILLlzUy-kE8098exg}h* z?MRb!9{Vyz{8v!wO?hIBm2ro<3AW}uGJ&Zuaab7A-IRx2PVU5JlgGbNVtIjv2*z`eqxkHoeWsB z#RS8$ZJUl$q%=AHW1_*v@0m6YcK>upaKW)`=aWtg=LII`hDf!uGMO8LEC3ITIZ@e1p+*#EwTieI+2+liny*zbO9#8<(J> zf}gy&l*Bskw-ww6kK9#{8#Bpn>K5NymUF2HzpK1Y1cbWnzc8=B<{Edn+>q6EoA!kI>X^m0I{R z37li|wc&)FeNSC~hfPKSy?<&|ZiGmu?Tla!cG$I+IKuy~+e245_ovU|Oz6P$WNdhZ zsGz7Z2>b4(?#$tz4-Ys6dVgm98|J3xIV;*~v1wvatpTK{ufBb6~6_KlD_lj>AKWxNKaR>%DZ5qbUV;wc95yrz2jFBXFU2KsCT&Glx2!%P%Jny>NPUM(-G&vcIY~V$z${Wq_b+T(R;-r^DJ<0m*AXsPskU6N+r$wPcVIsm>ejq1R@T@x2rKmz|J;*iq8Cmc*Z-|1e&L7 zjxY1%ZZXDB1>zB2w+N0<_>ud2PSU@6ui5wHe2YNN9p}#wln@PbgBUF7k|6#Po0}k8 z^@gGd-hs z0Z(wi{_i0!O2?tz0#W-x+XC4jG=Hj1CM9Y@F=l>>s}Ztw@YQPD$esj4x&(sMh2tl^(hf<7 z0NcF#)Y?9_^31?%5pRZCnV5?sWSYdc4?6G6kfGo}j_7YMU&F+RPW)Q>+{}9iLm}|z z4e(hpZWE%R>^0LA~*mZw6gnGg(mBybKdl z{ZGeoiZwOmNq?&h7!~bJ&~9*+4SAy=&pUH`k6e82tPTk!!P^zh&vusp)1{}hwwl7_ z>n0^bQy-1Z1f@XJ=$lupP$XK^pmF=;DPtTf$KNB)*Bn&*^i?BPdtd>?MsenvhLdMf zoY3k~T{ib-9)6dh4K>^fw4XQl@I#ZpAfmhs&$JF9^RnKO`3@~uTyx?dp|g^r zvY(^yuo-+3k{0GQx##*I;_1fsCXDv4KS}4GY}A;?((lu(RT}8RN#3Qbml^#2O1D_n zZo+~#;1vGFNZ649=6qmIz(ps1Za$HSlZ2g>&@Wiim86u#4f;eDJ#Z{mH{zrQ z6D0DSWS7yR`r^NdJ&0f!r6l}QOHU)6b-py^b33*HX=3$L=KX1z^zkEe1u=he>f+nk zb0B|B$uF8ch<{Q;OvVRNIQGpj9TNV{4L$-~Ys^>#A;fPVd+z+8&M)*Sv-8Jc|6`Xg zld#K7c!*k#X~eh?mGx;GqxMj#&xdV zze`B~D~l7@ttu)^8YQy)Qy2p6Vi$|a*l0ib!l6uv*hb&VO~~g5O8%9b8n>f&Z_%?k z0~@Y{MSB{@-kM+oe^bJa(Nsx4?37W1@>V!{e5F#-iS!fCYkNA-)Bqt>S!-+xtfGlp z64%hvjF`9CDT>}6ODM<2frhN{RjF9hd=Fb8pcJ-VlTU;HRBNu__O%3E{ohIue93=y zQg2#J`2BB{guv9N>b6PK_HoTFZVmk#dOE3z5}NObtu}fXxmeguk7z#w7QH-2m7wL; zc~k?oHMLebH_N8>I2Q0=5T5a4N|5EDi{qL@LO_CE6C`Ya8?kazkNzQiGt=Gi{EE8h zhSF55%&30ZJ)|e6Rc!}6Av*H^c(+Np)aof;MRT`21(2A=DmhN4f1c`0`}y?wR6NIB z)oWb%#Plvuh7Jb3MFv|OkceYdYcDNNZ!3@Ea63P=H6(#q)b;9$KHU-D+^26<q{WBvJBU!lUOhpZ_3w%`E(@Q!gm1G*@pA94Knege zl?YYCsZgU9<>WvZ|-sUrI^Zk=+(*7|2;XTg(TY$3PH8q zm3=gtD_yLj(Gx3!-KzSedXl(JLHC~{1|}LJT60uDP!sPJSWxIlU3C{a(z1q>?eiC? zV63tI4*YW3feQEEj@=+$8(RYSGJhW)=2cEAuth~iioV_TnKElMN;$C|El8~4mEIBT zVUk&TYw{|EjspIJ_X!>q0TV}Hl7-=mI#~w{>yHR!5-+FY{%BAmb1y#$%6}n&B@7v* zy);J&2m+_ihK3d!8UcZ|F|+?|@s)rM6}DX|07BDwj};*rl4|h45^#e3RWHKeLiK_T@)v4($qj)XAINM#)mY45c*77-zo8OY}pdj zZcPj5jsH`NSk!y>_tsf8c>sw^>oho-md2c&`s1RzXCFf8xaFug^u`{F+W0kJ8>iEy zj&Ids@|PGIWWiJ9Aui^*e{e)VU3E)T5>PaW(khm_naC;axPh&;Aj{`r%5l|BDPPm= z^>-3Cd8szPXu!VAhd%P)7V_HpA5qZ2S@d{8;Vio|7(XR*3h)2l zX}O+We-X?`lbLqU$g$Vf*7dB8i;j@Q5vTXcGjG|0=1Sy0{B=Pb)z^|f308lPuj!JX z(J_5yQK0y7(r6G!HZRbkC$}p+Z)>^zVTq3YoOCyr^@cb7+F}}JD-Az9mK#>gTJ%`d zojZjoo=8YuE}g8*O?Q1>ER?tN&r?tD!_IPcBgweEtpyATmA$ZSn(RN*E%%FFP*@YVmc>;BJ4wZmvz+o&L40vzQd zNOC)n4%QY5lBdt({*yN4P$8PF)Nr(P+Q}b9J4wXS_8+4j$BFf zYdmcDp&AzDkF4li(|ruS$v^giae&n zdv9=hRwiL%3=+K8njP^`UfXaJft1PI!a}S|${<^)5-iAMHal*Ztbri2Lj_%oGO*|U z1<3nmNZqmxnB)=?t>=$`T0D@jw2Yl@eS0^bv&{8a{*eaWS!=A8UZj01axiWySoH;hu|T&y9akRxI=Jvhi|y|zExk<{@5y}hS`~(KHYsD zSts1<2CVa*yzZrI0Q*4TT(w%K`P2+p2p?zLY6RRHKTHi@+Y1YWfwM(RJV)wjrULwr z(y|dk&d%D}nPYGK7>T@%l@SO?fT?=>w60d30vxHOy;l19=;-LzZzst&3w!(0nwoe( z-q^5y3D*x36I0Oj{AFEX&HZ(~%jG}cy#3C@!T>{(wMU#=ugHKfjNDI3?QTPUJFLnN_qO<7Zw(t|Gs{;sVwztYIdA3VFf6+oWJ~drx-}yx(UemD$pBs2xH3Q2CDX(>;SXKepF)E}+&vjyr2#*0OK22e?8N6%{KV zRGQwq`d;QzTASu(%qjVruz4!=*7Ym{w{0hX8{49N_Rg3OZba^N!`rf!`kMMcW37z@ z9yRu&D+xkPQ)jNb+v4-@t!xkh!{pvxMHH%lLj22oNAR_Od(6un+QR+(@vR1ZD$zcB za3hERGs;^-BM{9C58H~`*C*z$TS7M`){r?MZrceS{loISN_+P)E0sm51^3R_j z0J0*gduLwciP^uu``bBS=$fHDI86OKl^h( z^?iLp(Y38CE{Wu;V=^{f$FvZ?m%dQ5hWVI{z_@qHNo$r(`OWhv($Ul3SZx4@mioE< z`VUtmmPcMy72VX-RQOzoTX|9IlSh(B)~zj|HbpAD1wfn>V=x5E;}i*DC+pPJx<*4YyE`tA zzf1S$yjUEPPy{Az8frd3-^L$jpnvnl)L(dqN3>Je8S{7Wv)|{RAhs?LIP`0o7lSdf z2I4v_EbQks@hIQgxzpolEV~zw18u5*{aj5Dv?|b&mvn8Ez3*JY+vHHZPG&)UrAOSz zE~(~F9{5XBH5vP_2*Uj-yYa~@_uX(RVBXTJuCc!X#=&}Wz+)Q_Cj`jG?Vo|iyRt` zo3jA#M7rUmSCeh_<_9%tP(~_b#VBMU74C59@7}3lPdT-(qeqzg04n1U!MbKk2BP+j zt^bZ1mTGu&le`jU)OEdp>@^}$I`=jF`}tEf$g0Qa`nB_w)L6gm{1A8FKk(O>lF5y_ zE`XWA5%S}gDV`mh2i|vASJ$;c4gX?#cx1d4nxPMJ#nbJv?z>*273R?vtUDuo0}-*j z`46e(V_Pw|Wsfs?1ofBiBPEw)RGNFlp~b6sn3IOfJ*6ABStU!jiySsbk zjnhyEti%Dnqs|FWuhBxg_~GZi@u+AtWWqwB@B-%@x0i?Y{>*3Sf}W95d9hn@IJ)hX z1hK&C!6jzD`tYn$D&}nEae$|VDxPq2b0c^jqZH=oJQ~Ws@I;z7|GwGw=Cn36tQB}n z{l*ag{gy5}$>o&!Ca)JlGu0AM7%QClIfKaft!iM4A56@W+?$_v(Xjq9$(U472bG(` z%A`LJ@MLMr2K9<4%&7QV<9%lOme4Zrht6KB<-vyXF_Mfh@ecr5@HA1O5*Ye{s|WZ> z0KT}LE&@V(U_>J=38k4EI}53VRmbf&;@Q{76RU~!5u$%VzL;EAfJy6-Q}n(1H*OIW zYktn&iUKinZG1o#Z9PByeg~viM{mrTWoc_m$;Rev5o&s*!NUkM*X-?SU-vrOxhFxN zRgul^=^>I>k2H4s_InZt)YZES4p zRz@lG=j`j0gM;-ILt{yFZuHw<(0$2TH)fqv-YYg}-3>e{HxXnozk=+SewLJc(oFS6 zo?!s=E))vbzLOl4$r!Cr>iP8d6`Rv8<&qi2n^rBUkBg$S!HsJkw;wyQcdkR@Uk{pV8PF-wMT!1a8~t1?NdmEf*JdL&JXjIn$z<`FYOY^LW4I?!-M6 zReqgBMAuCj6wR@qWc*gX$HSerYMcdX2OAq3Fl&4r2fH6P@XDJJg^92$e@CwtIe~7$ zJ@O*X{@&p|p9lOB7!epaJ{{7~LojjqZMVH`+zByb3rxH!bD>oc_+W^Y&&lZO65`?t zNRBNM&#bS?(w-nNl8?fs;)FFYu`*^xyeBaPi)E7k3NGqaeSv?SQtC zCiOfpY;C_tUW74(&>+LwJl}lbVWZPim^uMJwHvBg-fFn-r7pu!Z)13P2h$3OmPr0G zd%E?V^vpC8iog;;{RoZvr67f~FNHZcKjWdkB^KIQ-T$neFmZepunuSfY_b>_7y$Fo z(7#0B0hZZ41EUUqy^%Wh(=~)}&4gdAd9Vo*dH!8Z0cvi5qzb;w+iqKv*A(c$iQ`{9 z=f5i$1mNe%%gYbPtO3s24NXm-LN_V_5|g~Vcp?SBlLuaq2M=$rBVgJEEc<}734u&8 zTKSw`4;Mdw_OO)qw=j0C zW95j1Hsl2=y@($_oE|LzVlPlD0Noc*KLN=La2W?)ZNQTlNFfnF>Li7%t*rWtYU7hl z;tZ^qaexAfl8S1ukxLnH$(AT|eEei<>sIFth`$%m7}aW6*w|12Sd9yZXRW-XmVc{5 z$AJ4YQ04(A{+ojJw_1&)Ny}os?+1Ev^5F8bSS6Ubwp`H|S`xKl383|LaA4uW`|Q)) z)P$8HBd(*9t*)EBv7(t45%F$*-qv6Ed-m;o{g9y(8x3vtD{n;Secgns`hpBLIDUZ! z>Nhd5-cK~J8tx0OLb|T5r@G$^0+c|aeMR@YzGts*=^5II(yU3A?q*lsx%`S}8QxO@ z=e|>(Q{I!FQFvC8qxIWQJ08WCzAlRzI}~6oyoWlgiLMM%s1|m1VIuhkcU*04Z3gUk z3EA0*K_mvO8PiKkJSX>VSL=_R;oF@PW}+&I0+s1{)sl*eC?9I~pNyPZ30PQIz)rjs zJ_QFpuA9~40*2(lU0lMbM3-Il_2_2xo~Y+Ae)eVGcq8rs4-V8wF~)9pZ*M+}Of!$_ zh2xo(l_)?INve2O_}JQ9|6V-=qoB2wr_M}L=qDfCd^aOapLRBD%MZwkW z|0em(@s$ZY^-Vfjzy34}&nTz|w8Q489PQ6Fnu8TPDU1Q9a&1Xx?5ZTfY%{9RVT8MyFoQizM!zmZDtHsGvyP~~y{&-KVCBfN%~ODTbtwmk^- z*ZGmR`g*#I5~5tinc~TV9!?YP9i&ry zZ(IE?!B>4}$kOipme(VPtWHy#)Q1K(BTqINjeJJ!Gs7P0v7|PtM4K_v-?3R@OP9Ng zqe(7o6tE^^=cAP(-&qJIFyy!LT=TYefBW~zX?k?)rn*oO(Q3fPP_W0~^!eJ{Yu<97 z54C~?4EeP|apk0ggIRPl5$=&u(!)bD@@c_?4JVFV^cKDRY@FM;2+x&p)xKCw+kH@H zY`4&^Qs23A9`x32F6Ca;4NH;aDx6pypnKQe`<|ZW!SJVu+vd5IF64QU2>xug^Xzs1 z;>H^r0<0_33(Z{MWuNr?wWbnMF}KdU_mxx-tGr%6kZF_=Lc8~*(D&ShLGr_Jwr@8I=>%#hGB(b92v$~IqUMawroMM5=c zJ_E;!6zXP3rtx7>xsG?_i;e1cyyG#qpik{Nym}e2@=52CO;#>u`w7FxQc0F^e)j~q z{&RvT?|{@ng(RcPh&`SB&S+urL5-F$#DkO5XCr6}3|>6$XU|nX^rCiGi?rEv?_eCv zNVj!5DYPu-dIv8sl}UF^FUR*8dG5vUeRO$Qx8C$)t&SGP>L{Nhjqy<#*WUm7hMCi? z2h5W7=C9pDfZ4Rl;4EN+gU!$X-Rh2o?aFeha|nc?ts|2!aoqaXoT;?9FuJqUcr~ks zxtEi-a|^r`gKc#S7kOd!>8w1o{db4uEIhnZ$4`=w`FGC#_w>1}tSnv7m-m_)EfS*2VOp9MCyzelHk+GUbj(o&M{&?)@(v>Xm^qJ1GpH=?uP0P{k z@=U|Vi8V_kaa7%#^YEVcl2f`w3hlCa#N;~jN0n@+gP4)aBVQf5qwS2E?gvY*wE|W= zmNM{wi`X9!50Z-Hg_Ihe^5Aw=rmk6ODZY!Bu9OF0-lvK&j6ECX_C0?sx`bzhT;BVG z=a~Ax#L?#kI}opk_7b*PW=b^Y=D3@Zi}^mQ7&tf3dGy)yszK}=@oO+Dh72Nh+}YEa z}{<#*7G{g#W-Uez=;U;dtJU`8BMJ)1Y7b4?}Vg#J- z&qtvf>LkT+XF%D%f_{MTPMzxl3mn`{k-E;W-m?kFXAD*vBpozoGdivotcCiFDYXsr zJEAg=#3*8IzqYvW6>d3@NAQAfzyjtIj6%VfMNgNscxFxTuoe80@Zi++R3o%qPVU!! z9}YD!(RJw2p+g0RU+wR_glNiTB(QFskxy-!_`fnMKB0)5?!QU2%;=h11g=sUR_)9= z2A?_3c2qYL3&g^PJF_26bBTcm(7;8b?Dsmkq8TCe9G`2k6!!}1#jsy^xC`CgJ}Okl zCQ0nf9hN)lE>m_~WS$qnoV{nO0rRIAQe9BVSh#D5m zxR7$>;PR$Tb~_}%PoUUmYH^3yu)3<>6Ij%_REyW*_~c(8u>qD5^Zk!1hcx5)apUqu zxiPsO1DT@)7=K<6xK+WYK_qb{v+|l_0lG=vk;xI1yuVvQwuJraBw+u_hPF;Mj~$H% zQ#!6b8Pn|%>jZOI3w^?b7&J`?QT5`yXS_!pZyhN)jUq6{@DEgqaGYukO<(8Cb@z0Bw{%YBpJ5n4npqB36^XHTJqJbo^tMQ(cZj%~O zCYt=JcEz@f8gINrf^TRyYQ{>-oS&xh*=i*6ufW4~IWq^rhxqBK;j&8*yY}_D4JM;8 zI?!@rX$pNSb#M{J%YTXZir>R3#uBAb=Y?XI@<-6Hl*`_(AZj??@O0?hPQ^QP;fQV; zccG19;eIJy7zEG^vINgmGlEf)%#oWVU;zlIxed)>j@qm~m#_S3!|;`Y9ui9<8m?P>FkZ&90?m=?*8mYI@Z+cnD-h+v?2;gbj;# z*5azr@vVzHjl|zO5z;Xsl=5ha_4rs*MUT~e2JYW06P=ku_LuXr-viCMU7&KxBAhr3 z#y_Hu*PerGDX+Y%1-?+>?PET7RV=VD#)C9|BGXQgXiydERJ{)tf)rLPdJoe-#zs$q zf+1>}nvmbEE~oyjuC7J{)12eK5qkC>NwBrcvG zZVJRsq(;Rmde;{e#L?6BwSzNN-ia){W$zhwss_lR5riEQ-QVla*gCZDTbVNVxuCK( zdIOqSE7dl7R$LV06dXM_?$-orc#pc7dGXM|Jz^fBHe9kX200$%b&@00H=4IqhO*@# zHQav_*>g2Nz2uzr>1LXe(W>oj#4@N7i)4rB+Gtwh>s37Qo$#IqrY=)L5OANcUh{ijK)k39MW6d8$evAsz7e zWdKe@*8zzZwCkBvMtF@}(aXi)4Y{0aKnkRFC5LdkoUX{`!zvX-+lV_|ca&^_hwXHW z2w#kn^#vS;?n-Q`o|Yysr$(si4*LPm?*yVVc!Ywm1^EZb2R<*xcb~>1bH?f33wE)A zhk`Tb>-xF%Kbe@XvkLqoy1|k*(kb|}FLL2P*_XKpUI&_)Q@ZHXy^+w%#f02YkD(<; zUyMLc`Nm(oC*A#JY&)gf=k;7azvfKP`FGxl(lhzt<(S)LQZck}8 zZ*0D%!6Nb@sH8f-36dgM32->9avz`JHwJL9jLxA_iI$Ko@f#r#e-g*24J=C&X}y`2 zf*SQx`;4yaD(SJMFZ+^HhQHTZie<^!ru#cExMb7R1_mfSw|0NFb6LRGB56iSh0_6a zj|!{G;5J-W_ATIqH(w4eG7G_b-0b+H6){9`DF>|2HCakiUDq|f`@-ivEGpeRMUT~( z9`*C@oB?Y%7NHMB9_Q;nkh^D)!|~2p--Zj!`;9rGA2^3HWPcc0gwyxMmjuiOB6I4e z7}uD^xy5bgfrtVcC2(X#qL0Bopcs$seSa1@fwdSMZV)tN&9)Nf1v@ku*N-DEf|_2S zhU~*{LK-5dmyRBl!?TmH?OgA;W^^(f zU7YP;Y|=Y6(93KIHiZZAxf~--bjZ8M$glx*5WADe-SA!5#&j&cpIz1s2M3cnzWR)dG6C3PA+vy1uN78e3`x*yLSzUU@|ESL*MTB}a(r@YU5LUCCW4_@ZVG#^EZ z=}FG|X?5mjm{Tw&jObiFf3+8CtGKgg(Jqvz;O=m7O?zFfRinZ(+bUMHX))`0yHyZ6 z(QogQ&rshvly<*HY#)2Fa=3mAcPuFN`g<#}z4$3anoAz^%elz^LK14`BVxCHYyfv^ zeW2B&CQsMhC)21ucq6%I(fsnrR~e0?NzNCCHrv&{uoe@jmc(8CbJShEAxQ544Z`e$ z5({{wLA7B*UOw^Z0E-$HcyVQJ17;S9U2}=Dd^pg7^tV{Fuu=rlF;(N|cTGo9>g&PG zW!{d3r$1OWWnNq~GcEmPao!OAAOW-JZE94A3le89 zV^A8!W(M#Jw@}MrZLMtvWpBF#UV!O`xRuq>Fjp+;zuuk3P)sF>T4)k<;dr-V-#Qt% zRxmQ62Y8Xgoux9olWcDArOvx!M(9BC5-NgK&}Q2Gdm)J_{ z>c_5YZvjdVgfcidxZ5(fC69lvtg6~&#~;LGxb}(ne($|=gM0}43oN;i*@ry|i5VrE z8+s{N3-6`iswKPe{(L}kVUuAZW5nttJ2QM$?>SeeIjF~|!QlP=jW0Vfsz^h-!9?lT zr36qd5qTg2T^nZs|3}=S9mOzoxH{>`Wy|{c53s;u{s4tBvFHdj>&1huWJ1_Hr2IS8 z@19+Z-ao<>qJNaL$+=_xYcyY0HMbfG4YROWo~keT-MlE)mUMQ_@-Q%=t~#`3 z(6AvHN**K!?63wLLd*w-Mr=L2ra9MN7I9#ajS7bOOXWLGO%)#;Uob+O*6|Zn%lRko zM;H=UTPx3N?|ff76Nz}`M}?(sTN&47R>h+7%8-|XWSn#bgoPXf>S6F=o!L>8(Qc|o zg~u@P^`54Glq=R;U$M1)IIc_ocyV~>j6<{isn_f zoaARbFNn)>y1mwaad18|>l1!@KV$vyr}$vZhx7LKjEi^dK`}ToaYYj0-Eu=c{RkMv zk(wKGHwC}yO28#ECx{1%zFIoyPsfRn(SCHJR01XQF1v*dy+0wJwIJ*>ETRZBkSTVH z4ri1If|+SY_@JUfczENzmT%2t`?dZAy4ckDW(e;D63ZA`-P$GDvPYy18Vp4bImnNC zc3f3!`3(dGThDBpwp_A=5V<^2>HTAEMKD$dduS?$nbbVkPN(TDIk?3ALotpp*xSU6 zaNJeoa116oV-D%^z=1I-ogV8yz8*j(k6iuYZOxKOpc!sfXx}+IxQTy&XoC@pQ{!AI zF7k76%e9h18sm#@TtACPT#*Hj+xX;=rNEtQn6QjN>u<;ne`UxAOF5wbIc8(*w`Q9s zQ^p%h*0#jYt@MBda=%1%vHt-)87fd8sF_>ri5n@=!5nX4Wezs$-u+b|1H%r{{6XaY zb@#WyvQmiT@js0RIzH;|mE~AThz7M>Og^}FbN<+Go@ANNLNS|_ZhT>V|{e-E$<-$21?j$>@ZrdPa+hUqP|n# z(y`1oGni;{^AF}fZNTtGB>uX*`Wt?+e*=sn^c!EoC`tAch-#{?tQ1clsh-(1Lrt+HGD|8fnDC|g$1sw7(=Ka5|X45-~;s;iCSs%a=Gu0 zFll(O=m1;-dtPZ6Rf{-Ib?o8@7dm~$7JJu>CGfeR{bILtPH@fSnsSXoczYyrj5(pc zY~93as8f;?eo|Z8;sqJ1Bf%1D^oN%*oAaV+Qp;JezLUxgEbWUw$)o&`w4s)20ACS{ z$Ah(-!dpox%$TfV0oPYj-Ogf9D;MxL&nLDPW<$dJ}l`;g1#dMD=ef@kvxCtmt3 zRmFG*=Dl1CE|kWytXH`suuLj1QQPdy&5&dd-8ndfpS6KodRbt5)_@z9%;3X!{cFD6 zhDu-fx6>O;F{N~)UwNvbtqo(1x?j&Oj^;MyL9kG)+earfs~U)ZFBH*9C>iv(u7@mn zkn6sNF4L^@Sk^$IdxyleO$#m(|61jvlzsTIhf|EPGWn(FP~Z+yI4YuN^nu9dY2!=4 z)kbA75GRRT+cA=jm$RJ-hSUf+plyIH%${hn{I#Y3{JOMcbN7IqhHxKt2rVF# z`pb;hY&+!M$M2rdh`JngDXCakj^m5U3u?MzB5hp|^ z!}cY(Q7Krpa`Lmn%g`0psor~PM^VlY!Um=`i~8EWMd3kVS_rE!=uaiP}JuZ3C3R8eXQ+lqHu69>CODVejV?I#Z#P1 zKJv{X6#dt#M4P*J{Oj7GLkc!XGDJQ3Bw~IDxUOMlixyTI)=rS(hTY_>q7732)I6@f zl5W1F#xpZb_UV_F?6fLY#B(E8H%bU#5m$<34ZI%;_y{{Uh{c#wZ-nEsRsBopc0KCW z&~HNL1dp+#?(?)+0OB7kAiHkAvl#AYM?E1DvVApwC_g<{OK5;Bb@Ap>I=h+Nxjf_< zzgFbgkKBN!LSQ36S68>ib+ysMa1>H0QUm3M)0z5=-tUV6!sA!c|3jpdopXF6*GSfhWe8B#wa;jy

HOc!KWtqI0sl}_A9wAiX=78AhQHbD0$SyPj~i>jRZ96QX&00e zU&?Tpvb6&cyicD{#nC+I`vd&_G{6^Mn$5A9VtSh_;|!GV@;pD~yAGO-3)JAf|9&=_ z&NZaC;!RWnvM!7opo0W= ze-vmZ0bfaE`@DN0UJ*;l+^ETu5y@=#=T<@Y8u??X)|I?A{CzJvZoRsihA zaxG(%S%>DNGMJpl%D#OES?<`--e-P}2fy`qNFcELkcds<5HPUdVEyZ_mpf`88#g|E0;_;fl!DQYBt8VOVS(y7teW{nAVYs%WRVzj z^21@jdqU_v5+fClyxES@u0Zzj)l&jk61vjMHK&^aglcvr0Yn_vHe$H^ZojbAgz zSZ`ms<4#o}qm_%)hPaaxe<{~|DySzn31-mnTK4pW^I+kDgdY-ooH2nwu(q1^qHs8L zY>!jesBLklR zs$3L5P%Rn`kdaH$xhtN>M~l{;%9>GRWq(hf4rnc5w|sfjv6*Z|u~bR5!((sy{*G`@ z;EA=CdU3lBpK_^dzKQ=xOX~*d+MQt>y zI2L=awiV`!Vx;JO8R07S-*%0Q6@Eb@ITcNgSNn5-WuZ$&G)BfAeC~y}lN-I>*rY^| zD8uhKGUjUe@T1^Ly+%?syih_AasR(x{3YXJnl)F8W;VY)#+aT}{x78MZNehRNb*m- z%|mQ1^qN8oYBshODanDdq7u#mKR8sFl|cq#r|>ZyKQEwBUqhJtW|7#-ySAYSPe5(s zXl|c+{Ldt=wTG8WX)#O`ia;PR@_xS2h5W4GyNV7BdM|isiGsc36PXz%1~EaPi`j6s zVS=rh*vx1RhYB=#v-^G|C(^Vr;3L_^68%*f1CYB=1~%%Ie^A9OWDnC&qc4qkG#Da< zB9h)aMoNWHPfiTwAyw>OkMUr2yg1TYbh^VgcOOiun;Z5Qd3zWx=#_gCdoQCrzUUSP z#y_4id5{BR1|$-TSdLbk8jjZZPWhk_dtmU(mWs6%Lo60?+&ndMONPHkT-6gv^j>@q zq%SC81L;Y9hx3pu&)qzZ^WIV8EW<03!e7_H%r>`i7w{2*J`AAF9eHzJI(1Ko`zUeIZ1)oLQTR)!?ym5 zwQ6>p&l~vOG)frI?CCWkE&_}Zc>~X<`**=DmhWFa=E^F^FHuUk8><)sU_Wb?$(=N$ zel8j;9R4LkgO(ZiX|7B9?ck2`MYukl^C2rzz+jbS{l~r_E%e;EK6yQlqw2*J zh|9oiTukrL`&QpT^wDmRgc8k@koMVfZC>zZ2{C?Y5t1=dWpKy6dM=E$^VNj&`xoIh zIo@Bn4m}o6JRHKInzB(f-f=j!Ue6w7=u6D!4$!gpH*psY_kdYkv*{~x7WKxIbIDP| zjloBf71`zMCvuYfPk_4%n8zxR8fUyKexYgLLyT2arOhWWeTtDvu&mmo?WQiWs;Otj zK8z(@Eg`GvnT|mB#tZj%fU=`JBKScn~6(a!|BSF4s!Tko7wh)rB+Zu~rB4+_J(G@WL+!8@jb5x-- zUSB66Y`>?X@vcc*AyBCP=|%dU2M*+Dzs_*d{&go|hlz~`KNv3mdWHBxqGav}pLCbz z!YIRJTHuAhqc8Du?;ckUiTGKkxJSEKWHh5UA1?(vR*Krzki>h)@HNatb96ga92Why zXYA{u8yE_Kw;nUCchH2je^6ElwI1HY_)K!LNk^v?7zmp4?IqOU*iu!c;6lp~8I91& z)fgkNHI?d{&%)-td;8HoTpdma>#4F{W(S@xWGa?Ws9yOy;s(V3g>%kfdf19d{VaP@ zfusUjIvPY7=j(+1F=Zt8zP;z-BOFqUaixyDCiA%zv_h;=#U8Q1gS2}UbdRp&V`D~!34+rm4PxhTdGwdi;77mU3Az+#-+?jc4~OG;B)hl z8mb1p)j(jit6rlxrP^k38Ojz)8TQpEihJ75;48}Z!d<`K+!RoadXk_je9V3yK8sNX z$BnhdrijRJo!cW)gDUn1c3!%7jfc$H|Hjg6q)ax}%`{u@x`?CcX^vpz!Ss7@3TjprS$b+T%thhqiiv;sXlI+HE)@0x@r0AJjA4iO8xpnKIv#{aEG| zwUAkQ@A5x(6IBPY1pOB*K4i4vR@nu1Fv`XWbg^ZBjwEPzDwPFLiMU{q9$2CqeP86D zM9J`a-tH6?Hwf%Nl6-TAzu56I{Nq?^k!8o<*gXaBXkf5kFW23i`nXc-ZzyG(>bL0d0^s~eqk21v(blFe#&&@HU; z^jJHojtkp!mgNZ~F@|R>Dpdc;85OVGCU+F8!oL86sG(ymg;A2GMbr0uIX5|Z)mHy$ z%r7p_Xm3RsfFoIUPG}0*Joy`l9uMVB_#2xQ~z z*_vIB2J16yiX;=1+ z)CunGvhmSDrcvh%&TZmd zfQ)W++wHqePubu{L=%FrCXt0(xu>wso8k5uSA0zKzBS8=jet2(uJGzxdRqmo{R@eN zNS<#8XCfy(w@PH8pdOv1>|da?N)Wz2rh0wajPt@^^j%eb$g9z!~tQ$Ojz)Cb|fRfd4~7V=cToU{LGAONg#Ff}t4Hp&ZPGEXCZl zw%$ebIfhTB{L(n;RkyRV6F3hupUMNU5a%d_Pb$o7X8{3;!yDWSmZJdEnS0w%QC%%* zO=lgsIyVO#0#i;-kUL-$s8A}Zh=R}9(b|d|6LYd9qpwd4{I6(aI=;*j;5w#fdbRqS zo13q@nrAFr9y_(QG{$bv&g|Cj0W*q^OFug^JF~R36c&YSA3i)kcYo~Ez07@FM_#|b zyJNivq~lxvbzXb(c}~5q+uGVPdJ0{5w|^karnbyDvvmE=OQ_}x$40!9M*O}CD`NmW z52<~s#+{$#R9MW?C-8cS!x1G=6bb{$Uzc?#O+jGog*_&3uToLuecMx;WuWr5e)B>Ix z&?z#&hodO_)~y0*!23)C{{aBZz4n}+#%2@RRUlEChvQpwydnj6RJA%awJ4&P-wkJc zp@a>>ajIw~HxJKQ2#c@pkKqUv0neJ?{K9j5 zS*s5J0;fN>!3);6pItIDYSC*850o*6>(e(Zr#)(q&OQEJ$jTjo*$*!Na>YYrFn8sh zKb|AZk)X%w2ku1~2uw7t@oN=v%eBJ~ZseN9V}U;z;ibP)#_x$ND*z9fh=G$uSNGS= z*leV~Pra%+WX6>x}!&XD7Lx)oK&Hma8Ex3<*et{&XNkp!DMTDcszPx-~;I(qJ1AfpmX zsqFv9H-qaEx%Iiii{IhIvx06dFt&?v&ztX-UH>G~s~p75vMiviIG8C@93(}7HvW{~ zQH+PN_(+*rSB+}{1~YKy9tloySLmD|0wWCK<8g7jZBff z9MyzQUozIu)A$2*CVM!r|6UeSb(gHpJ8`bU)RP+YT`Gx!xf}Gews7y=A^Z-GO83;l zB@?i-0rq8SQrtQxv+Aiyf$J#%NfoP@tug$&?UypH?B!n6_$#5pzn(<{A5QpLtWXLK z9pfru-tyDv64r10opZWBE0i)Ou8ZB0X^VbUFY>-wD;@5Vr3t7;{2Z1%d!{c$I@t%6 zgE8L3JpEj2b<3-dq1RE`8%cFx*^&eMqHp z@-@>HZyAzxJl|0$YwzXbNEDGtNfo{fwq9A27Z?3VI34$&J@I zYsB&sGAZgp^NfrJbgm6um>k~4$CUh3DI;@QCz95;WM1Ne+2s#b_Df$A^>Pcgu5)q7 z6d)yIWJG3({T1yOt^;*d?YKBk({D1QwL}Av%Xx5lo;m-S=uT+6m_;Ma4~9{eKS}+~ zbBIYp>jk5YA@}f2Bt)eQ<7HKT2II?v``0oU_L+jF+s#&Kr#K>UZ9wHgPg#u~_>U33MzMK2Z53 zdEtd=PpzLoc5RZGc$skQNJMXZqLfy0l={l|^uNPZDa1Bbe@ZL8^3IqNpdz7n-a@{Y zH4FDHjUCn98h)P`d+2_u_PNTH%5CpV*d-4H0N%(GYZBo3ADC)G7XVWoPZ7y?)}U+(4hAf`0M`!;3>q3bXoKV$hT@##>ysb(ybe`g zcgf13ek$4EYD2;2TmsRb7qap&YE6Ip52h=xRxE5rMn!xA@3X+V2Gtq5w|kA5m={=8 zfm_`^D4p?t2+J;A_^vvJbT#!Syz8ynDu2*Y)W6~-k? zbTllzLg3pLg8W~a(XtRU$%8>&(l(hK;BddEAHtZ_U(u@<{DyVLq;Wq`W|7J~!q%$X z+x=nZ7h;Fy6+7y-JYTT!iF%)xYhi%MNtt#60_@F;vOd;F;rH9RYQZGBW#AkN052!H?h{F#<@BClqe z9hhH1dSVDxd zy%v-AzP&v6YlDHMUhf!ov1PTIdyBHUu`k7_shJgRhZRAoe-EXUAP31k^Ia%aA`AVi zxn4&K`E)OT{i@YkcaCw!_e5}n`0^FrU#=6D?s{K@5nk2)k;LHn?i4H_%f4%=+-tCb zl$eBr0~1uLX#OUmyA+>;8z&E<-fUx?S2&c{Mj=|#hC}CQNRt2<3`{o46agicH#du- z7Gb}!4=s9j8Uehpxn%hMAA;Y$FBK=;He5SPM&@uHq5x^W}n?% zvu&3cycV^4m}b#!^aW0$3tG$mM6ELRra+W*&-)&S93_Ckz~zO@?d&4mP4sC9&puNN zlQoQ{cf0vy+`}f96WpJ{&~#MDrqjd09vYGJU4k7)x&(086yJG|E~Q?BrXBIx1a=z$ z$nB5=u-j05dQB~2=%ao!cU5)$ednu&1;MDn&`%kwMo?QqK02mptE9xqotKrP7KL*XVbbRbW5J@iiZt2#9em91aw|a2e~M2d#>%hN0y~xMhQe;d2~nKVv^DU% z+qn0wk;b+HQA#@mDt|&h<<-Uu<+Cu^kEW@i@L6ul8~*G<7_yH!%EONhw4k0H^W7~k zwy~%*XZppf4c6&T=XI#Snu5<({V{q@Ad4~|t!zL7Zs_3a5NH0vwx$bv{w*NAtaIQd zA%V*nMB^TtYk*KGhqG?P&MMEzhdebo*&jn`v()awboSmz;6-eXmhqD)+}*5l2-i{7 zWB1+i1*@6Z1EcXNj5L=3cWZV?AoM@mHMqgD5rgFy)0m+x$J{I8UCDU0E{e2ma#(3o z08>_vs9Xw6I&pYpL|8!qS&G#u4E$K~yYU0VA3{AWg5xp-K$zTj+r)Hyy-GNQ$|&!HRL3+LU{R~`q2@5WtS+`-OMkuB<1$^|9Wgh4z8ONLHY_A@0|31b z(@BdUzhV3ThHDxMvjlDY68UFLZ^vm&c$a6q-k*;RMKm31>A@63TCFTUdURCDNB!*x z-h_!a!=mXf4Bq(lmIkjD9Bax=BB=XdMCL#~a0sU2_5EP_qZ#41oamsb#?A^r_I0Aa zFi?MxOL{Y?e8`wOCxja~pEUG1XwKmLGU2}6C-ftWbSrE`WU!!n?hg2xYJ6)#-hk%$ zZu^t8;jz3fjzeNZr9}82_cD#beGZEZ#c)IZrmSBSECkBrNH2d@7_B$?P*|xDU1;UP zZALP6I$BO#_tbg-+fK>VXt(uRTvh{0ens=(X@@C4;5&*A@fQ1XGXhlC|1YVd?7Q~R-EN7DzwWTlEbBTYfNzDp5a;Av4cGch3{ zC$H<1PNawgtO_Y8DaDfuMs^xA2DjLQ;3CVuYA=TUM7$N$i~lt^8QCi3jJTo35%`!& zMeuIPrCN)2VP;0~WPOpSE1LdbgKU5u=^DbHa`eV~>(74;$!#aUI=mi*ySi2Zps z!_4w~tQ8FlY1c_L@~QAcmT+6638Ty@C_i=B_J+jYvVRud>;(-OgA)!UcP7bhMKZ|% z6imOQevn_6$4j20!i&pZTmNiK$`EJ2oM-nIHciORq8m*AOeI@QnMuyfm<2>YgmH9V zMxl9lyrkRoBO%?uh8=xhi4)IGjIWMm|0<;EFRSbE@>yLEGEj-c{!XRlaeSdscLKnh zSSO#_P8uYBofY&aJ9u$}TpgxiK||Vxd)5lW7k2rvTn}uB|6Eys#hPfX{c@6>81CrB z*Ug&(g%zRYc(5{axRkqDjhnWUI&PhAO=sIbT9_4#CC;pbT9>;=2dp$-dj%yO1gce8 zRTB~t0+FLIze_y#%B9MMiADY~71)CCk3EkxFWRh3rvK-%)a~A#+~XvQF8KDCtiQew zPkRORu`8aszY5FJDf6>;I$aETgjOy0(pgba%IOcOxh%NJ@8iNVjyS zq%=q<-3UlGNOyO4H{arZ-tV7dc#X}Dwb!0;p2xHXRbFL;PlY!jbCu(?&4SL@$3!o< zvHDjv{2w@8tr6>GO7;8bN+PIK9YM$ZlEzrN33l)TE-{yT1`d6Pb7KU?rlv4;exkuV z>`|df>%pzqhK{xI8Vt!rw2M9!MA%G!g>4E!SM??^t-@ejNFfYM_Rq3uS0{~bhjM;- zyZME643qYKL*XgUQXCgYbi1RJl=gM9VDmhB0BxR*{p4@+A*Np)WAmSvOQA&rgV2ZZ zBw)bq8?^53`7ZRa`i>qt@B=9+ZeCZ}-d*2O^~4w@O@;b+_}`V?U@vMs&>3Gpz5Lna z9^sEmzalDa=iD}rhVqDlWqHXweks)etD|klVnE^)gwQ%6AJKX6om#)3vwx7DqC#Rk z>_|_||C&|keYQn(qQqK0T`^iWyxybZgQ(Z+txelJL?BAJkZ5Vk8;S6x1iHycSfU?+I3#aymX8wJDcp<>Qnj2YSQaLeUSp2&G}Q9P?CDjfn7% zEc{S;Nze2Csw9q#G8NF30i|<)NeyyLqII`c;WJ@Zk~@m%sVB63l-R|T1{o7)q+#}? z!)PKEI;Hr&#_xguRxtIyJxe~9VaE5OS>DApdJ?Ojond{Rn_*5b-kj@T+IDC-Or#tD zy}2srsKcb$2}$*$sZXL}=g3k+ilXtN<&O1BAo|9fOu~=N3UQHEYaO0cfb>nx#b^N+ zJNq$RW&|Ex)X?^t^t5M)hV66Qz{64gZ(n`yxzFl!EBV`4^nskdwJH3gRwligne>#B1u3G;av8k%P}I*H`6A_D$`7dFF%Wz7LP{q{*2FO< z7b4YNZY_wuc9MxpJptk%?5k}ozyau#M=GmgT9b+QIbn$mF?OE#a0MRL(PvIVwF{te zRA%(`z{tlkmQTW%zFAM42$OTo=Qo5c*St3Jyq9NV|C1p_8W^KN7w8D1ln*M!O&j47 zWqj3ls76^KHs#?3eZNSF6Yk*;$eePW#_a9J?BbEm0-&=(jnEA!@75OjIBxCl8!peN z5|IQxv$SpM3alV0LApvhucwi7&-shrl*~%2w@DM~=ai~DA9jDszki?6CbYm!|p^Tyt_!u#uYVt)TeBDbTUpCKEqKc(u0(*HkR^Y26rk)X9g-FL`km zV?bjr=ZOVOldFlX3U?@(%&?(ID(}zSV z5NZhsKX+|h2;6#d1$$*&L`=g~FwQwW5wiL?{oA@CCeBQq_`mWWI$uirZRsH2x@Dc@ zp++kgtVgBFuiw9_J%?+AR%#BNi!<$aH}Zhk=sJz<6@cJ!IP3Rt+=Lo|%hEHD$Z$5T zWta2U`!WQX`a3+S_a(Y&xo#Bjgs&bqo%Db?A@;YY2KAX>>hBZ){jp5+dg&ZE~W-=)=@7H$c&#=0lp1HH2g+WpcZbe0U>eWyPSWr4{mv z{1G4!>_O9ph~Ej0TkBS@B5?{zAXpn;9 zRNoL)`0=OZD76;ro-Xe*zwWS3Mh-kMB*T2{3C3()>NYpl1l?lQd7tv39sR*8(ow(U z-X8O61`Yoh3t}a<5y=7>M6LKIHNgS|?1Y^j&pPO!aP}~X=)Prl zAlyD5uO`+(CT{*n0%sde(q<7UcBXt8xt{%L*XaRDEL(#Tdn3OZ(O$P)$97%{vUuXs z?Pdev+j&e280(IpTu3q^uK~|R({-B+>PAuXF^}iN`jiQmHDew5inQOR%eVnD;(TIG z;yoBC6J-~s9m$o9tuKws;3^_txi&16zkAv-yP!&!yHaDNkEZn6i+-6zC-M6eD1yj?;VEmyuv9@D+_~E&vu|wU+Fbp18-_uZk1(? z+V$*g*wkD}?9$g1cAWPT=GSRG58sTGQw4V-tay0gp7~-ut8B ziZeqttR)?C`Rc;ceA!QF7%@wjG^v@w~SO|*|1`Wsxw`(D!6)u4BI63L2 zZ3dch)1_J=F(S`+$jHb*vjP+FhURm6+b5R4fiI6cBAvo|fM79IthOQYa)$~aVg{A! zV2CbQ=9RuLK3)%{b|1PztnjjKt&!`pGGh=4jxNWb{miDkXCK}1bGg_;BO(yLBKD%e zb#-^MH8Urtj4{;Tz*gqN?}c~ibN?$}9VbRnkm+)JUi8x5pEb^dhm8)*wz>X*`#OSMKIhli~{X#RQGQH)XvwV5+nlssK`1EQ6 zDZMJO=NlcImF?>*uK$ZwTqKyGc+;%Y1!osOR482Z;ZU^Z_5P~dI)v2L8S&XT8uI|M z4J6Y%u23eZuAgu**vvi6B_ihoA{O`PBdX2hZe|4J=V=jNaeHX5o$As9m}_@nb;Jr6 zNYN1fA;iHEjxe-Md0W?1m~qI>K0Dx>N1Pxxq&vl^(qN@n|RS1 zYI6~=dm+uTNl8g#1TJjbFvVTPWGi4Z^S!wmzC6&<-+z8v!sHjIV9W=h^0lQhJ%Qpw z9Q3@k(fAx7@!t)cI+q|pL$;q(_x2iD&GVWMT_1$IL0&j<6^R@Z<}pX9hk+1fJHMV2 z)R>&zpst;X9Pc7y?*TFv1!zHL`%Ksw%$}V~5+fe2?0@JDjTfPT6FKLECH%qpPFJuT zZHBYLacx)~isYdRiyAf8s|nF_J`Hp%Dhef=6&?^^k zIs7(d* z>TEibn6yrtR_1tQMD8{*LFvB9s}A(C)3|NKK-(P5`V0bCK%(-Nd-^&syB7>IK?eie zx;Oj3|9vN9m>n8tuwf$Jkdul%=_}8^(XaQ}uO{eaJ?vF@0>*#q52y11kO`#-8Z~I) zDe!e5kxo}6#RcY*{5lWR=Ndc#F9vgL_(!+>X2{21F;QiwUkmVAyftA4taofG_CCjV zuZ892H&=mrZQgHro-WK5(TY737*M*jytIb%NKL$m?EIlkNa0@bA$4UYGc~MqpVM6S zT8>+X({F+Q;PfDKZ2}7VJJ5WFbBVj2a?fWKyK#^$8{`aGsbyObfag8r>_@%u9FuCw zJqw|4Dl4l#c7!6PD4&*r9dWeLL*9dqUrn9V_E?}?#J8{EByIO_SG7p!AaRJb-8eTH zO(Ua=ed*`i5M|>E_A;0>cqWuo`dqkB+TQUMHWARUlO$f&9iu>}rriwKM`I5hu(L?O ziqX>u6#sYl=9)%YmGLD9TF7QOsQF6uwdiN^hezLJ`KbBsM$cJKU+w60Sg1W%;qD0f zhE-8EG`3U*)~1RrPVpy}0&6%MwNvBM8}czma<~#99#o$Fxeo)x8;rBJ8g$mwD;|Fx z_k>vtsFSuI6Yrv6q9mhRy99XQVFN+skFG&bc^(W?%BKQ+9~tYC&+j&!t60z@&%Cz| zk*p)6C2Pi>{}OURZ(sAQhGcnVk+fl_bLxHf5Pr1_TC!QC%vxLaK0?K;xyhTnpU04b zlTLD+xZEsae~$quTbzy9*L)tiN^inY)59r2<{9+<%u`bW$t7|`qWMF9Sp+p}`CpVN zSnrMgavX+AU~T=+1&&Y0aV%W*##0~~sZsC$0{TA|mz(LF9wkQaTv@b;aX_@>+sFA! z)4x^?$IyYHiTR$fKiEVhF}GOb zPeqo5c_i*uUY=pU_Xh%w&Z0vvacFcj3&oqWD&Vg~(oCgvB4!z~IBqG-*nQeAQC*S=|TAu8^-5)$xg zp`g^1CGf@(`Ox@6wE+9z)yj&d&GMNBxTJ+Dc@m?%??d=mgHcXMD(j3oJ);4ajhIvK?o!SA;CG=oRAO5Ill|#WTSe9 zABm_0X6JvBv$htJpuS8F47UL}_ip|MMsGl_?^>N^}5o0G!geokmsfs$?v*AGX=fItmBjuZzD(gs%xu z#Imo|)*lVuHWO(x_8D((s8_=tV*=~+PRskEeT!rN0*hsBMn@tSK4pkgickdJ3>#j3 z30=YEfkE*y%DfO!u~p$OG|RUo6xmi=6C0m94>&U4hetZEA5`O4)VMvx!WtT#qHzD{ z==YgErBzFWhu|d|JYT}4^Z0g}Y#}Dc>0b z6u3oArLg^~&sl$a;r~d5gZT5mQfOcmzY&M+Oj!@^KTogcVYY@~d9_X~aWK~b5`wv5 z6;cW&5HB)3yaV4X{SCxylWY0H)$u|->MPqR7zhB7@1Mp$vAl(toSMpM$vk=Mb-pQ` zkd!1w{e7+6_vs+p>?uf!SBhK;gGYyzgfI@`7p2+C81(A&56cA7@aA;QxIlmt#z#x51>VFs?rJVH7B9B z8-KT=jC^U{tG@~2X!V8%PuLj9E3=Z~dGW;7UON3&H0Ugw*_zPIoaVRK<XMeJAA;q#6l2;3M->4fUe2&1bb+~?O6#XTzWjd)M zS74D%STsoII}O=jCG2=US;gpdV1Oq9P;I}_ySz}hz?zoR?up1g_1apXJt;l=t?Ns^ z*i+Yp7j8>z79eNoi2jE$aNArB?yZlW=P_?{iIm?w`kxZ&;I>kx!U|u#(* z&n(SVS0?3a3)9}BmSd-A?5#GO-JjmXmJdTh5Y<)1*%uIW2V^?JiWMyAp;5f5&)4wh z++xEG282HqR;)iL;dux~+zVpCjLV@xPh&B)L-)4RK@c7M>SCBWx!d$MIu&Uw_1>+< zPqF$nRq0AiJ~}%ay3*K~x?=iK3XDsQK8gH@?J`2w^(Uj`^X1nn^cZhl$h?T!s&dxY zZEa_2V7!h_=FaW~mMv7F?gcG)XE^bs8T=pmx$4i`zk1(5gm26`rqPiX!6G92ZQnGg zzjKir{9s$|oiR^IV-KrYc@nag2i1g_4;sLQ!hxV}p307C((WypC7u^2ckwR4hr}Et zw9e^$Ch*XnIFNKNWWDQd#g5v_ND#E> zf8|j?l0j#QG98FYfJY_vg$Hkcx4=k@iqAuuZ5BZuCnsli{mgN^fW!L7o?#7-fBRcPet4G^q==)|@do2&9VNZUmq2>KV261$f&7vCO= z*&;g)q7^!9d{xZSiIRojm*qE(dZ!Qdfmr`J?mK=w7p@U{jXg%_E#tyJl7xby&2g|a zWIw%AEXL?H2(39guCEbreI)7Lxvh0jEYAK57JOt~3KqCY$gR%FaxF(QR}D2*S9XIf zw>G*vFz0c-JIZ)n(X{x+k@3h7ys{N>c?EMn4J7LY;GBh+xHSDTsu2`sjaG~&KEX34 z)~xlONDMQbF!+pwX9T{T^EE8{m+-bYx)m-#>|j9d@2~8{xDst+&a3j$ejEX zUpMJCL$PCq^_eEo4$n$er7HG1#1`i}3zqNo=z|1&=)@PkfpxtazWq^yQ8%@P08?cn zr3&Q}&oOTe3bH|bG{bDOOYYbA9(HEN3F}mKLuzq~9XbWbA^NBPU*h_wmstxL)Zge9 z&W_Yt!q|Ue4W5lp!n&g?&Hr0!*y-cgt)Cy^3>qJSiULV0(9Q>&&UDlScICAA@P20- z9xr;2_ECNGkPec3B3-einmBIo-URwMsc!8=Pu1_bQ^2eXYYkvYPSZ2q=$rk6b-V1s zNg?iui0iX!dvSW0#Ot=;`hW(lq^zv7yuny#K>( z=|yE_Fc6W1JSZT2o&D>{11dJcjJnNusDh^u%WfOUfEvTU+aE`nbwk6K9xR^}mZPrMM5DZymm4PdXJZdkK zr`PAukPzp=r5ro@{qK16XwQ{I9adZss8L@vuxbCu+ZpsmGZGSB<0PVE1D;A6E{!+} zc{Ijy3FY4Ry5Kc=r;A(?5RtRr@KuJLTMCoRAsAbp{M1|yR`bBazk`8U$pqewDuz_m zOJ@&d@^bpYOZ(lscjV;cqNB~{R}BQT6B3q=DaQ5*0upVaGsG9 zpO>gr$f6p}I6IKa;l!QKtq-F+P*5-dZc#}w=$w*i=pjBnJ~km?Q!(wSy%;DO-9rq3 zjm4UF;fQT%@dmlK*w4vxd|Q9;y_&Ncx~BftTwOE zO)%no8g<|LoCe#%A|tb&$aj}AXQNk_+6}F0-gw%NJJsBM*9Hz~C%>1OcIPP@MXz6G zb%_kvOcJA8*KPdioK4EGxX8b^DSu^~K>sr&fuT;i5@RO96f~#rpb=7h0|q@x6gcb=+N8Z% zT~1GPaOfb~o|o0IKZ!F_9RI=uhrjEU^?gN59TTO*NZ&F@TO5WqyaPR2ao0k%zi9rD zrST7%|M5U6B{{ht{z9Hjwa5&@3H(R8=^b~Hox!eF3TCeln^r2pjLP^ zbpiB~{Yg;0IhPK>Rgd+J)h~6^kppu`dn*%cnV4GS-<=B%*tobMU0q$G&PCF1byJ_= zsuB+Gq^o}s14mhys&a3|3g7I3tKBY2%_0fjm_suKu?{sRJ#nfON0UWYxVUhRXSS?k zh;2?ehxT7PS|5R47qSJSyja5nps<{<5fQ8ng%d=ZiHZ>}hBTkI!Y@MWKO5@uj3qbA zyHmZ)=;-X#^Y1rAAy}fET03#TCM6Z2SQ1Mu*N$QUEo2Uw4mrlzT`6w#An&EWLsyJZ z2w39eK(BXp_Gk@})5c(TpFCwrOf|9iD*(~ejf+`4YQ_wAH4=q;;AR_IXxdvBrh07u z;yIBjq7%p!&Uz;!+-|(4A3154Cz1)kdEcg`*^NUSJO$`^~{Vx?1nX!$J zPMil^OG`^f=OoNXFi=CL7ujYZzg_h+n3!A`>Ytx|N_3iVz%V&K-SQB1##il(&;1^a z;PdSUuR{mNNml-+WRyEIP6B|X&z`b0V6P-ZJ32Z7T-|`&`h>*9*D+tEQP}=qGP-6d zj%I1nOeK)a=S*4RQxeid6AQqUszzjHk`$D*wvvJ$ba!_*d&+0nsl>p(ScZ|~P5dZnDKt;3fC+%32u z*eesY=C9ZCrK*FNN&t5Seo$0WvN^?uRo+ta+pvs=TPv1cKJas4fNF8~FJ-TC9eKAe zIy%Uusseot*1WoWl(c+`nwtFP+Nu9c3s9H=a~fQL!#UMT(;}ws)bz9%xRqsP(Q3!= z<@EIQ;Q#RdymcEc-sp|_P&~zcj)&)=joe+lzHV4_S$LW*NFr0M^PCQ+Qd>!XDwY)r>kSbe1?vAa)(2>7Cky_=G_U49oF?8kn#3a}8P3FaZ zn;#Uo3RVJ*5pH=mlUmJGVElHMcgqKM25@Ge%)b1$^GpVuR%;g5J+KY9(A6)kVT+=L z#>9lkyf2&ZERvRBOyYspb`mY6(5~Zw6zAf&w7fh-wOAZ*{L3Hv;wS@*R~4GU zas5<_i4&N|baa;zA9$$34O0&6G;h{>>!3(32KdSv?pLLn33$s;i20$xV*I<2jdL2Q zh9%BsvrT{WzpDm7Vmc0jsMmA1UxheX_G`|y_+b{wF4`XaRfKBW%{XEf`6S0}%bG*Y zmDo}{F*zALsNC8_xk289<9+z@;BlRhc)v2Ytw|mEblbbBcqwsm!z8Xt!&b*cEj zpJZ$dBq9lVB#89#JI@@~nKnDwk`JF$ks2#d`Ei9k-S(O#${GjdOyg&sTGB4n9)6@N z@G3cVtDEIJctzF$~b(ltZsWpD+*I3Gwn-lr?q-YcU#vn+C!V4V(hCW<*U2FQH; zuuktM`}Dlr*v*}9*DiAZJ4G=YIXI-h!}jOD^J+=7Mp(K?1?J#jPYN^~PHysdE$T<& zC`;i92?+2~CC~!prvpP!h`LVh<$Fu;xQV}J$;G^b&FX4lf4;d1REw*jCNhuAEkFF& zO-D>G)l?#Ll51dT?v$n`riqC%sUx(O*g6vk?uKQ?S`63P9Om~5ChiRB_Als&LoCH& zIyNzS(}BJ+O?b)F8SRhD275jGm|CJ^*Z1CkshtdIm!>dv`JC0%n(3LDB~( z}ZN#aN+_#>E2n&@hZ3yhpDw|V?vfWtNE6|muDpU9kJ~-)2>`R z5S|{zxDa!rS#`KsAnB%F(<*J1j7j{heCtZ28S>dNX2D8~M!S?F{p*5`?w@g;5AJeq zMR6HMdEJ&y2lHoH>y+8VjVCqS9cETyW}X@B$frj?z_Pt_l-q?bhx|jWBHgW?NE%R0 zyrak|x*BFIwESFyK|^G7Z7QeknM-hC|8|msJ9k|E2)6Qm23O2bZuevM2z*d8wKaR4 zALIiu7gp1VLvt>)NNvT2agyfI1eXDA1}6VrycAXQ6C}8nJQXEDHX-bp=}Pw7PArC` zXLbL)ZtMUjwYDa%oP-4Zt=olDntu26pObCvWf+T%Ck9@1CkK^|VzA*65wJk|f+Nf& z;lQp-pNQg)dc#u&L4vU8x%dlw5Qh7Y4$50$v57KqL!BQvecM$ zb}Pe}Dn_S7LPA2ZVc%N2@!0BPGO}BTpzBhxcI~d@3b8Q&h^Qxql=RRPnh1Pyb`K6d zV7G_I!k5DQ9KiISrGM#^cKxY8e`{_nj~{~9E9zpy7*;5a{#n)eZM^}6ZN#7O{wo9s zt~zQj^Simi6R_iKGsRN8p@@TXcXt;=yjfG25CQZAQ|wzqx+ZB(2I#N)uCA^Z+`S!d z3!{|R{xxfF@;aFWB((Jq;V<9jLh2A_*y6*$LIO}LVymr0^P?cn1MHRQu== zljgsS-I@x-9It#GW=#tM8mwzJJe%yecS*t6OUE5_6X)mWZV@{Qf!d569JpAk`?fAZ zHGETnYAIMLK+*Wppyg)r!s;8v{d>^tWc%g>sIf$*8E?WD`vc*T5juDWY(YPaLuAUfsuL zyKCwSPAgD!?Hw8YWDak8ROTuwJ0$qx-8lxbeiA12z>f}$%GX-G=*@r{lIM{e8=IMV z?3hZ8Rinr#!o`^;Hbo7Ca=CDW4+o*lJJ#Pp48DW@1S`rH>y@H;A8iYDlDR=Zui|R3 zW44tITRf8obF*qmrnCv~<~*MlNwVrgP5BIOTeAR^b_3H-8T?iX3@uq5Y8yVh0^b&zE?i5wD8BGV)NdNPFgy@ zH~t~@aXp+0Gl_FHB_RbC^V`&4Q>Qz1RVbHx=D49Q$UUyuIBWeVk53GlTrCkB-d{Qe ziCb0)Zf*%aIyzR5xZnyuT`GH>w!?--MRhxl2<@Dc6iv_81zPN5Y1O zKQH>eJVAWJW>D2%?+Rl+S*SFEy*^%w0L8DhmWN}b0bC}{F1YZwh&Zc593z`TYM>;* zWi<_C$=a?<&JFv&ix(+f@R~1%1wdZ_5r^@c6qO+iv$$e5ZFoP&cHlo#D7gtR=$C2_ zPI43O9ZXv(fBJOxhbi*yO;YEp*G$Xi;+Jya`w7nRi3xIyu+zCU2|)vk0CD4ThRT>8 zQ#l0c&+-IS(K+*i7)xdIhbT*#K0EeniS$J`De*B zgB?j~{23@9ilFNh^HYO5!28!QucjSTEA(Wpy0AiQlzsNqi=P^&2e$TKVWb?u1$)-#c4Imzqo~+ypq$waQqkKcs6PEs(&MNYF`X|ScGq(u^x_Kv|>uadLJa3 zl6xoSQX3eVgJ(>0`rFoSkEGLr28wk9-o_mNY8!DlT;DtQ(D%uK*>LRrvt;Ufv0oWq zdRt}fnaOf#Fd;quZ45K3tcr%t$!%)P)uOFx%i#B+ zx9y_rQN8?hbR&*$VVyv2a9;ymKYxg->#W}B(B#5p7jWJF=zeR}v!#1BfV(lUhnyZ4 zhknVm*2eEsf5Xg~dWcRj9Gc;uOf3>RqcwkK`Ta>i_&gDNCL z#v87(5zxV)cgd1d3hzB-8lGDLwg}XI;ydULzU|dec(tan+95;YprcW%~yQqG-@PQG`6!X$&5gmA9wg zcdIJm*qNmTq2#fdp+wQ%>?GDd4eB&L(IFzKQZnDV3sZ8u#QX56er`Y>9JH#K(Vq!; zIk7^oQp15a)P{G+SYs}KJ!(7^I|oO=yeY)&{U_vQrD{dkvSM6=t$g>`zIVD8`%l5; zl`YmZ7in-*B=UNJ#R$wu_`1kHJvnV$LRS7u(u!Y-U&4EPpFBxKC)qq}Dqn2zLJ~7v z3ZqxLdky81gq{iwx%4XYB-H2Y3+TziRZE37yoF3bi^ci8UFT(1#gF^@#!w3Ge~WD zJR?5dA0Ys}$EE38=KT9kiYkgPnHbZ}GSbox8p4wg!HqnVyP3ikL@qV^4z71}lONyc zAV5Ym?N{D~B3Bn8MQ5WIaf8PAMvniTx^h+2owv;%gBy<}W&GBeZVZF`9TT+f-GevO zLD8{U=f7?#&RF$1GZghXT1pPSIK@DEsF00%8XFw?a!v$zZatMyCJ~j5QuBw7#|WqF zHDi{{2zCl`4Zfmi{nP!-X06i?4{vsDuAeVFjzSu!w*-IE#V`Ku%-|MqXHwC1SCX_~ z5$Q5hOn72lmm)n7=PAvEEWki|O}qo?5g&Cz>Q5-)AsL28K3tB_oc$gc-nmgK-MuRy zvSJwsQMdIq<@NEL*!HAZ4F8~$UvyZ{q7-wbx;FLw#K8S{CD?1FjbFlJ#eCuL=Uf`U z*PN-|MbfB$PK>cn0Wv*WG62a`KxHWUe;DlOQ=7ehc~WW0znTn)U?3EbbQ!px(HMs!s| zK{VY{M%(oG%$_K=^bFWkyd=_l`-=5*dqdnxX&1Rw6*lvf>Q1}xmm0*1%UZsj?(iJ; za{G6}g$pYi1K`D;+vZnBe7z>j$y72aj9%I6zcBe>5}AI1U&uCOLJuP2mU*yR1Ln4y zhX09Qme;yz*zz2Dh%5y!+YOxE2HnNdztbIi0xUv@s#cPhk_RLReW;+Qe<%81P0`sC z=|COPb(u#gZE3AuVVgnih8s`QeFh;7`r8uT7FzF`bCPEFBwMVhZ=J^Oy#kpVmz5I5 za!K;W@;O0zB+R7}Pa)T4C2FP;1K@+^rQV=G6=QRX1l)C0U5v zDJOW;E4l->Jy}P@=>m&wRBO2KfhuInr0*T6ZhZC0#`x|i(VITb?Ys{Ouxll2Q4V75l zRV>a1o}hB0yi{a4*zDgm@Na2vH!jSFgv7K$Gi-V9HcM^R7qXWII-==j55pML*_G7( z{zg!&gW3l~EToVtY#6sp6w-^{YtSXNU1EmS7yGZZHjQ@!G6E8A{H#(5-G*nkBLBIh z{w3NyToSK!9gHs%Y`@@z!Su5~_*HYPzk!go%6>zKuj{#E}ZT` zusisnl_f~jF8S~Cdc8JP_r&+(;B@28sTRctwrdxnv%4lianM!(h5cF&AA-Ne=xOt7 z?-P(eGg*KK=r$2Z(BZejmpbNVq)B4R-+{6q1u5Tsxi&X4s9%dTZ30C;K`psspgT>P zY6Y4|c{FuxVsF)g5fc9+8pRfpz=jt%46&gOGI1hkTD<3Pbf8vgd#ta-qwk!kLZi4UEaKM=V#&V~SM3JCpL zqdh)E9Kb>&k)Jl^o?xBut0jh6=D|Oqj6Bdqael;@fep?RSdo$lUJJ@{zvS1U5d?OfjAbv+4n2~x zM8Wj$;b>AeC3Ao3ERaWZ{vjElKUg#5gshvT^R0TG2weyclBH|^tSi}smC$=76M$is zQvevIyCPKssJ$7YZ9A5u^Mrk~(AG|Tj+KqD3WGT0Cd@4@zq-e8q%(`6MWXlFlfg}Y zudW=s%AvXO)@HDRU@mnJ_ME|!KrNoyS7OcYp|7|&q|jdM*HrwQWZ45u!|zux?=fq~ z%mc^FiSBw>!E*05h@QE+^gy7FL;iK%Wsr&BjWpHUN&LBS!*I)O>k@Lvwt7$|BBf2{ zH#X_X)Z1Eb)Ge0xN%4tKU|Pzn(Y?8hN9pdUO!k1)^+HfIf|KuCXWyv;zd+V!wU8bd zEvmDJc|QDElEi5B0B?ik5+Dv~LRop45xXCa3wbJ_Ud+2^rY}{`0@E0*iAY>C3~1EiGy+t09`2N$LOdeqk}u~+YbUw zdl$Aj+F&VX>?GVQfG;|c=FbI(=vK{d0SX=AZ^%FDA& z2?7j+?00z!9+>n?&mW7%i7=UZr>ha{Rf~0StHa?0sVsY8Thj^Fqy-l9!PFK(J_r1D zsxjF)o>I><-KXR{E4NtmGLIj_qg@dSNiscbFSwGGJ+u=lIhCr{*uea!$Hzci-fcp* z>_9RHpjq!%zOnd{EVU#Ta%SO+VDp%2_iNvPfe+q>5%NT3knmtB|IQkzhW{;_Inm=3 z0zl2^W$ZRoaDFRL4om5>f^t;v5AD0|--Y#z>wOwK5^KGNHdG1(-oq&EFEGlg^J)Qd ziFWQ^>}W+pAFrWl9yEHRoZQ)0?Mn_5pth(zU-}ZH;}}h5%yK?on4?>#7ASr?d+Zi( z_?7W5_}n2L`;!m7xMvz*-$;hgh7o8L2t{%j6|$O`4)}YwAxNcNPvK-s;i6lD=O^!`UKWOfw+Nazw#m~+d|eR+aPgtG!(Yb9gYTRrneJcyK#zuPFJuV4YzLg zK>)xnwa0^8uP32Py+I*^ka`J(AeGwy%wp@yU(oiGH`WX*z9ci1wC&}*p8NHC zG!`+g=j7MhGq=xqJ%OK_S_~7=)aee|j?3vq7yN;tLoEF4{j;|2Ts5}c?GS^2w%d}$ z@fv<0w&fw6$2=nrXUb6-@m(qBq$z|FyY=ohbX<0!4jTh;T9$BbqwD+yEL8ipm(Mvb}ARSjn(2p*eGZ)QgRETE*rl1=4Ss z;zCb%-@R=pm;dKx{~Z6($ku`H^Hha|u3x+bhEk+6X7U9E+0pMi2+795r|aQ3G8G@k z-XDQzl%GlFucEzk6iHm*6K#Dd5-e2d-_1JtkTY9Vdd^Qk`xS03%|01jg?a{N zj%JWWv^Po*zW?S70YBJRr;t~1AcIeVp=h`wZUXl< zaNssmkQ~JhXFIoI(8mS`(@knFNUgO9Vrxy)os)9~l#!Q3T^(HUmy4c8^Z5Od$xnX( znJZ&Nh(s;{tEBR`F4yS(HO2`Ef3({pgydnV&Wm&7KBjBFTPeYcTLr#(%}Yu_KEX-D zcbP&qZ#SVm-#`0a>8({4Wc~fkqXI6p2@3RzqB5Pk2EUm3+w-cD3>j~=N4|+p%#pn? zC&x;q#))e<8TTrgmgML$=|1DM6;KQdr(ZGSkBi4xBy^=LpanW;N|T-?$;|dOva%4U zH@-KHS=SWtRBWEt))22!GZES^@^*GCJ`YDc5N&&fS;v3@;(2gzphNJ}>nic7jg6Ah zNP#LLmBUPoJ~6koHOrj`caa~c(*$>K#walIO2D`!a(a5pz7^^CuJwzr6@H;++(U!w z-?Xgc*LT;Z$+IxorQ$!z$|8Yo3WdzrPZfGjejI(wd2{n22s-2!@k=RhL2b5J+f=bg zWL)g^8#%_2EVaw^Ez)9t(@?eS{vK~k+qJ|}mW8kv?q}A0e#*F&%)XlVH)$D|Tz_PL zkk}e0(2*NPVuU@CWMRkP(&TUWbGtCwMe*ogspYd0_*o`#Qtb+B8OJdF4lMkicoDQ8EY~5006T=xv{-wWFisW2;l6xUzYOXuXFZJBy{K-zu z+bMKan!$*OGt{M*N3aah!n}#>4NLX+vKhTR8Q7qnq zBAYG0ouDq-JJG$-Ld#sg1p>>;o7g3H>R5IrV3=v5Ssc<;u7w4VNY5l4Rou!N|Tpa8B#*oeYx2PBBd8au2#KHIDU11`*5cz z4T2d5`?H9lgRL=XcE5C?lry+2qeAGIDjks=t5_Q&Kpd=i&dldB=Y*pm~*^HS>8`1_=2V zm7@*+Z~OkRR?^?^_Ku&J09alrU{dsyf*N5?((|gnSg5CZGn8BF%%P+o;!1QG_=18Z z2|U+5jJgH)xJsr6(Sdqu|GqZjXtXvmc@EM0PTqV|^q%GWw&4JY+Ss76OG# zDY(anVYFVEv&t+RV+y6WYa_wPq8o!L^aX6%3a^{?g|5?9q8bpAy^?H!1o^#d{nGcs z+FER_I&09yl(e>HeATBdJHC2RwnwsJU`gEc6*52{trsYjAs_@?k3VW?;6t<-R<3Tu zh?qvoKHv6=pm?a}jjf&!vcN(-USz#=wFkha!qI_+-^Ebg4EY1_rEx+jl ziHX6i$X)c4CMOR97iv?Av7DD$26#qJuJvltMMORR;MKffW89CQ?O5Vu1t*UTpj;o^ z8rrd!41dAJ=&FWl5rAO`Jd++JFO`sW<>nxC?KcK?nb34Vfa}~(TbVc9F zf|9Y|j5xab@?nOFTT*YL&n@U=el1jbe1^A)TUkL}T z%-a^CY4V;k^IhG9C$pi=&DwGfZX=z&>(IzaMo#-EMU4DPg^BB0RR?|sMAM!g=td1u z$)YH`AnnLP7P_u==4t!gG%5r{9|mz{qbx0FF!0CA87FCHxlen+93h5e1%oqBK_1;& z_eS%onKl=srn^;|iU(5daTA{@d*JjFEG~Q6BrEQOFbc4GHflE=LS0J|4>;Q%_rDhv zo!OQ?_MRoL-d_%;SOF6XY_v^q`?d}}S0prauRtUuiwZE+ur?@k79sd3=0)bZIFH zl-t&a1x~ug^FN)9Ns_*SDEqTb(4%ic=5y1uV$c(b4}`_Djm`{7%sSyFgGmNUjm}_- z>POIG12TP>RN3wGJGNUA%--Jh(lAWcUxUn>Ooos#mW`EL7woeo?Q*EA@a8`xz&FLi z)05J&edMaqg~Um^r$@fa59@owL%0{Cow56iUr%6&FJs6Y&aGD+P$zzQ7SvArDy%Hw z*ON!1+k;v<|E-<|Yb{Jxpj~=`L-D(n$SAuqZ=7r!W8L62-S1K1-EgeXk5oxI@gco( zY_YszBqR|~woIiTHU6A@AZd)ia)-pR7ZgV3#>^~-8zxUdQyd8M%Eq9J&5?p+Wn~Ya zpcG)|nWK=CXXuORE{kORc|C7o^W_bqQ!Vdy$Y?%*8!)%6pUrU0sLlt6M7M_e6rWt& zM7IkeE$TBUm^DRebMt+qNEWB~TAh2gT_ZSTTYnKj0dF0--#ww1oR^m;pwAvf23Nw= z2&HH^&2b6}j%SVwa2(wpy*pM_qgJ&!1Lh*%@Mh%6hUpM`QJN@Fz-*@s zwe7VQ(`&Sc)-hATTW|bG)s>RO?w@c6G)$5ufmiyEzqfcEo1Q;qO`h0+ZCIzagWBZjCYrotEHp4pRaN)_C*1G+#G`6?mDVykC&HVx z6o2*`loj6}RODDEt2sxv`xYJUlqb^gQsk*it)>X&k>rX~7zc$K<%^K3q$b6o2Q5{f zJJ?2edy8X2>xLiq&X*7Bvp;YT)XS8#CH+D@>v026Pgl~pP|#|XU%`ey9SnDyudz`7 z>%p}>lo|j`BI=Adz|yq#crnsDUuzYYk#XdZVOdKMBYaQ$x?;&ez|JZ6fjQX-G+i1F z%9^w##2x%!v+bRX6tL<+%Z>~u0+^{{)6*jdnVXQTX3E4>Rg-YBP=jM(%(F+w$NiI% zaOzLw!$Gab*n{w>^cHC8W5ro^~R8fFu{eKv;)Wr^S1Af zXtD~)a}RCi^_hLUy%Qz{M!jBQh-6x#Z1h8U9%I8zA^R?qpZtX=1{DcIBUJLcjQ#{L zHjRY$TF}QvCH3FCMSAKB#qQ`QF>hGdL6)y9M4UBoqTUs?PWVn%F1Ah;aJMS zxwcoO^F|L<+>jI&W|Ri*Ay)0$c+cfh^B(HlhbFM^;;>(eu4hGZ2`Ew`|dT;Uz3ysud`7s_q1fe6XZ(s){{8DQ> zyVIPL3X)u1Cz=u3OMpZY>zJdTZ7$m-^jh_rG~w4;A&v?vmUV<}->z@!8;a~G^C#ML znJf1+hCV(l>a?Sgn7IZ^#HrSKJ$2&PPjjfO^m*YDO4#yt7?uf#S}bU#Oku2-;P*SA z^J7wk!a*SQPAvfq<4Uf}O zDu7Fh?kPh9`$O(XUHKe=mfy*rz5xns@U4H$fVV?`ELVKC*_{J)+@sC1ym9K6Js8$E zHguL>UOgdAE=L`phZ0hv45aiotuI2EUgy%y=K~CGd-=%~hTRCV8T`(DX6e9k2<### zuO?gI5y4-mx9h#XIyjqYeRgK-ijM(f<_&5+Ty9HZ!z+*1As6R5>8Dp{6jNHuk&vB_ zg9MSdsW9NFF#7v=g5ig-g4nB|)b#ojk z%BlpdSb~ee%LHd<|)}XiOx3r@AR!|7y6>3k?*P5YLSGS3M zsV-4Y83O z-@N@B*mj-?I@*BR+YXMz#-w<4 z7p2gRLU2e%z(WSfycNTbYqJYe3H*}0ZSAKKP93lrYPJA@PxY1Vp#`X8m zeR7SLpq{w+{aruk(UJ6>n1>OR%X(r-SMe4c0@l2nM*(|_$Gy-3W6h24lF2l1v)WA1@ z4PbAZ+I3aO_RJ$AzDvX(gOhi(k%Qv8*K%8B-TeQ^daI~7x~^*!3GPmC3-0a&cMAk} zcXtgC+&y@3cXtQ@f=lD>?(Ur8dB6Ya+%OnW)m`1SYwx}0nzDe85KR8*bcz}t;XWn5 zmFj}W7Krb}S7?VZ|0{1e9F_Fho!Aq)U$@Y17A^e6O}z-|rXizb2%H-4XY>H6B#{l; z53=tE1TNxa-Jy9r9N(jLi*Ysr)zsuy@bU+bs)r5Oq5Ljg-CkV&hk_U#^#CajlDhib z7eEVpTBH%^JixjKRZi9R?lDWi!L$j8Qyf_;>?jWZp)1}uZt5%TC8MmFo(WV$exjOI z&ZD=RgkEVn^50x{4Uon9C_8cGxZFW(lF8t3G|;2$NBIG2jk?ZEs{csIMZM`rzC8d^ z)2eO<{-*e$FwUi2ul$gnz#`rkhrdG5W>pse%JWxNlPVhpzx$f|=rhZsMjfT+} zRRLLs8jd?WdbBjTq&l|^5pUojR_XMpW)VOzA)g>8{qv&~Z0KdyuYx~!^^p#qkzq8; zSmr%J`l%w-#QbYM!q@&;O`5X+bN(HIJt>Mq9fJZW7?*7PTX$kzqZw)^uoIo#yip< z$HX)p-s9yD?*7Efl)!TM@l9FJ<`4bVid0mJH6{;pidLQpnrIP8HnT^iWj%G@H{Zmv zgf}8k?#h_y=}1v|*o@nUHdAQXa?fPP1A?8Q(0a%5waebZ$yayt{bD}=L!u=#^icneBvKLkE}FYb+jjD-J^Viq@xS2?9V2U!EcGK5xkC*=u6N=b4B`Bchb#-ZG4b2M&hU=H`JE^qB*TLqp}R-P zWJVt!pVhVoq)ol}kJ}5~+y=7Qfz%VtZ`n z!!@Y-7HFGkYF|E0P(dc3(`n@ml)XH5)KSU0|6a%Q$ofjXftL^DAPd{qZ?=#_eGL?g zx;!Q5iW=)T24lYNa5*7KOdGqxu}4?=lNwhzRLGn=FE(Bp*KM)3O*o_KR9X5%&9uZ{@#sBuDf) z>KlN$5i$$@i%A&7P78FODN6=&#q59dq8+-HY5pM!i)M9N#1$bPrl!djY6eT?o*QNt zHXvLKU+tca(rVVre&+gcJ*zs78uK_hy_v_TD_fSI`;uq!? znix46sF-rIa`aLTo-ycW4}2Mx{j0-tv2xdkRwL%p->?d>mn)Cy#7&Vff9qMGnZor6 z0m#=k_uj=WI6DJd(Lilg7}O}|tFsu5(?uWZ8WtC73`^gTIoWrZl{NY<6;+A%s1#|M`^|Osn zgSdrKiN>+eW`_BBV7bY8Fky0jv10X7Vn&Omj~*h#V}RHJTXMSzBbmDLjNppLpF|?B zH$9Kf!}NGWPn3>|xV;?~MlbaiXbAvbp@3MDI(Zsn0-tL&0fQSg?{a>RKXT`B9m4>}`+%4#lkp zHzp?$GLkaYecmc?^dGco^rr|Il#RvL zDn~hx@D!6fp%K1}HlX$HxVE?A16$cWptlFdFj(u<6rbqyCp2D}>~k(}Qz0!}c3T0g ze}y?Yp>6WrR$30Nq3br7H_0l144Nynr|wJLYVV_U5SU#%lw4(47eFtN=cAgzk6HaD zU8*YIr`b`85DUsi`kqb>ceu^IAizev-?XsHE05}-3<{;{q6u9*Sp+O}{U*kq1ennM z6HAe-W%b~~g2K9iKAs@w_7mLZlL=%!d73 zUk*;$P_9ij02P1(Amq&C_e5`k{daGbM@``B;T>*)f$puT$SuO@k%!FnP!=1CCn4%S z9wm07Kosh@>ZZAn3x+*AzeQrMOhgR`RXg}kNi(rI0%$;hqmovKpT zb`1DeWmRObAI#S%Z6afU1<2zm7&6B^P12c6aW~cJ29y;oYS>DJ%rtm0kb$p?y|U01W_4K%WI@HGyvQ4@Itd ze0(r?c3=xd$}ib2LUFZhR-ap0jyB?q)lwNCAoWN;5GXE``nz!Xy_7|LcS00!*U))y zf1^7&=ij@(hmT%gDWU!$03Y8JD{zors2s$69W5dWnL9-YD+V#Pn7Ccb$AGYyf zi@dTr7nP&vQLU{QOY>I+BQ*$&?s{GDR{ur!2hVArvSR%=PSx9bOQKA);U!Btms+=M zIT8wHSNC9FA@^Vhg7wtQf;y(HWnJi038TMoDttD zi=d3%J4h+X^2p*dr>@S=jEq9L#lcH#`p4Q>}+d$)Vd^(s3GGj-SyBYULJDY_(qU z6@FdUQeC(U5d#@#;Qzn0hR`ZNv<9fhMgzi!Oag&S1Y+~PyxLkcK$XnnFokJ+z6FlUVD2c@5N|!NrR`G191Q$8UeNsoswAs;coX z=UMB^L(c*0%UJ*Y=6!Z=XKn5L|NepzmUs{FwMPYjZ-vp*o;A&(Kp&+(NP%V+EI9f5 z2H#WLulKBueXVH@cJ`K+HOP;w2QJRK$5r5Mbg%qcYB@2_fp`RkH53ACu(-Imp69h* zTx%c|qNLoIi<|#5@E^YJ`>$)x-R}QOp~%b20}k7m(l|apm(&tQbW`{z+(jeGo789xP<%BcEY@9_D}MCBgyxk*)ebWZq%!?L*m1v9NJvc{u_c9GsMt z6z;ciFTS~utPcX4vg5>=bfe_t)>4aYlQjUUodXmi`BPzgduEgDr*|68lH>5Y#o^)M!XhFN zY-ip#oh|1_5G%Ta(w$hg1G+*fxvlks#k@$s1Ek^tGaivP`~rl>wj5uuJ=8i?uMeb) zql{@JI$#d!>F$>>t=;KcV=W{eD(z(6quy}@(qz$24UbKxxoysqj)CBf`u6R z_H1TNGKccRofqle+u1WGF7C&#U%$`>my|kCfaHbcMqc%C-dpziv8ZEnvCSbjBno8v zlkF*XI{~c#jJ7k<-HPU8nEJ)2u01>Yi4Jg`3Z5n;=#2RLPTxupH75KdJK^MQ5Jr_p zclR0dIlkEK(1kV*AEnb6r4r?{dw$_g$sl0Itwg&h@8~{{a&`e^X~O^kgY_%tK%Y&F zAXe4Cl6d7KkYYKN7wNO{hiwE<=KCXbCiURqUX0b6RnMc~P>uBtzbyCm??p6UTCSq# zRTKY+A4~`Cp9yPjZZ0?wd>NIEedL`7jOYdTD^z-R{8F+Zbfiwb*uHN~6_XOo&hEeG zP(-FIfiZ#lG2h&ZlDMQ7P;9hPBT@4FYYKzoCp-I_Qay|cw171hOFFM6Rsb2Ktx0G|!NUin zqP(rGtszJDZ@B|$4+_PO96*YRfO`e_oiiy_2%h!Xg&;1kytO%BRR&h@cO>{df}>|@ zx|A2yK!wglU?wmZzP!8ydoZ@OatVmMNm;I~-VD=s!TSiDATyt};;27EE)F{C9BRgkI5C~`d~m|V83)rJ+3b=c6Vo z>(qe@XuIv)F$1=tBaSUU3AOtU*%btAsk100Dte!!M}(cCy7enw_+su=LmCtk*PHr5<*I7A!mVOi=u&QG6H$fcb@La5Vq|YLFzD)yTHbntMrw<-jjk1kLe< zQX0Lqv=kuv6JBLwbbjwRCX4RF?KcsXuG2-PNP{hKz|PABYt^w+LfJ2e6mls&1=A{Vto(7F_==nUou}R0h4ut{G=c@+ETyiWp4}Lz zYY+m$({;dl3^DKp?ApQrnY;oWV9bJ)Ck4>6quow-OU9giD5Jt`Fb z&=22BF4w#`Ff846>9$KrvCQo;4p4|AtIU~$jBQ`7OIT-+u6GVdlV!;5)}SArWE#U) z<)l;kMak=kjfmBk49HLGeoIjh=}5zhHL_1sA^PWn9EV<3N~os%U6&CWn#bf!)H~mf z@6RNB)~X&P>C_Ki6u)vUuqz~a8hLV*z|*Lcl|#Z!>oIXBTNV+X%x^_$Siutd-+^Hz62Tf%}D zpPbA7o~cUk?OPxbExg3weOi^8h|#7GUHG{RLITC-P-4e$`+^7s$rAAF2#XqM zy5su^PP6~%JIjI_13VQx)BH{TuRMh99DARVd4&oV*;Ln50Oa=wvf6OM?3|oe^ieSc zJP-*KfQgX%r`qqE!NU;>E6cw{g9aEM{&M1>Xc=7;*AGCon#Kn|ntrEtD>%&c*6WA# zR_J>nFNOq*LQ(i(D*;IDxuC)OCaniVg;KYRP27ex7pnhkIS;_-VLZO^W)_;mWPxwzAY)A11}2oD5(eWg*vo2Xr8bLrVkU_08Q_v+T0?g2N%;IOmM$ z_j62UGr5}f!i&}V#X*ZIVBc(qjD?dqvYz4lxe;I^ws0>g-*fg^alyGRln0wYCo)L) z3)o49wSM+1t*Q|gBd-&LFDJZHLJx{125RREH&_oZ1AI~FRp8(r36SjmXS6Mfm*_dOie;!U$Q0 zj{*T!g2;oIK?zk^X^bi;w`x}LR!gv6P;b4feIv8t>V_=EG{6kxDO8xy3GNm^D@7(R z2>NnFu=Dis^Mp)o6%PAvM5_?9%&%v)BLG&W*nZvwFvcg>7om>ZacKfg?$}koZ7|(@ zb%WJ07W+y984W;5It7#ul=6AObzAnvQmzWQUbW(hZ6pv6`SL)sk3Ea7ru}bP4 zrT5@%tQ)*b*E6yMJ>O?VuaZ~WS1vRJOQgGW-=j!x9Czj=Rzw@~v<-8DwxfCwG`E>) zR@oM9b1Pc50rAJoSW$Tvk#3lJadpT~M91wcRMEs*B=y(2q*gt^phg2Q*3^i-+aM4{ zqBnwY#D>t%7NogB1U@aj3&(0p^%G{9@yYxr`E5O4%s01~duvmC`OWdIVh>B}_c$+7 zB06}c_8+Iq&5&SrU5{qfM{p>hYZCJRm-oPb$%;$`cnMvKJUpOdTp3-?74XZsi;>j< z`l)r~ne1?u3eE%GLWV83A zq4-6Q=P_G*B80Wt^@(x-6$*?|>Q^v8OWcJfeKcR4qK;8UdBjTZcp9VBhOMO?Q-7`uf zS;WA9K*)1m`#aK?Tgyj(gR1lN6D_z}#!7I?uW?obXS6YxH)b00zWnRH%N!eb?AIU_ z*T3=Bv7Ba&$4(?r3nhU4E+&MD-klL;8$}8awqsrA_ya@OB}D?rm|~HXmFzyHq-cW- zmMYN1X6UcWqt=-i3VCY!7Axsb9W)flA_s^J={g|I|0);`KUH|q^FMIkH4tAF4H@G? z=q$$3M@lw`At8uwwhS<07~Qh7V%3G6?0+?hvi~M#w7Ki)Awdk8Mh+pViRj>Mi6v9U z7wW$t4=j2_G#dW^>E;#^&|(brAiIFYuBJ)f`g|y-WG*ryy~`|{4?RlIZNs#8z)}O- zTr03Us@egNdmD(n^$+79Baf{vRmADeyW$U0;*4xEeV7tVFXa|<&%RYKEz`7ENMw^> zJ_<1Vrn0fhl=j0$k}tip_f0BCi^T7-EX1b~Mz4ad9n>PTngL|6z6?jvR|VLgHD;eO zcK_#~$tYPt0WjKYF8N+2%WmbjArbxWuWLWMBMJs}_sI=VQrDbzkiF!F3+%j@SHQXZ zs|RNLT{A1j^x|+&7l+Q~Qb%JfcQ>yL$U~yOZBZnMmOcgAh0Fbvtfv1sQR4myj%6T zqsM@O=Z>y^h8H-Pfj^UbkUUgi2Io*b5lPY^QP93a=sJcO#a46@{f^thphFI(#+q8_ zL~Jxc(+tL6>HN#3n?`O1D~JzL$3O%Zz!>1FNU}#BA#aT3J7nAz%K<;h{{3T>?XAZ6 zUBxUnz8XH(9<%g?2tI=Qb9QS3Z1a5W_0}MZ8U1rEW>zO7H1d5<`2w~ugaxx3?iR_lZ=aN%cPNzpB#!M<0(BaBP;3b@+9Co<*Hw;UIL zyTN4u=2d=*0^A9Ou2}QGwp{S5VSw@5B`_!*z^hmyu78)08vGpEOk}Ifh9<=jw-Jh^ zXk+4`!f02ulyWJUwpM{a&~|-z{PBEf8rs+JOGGEt4emd#YvgzTd+F7#uQeX41~$R* zMz?^A93}GoBDs%bxY$4Sf5Hxk6256gR0(J?#(dUJ{A>S+V)HnkaXF=6SLT6>K$&N| zZxMCxV2942Tu1qAetwicaDJiFpFwIJhaT}#bt2T?p1tuaKi1(}nH&q!smA9B_Sk@6 zO0}4MCfYyI@+aIcikY8B{HTS^CpH@Es9qF+hdExPE8rlpkZ;oR?6PV~_(%7%=R*z= z3|u_!IE|nn5l|kGuOC1aII$3Q=7G^IC6N$d+}S%~+RdlrHcbiXY4r74H5#pV`7Siu z6Iaaj5Ea4Ttsph2rU^gX&Of6U4xj@HGXGDzur`wRF$ zhqYqapH<%;?r8+lL-Q3?_X54Bi{bV1cZd(aJi+o~{*`PJ^k?p#Y298PFvuVLuGnB- z%~|t7@lQ_;*k46LLdS^!-l=p^xCt43cN3WP(hMpeSt?;zA@jWfj}@LzPEIz!0;181 z`eX^j+WKZ-`_I2l?4P5fcLTt3-wQE=n(?<8OKP?St~!-M^n#%RpL``INIHdT6@w!bULbW@ub#VhevD(?#X%tlY}tX{orgKlEUotuTcmwnDw0^s5IZ1s zG3FE04k83yImQT(^H3-BBsL-2tZQGtpJcgv5X{bouBRQpt)XCi8JLfXfqevcbI4xd0Bc>dn8s%d10U+{3a5=?(Jg|r1mYbNcz*oi7Di0 zec2t5%B57`S%PcNDxaIs^4J1#W)pssDP5UE;oMuanxyswn0zL!hf*=_-P446RAp4! zR#0nUI9+?U3_dpNiUvVY>{kTSn=c@@wxhGQ%_# z7)QqX(p#q#~k zI4|Y|5~D;@&h|NrENWKy;#+5++iX77h05r)q=cGWv>gn2&7*d%vL$M@A5I)u3p3?0 zCq+w?=1GWSnzc3mW_)eNxa7bzI}oCmo%xl7`pWSyNE(mQIuUGP%NtfrXu31~Yt2-( z9L6UFelPfPf^e~n%xiUGD4dkktL5>HiCT~E^eAH;&}hVu$}iZVDK0*w<3ue-pj_kky0Om{22+}t1Vj`$vkLIE@jhotgnLD)# zDCaGEyfF6_QiMhUDE#K*1RoSR3h7rN)I8>e(-Q|<6Dn#fc6Z*$&(Ee3aF9V>1%nS7 zy$(~I@41PZbd(t9GTK`CL6L5$HPXbHylnww@)`ezJ>AhuCq0*dfirHKk&|0X(-HOX zW};;n+8pOu!5X0&tunN9v|Yg|B*wMy$I%Zaaj!&!V}d|1ONia0eybzfWOIB1fyEV3 zpGH6!wIzSU$V^i4wqf=cUW@H>y#}Fx_gN@y^}Fu1e)sWuF#-J7++L~F5$;UlQc)UM z*g0RW1(D>lToRp|hHPdfzjC7)evcdWai;4dH~)FO*3)*fsJo4%DR5M%_;Tm>zgLIq zzfn8*7nck7Uy$694#D^c2Dv>B?*vFDVn;A#Y(9aw6o!o6l zM(L$-shAWi;u5f3M>MTM2di?`aQZh|mMBar7j?}n0-)2_+Bk}YELkADPM9qF zB8}G9NRcR8(fZ_AnWc3my!O?(eqFw76s^yry+(iotnN1SM7J?!JSJXeXvwoU@4Q9t zgdw{}K=QVH5z?n^Upu<|r183IQ^8$kaygxMThip)06y=WG)IE@z3kojrnVcxw{Mq* zlTWh`-f_r{nt2`NciUy@$bp8wCku)s|rc^~l!;#l#lvxRE~qY$l>rHeR|c_Wi~%h`_Qggc{yRdp< zUmB6xY2xQEm?$|g5mR{E`O%w2e718GbGv)Y)#Ih3+Ft<6ck9RFqWBS~Pc_VT&?sXU zifnJn$0!|oZ@po6#ua(JD+99a)%UChj-rN@0V)54~W1Gr6M1^BK z#m$s|puAB$Gu&VlZ1x4qV;{RxupW1;-c z52%Z#HTGKtDIdQAzB6~Y@?dgmouI5FoU!uyD~*#Y zv|4G1dkuWg*ZC__9`CFyNB-D}Ht__PHHANwJb1H5A5lX#N>yD_K)1Fvs zKlI1c#x0KP8}ex@i)>BX&Q4wltk}F}G-?5d7lhu=u@!76g%@AO3C=;U;c=Y)9`Oul zHMh4bnqo)0z4O;4qSekA|L?w^XU>puM55Qd`Ccb*uE^MaoCPGaIuVas=1N?Df)KUo zNcj$V(ZNJ*PPW#Tb(-re6#5+^5q6GsM zPfS@1Q_@_j)I}zRm@S$PzcIUM0^?NYty?4=AJLbehn<@MIXyicP+a5b--6nD?|)l2 zDTqhT?nZ58d=~%g6*>XgZxM4j^;c?=Fav9-?DdN0Pa*MeV2_Fu-2~7jGXBJtND$xf za~Xm0&e}V7$No8K5V!h3wg}5D=|OiQ%#Al6_rz_2(nl*p&dJ<@w>WtFg-9ViR_oV* z>}6uOD>71<(I-Y`wfaL4JZ=$>0G}DHyJGuH_336_qm3oql{JF6p1;Pk{zNxNUPOMv zJxmYnh>e?PrDPZx6mKyR#luXm+r*$!fp-ZkjzA?9V)%MskKv&Frl~Omi^RSLZERet z#lD`~ToX)fYFwf0_N_Qd9f@0;{&QJEv!>ny8Mfp`=K(F*YQ4Zb$7?kq(DD`qX zA`wpV;tn*g--LT7(L<@FUvHDvOOzvjPI}e z{Y|Zx&q%wy=`Wsz8igKoiBo+@@V%X23zvoGQS+(>Ay&zw9SS}_74fl(4?4qOJ7li$ zHR~xgTrZ&X1Br&}#K8BMy0v)}z5y_Ibn=H8ojUqD;qRea$1Bi1((6 z)?tmm4zbr4>B1Pe9|<3$dp)28DEvSQr^_i%ew&C}F=P9TPy6R9veKIuGi^@X1SgC2 zp#t7_QQEmHmd*7e8&N;y)o9}h^h71Loh0I+zOuY!DNA@q#bQfD*vSWmNXBH2r%n^S7p`oK(IrY((;Qs7$mi{Xxg*0RHK9XIbdgebU)Q=VG-NP1qO2SckykA z!G-rYsbxozJbC3R&pKY_ev(|B;lFvE{uxlRJo3Xe=z%dJ=-H`RjmB8e#HsRBWi%bo`FBmBU+d(!ty z&4>TcayP`PqK=Erxoi1zVg0jkstOUXhrJNCXP-zzAG8KJ51lz3nGxaz&?PKC+*G&s za<}mKYCTO6q_pJhw@pnC`v#Xw7V`HCy1}%f02U*y`uz}z4d6Ja$^%Z?z515h$3F3Ow z|FLiB#AnVbL*O*2T^-Lq{gyOF2>dE0_6ZFQZM%sbR5Z@GVm1jZ8CGL@;3qVoe3!XS z!gE|YW1j++1Q%H}c)O=pb~}0%&n3aw28UY|@rJaZRGAJT9l>4pm~g$L)}|3;yX7}I zB{IH2)~5tZzGVPWa2&SyHgoyo9eTNgHZ=;V_usKY<~q5svsqw_Yb1ik*TnTq( zRAetLdsyu5dTfddFD+~ke&*F`$xr2r(Nr+yc0sUpjlf0j!kWBpjW3ABTu>!))i4A{XuA?G+X z2@tyU#<7OQaIWSD0Mji*zP75Yj_Wl0S;-7Z%ighnzOBw^?qfAIcUf6VY!2F*sGrU<+<0h?J}EB0r*mGL#mVd;eIg$_o@h@# z;9)oPZ)!(Qr=r2!v6#v3_O#h0Iqu(aK&t>HKEo6`~Bx%`M5{&fXoM#EtcyIVqu9y{s+oGJv+nBfc$|-ekJBLef3gC4X#b zNdP;<+DMQm4QI5*e5=#pfH@;fias)KveI`8Ai}0dK7DI935Z_J`866mN1r0_zO(K zX#(Dy3G9AWHP3m^!s^LGbaDKqUISADZu+>g#y%7*(=G@y;q{6``|(GxNpAZh-7Lf7 zb@~w{mc-f7HNHtjwgccnEaq4(-WNKQ%mGKW=;G6UP1cca#y?FQ50*h#d4DnL?S7N6E`#Q*PB$XP z=%~3=LousQ>w;pfyRUVMOE4Cg?27iie2XVYf7y#Q0Y8_2BY$ZN3U-(Td5JPV66O&1 zr7x=R{A+yS5etA}kniZ|qAx*y0QQ2)cQpK*$6hmn9Otraw5<+(oj^hM>>~((2VY&} z*mqO#CR~M8Il+)M?<%HvBS&YTc_{vGVAq%|-B@0}@Cc;_s_i#Q(>OT$@cF-)qdCn_ zat%@l@8qV$Wz^1Q+B^x|TI2p>r~RdCUp1uPyb|+t$J?J`F~tsAXyvqB zU{WS;CoIqkHD9;lA8H67BiQHUK2*qx{}+jH%`;kj@`7<^mi=7F{=4ovfy7Dn4T_)j znztcg-m+|LZm3b4XtyxIAJICcu9qYUAYij88DE)|4@HiGwV9$Kk<_pzSs-Ko`Cc?O zqG;giMVnT2I;YUslRR|l^Ds|#@UgE5LsuN_>ctpEsA;VXlXS1fuMejO_QJ6_t0izz zya1ChEF$9QeE{vx&J6V&L)yR=XK_tKBm~M%n&+E7pQCE@XuzGv5B~=B0{sZnXgaoG zkBGVx1Y_H%SWJmvJK>E33@43Mo^Yvp=K#j=q*jAvJ-1n?lq&y{u*jI*%T}&O&)TL% z-d3yYK5%i1SSt2k8I}zV9#zGX^5B`8JuAxdczl@bKkdwtK4xR-dM!*(14p6})!OVP z6a=vrWED-tGlUA9YfOtrWr&9@`kXV_1;%HW);_71aDEr<_Gfn zHw_}`*pwS6;;V0YpC3|S93}=G2(~w)46e0Pi*|>C5V%`M+b!EAPBsE^?u?M?NPShO z-zw7liECx--vLxWr{i+Xmn_y7t;)DV-th0iMbS6cRA_3pw8I8IF2;S;5o(ix?`hc% zyY4k{nFPH{kVTFb8O=L`&aG-{K00BQMi($kc7IFrGsSBG-*$UcnM>>@l*%5il41s`6;TlkdVY-B0&P_8hXZ=OrZ4E*5i1p8KO^0+>hrBG z6v*L~xAsc+oy~h$yLs>1c}H}!kvWOuh66U|?Ci|tK z#7OBJspk!H1yR?XAg#dm`j*#5IAktw6ly0HY)rlL*BRnC!Nceg`koiTzG_5;6hwmd$z4XQS*+B{6OF9*^ z3#JLx6|g4LA2}@zyD1wyBGQ$=eTOa7edRwD@1RX7-dl;1xKRW1sD7e*Q@-__d?r9d zyywo*a1HvAo{q<9yR`E-Vb{Fvz-?i5HK$^4XD3lT@7<9-YR2Z(nXQn66a^f0bacc& z50HHUpT`O{b4&R4)fl~Mz`bJDSy5CJ^85ESYTuyVA9~e;7B{@ws%mP}3kM99fRsN_ zulj!GsZN6)IFXmP1E!;~v2kY3D<6fAmlsg*YtWBNQHJ&b{ujlC{odS*3ky=FriJ@U z7VLTR$1J!V@CJaVIueo|WD{VN0ni)A_HJnFwJL!ZTUuTgxCfXO$|~E@cgH6uV%77; ztUM~%!*x->i?uF#Yk&YAv|crpO#a4W5W+*})UoE%fJ@8k;OdO8+DWQgNoD2Ox%aXS zC&1~mwO#A)>gviqva;8@s;a6Y>ULM`aQC<8I&b$s&-OTfTeDkpe_s>0?0UXG3%_@3 zXXA^?xL@sV&bUA2;rWeX#Fo~Wr0^IGvCpfsy2e);cul-1z$8_ncs$1t?y-|MN`;Ik2h05=7h{F#NR;g}jwG>oD z<;Z4u?fTxgV#A)df1JmW5YY}|B2!7;@+_KL`Dfa_s;JwZIv&s)_Bo@wHoZt7cKEr;V2*oKY=OMHB$@*cbfs{m@~gJ}aS{LeQtSDx}oc zjS=sAo#j={5GE(~Lok~wM{0Nbn$LtOhRwtzExgg^_sAg%81T-vEiUP2>+PkvDZ7zu zJo85a1)f4ERZAVIckdjCn#Dsig;ysh+RAWiQKb5uFMs-$_26i-_WC;YL6-MdCzA`} zz^L@Iz4i;GF-s&qZ%^;^7yW{0Sq1gyx%Ys*&sGRgY}_r!n%q$6QyJ*N?|f>`vd#Z| zK@Q)#aj2k~r`x<9nz538|G6{TZ+$r$_}J)!?AaNv_{#9rHq=}*4wnPZ)Q4p!?p07^ z=7Y=G2Smi?Nu`X%lk%r)_pNMU=>#cgs~ChMyz6RXDTn)?61t6U`PclhL#>)n6Q+zHv?}SR*_QBQcgTe1>a(Q5qROb`1f-jnw zScl2=*!Y3RD~n_cK}}Rg0~+&|&}~%ko!5dZuIXpT>GGEQqn`0P_4CK0kEP?Iv+Jh? zeMc{+Z!YPXVMF|hzU1AJ>7h)1c5B0*yI1~Hk1Yp;3n;_-RK1q1Z{0KG^Uea{yIuqm z-`##~($-Uy{{}Vv;r|5Fw+r7Io?b&C!z~q4n zM&NXkUGTa*jP8$pR4(h+?}>nqUc=fd$DRKP+`j9Pa*)WoVqYkzcjNQH=FeK0=5Glt zw!+XjTAhL0*=&Y3!VxFn= zk5bhtSH6u9icg^M&OT@aui6!tl>Aft3`u=*;V$85F0p8MTU49@+De9Wf|bylpP%=} z+;b4NwXMuiX8XoX!xnE|Y=XY|v{HBpVLrj7eDB3@RJL)126v=EG}IP>S?K;YrZILr$Y~m|C%)dH0KrA9I zF24Ou@fZQf_U)^4L(qaseKEwlPbrDhQBD_<^{v$wWJkQJ~sK1J?6F0JBSSVq))JSz>Vgzda-<(iqBd$RQlhFtLiR4L|@ zoIfdqH=e%mtYF0-q=Am95Hjt{a!+5qYLHId&BXT|WrumfJOUzZq*AuGp&k-00Sd04+0?0^WY-mXjH0oi-H^i z#<1cx17vn$2hA>&f{}xdJ1j*TM!x`H;F`hNF2mcTG@hM2Uu;Hk_IYYy#n93KR)#u& z2cIwOPU*5~YiWs?A<=Pp6B3JkVpSbdUAAdh$Xs{uDhH859k6MCQ&(62H%TCeiG`&M zSmn5}j&-`xK?UGnVYILsCG6Yl%VD)vWr3Nt6oI5$p_>5=x1nw`z1i=jJkQJM$Uot&J6++&Ek zO6>N!%4kQc8u<%#&1NaF7IF4OD(cQdy?>0E8NYh%3j@XxkxJBo6+}Pl7k4#R$KyS8Kk3^h z-QBRgKf!5lxB5Xp&s{lO#UJ_|3RjeFW;YhKfk!E$21`cH^cFjFIF3Nj zmCB+C(Q|B8AIf--n}&#zfBBNeL|ybqDTg$^eCipap=j~-xxHe}uxbvgK-sJ*b+_xZm5&8pOh=gV{=J1k$FZfa z;ld-s$jgm1PxIeqV;3HhBD~Gu&#iLdAgJ4702I>cd_;@zVf{h^S>t8rbX>~VAn(2+O48cI(yjWbe_nB>! z5Ht2~Iq;4!#$@!%UZ3ao8tpEewuAkfDtR1?^6B1B@~;-Tt#Xe2=OT)HSLlccy~#b^ z7jK5kyE@>7(fnQ)N<7_ZJ5r&n)5UEqlIJQa?*(ZRVS{{c8PHJsixd?_*VbnSih3qbB2kh=78m;CJibjmq# ztNHnT5M0`SBYle%EG9Z~GnXc94MwX{OlOZ?-6RJs{IDzV_pNEizlL5Cpys?0Zl=Fp z-uJSLvg`ltHa?3<&Mzbox+0CXst=+A-e)i7bVAwM?#4O?Xo>*$N4Ac#E0rn~C-?7p zB-hGd5ohsucBSn0YT?9%vI@d|G9R0ePK)GDlY3Txo^JJMz(Mu|jA;0tfgunec>N4o zGCQlT__M_eA!D7W`I?b1YT63EIPA9Ai=>@%ky#BU7d>jS8VD1nWDz9WLo&6@?fFC8d3^4mm-(DWG-zlU;F#FCylvGr)o&i3pOB8z9DSZ?fbaXfnBj|Z4KP&B+VIID-_;lD7fmGn4PrI;uUw11klhyqtdVmQwOW3DT-0T&Z{dGH>UbWVO8zUiDt~hEuiB@n-_< zi+1Y3)DVnE)fh6&vW}&=F-5peboX`Y#`Wn6+OPbv^Qj(>dC=3Jnrm&;h4%-WIW6>G zGrKyF)(s9*RYsh%pSU7~^sq+KAMaV2%+ibhKc?O?E~@W~8%0_aP*Pe6X{0-(ySt@J za_AHgX^@ug?(Xi6p}U7}7@B+d|DNaG`@%QshncfEd+)WrwMM@#HF`Z%x9C6B=F`6- zGmSF@SWzU2sNZ8|4(vq|Noj+eD3nloM@(A35Z>`EGh0h4y)Pe4lWH2hJ5fvR=tWw* zb(a0I8Ifr+dvA2FsFUIpqQ9ieqqnZFs{g<3_0W#m?nbBx6Culw{OdZk&H17&5XDb^ z`&!{@(~c0bA;I!K)y6vd4<&kPAIVVbmUU^B|AWuGzZ0^iII|;liMFdi<3~MlG5?hw zHf`dKu4hL9#SO9B`h1bC~q zfnaIF&mdGVyUE zn?rWs_gnZ7_}pkVmP<}@fS9}4Hb5a(tI2Ay#TD}UQ78i^n8y$Yuy(Q`ivov30N@K+ zEay0{dlmrhd|AFbxgE3RrYF31e_)OnonD#`y4K*KT~+Pyuio5px{#3XN5pt$*O_Et zkS*6)a34w@QA!`dM+@Ux&VHk2{IY5FGgW&#qL!@Kk0nVilt?m35DU=f%Z{>yJ5X<+ z;8UrBP;sq4cY2uoiT@weHnbh~bSk2q9$sXVu-`JtS>Ut9M^DqYWA;Xh$jf#$1KR1w zqUWbcz}d87Z!(7W$iMSpycRAoFhtM5@*)M5p29BtXUUV^loU3S4tn{b|*aIFOl46b<=HoyI8PVJc2JJ znzEgl49|sE0P>74kzV8Vo=hpns9juP+Av3HM&~j!ofpa5fvOQ)Cq1)R6hxN`U6LR^nwqWhcZz9yL z(5|JQsjpYR-nW+@BL|b&;qIVn{lDsZIV{rA9^p8@L}&QdY`WBLx_`?o;exVBU-w{@ z{a7zUZO6_F<=JyPH0!pYOkbNzDswB5tNugbnJMP#yw<)!CzwtvyZCaItN%tXU>#M}M& zqrEOc>gA)Iv01^!Q<5$3%dC`Tgq(w^+1Yps*5qgbI$t8=EKn@{D48gU6G{7*)Tm;a`wu|mWLi>6BT;C_Git!GVI7D z$|Nza*Ypp~y4;F+Hl`}}p|n#nGJlfv&Zn1HuO0ch zJImc)Cif5nNnb$0z~A@_iKbQp4bt?e92-9Dy(}s`x1QQ!6dTpTd1@2iH+o*PV1ndw z>ggM4*+%5hE{xZfsOUh(4AY6}REh&{s_mup9N4Hw9N~x_XIe^rVXTMab5R*5kV0+0 zyWwm}@=fHPjnOO`khTHHm-F8Zfj;;BqdT{)Vh;__}jQV?(u6yN$GtD zPAb+eu%_dfWRS4DJeOlA1 z18vn&GDcPj4*~4`c{KrB--ig|V8HlXQ;Wbs549teigtAtL(A`TQ@&}hRoHBrmLq)Q z{%^P{Y}B;dv^tz8&1YjP%t1xxJ8!=RuvuC zfJI@s5R#uq|2SO}ka|p^LO{ScFXQbl6gb*3c4G*ff+SW_FN3Pu#HPT@>3z!cbst9W zp9ha3Kk=o_;}LGuitwmG`UOmtRXDNqBQbTD8DFVD7;C#xo>;Z}stTIRF?7JMBW4yS z?XDJH{6l-IlFAuyjdHOaOZ-pDe15w+XKsPIvNzWG!|K7N{qT{>%oJ-a=txv7UAW?d zBhE1@CbPAxNs=0t+fOZavp$d1FE4f9H=71^2cRb+69h=tdbtJblbUm&-R-T%#TR8L zoVvC5KQt@#$nkLUb`#CrfX()E!+jp_W6FGDw2txPR7b89_tQ6%Q6iF4{HMrj07dY> z(g!}#MsfWX^U}4A0w>jq?j!^dV1sR>lHAjbe81;UoETh@?IMJn zXXI-FYSN|_q!6I?Ibu)RtKl)}X&FFP;fMHdlq3kdP7%FNq7Yn<4`V$UlIbs^!zU3{U#=^8#Qf&cp$b`${yMbf zlZ?m6zL z^TOBr_*B)W*GZc=yBjCv>FoIf&Ew6e4&qhH^sZogfYO=6m0nI+3~+_Y{SIlf-U+a0aWx&IFAzD^8yz3jZZvrSdnZhI4n7HP;qFlX8we^%}#33I1EH=Ih7~P=(?pjk%Y%uqMc7`j{&?| ze!ix{%XQ4yQTW%!j`~bW@P}Lu+VaP*G#`cRPzkHIJU=nvSUf8$!Ny>roKS;};JimM zxS(_hR?mvkkE;wabKBpqCT6ubR`6)BeY77xmB+XCTkV`0#XP0TN};O8;upD&n-Pmh zX=TMl^-yI8DT-j^PEQ)JDOlO$tS*OTMslaqC`yKrVkG~}?_I3VzvIH|2YIb>1$DI@ zT7@rkIjh&G7fB6bg}bMFJd#x*2sCxS-BOi*2cO+(E1MKAj!wJ2KMp-}E(5)9E8NT4 z2;^IK`Oa`ajP?@=PVz%z^$)zsA!I$;mk#iAdR=-&@w#CD3{~&>xRqx7lT;9(y&0Iw zo%~U$WaBJ0y=^(&^MKeDNtWs*l!w|b69ey?TsQkb6k(X|HW!eDt~$xN=Y_*p)w9#;cZ zuI1tiwxbf~?8nFA()@ocsIreARM;jW5BXK(hN=>ZwQDYv|P6j-aftY@?FYhzhvaJGYM>9ohKr}@vTHgq&2uBG$O zV8l>>USnizniW_i0P6&*$vlI6PoDXj>X>McT3RSaxJ_f zNxMncu5&p5dhiGcKQ>ioAnyu1f z4*tl1KkdxPs<}VraiHN7`CMm}t!b=Er`Z;hj1s}0gHI$hecUT7J_)a7y^IZL46Mec zqo+9**$h|Sxqx|}tqmmn1Mdf!mr{5#ky_c>J*P*rn|>ha2wLdc7xg-ZaIVQa7_8(G z04hwjsU~wY7n#(?As5Lm>%ZqDK?_q&icG^AzI0QbXtazzk;36RB&3MLCNj5O3vMtw z`l9NXzDgk0|h!Jg&X?pDqJBPPlSAZB0aqXFtV-cR)2(o8fq{Py@9SRNc*0-=nc z|5Qo18$i<4+;&=TZKK&;t1 z@&h$d-I|hbd83kp7fonwB{8`mtiii;Qi`o=Z`j2JZ1?cY%m~M~s%_3fk!eqgw!?r% zG;Yf0P866}(+=o59^UCM_J7=oK2mPvKP7}0>^QPJD=ij@l={HQnHT8KfV^m+&KYqD z$bkMtp7=c}yYksED{H0HIRMR7LE(B}*S&Yz5s{Q)X9(V$o#)W$<08qz6OGS|4|C4* zAN)3}<#iW8MY%%nZ{G7;@5CS2G4rhBK@;b*VZ3Np)HC;shQXnbr2Urm5BBP2B=S5_ zul4gg;?L3$dg!DDi`~p_;0+$wzt`^4UHgI9(o<@XB(6mOG0^{|mWw6mKqLw-D;qGH zeFJI!Grl8!`+IBok1v>Bl)CW_3T`MHc^L7@qSJZN{YV5?@mkbPQTuFn;;Cn2wII!U zG+(8(KQlPjC0w0fO#p5A4Lvx9fC=wSXSJAg$KwF9{0|eKv8_y@OL#y3?|1abu(-M8 z=Mv6;C=dH>6Gd;88D1ksqXKo{ygZ&TbNqFdXivo$LTGM)5uzeke;6HR*n z(D<(()-e~(ndopEg?onpi&W9xRv5-t6wiXl^G;H%y)<3{-#M1*MAcIjQdtyVfbKM|B5|3Y6_@>!oonRzjI7%WcbHN8sk9B@_U!7tFz_;4eSfXk}#8! z-5R@4JA;-33*R5CcR-&o##Q@E{E9o4A@C$z(K-G}NksNxUCQI?&$}wQ%@aTAkDj{+ z=&}Tjro&{85eiA0lU@C_YY)2Ve;pVny78@1KXIjnGct-}akwp3eGF3`D4bi2oFi@W=P zOB>R?X!`^tqw^)xI>4ZVy4%+Ml=7xQ&e6! zazL30AqA5;^2Lv*e1dHFZ)9+ZWv(x@{A7@qy)f?}U=|tUe{+yVD|BwJt*{se^9BY+ zQbbTix4q6Gi9JdkcX=FG?KJl4?jc#AtjH z1`EG3@Oo}slBc20yI{B`^A*>9A7LX%VZTa!S5grCeWNPQC%6){FE2V>e@(PLP1K+N z7%_8saskdJpf7!;l}-sb(DroU1gXxNSC@~}^UN%bzs8xqb5euct+J-ZODJ9q{r0}P zR>u#_+q82cnkZ4VHM(LHmtpg`C7yT1egp}5h zqT~a}V0LhsZ~Z4GZL_LQ93?Sv9rxtMDqhjz0bT>Rg9=sW|G=qVULJ zvv^OQ|LDo5-yjvyVDIrPnv(96rN4wrUz+9vJ@|m~95^mq5!Y>>5=b`6_~_VgEM8^V z?&%G=f7?uDmp(s|ycUmkp9+ZR#%rYS0H_+kQLx*4r72$aT=X4lOcoU?v$Ov(`zM&a zDwl|3dbcXr1(X7nKDdv>vNDZzBXx^bQz7d_Cyl&wTj*&*YrnDwPRd+kC`7d&ogTqx zt?q(c^}W^Z+99rvNdnQbc0&k~ODSHo5!CMD9_R<%hJO39gq}_hl-LLoRPqTN@sRkp zxL_YJTT>zTH=+t>01B^@TS7g?o@~&5SaY@s!*WyLR8qv7R!f8B_xZ%7*9Vhd0}~1A z`8tti)_`$y>mN}bpIc7E<*60yh;LtJ`TPrX#q3t5(%XnpSdj>T7WT)ZGm@&D1A?kr zqaTe6ez>{qH<87O#lz}X3pOB4yhjjuUapF}NA5h8tzA@dKR6={hP*T0SBbIx76=Sq*$a_%0B_QOeOOrk2-hfc50Xl;cIx1wT=KpWFP|5M7-p zE%Y-2zZ#N|ORP};JJ9KR7b;ZYSPEOqvS71`KJt9?v3XMJ!1p8bPyy@gx%RO0_;u&o zcZoR;HVr(+3tJU=0E8sImx9vbkxnKu>>Mz~iH;-WyDJl(|=Zy2`sH(pYIr}o0eyzF@39Y>_sQPS!I>&9sQHm@eQQ z*HmZ!mS$fWKX7x2%0XMT4M%vKZs{%Go@0881WW{|#d#NJYW63jPz$vZC15S@!PVh2 z39S+D^55ba*V!GVm_+CB4pB2I*WERCH0?^HLkkNHc}cvA(iFgsV;f4cbsCp`k@sw* zRk|8}E7u(5lGMHpq##BOiDIbQlNWAD&dQKV5=H9PDO*|Q%r1+R7EYcnbbc3EZ`)Tt zdzcn}T$DvaT5FtoDMs-1H@cC1IrU}Zl>702C{4U3wzv3coQB-AZ8V$NtdLJ$UyEXP z$DKjfQEov%QMCfNf_W~!iBVJCYVY{)9$O7POD3!g0JfQkCAhFitEX!5S0B8Ht8L=#i(}_k0dQS}xzndI0X&OZQ$RZ)^446yMH`^?qjvKGBzuBa)TN z(|21no;&7bua{oxNpE0IwM|S&F^`ow(D;S_3LTPi%Ogv5yE}i=PALua7Vp&Uz;%=h z%WCiqL-Hr?!KTs#fXW+dx|S2`_K76DBb-VU9;s*C$jvQ0-&#@SclxEP4`3|&4%CK$ zofk_)DsD5Y%tdrKT8<}d3w?r-xJF#m2#0tUpO1M+0824RzYG!}?F^80Ca#Jlu;jGu z*5zftycaC(h3f^NzhG6De~fzJrENfDp}3CDvbhTxm4phlW^#Hrtoq&CVsg7JfVLXN zRBTlZxF0m!tJ$#QEGR4lvkYbUvHzL%-S+G9FTq2sfU^sL+HtWB26{ZV_M2yo##LDZphXh}`X%+~4;`w8*C)^KSYp}&7gUHzhD2{}d7rULV6go*RfD}+&aLrxNU4huE6 z*?BlTxB;SyP4(h9elg>Dj7bxz((+kXL~0ck3Y`B8t9B%DeN7q9v*y_z!D#};~o!&hOsO#DipXqo9%a}BM%(W=Q(K%*sC4fj|Gr{h?Pt;*r|QLPiit}7lKq*z)E zL;L~gP#<3_(D((oaHV1x&2m)sCxA`jUJG2tKO3!w~VdTlog+r*_yF}`=_TGG#kQAX~+yF&A&<& z#Ns_XdsXCy!H*{5vmNH`C}lVyntxJ(O?Xl4?5|X-aXAsX*9V486;ogXJ+`m%RK%H8 zIU9%lOnjhQ#hD2=;y(%#&OPt;d#f~B@8R;}z7`M{vjz29tK5$hs@Hnt!jYBV^;37LQH{*<-foOT&d?i zpr-Bk_}#hlmycE0WpkH;uz`5+|Exq*2mxl{@xR6Ci8SDa?!DS)k7wjTgTyevUCH?_*xx z@_alJll=iJC>ASZXrjj+*vm=TPKR8=Db*=0Et-RB{d#fDgC*VExOR4SwuGoSG)jIt znD9y{(fq^Qpzl>Sxo{CnB=_I|vPlOi8D~G!P}uM?q!%Z*8r?o&5!8EW230!Qu^qz+ z#xsONAgd8#SEfRDZ5Cwc*sT~CJ4=LUNVz7to{L8-8q!Mg7ng04H+nhTolB^YoN4 z&wwWXJW!oXBVE^vy(5}sXtUNiZPdf!@nWM#UjYv-*exFSqGs+Sw$ueU0Z(yB=*Y3%lFp|VWX{c zHK*@@7hLybL5FL{vHb>W*|u9oG;ZW{bhyVH517f$jliY?kov6{pFr98h2M?xH+60wf%pl??{yCjPf)fMy#!!4&)(MR#yX)ujMHEowX=;p^s@sDmYY#b64`wx zMJ;XKmyeAYrLj!1;{4R2uQ+NEQ#!vrBKQyZZ&!T|}3K5x+(m&<w zLPPFr6Ikk zkx~(S`d+kx>bkH~3OYijShX648#_nxk~HmYSt(pIa(!w>M@H3o{wP}POQHDkO7Pu1 z;daidv{3;5ijC)fGByQ!o=a=@ENEp(A=iWI1AOP!i~#XfjqeY-3m$IK{&z@Nc5~>> zckH5lUr=}pEVA#0TXkGr(S&S2hP~;My}bHO_}bN||I`y~T_|kl(9+TX{BOmOwce|O zlrLcBq}!?uv-a>Fe=-OdP}Bw?#Ar8Ad@U9*1(F5mvtrTLD#*Ov~N zH}5dxMA~e@jp@6#CWgoforahncYK2M%f7`+%QGdQXyWC1_)3c1#J@Tr(8mn0WH%tO zVD;V#DjS?rcK2%P=G2=^at+E%uG)!s6%AGtgNmA zwvc{HCmZ&~V`sovQCeD>=7EooUry>`Abirsh7L1Pl-k4`}8i#glst z1OHJ7=Kkjmk(HfYSO^BblQHv~F;T$S0$x6n<(Z$J z-iEfyepQZKYi?UT{4qH@y9;f#W>3CMym3Amk=S}PJ|)*_R@r>crZ8@n>7&Fk^`;_C zY+Y-nTy1`JeXRVy1`)4z7b7F1$d=RRR*%ir6;;FTQ4c5-NT(FUb#>EU*dankAy+Xi zzul{FR0N*7(fP8ic$gqnQ&)Fo3wkp4PzR(t92_1#xvtI3%#fWvBmpjtw(`c^UBK}% zJ2~mQ@bl(jHJfP;pMb#Qan*MOFn}O2&xMJRnO3`f2U&mq&sI`iR(7M~0^ysW1w10P zWVPw6&R%NB@oP>h1j02U-95*E=KmtY~mJw6-;v zTJF)NYTM!x$;5FAJd*9}^T0(_^Nj*Y)*9bVZVsWrg@Nv_`fKw8V(K^K;h#UOEN|!Z zi~H6GulgX-m;s-f<|^>FaW*;S_|@X_m7ALzk-`jkoRuBAEB?9r%~p@H#*bl*rtHc4 zM@R1$|K~Viom)m0$+svd+pXI}j<6RcABLq95bIo|7-N&9Vb1`vZ{kl|*6MjqQ4#&q zdC`GLe1_EBVVu+YBx|OdGVra4{!rNz4102TL^Pk0AV*!OJI*{;S4Yt7n%=D8!n_6^>GQ9VQ=(bL& zD8#9r*m#Rr-_ijEPusa*UHvIhjU47)6HbsE_{jr!UV)->;$MaE6w<6Lz?x#Qu_+qa z-(-K!7p3IfsV^NS-~vxiVmLm$NvQ&CCHQNn$HN}g3r8D@`k+z{E*_QJ2b|CUUvGecKAoBo2q`TbfAI|8X5Tm)@% z$>0uGn_|>wircD@Ze)V!q$PQ=l#lxSQm;PQy+kO!-T%vRx80%2n`FF#7?jpj&qlPp+Y+B6Pef)_%(OLHlWBu-{&GYCp)8W7fxfaUi#yAs=jc z=6QN>U^xW_^SNsk90k{D^W2r$XG3g(9D(R8$@OOLQ}Eq>z{VYi~|)}S@X!?mes%UPoC?nAc38<;MUe|6nbMu?mo9uD@_qkLN6Hb z@t7#U(Nk#(q7#bYq=OBj8P3<~BhU4Tk2*f~Xf%UJMLcbw5HHmHxlsFt?g>c(wqIDJ z?^td0g_1Mt>BiRLshjDzeuKdNHPW8$HO zmnWSC{8fHPcr0EE$joQur*U)lH~&4yxz6_WgvODD*(Dv&FbFvkwA$Av1{~>B zR8$!m86B6a3IY&Rm3;g16=6PzYAC4-WsgI};$chUCKbZBZ`dCRGw!Xh4=6({7>bty zp|WhK%jqDl1mpCOZ%IHBA;TR{|I?||$x=gf5d*{)LHP9tNSg}yWi=o+0)wFMu zxqg8HmDzf0z85z_BOKe`Pa`&r@SSjIwVP7jNoA2U59f=Zf3F>Eo}i%Fnn0oHpbqMy z*r}JwCFSGus%d80l#r4VDpd<~?8_I1Or0}_{d8)k;(4gR{-_hqRa6#h$Tq2%x4V|D?DpSOm+Ckz~TVawzgFxs^2JBejWY`c;=!}(Bzc9shB{T zJwT;$BTXBv_|-<0ZI+oJzWOF^0ho#Gji^tR(PxuCu{T}GtRj^sp;QjN&&R(W6Aus) zR8dipkCgdANXo^9m#f6}6;hvr(fF_jyV=gLJL3vzc=ia1iyud6G_qF{kcURh&ue6P zRbi7CZ@!A#UwQN!XRhHlPV=Zbl@0hs}qwF-*qg- zt+I_^9tXU9U2>gT0E5AmTBY8}w3wfWg8Vv;@d`yGFl?uRbOm4wanIPDLY%XlwI=v= z!mqy)MYME|HUl5r9?r&rF&eQBFo`H)_3F)TIq}Xf~mC3(ADDyKryR*b8 zGMhOoeh&Xt$~g+~fR>gA1&=pb)KMkOefGk#6ht&s5x5$&TBD(BOA;$Sc2QB{eRN;N z2zs-z%RQ;gLyquCI1vFMgmXI$qYY?8f9dUuWmJZb<#~>n{7DuAWdUPqmlqwKXkkqQ~qVS|CO2PwqKLLaCpOz*?j@OM?CDhr$Vi z%47>mTfrLY{R#qew))A5g|OPO2qC4!+_d6>Ja3D~*DfRKwZ`q+k*QRuQ0y@-$D@}C*kQcoK2wW~rISc6GGKm_ zaY$?SOhQZ*h`-o-b7u}@jf_!J5J_n{R_O<)0ovD;`ez2>M0eES_hne7o}RqiD-%`4 z?{S}(>N-#F*9YzZK`UaymLKfDLi^Muv{VAA&b4_$!mV@S9hJOn-aBGaW_^C8`GF*;UEkDi2C=Q|g@XpW-Lt26 z+jAsb+!oYeG6w|$iYn}w!5L$BsguDfnd;ndZV;vkeOzq4suBBQ%7TV*zVP27+2A_S zKw;;KMmJoZ=8(!;PT#RS2y-1=05I7Iw<$l=2%e3N%{%#rcD;=#mMBB}S3<8O<_;!=_kHQlA9LfkvVxm zx%bE6QFE4un){0qEmT}l#Z$`et?C6F+0CXrFm-p6|7_E_Nxf1!;1T`Xef0abKCYr} zQ?Q-&JQ9-LQ|EGgsL|qSZ~&t?JH@*#)kc9;9I8WIH`QlmN+r+g}bP{r}1r4HWI|4U4KgIWzv8|%4ZWVNfaP}aC6zOR$ z{KcQ{EnpQ2JD%_PTNM}Xj3oYZC0H|lG6+_GEYY{FTxH)mF{nC46O#}RKTQ5ld`jZ? zTSIvx$~mmKsSGE*etcuKx*o=--y?$K3ncg)_QN;%j1RF1!=VGl0B$Cs(2tloM-~~% zzT9t`U{oNca^5Rwr4V9?wz3(EIT_uf4$AWw(ko7<5j(e{h53_jMw$=RBQ=4=L}p*L zFyCZqo%^`^7kCdII{x$_-cWO!1uw-uTkil~);o_KGf%~rnEuY6IZQxUA}(YtK<#2I z6D>J4yAInh&V-aA>YJ&&_)I^3se3NrPQus^=`F82PE#3pE14fhn=vo@nq@YfCqvsz z^=X1}Q%e(7F#wGu8916uBtmK7`g8W0@RNW*ffunXr!f-cqbpmjDTLUd>1(jh=?ib~ zR~9p@lQ%!Sb0TW*#(tpLd+;nGr5?{3VN~kGa&Z%-f7kdPZ<1DCv@?Fa`s+o&+R5(J z=V#C_x+$v#;$Jw@Jf|vNeQUG=fbp$ze63lSf+kp1Y|_vII?TZSDW%%Vhm@Qi@b!%S zU1d?sqeTAy`Fc>AxwY11NVb!UELt|@CEwDGCmkj7>hA>WxaYz8PvMz0ncy4HCQJkI>)9#PGDLk+6q4L+oqZYtSf&ysk5~m zVTU)hG+v+>6?YG&i2gu7-ara*EF0w;E`Q2iJZ3;wNjC0OL+aO! z0ljQC^9tlZNVBa;&^N_WH81novPeM+QOE~EY;0uYO%jKxQP#gHA1ynXV6o3tkslum zd1!x``lB|^mnq?*Z*|4LmwRGOHN~egf9zamz0?Q%;k7XAM#$_sW${iJB@=>`Y6hV` zQ(!YJsmWZ9#e1hM+v1^V?6RnTjG<+shB1KZU_zC6R^>1KAnx z8c1jvkNsuvE9B1sXTFX38l+L zm<{BW;n%ju*Y!}uU;Y@o)ea}AA`)8iORHrluc1+Ky0u1nc~0WFm1A2$uyz`o-T)-| z^N`tfyT@+;Ig$)zLYBj&4#+8tMC^(>nasPp>Tx9=NeWxSzFXprl9p4RD1P+2EVvM#G_f@}kW@^;`TBYW*Phd!`mfsI!1L)-T(o#a0S;!>k8K zkvESJqrcai3KQTz@3Q&E#NTzxLSKmfbt)fhdr9rH{j@%TNczx)C3jlABl)bmwZg+P zFZ*h4c-Fk`{q?}6cGsF~UH{4k{M&~62;b@Rjc1Ayl-LU)%pghiDw*O<0q|~Mc;RPc zo#eExxWd7-x_U^^viBeSE1JU8Wo4kyQSgfIWb9{U~R& zjJp+nGN_2Jw^IIVUkoB-sqj`Ob*a~-{M3)(6qZP)>DvHzFweXAFSpYNk4+ouHuLxJ zV$F?_l;Vg$l4_4A!Ab7m)PV&czy3ZQUB8{88ow~TAB*`hYrv6&>&unHEs@kG+b!M? zVMs}U(ki6Jxa@Ke>%t~BG1)e>n-EeWM(wyT$*UK3F)CFt_(j|$U{EHiSVTTvt5?N( zZ8Fvyv349$yI_*&J>cdBE=nNI)*wGQ5TiXZEq$muW@@rYWwcAgH`MZ4c299 zJ32We@v2;IWV%aZkLm7m(k6if_R0F6JV+RNJm}GctsaH-=Me@8#R6+-=-~x-t(K3* zqMJ|ARo@dJ{dFLE!sxeb0cmWXYsKsI;joiV0zA6~3a$5Lj<+HDT9d1KK^pkCh->B- z57PR96Z0@tzKG`;wEtzW7zLhONuXLmX@4{gHb#6>g;j?T+-=Nc5p(pxb#^u2wXnX} z7-Fr$eQvFcmu46EE-AkAFTtYiwx^#OYyCwD4e{C}iYUd3En9*8H{`%pV;noB{V}<>OE0v1z~#MqiLs4}|{%(pJI;7mcS_gL4YD5(#3)3oXPQ0I5WYZbiz= z^NH#+Xx-B0TSE}lPFo@-5>`#;S$z3>Y(8sFMx4Go^B?4U&nrj9YLsRlc0%4VMBp}5 zG)52EBB~X!0>qUqoz@0!hCu=muTD)oFTo& z0)maSOvQG9sMJX%cp%PUBjPdiZZ10i?x-U{A++e30fGoAFg=J4p1Zs+DAEMFYzd8=wyNWpT9R#zFWFhuZK(>R21 z?>W9OJyF#}|JeyBu56BdOi!w}>&?Sn=CZ~E#6*Hmt>4%G61C{uk9!RvQ&3Y@(mi0c z*XbgXAqG~jU6PV1Twxr~=%f<=dp&=;vwcR`8my5SD13TV z+g4VNG`1+IGJ5KKQPg`4-*?Ri8rQywg_Nf7IpR=pP>xW4QKO4JU>=;GXu`A;3tetF zehWl!(u;qkM@6CU4v4gDzij63bb`SlAsK(sT6$wvq}D!SvaXxmpLpq75PtsSbFA^= z>DJanFsV!Ye&ryuK<|9x-XgM|p3&z#VX+dH>_!jVcn~b@5{uR&`~30a#BPcta(czLcTk6>4RyjI0gND$ zzsXjN0(QF%ja>QFH~XR;!T^hGH2hej#%L4A2)T>j1sJhsMR%-Hzo*Q zRm~5hlCaCDK8Z=bZ?qBWq_H}!&9P#r(<1M5eiWF^w98Q`fSUO1~_`~`481&0& z`@`E3!cbOp4ge27+Zf4#Cnb+U8ZNej(eGVsIO?NPYnv7o352U$2-$rmEiub6;;V#I z@d24oz{SM{ME}Y-zq{TwJs1g}PE0Cb<4`oS%<5en1HKjzXbl_@l1lwCC5a-@+{AGO zBJn21I-Sx3j(G12;1NE4?4(UT4n4yc1rkR87b33v!Vy76h(*v{RHz(e_ja2!ARJUS zr5LxR(|`~f<}S;10FgpU32`N#Os8~PkE+LcQ~k3?}Yf_F>((xjahIt~P@z zXuXLW-Ct0a-7-d+ZBK=kXSnDbNzyNPfWysS-@Ur@xS8v6ZmGcqLQ@ou>cvZ>0|>!v z7H+QiBd9<|7j9OAWaO4#?`mIm)q#pnX{sBzMGRUZF54Ja&7X}7d7%#?hCWt%+ZW*2 znzVSoqp79b6K@(7Um8vjd?!kj&0W1uj?=oyV1OL^y5n&)8qsr!PCzH; zwgM!9E(Z-_iI~F4HPt7z?yx|E2b^uI0`~5g354v!(6KYWf+K=LHxg6mrWwRzMp0-X zx|o8(5to0ZD;kGxcs1XrdYS0}LUEt9*$w3^N)*}8YbzKn7jgebmgC_lE`>3E!V%|> zkYD-}7r{p0)9Q=I$IZGM!B&?4sdG;#XDCZui%b2rrP7SF`&TorJUA;$z0lpWIWV3Y zw*3K$^=qKNb(u_eB}%Z4Y`y;@v2mBi7F6O3;Xbi6>$ixA?OxzF8=YdMX`eH)kYG8{ z&;7y>_i18P?~}qpTH5Egq`>t%RU8w`6SVJ2Gr6VF$@u`tlvs18Cci_A{6#fOx?Rdu$W_1nEyKd zG6^vIC0v4n>~p&rKpI>S848L(w^VK{fm%*5?eX!!FN??#YgGpqkjt9(h?@=ryU9WnE4TCETJ}0$Ye*&g-f86vAt-i#?cU zj2N5N1JziamaHCh^q83OgTFg0<|nIxkg1D{MM}yJi!&PSCYRIscO}4}h#$CU8 z|8 zOsJL?EjkXSh;YQjK06OzZSz0IBYaP)h@)g|`bU(x6<5gBLz_}(pF7p5nP9QN*PFrPdTt^Okj`)7CgJ4oq>$4)hTevez(P2-X2-Gf=O6>>)iBvAG7cn*zOHikBt@k`k)f2xh~ec#>j zV>K-+7OWTuy2fFJo^;*kJC;yhrRZ6(p1G&GU~UxXO}(fmwv18XD~4yb!AS>Bl6~(o z0lm%u3G-=+^Xq_PshT`4-PR{6h2eeT2_8$oN~v!qKJEqk@#~`prS~r)KriP{oPJuZ zZCTV0v9C`1i~uC9oz%gGv3O2Yk)-47_zZalMk)b35KcMteg;ShrDB;@uqntJUG$Yw z$;62(puo0N+>vSgBa>ShA!S6wmWL=G{8>K;`8AqmOhN!LX7D#EtybwQ8F~pC5&)~C zc*c@PmmkL`xe*e2M?&paG5cso1N(c=!pI#!_KnqHdI`SLHE3!ADe^-_C^@NP-3&Y8 zPC-08jQSi1Tqf)Led4hC&cix53U~v0%-G@T-cW@4G{oD%8oTdQmpqE4hNGLXHj5Pr zs3`9MxrvkXPu`0Ih6rAIbhnGP2rwgK(oA$nzS&wA5XF2~bK;YB1MuLI0D1^`>4h-* z`rL0cS6&**&qT*-e|6XoBDt0M6i$GRL8fv43c*=%p7->_dWno&A^TwjpEy({#L>I)N#Hil3$48s}&iP{>$Rq(> zq)#w$hb<9tk>3C9Abgn?rYZBi-HIU3dAt*XQA%u=hE8ueIhJbHsOayC;=y;PzL%qyJ%6Nowrl z>Av?vz0JkQw#_mtpjobSoZkX2n!k0Tne;!i#5`@*kA(D{#>`!f63>56M85eE zFLoL85wGZx(BfYe7P(!(MQ3_pTc>MDRgFo5Fw1!(4L|J$(LF{QaVOf^K@e%=V$$Tu zQC@0f_`tCQYzO%pr+0sf>bCB_61)5&QyFhBoWF0}-ll@TL*_O1hg&OWGp8GRvCNtw z`D1)ZQ)_Ck7Tspq#QE>aH>2BDpo0*Z`e^lVy~D^k^hyEupibwBmxp%;bGujS;Hxfa^8`vS(}{#3883Jc2*_s*n62AA zm>DqiBk!UJ+jqa1m1jEZa7<53l%+L6O7LmHJ$F`g);M1n61ts!^|;%@0+t1`)UhBe z_Ts2^rNZsbW?*38-Q&o}h?G*XN_*?elVxF15z5=wSz~=8soc)bcRS7}%{Om6X8r*{ z;grCFVbX-n#Qp`PaRbhwF||a!w!;2EsX{>vNMFe{w|HnRD(32(#{CS%IzeQ;yR$~HwC`^hTeK$L;?X?YX)D3S2&VnTay zpMSEo@Sah%8Gc4(&=tDV=>H{0_%0Y{jI*ib^lMszeU`R9_LscjHtkEIv(-|ze}fmP z=R23U=NtU+=QZZ=+h27oRpS<)v>NR;?zpiV(WuF94ppDC{{x;yd z3cJQt5U6o14L9<*d8f@gteooy^(}QpHmb`uB-iH8E*+B9LOb(|hbzbWbecR2Qj8(+ z+wKl6;@;ScF%0{Qi{gT-{N@!SqPCo}P6s94d(prQ0bJi%>}u8Nlw zvU=iFNELMb{!fra9AhvKCX&kD<2WNSdgV4hBv=-RhT7AP!~|)5_ESw*X|9P`)gRM{ zj6DV`h6eV5IRP|PkXP)k*B?SVzyH)lW)pO9Zya}|w$0MpIf68xO zCF7CFd}lWP09xghd3*=@`_xn-1`z=VI!E3A4T~vTOzgNmBfSD}nD8)N9r@^w@-a#% zo{t25{~)6Q5K_jZ)O%;8SG5}+^-)XZb1c-yJVf*8w-$UK_#PiDvL(%d4QqrC8fJw< zyA7%vvwkh`?sc2+aoa|#S_>)fIU!17*DXutndt@2va<$>VWn(pWbi}#S_o~pPC8pE zSrrl?cwBJd1>D6fmj;n%}C+C;o)u_#xj#BYT7t2_p%u+*Dx@3&&GniavPd$B$I)Y5BGeLmCrj8UQ_4#vig{@o4N~zV$j_ma8Wv@1MAy{uTtI%Pq6i`aXm0 zHb4&0DFwz+pUZElj;ZUqr0-7P!s3+Firb^{CV-kgUJ$9=ZX91a86si3k>_AZU6+>G z{5a_CyM2#EzX71V)NN>4ln2U-!Rt5~Ps2~St{2u4HaVp1oPUdHzXP|UP`%!^`-hx>K0K4`iuxr|*GO>f@iJxz5+1T|Mu>Qq??nY`qpNXQ>B1A|B?A`X>#I zqd=qQZZx*cNZ50$gFL`YCtS2P^{6qf!ETf_)l)G|&Ay!Icl8Up%Q>tlMs^|fI2va7A~0e*Tlb`S19uJvr*KdEn@#MXF>fb>E-mM9PYjNg8XCafgX z3VMW+kX6aG!nT+*(D7is#O7T;;|L>pp_7G4C41r3@Qp0Qrn}4wybTw(Hl#GInV(%Y zctxz0LEM-Zm2_<5JOJ0s1KOTJ*1UX$;^EPZHUlFEPJE5X@e!;W{Z$dWxL8bD=6$xU z{B#;WdiAywLa7D>;2>bq{585YBI01<*upA)ILh}&5G|4cuQ?_5;D+00rX)L4!N@$L z9jokVQ<@dW>@MwA`mblkAUp0sPsk3@lGY^<^oVKfMP?h}1f!Luht2Nz0=>Ac?kuUn zu=qgc`bzK}S*pWMN;)2jSH;6()n$re9YrWxk}y0_^K3G*eCthev&3np4v7s>r=FWz zQd(a2x}HuI!Bg{D4gj%8yJUOO(tPb^?9mAceOvL`QWBvo!7Nl%K}C=jT=3QduG`Dg zi6@kYk+E?>@0k8vg@Hu!wggI!T*2qP>}Zt=eYh`Q=4APvZ}k9+i}S1tEhs#k5Zf9p z;R^>PIy@$W*3f!)h-}?k!6>nQ8hP7x9zLuhX1J-Cas}Ndeb? z+#2Bz$%wAXdw;I8DBpXgQri5m(T%v7!*|#pUJkT&Ok#OysO?;sfs@e52CA6B@u+&^ ziW$|jbX)Rc`m#SwMabntjI^yq$mCLz{832Pp5ZjMBg9|XUg_Zm$_vROCrV0n>3=ef z5|!yjDGB^SM=cAB3Rq5v39J$SNY1$hJ7+^F>i-Z#XVWn<{d;|bJ<;6$ilKPA<<2@N zS20-&f|lJVaCOQAoQ#bvi-E_ArEc^cN+v!&s0C8X8k8-^;eW()+P(cFd$M=Qv=>p* z0@ut$6!jiVuY6pZvM2!a_^-Ddy7NyLb_(HMm-#dKM;4AH7|!Dli>Lafb)A z=1GX*H83$qxt*wPlDlX4z%EZ@2}=(m8U7uwAfIF!^3*l?U6t)bDl=9q08KS+ZdHu8 z82#z=~VhR)$gJzH({!uC(z&gmxk+6TeT54zZ;Chn-8s$ID zCCJu}MwSpj=@dtfp>+y^hVL4}xk;R=8VFG(}FxGz`8yl;jsCcC|kzZ32_wu;IpPiFq-Gw6jHb&H-3|pLvTo@kE zL|=7vBOD^z^N>mvtmZu8m#(PyY|}#-s&4nJ+bBs4t|s*6W_gsN8(YS+G>^Mhi*R!> zYRCJe{J|~fYf;e*aE(cejro#NVPq|1WN}V&1SU(F0K2a4-@Y`wC~)Oo2JZA=bK|3- zdfhnIS1DQY%8gOIgL=-{%o*j{G*?F(n;R^vSXSD>XQ;u7moEX;A-M8TY`H=v5(o;7 z&vdU68(1ss3jn^;Kb><&0JN^Ip`QkZM-D$gt0AcJ3b=*^be8_}ulaVNP~u;G$Eneh z7sFK)>rxbE&=~Cei6NPjV@LO;>GhO0HA*qFZVArtlAy|nSnsu`Xs1#@CBNJF;&wFQ2%=9VpG$*Se?L@E zo&O&$KmY$#cO+H2d<>i@vBakW1_-ZS5@>#492M8K!Y(MvmoeaABLIvRsD1;LyU&5G z9?wzw^i#w-J#Vc<^DjZ`hhu0Y3ijILb&#%dXF#q9i|UB3F+{}|&Z1rA#Paz{MQ(zg ztPYLg9yoZcJ2Ik#+XcKC{!gY-SD&4d&dpU01Pk>~CWuISu+u;nQUpNrbjC2Z`-u>CelYRgly^N{J`q>-@pb>?^HN1XS zydp=!DiQ1{awST)Dcf0jF~2HZ3vul`=l#vh3t)P<&<{e%4p|Jpn`Z_kjOR72~lEpEkpJ}V1W@y5o# z%MEB3TdK2ING~@F(*~;x>^t80bfPKIi>~)M)LEV;wRYxFz}wsXU^(2;_W&D7xd92I zoiNA1AOHpDR^Q)O(<iz8ls^+JR63DT_=ghS{6a;O(94T<0~O*Pj&x_EQ=t;((tx zzy2*Q0oz=m;UZ{Gjq*J7=DBZ0o$VD%y&{4Pa0IZ)o|_fS&u(2&y-++N^mseks7HLIi&CEn1GlDmxJtg~-IaAcsqmiAA1|KqfSG}`YjjQ+2n5-XeCpMRa;G*<`iG8w6cO!2rF7PtZ1AE82{h{H$3Mg4*6lj#!uSKm!hJm0GF@3o5SSCb_Fu@uF zh~rl_R`_pJvyg)JNNndmTLE>{hIwcJ9>{u{oxzAN?JG z(Q7Bq8ed6Y;dH96JY)z5{ZvpD|J*==Qzk&Qa1N~a(tL6N&rG9X?{&C@M#q)&PE_s@ zXO<-+@gOq@69vkv(Tzs!PHNYzwk!;ke?A`oL*6nrEmND@4Q>cmrgRw@(K(uxY77N$n|A-~KgS=S8v}z0a~1AXsf8@jn`8{4i_2yHhiVX`M)a~n zouzDAUe>KB#GqQB?_UaY52Hg9fuSX>qt7`1=nywHxCM5+LkDO}jq1FZJe$hdmo&GS zlbOs%VK#55E_kx}h4FV6%ja=zS;{F6j-}-gG?^aMn&AzEf}cgg7c0_KKJrY zN;Qu6L{eP*;EeDqvWTc?Ms{|Wt)=7REa>Pyik=IUapEHa z{hc@QEoUd7#OSMD7qycQGCMR*xbyvXoHdgoE2wq6&6V5VyK!4#n&r#O&DE`4@DZxD zOn=B~%v*Wyd+Y_or6*RO@d3pYJU)PTQpSq4I#LoKru8Kax!;?#n3(sz=8=&VY@F(u z^Azi3V!^#Cl=EfB`xZ|yEKjZyA<<@Ytp8V}v!`fEak;8>nschqe$fv-`GB)P5yO*+;+s^a-p+~J21SZ7+JSIKEX53<0*cfH^ zGuPrX6XKP-%xovSs6G~Y&FfTWRLuUK;6{f?Yfbj+MA`4#Q{JS->ey;8Kp0P^a z-rrJcVY6zIME&su3cDL9`C}4sj2g zY$7hkwx>i!ieh47m<-Smx40u%m&k^T_`7;D(BBdk=YM<0mqhg=_HCM59&Yur@7*~q zKD^6OB~T7EG~j+k2KV&^`K^>FX9_k|)I+e6o`V4u6cDRnwOG#gIVV!se4P&ZNiNxH zSIgay&p0V#T-<3^OG-i<1dpD%X^mLI!Y*f$pE;=_X{=0sRO2p=V6Z3W3|v663s9fT z)*$NhJjdAqy#ge6X3vceB)CV*SOo&o>GJaOysg@{#M*wD|p`jlHWby5j%Ubzh zO#fXfte+35mMGziOP0g=#1e;*lq)!*oe9(mh^C45Drs)RtL?0#-mLN*GO(>p8c&G$B*JxvjnhF zZSj1-+O11qt!x3Mal-t%bgV*dw{lceR5a~CXPh_AUO9Pqdro?AVBma_Xuv_}&&h7k z3V4dxvN}^S5*D-*mBTuAabq;}J8As|__n&FHHncwwJ5)vl@Y5LOq$Xl*H-^?jzH{5*P0b0NT;{s$}_SyHKl2EJQ2#9 z_?K5d+U$CBoRgE|S6ocX-lWz81`;0JaA1xUawetjcn(0=j5wU?`C#DA>k=ueP?f(sYKN6&C@3 zY!{0lv_VWyk1U!(+VFg{Kh43>xZv($C(B`~)WXax8~oGO0$aX`Y3h47O-%yvINGzt zgTbPJi*u*4rl^P{_18`{x#1>0Uh3QWYoH1ouXL5g;^JtC)n?}!yw>3Mlgr@K(W6tkPL_)(f zAkhLRtEH(B*cE{W5mecW6@tOs)H-KyYqtWU*FIW zF<9C4`Y@xqI`;6;OinJvKHoUJ@cn^P z5x|{-`uf=c$6uVu2P^VM-(%8#$&rKZDq39BKt)T9lrpTGlNU4J8_#(x+{CBlc{KIbPJq@)eHSAbSa$UjPQBhIx^;uz7mJj%) zOt}J;GM)Bc&d`4s7l)RcU4ueH^`~hqyVRsF3MsTiqXfX4fPsM_k;EGG_~B23(FHCiA$0)NPUTki$g_2>%82X;60(FrOmFa zjBaY;0Wd62(|M}$F;n5pK|x_5DHBuVq6Xw^Js7CaVv2uhqNbtA%E<7#ytHFxW`5UQ zwAAPbyp(%lsN_YYt}SS!y#_)Cdl>hb`uN^)?r@yxlYvj|#z}jhCiAJ4OhA;)9 zuQG~tv{UtTvcqlQH75V}HeQI!##AT{i^wUb+p=a&yi`sU^m|OF7EPe0iD3{RoZ!0DU`pJyZ(&q-r>UZX%?NR+ zWO)ZJa~S&UG?kvZHdw@hNiP77l5Mmw^TkmVTwQ zQGZ|5<&u|q`39r9$UlJwvX2s_BX?+Ua>W71$4&R86~SCN@}(nTee7o;Ez5ub1Y2_7j16p@9(Fmas$0ffIixFH~8o?UZ>PD z$ucxSw9MCDD! zw!z5*Ob9@;oB;gwrex|xj88phI7nU>8u zj+@}SMzCQa4GTCHAAFUY_e#BHeJ!}Nz`4@V(ecZ<+PU*xIJ6zr-eYHVKyztnZ0FSKL!H>v5ENSSRx`@;@Ax5)~*zO!`0x9*II??h?6Sn5_ zLgA$;iY$oYDd9JmiBEQ9yu83DMR@6xogVSEYyPaS*QrT9JISS)(Pi(y*Cz5aMH4Z3 zq<@mha$G9cF8?;?;0VMi6Z`3_g9&B`?L0%7ZO7YyB%|Dwq0~n0)6b^tYHIa%7f?K0 z4=#wJ8j~~-|ISY_28lbtE9;{eMC&2)6XBcT-XU{U*3kjVEvhXOriHW1i)9g#3DbYS z>DD$M%9O$RI7`i9K|l-=PfgxJJH3onJyY5!+{3ye<0#z8;Ly6Y=;ll~eR0K5^Sy}& z9o@$9o$YU;bg%nZ8+3lI!2?Q9)9=)CL3jI9pA7||hd)&<9C?H@`v?MnVNr_A!k~`g z_IY^bbQhuJ=I!}%+Vb6TcZ;lHl7 z6!!y}nWv@I^oeU;iO+o$ypq0=P9sU`2>%H%CWae(ts4d~u||>4V&a-#(;8xDsp)Ip}dK~2^ZR~^9St0+K0>Ei?h~s|CG1% z?g$W3%*oJA=#{JRq_wZTsa?jjKsIN$kPy`m?r(cfAQbBTC1iMnt=k|aIi@Yj_-~TF z-dU|IWr!p!vw-JxPscE7H^q&X6dCrd>vuFs`g-}*GI?U|d*@7;+iYC>+gbRvKFeAO zpVKVQrU_RUT^_(@^rOLjh{hTDd6=g)lQo`8cw2#8XIq9bd<9ni&~=iqR%O`{WvC3`fMf*Qni)ht?8 z-icbyQo2aqb-EOKAv~WG=f}P5lKpNDID4m^IL)g|6_bJbmcAzOE?I1oV#fcps2br= zCNL$#r_jJ!VwpDc$(7DqQD}j_?34g5x*oB24~H0fN8Qc1;_t4FKw`#(jf#XFzx3q? z{${5@a`UAPjl*6;BI&X@GZosnvZMv%c{?H^q5!i>Yfl3N#ILJ^ZjpG>a;KLt?<&&S z#%!8iH7odshlG63kvk%rV790FM@#sZA=e3XapU{d-w%d|-Ih*^Zno!-zUGO(3J+H4 z08C~_l!nRtOM3zU54#4&fg=pbC{qbNLg10AL~4>A-FWs1N_SH6L7zoF&_`DbXw-jL3cKhYz9^AAK-s;c_Jg-)WEuv`Xd&-`L{sT1nAaE&p>MD(J=NJ$%tGK!CYuvnciy@q6@& zm|Nq)Ljk*iH+#sxA=a|{jpq9Ly3=_-g=yJeB#YG@;ZUrJUM1qR>h z6_&Q!*{`2R@BfAKRnS&~!K{9;pSHs>b}T&uG-_6bDSE*BA4T6foTPlzk$lA1a1K zxo`d+yIfB-nHla?K@n>2|H}%qHFV!|)1kiBNF`c2jXae=@7xb=INofAK$syR?d`9*2lpt7|{V)=`6&b=#J5>g6l zg2hmK%SVg9O*ZicNj%Qy3G0f|b}*)HcX8%8@7dR6S}sH;c;}fe(nm9 zK6x+Z-$~#S=ttVDRo4GF8GtoubcIz+~g!T-~7B7AQ>z!F5C)pv6S<@i{wfhvM%jcz!@u{6{co!@nqnC z(;1rx+n)p~aJ(f`ZFh|S#g$>hd*c#qUB5Y`@gBUfJig>~Z@)?VvV7p$+PStm>iNu4 zL2G+GXY}B{xaLm`3%;70_8tEd;)8>`mgTXD=H}+Cyp@9^0;s)8Zr-t<6TB&{9FvZ) z-fb0C=*-o)aq)_}aRv@Jk}28>LzVS&=n`Q)x4Rz{Jjb%^rq&b=_es}lG!x#(y})ElzFe_QlsoX?kED4 zBIf<#4ELKY@Ol#AqYa~RCN8eqh}@9~Z|?I`s@#<#4BO@e=4I>f@*=#2^jhT)w519~ z_o5iYNr@*l7)g76MMgH)YE_yeN9#FvnVLAcVjF=O-;s&(vPk+Kru_Y=l3^*@UJY1J zm*wV$+gBs>wPE^1hFr&8Xjov%KgWc-E1~Zz8Uzk2y{&}0nupI0Gf!X`{1&{#(P3WJ zZd@lZ4wJx+FHMdNUn8t<(f6NQ%+n9z# z^_YbvrHESdzNATW*?ir2sg+4rZXtL3o-^8lJ$PZlYOuOx+^=7#2q0!ZpppB*XuXz( zN+>3!Gr)?G8&DzBtm${ImlsBT1k}_EQnXlxI@}+ZrD2Ff(pQXso`24y4Gq;Pkgmz_ zIv3j~8L%l^nFB7#q!8~X*JH=Jn^^Cu9hpSs_FPw1{r0i5=-&cC+#06mSkR;#Y5A*r zo(q3l6ufcpx3GTeUeQ$I`gN(}Z&bLex2qC-5HUv*%xb^BG3*8l@~{iDOef1HNOV)8wEaN<_&G zC&In#uIbXZFCJc9K*t1Z&P^>BdiW2cTbLs3x1K`rpNYfPm@ZTOy>@A=`PYK zDuiEY$S5YVzB94bGr*q@z2aFi!K=ruHM(zh`>9+nv%UAIWd@;5>aib2pta|$-*B=! zzp2z)4zfLmk7JTPq9#>IQ4`9P_vHkdDuuQ-0kW zWLCpsR(UH@wn4Y=&32UIM$5?I247_-?K92%c1jVS{6Mi^V~nfJHhqy9g=)byJ@8W? zj~9Eh879JNXTYH8c9Ypndol3BYh(5qqZ!uF)e!q2%oWZ|U1~El*g4*q5q-NCt#W~F zb$|+McAWH?R9%D1s=z~BFlq%{Y~yd7?L_&m^IbX(oyOHCyqjmzz=!Rpx25WWo0qC1 zdd@GS z<54+F@O$0qRNj66=|QmLUNRPx8P5<9bxCjgWdGCGvWvIMT5*GC;-FU&KK0~07B#{) zC@I6rE?r%9GaUo=o99VmJ39cBP2h zH3szURVfb$$B$y3!KV_pQ?*D=o4FGXCFQYAE31uir5;kQv@gGJ2tRkw(Ij!^HHEG= zCIzL)1#jTdsrYyPMwu-duOjj?LVrc_Z;JYuNq0%PRoE<}H1CzR@*!wR;lb;O%fU-#w+Q?cUM)Js{IK zC(UUc?t<5kl%QjcQJVjW75r2s8d51rQPHnI94J@LV+?O^OxW|;RK-GS9Z@FjNf`>; z9=gMPYbD;jURZ&#^0Z@!bI+oB3IBn;xUk%PJ<|VyLYZyyhvbi6gy|U2fBM-XmDs|f ztG~$xrpRmcXcoo&Nd74t0ST89fm3O(vBka_ei&ursTpAgwkT0;N&{~l#mU#=@*=xP?M9La01aDJ_nmxU8(I+ zB6?9sb_Q8Z)medAuCTCezgGpET&<@^7R_7NB1W-HI&Hj& z)%$T-{2M~3lf~YFhi1NK#h2OVwdmx1P@3Tk9Anohi@&^zOTBAGkr=kth#(>?S4#r zonG_ZX?tUc@xyatbM%SbP11>`nsO%%ja>55%-VsZ6M=fJ(I1-Qr#G$xHlMNyH^go( zyW$Q-6MmnkvwJI*Roz*8>T0WDb=vyLPbOXxfFb&|H>uOc|T^vUDeeK4b4^@My0k) zdKjRbNB!?p`Q<%44%k>|)=%Q&K3g~Y;VmPl{?^_5u=>2|Vb&;o&YatAMB#d6hGgDF z_xjKM7PCE8)Hd7kuF74^`tDOo*^kruY4(=sWx+1Sz@|E8E+syDn|jrUjXiz^oQ?d^ zQTqV(AwiyHS#`-AcS6x;H0F4N9W@8Oo+=3$kzQx6&FEug#g9@V&UPh!2g}IK{ztdQ zFe3~^;&&uP$Hx{fE-p^a!#IzJ#SG_j(WTkT^&ht?(AAgBs8-q*k{C97s!z5y4wgqL zrnP&94;XeP@M_Ky5tOZZbCJ&fiXU&qGd!bml)5r76nUU@*UX)ezc3xQ52%igl_&h} z&>wR<=Zelxh->UB)wZNc9Qu2+;6<|BbV3|~5cZ`$wGE*NPNN*ZlZ{D<5OJg7f-&4u z@YEf zH@_-JxM;SX((I>IAI~B@vjNf$hN>0T8$G_GFPC}zufbePLQgO2?wLGZqXYaz*|j<@ z*<-;V;;)i3IK!QIzC6g&N9ekIlxhQhWM=bK{g1BnF={1l2E*_z%gf#2X?!166ZqR6 z5b=MQnzJq79$0D0i0jK!jX(%G=hwfpw4D{v7mtP^*Ex_2Z3I#E+I6nJPeb$=QFBd|D2uC!wt^tV|A*f0BjLs$yV0(}^|(Vgymt|h3aerDL${|L5_~-r zjamZI+q4{ChJ4N+2oD+`F((N3jsh}vyS-K8cfIDz&jbpT3B|`Z=S9<-$!)uFE zxVRu zM`p9a&{6lo{wrr#8Y~KIwhJ?(kiK+(|Do1V2yJiR$JWmZeS?=GJU!$+Rm{n;5Qt{K zG7`a-k)9Um7h%S(*no($+l8%8)JCBSXBxC15Z=IiUcG=S8`{%Z`XGM!Wl@FG&*`_NmeCuG37d4W#;_w(<+JEC zzLv2u$u`E__kMSMV@g``s_h8kc==8SY>{C(pHF!Gui8Gpy5_(6;r=70ZHngaj3l3# zG4?x#x8820m7`$z+q2aX8^pwnGZOmdG-;;kUEYMKv^3JqiYI?(=UBL?r6q&*%l*um zOS6KK(s{6Q6X}{O65lQHza@0HE6nfG!KYlR(GNP2*G{WmFrTefUm>R^UL9z^%%`lL z_i(f@P1tM?earSAVgnL}Ve;7QKgPI#{QySABZIcdxn~*M?^>EIFa}e{LN>TgebV@r z%TJI;!@~4f8_!l6yjBkmGUs4k9mp~qCtvHj=Hp%V6XURd;9HoFV?^2dE_r1vDe!vt zl)_NRI7KDbNYr?1GueB3F2*U;XPg(0freotgl2;|n|7kkuqgTu1}j0z%GK)av^DI` z^TcdYuB?V!$HvCkdo$dz$<9iT(Gey(2fsS*&!aPbAq2!oVzbsziVg6!$jO@wf0Zu*8403rcJK zAT((4T1!!uy>dpBnH=K{YJ_zG({QP=MymxI|6-Z{l{HqZ=NLzu`ZeJ?8yCzB9?a~ zF>z3%U98ciT39b-;^#l!I0EHFYANA2+`5&9cQ07%sH%jiWjQ#jx2^OV97JDCFNW)0 znm4p+2$E6)D;D=Q)lHRUxki&S)Z*eHG4s+s9XuoQBt-VDg_$Yb;7Re+e4-z$?TvUq zdno7QzF;Pt*mF=LXtL|aq&IdWw={0~<;dVl5D$4|C{@2eaKAU^jEUi|XcoRKs+;bzv%g?RD;Mg#xmB{`mw<*^8OYRhXV&x0{Pj7r5>6zTs4DwyDpEgzCHaB92{J?on&e?6m{-N9k1m=1)S$W<8C{n>1aKr zsBC>TrF^mKgY?GgtQ#vCO$j~NZL2Cu*TZcbcUfN9oPA^(v_eEY1BwCRXZ+uN?3!{A zUxp9<#tT#;8h?e_xmmDse?EnPA&H=+e~5A_Tr5SY zx6887-V!6&NlQt#NAnC#ZXcnven`?P)6w!poTzk^KmZSxUYAOKqu!dK8Ex;SHU?dO zqipmXVV&y~l-ckwk`qqS?g%% zBDq?xR3R;-yF`~ZKIp8xO1Cg4b6|HjaK>?jsQI&yN$X2j2`8)FD3Qd+$Hbnm6vc0( zd}iRUAL_uctlX&fVaM&UKOiw{J(4mtKh#)FEVsU=m^Ss0HD(e&tW3%JKEWSZBC|<$ z5VGjz*@;_fme2CAxRilBLu9_?y>nwN?#dm}k{c5#4H1MSV%Pd39P%6I-Hbdvo{2Ej zR@GQbtLN2^a?loR#({VI$-vt;d9-ke3Y|hq#CWp)8LHctA}RH$+(RRs^Vf9zgWlHd z<%_WavR{*j)%T2q;9O&kWtrZ1WrjQl-My6GKddZ;IZoz06QHz+dgM5s7jk(NoQFal z^d8EdS}4{s2Cy4@d+OK!G6|861yL4(va;HOyt+UmJ}K;tR*PJQNPx0ZjO|R}mf_1y zxgut%bCJ(4jH)x(5pE>C7e%Axu-J|GF>cQq7#ajU8&Web17yWM{rbWF+Ub(@`|WoZ zTq>TQhm_|V>-0xoFI%rN-lUrU7~N6M;AmugCC&M0t&ODpyu#aba`)Zs)at!gkb|e1 zHOh)gV-&plHs(w}D5{v)EtiM#_^zl3U3N*XPgX{6Z$E>#ImKpxO2ckUkXAM79#@x1 zOiZi}h-;j0*8=A1Z7JN{-Rm^y;~2C@oOe=t!Js`3nmpJJn;?vSPex6RYcS5wr}Q8+ zR3Kf7mWHM?$}3rfKE&@J3D?O$kn`U&m?Ua@m4;8S(Lcs?d}(JTW{m=QR3U)ePEbC< z2+uC%pK17{?;sKB|M_|Tw(xbj+H@EBl%g%Q_#-o~98R!DkW~N@cz?_HhDgoNL(XD4r}W^l#SMoUzJdF44eqV%bwb{*O8jqkh#TJubvBP!%ts$8In z_)rOC_^0yAk2IxfUKqc~!lv+>b-L)MwAE~_4n$N{PH5^R_nVgdVrUTO=~0vjxp!Cn zP6x@S+^{V%KTK7j*Q3N=Yk&Sqcu15ztGo8%o*x?f@OXIfFt_xFNd?`1t<=}OrP>gV zgOx+4|1#PmV`#}O?!U$Z^59(v|6x_0j?iuuDVF3`hsx2@9Nkr)^x&lTdcD;G=x=UUF4;8a!;p|cJIZjD|y8_dIEmwL?3`myGf%|3>!OmA$MZx6s<`r>({?V zM;ot+wvS@BnjDSEVo%IIRpj9BG}Ecvd;cT>TN2M~8tzA{ZuroKpZ=$L!o9bvkxFi8 z()tj`#yZC%F=`e&GKu#Fj(1{H(lm=3JUDm74;b>09}Iq`D_iTP{FfV{zc%s+RKi{0 zG^*b$2I*~SOfIb>Sy`>)H+Ssm51Z}m-WssU??QGmx6QJ2)t>Lnr&vMzGt3E&QJbbz zqn@7OQN-Iv{L{O7q@OL5?fEnPWpvYsA7CX7Z}}>#5?%m6mI-X1Vq*I#Ukwir|J%H& zEIs?lo`i9uLZXG}ABjkY12KcBjG(K*i;~C@7|ofvR!{y{Mk&@pLO$nI z-GYxlJ8@ekrUqXwuafuR5Oi+p;+HnGS}LGtnV$}=XsiZAq6 z@CbV~@`e9SXn`|areR|2=^p^2Q6HMDo9b-z+Z4jEV|o*|fsd$%1HWx*kAZdWy0Qz5xLo)?w(6$e5C&s!kvqD%Jb%nEjBn<3gK3bd8sWj39DVv z+O3CptBM!~O}Yl0c^+pUgIkZO8Jl?{cvrKJTS6ShL6+Ku3SwNL}S4 zlOYgQ(L_2Qj*f~Zx19YvjB9H?g1gd(EsQaP9m`P7&eDnc|0C-w!>a1qZc!9LKopP; z0qO1rl@cid>5}g57U>p2I;5q$yO9p**ubW{H_e&b=Xu}neCPbo>vHeyT5GOZ_dV`0 z#&pwo0keXwgnik|BV*XRK7y1IWZK%V@Da1uz zPZb+PPW5DpPzbPb3>>u@AhlP2wwX;JQ-UIGIJE`pOnzbSz>P(aezxp*VO*wEcg{j~>qA${a@E)bo|i7HhaFcITSW?qd)(XO!nD__Va_A%DPGN3xMB(x59hN0rH2p#hQR!kT?5UaLKx zy@5Cnz}!{E2*;}RP?Hr5Z!(|n@9msT(Fh6smCAT4{MupZaH_{A6zG9&SC`T`|XvGhB?)z*S7Usbe!9p7fZ9g z%Q2bv-C)g>g<2>g{ZY6bG7@Hti`sN%gAcRAwF&x*kxsvuTqz2VrFzW$7VBip5}&hL z3|J5B#l;dGdG6Z!_%y;{)b#3a}r%9A7CjC5Zc^Vk_zR zl42Rzn=m5c$2}*T+2X)M8#4mJKu*~?(v?55zKnZ(XKf^3HHiI&ONMUH52o#02}Tq2 zPyPw^dq-~*!QzP~G>)lNd>o8PsA64lI0)gj*@I<(P}Y_|mIC^ySktzBd^%Lp!>L>) zH}Ne8k0%upt(TlwhLvREFdgHvF?A7iF@ni!b}sV4X6v{4f zbgfPuk74Y~i_N6@VStKxI1WDjz~)I|@gR0k;g&-U`|Ez3Ov1Ng*cgk7XKjr80ddC~ zduio0z|=^6%vCU5fmr%CU)%bv|}sGSf!>B;BvWAp>1qA(v%hT1o8Yi?~39 z4>t-C3ZmmnTQv?@I=hPB`zw{y-809%G%^&UKe)mmd(;=jM(rhiyQ*q3;_?P)x$HG* zR0Bv{N#TP@+{U-gg^AsvAEaF5O;M(}xl66}l;`$snL$+|DI}C9yEf=-*p=3G#FvZj zNOPK7qfChR{o(N%o>D}Dx53jRHThSp>>&$5gwI!x1~(j{{$^sh+Vb+;O>F8@~GD8Kiq#hxlNs!+deGY=~_(*-%5pXwme96sVIdCHybKz*6i}s81 zs_ElxrKV^GgxyrApwN%GM6E55YO>X{8)p@fly2?r;DToFsn}F^GxT|S4d;vc*Ra%X zqzh0uZAW&5uMQ&X-n3 zO(`oKdV{4El$`Etrf+V34iCRYE!Dd^fzl(&TJchzNFlbyoX7hcx_uIsA@R?+2Gu?f z+X*%yw^JUnjwRAb1Qjiv?k0>28|TNP9(=_O5zjsB5!3H2dU+QlJiWl^K`3?|^T|&Bb{~S{b2Bwwm9JlHcjjj!4hBZb`DW1IE@HOGsr6zZ* zWp?_3JtCqOqeb(gWnvsSnaV~4%tw{zv2$_vCBt5=CzZF#228d0<3+Ukir z7VC6>M-!QS{V)^#@)N?z!;#;FwIG2qj*ETmi7-pd#&c3T^yKd4vb!*f?FmLt*|}WW znuT^}O%EtDW?eA?glstHvTzKux!maSQ1Am-#S7s$OM1Q47`<2Z4uMeWJ)RZ^Y>%j{ zYc;fY0c{i_qlJFTOFwM;HwS<5FQbgiCw*oo1xVm`$sX&PiFSJWzPhaX5OguCT`Wr> zJ0mfN!W%vNHnqax$Q4i)sFt`MBcLDl<3(XWw3Pj49F5=3QvUF;a%C@5K0X{_A@$}B z)2Wzmq&3(&gx;+R70RJAX}=9->bN^QXF56aR#wSLMd$xr{%Y(df=s?fbP$1Xo=IqO zzO^IQV#$3+vfb#QodpCaNo19Li6cEk5ZNOte_WZvdJ)_x1^|RG5Z&VG#i7o_A|RjKfg69 z56GrpYnfHa%8DkuI$rtEeZUtyk`Qg#dp?i6Pk8=QjE!AZ*?19cWM<}f#jue1U8pFz zDEW)4>+3;FBqXFm7XdshT%LzM2qck#Wo2c4w+_y7IX0yD_-)Xm=ZUJ{DKUeWj$8&f z3lQAg-A%2nxpmx|v;{~ogdnSm^_G^Fr)M(j4TMBQozSCrbUHk=l_M8C;uH_^=7NII z;^NZ@alcU%NWke*OK@$ZQw&CSm4^4L4M1W(}7q_?FY6YF zu%##LR9dzckAy__7tlwB^+0u9T#o&Ki z9(HuLFg3+p1k;uXYCS7B)T#Iy#82=E$o$$=1r2<%@M#hc=C;UgQTg7lcdLEV$z7_pk~S z^`Jb;@ZEIi-2wm+7p?SmOGmpTypUEVBFwmQI~s~nFhU| zkc@@~;ojb!B-ElfjP#!;03(Up5j=P9v?YAE*NinGz2t3)#JGt|Ne`u_*7{pCJ@NX= z*g@^mq6!TZhMltu*cPT~DZld{G^(yr^){@p#=%P|lpuJK@C6i|&cqPryz^>i#&SK61_ZyaZ$)1M(BX1i@@!z64^SRI) zBl;n*=&{|IO&t?!Yn?;$jL?PLU}0xw z&7lNhQEhn11#?E|E1*2!hJ`)yF|F*l@3 zL^>w|-hT6}UL@(2xWuIxWYsBmCwl6av6;F0d=oC$V5H);fc?V%IIw>9l015mY64>q3~wTrACM9 zl`sC~t)H}*Vqujk0}m0tX22^97BpXAjrxq3FGl0G^6{IMy16ZfoUBU_;y0I@JuYKE zwAW^y8+tnGwuR~7ekv%Hly*E!lD&G#An+rB>P5$r&*E>?SGX!lR31W#-eRFrt)EQf zzTn{ELY*3L8}Lv+fSUVAx=2`LWD+hk>)V#S^D3p%#r}-n!5{Jy!8!Jh81I|sYjPKF z()4c$0(kK$v2OK(H>?UK=*qp#%2a9S=n_3U9zr<|cvR|l*ZpE7JRb-Zp|dz$Bi&HT zO$I{Sm_qgiLL5DG(-bDqeckz~tZ5osoKS{1^rCQ5y%JKTwak0DLqbDs>u|hhvi(KN zrxb^E5_8J_7_BvyV}fYCU1&7+6qDWuqp1BpN=ftswUyUnhh)gnQu7|m`Q1Pm^gCnH z4_ZBLJm0p@Z-wQBiE%>3cIz5OW??g8R{IhC-;OP42C9q$@UKRmvfC$AaJPq)Jkz`F zX_anJf9}P~Q-?im`i#GSmzE^(sDCDB#JFZ|@9~Bs9TA^HkVxRO;84@=!wXJnA80Qc% zW5O%p>VV$Z0VFE_jOVTfHt~_f{IV8!w;{)D&83A28TVVAM@y@ZnVN=t?yn~B`f>O5 zRwn=$-f7|>e$=)6s$^7zwuhs?jdeba58=(`ODSaSI`SkjC7NRrOBz2YoGvD4&}>}G z_y{r~eW5h*&208y>wJOu=Vm=F0&<$R>{1Tr38R&EH0~`&SH{u6Ca_vFZR57pUHh{_ zzVG;_Y&BJ1)s31u$e$^n@*=`WH47!KWuJ7_zGzf(#axrg%WjN-fwmiEst2YkNZ^@h zbn`@`RZSI3AuC-^9ft+YA`)ZiBK652ziS1(odSwaf1Ex?j_Wvw#mAc=V}y~ox+70p zeJZJfkJ#8ptVQk<1VWHW$=!!%U@P)4GQ}#^aag|STE(h#b9DGx(`=?|^;|%JrIT7C zLr#y`neXDV+mSkpGYw^9L1I9t1tyg=7D@ZmpF{i|PYV=)J-?~D(R2Nm_>+*+bP!|f zU_HdJ8ohg|(>yzf@l<-+C%%J~?#wIGkasJj9hvhsl|Pm`A6-;PNnL!;j16&*(A`S) z_)Ov8h293^$gTV%lLN9Gm)q3aF!2oNC7k~AyDLvis%Dp@&2x?n;T`Uu=N^#q!XNB9 z@~kpG;K-6|1eoB7JzAVUu*)1WciuMpgk)l3^0_~jab37zBJt`fJ*2T)udLKzOCgp? zE3rZDk2%4ziW0N|qyUQ4Q*kx>Bwe1jBo-}OUuk!|wgQGmYX@k|Kjb8TgBnNTOe@Ad z6{~hpGURnGOx7&lDCwZ^*mWUXtl?a_@1;Xisbo~E_pP;Fj6Acx{p}q4)+r()0ZTsL zLV0oGW1O~hsN6&~vM+`|IfR97cXaKvIH_E;^|r^>^X|F2#CAfk>?_>`jS1YrP_IP2 zQJ$vC_>v+uANQ5%X~F%q{Li?8HN{e!>~r2zzB~3$My}YR+h~Zt)(_pLL}MwJSQSdS zl0SWI#H`3lb}!G$h-yNx9LL<|JlyR^-BNhn4JV47>o~pR38#JlWk-72_bUJ6fd57O zdHpsWNNQ&Wz8yFCkO^&=_S~-{-H>X9%VY1cYg~P;74k%w)44JlJm=Q|>4c~4#u7c@ z&Uj)F=7OZ=&Bv)B?2sAS3W`z7nn$?_G5K(Sd25KZGHOaw=J^j-e6_{5Lwp@)8F zuKc-kj06cinSa*S(@r>6Kid3T)ur3vPBiX(uB=vZVMX1+$+L=&Hy<*lj>vhS1g z_-Ze{kY2m?ZvE)BDHHh-o(e0YyBDF-GXREm-!Cg|u3>SvyhDmeb6mQ+@L~w;QJj;f zso<{vi`Du{FDUBI?!hwzM<0lm469jbta*GhqY-e_ z*8E`h;pmPYNYRFhXp+_lslS(IS+}jLTjyO z18;Np?CWJ?M@TAc7&Xqu|JZ7qG#VtL(2{OhK{ws|@ICY?yE}EQ1h>0x%RE(~<@ZKO z%^!o(PQ}@YOEIe>}sH(v<0TGz(O^2wlnKsouf z^nlUH9gM1d<5PmQMx?8)ryl7!vE}m-UI8zGW%Gj2II70UTU*o-RJT3_I4{^ZHV;dI zgpg!;yQ2p$&v~iA6LGnMe!y}MP`Yk^-%TIWnQT6T>ccmL3W}w1cEj7? zZgSxf_V&)Csd2MM-bR9M6QXmc;x-GOk9siXUM1g_9Xr>%9qo)lTrHIz7c6Ws`o>uy z$)jk~Q$=k%S38<7EG!%=xELf5^E)AwTFzCAF$I&)Ne_OBw(e(Fb4G`{Eb+uH{$`+Y zOYzmwn(w2w5aximUu47Ncaj?=_ik2nE%-C#0{)hg>yF~ubcJSC$T(g|C^sZ~SPp*J z-sQ5u0Avbz!r9Iyhcw5S;R$V9=32pV?t;F9cHy8Wscgt z(3c(a9t7m(?5L3>0ybrF|99B>x^?EhV?-qkHxzx{kx9aX@;z;^tKYE`HNNf zk+rMCdSj1GTQaMzX|H-o5ZaAnuxf1wzs4w~_evOrm|~!#9nZva>5aEcHfX^Ux_nD6 z3-A4oBTtOk&Tzwy;unn$_{%DcK4@KC2hL~56TxU1%yhIy*RwzDL+Xk_U#G+~u-`$) z+wxbc-?36Rz915|>^bkzuB;t-;dY7nRU;|g;=HVU=j2IQGYi4Of@kjMPrPjEqVPqW z?VbpK?TVu45g_K{{=l{$&R>ghbJWz~4{(J2st605Nt6N& z&bRlk+ktQCZ}3O*_4lUJpEKm;bwrQ_LKLk}<~d|F4o_UiYY1zhqf;N3o#l<_bGqdd zF1k1r6KJtRuy||AlS_)#-X3*EPfOf9U=pa zV-&mR>hif4@GJV(R;!d=+J~6V$U5eK3`*}52US;(G&N(Una5c8--XJb>Mkr(R%*dSyS`()u_mZZ3Kup+=ph241afoP;{0U2Guo7lds!n(qJ{H`9uLv_ z^+L3oe6b|=o=w;^uX>m7*EgW=#f0myA-LR_jaiG*B34_dD_8Bh$vT2a6zN#a?BjN> zPyNZG67*)x3+OKU5?|I*5B+}P;kD?zgxrJpwtZu2sl^e|%@-?3qk6-faVg2$f(TvW zLVKR~Vm9ZB7xE>z>ruzo#Gs6i1A*l9Z7{|T?|!#aL#q?ZYyDen&(+5kk+5MtIYoj9;ETuaHMgbCW^%~EL+@?d%Rh_161c4S`6mDls`9%hE2*~wqJds8;}y1qGfn3;2FY4oneAy+ z*G01p=3jhvFY+7?FjiJy{-Dp=@u;Yn^YAp(C!VYuvXR|v-LU?*zFt?N0Z|P(D2_&M zu6xjdW2qRs%u-xJ(sAkE0ieWH9ohGs`LSD3VWKVU>6ewkD72K5CfB@Ntn#OyTje$_ zWiEuPkuqP`kE9y%gzZfFPJ7RwxEV!?q12rnxmSq#9LQ{`n&kZ ztgtdAh@H&olAT6S-8d(U8cZ1QSKjJ>$%x!-JD-k8(lJX&b)}GJ@0}3Dx|dh(yERu) zFbz$0p7SMR5_ItsglfY{Emp#`wlk^T(hPIs+bL5AcRw5AqJoo{n3ZT)U!JR>qw@720<^ISMPJVp-IC+$$s&$s4avKmMBQNXv(JW;AA9Q1?lKEw zm`k*M<}fYY18=?H!YGM{58eT$;(c%xo?#iKRR_-jkKgSEF+MRp>CvUD$!BDQI5DW_ z8K?bhBu*G8xV~rZV6Qkff)3DbgQ&SQ;I*?sLoaf2~KNvNtOAY&R3YB;C zaE-M$3qp?|PMC`|6VMv*v}5%Z=Ji=fa>UNLhzW5t@l~m_of@emu?rwR(=5ywc}682 z6zdF@2Pe!^L?Nq?@OA5pP<+&*u(_psc%T)+di4577qsU#_;xfDV!!Hrg|vw*K6jZz z&RxR5jJS?B{&W@P<3C{-b^RXByZectgHXa?3kFt5^&UYRh~sx#_7k0mwJifsEnL(2 zJFpdm8MR(trO*!M#$une)=&JI&BPsZ6VYYjcZtar?+LP??Qz}^CpQm$FoI@tQ;4{M z`>f-=OU^=$v^7nqoO=czL+cN8c4INgeE$81Nm1>Ot35?e1wExf@^Ap0}@=2P~CDmluD^f@a+2Lrj~o#7fF+IYQO+1-qXHe zJMM2tCKBs7$MMekSC2D{iaa+q(ON?XugkMTd$(m%S++{c? z&Uu-VlGY#D1#1_;!?WJz{hKE980dRVk%IjE5a0*a#nk;Z!<0Za7b|yM4KH<$<2(g- z)zSKn>E6tO6NJSetAc9p3Y!Q1j93Wbe_%*frCSW**eBWUWF~fe7enQvG*$!}tn(i4BX#w%$5;yO)8e#P zB+T2Pto14@T!>an;zaQ#CIYm6s47sy#pN?{=B&?s#SSvqZmg``tscR8&h=)5xeg$A zPR1BM!GtEbN=oHpdx^H!S@oy_XQiF`nq8G*=X3clnrolI_o*~>uFG=(1d=X<-u76U zWZFiLv3+A@p>|+q!Q=$}me*aG%|s1RYY92S+7L-Aw(l5)&O0>{r&&E0vaUCDkH~GZ z7zV6#A)7;*yI|^Cppt4!R0E3urbdp$S^tBCdJvuZk6QlWKl0XNgeN^QvIhFd_&i>- zte!0blO&b|s%(%*P}FrymRb(0SKrrI95@aRq?4fFQz7Q-)LV2j{GF!;8R?&XyZCJQbgG=vtw=ACp@rtmLWYZ6~ zF!}{lk?e);^Qrw7>w=4O7V~~;mOGB=<88|yzGzH zX^UP$6Dwp+lKYJzc0+WG2}k@Dm~>%=Zhtcz5t8jmj`otm?(1wBzkA5)&(_)PjyieA~Tri$yxiAO~1SzMUYSkuN+*C=sjl^7H zwy@t$1)yK*?f0J(om^iULJ$zRWT3|Zvue#zn$GXGmmemFfuS2G&2(w`hY#g%%Bhl} zB0YZ-@&(#vl?)?EnrA}XV~TTN#s*!jxsaz|Sz~`+uar#8?Q{z+cQEa3VmFh@FH3$i zh84G0RyojYF|0_Tuj#rOUnem9Aubw&lXIYDNfK;Q+cl!_tm`3YAo&JE8@z$q&7B@| zD@V|~fd@cglr+%$ElZGYJ(6$8P+n7WV7Bim5ZZ9&VoQ+bqY)r+6Y~#6x?iyrK6f)_ zzavyh!cbB}5~;Nk^aCl|xDiugc-ecu1_9#r9oV0Vk48!E)e#BhPvrtXm1L7o99Zlq z8|(P%k!;q>0!Fr=px|b`&^7My7ZGUcCMm&<*)1yCd_}~F>jWMaES|CHZRJt0#*Az7 zus|Etkbt?X+?mf3%KH^d&uG_`Q=`(Pb!5Sxg z(0X?1YjWFW(2x?FDI}~y#AhUn=c(xUG8{`TX)u^W5rf{26j0oeWhjpC^AA0@4BnOG zarX2D?+h0><$fFxt!FLjG+Q$_SGLj87pxAZc8GlPRnu(=8M41iwo(q4Wcc)hp0!>pxdOFrFl_;b)%a_wt0gv7;3#Pzd%ai8V8Jd9Gl5+Nfu{YKh6cI;>NYw7yCN8+TNntByS)rmkl;1y8V9zsKxL(3Mv zjc$yh|I9pkou8PP7#P4txDSb#0tAsHaG*(z&szJaifFhD*{K$%r{@ zyeeL9Ohx!`v%W0T#q+3Y3U%kNAB4fVIdjTPT~?A79U$~RBEAr4?)`_3b*xk4Wrp9} z!2QBQ(btts21x2|&TV&Fk~P1YZ-3!~I1c;2+s(}m5pAi+o-r-6>FLXE%yc?7?GJns z=(^MFE5OT!BlE&*2kBi&!hjy8Ms>&4L3)gre%e%z;giTQ+z=yPGl%KRH@CZL@}H3w zj-tgX97a7^0apZYEquLj)liz9Y45-sEvGu7W$WO)_p%+@9wPs{cH0M=D$76x&p182 zZ_Sit8M1L7G>^^EuI!gzXEkmjWK19} zX~M#ipU2X-uW?M> zFvZE`ruGt+_&s|aa+RoeQ)B(=usK_FUcM-*s(egIQlR_omNo;N-xeJ`X=khCf4PX2 zso!XN@Ky*i+pWln1O-9xMb}YY&=Xs@LKShe%9bLajX3pLGi1Ts>ZEwq%u0LG&oMEc zGdDig$gD%tuDQk z!Eg@`Q;MNr{XA;y_56;W+Wv8$;SZ+)rxGf1#cIMhZH}-PL=fIomooFG!x7;XdrR^G z)Uima`wquo_5YM}A?n1oFpI|B_Vht;Pi=^4-A+w&Ir9C+6riHvyZNIx^~tUdgt#7X zPdOSR1}DDF*}v?p1RM#kT3vMOqJ(6ctNGfvnmztb{&V7$>wVh@NO{1a6t#84%$*=M zF?|b5-$$MSjC%J=Y4fCnsNH11%&j+iOgUMXdn@;f%-1AC=s$QG`A)S4a#Ps@h`03z z)pfqR6N{f$rrSJm?VlFFt^<`KtTS|F@4~_meCAIvZ*$6%W^So3J&w|p$(y)V7;Cm7ht{PwnEg4U|4!fphWHems`=LsWR0v9)<8FWH4vIVOdDRr9B0ULBTrtdn`Mg13AZR-&;JqrNJk{2cSn@3xxUw=g zXK(pSb(r@k$;{LTl#1=!KUWbjKz{I0KLDlL-;HT`MO}?)vy<=ApI22?p`110Sr(O) zSkGR`W`i%}a*Kc`p`wOH(qFp6r`g$02R>PFrbC{Ka8(iTxs(TXo8Xbhc=*$*k$yK} zJjzJ1(3-;E-CXiD?3%B$!#BiYHPW2AY`J?|4Wd0UiD$Ma{$#1m4k-0nnGKKbvX4{!Fegmph_64ATzD zTAGi$rpanZ;TVI40JB!I=g0%JLqmTib54ZRG(utUzoLSxaYBtl7bf)va^={onvIVa z_nfeh9|6{hbk~gk?l|6=>_hINbSR>dUp^LdGA!(ry0Yrct1lg_b*mEPJp78D%uZ=k z3)Pb#)dbd|a5G!8s+{@Br|EKvYHE^yTb@J@4V13tjO#b-u9B{w_MhHg`V~y4Sris-Bs+GB=Awk*Vpqi3i0xs~_51 z@o_9DjSL?mFxIzZoYYB}opgY#jzh{&EoQdI9h{wqXW?{?e>%=x2fTel!?i+7#snBD zr&qkSMrdS3nU^|{GQ3NQpPl^PHFFt3ic=x?k8MVspcfuKm4_92vvq3U(eR&foWxVd zVoS#7$V*Og-O-=AG4kAmtC|&qE9_0px3qJEw<4p8jzsc36ECiYjMAu{BbORTI_QZp zMUs9#hci*oA3X%!Qfe{71_;ypobokY?b%HHX?ZldlJov2h(f|TRtGDbffz^4sOZfn zcjR84A^r_IR)%wRNVun@(D{Yyix1aXHO%(2m(rFmi-VI)5;n&liBm_mOuO=|d+yFR zjX(ok4%lsFIMm=h4af?#%*;9?M;-4@O^pbII~#{OFUZoaIKbGQ-a8i~7CvQpw{$ge zA>15bQ?zh1@T)R+Vp4B$_|GH)7)b@nMH!Wq9O(y9B~zmMS!`a&{_j***qDdc_+*;T zOaaRZ`O!mQzl(6v0EXDW zLS{9_WS#s#(pJh;a4hg7(|z-DYV^@T8qZ{V_BF;hPEc$~yWVnaxgKy*`0(q17iPLb zvbv3*ETH|pinCzC%q-R>t)`?T5*)|JWi{X19ZooSyFSY~3f{Ou8kN)j(8hIR*_CXr z9GHcn6J~;BLq=vV@m$B<%Ugj7Z0+@a!{Aif?XEEv(>Xo%WqW!V6r}{pp4o{-TfHP) z7et<$IGpp5;n9Xtti74-3uhwBvtQkkZq-G7DrTj z=61{nBUE#OypPqHTMZF_EUUHQx7f9$7>7{0{=F7=x*1{fOQ$}ZhR;vM9*kMk9POPI zTw1AMK(=?^K2b+}3x{?}=$N6>aYOw=({G^A2O!;+7;l?-*?rOJ_0`(?Yn%i-s*n(0 zxAAPlVDnu*db^qTMVHU0L1p`-5-kZwea=%dMnMepo7S(W4&NYe21m*mRc@TzO|E7Ra0 z6*V;QvyZDk8lRa-VCgV{?Jt-lcK=Y(t_#XmchO_-@9Xb3o>7P@xGCJjn0GzoU*Abf zb;Jca*R;}EU~lzN!|?WLE#)TAzSUNQkU!fD0UN1s%~-(aeFmC z-_E4_0WIFdB`-d^%Iy#phy@WA$|Ow{XWiR&lwZFZJ?I)~G@kFzRi8CMe}uWnT&3=! zB*u#y!SA|t&UD)R>WMkW`J~yd;P1A@s%Pg&x1CHrDQfBi-X-d?qeQVt?{ns^PM-rl zEW&dSPvUfEu3To8KoF2hiRVKw9f4nsoue^92g~%v+0k_y*&Pduv^S4OJJ)$>+pLhU zV-wPb%hLS43HfpUc39*OMn>&07JyR*a%~-g9}Dg~H2&FIYUZRjwJ|zZuh>z%E+Yvu zQo{FM;-E?4HTL}{O*E*lv4%Wroh;JWsPg`SPl?FE!7(zz!du`poGOSfr4=pLsemA9 zmKF8h@AevoSPG7&wa-iSSnItoc&d_QWN0WqUO6XuN)Q9Of}5sh#zk=ubMaG!-_VvDJ0bIhJKWQ!1zuc4sEP!SHmPn5zO@?m8|{7`rUa%2;;clM{7C}; z?Hfs^EZoL@Q<_RIbv~dfVdb!4D5^+RzY z(Se*i5u4+$^Zk8Nm+gIqJdF14W_)@35537X;5Z*ZKi=k8{S62$Iyq#d;9$C8QtF#i7Qn<1@%LOOeINMwhKKh^ zfML}7Tb>3S5CkPtgG=-eFpK)BS}k}|aaUvg1#*T_E^MXH2XbfMi)DfLPN8m9{lB?E z`Y@Z?W^W&M!H^L#)6@4q;k+5!huD$w!&BE{EMYQ!^nGXRNk?+UNC{>*Q zD4#^knyKGB05hW#Jc#OI5w@N6#aP>gwagNNqbf}DCDQ<{-?zV>c^+4_E z{-xjpqO`XT+y5=y1JE%)jS3^1Ur@O=*}}XKKw9eO09AIiiBGqQpRmH+SzwxcZ29Sa z)OT+tD%ct=y@f>xD)PhLXobjfnxk|;NI7=13Oqt@wN*k@e(%%tkH`q_Tnff(G{7t4 zuX1PrvHsz0n19py4ku;*cPsi)^N;mE_60=8k<(N}R#z30Vb$?Fy0iCx0?#hxf$PE> z9Thz*q1zBwX}t%d45)ONOqsxvAmaGa`d2aEQAhuF z8RuE6+$@>F=Piuo=CkMNsAkB`nOlCr85L2VoPV)Ug;G((-DuN%g6BGabL-weO`EJT zY(?h zgfaVd0DB9M4w+B>v?{b*(JEsebd!hC6G4lil&T?fs5N+!N@Iq}FOeJn_EW|bUC!@g z!t#=a!{QHX$YTn)4;&mF!Rg&q(_J42qAn=i5GHY`)56Fn%(FFc{IlkMIWOPux_z}a z50fQ$z@YU&Gfn7=r-a6e0{<4~wN)x)lkRnkq8NPAy=42g>AYxCZQ{qA-vRTF4l1N$ zgH+$AE!~GIOw{GoJbUp*Iiy1;gj$a` zoS(k`gZ823^;1BdVFD;U_n>$M;r#~pXYW$fYi7O?azO1Aw*NA+vyI$T$C_<#uCS2a zuAM^-xfyx{xvQ&#LrihP4|leMla(V*%zH{nU=KdudjhYcz)Up-u9$)HXwgc) z0h-_q`+w7MFh_V_j^p5ge~zWdgt_6~4Hxy?C0XqXAG|>&RCV*Mwc>q$(XI}9OqxH_ zb;>v_>p9cTSH{1h63mgGf;*Av8PXAHyCVX_k1SAue276if}WYDrYyzwwY zs~cyF*1LWtP#qE-r=|+=I!9QZn#A-l$Kp{G$n9p1B zV(_wW+tieX5L+J>cON#ZGUtI2DrJVZC@$zAt^ZsscuH?U6}pT4pZA!EGwy z-$mu$b!q4AkUggm;v9bmJ&iJ2*!rxix zLzxLs!;nXD7?ZE_CgxDy^s7X;^P><(FBZ`zxUz+amb~4H4ZvG?hMHc4rKUiT{O0sG zbB~B%t@U*1SzXjBB)p+jJXP3{vHO7MwHZ>j2B!a*ToNkgEfe-&S#ZX<(B;`1dKWBC zs_~-7(ab=^iyZ>l`uTqcT8%-b=bMAf_eH?$L@V0*z6=+J?p`Xyo_y1gzRKP3`U;&5 z9vrhdZiq?uV`APSWxKPEsJvWm(MN2%H*1ZL$1vMMUuoWZ9${VGs_HW7X<{EAMm}o( z5*~BSfY>#8_dIR-h4ODXe@pGf;nVjuh}YKj znQ~rdNVW@JK_mTf&plMwV`R6uut&m~OaVg(uR7giT0;N#vdzSos3D(PDvIEn5-m1r5HN16sv4b~3@FZRiFGfwaoKfg->IrF5SORH z_7Ar5)o1pd#87^rw#)^o5uTJAJ##O;(??i|O%H8pjXmf;1@p5#^W&B2)4F&$uO>jT zAZUs=!be`N-=G<4i2Ql>B-*>KHEt^^D8%%sf5x}ohIpgM#hYW#<=5oqA%iuR_jp;G z6z-*hlW8oX3a6k9Zpy=+*lCuQ-i-H~-uVof>xzAV3 z0pI0tl%zBC63NGZE!rRfdiW|hwvqF`YitGxjFRTi(9nS5iG>P@3czvzRs@G6wR_b! zfJB{wf&$=^0Bd_L6AcFe2?*F~w)Xb2o0=9p_RidnTm&vWgie}(uIK9NYGBIO*BAVp zJ?N1yz%Vf~Gc(t@w6wIqPM%OAAt3>N{m6F|HMPDNekmd%X`1^ZXmm7zhY%@Al1sP$K$kMb-_7>%A4|bhfbTG}QiqO%~fpSLtED+oi4MQ$xVRvgQJu{Ocok6=K4oJQ#fC>fdB+{9F8dEo(RQS(XQX#ErTZfs8)E07=0b&N{TEhw^Uy| zK0BLeB$p(LPDv6qHL%qouy?y?2W=fZgtfsIJ_AU5P(NWsBdAxV49pFr4d?k zV6fOzQw8)^{}Ejk7bOtOY&;JvX3)K1bfk9LJm3kNeEIqF=PyjdSrRV_ST}h1tBPbc zfC7wB4KBe74+|Tao#o2~AfZOm(6xc3CDj3d?8K>NXQ!v}Kp`u1@qb{)=9-!~pvMB} zuc9rN$~6Z#`v_(3H4t%4!1Q3I>tmDR5)y-L_W71Y&#ySjPE^Zz{y`P178kWEtk`BI zSDJ;0%J>@ZtWUBebVCBwMKTq2y-ogHl7!c$uZpU2=N8ei(UjtmGIdz4J)Ss z??ZlbICcjRUki(Y!h4|mVLQMzy8--Q98zQb+se_=QNMC&OY`3=yB<9lp)+`J&q^j{$ppKWzZ3*=ATCiF>5 z9Eki57ph(y5CmS zQYi_}8P5$)X*f9&I`FvS0P02uC#Tfs#^D#gCr{qUi2p|Te*{eA&yj=1i%basF$tW> z)u^4g^~;%Uy2yrWsNVB6rX&xo6dBPo>SUTM7B)6=1=!NkPo4!(_tMgmF*T)C<-Ea# zO93dBWhmFVsyD=KAflO&JzoNi~5pd z%0u)F96x(f58u{P8+v+rP}S{A7rU2a`jIuO(K2c3-&9k6{&)^0>9gVu*}I5wA&JA! zexBA#0+x^3_}4zF!h_2;1I@NR=|c;4$blWv(c6z+1dC!?y?>t$kW=An5XZK~y&S#W zGWtvL!6imnZnkAUPpird?_rLM`z5zhg%q?M(V|Q7;J0=U6$ZULoYd*n zM{)g}{jnjMdIG!9?gYiwoU#v}oA;4#^R9Zs*T z7PWpDc5frKC`XVI^19`v-G6q-hF2_Th4)0AfD{|MyhS>4;^m4Z-jP-F|7@Z5pI|n~ zz|pGoR-dgQApI>6>pX%i`mM#|!Yl(3khN4r4#x~D_SrT#>Dj;z8ojj$&f7x($Ka(* z-C3SoRX_X!oPP-j2nMFWv2JReV+85>O&1f)^;k648={K zSvx4y1FrJ9L?-RF9+v!<#+Kidqt+l#+fwd*lL7h8LHNVzA*r_5#TFS6Zp*8ZCRumD%LnUH}vPpaV1lBwe;`WYYsizQu6=L*^u zGE7(p1Bwt*9e9ls*4g|Lv^7|@R+P(eO3N4LwhV%RDbRAN>u&b#aNW*+{1bc7dZUq; z_+QfY1}ud_OjZ|9yn8ZIfq^KnCz85RTZ8S|0Q;YKDBoTDgC*!Kp9A}y(KsrnkH?-U z2*H424l=fPfKwIwi}yI=X`^$R=;4_o-l#>VNrx_2gWASe%l6B)d>={|(2rXG{+}H6 zYsR$rVYwmPK(6;`&1H4EE>nqdGxeYU-GG{4kT^OIQ+>5IYb_P)=>P<~YX}v4j&uq` zVwlHhVJ{jyC*8kkwvXv}FQ5uGMiU@S1^PL1qG#~a2!Zjk7>|G_-;n0Ul4`+aO+a@( zHe2RDc-Z?tDQ41e3v0j<`Fdc{ZllgpND#%iCRsE5=rw%QPi(HnyWgXJ;o{65wPpp#i3o~R;C}xB z7?}RV$3BHetNhG1ASudz0TCobv1Up-Kl#*4KZyUXi$l#zBu(4q#G4?eLcIg8ZZIuvJ?*;JAV@kgY** zIWL!l@pooXITA|EUs!90p6U4Vc#Q-YvS53*WU&O^fS{692IpU(8P`I(!VEwS6dv*m zm84St#S^}Un^wGnk0)=IZLLQ_)d7c!B0S9pZDXYWhrPEBs50H!hc`Bg7@&ZHfKo~b z(x9M7Nq0y|ONw-dqDV_O2!TG}9_g)Jo|(p}Q^ThE4>aps&k-+9k@|NGuEXP6Cp z?GS6!D1Ci>6^6B?p#k~*S1qbC zn`5%Bs?8^;=TBt#s$6^`kR3VX1Q8*jk3EQgo>dWj*shmC+)j&M#lvtvTO#O#2T6iJ zA{`aH4`Hh(#F|3!-vjSC<&on(o=Y?Npky!p%>axl30Vq$2d5K0I!lNps!)KQ5Sk16 zYWQ(4mSoltXlg0AHC+r7Oq3bgw{`(T2xW{5@I{@6YPe;&QD1n8N+^7gxbq)&mvh=x za#|%OWVP zf6uPDFxbDd&Do*lc7t9iUDPB2mgF9=WrK1g>bo`1{F?JrZ%G7L;aY;b;3AlB&U?Jbda8&)jGUGwqfug&7 z`4(n@Hlst!X~&=QTG33m(9%`$wUX0iFqp@goENy!jYNA>4plFb9|I~1$n-dt+Cm|Z zoS%H5k5SI%A%rLiKd{UPc#N&Zzozez81rXlX8h1|$a#&#JV2_f(2THeYsO9_%7zP5S67F$#5~VoN%Wjsv&go{My#0O?(KV(@ii3)(1Q7I~Baj(DD=KeSul`wVVoP z%JAdDa`%pUeVXbiB5-GI;@Tg>=%!R&?AS5AY4V*LWf~pEU-~mffu~MxJrhZ~m5Prg zI0qOl{&r{YU{4pjbl%xL+db?P%h}wkT9{*#UI5kr5yDPaqM1$`%hM>+-eMcgjlzb> zZp_@5+b2#PIq)VWWx$6%^F?VXDY!!2MGPi;%sFAyZ7yZGNjfCd1d!=MKU9>uZI`}j z=UW^U3}(dY7&5Zs@3UN&(g?~ow04%XdK@P+)Ga<7gbRSvQfF#x{G)g>^JO+mF+(l+ z&T37On3BW`qv&^sj<%Tc+LpLv`v#pY^SBjH+G$qqIv&h;Sy~XM2%Ckc@{;S`rFo7_ zz<>_lu43cHVq$DC*F3=jTFQzD7&5tZ0zh& z2^ktC9OJIjw!C1-b_lVBhQ`2>DGWYCt6MG9TIx(47bElrpb=c@n9$X`Q#!92$%}V9 zn)Kve`C?R(4(mA{hv!mbb;v}b{s49|M!+CsWbU3+>p$MAJ!k`auaNN_{zi3gVK8K4 z6%!Fb#uy4Z20w((1G9w%1wR(o%>_2SKGwO4O9wg-Z?(J-E8HE+SdUfEL)T>&m z>`;#2G01%j3+;foE9%j2d&7KN!~b^?Q0FGqqjRna!YX6Ba#9pbSkc>iMJfC~)^ zI&XI|Yc$F0++2cZXe*=p_akj%Iyatbe`#y0stcnx>`B%p9&yzbpO6s3uz?jXx8qL` z4W(An6jvI`*B*#QpThS7FKh$j^BNs3He`|*XofsefF&n^pMVNO%i67{+JLO0om9rlzM$lr$85SG=MxC1S^;ugQ?5(@>KZIpe%wjP9qW%4)rAm8#h|WS8j>mNH0> z=I$@8do|-ce}!P$n5Vbs^s%EU8pC3Eert@4X{O^%!{sIp4h|puS>?J!goLWnx2Dw> zQ%}}-MqODn-FUXbt5sT88EFAu{GnJ-O#&+=?nWa~)`*ky>r^#=Tq~#8pj2h}YwmWR zPAGS`=5XqaXmE`5^Yvx76W=G& zvZU6#!Wq@xc2C3n6ap4qF-B%!k;82{bOfxFaqEwhaap*76OB^FT_H0wMpUBAGsAd? zLx@d!{q-ZjGy?>KK{ba;8#jqa(;layzZp6Vzj^Zpbh>O;V6 zVD#KuTNobMXuiIPSDa}zk&+x8WdLvjm;D@tkdRQU<3!3xf!7Ig0}G4i!}Sp{1b#i{ zg+&q=WFr?EfU2CAmnS1D`vG>-;DW44VD!+QsZk$HE$;rNe=l!oS2c|4E&wpBrR5eJ zHSkof^}Ed!jRHRf9NE2FTjfx~!or>4z{nKgi=1@#1zuY}SiGWRVvNkqIr;;`96(ym z6(@xP;E2od=UBR?(8W^$7jB5TA+C)HE(JwqJepv@n+?6Gr)-@B*3+y@&ykW2fh`0W zWLVW*PNrI#uzRQ~i_(;5b(pfVvjbR0OkbaRvLj1+Lh;TWTtIrDVRHQUu$sX{=w@78 zT4etS;c*;ttccY3x&jf0PGa>*Qpw>S|%QsT{OfV1ZHj<;zJ}(qEL9Uw9VJhBi^IE&Y~j zcmj40!aP|;#e-B2kU!;{5Di#F!n7C_9DEv#S^-Pb8EuNY?4S=1)d)tKpA6Q?VC6LB zEHoN@$o(e8`%H}zl>NM~*7Y>yX8xV)9yi@XqY!OAd6!Vn;WC2Blb+Q3+>jo#hE0|%d+PXhJ`^S|Xc zY{&1GmJiU18u~-)z;Zakw>;AulcS6{F@aSR^m2jL7c8_{0i@g?-@iw}ZD*zZL1Ur} z9oa|$ggB4|-PvmZfih`NPb@BWyql#n42U1t63NTUf0}4ZYjm0FD~q|u92u<4$jFE= zC%=BJY<(?0I@I>z@nMn+7Yu-j2&*LZ($N>NKd|^o_}&(O!)b2KIbExwuhfIJ4JMrM z@NlCtM<^|M3tmKAb72rAPlshnGpVg55tV(OB1j$#>z^HkDDpNY&vQ{RU4wejc(B@k zgu+2j&(mdNIZCt2nw;BG4~|biV73H3sF+i3!lOw&S>kv-KD5kdw!|EI5vcpH5*}sY z;(~*%UC$i14@;lriNjvT?!ptvm|7S$4Q9G79SWt>A7@t zl}4Mz24yN^{8?LxI&b>&Jk3vc%3!bd;Rp&fDk!BQ%#!l1%jrkG-r6t(e!yJ@@-PmKDe6;!}TQO z$v$`zf<&pbgX`6^8_MrYRMPlY@_fRa+EJxA8EKO+-~B45UtyV~ zduDrMR;0rQ+$QR{M`J@;S0Jas`@~F}G_?QJ?a>ttH%={Oli}FA1?Ep5Kw0Y!@zYz< z(t$-o@lXjHV$F^ObFRnQpVb896J-d`0&SnrM?m-febFkmCjzoEZz9n$bVof@NRJ(Q zj8OU?fpi8vE|48}U()l4N* zIgjpCgo#D*^6-F-PH{00%jGz0jheyvd&Gxe!UI}h?D9lPBGEhJ4zm%%2u7z%%9*Yv z-->y8d0Fs2#omcLq1mWUE?*XX$F3aRFIJUiZ9^m$-EZH!_Cs;Az-qpZ84oxGuxY?p z(v?g!?b#C?rK)BHG|;pKdD;LK*6BAL%#uqPwYE-{AE{cnBFs~xe61H4i4KEp5)c3= z11kX#eTrg*H)td7aYcChk2N|iIr;E2$2e(CeL1^w`!H`?_P7~!@9r*R<&$Jq``I`- zW7aKu(4Xr)*3FR93wPFcr2Hrai zx9hAc-Oh?9uoCPI(6z_po9@U`UDDf>-=P@;#^LjoF}Sf7b5+myZ|dBSw*9zb_^rme zo2I)4!YWg82#A*ZbS9fdW+i*Q;21@H**mUX4OOm~cD_E4>w8|y{7{C%%BgOqUQ31o zWvi|l>zW1YS=x;s=c{?x=B;Au#oSDDqT9Oz;^j@G6%@8G z6-z%A?s18Ay~N0_f)kF_r8G|Zh|H00kPaogzb zhX`2RVK@xegib$r_57yXvkdMxpCwDR`2&CQ>6i26o08T0jBuP1--Cd{K@Nk(dnot+ z9=`tx^ZZinrax2c)0-?^XGndDlA=x_rJ~GuRZY&oTgCM{$^TGEZ~3t$re3g`D&F`;xvT zrY63PsZdw7ARZ{`;YK~6I*IS)0I{Jx{M*1@VHq?Er02Fv{MWR)+2}_*wrXNmXb}?9 zYf4$W^2$6@ie0!h9N?my&D~rX>o>B8+NmMA6)+{RbO~(L9TGIr-vI+w9+E0RyGNo7 z_sw-wY=_Cvh0d*keWUdC`2#4!I2)z94S%!lzCONb&rtrYacLCHBbd%k`;Vi6{M%go z&@&Ooep0Q!u3l?S8G}kn?DCfN$8HHM3D&=kHz3Ekw|X z%}Hp9M4?lBv{ZTzeMM^d1^;0loMB^UXK3AC2>}dezcVYuVi2*#!3-e>kOwqcK_CwZ zs?j+)!QBrkAe7T~o&9i_d<{Nbl$#qQZwRC5hh2s1|J2BQTS4S9kotK z;FRq~=`wsq_Y}GI4T;WYCs{5E;`MI!qg5Z?CF5eSjXle2+ZfQO)9C5R9o9Cwi1XbR zrcpE5Iu_&%;(OH4my?B@gKIOE_D;GqM6|t{$t%y^mae)v=|9W72=yf^yNd2wv#%Xw0XjSV;_wxWsq zmL08A0o(mUsa4Q3*XSN)^b^6`FCkU(J^eoUaMF&*=ITY9kHW+y2A|BcwPRNMGrKHQraEc1 z3)Ip_oKD>il)6b`GSF$yt9{8*pa|f{nD(+jPWHG6mJFadxI^-3V4ASz-kM=e#8aHf z%0+xb8G%-^8Tt;CJb_+#zdU6Bb5N4kFk)O*u=WXi-f{rx@Ug=cjmIu|jg|&(e`ntM zplusS+HkK{suHc5VyB21OHHg*6wgRInq1`}nXA*59#TJd{~WY5{c_}#pXZS=N&(@Y zJI_wtO8ER-hxpK`pS2ytf_`HryzA5VPVLb%ZBwTa#z2j3hN| zOJs^x49o*JqCy}NMPu~Qf_m2|c z1kG}GH)86Pa82$h#oozg+rgTgSSK}H344aumW+6L*A=x#a%a~xrmuq2QR;^N}4tRFBZ zK>;uU0M-EnIDk?Gpg+PGHc&|d(ged^PEJl|rbZ`QMp^mrdnj)KsP?s^L$|OS(sU?| zK${xlCb@~}X=-9TB<+tlG5g&szCT{3T)ro*$acJ&>*bmP3QMH9@UkG~C?o^S#Cors zo=5u}RZ`^GFSyj1=qh;w1vp0DlHJKGm@!{G7~5myV>JWTG79Q`+G9VD|CIL(!9*ko zgp}Yv;sFK_9IYq#rlP)ecjIz7Bl0R{HnvI#S3o`pnqOc;K@t@TGD9V$LpSa0IDrxL zD06&o2^T zDUDA}y-H8_TUf9}L6=9MF|cuP$PK2yqMLegaqLIzx5jt9<|s(&EJ}L0>U$3?okWOM zWttNcle81O??HxP6UNSPIZXh=1}N7Tw&?@2lM@pbT%@h zM02@DU58B1(radMIyQ7gL=wm%AK{5pP*#?9A}mX<>L zPGE(TzL;^r4x0dS{(wdUNZ7j4A0#vzmM^b4!}s!%a?%-c93Z0 zPmpfLdU$vclwQ4ZMGORf4*c?Jz7C+p^bZV_S67#il=N5a2dE9VuS7kQV4@@?rPdVT zN&p8V(kM$OTNn6Lr5!eLVB!s+*_(7fsZhu&Kh3Trz)rfOKMimt?&?0frfoqn2V1&a zm~UMQp|IrW4Z)6VU^=O|Boi18cHd=adMZGvQ~85|xvL%h)vg#3A9v zZ8y>%+Jd7tLsQdh#3UKmSTc0hk5@*|NSKyQU41fn-wM1$Bcu_b}!R%K>14!NXf zRJEHm2&zp^PlNNGc5c^MU|)40cF#cQLj0`z0aj!teg$lp#B$a%hF1B~VD0_1*PL^b z6X9p=9)jT{28MmCOn;ZL$-GOnLib(DpGKtkhan}0%9+vNlzR7FrX?eEdtsFhOJThp z=tf<^Gdk*9boaCreN*+fy9^qcnDJPv*tiD?G+{tN+F+YEW9-`iS+TVSEioRGN`e8? zpx0VKe$h{(-{qEo_DMlHT~x%KTyrAI+yv@vz|4`CPaX79DAjs1f4dkfdlUmp3BpG}fx z#jJjq^yhm+eDul44cE`fe3B4C1NZO~vn7zdB21E45V7wuGDFJ3bv6L~R5FxuFN|2m z(e$sgK_v|y8yN)!K@hX{X%R@$HhlvjKF4`>c6K<1&w6V6EsE6PF?_=(8Lvqo2|8L1 zjzc#oPKu86NGAR?0xS6Wjjj99(7iyLn4~t~CCy7ccW~LW0L&&Pi+`i5nFf#P>?7L4 z@%-8s#qwVUPj;01`hU=Wr!nKOBkZ03tT^}`#ThX?xr`4=)*6QTcYY>$oairgV@&$HakUy(Mx(V0JLz(Sq&+E165MA#8e|*1TxEq~3ir6! zX{gNL9YRcx;Rc)@w`-Vu5-{phMM;dOL!5inOj#7Tl-4c-;p6pZJ`TL)%A$0{Kjvj+ z=Y31a0QZT&54jZKi>HFN@*)kAF-4!LRaL0s3#nfM7wU_RM$g)@B+VLryhJ)vol*0W z-g4~w0sOj};=U#y?txXDj#RV~A;$!t2Lo*ToyrBLBLbBBQ#5PVjg(AmXE?DYgu*{b z42%szdrRzevsEC>qCY#dQu9%>Z(+#a`rvxQN?+gRIi!uBkJ(~^XOgJYu5~ji9SVLX z#}$D}eiq>p92KI3)&0*r0HC=3v6kqV{+=oDUttwP%x9V9kKs&p~{+Y$G&qmmHh zE*vp6SJ}AmFgKHE|0iaIjk==*R0n6_zpg_6WOqIiaHog3cc%KQvUs+2$}{sK=Dn99 z80!Q>J9#3rZPKakfr=?x=gC?jA=O^JQPkgv0)yolK~96DxY)|xZr%JhI?6v5&R?qq zgN9_!F`zKoFPQqQPC@7W`>|@v52Wp92_~<;Y?Xx^EC9u_oH4p3gjVPud zF65KbJ@@&)%DjM{4ddGT$!7`6mBd*L0Wq_dmdwU!=(Wf@SrOwmF)<;uVOI5VS5G5n z^Bc_}7$Dt!iHQV#?-O4S(*4dS4{GzvjfN)QU0_EtT z-EuU%2r}!TR8LY47zLn z$lbyF^!Z!)EcZ{B^+&fyCVeNG2hOk?8ceUqA*7Uof`Tfhr#d*#C-NZ_Ou=&NekYzG zp*mc$J!`q4iEtphVO{2SUxpzeAOi{31MV)Gwt3FJWL2Z1zoCOYK+IfyqpylyhLkD7 z1PDssVTNns8pKPO~l2^J#*GZn1oE^um96s@(Xq2*kh1P#Gq@dbsE=oI(%yeKa4I$%>qQ<($Qg94&+y)DatLXzqbg%+t+e$2)e6u z$)T7cj!9w~I`|S!0BOEslD*&L!Gq+&!Vc#fY;2xjCqjz9|KuLY-Y>En92-CmZd88Z z{P|CV^WRrCJjMhOtC9Eb-HRmM+}s3QHnz5nCQFi&Yn*Rfzi!&jd6SD2Sk{2Snwn#< z{ZK?6RYyl7NRPxcEYW{92O;wo1TTy7@^T|2K!iRi-h%FTW|P}jtosh{!$HZ5$jZtJ zxD@8+Q-6iC)^>Kj79uSoQj@oIqYa4qWV2hVtE+hksXo{tAwA>6s}<;AGQt6+#9c${ z(-TfC-|m9PVjeUmfjATVHqtUP(J3jHGYY~3R#NivQ~LJbDFcGN+`Ox?+WB+ml2TH< zq2T%oT5s&egJ#Aqw2Q#vPloW%!~`hLV4DF>8j#VD7$Jo56f-lPS&R`vL6Q+RW)ZcOhc)eBWpNd4 zZ*TR_g$62=ROuKP?$SP>t{P$vN&9UyVaFHJ6I6ySjHl7nz3~ zCyzh}Ah<+fUD7d(O$LseZzElzJByqWfuP@;Y-DVl1XbNzH7Aa>Bu5!-o?PT181!Y}ZQ1%owYk_h|As_oId3QbQnzyA+Idyl72sVLJ{+CFSw;(2`>kQ@L$!YIP2>}xTE*84lxtu0i3h|`?+X{F$ zCOR6DDB8*{iHvWGI%6Y|p7l-?h3iEhLSQ}O zdp(9bv+LD)3-n+VSEyC-e5)Q+>D1OO=oa}2WUog%wD(&ekf5MA zOJ$I9;lB?+z$zeMQFJ!s=RvQAj-4+13%26s-<0m&E$$RjvB3NE9x{D5@moota1@6S zCWYm=-X073e+UGdHyO)BVwbOej>fu}=q8QIRywo}M5sWbUn|6xxc>%$`BUtxcMd`{ zaXpAXw_9|l&hgzVcU5du{mPX#Qr2$@`s#x>U0k-X+&dKp1;yb^+Aaa);6a`l_{&20 zpHl78E=zJZG!Nz^p-S`DJ_=p&{+sF+R+egfAJYDuv(9%>ztKBKN&|zw5EE?<9^L17 z#NCFveyujjF3ISwaNV2Fcz{nYuA$&zt|JE>T*n^>)Su3OkKw$VYMj#jgR&_bC2JYV zzr0xw{t9#9=wk|xn{Ppl0r*V@@Z1Pq460%ZfTL|V_V2}!X4%JHM8@~q03~obhpXuA z%xhnj=&zuvI`|?F#Q5SlK*U=ZvA(l(7x<^t6fD2TcF{`_m#rYekwy`!lwVQn)* zWG#W@0b%lxUZ}AMwV`5M&NFH;D5z!sZ)`riXiWYopl!SQM_`;;Yb1lzs>k5oJrF+X zGWCPk79uzF_otp3&0>`PGBU~0zu_j7oaA*01qcQ>vqdo-ez6yt<#$Y0L5#Gx*02Jr z?bzfbtJVp8eCSj6#fHrN9`m!BL6#2BePe%dZ^PU7Vv+}lf*(G7@XP^0X;hZW-wPlQ zQT)ZaEf?c_gM;HKM1->|`&)3~fV==$wTju^-u7Hy-q?b^Z@_|CbF{Z7#)g&qDE?&M zwkv`Jqe>tjR;4#Xc4Jf)=yCxGcldINwzOVw0w!d_v8!HaToV+tQ<&1#nf)7VBOTvlRPl1{HkmOGY(KuLIhUt z5^e8~L~%=Hoi5SV-FKChiI5AEpMOT9L*Crv$(Ll@1N*?ZRX4%F*kx2L!Jv3OAna-g zf~HCMkq77JTMwE7>bFk6=$(t0nTaRRl$Q^db=dT#N9-yWEjO9-%SWNz+!6+;jXb)D zCDf@rY7^}Za<64G=gO@S7EI#Y|!izp|}X1Omy=mPo&xELOd`<|@h7Hh){fj;8v= z+SlY3n=MbSm}7%pMd}3pSm-q@AKKu(6bYoc-_QX#o7^}Ch9LFV74=NakXizbQa_77 zvW++{UJed}Z6$C{12HGuK8ePZzEMVKlxJc>4>SXVvY`$37KIHqh-g9)!>@K5mv3C> z(>B(Ue#6rSo)AUvlxk)h;op`*%iSy@@} z#lW*iBbBR73~I{OuCB{W=sSFNHPQ>UY$=|r8Ju$@jPZM z3h=sQF6bQQCi=fC3H}n7DTl~nUD!|{!BD%~zaicn(zE)}4Pehw1Nzy!%f)`-P}}(p z1lYp@{`ij$&o%JsV8n#n-prhQxcK1MIimKh3Lysnf3>Wyzp15Dz1VA$_f+8JX4#JF z;*zRjvdmyZ78`^fE>JmOv}GYY=Kf#O=gm~Rb1yP(cWz046s~l3dAL;%Y#J*l6I``D zbv70_d!Wd_mis5{SBmCpM=Xjru)dgN8S9Y438zck7qcW1<_d368#Y1^ytG~i2OK*a>r z#{bo@r8{_>3?C2AVrOfG0N<+%M#4&u)d@sA8n?SvZ1m2y zLcIobXq(KM;G7kw zJKt*WM?u~y&Q#36F~k1!sw z(r~?;&|(t@ngkRKwYMq@m=bW4LY#=eLhBc74yzwRBt?MXI{Z@j{-uJCJrAUmj|hn_ ziFVjv8xYcK&L6e9DCP%PgXZQBqWyD2A=2p5{^WSaqwYYg=P=`8G5HJ{q7yfF1wI^rl-NF zSyo+e$n)r#Y=Q(6;t&u|pim+g9P~ay8)WE9TTLn$l5IEJ7rLQdYM=e^`SMg(NPhE3 zwDRHp%E|ab|KSjW%<7zP2OZ4zNAZD~>YLQmE7q(>D5>a~(WeBa4(Ohvtd#mEFKcO3 zz1rZ=jjwEtowGefRs`lR>5dvS$NPgm^L)3| zN-hQ%QBawJr(3r!9wq||E<7RG?-pEhn5~Lz=aKL#Wfea1qfby2<9xAF$=NQ<#0O9? zGriOcb|44a!Zhf>%qE#@YSJgd<94-$4}wVOQ$ErV#X9UlWwNMOOt4jEZEffntGfc$ z+E3fkl+SN`VauQ@jn13_zVQ9%r%)G)@KcuW5=mE1u_j7W&fbXhQI48m(u>LM%4#SU zucBWpke>(r5gzCYSe8#6eIoWTZJcz}db8+9dc@2-Ab-ue9}xchI|>Ym%Y!yvM8(s;O`3`g&6FN`)`Tk>a#~!hmvz z$0;mSx$CRO6;1t@TGXu?3=erDw(73uTcp^B`Mc_uXUSvV85Xl+3Dj_MbbLW~6i9xC zF_V7I<4obik#}O0Gwv#0)6`##{xW5Ue97daV6ksinz{yot)1O%S;B?{{)$(n(KBmd znKRBB1Zbz&aggO+E{eq#F?}i^_4VhYoZwC@iD13 zgRSklM+c9gO9SQ3m++9{r>hs`43*XiSBMSSu{ecgxQ2<@aeOwu2G-IzCohkl<`oK* zx_$fcJeaWDZ*>U>41`s*#)YHHwQ(c1$&hw1H(|@Pbp<3rz5r(ejqx~gfpcm=)HL7c zG@F>2iN8PBxs$!Ld9~rns9eK>NH;MgRqK;k`%z$YX&9>l0lAFgna0LOuFbhm{?m5T z-=27TBH~uaUdr9@oq4HRcZv>Nl35T zp9Gpc*N28Dm zoF|VQu=pw~f}AA^Aa6eyCofV{>nw9;K&J~}L?pjkIScWjdlHQKw$pck;Ia<|FHZpCnxL;~K0ZfRw_M?FFgDREDuPpv zziO_5YH;JVd1Fv9f<<`^3;{onMm^28jt;de6w@$w0TbBB0SFUM0s`zrV1~4Gcl#Dujp_`1d?LRv(QDWL1X9l*Rlfd}ff8j%m&f~H}TUVDicyi>Go`cTxY7feuzz#^Q8d%`FDBv1&7Cs<{)i&F5xX!OE_01c1 zIDMetGFy#EFld$cbk@LE!U~kV@W})~-hfPzRlY>hwP`DTPKYs)$~%k1Ac>e15C>cg*mZz0$-9Iv)l5@>w(nl!};~yaocUFJHfgexcW}yOsrl{Q#J%UIy}=gJ6Ng z=?uO|a>jKSNd7DjX*4AzB)v1jPc`#&Y+A^P1zuAr7w# zyRO?dR;KCcc1Vvf|N^CQ-Gx%&J zYv>nks%1sU^jG7&m20arqwK>>r=q=;y{kb5r61qV(PATv)}%gHA~m9zGwG+GIZjpF zBw9ni<+zV7z~m$B&s2+GBA#l|r^BGA3y-Frs@_wHe<$8e^R>V%FM~<*+gC%nJ`V(&#%L8 zK41h7IFJA*^@B0aK?1se10KB-M+JjGYCQ zqs23(+ZQuBQ_|81x+*3oC;ek8E4P7wcFy~Da3r@CI*5x3_lEYZbEkES6iD&CL@VN? zl0|z#D|^v~mcIPvl=s(hZ%b||d37e`_RJB^2Yr4uF^Prpr zWr308RLu!E4eGdO2uB_@7r3(;816@djl?w_hR=}Ne3e~ojVNcEZkF-_DLD?x{N2D) z&tc1Ws~s{emq~uV>1OjAI6LbeZg0)*B+D^Ygh|CfBmv9Ljr-8f8M07 ztSQalqR3LXK!^$zrjH~cUm57qk#)^9muy3kC3LOvwQ^Kml;)Z0w3Ki?CBlOs13i3l zO(y6`eJQi?w>)cD7LN$Io-zZspS;FDCDfmzY!^9b3> zP}pEjkO-N+)YUJZcfuw5l2yu>#7fZd-l9#XY>29k!!(6*2OSg%4h4o|v^#BlqCI)Y zXNjkc?`ZEx%G4#>ZiQmswzQNf-Qr^3#Kx3mP$<4mb>eZ8#<0D-_RMuYHjsnpHlD<= z9gP{&YvTLu>SCI&zlrde#rw<%II(x}U2BVbrekWAS`i@?^Z3JyQ07Ou3x$B|e{mpo*gshT4u%11e*Do?$z==oOab627qturw* z&aqksjjxB=^xUrY7mHJ$9a}**DfbhJp_rE)UlEpy8Ir>@ezmvCdg}u3{8Gjl6b=e? zNAQ*c&DFELMKj9d6HI6hX*+W0y9QiJRFXVl*t$(MY%i+6s&zy?(91{BE^|YXrx+r= z@$DOBAK$KRi(R%4YvK#ux*;U%7ikcWpVC=Y7uH`jrC4qw9X2(M+aes`?+;xas2DW# zn2yI!8N7>vWd~w_kE4quwfNqmp+{Kanx%-gl*O`5AC`Hp2=n?4pJ?VeBW^N6+f(or z`g7ns?;TW`f^nid^Hz|oFB4#(7v>WM{J;mo5|MBw!e7N8O=wQD@BhkphZD&fupP|~ z=}j0Qw!K(>gu6s9l6*i)f)J5N5WB`9O*FWysa}Uq%F}LQPr{k`+#gX)SV+TG_nqFUhlRc$C`p&3!Sal=jiNQ=y z(GzolzK2|-k(>`S6JvtxfHWmj$OhTpISdNR-;gP!BF5-JZgaCY_}-qIDr7#ad+Z)K zZW7GUErd-J1u0@tJG4teL#UC2#8z|dY7eM;My3n<51|+|ONk*&F`BjmwbSL5E;vSL zUV?gmN`y2hzu6#$|J}CFa`t_>2BF;M_a8}et=2ggy)okwcOO0LJeHy?^jnR1~Ta%@lG=zK%0(w0ggHRYqiqMP&YuMX%JELLJ^3!Pa`_k@`bRh z%4w_GU}}|IgX5_0ox0=rYt^kOYnUh=;FUd2nBF_c! zaHii}XjCw3e*3jm^T(cv_Vn#W0pNe=N;psfUh1i=<#HygeEkYQgNZRAoPRSo)}ZjU zce;Nbx_XEV;CTvmtix3hNHW0Y%|#s=;nQSI5NmSwS`%zfR%{>3s@Ud1;vUF&{Q?8` zqYN4%J(^u+tiU7T^Zg3MZ>Jo<9O$2Otbe0#MMhQC`yTUsYtLg>OTUQn)Q%V?*V%V^ zO=^{}4mh0&u#8vX6)Ba!1UjPq{|6G41kLMCM&C^MTFe{7}Glxq(Kk6`PYU*5GCH1 zo*uthmsuy=m2v3j18RMQy#-kX-PNl#uzp#9T1t0mqU~}wYh1HI9a=I5)JQexOPW4T zS#`1=SFcv!M>K8SQ`(`qj2De2dF>1NPa>U|hnnCKN_j69|C2hj#F!(LwvYbt<+CPe zl15KA$*nF$|Qius*l(3Ecu49;g)L=N)hueJ(sUdrKa*zKDlfDEY6$t;ki}vv~M@Bn{xZFn=D<-4mH$N7t^%1dGI+mU54 z!bOCI;rpAe{O+R6a*Ai*lhqvNg<$_cR=u#g%B7$PVP|A^CV0^Rm|UGxGw6|;dgRb! z6gX0#6ct&3=4Co)S@fm1*NnlbOcVACxjPC>6JbAa^wo$FYxv*|7M7qn`<3P8bM-*b z3LhlHJCvAu1zbq{%z%FlyaWA~&eqmPpisYrlY;oNuB^|4O6o?RcWFmp;f%}FywuR{ z4?4nqC&8!Ho_3)R1dPud$(>3G9Qb*7jMG8lAZA~xi+syq7VKpS91~Krs2BMFv@0vr zg&)nYvc~%iTRX1J^Tm~)oxI`xs;_1lv;l$BCgb+}z2)Hz8wxI<0m!c5jpK@WlXcnW z5tvm#_L3nSUAZlE1c zU(JOFxVq;S=cPtmQU^7_G#~8(oFqim4hg3WA@y{5HH)MX-2AqVhCai=bxKvOdbTEX zcgF$?I;w8zb}{nhCOwIlAq^XH<0d0qX@MBuleSaf+X|}~lFFA4y;ccz@wi~h(3!jGI zl0*Kf5^$`BZJ87^7k~diNuZJYkW1rCvjc!rGFn=Ja1n0nviKY2Y{f?CMvu)y8@ToC z1g3Pq;Df-U@q~$Nqk2KZt`{<8pM3>yn4tjoklGKHNg%GVJm|a571t!dN&5hv%1iEI zU?TWwaw!Q4&0i#I>4AI+9gDys>oR0DJ`OUM4klx~F9lvdt(nzvjV}28*w~wQv&>)x ztWG7WqoX4b+u`0YYc3=U^a3wH{D_J#JAhRSAtWDIgj0UuY4a!nw^Rt1CeFp;rSn(i zzSJ0voEMV=1VN{wgqDT|zNkEg9`e7(OxHfy(jp5)Yh)w(uuT6bFU0BU?_GaPd0BM% z?zjA8%y=c_+0dk!HuVweq{F)_84vcij2;NCHo7@9V9iB(c4>?3$N|AV6E4V{aoz{N zpu};t8$DDtY^hJ1A;b)@R`_`VaH#W4qI(Cp(y`9e&6kF>Oe$|*yl12=5{8vTvbVAv zONZE<@_v~IcYOl?*;*0+AsoVu&@1LN?>T}3RR2@na&sM>>OEKn!`DJ>XZtkXw-W}y z6&B$17{dMU0v^r~S<&`4>FEsC1PdTY_!xh~34mzQhn|rsj=xT-|51R~s7Dyg&c=9c zFeHiYp!uC`2q}=M$pqm%{~qRcJh&Nd02Ass#IvKE6yivHU=1{!p~e^_rRJ)i&VeE0AY>fWcP$1&ed(7!x+?Kqp{W2m8_Al>kZ5%D{zbM^0* z`rQCP@4RZrjp0+0A<7o$iVAX=wV#*^Yl5T%=mm#?faM`Wr!Y1$blh7L5{+HXKDH1I zzu_XG7$_ljpP!7onA&_gYl z9~&Jo;&`(h$BF|W>cc>Nqy`Asuxg`svmV5+{&O3)Y_b<{VY40^#DI|%miR_^Ou#A< z^&Q~mg!XM!7z%)~Sa7M284R6~!~mVSY8?N-K4GuWM+#XfF<2%R4wmly0(^5J9YL5_ z5RGF89JUn*Jd((`z&by=t7C@?*MHWrt7KM6;V%^f`