From 7a19e8aa360f7849f871f15d9d971a4aff68739a Mon Sep 17 00:00:00 2001 From: Kosuke Takeuchi Date: Wed, 20 Nov 2024 19:58:39 +0900 Subject: [PATCH] feat(simple_planning_simulator): add mechanical actuaion sim model (#9300) * feat(simple_planning_simulator): add mechanical actuaion sim model Signed-off-by: kosuke55 update docs Signed-off-by: kosuke55 * update from suggestions Signed-off-by: kosuke55 * calc internal state using RK4 results Signed-off-by: kosuke55 --------- Signed-off-by: kosuke55 --- .../simple_planning_simulator/CMakeLists.txt | 1 + simulator/simple_planning_simulator/README.md | 76 +-- .../docs/actuation_cmd_sim.md | 105 +++ .../simple_planning_simulator_core.hpp | 5 +- .../utils/mechanical_controller.hpp | 208 ++++++ .../vehicle_model/sim_model_actuation_cmd.hpp | 220 ++++--- .../vehicle_model/sim_model_interface.hpp | 14 +- .../simple_planning_simulator.launch.py | 7 +- .../media/mechanical_controller.drawio.svg | 602 ++++++++++++++++++ ...nical_controller_system_identification.png | Bin 0 -> 268250 bytes ...ing_simulator_mechanical_sample.param.yaml | 62 ++ .../simple_planning_simulator_core.cpp | 104 ++- .../utils/mechanical_controller.cpp | 352 ++++++++++ .../vehicle_model/sim_model_actuation_cmd.cpp | 265 +++++--- .../test/test_simple_planning_simulator.cpp | 82 +-- 15 files changed, 1817 insertions(+), 286 deletions(-) create mode 100644 simulator/simple_planning_simulator/docs/actuation_cmd_sim.md create mode 100644 simulator/simple_planning_simulator/include/simple_planning_simulator/utils/mechanical_controller.hpp create mode 100644 simulator/simple_planning_simulator/media/mechanical_controller.drawio.svg create mode 100644 simulator/simple_planning_simulator/media/mechanical_controller_system_identification.png create mode 100644 simulator/simple_planning_simulator/param/simple_planning_simulator_mechanical_sample.param.yaml create mode 100644 simulator/simple_planning_simulator/src/simple_planning_simulator/utils/mechanical_controller.cpp diff --git a/simulator/simple_planning_simulator/CMakeLists.txt b/simulator/simple_planning_simulator/CMakeLists.txt index 07e7e6b5ad169..6acb74342c90f 100644 --- a/simulator/simple_planning_simulator/CMakeLists.txt +++ b/simulator/simple_planning_simulator/CMakeLists.txt @@ -23,6 +23,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED src/simple_planning_simulator/vehicle_model/sim_model_delay_steer_map_acc_geared.cpp src/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.cpp src/simple_planning_simulator/utils/csv_loader.cpp + src/simple_planning_simulator/utils/mechanical_controller.cpp ) target_include_directories(${PROJECT_NAME} PUBLIC ${Python3_INCLUDE_DIRS} ${learning_based_vehicle_model_INCLUDE_DIRS}) # Node executable diff --git a/simulator/simple_planning_simulator/README.md b/simulator/simple_planning_simulator/README.md index 1d91d5e6149b4..cd362c0115358 100644 --- a/simulator/simple_planning_simulator/README.md +++ b/simulator/simple_planning_simulator/README.md @@ -65,32 +65,38 @@ The purpose of this simulator is for the integration test of planning and contro - `DELAY_STEER_ACC_GEARED_WO_FALL_GUARD` - `DELAY_STEER_MAP_ACC_GEARED`: applies 1D dynamics and time delay to the steering and acceleration commands. The simulated acceleration is determined by a value converted through the provided acceleration map. This model is valuable for an accurate simulation with acceleration deviations in a real vehicle. - `LEARNED_STEER_VEL`: launches learned python models. More about this [here](../learning_based_vehicle_model). -- `ACTUATION_CMD`: A simulator model that receives `ACTUATION_CMD`. In this case, the `raw_vehicle_cmd_converter` is also launched. + +The following models receive `ACTUATION_CMD` generated from `raw_vehicle_cmd_converter`. Therefore, when these models are selected, the `raw_vehicle_cmd_converter` is also launched. + +- `ACTUATION_CMD`: This model only converts accel/brake commands and use steer command as it is. +- `ACTUATION_CMD_STEER_MAP`: The steer command is converted to the steer rate command using the steer map. +- `ACTUATION_CMD_VGR`: The steer command is converted to the steer rate command using the variable gear ratio. +- `ACTUATION_CMD_MECHANICAL`: This model has mechanical dynamics and controller for that. The `IDEAL` model moves ideally as commanded, while the `DELAY` model moves based on a 1st-order with time delay model. The `STEER` means the model receives the steer command. The `VEL` means the model receives the target velocity command, while the `ACC` model receives the target acceleration command. The `GEARED` suffix means that the motion will consider the gear command: the vehicle moves only one direction following the gear. The table below shows which models correspond to what parameters. The model names are written in abbreviated form (e.g. IDEAL_STEER_VEL = I_ST_V). -| Name | Type | Description | I_ST_V | I_ST_A | I_ST_A_G | D_ST_V | D_ST_A | D_ST_A_G | D_ST_A_G_WO_FG | D_ST_M_ACC_G | L_S_V | Default value | unit | -| :------------------------- | :----- | :---------------------------------------------------------------------------------------------------------- | :----- | :----- | :------- | :----- | :----- | :------- | :------------- | :----------- | :---- | :------------ | :------ | -| acc_time_delay | double | dead time for the acceleration input | x | x | x | x | o | o | o | o | x | 0.1 | [s] | -| steer_time_delay | double | dead time for the steering input | x | x | x | o | o | o | o | o | x | 0.24 | [s] | -| vel_time_delay | double | dead time for the velocity input | x | x | x | o | x | x | x | x | x | 0.25 | [s] | -| acc_time_constant | double | time constant of the 1st-order acceleration dynamics | x | x | x | x | o | o | o | o | x | 0.1 | [s] | -| steer_time_constant | double | time constant of the 1st-order steering dynamics | x | x | x | o | o | o | o | o | x | 0.27 | [s] | -| steer_dead_band | double | dead band for steering angle | x | x | x | o | o | o | o | x | x | 0.0 | [rad] | -| vel_time_constant | double | time constant of the 1st-order velocity dynamics | x | x | x | o | x | x | x | x | x | 0.5 | [s] | -| vel_lim | double | limit of velocity | x | x | x | o | o | o | o | o | x | 50.0 | [m/s] | -| vel_rate_lim | double | limit of acceleration | x | x | x | o | o | o | o | o | x | 7.0 | [m/ss] | -| steer_lim | double | limit of steering angle | x | x | x | o | o | o | o | o | x | 1.0 | [rad] | -| steer_rate_lim | double | limit of steering angle change rate | x | x | x | o | o | o | o | o | x | 5.0 | [rad/s] | -| steer_bias | double | bias for steering angle | x | x | x | o | o | o | o | o | x | 0.0 | [rad] | -| debug_acc_scaling_factor | double | scaling factor for accel command | x | x | x | x | o | o | o | x | x | 1.0 | [-] | -| debug_steer_scaling_factor | double | scaling factor for steer command | x | x | x | x | o | o | o | x | x | 1.0 | [-] | -| acceleration_map_path | string | path to csv file for acceleration map which converts velocity and ideal acceleration to actual acceleration | x | x | x | x | x | x | x | o | x | - | [-] | -| model_module_paths | string | path to a python module where the model is implemented | x | x | x | x | x | x | x | x | o | - | [-] | -| model_param_paths | string | path to the file where model parameters are stored (can be empty string if no parameter file is required) | x | x | x | x | x | x | x | x | o | - | [-] | -| model_class_names | string | name of the class that implements the model | x | x | x | x | x | x | x | x | o | - | [-] | +| Name | Type | Description | I_ST_V | I_ST_A | I_ST_A_G | D_ST_V | D_ST_A | D_ST_A_G | D_ST_A_G_WO_FG | D_ST_M_ACC_G | L_S_V | A_C | Default value | unit | +| :------------------------- | :----- | :---------------------------------------------------------------------------------------------------------- | :----- | :----- | :------- | :----- | :----- | :------- | :------------- | :----------- | :---- | :-- | :------------ | :------ | +| acc_time_delay | double | dead time for the acceleration input | x | x | x | x | o | o | o | o | x | x | 0.1 | [s] | +| steer_time_delay | double | dead time for the steering input | x | x | x | o | o | o | o | o | x | o | 0.24 | [s] | +| vel_time_delay | double | dead time for the velocity input | x | x | x | o | x | x | x | x | x | x | 0.25 | [s] | +| acc_time_constant | double | time constant of the 1st-order acceleration dynamics | x | x | x | x | o | o | o | o | x | x | 0.1 | [s] | +| steer_time_constant | double | time constant of the 1st-order steering dynamics | x | x | x | o | o | o | o | o | x | o | 0.27 | [s] | +| steer_dead_band | double | dead band for steering angle | x | x | x | o | o | o | o | x | x | o | 0.0 | [rad] | +| vel_time_constant | double | time constant of the 1st-order velocity dynamics | x | x | x | o | x | x | x | x | x | x | 0.5 | [s] | +| vel_lim | double | limit of velocity | x | x | x | o | o | o | o | o | x | x | 50.0 | [m/s] | +| vel_rate_lim | double | limit of acceleration | x | x | x | o | o | o | o | o | x | x | 7.0 | [m/ss] | +| steer_lim | double | limit of steering angle | x | x | x | o | o | o | o | o | x | o | 1.0 | [rad] | +| steer_rate_lim | double | limit of steering angle change rate | x | x | x | o | o | o | o | o | x | o | 5.0 | [rad/s] | +| steer_bias | double | bias for steering angle | x | x | x | o | o | o | o | o | x | o | 0.0 | [rad] | +| debug_acc_scaling_factor | double | scaling factor for accel command | x | x | x | x | o | o | o | x | x | x | 1.0 | [-] | +| debug_steer_scaling_factor | double | scaling factor for steer command | x | x | x | x | o | o | o | x | x | x | 1.0 | [-] | +| acceleration_map_path | string | path to csv file for acceleration map which converts velocity and ideal acceleration to actual acceleration | x | x | x | x | x | x | x | o | x | x | - | [-] | +| model_module_paths | string | path to a python module where the model is implemented | x | x | x | x | x | x | x | x | o | x | - | [-] | +| model_param_paths | string | path to the file where model parameters are stored (can be empty string if no parameter file is required) | x | x | x | x | x | x | x | x | o | x | - | [-] | +| model_class_names | string | name of the class that implements the model | x | x | x | x | x | x | x | x | o | x | - | [-] | _Note:_ Parameters `model_module_paths`, `model_param_paths`, and `model_class_names` need to have the same length. @@ -125,32 +131,8 @@ default, 0.00, 1.39, 2.78, 4.17, 5.56, 6.94, 8.33, 9.72, 11.11, 12.50, 1 ##### ACTUATION_CMD model -The simple_planning_simulator usually operates by receiving Control commands, but when the `ACTUATION_CMD` model is selected, it receives Actuation commands instead of Control commands. This model can simulate the motion using the vehicle command that is actually sent to the real vehicle. Therefore, when this model is selected, the `raw_vehicle_cmd_converter` is also launched. - -`convert_steer_cmd_method` has two options: "vgr" and "steer_map". If you choose "vgr" (variable gear ratio), it is assumed that the steering wheel angle is sent as the actuation command, and the value is converted to the steering tire angle to move the model. If you choose "steer_map", it is assumed that an arbitrary value is sent as the actuation command, and the value is converted to the steering tire rate to move the model. An arbitrary value is like EPS (Electric Power Steering) Voltage . `enable_pub_steer` determines whether to publish the steering tire angle. If false, it is expected to be converted and published from actuation_status in other nodes (e.g. raw_vehicle_cmd_converter). - -![vgr_sim](./media/vgr_sim.drawio.svg) - -```yaml - -``` - -The parameters used in the ACTUATION_CMD are as follows. - -| Name | Type | Description | unit | -| :----------------------- | :----- | :----------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :--- | -| accel_time_delay | double | dead time for the acceleration input | [s] | -| accel_time_constant | double | time constant of the 1st-order acceleration dynamics | [s] | -| brake_time_delay | double | dead time for the brake input | [s] | -| brake_time_constant | double | time constant of the 1st-order brake dynamics | [s] | -| convert_accel_cmd | bool | If true, it is assumed that the command is received converted to an accel actuation value, and it is converted back to acceleration value inside the simulator. | [-] | -| convert_brake_cmd | bool | If true, it is assumed that the command is received converted to a brake actuation value, and it is converted back to acceleration value inside the simulator. | [-] | -| convert_steer_cmd | bool | If true, it is assumed that the command is received converted to a steer actuation value, and it is converted back to steer rate value inside the simulator. | [-] | -| convert_steer_cmd_method | bool | method to convert steer command. You can choose from "vgr" and "steer_map". | [-] | -| vgr_coef_a | double | the value of the coefficient a of the variable gear ratio | [-] | -| vgr_coef_b | double | the value of the coefficient b of the variable gear ratio | [-] | -| vgr_coef_c | double | the value of the coefficient c of the variable gear ratio | [-] | -| enable_pub_steer | bool | whether to publish the steering tire angle. if false, it is expected to be converted and published from actuation_status in other nodes (e.g. raw_vehicle_cmd_converter) | [-] | +The simple_planning_simulator usually operates by receiving Control commands, but when the `ACTUATION_CMD*` model is selected, it receives Actuation commands instead of Control commands. This model can simulate the motion using the vehicle command that is actually sent to the real vehicle. Therefore, when this model is selected, the `raw_vehicle_cmd_converter` is also launched. +Please refer to the [actuation_cmd_sim.md](./docs/actuation_cmd_sim.md) for more details. diff --git a/simulator/simple_planning_simulator/docs/actuation_cmd_sim.md b/simulator/simple_planning_simulator/docs/actuation_cmd_sim.md new file mode 100644 index 0000000000000..5219b20b6dbaf --- /dev/null +++ b/simulator/simple_planning_simulator/docs/actuation_cmd_sim.md @@ -0,0 +1,105 @@ +# ACTUATION_CMD model + +The simple_planning_simulator usually operates by receiving Control commands, but when the `ACTUATION_CMD*` model is selected, it receives Actuation commands instead of Control commands. This model can simulate the motion using the vehicle command that is actually sent to the real vehicle. Therefore, when this model is selected, the `raw_vehicle_cmd_converter` is also launched. + +## ACTUATION_CMD + +This model receives the accel/brake commands and converts them using the map to calculate the motion of the model. The steer command is used as it is. +Please make sure that the raw_vehicle_cmd_converter is configured as follows. + +```yaml +convert_accel_cmd: true +convert_brake_cmd: true +convert_steer_cmd: false +``` + +## ACTUATION_CMD_STEER_MAP + +This model is inherited from ACTUATION_CMD and receives steering arbitrary value as the actuation command. +The value is converted to the steering tire rate to calculate the motion of the model. An arbitrary value is like EPS (Electric Power Steering) Voltage. + +Please make sure that the raw_vehicle_cmd_converter is configured as follows. + +```yaml +convert_accel_cmd: true +convert_brake_cmd: true +convert_steer_cmd: true +``` + +## ACTUATION_CMD_VGR + +This model is inherited from ACTUATION_CMD and steering wheel angle is sent as the actuation command. +The value is converted to the steering tire angle to calculate the motion of the model. + +Please make sure that the raw_vehicle_cmd_converter is configured as follows. + +```yaml +convert_accel_cmd: true +convert_brake_cmd: true +convert_steer_cmd: true +``` + +![vgr_sim](../media/vgr_sim.drawio.svg) + +## ACTUATION_CMD_MECHANICAL + +This model is inherited from ACTUATION_CMD_VGR nad has mechanical dynamics and controller for that to simulate the mechanical structure and software of the real vehicle. + +Please make sure that the raw_vehicle_cmd_converter is configured as follows. + +```yaml +convert_accel_cmd: true +convert_brake_cmd: true +convert_steer_cmd: true +``` + +The mechanical structure of the vehicle is as follows. + +![mechanical_controller](../media/mechanical_controller.drawio.svg) + +The vehicle side software assumes that it has limiters, PID controllers, power steering, etc. for the input. +The conversion in the power steering is approximated by a polynomial. +Steering Dynamics is a model that represents the motion of the tire angle when the Steering Torque is input. It is represented by the following formula. + +```math +\begin{align} +\dot{\theta} &= \omega \\ +\dot{\omega} &= \frac{1}{I} (T_{\text{input}} - D \omega - K \theta - \text{sign}(\omega) F_{\text{friction}} ) \\ +\end{align} +``` + +In this case, + +- $\theta$ : Tire angle +- $\omega$ : Tire angular velocity +- $T_{\text{input}}$ : Input torque +- $D$ : Damping coefficient +- $K$ : Spring constant +- $F_{\text{friction}}$ : Friction force +- $I$ : Moment of inertia + +Also, this dynamics has a dead zone. +The steering rotation direction is different from the steering torque input direction, and the steering torque input is less than the dead zone threshold, it enters the dead zone. Once it enters the dead zone, it is judged to be in the dead zone until there is a steering input above the dead zone threshold. When in the dead zone, the steering tire angle does not move. + +Please refer to the following file for the values of the parameters that have been system-identified using the actual vehicle's driving data. +The blue line is the control input, the green line is the actual vehicle's tire angle output, and the red line is the simulator's tire angle output. +[mechanical_sample_param](../param/simple_planning_simulator_mechanical_sample.param.yaml) + +This model has a smaller sum of errors with the observed values of the actual vehicle than when tuned with a normal first-order lag model. For details, please refer to [#9252](https://github.com/autowarefoundation/autoware.universe/pull/9300). + +![mechanical_controller_system_identification](../media/mechanical_controller_system_identification.png) + +The parameters used in the ACTUATION_CMD are as follows. + +| Name | Type | Description | unit | +| :------------------ | :----- | :----------------------------------------------------------------------------------------------------------------------------------------------------------------------- | :--- | +| accel_time_delay | double | dead time for the acceleration input | [s] | +| accel_time_constant | double | time constant of the 1st-order acceleration dynamics | [s] | +| brake_time_delay | double | dead time for the brake input | [s] | +| brake_time_constant | double | time constant of the 1st-order brake dynamics | [s] | +| convert_accel_cmd | bool | If true, it is assumed that the command is received converted to an accel actuation value, and it is converted back to acceleration value inside the simulator. | [-] | +| convert_brake_cmd | bool | If true, it is assumed that the command is received converted to a brake actuation value, and it is converted back to acceleration value inside the simulator. | [-] | +| vgr_coef_a | double | the value of the coefficient a of the variable gear ratio | [-] | +| vgr_coef_b | double | the value of the coefficient b of the variable gear ratio | [-] | +| vgr_coef_c | double | the value of the coefficient c of the variable gear ratio | [-] | +| enable_pub_steer | bool | whether to publish the steering tire angle. if false, it is expected to be converted and published from actuation_status in other nodes (e.g. raw_vehicle_cmd_converter) | [-] | diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp index 76fdf5bdda6c9..3e54bca245f82 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp @@ -224,7 +224,10 @@ class PLANNING_SIMULATOR_PUBLIC SimplePlanningSimulator : public rclcpp::Node DELAY_STEER_MAP_ACC_GEARED = 6, LEARNED_STEER_VEL = 7, DELAY_STEER_ACC_GEARED_WO_FALL_GUARD = 8, - ACTUATION_CMD = 9 + ACTUATION_CMD = 9, + ACTUATION_CMD_VGR = 10, + ACTUATION_CMD_MECHANICAL = 11, + ACTUATION_CMD_STEER_MAP = 12, } vehicle_model_type_; //!< @brief vehicle model type to decide the model dynamics std::shared_ptr vehicle_model_ptr_; //!< @brief vehicle model pointer diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/utils/mechanical_controller.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/utils/mechanical_controller.hpp new file mode 100644 index 0000000000000..fcb8d41dd72b5 --- /dev/null +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/utils/mechanical_controller.hpp @@ -0,0 +1,208 @@ +// Copyright 2024 The Autoware Foundation. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef SIMPLE_PLANNING_SIMULATOR__UTILS__MECHANICAL_CONTROLLER_HPP_ +#define SIMPLE_PLANNING_SIMULATOR__UTILS__MECHANICAL_CONTROLLER_HPP_ + +#include +#include +#include +#include +#include + +namespace autoware::simple_planning_simulator::utils::mechanical_controller +{ + +using DelayBuffer = std::deque>; +using DelayOutput = std::pair, DelayBuffer>; + +DelayOutput delay( + const double signal, const double delay_time, const DelayBuffer & buffer, + const double elapsed_time); + +double sign(const double x); + +double apply_limits( + const double current_angle, const double previous_angle, const double angle_limit, + const double rate_limit, const double dt); + +double feedforward(const double input_angle, const double ff_gain); + +double polynomial_transform( + const double torque, const double speed, const double a, const double b, const double c, + const double d, const double e, const double f, const double g, const double h); + +struct PIDControllerParams +{ + double kp{0.0}; + double ki{0.0}; + double kd{0.0}; +}; + +struct PIDControllerState +{ + double integral{0.0}; + double error{0.0}; +}; + +class PIDController +{ +public: + PIDController(const double kp, const double ki, const double kd); + + [[nodiscard]] double compute( + const double error, const double integral, const double prev_error, const double dt) const; + + void update_state(const double error, const double dt); + + void update_state( + const double k1_error, const double k2_error, const double k3_error, const double k4_error, + const double dt); + + [[nodiscard]] PIDControllerState get_state() const; + + void clear_state(); + +private: + double kp_{0.0}, ki_{0.0}, kd_{0.0}; + PIDControllerState state_; +}; + +struct SteeringDynamicsParams +{ + double angular_position{0.0}; + double angular_velocity{0.0}; + double inertia{0.0}; + double damping{0.0}; + double stiffness{0.0}; + double friction{0.0}; + double dead_zone_threshold{0.0}; +}; + +struct SteeringDynamicsState +{ + double angular_position{0.0}; + double angular_velocity{0.0}; + bool is_in_dead_zone{false}; +}; + +struct SteeringDynamicsDeltaState +{ + double d_angular_position{0.0}; + double d_angular_velocity{0.0}; +}; + +/** + * @brief SteeringDynamics class + * @details This class calculates the dynamics which receives the steering torque and outputs the + * steering tire angle. The steering system is modeled as a spring-damper system with friction and + * dead zone. + */ +class SteeringDynamics +{ +public: + SteeringDynamics( + const double angular_position, const double angular_velocity, const double inertia, + const double damping, const double stiffness, const double friction, + const double dead_zone_threshold); + + [[nodiscard]] bool is_in_dead_zone( + const SteeringDynamicsState & state, const double input_torque) const; + + [[nodiscard]] SteeringDynamicsDeltaState calc_model( + const SteeringDynamicsState & state, const double input_torque) const; + + void set_state(const SteeringDynamicsState & state); + + [[nodiscard]] SteeringDynamicsState get_state() const; + + void clear_state(); + + void set_steer(const double steer); + +private: + SteeringDynamicsState state_; + const double inertia_; + const double damping_; + const double stiffness_; + const double friction_; + const double dead_zone_threshold_; +}; + +struct StepResult +{ + DelayBuffer delay_buffer{}; + double pid_error{0.0}; + SteeringDynamicsDeltaState dynamics_d_state{}; + bool is_in_dead_zone{false}; +}; + +struct MechanicalParams +{ + double kp{0.0}; + double ki{0.0}; + double kd{0.0}; + double ff_gain{0.0}; + double dead_zone_threshold{0.0}; + double poly_a{0.0}; + double poly_b{0.0}; + double poly_c{0.0}; + double poly_d{0.0}; + double poly_e{0.0}; + double poly_f{0.0}; + double poly_g{0.0}; + double poly_h{0.0}; + double inertia{0.0}; + double damping{0.0}; + double stiffness{0.0}; + double friction{0.0}; + double delay_time{0.0}; + + // limit + double angle_limit{0.0}; + double rate_limit{0.0}; + double steering_torque_limit{0.0}; + double torque_delay_time{0.0}; +}; + +class MechanicalController +{ +public: + explicit MechanicalController(const MechanicalParams & mechanical_params); + + [[maybe_unused]] double update_euler( + const double input_angle, const double speed, const double prev_input_angle, const double dt); + + double update_runge_kutta( + const double input_angle, const double speed, const double prev_input_angle, const double dt); + + void clear_state(); + + void set_steer(const double steer); + +private: + DelayBuffer delay_buffer_; + PIDController pid_; + SteeringDynamics steering_dynamics_; + const MechanicalParams params_; + + [[nodiscard]] StepResult run_one_step( + const double input_angle, const double speed, const double prev_input_angle, const double dt, + const DelayBuffer & delay_buffer, const PIDController & pid, + const SteeringDynamics & dynamics) const; +}; + +} // namespace autoware::simple_planning_simulator::utils::mechanical_controller + +#endif // SIMPLE_PLANNING_SIMULATOR__UTILS__MECHANICAL_CONTROLLER_HPP_ diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.hpp index b78ec8ccd538a..25fac72d283ee 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.hpp +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.hpp @@ -19,15 +19,20 @@ #include "eigen3/Eigen/Core" #include "eigen3/Eigen/LU" #include "simple_planning_simulator/utils/csv_loader.hpp" +#include "simple_planning_simulator/utils/mechanical_controller.hpp" #include "simple_planning_simulator/vehicle_model/sim_model_interface.hpp" #include #include +#include #include #include #include #include +using autoware::simple_planning_simulator::utils::mechanical_controller::MechanicalController; +using autoware::simple_planning_simulator::utils::mechanical_controller::MechanicalParams; + /** * @class ActuationMap * @brief class to convert from actuation command to control command @@ -101,10 +106,8 @@ class BrakeMap : public ActuationMap class SimModelActuationCmd : public SimModelInterface { public: - enum class ActuationSimType { VGR, STEER_MAP }; - /** - * @brief constructor (adaptive gear ratio conversion model) + * @brief constructor (only longitudinal) * @param [in] vx_lim velocity limit [m/s] * @param [in] steer_lim steering limit [rad] * @param [in] vx_rate_lim acceleration limit [m/ss] @@ -120,49 +123,15 @@ class SimModelActuationCmd : public SimModelInterface * @param [in] steer_bias steering bias [rad] * @param [in] convert_accel_cmd flag to convert accel command * @param [in] convert_brake_cmd flag to convert brake command - * @param [in] convert_steer_cmd flag to convert steer command - * @param [in] accel_map_path path to csv file for accel conversion map - * @param [in] brake_map_path path to csv file for brake conversion map - * @param [in] vgr_coef_a coefficient for variable gear ratio - * @param [in] vgr_coef_b coefficient for variable gear ratio - * @param [in] vgr_coef_c coefficient for variable gear ratio - */ - SimModelActuationCmd( - double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, - double dt, double accel_delay, double accel_time_constant, double brake_delay, - double brake_time_constant, double steer_delay, double steer_time_constant, double steer_bias, - bool convert_accel_cmd, bool convert_brake_cmd, bool convert_steer_cmd, - std::string accel_map_path, std::string brake_map_path, double vgr_coef_a, double vgr_coef_b, - double vgr_coef_c); - - /** - * @brief constructor (steer map conversion model) - * @param [in] vx_lim velocity limit [m/s] - * @param [in] steer_lim steering limit [rad] - * @param [in] vx_rate_lim acceleration limit [m/ss] - * @param [in] steer_rate_lim steering angular velocity limit [rad/ss] - * @param [in] wheelbase vehicle wheelbase length [m] - * @param [in] dt delta time information to set input buffer for delay - * @param [in] accel_delay time delay for accel command [s] - * @param [in] acc_time_constant time constant for 1D model of accel dynamics - * @param [in] brake_delay time delay for brake command [s] - * @param [in] brake_time_constant time constant for 1D model of brake dynamics - * @param [in] steer_delay time delay for steering command [s] - * @param [in] steer_time_constant time constant for 1D model of steering dynamics - * @param [in] steer_bias steering bias [rad] - * @param [in] convert_accel_cmd flag to convert accel command - * @param [in] convert_brake_cmd flag to convert brake command - * @param [in] convert_steer_cmd flag to convert steer command * @param [in] accel_map_path path to csv file for accel conversion map * @param [in] brake_map_path path to csv file for brake conversion map - * @param [in] steer_map_path path to csv file for steer conversion map */ SimModelActuationCmd( double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, double dt, double accel_delay, double accel_time_constant, double brake_delay, double brake_time_constant, double steer_delay, double steer_time_constant, double steer_bias, - bool convert_accel_cmd, bool convert_brake_cmd, bool convert_steer_cmd, - std::string accel_map_path, std::string brake_map_path, std::string steer_map_path); + bool convert_accel_cmd, bool convert_brake_cmd, std::string accel_map_path, + std::string brake_map_path); /** * @brief default destructor @@ -179,7 +148,7 @@ class SimModelActuationCmd : public SimModelInterface */ bool shouldPublishActuationStatus() const override { return true; } -private: +protected: const double MIN_TIME_CONSTANT; //!< @brief minimum time constant enum IDX { @@ -198,39 +167,29 @@ class SimModelActuationCmd : public SimModelInterface GEAR, }; - const double vx_lim_; //!< @brief velocity limit [m/s] - const double vx_rate_lim_; //!< @brief acceleration limit [m/ss] - const double steer_lim_; //!< @brief steering limit [rad] - const double steer_rate_lim_; //!< @brief steering angular velocity limit [rad/s] - const double wheelbase_; //!< @brief vehicle wheelbase length [m] - - std::deque accel_input_queue_; //!< @brief buffer for accel command - std::deque brake_input_queue_; //!< @brief buffer for brake command - std::deque steer_input_queue_; //!< @brief buffer for steering command - const double accel_delay_; //!< @brief time delay for accel command [s] - const double accel_time_constant_; //!< @brief time constant for accel dynamics - const double brake_delay_; //!< @brief time delay for brake command [s] - const double brake_time_constant_; //!< @brief time constant for brake dynamics - const double steer_delay_; //!< @brief time delay for steering command [s] - const double steer_time_constant_; //!< @brief time constant for steering dynamics - const double steer_bias_; //!< @brief steering angle bias [rad] - - bool convert_accel_cmd_; - bool convert_brake_cmd_; - bool convert_steer_cmd_; - - AccelMap accel_map_; - BrakeMap brake_map_; - ActuationMap steer_map_; - - // steer map conversion model - - // adaptive gear ratio conversion model - double vgr_coef_a_; - double vgr_coef_b_; - double vgr_coef_c_; - - ActuationSimType actuation_sim_type_{ActuationSimType::VGR}; + const double vx_lim_{0.0}; //!< @brief velocity limit [m/s] + const double vx_rate_lim_{0.0}; //!< @brief acceleration limit [m/ss] + const double steer_lim_{0.0}; //!< @brief steering limit [rad] + const double steer_rate_lim_{0.0}; //!< @brief steering angular velocity limit [rad/s] + const double wheelbase_{0.0}; //!< @brief vehicle wheelbase length [m] + + std::deque accel_input_queue_{}; //!< @brief buffer for accel command + std::deque brake_input_queue_{}; //!< @brief buffer for brake command + std::deque steer_input_queue_{}; //!< @brief buffer for steering command + const double accel_delay_{0.0}; //!< @brief time delay for accel command [s] + const double accel_time_constant_{0.0}; //!< @brief time constant for accel dynamics + const double brake_delay_{0.0}; //!< @brief time delay for brake command [s] + const double brake_time_constant_{0.0}; //!< @brief time constant for brake dynamics + const double steer_delay_{0.0}; //!< @brief time delay for steering command [s] + const double steer_time_constant_{0.0}; //!< @brief time constant for steering dynamics + const double steer_bias_{0.0}; //!< @brief steering angle bias [rad] + + bool convert_accel_cmd_{false}; + bool convert_brake_cmd_{false}; + bool convert_steer_cmd_{false}; + + AccelMap accel_map_{}; + BrakeMap brake_map_{}; /** * @brief set queue buffer for input command @@ -284,6 +243,24 @@ class SimModelActuationCmd : public SimModelInterface */ void update(const double & dt) override; + /** + * @brief calculate derivative of longitudinal states + * @param [in] state current model state + * @param [in] input input vector to model + * @return derivative of longitudinal states except steering + */ + Eigen::VectorXd calcLongitudinalModel( + const Eigen::VectorXd & state, const Eigen::VectorXd & input); + + /** + * @brief calculate derivative of lateral states + * @param [in] steer current steering angle [rad] + * @param [in] steer_input desired steering angle [rad] + * @param [in] vel current velocity [m/s] + * @return derivative of lateral states + */ + virtual double calcLateralModel(const double steer, const double steer_des, const double vel); + /** * @brief calculate derivative of states with time delay steering model * @param [in] state current model state @@ -301,7 +278,35 @@ class SimModelActuationCmd : public SimModelInterface void updateStateWithGear( Eigen::VectorXd & state, const Eigen::VectorXd & prev_state, const uint8_t gear, const double dt); +}; +class SimModelActuationCmdSteerMap : public SimModelActuationCmd +{ +public: + SimModelActuationCmdSteerMap( + double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, + double dt, double accel_delay, double accel_time_constant, double brake_delay, + double brake_time_constant, double steer_delay, double steer_time_constant, double steer_bias, + bool convert_accel_cmd, bool convert_brake_cmd, std::string accel_map_path, + std::string brake_map_path, std::string steer_map_path); + +private: + double calcLateralModel(const double steer, const double steer_des, const double vel) override; + + ActuationMap steer_map_; +}; + +class SimModelActuationCmdVGR : public SimModelActuationCmd +{ +public: + SimModelActuationCmdVGR( + double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, + double dt, double accel_delay, double accel_time_constant, double brake_delay, + double brake_time_constant, double steer_delay, double steer_time_constant, double steer_bias, + bool convert_accel_cmd, bool convert_brake_cmd, std::string accel_map_path, + std::string brake_map_path, double vgr_coef_a, double vgr_coef_b, double vgr_coef_c); + +protected: /** * @brief calculate steering tire command * @param [in] vel current velocity [m/s] @@ -321,6 +326,75 @@ class SimModelActuationCmd : public SimModelInterface * @return variable gear ratio */ double calculateVariableGearRatio(const double vel, const double steer_wheel) const; + +private: + double calcLateralModel(const double steer, const double steer_des, const double vel) override; + + // adaptive gear ratio conversion model + double vgr_coef_a_; + double vgr_coef_b_; + double vgr_coef_c_; +}; + +class SimModelActuationCmdMechanical : public SimModelActuationCmdVGR +{ +public: + /** + * @brief constructor (mechanical model) + * @param [in] vx_lim velocity limit [m/s] + * @param [in] steer_lim steering limit [rad] + * @param [in] vx_rate_lim acceleration limit [m/ss] + * @param [in] steer_rate_lim steering angular velocity limit [rad/ss] + * @param [in] wheelbase vehicle wheelbase length [m] + * @param [in] dt delta time information to set input buffer for delay + * @param [in] accel_delay time delay for accel command [s] + * @param [in] acc_time_constant time constant for 1D model of accel dynamics + * @param [in] brake_delay time delay for brake command [s] + * @param [in] brake_time_constant time constant for 1D model of brake dynamics + * @param [in] steer_delay time delay for steering command [s] + * @param [in] steer_time_constant time constant for 1D model of steering dynamics + * @param [in] steer_bias steering bias [rad] + * @param [in] convert_accel_cmd flag to convert accel command + * @param [in] convert_brake_cmd flag to convert brake command + * @param [in] convert_steer_cmd flag to convert steer command + * @param [in] accel_map_path path to csv file for accel conversion map + * @param [in] brake_map_path path to csv file for brake conversion map + * @param [in] vgr_coef_a coefficient for variable gear ratio + * @param [in] vgr_coef_b coefficient for variable gear ratio + * @param [in] vgr_coef_c coefficient for variable gear ratio + */ + SimModelActuationCmdMechanical( + double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, + double dt, double accel_delay, double accel_time_constant, double brake_delay, + double brake_time_constant, double steer_delay, double steer_time_constant, double steer_bias, + bool convert_accel_cmd, bool convert_brake_cmd, std::string accel_map_path, + std::string brake_map_path, double vgr_coef_a, double vgr_coef_b, double vgr_coef_c, + MechanicalParams mechanical_params); + + /** + * @brief update vehicle states + * @param [in] dt delta time [s] + */ + void update(const double & dt) override; + + /** + * @brief update vehicle states with controller + * @details In updateRungeKutta, calcModel is called four times, but the internal state of PID and + * Dynamics should not be updated. Therefore, a method is prepared to update the internal state + * only once at the end without using the updateRungeKutta of the interface. + */ + void updateRungeKuttaWithController(const double dt, const Eigen::VectorXd & input); + + /** + * @brief set state + * @details This model needs to update mechanical dynamics state too + * @param [in] state state vector + */ + void setState(const Eigen::VectorXd & state) override; + +private: + std::unique_ptr mechanical_controller_; + double prev_steer_tire_des_{0.0}; // }; #endif // SIMPLE_PLANNING_SIMULATOR__VEHICLE_MODEL__SIM_MODEL_ACTUATION_CMD_HPP_ diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_interface.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_interface.hpp index f8d682a6e851c..5ca886b1b5847 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_interface.hpp +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/vehicle_model/sim_model_interface.hpp @@ -64,12 +64,6 @@ class SimModelInterface */ void getInput(Eigen::VectorXd & input); - /** - * @brief set state vector of model - * @param [in] state state vector - */ - void setState(const Eigen::VectorXd & state); - /** * @brief set input vector of model * @param [in] input input vector @@ -96,6 +90,14 @@ class SimModelInterface */ void updateEuler(const double & dt, const Eigen::VectorXd & input); + /** + * @brief set state vector of model + * @details In some sim models, the state member should be updated as well. Therefore, this + * function is defined as virtual. + * @param [in] state state vector + */ + virtual void setState(const Eigen::VectorXd & state); + /** * @brief update vehicle states * @param [in] dt delta time [s] diff --git a/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py b/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py index 9b31926a53d57..aed088de9fd22 100644 --- a/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py +++ b/simulator/simple_planning_simulator/launch/simple_planning_simulator.launch.py @@ -106,10 +106,9 @@ def launch_setup(context, *args, **kwargs): # Determine if we should launch raw_vehicle_cmd_converter based on the vehicle_model_type with open(simulator_model_param_path, "r") as f: simulator_model_param_yaml = yaml.safe_load(f) - launch_vehicle_cmd_converter = ( - simulator_model_param_yaml["/**"]["ros__parameters"].get("vehicle_model_type") - == "ACTUATION_CMD" - ) + launch_vehicle_cmd_converter = "ACTUATION_CMD" in simulator_model_param_yaml["/**"][ + "ros__parameters" + ].get("vehicle_model_type") # 1) Launch only simple_planning_simulator_node if not launch_vehicle_cmd_converter: diff --git a/simulator/simple_planning_simulator/media/mechanical_controller.drawio.svg b/simulator/simple_planning_simulator/media/mechanical_controller.drawio.svg new file mode 100644 index 0000000000000..a595b2479d4c6 --- /dev/null +++ b/simulator/simple_planning_simulator/media/mechanical_controller.drawio.svg @@ -0,0 +1,602 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+
+
+ Desired Steering Whell Angle +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ PID +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ FF +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+
+ + Power steering +
+
+
+ (polynominal) +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
Driver Torque
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Steering Torque +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ Delay +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ Steering Dynamics +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + +
+
+
+ VGR +
+
+
+
+ +
+
+
+
+ + + + + + + + + + + + + + + + + + + + +
+
+
+ VGR +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Limiter +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Observed Steering Tire Angle +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Observed Steering +
Wheel Angle
+
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Mechanical Controller +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Simulator Model +
+
+
+
+ +
+
+
+
+ + + + + + + + +
+
+
+ Desired Steering +
Tire Angle
+
+
+
+
+ +
+
+
+
+
+
+
+
diff --git a/simulator/simple_planning_simulator/media/mechanical_controller_system_identification.png b/simulator/simple_planning_simulator/media/mechanical_controller_system_identification.png new file mode 100644 index 0000000000000000000000000000000000000000..f96a5848b7fbc04269a29335138fe474e2b7b6fe GIT binary patch literal 268250 zcmd?RbzGL&+6IbaqL>(nfq@{Pl(d9N2!gb;khhJ{%^lszNyY0?jwv)FsuyfS5(Wfx9ur${{ZmVmf zuWw;%WNA0NvPc*&I$^AE+3u{3zP6pQrNsdSV{?7{kb;7fos+94=M@LXkMP^ z4{&n+2))kE*K^y8o3}SUP$q>Vor2;3g~Ykj3Qpla+Z^2#6qlAq8z=N?Lhpa0KC|u2 zZ|8oy_QhxQ;p9Wtb@Z)O76y_MSaNk5743HH@+=!*{@U=`L1We1SYxB7;xY%{pE`3! zd^j|;osM;!Tdwtb*_gWsoxdQLZIw`O>j}pn@2uL#IkMXQgD6wh%>{QSvYGT>c9V@yZfSya21{W*|RGh z+w6BWs@rb#-n4J7^yARLz#$QlsQ%jc+AK@0cg4l{-R2N=8_FoRu{-f?=XYtm#|JD2 zeKwvPsGk_9_qiCxvsgPH{NTapM6FDQ^SFUJYon*2_r8-3>>dkFk)BJl%h_yy7ApV4 z+1|*je->Fd{{>0O(36g=larIJE`urLEf0&`yL9Q&DRc9b_%_2R_m5ajkC%I*HCT6v zMhA$|xo^Mmb|lExxo)hdoQa9)ZKqYbNjg8`_jXi8K)l=VPZx`M|*mDwr}5V zx8bYcYKh&=ZE6f*3B2wN3~*{JdP{*Rgu_>fqquONxpgB-sjXRvXcCa0Ilrs)tK6on8!h-n4i?NQw-`XsszGWD0KI!-?CNYsxL_}n6qW`R$TYj(Tpp3}kb~ZM) zGiT0x%{1M`6Xq9iSnQ=?)qY>m!`0Q*b`B15SZ-I>lbgJ62)RyuX>Putr$@hX4b_|W z_VyE+*47+qugylyhO493;$o?2xo&rKbWo>y*YIoB?vSE| zBMd>5SD!yW#vmR3X=7b^6_-<#UR$(XaCYVw78a)3FZd`uotm z!66}CLqivfJQmk&-fT$TXy;BH&QNg~8AfjI9Wy*L@^W%#w6zarW@ge*t*M&h-@B8Y%HXhxxp`0J$zggv zzDFVpotx?D=_#xlR17)XW~^BAN6zeb={qPVFON?c{i&>}S-DHg?XA`vIy&qF$u!LZ!TDFOUZvwBaKpSm=p5wa3`|W;rA~F1l-#g~*W$fJR!~4d zr?XIIR#t{}muRa6@5;5C-uK(R)GyyzIQwIdfPg@H%MksMBLRVd-<^LIna)oQy?XuH zrpu4l1}m`QOOdDN*w~ohuq_2X`=dn`_3qsgVq$C6vMg{jZ#{W(;I5C4v4sT#1B2Jk zpJw;=^1s72Ha0Rkz{M5(^sKi|Mw6951i9FxB<3}n_TG+)it45L=DF;?W+Ux6b@f&b z+n+yw#$;zddiLzlz~JDE%g1hddj~~C_*EE0r>5RRHM zDkblTuKpBvF|4m8iw!q7a?f@DHK)m{;C@M=lMgne6zg$nv(wOU>aEjq8(qzoKk}PJ z)*eq!&w+sfc3QtytKyB_KYsi+LT;Srl3RX${>b!n@27ynGjnq`wHJA-v3zI>{(@uc zDk>_vySqDVa!B2ebi5_q?W-BjN8jCN(J9i3mIP*JXY~vWbTU z$E9DJHJ!1s;S`PDn$=QanpW^JKFXu))-FwPTiX+u4BL0@A~VfuwkKp|x^Bs)NT=_V z%q%Q-?%sW8#xvd@A2o)?jw@Q|@)CI*7Un!$Fztl@PghNGa&?v0)RabJ$1I&}y}dlu zVkwV~I?-P{IyNQ{M~Bbbz?OeXN{XsB?&3)X-z%J$rk@_Ja-8*myD{ zI@pq*A9HUAtN4hmTA5KLTz-4&VSGYeV`GM8yRg@0I%#q7bss)_Ks}Fo9654?o`InT4GAsN$igBnJ$(x{Nu-yS-f&?Udaw>V z&DV78mHxtWNB8a9ckcZ87k2$}sBxQ`#`owW7_+I2;=f^UzP+(oSX@nQ55|oSKIL;5 z@8;-g@k^Jsu!i^mZM@9L7@eFHimNhjc`b`eIlEb?o6=+Nj&0lCeGWa5Gnkrp86Do) z*_ooQu8!UEn;;6w2t&8y?G0aA?z{N=dtbg>8XF%cFI`7TiRnubQhwgbiXBsMW@hG+ ztnAyBn*~p)sO&~lLPz-W_3J0xk(|C~K7D_wDUbj~~;1HaKDXxw$ia(f(u;`U_1x>J3jzO8P!sv@C@6)zjA> z#lIVCHci_~O?{)@BsMzwhOqnGmYq8tTAyGn>`F;V0eqm|w(X39LNH_aR2wtn_>YRi zXldHTUe&FwpZ8eizeOkbR91#6B}KQiIG^+VE(@0GS$=*vfjR2xpDTFVKL<0(_YDl_ z^w-2bSIO`yq4R8|UP4(IU=n_g5?RhJX|Jn$54akPs<`pm^2K*o0;6%S(<6i;EngQa@X={DB%Q3MQ3)Te*^njjb2+Q?Kiz-}{o1 zuAZLr8XEh&H`59Kvi%E!U*`WSN$3s+I5of|&!7J0`dlOL;qBY&3y55IoB4BW^6+Pvi>5YsvA=^ZU&Xu zD>}OTMGUb0rNVfIvOE2wdA&F9=6o-|;=2=S?{a|)H()hoZM;k`E}^wTjr07V&bUe*c>6q9=K#-K)LA9@#B7DV>TF#q~NnhKkh+g`0nKol#Lec?CljZ zG-M3pG1uvQcPl0~mcw~WPo^Ce)#}h<9upH|)%WG#kI$jSj8Sf9+6&z=^T?XMe$BJr zV@4a;jER|92ONV@Xf58~sXIVy1`u1Q(?3Nm>m`5&zOsz6@-EYc=T9*q*Y0<^dh_Ng z4Dy781U`#;%B#oKUSHt}6M7mpyhqT99dieu*J*zXU`B|B!|o7G7p65guA!&hKJT+L z0IWt+bH8Q5XRj2wQALuhK7$Phx3b3TjJv4Bl%PQYn0J8 zFvz~YZn5aXq%pu6nY9;2h%C=mVU}{b&)NNSIGL=R_TyLHu(0+_F&fb68*4bw6{m*V zWzL;jMRDuat-X9!SAp-*pq)_WckbNjM4`TIX$eEORcBSs8W3sMYR66AdF=9=`QaiN zH2U4UcavtiV&xjUWVs1F^`#aPe zVHE%XFU^`bzj@4?$4N(&-K3<(Xfykk9~x#^82aiJ7x^Km*ZZ2--`Uz(?@h7T8@MAc z+-Ao-T`T`&|28&^OA{)8N(|jvbr_(e{gB!n=`03Z=mrqzRxX;`u~~TL0Q%_HA&2Km zECw07y^F6EcfM(C3;}<vmHxpi(J_r!VVbd-CEIRs*pP&B1 z%&3C0vOK0yXR&u_RTbHVhZz~YKYbEkLq+ojxQKGyI=+5YOu3OxZ#quUGD5)p{EqPQ zhH#rU;2Soin1d_zMmX-bwzfvwVt1J^0ON)<-^YYun%jq<71>95ug#a9{Zv9~g zIIymq^&B%6t{puCPUf$;`JG#1Vl=qAYmQaA88rQ~c-L*yTXrRj9=5615F@s7X0;payj zKw=nA*Xm7rNXG}X$6fm^9dy=V_*+Gq=b~vx%asct!Q{H!=Ozx))8Cw!uw%{bI|S7F z4l}(e*Pg}C&rjW^^axPd*4?{Hfeb%YRtope85$aPS@B(dp|g5uXb59wtXhnYyZ}fE zZ4~o@(5;444M~h}&_x33hKAf*g{i5jLwPOtlkI`}k7TAPTIgX@d1bU!I)41-IJl%P zfZjPVv7kqf#HFP-K^Fm~55ymEi8t14)S3R(1{fMS@m2aGpog+@3Fc5`j6_iO%y%E> zj%#aCpN60d7%D#<@)$>~CknFBL+g{3$@*i{ad2?lymgBM3eI=zqJ{A)Y+5}4e|P=ul@SGRBU4kty`UUmcM1;qi5}kMy;4M^C}?UP4O>n{rF3z+ zT?P!80@Rv|oBIXGWKC_YP>FF?OP=CyqvPYnLk_idb?4A0?d|O+el}&OQ5@#r7`>@` zGC~@9fVhW;Fy_R7(w!%nnGbODQR#iv(Iu40410HM*>bhbLWCiG%pI5;1iI6T4}a&~ zYYjk;;h30|G$y!{hUV*WGf*YU_3PgeQAHV?4CEHWuI=NU+qXvqry*u&X=wqW2~}mj zz4E4{q$Hyq!q+1qR~`U-)6^WVzCI&J7eb1Hg)9OB%_j=0joz1+`(O-1O~6=t+i$mR z_wN4P?M7SxGgdYBE3$vSEYBWDN}d@=PNU(oI)EW%@a`rhnk_iqE_JIF00+l3^B;-r zcfN`CU{LY+!}3Da^4_c>G(fy5gp`uDC5)FVnW}k0n>#x@+ZtM{sy2HUzeTkfSz7i2 zAb;$!8AW}J=d~~1LtnB0{9rAZkW*Dv#b(rAT9`eip8ch^q)|n#cfii+myaD&d3h5I^5K3Vmn#^z3!^1uClQc@J&IvrJ(!YZ zvozaF$9q+mGZbp-_jeoE=-Jpd16gC2XBbp`2Y@?#@?_Y=#6(vm%1-8gxSn;s^!bbgM1o1inrWvE)iOe7GAvs_mPh znyM;|h=(9YUHtiF5k52!SU(8?Wb574g zwWCZ-odjaUg;`*Qult}`KUxy?qrFwCN5G!cBlf3iSKa|{15$KY@j>gm+B*tlZ}H$1 zDcrO)Mh1p8$@O>JEP8?Je&AI^;JCG6mrc9-H1x6xj0fmY7#=r(Hs`WSrrWsZmju?V zT17-}!bZXS2uCgg0zpkej|3S5i~50YBoG(qU14w-3KUe7#|;e)7S|#$WT9G1=S~6Y zzR)chgS>g``t{#%VIV=>;kK2dpHJ}cJS14QL}V#|AnPk{fBRLm>~a12bsBz~ZVvbT zLX1)j)I<~Q?$#q)aA_i51Y(qX&Flh;{~kY4+(|UpHs-tGM`u>HN3Mh>2KA4_@t1nl zeE+YuJWs3E=(H}t#uKhnW@tot=F`*DB`qy`pjlw|Wi?h;KY9Frvi0o+zNH+`SxnA< z|C(jQ?ajd4EGsKZNJ)t;ER2MBmu}N@!DXWFGy%dWBvk(;dHJ(w#u$hMx`7x%{amqP z1vU}&o;{LPkwQZ4_eAtQZNcQZoab;HGe0|l~gW2#X9#a<|gdeD~CJr^gBX%*(TRH2hM$D=`U_+W#)knWQi76>P z*hu+v1Idi7V6gZ9Q1D*93B@%|L=ah-<~{udJTVCmM?Kla&~pqeQ}u& z$_-XkK}qSQ&WH7YwM%T1U4w&?N=iEkse_IL-R35#ke>38<&HwJ;?3mpM!$amBipij zH>I0v^b#~5BFEx=fPrkA^h2~cL#1g(`kOKs(Z_Uvw(>!)@fmVjS~8Fg=sXuV*oqc7 zvAco#T&DP;e9*a#tbm@oSJ>?lO8G9l2;y1z`)>vTgkUMFrR87Td8PYP07kD(_ouA@ z>hkf@`XIHD?4qE#7z<9$&ikm}&k0*vTH4s!q8itEE_BghjrB2ZfHA1ntbFm}1;CB0 ztZZkZsO^M3ZoVHr0@&vAv7N$;6Y|*7eE4_JLJfwRGexqOP&zSiHS#BFB=Z4UCWhPF zM7m=iWB)&W^5p9M`}gHl7vJf; z*aCup8A9af*RLPmSi5-)-89OI?#5fp?vj2xIYq_upxW(j;~T4lrq#0?c)~U&*AMV} zLQH(oG6eVttL+S4fpR5vijf4d%)`TjP)0Bl+j4)UcD;sAc)2?m{t@C z6U>!45FkiaLE&a`C!dA=*7({|kO$~b-;MRjKu_+gBnuY`hzPrA9!y^$-VMrvzB*I{)rKLTJVT!qef`HBO)@$RQ%fP!@?vp!! ze=|wR2qpRDGuRokWzG;_+T>#^{H4u!e094AqfAGl}E}RE?TKyz3@eVx4AC(d1 zS68fjBw)|%3GMADD=Pz>B4{(71CzgS&0zdF^S|;453g6&npDU~x9$N_j*E^imT%LC zs0F1V=<#Eh)+N%``eQ?g=Zv=i$AhL(g|0(jC5Xq;TmD5B6lh;t9xpK)h{gkM`|;yP z>esxqeuOPBKSr0Y{`%EP>Vf~icr^sB3-wT*|Oyn z)F_AozI%A@jaP|8-JxcD=|1nU->G8-ab#-y^}ud$6QgQ$cl~?zYzZ31wML@{}>`C)wlZTX_+18nv|n6Ckmmpt1pw?0I{`{6s%`>H(L3IOwA3m? zZc$ND!AP)I3wi$hxrHJ%niceF2;9TULI{&75OHMcVK>gUN=+KI!7J119xZ!GP3*U+4;pK8yg$Q zIv;Rn9rD1(uAn~DZ7aCj&TJKH>_TP6KYhBw=fk@M*=Q(icMaS2Zu0Ks1}*AGhf~&c zJ_4=roe|fzEnA4~gVM0Gx7W^Sy6x+$2aFiW%@ry|h%F{XenEkMs3mkqj6$i$Tz6t( z=&NQec)}#a#Sa`mz7Y!qsT4Sgl7IiwqK_mx2KP(9#Y2rui3cM$O`%Ld=PYi-QX)SXD8qxf!>eicWa1&xh~)-u@Oc7cc4~RDfCq ze?JSLhFbw*PIM;lvXSxe!$Ly)P|~G(L~cfK1bBv+WWbDX;Kc6Q zq*2^m2nb*5>uwDcdF-X@m>Kp=Q9Ffmbr?^H&dbjCQ9kdf(iESlHIN`L1c3!n#u5%|uh%_1Hn zb#}a$djI~)cege`4VbU)J@6+nJ9J1SirVv5$e+mfHn#uF&x|Ukfy8(tc=KT4Xag8c zr%~Jec@dyjt3Pspl^Vu7Dt`yf$PaYMYwwU@=gM zJw3N742q4omgsGo5as{>68w4*^@FAK&!zj% z-*va^U=>H&KY`rh8(%4=$CEBwu2MBJhpU!ZNUc;2*hzW*t+U2{juw>elmXBV?!LRQ>Q3U#bAU{ zt{3pp@i*biU{u39+(JW>U>c4*8pj_B1w3ici>JT;NOr;wo{zQTzy|D(Os@FF#7PJ#@(CBj22}K3X3dLN2tRKi&!00e%HGsM&|8LiB`#`GoG5@a9>I%=`Yuf-iq=3-!qA{lL z-Mc5he~CS^=G$K{@6X?N`)YFyJhTn)e25$L`-qWoZ;#Ix`_Co)_n!hzs005%FBO^Q zT1w7ov%vaT3q&xQ*H%}LMz3OCQpB=VR#ryov;MEN<|j}1oEO0Wkd7f?i=W>L!ocgG z{ZkOQx^~mv8QJ39MY9!_GhKAcGtm>6#>OzE!Amsq9A3CiTY$nNz_KX&aXts;hZUkB zqjmB!5hFRwM~`;E5|4fUoa!p%de^1p60GP41U>|Nx1WMen$>EvA+IeL=hr+m6fH-MGJ`5!&@}F5t}a`_M};Bc7QjX2NGH7@&d1aZ-^sb zb^Wz@mie-}Js~6KPc@r9*D8vHwuG6An|}q0xVrmfy-3-k_-J5f652tKfpB385GSac z+{C{Y8TbmeOSMlR_yLPDnaC6`U%qsLCP;_`#^2?X20Hsq?Xmx>4i*~Gr_I`OA0Vm8 zY1(kii)!~7_%%qkeCV{ggtS$2rYU5>ZUohi2nvSpK4AbzK}Y~`rZO^u-oHQRwQ1j7 z)SE?C7{ofI6xH)!=ID0Bq@bfCRw;zqxY*d$L8b4B0xamvIoOz1g7Ikfl^yY=rb73V zpq`K=x@>Z21niE2MN@#$1w=(vLB_!V(?wo~1PLU97`ATN@?~fSkwIhtxezE^_`zFr zkcDLf7zf__=+UDTPr#{xze#=%1#%mn2$&AKDuyUrHt0WLWn~u-A~^$s;aa=f5j%5M1w$qAo~K; z35}(+qGEDy2|^O5VOoGQBU1s}ZAf29+Sf)!)~5;KYd_IIo~=Dv*spk3q2q zmX02a)Fr+}57IDC3JM}V`0THfiduq5K@{Lg*X|Dor4Wu-11FU=dh zxv8~<=3O@XiXuLY4SB9;Zt*wQ&0HFu3Nl6#4B9*{?GMNV+`0mVat}p4kn)vF7wbLJ^2ekYV(zU|N$P+q-w4!J#8T21FnpKuE*Nek^Azl9H3#hDti7_SzRY zCl1U}-FI}5>B)6}jyM?t=H;?~^M(zio&eggn59tD2>d^K^tQjq(jzD-Hf{Eevane2 z-3cWcZjVAtP}5^pACB<_v>^C%P~=x36pbBm5n&SqpidIW42y~6?1<)s*d_Ev2nxNH zp7VPQGD3lTN$3Eon6#LfHzN%RSQ%7?1GoObyL>=R0`G!cs}#ENV>gp+Pf~!;ZoYi^ zatdKhq9uT;fqL$nc4j?x?7bNeM)loJK1PxzCd=1{Tr)`s014`sKO80Y1q5y3`JX3X zC7gi;iLx{Mntlx>W<5WY1<9vkVRoE|%Ywfr8^$0E2ZAGi=I?gMTY<<}_Z`N_jxSHo zBD1Lkuix~CG!K>G$o1VN?&gL!2wm3E2zO?hT8UJeyJFZq+_#5EQ# zvWVb06)@?w4?3O2n?>}Hr;-ZgyoLNSk!X=K0E%7(Oh#x9DS-TZK}1qu#jI7V=OE}q!V{Q4A9`%8p-+vW;@LrgkwFdRF{g#5fI=nZO#(nLGNBPt z5VHb(_)10-QIwLEQVy}P`7bQE5pe^zmJ$I+bSQ#C8QoG5A_lEN93nFPB1~D`kG|Rv zF^M|LZ~G(NVMrC@g2Kqi=n8xv@X(j$Ej&vj-XiG+6||^$mv_P|NKXG(?jS4S-f-CC zJY&KDVIlL8BoXHzKwPq zUf$@Mt)A|}T~}{!S=%sGRdEE_YsN^Y>wuImJQiJq=lTxsckbQ_zy1>mGnMKQvXH6z zLN$fL4T2c-x9|`xkKHq`UBoeSur9TEkU>in-%B)snB?+O{g)KrNd3cPs6Pl-kTK#I|evTQ&Y2~?Hj^0$ZC+d zDq`lSV3O2EfRKrm^&?`($Q(dWfvQ1)a9Vn<0mB#5u>|U&+bJo<@Wie~o|Q{EqId7ZuS#uR=E< zGz@?d6y*pyBfJp`T#NMO$(3mN`yc=}xqa`u0fie`K`>kAdqdd6kwajn(AiNkL^OoB zf|2LK>>U27n&bFRpWeN{5&oseDLcIwG%fZ&Pw6Z?F|O?hl)UHOdWFKL$J2AUrTtC6 zphsS`^P0SUW##_nw&B-lOR&cv`e-9xN7U@ABt1!x52V8B?D@SZPKb4nSop79v!(`2 z7}F7x+%C(?yQrwhP>_x;ih7L*#d9UotozqX^`0dsZwM)0eYM(X!Ysqh@oix|giZt= zNtEWynRgs5IH$xKg5m!&w5rrmhBBr%*^ba*UfU=?CInjk=^Dvwz~d6 z8(;=zgb?pIQW)|I3g`Y%U7+f2rJ=c9ZPfidqw*Q-02CA|kDSwi)vKk|zU+ zM$Qa;{YoOpQ8>mz*b>t9qT9U(sN)%220f`b248|Esd?}*Y968b>^4Jm?DRk0K;)DU% z=CxI#4N=;qt+5F%)%#AumQTI+e@6q+!!Cq$D66VU{F*AkaViq6B6)NYtwl--N1blA zSQbS<&ICZ3p{tnoCYYmWX)+B_1{y$SB-HX0ckqWIp&dqCXyi6ez)hU`)mDzXCjC{I zpMN)$c!=1509DqFgWeF!$XOnofdD{;7Xc4zMK*$2PUvdj+fMS(#k4hN+d zQb05kytsY$F$?jJAudfT+?q{%1jzNx)w5>nayghA0z?;qTCsJ0Nl1Ray`TWS1EC7E zna;sM*BTo+bpGXw_#xOVFm2cHaM~Yg1%8Bd!$%lb|5iI>$&VmlG&U+nDc^-k06kk? zL&Gm5Bt$qZc)99Z#9A@MxFNct+@N1}0ud?HpVm`)-QRM6{-&bd)^qpI?_9g%^!D9u zD|XdYudvr^y(YW%t@id+yA*bwmer#;Z+&UY*5G~H)@^wxe&*^=Q^t5t&yi*kXUc3U z$t#6XNeZF1bAr?E(vEJ&lGAcmblm;!kZ1q>JtdsX@nx136w2YqpI!(A%W!QSzCz;# zSlu%`%vN4i;!?L&DOnK^t*o?ER$BVrv7J63OwUjvrDi;c`JUqmy9iL<2-mqjR&p1& z+1E>mK}Gg&#=n9OSgWY4aU`q)h8Y)@s2>UtGZT}nx_Wr?Yjc*owp1L_`0(*#5_nGJ zew-si`Nl9@eEg}$rnJ-QC_jJGiQ_n`aT#v8l9ZG$qQ>1;e6Tc+B-bYarY(E`Bi zeoGlt8iP7VIM6vx5xgoHsn}f1vmID{m&pMp9v&soQc&M7$VkNJ{mPX@bK|5sYmlJ= z#)zvOpJ>i^w*632A{huHbNl}NsTlrcEiG#J)&tF%$&g3&XuPP3FPWGmg-gfNm-g5& zadOI4gz+|#E5!FfRh8rQ0Mtt7&fNsm+p%}=^T5Duv2k(C0s^Xm3K|;6;bml+HOV0| zk872;ut=2-=X;8QX5U|P9;nEqE}?q2XEG>R+2_x7*o_I;&9gHz2`^vD0rn~5vy+mO zdjM~80W8>pl1O?TB&+`mT#ISeuGMel<-mJLg<&^~T zWb)<7HPu%}2k|Y?&6rM}RKuFAr=*lMGD^S>h-cNvJ&MilD|k(t28$4glQYkil6##l zUi8D}^km}TkiGbrYgS`fniE@N+Olw<=#e&!>Px*lpun+Ei=(EzC_?UP(=@|LMMK`P zbLU6TClnN^G+x?9Fb{16A`q<9@n1=y&ViM5amht=4fphG7X^j#_G0!|h#KGW_QoZI zyKkbf`oKIp%mDL#rfJCOTgIdMWhurAwLcPhIb z;$uIi|6K&K+!FT}wZl|+5EYen|NfSJA|C2!Ju#?XaujpTwuS3x)qO!S!qwnlsc?Rl z<4hT)!xO+u3P3V@d-9e6A?A>bs>dl0)b)t(IBSR`a$2%r9fAiBNTBK0AZA<#bUO*P z(eWbt=#sy{+TRa3|Mh=*gCinR(8LD8OF6?T)^FTck4zn<$HIE#6dPbSkkf~WYVdP| zNyv8fnl+je%{N8<`WCyf^aq z>p8VgbY|t>Ui@U!;lFL&yE5R2~Mgmxva6|`nozJXclw8f^7CI znR7UZ%57Xjk4~#GpyUw*<*NWGf;mLYSnXMgHgsIIMZ`5&LN*Lh2AeV$N&xkadB38PH_* zuv9Pi=p-U8@sMp6;V1_IC?cr(41@>!4jT6$N}T!laiL-RHjAuQi!5Xi(6KzeH7+|x z9Fcqo>MR8xS2jx6y?c1r^X-5J>!ZKlnwj$=?z78hmKSINtn1-HPrg~X*$C$#Olo58 zz$A*!vF$ZM90MIApf?kV23mfb7>GXgXf*DK#U-VtPOUnsnq`rKaF6{^v*Lzbtikj< zwr@9r^+wv;nKRc(Ij3k9X?kh*;UeX1Y+gddi@mq+WD)`>w7eGKgzMlgI}bpfl0#rR zimLbv6fp8t5>zq_E=WjJ3r)91!<><*xx;6tW&ZCh05#(TiX@r5MpCjCQkfpjN0niB zU<_Jrli<|CIg=xdjHWXqowOV}H$NL>{3@KcaK{JG;tVS-m(deQhh;rB#=uCqV0v{i z64V;V9I2*XxdxDSB;qkWr@?2MOrz>EINMN%-D;0Eip592mjOzAEMT96JjnzK(xmy7 z@mw+85{{c4dhqaJ5`0RGBwrFU;x=zqz#-&#TrYzJ#$Gi-jd7?=OazmGx3UN%P{c6eVu@HnG8vntOU{@znp)GEX_nCUhx!Tvd?Re z#TTT!>tE=KRTV6$8yhD=FL(;r$RaGPiTq6+LTs2ji#}0BlGjS<{<}1<+Lp0Y)H*h` zYXqwb?U@eFn*FI|pO%`cWMB}7)~uRoawKDRx$2zJ*Yu~P^&nPw8az9QKIQU@GgTtX z`JjUdI6+`s8P1Q{6@c?%+&DD>f#D)h7XSmP=JK8zoY%q7j>XMl;^I<3oz&sr{3Jq~ z;$+yq0`V?bnj2idX;TBLo*Ty+^$iS|`T14Qj=z*WV3~wa!_3R8j6hUig+VP!^@s${ zAq7XejY*JJt(t3>h*Ve_lYCqPfW%|?yV8+@&JFXH&94%Lmu7Tl=jM`NRVQf`6(Y~8 z&l5I@BVrndMSZ{E&ekW&GvdrIDN||&sV_Ll6&xP^9B~yBgj4SN`YPadaGTT}<+f}#mJ<_Sr9Ec_lW>x z7h{K7vIa418qRJOib1n6!hyK>)p{l;AVTBwq|KXORYQBuM1V5WxKJ~h<x2wP*e zbywYMb2W(?roz#c$ax1E6gi_7#98)>=jm+A%DF@Ngl#gkbA zw~>~JFcjISlgQ+k>v0-)ytxJdEw7?Nu7!Z}eg%p+z|Fh&?kRbA6yhAmcBI-9Tb`U= ziG3tarVZFvvh( zze&#oaEv4m?s}l~t&<+>J?cK1WTL+6#`A!6VKwzQeIE)O2ofo5}DM^XwrLe8DQfOfCH!$v!GyWh9>BV z5cOG)RCEXc?w6`5klg~YoGn8QWCgH>QJF=Ocm8QNN^vsr995zgkj_3jng3a{R}hhT zGH5}NjNk_%q!ftWN>45j<`J2Bj0*u+`>dAZ61bDf5)yY1HX#k@;90K(cv}KC-M68O zKLfdy@tmuTf@VknzY*wqys2&2u34Y;uX+SMd%5! znnd<B&UorRP;)Lx`TDiX)r06F5o_tfBx%IoMnBiljdQ7jMcavH&K00{~I0>(f+2SB)i zDZwa@3JGZdZLVLp?h8Jf8^YctJTlrY0{JH7Ty;C>Fm8o2~o zi|hwzuz>x*1YLm)C`g2WeGLX57b55yuy7s=xxPj(s9I+(UITvq3d&fDX2G0q|2`OC z${rp|Yz;r#i;4&V1JzE>&sT?*pTsRrbQ8@2mwu>Am%#IJ1JmGUkjuo#h+nNea5uyA z(0?^D3W|gq7)Llp_k=t`!v#60dQkX{bi(S83vik>LwdvJR=e7Zss%2Y0(N}_@(loi zDEIh336BzrC|4SXxe+wV4V8uU;Z zN>%|5qE@Oh9yoA{q&n-Ko?T1+0xF;jg6H~~ssPV1INM5psXU&e?V zS0BeiAIkCGIxn2AGiJ3pgaLX+BZ{dC(JS%}V^K({9vLNeke&NtLo{o!nh7XP92!Y$ z=$#oYp<@Aq$AEd+WEL3(Jg&+p6IlnJ#Q$6$VTF(#mxW|Hw{tT;=6C+{7AW{04uD?^80jF=(b4C5xND&>^zP z;ZFT@n2)ts8^Tn~jw4+?p?WWkYZ=;bL>-JJ0-^(}cmZrql@ujpPlP7xa~$e$?W99<#4c2r@)s<$7J-qji6u(^tnUbzXdeScud?pf(Mu zBnx<#8}LxiIP@ zH>i`h(8cn%OQ29@fA=?+?>-o(_@27oVM1IDZt_r#W2#eY~U zR+LH~`j~2tO)L?zaLmU9(@Vg4EQa0~@Et_v0Y-17>ktBy{TRLTAFkX%alJMV!^zG0 zJX3sy{wmL<41jWl!C5dl!UhP~N52pvWViW+t~UVkJvxz8v=PlO9iO0gk`@A-qLEGu zp-45`>M4xH%9h7C_(3b;kuQw%l|I|P^V8+C+5cTFS=fm(tpO~zg9>}==FLy+ROlW! z;*tRSiwFcnOjSu~kZjNeA_GlKLa=t=v1uy*@E{apQ<%Z3V2D7pJpcx%WPLro1YDhf zRmW94vdg&uZ-EsR7@jmWF~RmpfrKrMRBErgyF}9S=XFQ{ymFhhA(a8v1B{n@Aag+A z@Av*{`M-9d!%%Z9gb@YYNHBjTD8XoE^b*TU(?yw{%O0d5VwXcNsMT<6i-p6b02n&Z zl9dL)Ht}{X-S4R7;>CK*EbRKpo)9f&%pih{@jf^{5r@O|N$~Ljqg#v%@Wdr|oDWhh z@+bhi*+EB_1{iY`BOa#;8=sx`ArQUABJW~~YG%zo$JVFF%pbp;ehLR-gXrxC>Lhqu zt!`YuaYLwpP4$&H<`j;0+vKQc3VY*`9ewZ>`Ln2#N+g9pI| z4RtU;Y`^T4D^C!JNkR&n=!=LSHNXfZBO4Y3;iff-5{F3N1N7FX@ggz^hCpdai5T{4 z4U8B(<|C2tWqdL%pVbo_^G`*|5WEbsd_h{e0gX2e{eW3K44yf0t z0YF(I2;wA<+Mv*Wpj`;4wK%i}T1jUNt?XsXP+$y7R1-&D{BWt@MGT5cO5nI218sR( zy_y8feQS4zTOVnVcGLcJAR8UC3Tqh(S`IP5qsf6?6 z3`ryMysVy(O8ctM0w@v1>4*eDF&I&}{|pi+s|Gx_D>yXNS(MF7`zU}Y2(vQo6cL6C z7RJg!z2z}i;QkW1mrVM$T>GHn&M)nFRtk}3u`n z+Bm<$I$k(to6< zw-?DSO#+)D9KR*v`BS)DBb?}(>$tHQ1~c*l0>+RHTwux{iC7tTrXj+W>aNDd(!%>RNJ>w?R3$wB9Ggl}LnDPKK{y0WixZ~gNnIQF3tqD3BT^L^VsO%5#-y4BdKjzT&TC?=iwh!nST_*`;f)-2U9Jm!Ywf=-KQ=;;r z10MAG0KtJvzbshQv?Ai9GI187mL?dX&Ll(27-&q30^X{}{?eLM$^P;WL)0U*$u05Z z2%=^+cruEN5YDd6;f!4-&NgORwrid+tgM6VY+8V4T%Lz?f<15_x-^b!Kx4*&v%$HE zvVVt6_QUyOwc^;SlW>FkAa^M_IJ^e0u^;P}z#=2CC|;A8es|V0N<&oC3tXuVldg&u z2QkUMBYL1|BP;3QNCE}MAUJYfRJ1|01=bn_yGvl*nK%_g)FjN9S0o||UfTPr8BHES zG651~Siv|? zhtG+MVmeBJtrNbSnmfQ;bz<|TO-edC-&GosovgtTQ2Pq*#)KzNPHE)Y{Vq-;AfAlL z8z}9*33s%&KOVA>fX6~M;2F%rSU6Qsr7i>#R@$ISx-|iRkm;T7p?M%_dG;Tyo{$wm z5?BI!iSKnVYU<0;Z-XB_NZ3poh$<{VMJp@+FO+arfJhkXTsq;mJdeQBY_D6M&UCwSvXDU^*1!U}{ylVXaQ zj}+8JvQYpwdYq%+trJ>pjOVrmc2mAyXm=5r#K8@u^$@th$Z%+gTwGkV$M!MB6GGzM z8Ssb|{^3cTq?6TuL$;^dx_gey&S{26MY+!w@_;p<=QU?rMl$^OWCQ2?nod5MiP>;@!D#wGgKka553?2lFB@ zEiH{aD}kB~I;w)KEO|3<3sRjJnnBR3pwR!J#U{euM9Vmen~Sjtc8U9f6)mEfnc)Wd z3XY6S1!=-t8v`GeefpFznTfATHa9m8T*2UwB9Dd@p6#YyM40>wo>GRTaI91%mNTqj zJWcB)L<$znVk)>(QyJDhSZ*STgXQ*E z@#$r%Dr#z`V#Prw-Iqt_aLUyL4g*qz(9(}$&qQ!5;CnxV(jkP$O298w1mZA!c?&M* zg$sAF3UN56DhK@{7ddlo>+k0(B8AitLI}Z{p_=d-oK8x^bB|OotsAtK=akW`$(BX6 zW;Rq-RW;&CGmw#vhgC3OSiMBCrw1I59pl5Ud%OFU26AG6}gU z0jpks_B zfCf>GQMBZ*@Er*ID?>_M9S_<#;Pc@bi8vs(0Xiq?pBJ6-|poXmjg}4 z5Z#W%M429EKf0C@)Jwx$QM^wNS|dbLPz|Alkz(R^;HILUgM)(PO>g6Hq#Pb`mH^|$ zq1hUF5V%n|idEKc$4pP({mSYSbbG-9J19;-qRmB~MbNd?SwjjJr_@%jU0YsNB|{(q zPP)RLBDfG_!4%sSk(K-PCW=l@+0ZkFXKrfJFigw5IJCfwNJVMj5yEUiEm)K5T@uxP zgEU8cVjR+irc^I*cOAvm@&NE$kXO_cc_P%mLllvbtk426Tz?NyAZcOVma7QeWj&I# zQGet!zTngy5u`|F{r98=I~6$QClDr_WfUU$3>>3CP9>Ng&e$WNUyew@6KMlCc%W`q zhxIIaA#hb1(R%S99RkmzJmwNfusqYGejvXQ&xb1_vIxE|MvyUrX(Sne2R^WU<=PAh z1yn5oq9FEFWEYwOaaGB-1`TTvaPJObpZz%TgaXB`U^p-E0tuq>kxN6a83e!ce4;(a!j#Ivzw0L1 zM*je*DC)HTVOLTN{D0I~I+WSz6)!LsT@_K>HDtlci*t~5uu0kM_Y^gud2{3OXfP>e zS2xP@X2XfkJucUR57&@X-HJgONYYf|-R=_R+jMH_+Jbx@=R~vR7 z`vM)6csd|Rh;R{+7`7x1ieCp%o4^UmG7}-k;i5)74B;5ku^V2#rXOm{Q$}AWp#*{o zAk;;M*t0M*2P21r9OC%PZ=NjwpfhN7G$elUK3ICN)NO@Hww=kGSf&Tlf;B5}A@Ob? z(H<;jC+z{{f{E&UTP5z_S%3&W>od^ofaORc2Q31KGz~8U9Ug!?j#;fhTJIpFXjQ_N z@O0c~n72u&2ojzG7$P_gbQu3J#&Ct(K;{vA2pqjY{OEuLtZ5}QmHYx3cfTS`dSC|( z;$Vy$xSNnOpeLi?NSPA~j&u%!BX!up&~)*C#8SeeU`SiUYzI)qJODThvSYRi2n$OF z)&f8*gD-)+Ji-?eDOI1b*9;8G%y>v&fWHGZH~`dJo2IO?67di@NJ2o==sjd}0efRX zARDm24@OXr%*)fKuR&HJezYjO5)+K?WPEJ`+bJmnYWstm+ztxMD{uOz`%o$we|@*+ zt}Et2F?W}ZR)a^Pr4ySy{?_g#Jl2MgWFm)vt8nAdiNtWki7_9dfB^D|5k`;4lyTvt z6PRUfh5^3oroDVm&_)Q;1jr1GK?Y*C*Hgd?Q#^tmLletMOw*74bZKO|p=&_&2?B-% z*(atc!9CCv2n8Wx0o-S_aPDSKK(+3-OKl(4jLsea_=~6%Rn5H3n^gcp8hA7cGhM ziw;HDIR5ofXc)NJ{X`@}(h46;3?bYB0s;`zz_1K}uN#erzLevhB3?+OLGtW_Hk_J> zuZKQPY+M{vR#a7G#&CpVPTXD+yOCn3^_*DJD!u*jZ<{uC9lpXG9{ow6BOZQf3h|#L zCUpIU7_b^JI|*b3o+MD4Pz5BQ5|JB3aED+IJowt!)CFV^O_7+xP#*|CGlBz;oeVEg z305mv7m$~JBw%at{7B5{37ps?;Yrdt+aa6xO|y}881c&|DL;m1cyka8~A)56l?`V6}fajQnkT@ zXhwhMk5U6tAfpUXdJ>BuaRBT^!Cv$cVBx2*#N{C=g&++AArp5!6Axb@Kz4atWH}mV zlg>kSBfdwbG{grStA9>_1BBmN0#We6M4N|4xtwA-?YZM0AnX6b-g^K=xjy}Z7!U(N zMMQ#tk`x4#C~;I&k_16SvPc#r=d1`E10aLssN}5V97Kg7O3pb+9&#SGU(db&59NG& zYin!k?$(|u3rm@q_X+*<)BWpTcc&jkVu_{BMc~1t!nh@Vp^Q*30Xf0o&j9*{OcWU+ zP>2nnoCR{pBDf2{eo(fsrJXyh9>E$QERg`p09ofvs9{P5*~Uo325e@qMS=GKw;M<> zg4&jDFG}%8$RI>FbSy;jK^Y~1CV^tR%|JRwxMLD%&~Mp59GmSgQT-o02?SXR476!? zgkn5O5Ev$-phyD8WE$|4cJNgZ00X!K(@^xJ3E`Z+RgxUd&K_X0uAjQYuMPl9niUO*EI6(;B>j1?`pQb@3=fEZ4k|LNE z7(cKX0pM^z`~$2QsBpGhW4l>KvOj!KPF8W15axK9j;`GD3RrNUxsbp$*kKSYMbJ!8 zT1Ifd5ljh5>OyoFxY-cA(odZ>yWR@vCJ0J^#IS%j#RFA45v#orqOJ{g&cHi>(IYfH zh~-PjgHl51%y5YzL<)9x86cEk)mni016(XgG(@MtUbJm+%;}k3Tv-WVK=iQ=XAyn1G7{5#xnaqp*5CVBR1)2L$c`n5{sVXZ6PbL4||D^8!K) zD1@3X;C;0v-lqo?b|l*xa&i#-7GP*7xMPA23hFTAaZ#x>=G`6M!JYZOUJ&(y4jdjB zht16OX-Z^^LG`SF=jiAFfdIrnvYP3<_P4d%rUFq-5)n=$>v?NciQJ_?LG1@J2eAE?hGiy--kDhE3PVFE!y!COR^DqlG( zk#O)RY%H{IKm(+Ruz!dsIB$a%cmQXnArZ=T$3amDBS_hV%?$zr7`%`KFystDJHwen z*kA~C6HFgSXOcl+K!}kb3J)rNNdn5!3~?t=(aEZ&C5i~s3n@|n5rT|D5HrMq1vc?* z65-`{aM9voCLlXB1~fTBl7PbvEa4_dV`vmm9s#YR08C7zgl^+CkQ*d81$bhP4DZG( z@L|A$j|1mZ8lut&PRZ@KI@7}RZd(oF;oMLe3V|C*nPtF$aYOuY@MC`#PN%0>PaT)J z@DH3$vU})c#sI0!v7|F)5!0?l;S`kXWx%F@T}N&?@RNHioxc8c3L%U@cnF?m3>M2% z02>j$ns7z|NJuLj3w6jT1l5Evv490d2Js^-7R&V%K@;HuL2wfYBbtMchtCxq4L&u{04fu`pbXPy34t zaKQO}3XZgXuPPi>NH9r+!9>~gLfi#NYEa=E#|T$07>A&08#n$2PQ=mRcCCCRl{El> zSf$7&4e>b3F&w$~&QO0PE3to4Aq4ysNZl0lJpQ7>9XQXo~~g7=AUOi4+>me?pDRz0w{F91gv z3{nIQ0vzcl6cnhk&p@sYxG7=F;aD3X#9ChC;6M(|bZ9EEq>;gH3GN3UlMeO2fz$J19N(V%9f)ZB2ZfgTakW(7m(3m5ypfN%!*8d&Vn zU=BgB>mi#;c0OGW$Uh`)#)2IT+-ZbN3tj;v{}clSVE5tn*gkT+89vC$bKuLE-G2%M z0VII~Qm{U@Zkg)-lRJesIP(v_pA3{SLtsipMe8Kh1MEmo8xR9h7!fNWr1<0)RvTw!?IE1nrNs4}ReaxrdnZwPW(YtO2e=;u73>0Pp}% z!6E+W^*?-s5VAS}w|QV~y%J}FpST2%gg;<);wwk(e|z*p01{!u@_7fgI|O&LZvQ!E zJfIhx+)wYvORW5d1^Iu-8UAO&0p9(V)Q-mE^Pe||x%sJ2I5r{fO z7)E-n7I!j`qK_f*9Ct{Aj*`Yt4-=-lq-ew8sQN1oAMU<=!=>}u?_Ac~4;pr&FD~69 zq~a`+Y4`bwokogyVbK4KH%|zLTjm!Bzu5HGvno(32eP(sjTRxa3f!F<9`sA zGxvVGY~-#k>`e=~QStRR(g;53Zy@l$AIAHC(Smg|IUd|ihsY~ZexDzT-5xn|BopW| z%WG?zyy;B_I)KS`0ppQfE&p9!$?UTNC`<_jrR*{JNCk7GZ%2efNhGvqs0;yp?>Y_r zBLC}!OS(+vN-bz}1rk2RWuiooiX6yu?7>x7gcx~zO3F0)GZ+j{p>@cI<<-^ryga_L z&9)2+Fv@x%K?6zvsGxPA0v*tV>!H|JpOvlcM9I8!#%~!%mulX>MuDXf0_OA>q&!uF z4-yVm?3iWLmRh9C=4A2i&U~594A{rW7pJP`u|wh9jUf`(U`Vz{cpH*XqzJ78wxK=L z+(a5Dje*(YZ!Ym)Q^CXAm3x-SjD?OeEC6`jI?JIE4!i=G0V~wF=vivdE9HSjpk=2j z0}rWqLUx)xZ!!YCKawy?S&w)P6y2bu|K4JrhZ@O=^p;^WA$ZuG4brMsAyf zMMy|Q6bGvTMWH0nDrtd0)(O9EKAgEA=1YSVu3+|o)RG7We#kul2ksqk<;DTr+5ki* z9I(~h$~77w$pNXn*?=30p?Z3GDP(kT2?#ilWt_zAf<>#SNCEXGJ3BjdWC`%nLpw6e zp%yCy2}5QsA1GJ64{44on_qD+c!=HfhBe@a^@2tNCBcoX&zi?>WIg4kOzN1Hc;bDC zsSl8xp>q zqL0O>=bK$ffEE@24=_2h;F&3U`}pWVJ~(j6f@hNO$`yG81VUliKq919AK(op7eTW| zNCOE0oWeXa;UJz;+qaz>$j+4c_1nUA+9#UOF$5EN98XP=yi9Hj3TOBWkq)}{LBRG1 z0YS!3YK3?;D3LA;H6#H$3Peh{6cq`sI0!?wM|VXwehd5(163KF`;AR)5+fkYQvMp9Ya`WT062q3qkKwhW;^5kw7 zIq~ibC^Zj61^xbF`^owFsF_Ka7x*#Y|9HSz(O9J*!i&#@^?^BE1LCSQ($+!M6VHG} zQBfCU89vhpRY;i~1@O$;)Os^!CMS`qE=<4v%}wczl;VXlJJlekGfD@4!2jF@IDU)) z0tr&7=H;=JAVH82X@6%Tm~%la?P0AnU*CIZb;$%M*t{jgStp=&OFh5}OI?jFyx`+t zpzfn(&$B!rO)-NdZVLggVARf}?BwihJ%DzLKDNd5PzMVc7w|H!na_b&fOHPr_|8}A z2T)*be^FZ6v*Ba3U_6$T2p{Nwx@r~>9@u{r6-aBC*~bGilA3wBow5&2IQ<7 zi0&de-bm*WD8%IGvgi*TXEb-FZf`FD33kj#b4vw^4#2XDY+z*Lv$D9LjUg1E@BeD= z=->bq{E&ge$Yh4e_MT(4r;^`jot>Qvc5z!v%~Bj=5XcDOx734W2!zrlI>5Z4ICriZ zfW9Dx5Mf7~(&ab~U0^dHhZ6P-X^vJr_R=PF@Mfn>5Qrqnb+G{3aNu-n3={Fql z78`6!moht`o&@LBt5?l?o14+#=<0(C*y$r+7s_zW$>>u02ASVmohke zd7}M)asmGLjpE-Yg9!Yq4F8wPkT-7F7t%Smhsn#Tfwhxmw=fKy^H?ClCa$O$f!tE)JxK>W(ZKbDCXm&@_V$CU0i;f^ROwv>4G}CkBqb~y+LS@=z$0LN1%da4 zct;z+jfg^ARL6lW4Is<}A{?$SihJ?$;(}aEWO-RKz(x=QSI#%n0-z@nnv0@Fii z3YVclx@S`5C@$S!D@O>e-=T5>)TzCPhVp5;;Jxxgfj!+37(tk<(=aJ%6|^zO0K@>9 zHvWK!#6zVxNS$m1#)>6yi2-q7gGi=*KNNq39ZE24r{$lLO3VybXiogz9RqMxcft zG*cc0xQ8^u+R91?W&pWm7-0W%3JGm{&X)iab^E6nss?6cD#_5q!$X$Or-sCf?vj171K4 z1@s|YmS%~^?fqse0QR6^a4;GWp?Guivdo7mW6*b`{rcbE2O%`{DBu?D*B{FR6f+Kl z5+y62%cQRNU{+9*s~TQk6|S@6($C?nA+-~r zw#n(~T8Ixh-8c|!2=7EtK`1a<4=#9`Im`u6704*zhsFiqf+P6B10bG5qAgN*V=DlU zI{@BL!pPOXLtiQya77oL2uY)D5Kl)KUR!XQ!Wdtn;KDHO@bCNEq#5?eTkelHTgo3gmN9fq454$dbbIGynpe8S} ztpF4vAnoY9CW~fD8NjG8bn^El+ZSr07OST3mci z;zS2HPHlq7N)lvrqa-YVeyb0m;thaB1EAc-#KwZJYdDDu)_rnrt^t+*#Wb<2fwl0yUZ$a$AL4toNx8^<)tlne(>2OBGmto?XzzbJ;j zqF%^Ng4#BN42pMBwzk&&dfryCU{F7JT$0-*QA3C;Ceh}M!Qy@fpXf4tnJ5VS=CX#9S_a#CB}goLjU z;2l{G=jY_`0I$3OBA*;oJ?-s*kRgP$yxMIl*bBR;CH)J#{Quo1T8FruaP?ea>F)aU zjBrtxj{m!QvZIG@;h(ySU-15~AQsetglt0Vm$!^gP5*dp`|Qpc^Tf8~d#bO=se1&< zTPr-fqh6DnsEj=+2tG+#O?LX|HH_yBo1^f=TGhrW@k2*3=%xBaJE-!h-?$MzzvgVi z$v^t3ap#u^pZNo%D*q!!_XmvkM?~-WAE4hK@xMPH!h?SV{QiA39$xgn3l4IK|F4*V zSM=}Ug6sTWl>+DC_`ix2EWCfO4?H}#e=kiq5C4C$Qj8K;@HpBa6DM3gn4 z&%`#h)sLG+X{7Z3={;kRRtP$jm1va-7p{x7TY?;qIh z)s$!KbHz&y0LF|1J;xNGq_oHgvcV)wfIgcW4&=?E)ExkSLZG>pnoXB3^i&szcAW@~ z2C_c{A)}-|KuIGcK0cnCmv+&VV!PlO{J8T+;r4aFFxy$rKYMLT*EzK}PSs!<|9 zaNbG|>WTz-dV1cA5a1CzZ~Xvr{tJ6HcX9K(4G0MboU-xp@o=**#}LmI(q0r;0yym# zN1<)_1tKCMLEnM?eq8ZH#sd~X4p~>CJ421XJkMW~E9Z*b$qI03IGvdDdEL>VtZPFX zXeQut19JkI06O*o3*u}7q&Dzu2QVcrNJEIwgyNV9rKKW>Qw-H^ikF~u0B*asY+H(w zifYLdV*C7!B|x19l!6I(Hkg@*O(T*u1u<&z#j zZ2uk5qyZ>sbD+jM#}y#Sh+u?q@(VNs<@rl9jjUmzp-&+Z^DRY`(!r}5!aMe3K+VZD z=?jHVPy69LzW0D7032Lq31|ybTy=nl2T&n+Mv1_87gAT~dX0>io}M1YA~;VA&<~(H zwyFcYz2ShR zU|4#$1#1RsLV+90yfQsLK}L-ea?VL48^;_>hZ z2^DulU7qDz5K~Z4fL?1^f3w;2A(f5-7%h-8wiwS>VwkrA`Ha<&ZdAN94Y_9tz+Hmg zniBGT3))b@2FikkTQy6-!(oXw=4{KtpyUu6;3LbbwU=I6 z6odoOTL(Blz=OM+R&~JbngV;!(zNET03zG4(cARYZssxaNu!XFg&=LjLf9Mg=6G*e z$1L~}RdK*l&bHhhStsZW7r09(vph>#AJh zU@aLZPYkH-y!j1j5auzrL&Tja+A}cyqz5&?Ug<{8PytjUvFtWX7!yNn-iNYQ?-gW) zc~~E&R_|^%?vApV+DpMgSpw{Vw0*6CDjku4$c+mQY{(#*1!|1z0S6CCGAfkr%$h>; zpau+701O7^3&<28lruJS3AX1Yl4*bP@bbo|r<(+AeF%hc!5=8iD6gb6fs(^J#|Jyl z8XyU6q1F(Yz0V$0Qgz^}$wu*Mw}q*$d2<{aLAl-Vk|f^u6p#UsQU;Li*4{_k!r22~ zX(cS0C78#2aX)>3frJR42NG%t&5XyP=3X7bK!k=7*E5`FjiBXb2(+H7SI#w7PR}2H z{l0dL8u*3wjgI~Pxw*N(tQ)J<#92VGuP~?_zzG}~b@V8Zed@P>Z$nuoxkt6R>CY%F zhykL9C}*V87y^?bas?n=XJ;^9$)q$t^v&P`ZNh+oM8`!ylCDBS=lf7j8oGvXK^iTz z(~B!8;2(f5=M)eqtX+WOB}NOGdme%p+2KOw${-;nB?bFyQ{)N_ibAexePLgN9!+sT ziOS1~lfRs$-{{h%x0eERj@3GcX7Bg7P5eRS`CoV%sUO<^!|4T+{1l-Nq26O1I_Ub+ z)mn5}c3H@8sA-7Mhd5sU6SH%rbJw*@`pTF}3d-{}%ej;MhI119Pr6TC4v@^Dp>;Fg zYs!}AD}u_pE)d*b(Jz#{^I52QMVxoVq^AA6YF2@(W$yAbOdyV}t61A|({ock{k?+Z zW%@Bc!XPh&qzCd6jAN4a6JwKGlv9+=-JPK+{dS7%LaSd?${yf-zqXfZ?C~)DeU|fM zN8VMFx{*HL3BH{&iM1QHxg;jC@K>Q%WI>6und8dpW7`$Z9}yoGe>7+Z$V*B#7Dn`$ zGGmZA47<@ccmD`&|K4tuZ510+K>tkonW3S9gtof&T%Vn(iH3`1sl$MhWyLk}&YeSU zLEd|~QEs=AW6?b7Miv|AgC^oN2j2TFiX%go>v&fvuRbMdoy5^LU#zZ_ET!JZwI*#G z8Z1%oZ{yO(|Cvkdp5VnSriPjWX#_LH_rk8GIrIszky0}0xq332GaCU}`%7h)}X zsE3JXFFuW*1|x~z;Me^{*7*D&04k;lT)sE*i88GpO@Sv z&^ZInqeTUleGwbJWV?R!#Mdt>m90#LUtjzBUNTO_H}8!t^@@+0Eq&BLaQ8Y;B zNy}Fi-^1nCmxmYc{O7CiI>qLC>@@pbYqu=xIWjQW$672f3qhm#%2j0S+v4aEz4Jkp z3Fjjf)l(MBzY`!TedPV#mHu)LWKMr>`yTJAaUFr|_T$opRnyU#0e(R?BDNfwS$>{2 zzOmw%#@Z2K--#+Cm++<gp=!ze+}U` zs!&$WG?bWg9`0B1Jyd?3VGkoN`s9(jM>3O*;QEx53A0s6tFmwE4(+yBO=)Oo$EDeu zjkr&qpGsR1$9v1Q_i0Z*%1cB#aVnPxTn_TLmQ9mddu*$h*Vynjmm-H|{!R)<+r%J- zKwqP(7&%_XvjZw{#h=sP3+lCg)%Il!(u{PPQos~iV`|b;ngv^fJhINlKVWHdC=Sw* zUy7v`82gbruMw4gUL9^)H}kuDc>U!f9WDN9_PQ1$-fbCMTmDfTni1*!{a3bFm=edBmo>FaUA9|C%YPm@PWb5fd7&0!u{Yh~-&$TOSGK^Hu$ zG2L|Ww}?|i#x1sY+%pPNK}?z(lAKz%7B?E1#m)!3<+jrQH2Dhdnqr5|rW~3DMx&<& zHQ^GL&GG~2oSt^Qs%oEKLU(b`%0G@udVr=k=?nayTmTN|%RnnG`1x^keZ;@8PzSz| zknfp9?)gy9CW#!HB}Ue`_YJuXb;eO4AcxJUR?YoGu4vn7#5SMXDuqN->cA~nxMb>wM)4xhZAJw*P`D3ZF%k|G59kx53Ju^bf;xdNDx`- z^o%6x>MrBya(eJEqgQssH+M3mO@uY2=wX6uX9F$X+w*%>9!H8KqjC{%!EA193Tsk^ zEHP?3q)Mzdrt3$^g`Ok1an6H@R?qrTBfgi}6q>u*L+W?JmRiddl49kN*)Z>2=;GAE zLbOqaG|-So=ZgHBn$&6MX=WNo`(%-WKHv=NwVe z1NfG=M8AzH?7Sd)I$a94qUmqgf>zE#%Nus^sM;7~kOMjB(H}&5A-1-*ahkKj|w7@-(lVU^Lkrg>cX|rHz1u}z%=<&95*+Q z&MRRvH12ht4a7|~&@LrV2bLAvJ<)5p2PNy*xO_b((^^{kdn0pX0roy8xc6Ls?=`Pt zTpDK#QbTVK5@0CwXG%xJ&~R^#e@>vOg*%PkxO>a-<0i!25Q_wx$RO3y0i zIY+D?a=X?dH@zofehzh4%wPU8|7z!`K1zy7+5wkSB3hzc>|~zqI9OND$H3|mX!snOV{Yc|{{JG+EB|%*++O3WJ65LyR z1y_TLM#iLsX9Mfy@4CAdn=!x9VMAgw5vr--&+6)+tC!PQqd&0TRlNIkO6o=kX1{ARpR=8E4hJ=yfzQgoInvS5-GF*zL%V|+6;cFWEw3{5?}k;}i%j#;suPkTWVI%oQSb79V@bwWz`o z1^bT^uYO&{!>XmhU9(x>p4up@vM>&8wsRG|Qgbr57;wf^i)WgsFLr8w^F<-o7u@H) zIk|;O4L&q4IBNm|Dp;#H46OTv2&n7vc{(w6|>Gxzilf zjs|H}&U>a#(}yz<=n=47nN*r+^x4VE=E)JBw`aO19_f@xi56OxgJzIzJzmu4y6^%L zO)QPT)6M%K%|eW8D0^3$d3zz4d#eKj-m2x^NxP)@`Hl8F`pddxQtCL3v0{|<87CrD zON5?fbB2zE1x*a^I+_QXYDB_xTfoN4Yj8DUcbL7yKZ50I?)|Z?+GyKnjmgx-;FB{b zsrl6fFVty=@iMCBF^N(8wRV&da@cU>@aBvMhg6L!g}DR>w)gujX;^9?mp*E*5j>bz zxQiRjtc9Eg^a+l88f%5IA1+MN&NaSfW6jjo5j!GwWJzb~8L^nqtn|GMG9WE#lUgEhiq%)3W)F zOW8VK1`Bh1c_Tp|6f&Z1f+?y-tt~Z!LT0(v*25dgEg{F=_E1ualu7;v$~bNwM*XOr zU0Xa5F~A-?JtGSkFxiF@sy#G~OY-M=XFt^$M)`XSQ)Oiu>1yqR zS#blA$bWTplw)@>1WPXwXsR3;pw4P3UUgx^Yj=qRvA!)uExRdus4*v#?K`+ai?8j4rtPU;_K-do5KS= zcfJD^0=jNaO(l1%tVmc|S}ZrUrHS@0_~>jdU!!tts(52DBFZ<8W1esHC@`z@IZ@8) zyVurLhsKpVJD9=8oVt>nhVq#PP3cB80TwR#n_ia_!n4kX^Q?+KV8JNJGVX3fVaQA0 z32mD-cRunKn40!KMk>FXEXvtyZk?Tu!qxGigbIs<}7ci;H6585Kj3LXZ2?3IgmUSQ#o!Tiu`aOj_1zU4E3&W#6 zf*||68yk)OvQ8KI=kjBd41G1fYqb#9F1Jr2Hj`0q8s>%JiPiN-c*U7}W7Oj4nNGi6 zGttF@Mn&7*>$r8Dk?#{4Maz6rEvVk8mhp(dW8S3SP5!dr-}uIXCUH(IBb^GWS-kb6ht`PGmAwPufdALXV}y1+RKQV(>RH3F?Dyw(j?P;Ghj z4WBUk-cBMpc4idL++s2g(;SESM$Qau6zdM(iDRfpn-OnJ(Le-H@n|B89!ScF@NaCD z$+8z-vR@w>ZHbbhaWEhud1PJlJV9q`aP`VSrc;IwxQtX|h!aUjFz`3TWnvH?ZrHBcPmnW#gxqzptwh|IDX>%~tu#A$%MZ)b~Vo zH*^dPNc1lSpbIQh7C=2esPt`gVw#-ot31TSeBMsp!OJ1bV!DRVdv5YEUUBnpo1&?S zT%CSmOs?Bi9K}uF#qAlU^D=0Q)??IUObX%(TfT$FCsSeoa}T&yZ$!R^=sy(n)5LLt zxmyyh-<~?^JTC=+oXc{|lnI@q0q*@qNE0u;QItxUSd@bm2f?Ai0LeW@%MB)(d${Q` z#K;AR%%j6(ZXo>Gp`Pac*2scc%eA?$V-^-$vlz|Y6|SKw#vsrcWwDi3Rt)5t;ZP;a z_G;3DRg=`Zh%hx5d+RO#MpqG7YGHwUstT%zFV}9Y>K|98To@#J04vG3=MJ{RXASbN zsF<1sJ2=KyX3C{jHrQmQD|oJAj#^{|+q#qcjRP8}0x0)1=d*+LB1V?Ub%DI?v@VI7 z+0B(CaDP%B&Tc%CK+9iN&cC|hk4kcJPtU(dao!o@1?mwqxg?9&;Tvu7nz{y72EV2) zzGvFl zwSdmfhNj>OB^sqpz9d;GQXJCbbrLSyBclz1nu{$|Q`_GoM`MgDYtqQ8A#soR}aOubBGW5P9kZoR4fArT5- zHl3RHK`yDgVUPiDaErmqh1QBEb2LXlpvRiy*9IN&Tul5 zx+bp6r0byY7+U@(`V6H3`{Cj1HFq=Fv;-|CLKq=-N7NW0w?RZ+5b#I&1G&qr+J3Wuu9mD3|%e;kunxcpk1zjO%A zpta=n`%s$Er;gubIQ`zV*Os<;vkhD2N=U^w?sB(7oV?1*Co9vKF$dE<$)}TL_VXk# za4;*J-h#9d!;^`Y?}#$m5~+aI2BsXrgOCO3K64(3X3uB-S2}?xuv2yWTff-{D6Vs^BT#cje}97^VBo3Blifx zf}X|4CXNoj$x>dQvmI)QB0fkr-9dmVo0OJQQK_!YkCr={oT6oL>C!oVn=5wp_^Jh* z!CN1^9(S-qbEmsKtfT?0WF7cJzLzU$(Xk<)H$?Yt1e(FnuU2p9bJb%j?xPN=8bnI! zWG@-?PH(%>ZJRIG-OuGVwjaWZ@t*Ma$G*`#Tu;L{K+SNqe@kQC%hip_G(2mtO1Z7g zY&PeUEeEyGbt$jFz%Qx;l*NI}k!}y3{{8fTR&!%)a6LSof@}N2Z*qXn{!2IO=KXKp zd|y^NDyzkD`f>5{*=spm+#+A&H>J;1y^eCWusAIf`OOiiuQ*Cdnq_9deOyW77!_~%>a5xF&$qcsjLC@{NePyp{F^XM z%ICz<+3#;pIO6?23Wj<$Cel&1FIqomJTv$ou2R0-=uLw{*Vsl^v5610Y>*2 zBKdu6vG@j$@o>2L4@FeO)NUQ6XZx2T>DJ92s#0xt>>gk1BQSL!1^Vd*0Uc)-Vbu}e z&+}hpGz4+$UbW*;ccmC>~=on=iR3 zqdlwg*X`p%+3`m-Ryo((^9C`@Lp&K6erf-|m=al&=+C|~AFVr;Uauy_J(E_9j_qA1 z|5J#bWAwDmYZG=)z5#+`Vm z?F&K+x8EgW7FIffS`}zGCa~pN&0SW{-Nn&?r$JZzuAxrU39sESH9ffv^DQilE~d7b zv9p2Hf*7x2_{;jt~ATIrbC~=+?eC;tQvnP50yV29!6dKFWLheOgCZl;FTNg-c4dR;i{%MS96ujZOLd zHI4Nu*O#_sMdgS1o*k#W;j)?)eTVUEt)Z%Pre~%d1+$k7I`rPnkLCPuWIgvESsjB* z1}mV-mC6L{QVS?Fa2D4s7>+tStrgv5AM$bKYpCTabCY#C2nR)}ghgCL&DHtcxmS^{ ztdo)cvSt%&15(_@K6#qfTtsi^)(_lF!qoFs`npnQ$M;$($PN1CwWYZ8?KFvL?Sf}D z6`mV#Hb6cg@!;UkkQnawY(8sBXzn#aSMlGskd01J5zFU#h*<{II39+Bdx}71mOU~>mgZ0W-7tKxUTpcb+B(GTM zAeir4oxLd@pOfQOIc(lp%rEZWYpV%+CwJ+#wjup1gBKw9ow*j~B~|Fy0@BF&1AlBG zcgd?)bXY&k4QFBFJ_p>Ax3`=;luN``b41%uom3LWPJA+@-ENpKr`>77cc;Zeb*>#M z&0BLUHvU$-UN2n+?}jFAuj}p=>UDI`4a3X5j`MGGdEWCL9`Y>} z&AR%M!7yq6$-@)E;yL{kHCyZB*xnA|!fN79Y=1Y!bJx!||4G$4Ur1|Gc)9bDf@MXP zAc5e<*PW>7OY&a{GH`ThiXN>`)C&98MBt`qYEr&FlbrG*IiQNh9fyNH%7OUxw9j^) z{Wp)bdNn=oW$JXuWn25NDos0S7P7;lG%lBFS(De6RAV%mtyUDV6(qMrEAbl}bhw=6 zo;No24>a^}I0}~K;yR9cotwE24kFgyS24C3TNicjj9}AkE2K0I4w0AYa{Jd~ znMrn!4fL)^*SxM--=-3gy%-u?sl-`!`WT4x>(|QHubg=SVryqQUxu1^MifVMb3JAN z>&0-{_8&|=a^9jZ@U1B;R31tsaRQ z9>P3Arz@xv`jRM6mX#B*NHkk^{;6fHUe)Mnb+ALR#r*Nm=&$sr3#vV>C;=4vkb1>n z=TXk_qm&}wKo|n2mdgN(D0WDQJy};>!VPI zQ!A9naqWvQn47%iJ^e?@ALzZ_BJQj5XO3c!3gjBm|4BQoufHbaLqao=K0P<=ZPb5# zjbr@ueU;-z9bbkjZ=Q@zPcN@bFQv>i^#W__dvB;hC~N33uP@Y7f?vmV!%mz-Mse;> zQ?u~4$1SrqMY9fdY&_ph2@E$?Db6}L*bOf1cqTj=)W-FwouJ0dk*~y=I+uNe6habX zvlHLD+P0OA#Iu@Qq>yUZc~fxv{rki7lfrA|3nSRfATql_Bh3>e!iNQI4$nIh!zf<8 zyqLX`LuO|#(JZgE{)e$Jd7A7E{?JP{Rl3t5dJC^evA(-UzkS1&uHC%!b+V~tJBoRi zM6k$q(ND?cWk+_g=WT|Y7X#^NUbQ^vzpXBDp^f~6tob$L-lLj3EO03bL{vIDUIWYK zU4#Abv1%PU>PQpr$cqTIWB6%kCBv)z zAs&su>dCe9g}y;-t`ucknFDc29}P{sH1J-(e%zK!ceuHq*xg-DQL+5Fk|xos+wU0o z?N2{U4gU4OA-PWE4CuFro%rMQEq|PzJZ6D!+k0SVr{zk6-jEmSWm8l13O%(R3)i=~ zxjt%&>tCKJ4cygM9(lvLc1uq6M2eEAsw(mPtkvmP(UEaww5#)thEkUHTz+ydb4zm% zaW2G#tA!aI8&?j~`c0iQ zGcpCdfYbcp!-4+AvqxoZt0oSS+_2??%jw7M1L4#Hn3jY{z3I%fRw`p{_SxGb&&wzRgi*et^^uv7T|LD=}s@DRH& z{z(5u12ykV9~A>ddJ(atB;Gk{+R+7n->l@PWGTrHPZ8VK{w(9=KPG5Xo>vxOsa)kj zMuuMz7V;96tm5t&$c5NJElV5)e{M%?0R?Vi_ob}M=|GMsy@jubXS(2;FQ3*Rz%bxd zl2*>lbYZ4y+ETA*@~??<++bt-^pq?+uky1tKFwL*%JKRiZ2^|++Rs*0nnSX|n30#+ zFIu-=zZvSA_v|tCk~0YX#w>ee$oKo*{B4WB?qbkm;9(0K5im$H(6XPjI);u*%0Jhh zK~f`6)ZH7$?Ye7zfYL_#5Wna3lbK!TU_q`Ma#gz4Gg`; z*bLKdHrCpQ@@Lqe*gXku(N6fKlsor}z+o%fN-vSadHu)T-T95Hbp|`HU3WT{Yy5ob zDIRzgWdbF^|O-+T}b#fFVi+R>qsO+3AdgWnh>-bC!P zK<(RmPN23Z2nox#21s7rCJt)|N8BDBqv!&PTNm(rh^fccf0zdbu_YuG8=4Sk4qiN! zzhkq$81x}7uDr6r6Xiqe)so6i=6xl4o5Xf)kTPTsSJZ!j?@ z^kwFDkAv8m>=V2Cn0rUMd$a~b?COo8)7h(}35X99ks5V?eN>QOV>8b{A)Oijw7!?9 zq&l|6Y$C#Jsosop;IxnUVNmVe-E{R(Hf}bsJ^7)$;XiADP%(G+o6p4<4yxweGBhL( zi;o{vDm%`?+MeeAXr@=e(P0(FuB=$_v_Vh9_@W-(aqD*ki53^!YFZcN8?RbChOV0pt)CQq(_u&t6$a5ZV*(Ac1({4$kkI9^9r8(Vn zn2n6hl5hFqa!BJ17W}o|LlF`7G>g61s_N?O+G(k&%RXdW*RP3dCUZ2tkwga`+~=b$ zU83=tPIn*JbCJA@sIZq}u2GJ7BR`mE=7uj|4N0{`8k82q2lnf#nQRwHDQt4~5m zBC4Qp63_lSu7Bs`i!t5W%WNzWJI~1rz^W(}=`5qo>=Gir#6j|fRzcw=9)o|u&qcFK z_u!UxA8|*N8oBPDO29BORvx>OQ5m&Ek)7B0cmysO!^>*s__r@k(70^2wt%I@o`T7_ zb-OXg+UVrwb&JEEo{QJ%sEH5q2Lya_*WN4-9}5sIJ`#% zr;}6MZ2~91&<-7~52z>fCg}nTqcHKO6A9gKHzgQg5d!!GBwqyk53sTEn^4kvfz{Ia z$$Z3Kc6Pc?e@X1X)2D+iQJ%LCN=hyYjT*0OubEWquorSu9|v>i>)<+F!d+QEMybE# zBFSO=dc1#nb@l$UJr_Q-fNlmOZH(h zgi(*poZjhhODNoF=_M>ayu4DuS9WZz|Ae--J++($%}a}07di`;K1zwc1k_F6sPf@z zWVcjRh|jhsjNW1Y>faO~0=qFF;O08LzOM-7OH{5g|NIaDI`NzeYWHpN{mgW1ywq=j zFRu{wVt31RXn9hIM7iiJ+(w_P;?-6BQ?+_tKbx8DlX7$wgl5W!xSr+Oe=;6hoNmwX zQYt>!o>ptFAV4H&bAx-c7+duLCwecQx$9A$`6@i7ruIV|K4?BJ{a<@AvQU*!rcoT8 zLY1MXWAU<2xQHTz8ng5f6#Nx|fkS`#*LPkW?seu{UOn>MJ>1F~Kk4P-BHd#wwbv%e zwU7`U?UEtiTknJ5ocyRk+pcTZhth2?jQY2*d%vX5ewde;`;^T$!tO2HRB(3cm%hM5 zYCtLe=EKL@%PZmssq?xM71>mLJ#5^2?&XQd5xId2$Z9FOj?EAkd<`dZ4ZjYC=DYfF z^Xg>9iV4eQ1DRuJGF{e3npu$vj!}AMPFHsx|>~_;@<}Tn#B|BVK6xC z)#T9G`!8FEQ@UB$4p$UY%mkC<&Ll#9efV<7S7(2~fCfY;r206BmLs zXxpqz@sr77N#% z`>~1TfRenCuq!3_Gd^$}E~b9RA>5W$pFsXfI|Yr|`c*&<+taWa-NHT*_VF7r4cIDU zerJJ8v*&0UmfWnT=_rZ1Rla|ZSJzOI7rRqDtcFBB8uu$&V(EK_rD?rLDhGDX6B2(B z6FJz{#wCsR(2}lhXH;KuiLl?BQe{>xi8EHJ>3Nqcy)m`b?P4xb3Km+n9FvgS! zNJNf?+>7)w?mGPv1@%~M3>81VPQFbR;~x`#PQY&hAFlU+ebyGg)gay(^2*m_au3fs zdFVS3=-cvz3*ZwG-Ml!&FF+tTNinIVu*3AkuXBc|^y{-uyp@$t+G0NrqJz>@Es0%k zSKg)9GovTliZ; z{<~45WkekX&ybU!!~LA|#JPZ7vh;-(cG)U?^0DrQBv{tRJZ^cAq*>-ZbI&U~9~!zS zL`UuEO{JxC7{X^Z_JHn#2`L;SY_9`XX z?evAP`pmUf4V+%bz^5b^QqxCEM_#{qeS-E;qvi4?r;S=Ug+oxnqv`<6VaV5qxLT*d z!&alZYuvY?qG6i=Zd%Fxc7h+6|9wRl0$2v$;aq-By%^Wy#2hYiv{~}dba}q!G%p-Z z$^VTgsIMHLqhqH+a|%{ctptv`I*m|W<%dTZwcijT78b71w?9R;aQyYfJA^(Y=uno? zpu3>x_km2I^sdWdW_{M!@}aakI2h$cVWZ$nfM z(!H#ddl)!zpv(9q?&svt4T;xf^V`QT251t^C9Trkx%nlJ>9QN@5`C!+sY@QWu;Y9L zvusce%KQfRafq%ftka)4em^3WiTXGdKm-w0`ws{O1T$IqXCtN0!}I(iL#hq2godQ0E>uC!@SE}d6P z`&p+bzeiULaNte*GrRK!y-Ac1A;q0T5C@0A{aVQ)cOxd2q4Ci7@8Hxr)P5mk7_v^$ z5VO3ql-iIunWjOM^6;kNWkQlhGfRfk)bC_Om6Wg{8ea>rUI>mn@mIqd-tVK7c+=GS zK&}@mY(HKfSvN2Ar`Q}()=;#?|7>RbaH4hj$+h*>Jit_sy48taITfeP@VT^kn!ob_e1r)mVKAS#i8odhNNDo4}Bm^ zN(ziKhy>$Y9+hstkTQDx>kFgyf8ohD6$vQy!3*^CX2XZidn+v8{_r{5&+L*A)yQQM zQc@6SF@GtEV-WaLkcGH7EMhx?)jH7ZZc6<=-}>kGj>sp`U3nK|MJXVNIk=;HjmiHG z%!SCc&Oeve;OPqz*Xx&bLj2HZ{V>$#CVOFaVScC?f&)%E;Z}lvKjxu_`uY$a1DLV) zG_cx^f(mgG-&1On*bpt+IQ6zh-P|18)`rh4Gy1upfZ_&M2tLO9671UT&2s+^_ZeMdi?<&ZKDn)C#zxyXD^X3gw^u&Kebu= zv6ac_m6$Oum;=M0W=TXXc=oVkW)}qws3y4fEOc~6U(^maT_0Pp$kgE%wkeE;ki;9W z{hMXBio-QG3y}nezF4(6GWGOe8n2K1Yywn(=Npd>rWw^AwOfvky~FqqcKzMT%8Iq(Fq99CN77}75knsj&qTI# zMw)Be*P|fCvOr(bo zKYh9=6rDzN`qrTmR-3~^B$?q7>ctmsgIe0J#}6r~opKsWOY_Fqy|0)$%`!~(o-Clg z+qh<+91nu(Kbj5zs%>q})#=2${n^#^Bre}AbeIwWizbdW{)76MZ28fKPfBV}^P~Oy z?JISYH5XY?tB2D9pQ^gh83jr{mPcgNxY z4<>q}5;>+<_Blb82!y4Na{v5Uh<9yGRFhWw{&fwZJ7AMy3@qC9TkGz`d~y+PZ7mli zxhWv*UazQl(?Q3Hy1R!XKNU_tA;qS`jt9vV36(SZz3S&fLxYaW$~0k7$Bw-1P-+RI zh)+#?t5b)qiW^?61w5U`$;`8!*6%1cpD3q&lVtFe4i5+tR}z;83G09Jjap!a6S`7g z$MZW%%1SjUyP|NGBj)-;p=mA_RLVmzLI5*kq~XeR-~kggU7cJ_-aqxgW8M zk=k=$OBe_!(Vxvd!<5pFhoYbZMwceql@ab|1+_{Dk$rge;l%`;DW`w%_&$Sr3I&{y z`1C6wVvq$Y;%l99cg7!kW`5*6-Q+~vtOnUfjouJxzJKZ^3g{`{UX!am1PH%=ZknRRWkOl!oN*WZUyHOe`Nol0J zk?u>U64G%==}XrI{`4;pgxIXP>jzUTdzo=0qG(f9I@DQF1@9D}Zub zvTCaDPqonyp*LL?(G?742bJ3CY5|*DzM$7HaS$RVP-cMllX+*xsr?au-`frvLPQ|> zE0~zi|7NBXA-Z?ZeCOP**R;1-OJ%uxBWo!S5fi6TECV<4t;md zt^E-=uTXo?uqa+eS2O>;t;|%#Q2+`J8amX;qM~%EjE#i>8V~b)*YUu2OaWDY4cqy} zQaj=s?t!$^@)YIkI0J&!CO+_2?!*SpbdX7+4{E)A3)n}aQu|sqKj8R+a66WU9Uk-m zz~OsfZD|$YN+}{@_&WeX1%9=_ZX5t~{k?x0D!6-1zp|Wb3Fk&I2mAiIyJ8A*%)RZh(lltdB}oKL z?S;uF*FME16B@r+n-Pw_nCs*$rqLeithVIM~eZAKhJ~pNK+ip(aJcWtDI)bc#&Uj^hh2n3FK>k z<{DLild$wl7n;MF3hhp#mdp885w$Rgo@f~ez&pEQSC#dbMpAUl;51-}90H{ZH1b)H zq5Ywo>Lk(Rmq&{4A9qcSYe69ZC8};pl4N9J0<+`8ZeB7nDA00Y!aq@|YCbR<)IJ&J zRvBNWbv%3R>Fedm1_7Lv7z;<~+>Wh;hR4>7@aoXZ+=7XowM_g7b2gAMJ>G4e|`f*qIp}>*f>9&!0bYG@P1%Rw?1z zTfFE0_|XXRq^u-nKc#guv4Y~;^7=*!^#TWIBq&;m?Z95C{1+_{^bNhP%dx@2&_~PJ~2((Z}#a)Lf<&<0&kLn($e7%LVqrHc7VA( z0U$N`BJ~3Pv+Vhb-cb*oF_bJWq+dAsRn^KGXAo1mKQh`oS`5Bw9*6ngj&lsgAPv9W`;4zDLc zO${Dxh1}qJB#Pmz02!sf9~xZ@fYy|g4K1-nL}*hb_6q?0M>#X_pa9%_bT&LmQoVo( zsC1?{zcDd+_=xwWmE@ndvkkJQ%)1@D7jGMSdNRs5^KrGClhS0}EpN1FOPdHX)r6ec z&e1=7aG0AKz1zo-B0_9gTqJt-l9?zow+=kIey}B3T46mv4P(#)a3d`yy@2-WIxzMe z*&z7yX~|=aPQzqhO<)V2o< zTxHa`2By35VQx=C(!^~K87yZU_Ye!~RGIYeg=H{TXLMHKNz5)N2mwzHXkSo!Z@72| z;dw40>j5huK#(p2^BouH1us7XpP=E>raylb`LETEe-OIQS zo;2(THCP%Htp*17Z-n*-@ALPOt7{bVgz9Cs6 zcMr7OK7FEv14fw8dF?!CAaDRY@u6b;eO~3Sa?vEAz7QH4w*lRAV7Sx1v_uOOKny)S zQ+8)-HD11yR#Y6Y9Ay6U-KsVmpM;cM>rhjq6W$2%J15s$d$x8u`wvK#b(Zw=&{#h?(#QA=MG0j}8&z~b0`_xmJ|fWUJGf{e^eU*Iu$`}Q9^8+KvIOMEb?W4m1f`l9!7 zH_BO3fls=LNxA)_d6Q<)L3{uC!@8&bPy}f7?C_iqyMV_&te{|sXifZ_rFa=62B^Pk zQTc|T`BBlw4Jesal64FgPnm__ckbf`0U_S(s;U^^p6d_^ti~sRSjbTKqd(qx`DhY< zlODsXQ`+;WswjMbTV&Gbm*l)XmhZ^m0`X5cS);0`NetZwprt*LkZ~euhkA|L?0bL> z-y`X*|DJ&)LJhyn5OnY>3M%R!=tWo45>eg&SL!7{8aOS`&jn*HpIyaNL{d?gt`=`4 zY`nI0v8dJmd<+&DWDh=tU;zBLJvSqR7OrN17jjSBOZ@4P?C5%A06mFc9BW1c`RP8M zH{RpN_EW9^#$N3MZ{m;?^Svj0lsPKK1V2C+UI8gxKrmM;Z9dg$ zxtiZU1ZNhI#Cg1@!5iDrjVXzrz_!)y9;P;My zMFk~Dyk13z?jSVNT5l#+&@DBnKiGN?;(!#Z6O*u?&K;^%K%pM$%mS8MO>L@y{9PZm1YnORvM#$nzh@bU2hsxn@s z5d^iNu~9y63ZtBt;Jn{1uiXArhv@v zmfX&Yorw4+=!b&_PidX?@cQ^%Vv=tNh8&}Vr4L9QU5|fm2>Nsa;zI>uY@#}rnDWMT zTX(Vl{9FiW-}|hw9)36g6q$0qe~$z5T)t?r9H35v5#v6SL2-0!lf31H!#7|7oNYz= z{ELKtF2_2+o`9(z%;pA%Phi+^1w7;ikxSmJ6moIU0t${JX5FyV90~`gIHxzhW?3Mp z1wMbapK=s{|D1jR9~hrz^Ox%E;0AT`(<20+qBGhNU^#5c;|U!6%z;56(#w}G!9d0& zLMbZb*Dp=uim763mN$>VutFA1K;s_f-CrU1;A;jQL6X>!lDO%YM3mwpiyHs@B^mCX zocx%%yq#{`=PKyG+F#ih9ve9AuWWSG(t1+JOrOa}zLTj&I6gH%tZ019eG{EPw!+DM znJ<6*lgxyTJ3ir^Qh7!Qks6yEr|)s4rA^h?h}(_OT>=#6Y0N7(w;}#2-ZQUZm&pln zQ4gOz8&=Y5Uyd+zZkBqHKZ z11Q_ScGJ$ghG~9ES08;Q!H=RYdjrLTaKT)~fT)w9HVG1L5VCC1rAElHXF=?|v(=_L zXl4V#?jjsj-}?axM|BSoNe5ssK6u;KxZhFcjS?O{uUi}Z*X0XE)b-Dh9@qqsYwF7g2}qm#N>^P=-R&#NLx^R>&7N?WOO zm8%2^hlj1ZvbC@ai|BX>eV9;^pp?+4r@S`WW}LPo1OgVDcXq^xOl z8B8+EE6G#&-snl`RXy*^{?O$1C{;!1REtc~dt^%3VTZQ&M@Fha>tC-yuw(1G`MdX( zjgr+OaQyHYXk;H!o!VY_^FC_QG>+U=W>EajU(oMgDX75dXKSR6xYXH#N{~ z?|_$iBx}t<%%?$9!ZeUBqozYaQZ66K<0+(+WV#`&!%pVEZ0sSpMa=5FFShHjhvCzy zaWKrH1)g)0AEu8d{GbQ8T%zd#S4CIn634}$WSf@6Wb1~I%$nkFq?=N?7^-4ML6V*l zpvNwB*n3JNC{EQK5g;i+_NeJS(}A049jp_x=|nUmv!mq&UQk9(SBtG6b|XMYmhG-; zKbqQ)T$lD3GAVgVh$=^?;`pIP#m5J3{LZo?3%pJ#nxE$Q`{peC-VtqWwQYYtJ9iS% z6}AIq6UeMAM|G*jU$p~s5Vwbqk^NVedR z&fS(2VB8$hxbE^Fl5#@xC_bF)(+4_yh;EC)04+VblK|Qviy6Uz83*ivN*mlDuREle zyY*(KQ)Rnz7)6@XPx12zAuC27XTzaK)9v^3#`Z9ylRxBr%v1K$Q2j3HEF`i#!1&iT zroVke9x$WhaiK~3qdR0`;!9#*w<$k+2+8yH@SSRroFg|eF4NwpN|b!)qoYe%krNAX!IGgh2IRt781NkcA%h6Gs{>}R#^2V{A!dI}_#g0BEn$=Iy@~-O- z>W)+Z!Il!25*KarNyFGvv4p<<_&b*2rzT4n$jn#IeZrz!zQmasWM5o6qjzprOR6YV z`OySc>^mgorfOa6@D`(By>r{;_xv!qT#ygI@EYsyJ=!EY+jt7IxkU(yU;6XC2u6oM4k~{iT<*vLa55BBKk~R~OOpT8+P2X!r}` zVgj+J32)9lA8x*ZMp6xl2Iq}mJd@6@70HM701Je ztNf!?Qva)q>IR-hswCKqMPM@qQ*N;hwCJm-2GPKgC~kKx!3$b>{T0ns9KOsS*>ZPA#S>aj(85COVg!j52@*9iWgTh*KB=!1jMESv z`ip$m-1J;qTXLKcj&Pm3X%V8Won2VEXg=FfF1R{doWIDT`}J*@hMvATp@U|W6>uMJ zFCynpOxln{Ie#)H3$#DOYfrzqCnICKnFCARpR$my-t~cJrP9=IJth-7 zUy}T)$&F1WGT!pWyM7+UbWiX6tQ8uR5zs`{rWYUZq3w{aBY9Snlt*UAKnuD z=s?)ZL&PWh-|v|E`7`%aQv#sO8t~d6;7J>Rd)R%Zf5VSOW2yJyuJxm`X7eDey#}m!jsTk5Dcq31-ypeU z%jvtoPDs!8Q!`^RKQuBY;y}Tzj;Nfv+r$!PKD@ACNWFs2>{Kn^AgFG$Dga$k}|)=OQ#UpNcm( z{EcK%GPE5H4AvSgOM_r=J~KH(1V=&-*a_G5rJJ{oed3V$1@~VZWKwe8_ht!msf0d5`1{c_ZH!3hbHGCuyDpDxyOw=^$EoURscn z(EasN*}nrDy5eVxsw!I9S(}5m#Ks2O`~ilH5!$n>@Rgk`4m!?+$%`(9uZcWe3-{go z2+E5!Rr>or-9g^r`?)nCWP9Hc?V#RsTxN^t=05&r&J5L!R*mHYAhWtQ@!DW*GcTQy z61U1>LxtL7hg-8mX9A!9vtw|-g3zrem<6pG2|OCEdPY`K<5{0d);HicYwgz;b0+d+ zRH>#ux0p@nK-zUr7|>I}X(e=FDw;BygN^+8^OB8^-0;-!QthZ_N&%B5`6IgbOz8tKY6Ru{bZVFA0$=E-Aa!S8f%sBN1+ z#;M>$^dqEu;!oiml1@<~>Y9Z|n221wXqO%9W?4h?lRM!H&RXb=L~(1cuhW+Hl4R;4lJ)iVjRr9gRWV%2YnEayqagOZmd5aT{>QAl)xnE+llmWAdXcv1o#01fK8FJr zt)@;V@5NN`yuZ@4&Z@RiwQU^Y+oHi5;f?#(*0=g+cU;=M;TJvWzffR;7t@vPs$SpI zHNBr+v&oIj-y4}SSDghw-iUZX*_;0LCb90pMt9U}Xt58O6kTucZ@5&BqFeLn zWtTuQ*PR;}npOkR$8WQ^KI6|nOd!s-ukT%E5D-t*u*iq94QvQ)oPtpj)fFTMfPcWz zIuKX_;o}A!xHszoZ*9+`4sOI1iEo4V%b*u)vHbiSBz+3kXm@tqU+r#+JpqTIOUh;V1A zNn5f;$fHKzM~zZ+5?>?1AlG_cqA4ox8E!(|^*y~izG<{~Tt0pj1)A8&1DhRYb+#1N zdV$wd0iQOmNTWOkMC_@3QsU{Z-zDAfr|2)HajSSljM+XmNMSvcpw= z=r{`^GgSNz7&xvlLm&a(23)}I1a}!DLd!co1x-!OMl5*d*`iN6!l6vh@uv*XFAuL> za1TYJ@%#edx9+e9Rg+TypNV;G;1vg)>c0B=-t`8L19rX=siCR)901lfi!FL~UBrXQ zf{_5Xba|IL>X4A@CHP~{fmLKZD?+0Gf<-fgCaG5}rad>)J z`(W}dr67$Luf~;fSGAIH0olPz&oW&$;)iMQj+HX^>(G%$D=&X_UmO`2GZYK0Ffy`G zM9~^`gA$Hm(BCUv;r=bW-j+v6(E)2#w`Sklda~}#hFms5r#d$h_#q(aaB=P2ui5wF zps|P#GKsLaU0bYOZn;vqnL1~jRp5cu!_VhhnnmJWQ}vrvIK6Arjf5d&ueb^wZp=Ra z_1+&FQsW`WW5)NwMA~=?x8mPF?jQz{;!;p}_lK;t^(4{bH`d#lz&w7}DGW^0Mf}>S z7jtCJ&Uq?>vNI>2#1#IGRqmA{F$?d+CO@L88v|7xuo6dz%bx=~KUFicN0L|5Bl$%| zCR^hL*i<6b58vNwt7HTIWzrTFEI@evZa_f5U;?+_R|D@vAXx6j0zX&|<>UcY_Mqh< zgk(OL(5~uzNSKtAB&VpDRa_iaS;+$graL33L`8~KHnqWE; z8Q)w+=Q%qp$+<(`Wr~%1b9a!s&mN3W^(?lpF82xPIPw2-|H+)q?vF-O{hLO~e)|Fg z^YgL?iiERx#3SQkt!Ce_9qdt_(Nq6tgPmXRGFF&|X+3_w5$jG#oEdn z&pN`~TMw)NRjZ8yhog4_CXGD|L#un%42>N$J@M27Wi6+ysOC63Kgt6BT6j6t4g05V z^FaNhvdq)R`GRq(OLx#`r+t`39OEe=w2VI0^g!Y| zHViuLFGlw`iB(P;B%Q&>&k@xsrEs*aO>^AYf=A@ejwOh~S+bGlzQ0mYlS-rbY?A*Eis?cH-oZtbm11OUQ`-W=@Xg1AI^Fs!v*LqO8)$2p8 zF}?~Ow#(HsI!Vdfk3A}hEClAh*@+Amj4qNY*#sV5DR!OCdM7T2C8`p}Q*Ijs;zzOb z?a}Xe6ojZ5Q_u+`f)cCTaBVzKQ6cuIw%e=Qu=MVL3 zq=7~|-r%uD!#{_nYOw|ORK5N5ZD6efYWqcwVa9V05$Ozo{U@+JFxDm+8X5|t5{<8S zScL3apM8BHBCi;lOsY@zL|NHDuXKV(tFNw=Xj*4>maZ)ovx1 zLDSbGl;UG*`t6uD8&<9gPK9ARS(=xClKW-e@h-*9XFHM#t+1`F_j;ufS82s6!Udx1 zTF==G`qc2?sVIICJ?N+h%a06EdaHTlwON$L7$E8G#viyx*uA5Q11TfqBr_pf_whjs zoSsBcT}=%#^If;0kqq%fOz|W0Y=tN-r^=ffLlFqdi+D5qNT!0qLNKDCJpU#lI9LvC z=EOUvy}?Ph@!y}R-ni}$rvQH^=fTJ4>bmra8%Sc+E&1{jk<{!s?6eBDsyeVKeUo@H zv>b_{O;S{2m1RAg!cnZ%pr9BUlad0pT%cS%nVbZ_$!wup{U@ZXq@=0SVNo^;EosGP zSj0obgQ>S1^$RH~rI)b#kxWQvy0zYJS#J1IrLl4h1^Mq58;<;R9<{umc#Lo#M2=`Y z9#wq6ZQR+OvaIMSLDO#drMtU({!YZ3r(vU`qnzO*0|Qw#&Lem|-QCYYM|OI8+DhWA zk12hyqK7)vA}Jvk2-;P-p3Q#+)e5J6+0~LH%jQc80oRMw7`^TY9EWxkjPCFc&zL@I z-CcpG+H$-Jbb|;!INQC$=6(2V)YD>6%o~7UBI{QT{M})n+Wl}YkL68vrtCcFuBvq( z#~F8hCMF^x`jVc$Sg|>764~|L9H*PL%ytldk z@&fEAcg`{YS4HG~{q|#dkp_*Kpnfre@EPsSFv7i=y1G7CQ?Bp9@%-v)t1a%E-&>{@P(tFqQnMGfDzI^ovVl7S)di~8j5(G1lY?QuXk|67$a-rM@Hwk4}C0HLx9|8YDUQG=jI3KJ7&j~uP@&lDqHC7a5&8Ou1&1clW|9B~Y zRR0@DJ3wY%G$6^j>6*J~xX^U}!2_25e)@ZU=G#m?%Umw_o|S>QMXGO=-Ti&o(*4Y| zl{gZ|bJ`<0-&=xLnpTuTL2+~D4axHe|72@0m2XgY>+Sj*6c$q-f}vc!IICaQan$G4 zWi{B8;w780LW%w=|28Fl=7Y4x?+L98SHjFjU5RqsxNI_6{49;C7zR-IX_Z`Eb$nAX znv-+v%&aHn-6u?`xNBh0ZVA2u1RiG(m;sef}(g>ka^5 zBy5bwoPb2a%?W1$FB(7vusF`u?><_>{lWB7&a5utc>n<6{&8iK78KY)ZH3V90rdJq z`br_hiLXnCd4$Hl!YinGiCw&zf+RrxwVlw8ctW~cxAi*Ixz;{&%pyo~!HZPDhS5cj zL;vencAQtKI%OcsQUY1lV48R`sevbc-kAJii&sdO@y=X*3`n;CO$Y>Q1TzSmoG<_3 zmf1NBicKQ{R~(_S>%^x7UyYIi*nSTq#iGI2p`r;DF524K8cEMkJMtHaY}8T&FjK*+moe3+$~)mBME7@ z;B-OXUt&sJVS@%G2H`h@R)8~Ndl)j`)2;bJL6HXw3YOzEuRcSf@r2z0PndfV5LgoU zEC_&Mj}eIAfC>T_W_1VM6p8#FG-byhkG=<+p{s}HihHPL=xV7#)@V~Fp17^D(vgG4 z1NC)e`cr*c!dmD~im`6rc7XS6?SHrc0fZ_a;hyI!G`lK5E}fTh;M=W+-Z`iK7|6+SK8wszY|KD{e5^1r>c(!o>VaQ;k=yZhdwrfIF#5!+8ly;;;PF47 z7(M-)k$piHHl;7|@iY5%f$s>}L&yR$D8tyd;6HU;o4=$2zoBwt6n{ub3K@1sxsmgE z7R&d>qo7|KA;HHIrKi+OVZ6g&IEFJgf>0Q0WB&3lMMXr@ zhZBBtDhMpgteNQrNmV4N7CZ^5eJFF4{XQYzfeFp8qE^~caMTFCB2?}=Xw;!;`zvPS z3%_JH*h4mK`zX}D^t#q5n9+o3Z9zi61ISxOBbn+$0n{;5e;Gb8LH z;Cr%yT9~njJ7Q$>VZ6eN33XNPAB+F4u785+8XQM*?(QP0;wMDl*y>(6;Bwy4;%MCA z3B;vRu(sxqrSWnEZ>ar~5Pv_=UhUYd205<|?s$1tW_=*q!Y!6fiAOp``n(~{if`G9 z{JvXz*_dU!6y2IAgV?|^sHuh*%EeQ!MG$EjL8K)MY}bC9+6BI37zo-o9hVPWomSCG7}xZ8jpG?Y=HPFm!}Zg+$uSw zoQZ@O)FP|Ib#~+`&U_P&@)^fXvl-<6=xGnDiDum0dZ#v z48{P6s^=4EsDlRXUNwKLDc90yj(Qv4qR_Ux65sEMX~GKaAk3&P$10L=g>u1nZI+xN zVGrhCv}J?VS6O>jWCzU+5}5XQ5-9kjMp9bF0jDDNe>^n%b43PFO)cd#iAfn5*{82K zJKgl2yj?1_1`?U}M|9%NSVeJr1lTjmVsLLD=9sJUeG-ZKg*C_VHrn>DC~gTXkS+_% zOl_Wg2B42Ih@6})=k&l4%Vw&@OSI3_zARbpbzzx{x*F7csg3!yzIO9sg>nT+n(hIk zqI2n*?u9Imo7dgfqaAkh7jIr#UCGb`kxMX$2%6dRFP?CrlNwl_rFyL5Yc-R9=mY&6qtV_}({vT065W6?@_D@s=uqBsSL3C}(s&5XUd$S^Gphag(qx5R!_ETNTW;6`>k` z{_h@`h0FOvGHi8qbt!9WYuWLK_CLg^L+>CjAMf9;O=@bEY%txrB?RcczOVQQok<71 z;W|a|*frvO+nG|A70UGbzegA&KJ&> zDteaEZ~X%n>8y;&wOj7v{A5frX4ldZvUOB@`u8S!V>8VoNgdhM_Nn4JVs`A}A=OC3 zh^P-U{AUs6_@zW-&y55|09m=XZ&7ci=D!-Mso zsmdm2!Cu+Dqv*3#b(R1*8ef|)~ zMTR{gxB0%3d)#ytG|giPbhR(Hb%lZQ5+)||!plh3#cYAXfAw9JLAC}W!QJg&B_<%@ zIKTEzF$iW@@VUJPmXqHBX=l1D5S7X2{27POr3Nl%^YH_ww5d*H(B({TIr6w`P4l!C zv`+@U6OKTWFgBw1FurUmLN<<<&$lhLn(>DdFcU52uL~$+5AEwVsACqdOC#0>ki%&9 z(ZC?L)3)IcTJ!*s`rr>`0bmB@Oyc9TL+@ibrqzS0k_v(`9y<}-)QJCadRy^Zs3*wB zbX-xH=rDr72zBk;gI72ti})O?SCAF!Te;k^a5~S*zIS-kXV8kjkwD~xkI2;BlflzP za56c-(Zng9uEYpn5oxf`?4M8wx}Ss4p7mUYnM1|U=*3hDk|RG<+cv$e!g8~Y9JE(ZFc0>bC65?H#95f68fCVRg5I?lpPUfqHyDtMDk0W zqZ1Q5HfGP<3tS&R1*yzeD8m?O$163gTreg7^Y_m$aVS`%QVtHRg06eBq?nj;SHF>c zqlozbh0coX>f`F`>$gnyKy4GcLP?K)%F?L4c<}`6Ob=DMO4S0QV%-gs3wucrBbAMe ze5sTtii_qu^5IY6=_V~zE=wz+HGBR6K+3k&%R#u+eU7ekA1w&tO&Q*is|=emd7)`; zz~)@2p&B50`(T~@VV>9%owku0#(&<~>);+L&ttWZuZrNNW{>0*c|pL`YF$v&h-o+b zI`Kk>e1DHe29!{%TvcvW$v~$o_+SMB6i+84db-pxwlbBo-Tdw;F})PbKa%B~sO3D~ z#{)!&Oc^ex_pFR&=2CXt!?7~jaa~(-8gIV>EJs`^=;SWIMOMF0>YEIw2#^2zrLLtF zoI`b+6T>ekdht68NrfqlYF5hK{j*P*c7#P@ST9B0{!)-dM+3X_Mr5dJK+DA&T~{Ut zp{3th&<+Gu%OtY>7LG?m;=C+hRR!&51tiknf;NQpvX7=oUYx!_K(iI151Im?ttt~rasWRX0StXgOf0Mdus&%X zdqz{`MysHFf0;^eP*6JD2V}F!MELrDWT;^yuiNN{L2YeK7Z1HuEhE|*6?a(kF&@&g zmTZ6CqX)I$v>70Zi=7aG9CA|6#071Wh=Wu~0#ijS-g|#A!$vbY;3=U79oK*7rkjRQ z!R<|MbbuUBDFNr|t>5@{P-I{Q+2Bo-XpSl_Cep2`1GRHZT%2iVFtaSpywYL|2GaTv z*1@&`X|$3EIA`rf<#B)-GryTxh4sxKV&PX`98bU1Z)^XNan+g@mPf$XnIwON3i~BP zn}(pUQ6(RX$WozL*HYcotwd<5TuPlkj1MDJ?uIpbrRwB?w2u;v>Lx+ZhT3J$4h?|R z2rNzP7JdYHqF`2k5&_y^ihl3<7+g}=-z7_f0w^*c9`G>-nrRO%R^H2lEafjpU8QL) z-m_`JgIqnkcp{4Lkzglecy0@X2(M17(x+*BRwzyPIbIZ`nCtjQ0 zF59I~5Ss8t5zs)UP5an>-H@-aX%QhtprB~fdq23VZQH6Vo9-E{cb3*{~|BG(bvg>~M_>x2DO$ z3iLib9pA7T5#!u!EjE;H|KO27Cwp(S*2YgK4S5Z__VqMc4yz zLTyhbUZuF`izg;}2rxK^l#B?fEVu++enMWEb2R}1*jinuyVigi@Db2wlKDS)zI;{x z3B7>G^RnRU=;%G~*6C@3yNI_|*xzc#v}|U7QL<&x&W>098JkisVcTl}L-@qTJIjQO zA_qv78_Q5I#l=fG3)JJIA#bsf8xIi$+Kc2!fKGuMSTk;~OUDi<7eKK&dxwV+eKDYR z5~Gk4+;ir0=iw;6I*V;1`}6Rbs_o&*ey2_ij0iUJPa|s=TOqj^KDUCaZ`(WV(Vd*> zGd+YU0spD(V&j?4Yg4Yz4ofKob&FSFx4b?S6Uo1L`C5HQQvf;h|1Ml&1l3chuU8K0 z*fCd6x7SpKH!;Cs%#Dl$!VoJf@G1#R6cY|xv;oE?x)zpvWI|lsOYPjAEnaA1Iz{=+ z?Z|kRYc;cv&v$q^p9M}e@^k9%yzP(W85XNbD=IBC?+ixo%NCGA;0005iHw%>Tiula z-#~V`c^AwdL(10vnpExl8B#f0aF6cv1!T?l5X$8vA#3$1@SR59BoheKJx_xqFHg36 z@VsHjz|0mCfs0buG_|(^v<;xsh^&N=QOR&;s>0ON)X}t=zOnhjT*ShH(WIy5KK6|0 zu4Q2vtwk>AF`F(D>Sn^W8ega*#q>Ak&+M(8%m^a71K%?4M2Hj;s=6*mjng!KsTkQa zoYp9V_^&*r`h(4OZ>j<^)a3S*gdGzY)J$MgkeFN^KPM+o*_ndoR*nW3O=X0I5JC|9 zZ{+Q*xa~~!u=dod?Gq!T=#Gxny^W-#6iOdYLYvmq;nv&K?t(l4u6JJ$E_C3C&iK;s z3Gp_gOK0I;o<$NyQVmOCTz zHB32YYwGI{x(Pmqu83V9ch5s3t(4;!hKT&CLeIo6{MO2wF>@mV=$cvi=jX6%=k6*i z!;Z&N$;e00D=w?mj&IMdu)WsB>x|hcxvOJT{-B=*`M$&?VM9Lvm3S+Zs0qF{v?qapql+ zB&yji6Z`<4{DtIWUsn6}rtf99~%S|~@M(Q;=zXZY^kj~>#K-Q=ahqW40Z z+2ErG0K231l<-SQ8UMr-3T|1hY{_0bjGWkFVoHn0+~tO=>73m73pfjKTkM&+u*n2* z*GGcZ26P|XkV%BajzGTYgyy`ONY&3m992{|HHk)Kt7~g^I~6_ZFJAok8AJ+*gfyy> zsn3{WmjfvtA6)I0_$Up`0r2!ki-?c32`sYy3$<^-N<;ZpTKfi=I}UQC1VFZOvdF&P zBVjMMt#>pZ96nBC?fwWyJdyug$07j6AvG8TPF0uX#sQJH*NY|abwORB?P7P(zH@YO zLtAy!0kH83Kn3fLM{)F=CP+XgBScy5-5j*OP93X>2%=FOwN6FJIf~bOd^@)dKdO}g zJ`-*J`NeoAsq%F4=K8v`TF$5jm5&&oK*wlKNy?X~r&jVJY1#6IL#HYw${=MYX~udK zL^R-gdv<$>*rhpNe{tEbrgb_#t4{3JBFi&+k)(D$ftJupR=8zo%N={NpOonV#8-v3 z0bu}J->3O#Sc9yeE{Sj%jp#kB&W6{47^}R#*k#>svmSLI)hezv* zdc6FbZ2Yn@Wv-OY;LdMcXnLg_g)iL;Eyh5(Gf_l0n#9P1ixy|*CZrTP$4{L4CJj7Q z+Muafi_zJVH```=b9`{`7@FHU<1#^iR>*g00&WFfOuGkHb+q1Q972>_*JQRLjk&+6 zyEpy!y(d*LN78U+Yn(>iu$lZSFAsm+_rrM`85BpcazF-GMMOe?{1K+dS*4Bib)pGa~#|l7QK4$dV>LI;h-ayW^}-EW;LgwJ`IVUTL(%iqh-5yGny;~Ph)GRdZ93ZO?UUa-nHjcak1~zDNt7`Vudhd0xVbOJ zao)Ykkzcd%nAOi=B%nkWI;JYRFZRq{0RUS1!aiij+sL;mXtya?^4G0T|L?#9?Lbmo ziejC$teh@d&}I1jgUtID8WTpwP2aDfYQ-Qa*(ZKR1TaRw`t4FF5)SN4$vDJ*JjTrh zipq8J43yZ^l=J&jv1aNNR-OBY1eOXAEn=#LVRR!Kz~IgFQ&Md4HbvHQ%#mCK(VAR8(ArlVEw18ppmwL zx7Ef*swC4XyO#WI7|C`6-v{xue*>!jX7k;haAN zH6Q>3esdkyeKcQ^{4!Io&EL>lo`oJ|MQsOcg!Sjnzl}H3tHXsk5fo|1qja^pIBSkp&0|Jw& za%Po{g|dCio2DaK%|%YtQX5~q*H3s*Hd21@qtM)?$9KK;YDDhc%zLJz(?jiJ>x{tx z>H5{3%9m3w-w0RIs=`n6LPq`CHo@DrvNsj;-()(uTAezswn*>sukXfz)6mp#2$KL+ zJOI`yaeIeVxSihfYUBy*d*2KRj@8}X+#MFLjR@r|?b_93LM&+%WC*0fAa}uja5zCh z?xVH^R^m==q@lwy_yY<+36T;QU%q7v!JK5SC#JH)Azk=qp>*hyS8^zGlHu5 zV!${fpryO9Y2Dx1vq$WMY{Fx3R4<2qND!_1H6&mdXD@ z8*PlqPs8faxo;$>-7ljQH_bJ3rR)|=-aI@+jpoxRE}F%(CQb3=n>%Nh%USv?YP7&a z<)MyvvHx>z0-hCWE8L9EVIxpzEfy8{31UjoRW%N537GUeKZoM6YE?3{twe5AIu$iG zDiVOtMdAKx^$FW9EizsooIy4h0*E|%7oE8A(Hw0{H^)zo%t69@?nocB>5j38}GA|JOLxLNwF)KJtr+LwO((% zeX!A)ZG$G4&c$dVhuZfBcQ)!ycz750udXc27n(?JuJ`XDzC0zg^HtF4{O=pna$}cI zA9FZ0hHjakLx_Kb9LUh|Hkr?$jK2vGN^q-EU0|oc%;n z=s!o;Qf(@2Ab~h0fEmrREGX zGy0yL)3S3xOQ=j93?EU& zmZs2-=X@ottRh^d=7IHx{UV=3cjvrZM1pAc!1Uhi`QDe@e|<*i+_jn9rsaVmS3aO0 zu%|jVWBDUjqt4p-)7Ob~d?CR*wN`}^A^Q)ZYHKeYJh9`hu6<^?({dJK*KqOv1uG$i zZbmUVW7zLxFfrEn*$^>v$Gz{FsUCu42@<5SW!@( zilzNN)3?E?9-}^tp^ovFxgJhk4PSeqjv*V4{531`u|yph1bg_rEtInZjplf#LNYmy2l&a`;}J?O1@h?{#2nM`~pIj4^tEN6r5&#J~Ua^Mi=U%NF>kyj?}A ztya`h4+jxSgjl7Y0X#DzGm}F$Ffy=^=bO?w@cSwhHcXxM5mvonOHwe<*DJ9(v z|3UBj-TVHII*vLF&xw8ZUVH7eL~|%RM|mp5Qkq*h4_I+I(R;&o=Qif)*+S5(PW)e( znU~J--a~GU{I1s1wqoOXV7tE~tl!kZRfNrk*FM*#`sw!#+KRhFpPjp&gK)JX>DSx8 z+y1{R6yz~BmI;b!QGmv;=ESO6H*jT~J5Ys0MxuizN&B{Z!^5TB>6tI^PmP8C@b|(Y z%YmrTIVMu4Q|IU*rMys1AhKuCKv~scE7Pt{RQr z>6HKS%6=${yWk1|3xpEOM)xhC{r~!Tn!z|fZ5rbOwo;^_fs~=O9!;3}a+bnn<~UGz zN#A$CMMVQqFHq1$ZUxH?_0&nb6Z&i<6VsgHd zaKkgdlg#E06E8H|bFku5>(Ev^d{Bj&%{dF4rDnqhM1y;`o?ZtX*QS)HE znF*>j6jDFj)kea{XKLB|_wRXSLs9R(R_=2Wn&ZOId$Y}VJsza-*RJ4&f6A;zXS4LT zm1g1=36gTZdAsPwGMEZCqcOwsB_x{KzxhkEPig7hwMHhD!Khv@Mr*@P)>ij5#ZQn^#20szon>@_Vxnhfc}~d9-YeQ z&()5OM~2<+Q7QQAjGl$7J_x7vdu6OKF>eNwCgxZ4{~oBI2N^|u{keB2$brMF9Rg;x zWpj1Wx-Iyk2@sS-Aw$y?u-4ZbTir{Rgh$I{<2Fe>^$920E;X&6g9z*rvghxu ztP|Xj{r%BPnpYw| z)zAyFvZ4+>+0+XY@aBBiW`yM3oyTrgoVS^`zL8y!w8}nUh?fXqqu2f^kxcFs+!_U^ zCR9v$#USgX$S_O}>w)yTvm2dXY$^>zni??TZGM!RzI~eB69%0cZC>|?yU=g`^UnNR zo-y&m2Fh^zJ%Yish0Zxcc9fqwcuS*WNVab>%J4siQ^}HveT@801+T3QF<{|(aJ@i8 z0r7h4c#7Kg_4ULOjIvhRP!~!sOMOKesgRGhmyeDI5_D$PGy%qf9Gt!6*1)LL-LOc> zg1R<6HFnJUP^D}jp%C*gCK)D$!L}o%&4~GLM{%OuftYW(TS4whemNyw=)*8{%maKceN6zjVi^zlsZz!UU`Y@;}91j zfLvhgRRmLI{_{gK2ZkUlNn$Cb+c9FY~kyi_k+4)AnkRrXIp$fp8kqJ*j0fJF?%3c+UnO&J< zud`*7cfTH>qO2f>=h9Dq3e?D)%GyxQrV0t^+v+Ym(Ak%Q+;r`TT6(g;<&w3t)1Wlj z*$Md4o=PfWJ?A%3Y5b0l5^Q9Ux9PnTae14j1S|ZPFPRJnRi!oY_fc^<)37<@i6B+&$&hixK6hUbzQ`sKyk$-3z_ti z3RMP-BV+s=fVch~O<2FQg5r5C2&oFC8KZH+;ot|4*d_6!YzfMc7{%H5w*J&NVFAf7 z-8e5W!v!ADD?8`i@e^8Whk^&P_TfL#4H zwUgspb!RpL&zz*hgzD!1NzVRV8q$w-)bKnfAMvz2c6Apyv^*0g%o{VST3f$SDz^=9 z<-waQ;D3==d)D4e(YcQDr@$I4qYn=nxcqdOJjhvNmo-bJ`Z zHn=K?6~b8ivK7LJ>N>~Jq!dP|_;MAW?5YnU>$UxYYxwfq#IGB-ig**h$TI^yiD$~PQx3d*7aKSBhBO_5AZLOIQ^nZNerUEZUJJ%8AB2-I+z zf+7JhMJ7lL(Q4%dqlF;k8|;*PztBZ|s97RMQ1b2_2`66b<7?3EU|b|Hb#^5H`SlGxw-E+JH>YoxX&(IsXE9^aPEyrb z&>!RXXtxnPVhS$%; z0lChDx=n$OBSbze&}~enI|Hj$${M&&#fBtJfNQ~x78x7WCq*?a`cuCv_d}+ROa-r3 zWj0x0<--wRbwl`gy)Ds0_*el$HaibhPy4#^+oTSCp}xeIw|cb-r?Hl=Px|JJUZ;N8 z+!45@MD`~W@t&w$uy)kje@ykpyOoiZ!Njt6h4|eulCe2=@uY8jgEL6%F30#V`S&%r zo$-9y%WU`p`ZNyj-gRos=Z~ueMhHlJ>{4BU?>c>c_Otz)362VGg@?@b^Jw1)-(6U9GmoanjehIxpW-9)Y$|x5+UD!W-;FXp znR7C$C)#|K{z}-JT7JHNaM4z-k&NIw_3B$jkI~^_;znd*H^^O4rZ-xRy!(_XNB~|3 z9t9`5Mn*f!Cv+jbtKDWwW@?h=cj;Zaykd|P5ni2i9J-kI56(_IoYyX~bA(@eIc_BW z=c4}SvAh4k*hbLzXG#j2!3+Q^A3PJze5(W9nj4KdEiG^S#^-_N5St0UX=28^L z7=qfU-KyAI0fd3AO_>>JdUNQM`7y40m1Na+1AhV0C`=S#V=D=+uQ`bwD3SQ+dZhGl zF&jg1j(STf1Z;FGc=_`+{Gar5<5CC9BuN$-%?V|ckn|O)Qfk*#<-_(iroQst!qJuc zY;b8m1~Yj$)%A|mI-5F|pR>f5xc|K}U_GM{Up!v-+0D-@oSq7505!TgB|TZzaRnSP zNiqpy+BK9)kz|;cF9CP3NRdgeceyUSrYZOj7hfdO552YQDfCAWgCP%J`SSy^|7Qt_ zZrw`2nl!ZOgrnTIZtCppw7{Z7)~KxHVqZ}osy060NaNzam8C6e+&1SH^iYK|C+7@2 zLiB|8so1B*O@2WJe_M78NzRPM(1IDkjr=KWM^mXY%LMbS!P)%Q=A<3#rFwLlXqZ1s zgnw7a>Z9RmKl}IQ*A|a(bR42kB>#KM{{HE%u&}=~=528ESw!GVgj=h{e9B3-&VYAN zd!dC7x8msRB|4fKyoX*9CSEVX)eWhAOC+f>nXY|DN1@hWF~92m&Y6gQ2dnn!%^|Zh zRo5Bmw7J8e)f_1sjIO%&)a>5s79Y=*I?vTg#z2;^BA~N&Vbt^B>^4 z-Z6E$=5$)+uh4z3ZbOsGi=dmzzhj=aNgx%%?S1vD^?P1R^f~SqI=Sa_^g`UZAzYf@ zp2b*>+uvUUMKGa8K~Gk}CLGs@I`A9x8G&RFFBKI;WFMmEzIZAb%+lxyCw)|$NkA(t zu!earPYymaOe!(vV^CxyB_AJ=#>}&z0$@!cBvzI?Wuo5o?@lH$b@c6wLAJMBtO%K| z9k{JQNO~}emer@NMJnQd??-6x9Spn{fI)hv_VeK9=MuH6E*}!?sr~ygbff&*7PKxV znOhnsox08f!TK{As=)xQCoGF*;(0f#UE}WuPvMULoq7ZbO;KjltJDp5)LVO;p1EcU z2}_53($V8=et>JPgkt+9KmuYKIVCCyCA#p0z!Ed2@eGNuH!H%|JV8~cFhZC<3BPU? zM9J*Ddf$3-%EM+At67)o#akDI4EL?A7;zh?%Q^H<5&OAiG;FkpVr<0OA%i`WL@vmO zuCFa_@f9Z9i%W~mEGI;BCzEdU+fmL5zE9I=2XsNssaj#E*xm)5GI$}&^+u@R)y`~t}(|qCI zx%%xm5MTly`Kj(JeT#~yLVQ+^jtX7;NC=dSER;mWLe{Nz?iQ8U?UL^`!D-LwBVViL z8pK&v(JA}HV!@&En>>%(;VbLowMhM)h10!tBCqRHL}uaZIqO}j4;msYggX4pwR~o3 z1yra<-dgm2`wA*f2#b$F4Nw!EbK{U7|2qO@A$02aU#(n$S<>wQe3OcWE8h4SOE*ZT zBbMtG${`EvOeQL?E~&3}q~h{Wbd~YeC%ek;tk)4)px0~?X*Ui{7eBKHO&9K1;Lp0U zT|-*+zeQ?(Y7Kn4r;KJ9rutpkHvl;95zB-FHnW4Gx^3<$Y)v*(~O&3m$3tajwOcf1+0MlD1X&NsMTb z3A+Nj)_bB-nvM>12`#b$A{YtUKT8XWhO>7OcT~)Q`61G7uZhy*SM5NP6`6 zZ{O zkyI+;MBfkk@y?ay)<`5It6gRc*>|V6O{bOsn%dLSuUF>+^C94a39H+P^7219^ZLSE z*d$;{`hF4V)T`?Zzv|)*9XhGf(ttR8NMTj_mKdIA;x-{OPn-KU(?7>)(^}hzT*}G& zgv*k*hhVT5FkDoGq+<8ef|-O52L0_l>E-aQU!@-R3d8gk3`vOyY<`cPxTK$@*boFr zID;Sy7uF(2_@7dXifD%UpWMKFX~mpFnbqIjoRf@MqHmg%APz9}w3L2zXPz28(C^D2@2! zi7;nv+@ff*y*1<)@1Sxnef{v1M9WFY4p*}D7)SM=XY}8hW+oAS17EDvpin52Kuwi1UfvotNO zcD$;4r~AIxMa z1&0WreSq+Cb{xo$u4`&a-(LoeP5`prCkXizH}5tjc8X+Sv^r+Eo2{h*~XA+&H&A3j@W(3r&NH?6}QYa zpjwo~Zng!9_XuIdfmqg%7oitnoSoI#`;D5=o!u{&ipdsg(TP<33D{;pewKdM#j3$d zMUkY^lmbA@Df94$CaTou>gFSgm}oHI?_<@g_j=fO+}SO>wi7ZmlOvrTaQQhB1&ZcL z_LcV1y3U``z|q=u`IDl;A{&kluUNYtrGw17>lXm{y-9LcEe9vJb?hK%27^-SD_}vB zlap&#&2elc>Lv2IKf}r-q@Z(CMheIP;Cb$5qTni7;1#J1S;sBSpY!w&7ZKH=LMG9~5X3z;dFRWjI1VOIut z3;ewaDYVa)pvj(CV{?;Y6%z+@U_n_`ZbKH%Gcri(x1$CJC%ZLlzInaTa#ynw5;FA> zDGjfXEb|BQIxoo4(#Ba;Dxtts5~3a>KJ{uPXYdXh)JGCS)b4uii!HuVMX)m~yO;D0 zKqS4aVe9p?P`X9igF~|>V{UFP&*Sw5Xj@!-2ws;NUo06L&qBk;f6Lo)Htpnne0dzm z?G0^62e6C*d+o8o`0gwbP68%NA_8|-R(4-c{>H8^3gOJgzIg0LxR#jZ-v`uIOzj=M zn7mQ9rbxBqhq8MB7fu>t1)6zKVOS6$9s=B0Fd0d^I?yXxhXXeb&Vz!qP%OG$))h=TM~~8 z@zy=owr$lEe#y#q=#2l;A2%h`idB#V-KW_u$i6Fiy_H@GtX{^h!}SIrY`;Yh2D2$B zG8!6^=LX=rI(vp!kF8k<#*PUl6(VfC6UUDd+Cgg+`JKa`SlZUj3zt^Nuh z-S;08j!GJ57bX_Oe0h5I+)(8{^eQQNSZHG+4ekGuU3fly^63O#aBTPmUkd}-ON%>d z30&lIdUoYNctQyK{~u6IK$4uyTGqq>9Oxx-N=q};JU(U{_<1Z<|u%CsS2mB>}#+%OW~_tLcXTq6@40)WJfknr8@vjB3Tw15EQ zpUdUelarI3Mkx`I8RbV*C=xcdfyIU)fV27y)z)e1Q!Fu2nU{6zRK{Y*21!^TzGzE`@^nFibVaB4;+N=W&QFLJQGWY4L?Z)&neQmML_*$jf zP<)7V+e^f;^i@l1o7>T%Y;sFBRI%XME05?}uRD_0tRA*4GL%iZ_UzEJhyduAOy>Tp@BSs_@N*Q=p*E2>upCR4!Wc2KJlJO zKv`SMQb_HS@U>?2N_V2MxLKVXZ29GJd%zeD{TcVMTGoEW?+Rv>Q?1oqe?vw5d_DE* zWbUb2D!gOkuj6lSh={c=rm(`? zE1J*Ie*J?U?$($`BiT zT`Fyuqrz}?miwp}me2O!S1X&~_Ryf#P;)2*^|HM9f?9 z=Q{f6s>X%Hg8o(oeG)=1x)*CS9R3P2pVj)Uddv`h4v2X3%TPReRCVQ-}V&x7#Wih)qfP( z;4=|Otmk08ixP|CyP^fj&JXc)NB%XZeKvDk_|yM=-H;*pG6q09VcF$Z*Pkhd2{{=XMg`1P$3|pq|AR#NMO5wp}j6pgC64C zW{pn3ncwcWnH-&)Rgp?1>oxn;Y(~af-8mSneQ+tFW(O+g3L~`pk*7q+s1G03l-tIC z4lP}I1P^l@avW|C((uMe)6U2)EVtk3YaL%Prc;tpB*7(-RhY8T6-~3R{4B#xg-)sK z%r0-&%J5!!z_j`8BmRH4^;TZkKO9FhXgin^{pQvb2lU%@b?t!OE3->=Mxi|SD64NM zgUPi+#+Rz*XW$eFYEsi7W)-cTQKvenk}4Go2na;svCIR7Cxbj`%RZAhh#*wgA7)<= zH#Z%mxJ#2{v+v!tymZjV}KWmwJk8W%o+y( z)$@iDxFHI4987awOkzv%HN;WNgUJ*4gT6-?V&#&&>f8_(5dv`ueT-_y4>mkGN6aB+qPKMW}j zZ%`$rN>M&b8BkDMeso_)MMtD*zA>P?T22AE@WJoRgS)SD#K;we*0l0feNmgD-sMjS zlBGR;sK%&gc_0SvWdQfImYghGHFWGDU_;J~yRm2@#B{H;LBHK5ye`PZx^0dCj zn7+MrMWn4@LW&$34gr}R{U0tsbfG_hRo_??R{=H#lQKi&y2Px~t8zNu%!cE$s-bN_ zulV0BJ`W9m2?zBLEVP0}eP%$R{KAQoof}`=;2>`#B{=zCD!vD6%Ye4NFQG$I2ce_F z_^9^UUbzMj2&@@y>sy@&_?$=0pU^R~-EYj{tYxn6R${H2>w?OhIPw&!n`eIa3TNY+Ew&-Lm{7q~Kf_T!Y z64b{(m==FBFn~4ZpQ$L_GtzbLQNHf()>yZSqXasRJ!!CPZKMWhXHE?vAaf2w1{Rh2`ajH>aBt={!l_ zzI{tCkSBnepJz=@rXwf+7#tev(5Ny38ZS`MB!F;0ev3G(U{S`!a#PVtt>R|d2@SMX z>mObG!PzyuJ!gBz!reHzB_lxEf%dCsV+$=Lz}b02j;~Z*9E4x&*q?d5rHf1#ZXnRK zJcWDR;0=s;Wu(0XZN0jub{*ffoWk#iA}gPsPxt@Z&LwnsYF0K?Tvn>V(M&M_Fx469bWSc+#G>|{X_OzcK6awqqZ_xaI z|Ay@fxJi2dYvJl;b#+HxC5>mm^86m%Yf|0I_&6(wRd0oys)>11A){ z%GrLx2JRWQM_vCeuW9j?b1tjARCRmntAaJwTsr)xf-e#EoS25CogptJUA3`=R znYzqTEq4qhUtUxhbo`8NYRiKlN|^wl=gvJddEb4By9Q!(fnPWvWqIvhE|oq{VK*JM zrbLs8{IJ`VgYt$5&^dm*I|9JaIL7-BA-|d8u~{QhUf!^Yxtk(^;v)9d>RIZ~KR?oz z29&po9&k$N}8{&H94;| z_mjgt%Uq({JZ=%uc*k9PJQMOdevet5@G#lcua(Oz%sL)1{@bygcU@lNa`>B@Y;LXI z%)ugmH!*SB8BqNw6138VtSbo<#0|Fw*#OTd`&UO~%NXmilU)E30x;0I;CZlvo6%Gg zmy*Kux^#$ZY_urPpy>AcZVZHPHG5b_zQrWr9WJm({;Aj(zivwyLdIz0z>&k?UK%1s zJ~lY%Yi_ot#$%>l^cdV+bUBv}uIW4X7e zRf!sSezPb?Z77~M2yQ1mS6cGz`#=N>71r|TJ~|1i(&D&QNKqqWn#K<`>&pJ_a3qwm z^`|h7M)$MKRc%Y%7ZVd2?+;$Ual-Y1^e?p{otaK_~|pGHgw$g zjd``=N}y)FNdfCq~Hv%@Hp2dmTTBStsaViTSI#yY3s z>kZ8U7h*G|>yv&aLm0C{uTUKCdvm$f*4@G@T{9OW-hT6@Y}_^Si(6x$6r7 z3yoRU{4Qm8BJiF5fDDD?>)!6*F2FXy-Ok7mv945S{|mek>^x_VcSq8>Io%O6rpShc zG%>`w($!T>R#qfY$U}543=v$t%VLo*^#cdu#?;-i~&U z6)J;=pj(#WQpx=toC=Sz12sEINl74H1S>fqQ@dh@5ZL9{<=%W6%CVD_#$U}4$lp3k z^hjls-5CT4rF(%_bvDVPPeDFx4IJhde6yh7-I+=S4+; zDB7IR*4duQE1zs^d;aQSWL!^XKU$kG2f4TFiDP&d@{=uE7(TLPiI;1}JGHg{sdXBYPgshck*wMn z2T6YX2mDg+2u+5+ZOJUd=d2_Is*m{SEuY7eRM{W*q149=e5dSdGAX*$PArTO@~Jck zEpyfpYlL^C^o0pDI4`COWKm&1ICHL~_~w5{-9APQ2{`e06=%2dn)`O$zBl&^~h}Oo~F?9OkZDI|Kfy zcycQzL7|~Bar$L$=fm9A&rOr7?JO>v|->dB&K9W1IlEiN9=V1<`%Vt=Zxbcib^XF zj4(6DpMuMW`SOmL&RoW)^by(_>)Rl`FRW)a@aXS`aFokflZAohYC%A z$~ZMn=@;Fv zmVj=S6d=0*?JRJBm?7|Bz~zJU#|%JXvE+-uUE7XVE9xIYTDLiH#VfV^BM$ee3o%5L zqVO%^%D0X+UsCEalp>t8{$XV6q4)Nn$!yt1*mtwtmu1XkXXJ%%Spqcsl4UW^Y)9v` zzx<$0SBq@@hJc(g#AZqVXcbjKq$4DR7wK^U&;D@bA(l*=l*A4h*b|UfR1gx7SFrF@ za(HRDaG5fAS2HjXc4D>Ue7q3278xnz(3sTyKaHXNxU!V(`(zknV;y(|q3UWQzb^Pj zWWC;NQHijqI4r@Lp@U@?+W2uf?(9!Dc)asZ2W(B6WD$gW+Zj)El#C;Y@khZEg|^pg zY30c7>%pbfHO3%JyzzXreNF8CTW8>#!*gnI*dR#-fBirM-W5^NXiH^Z?7zujOV^RI z^Kl2JrYn8K?!-dN}>U3rSCyW3;eEh!CI_c_0Xc!P|0ae*Dr z=%|MaZMSaJcjG1{r zl+u}+y7KI#?{FE#bJpBob)!@oWDwfRV^J~3Ekmq|Z`m0LEh~IKX(9N-efiI6Vs~z# z0d%`gllP#5_<-Qqd^~j5+-yuOvK_Hqo9)@iat+DdMJ!Jax>XqyaDYL6A*iu*xQ2r1 z?-UqVK-7bSj5?OBqJR{z=?iK0ZTOk)GinFav56$Q}F z1wxj=uX`XckZIkH1rVREMc_5d2hK(;J2u~a77qo{)HETY(rhomC}d#gx8P)mDpjf9 zgn<~)6M1JW_v+?GK#FHf9Ms03*<7s5ZEQLrgL&q%)lZ4hKZs~M$ZYO)Gbf{1q2i#W zGow?(!N|;8Ao|`=()gQTXw#jnldQ^`>Bu{naG@-&+VGR{-8+-O0SEH6|u> z();3YvdI1K-$_2R7NNpZf6Rujtdy0Ld&7}-TZgd&c)*at-p$P(=wm+fWfq#ks-rWA1t)T7 zgZ_p9%Tap(#wD^A`ZgUFk&}@vTGo8k_iwoUqgtZm`-_IT<}16OR|Wm~Kla8qrFhtZnp_5NGl-cHd4YVzY*|>M#WCS00?+SgL%#BneVST#u_jrvEvMQwTnPZ=UKrKi0ymcsdEr) z0rx5W$pTrR8`s!mNeYt~$rrNb*!F96LV5|@bAWZgpdgQre$On5O2nPp=3Oix+Ptw` z?#oi;ps>euQ$SP-ohuror=)%rGdT%sm|NuTSN`UY4S1GK&RJ^Gz_gXK4_7b+!Ej=zf;@0qo_{YCp zBh)~yF0WG?d}5EC%=%d=aNI$`vNyxcxtpWZ8*vdEjYh%GKe<~O!CPC3LbIIK;G+CW zSXcn4n}WVf&bf+;5e;v)#fdByQ~%{I(k9^KqL+(!I2(;jP(`3w#Q z;Is%VTBKz>ltg^~YB+QJ_$`faYu?lpz)4I7VZ_3apkl3_{3Iv$?fm=^As==u1x#cB z$&mm+BX7IYP+Wmot()r1NQW+lQBHsHr7-RA)MM9h@p6s-y4r@`A|*CMnrAQS&uwK_ z1Vgero84wbmp#JjQrvNd<65;I34=kMBnVBEd})qie7R#YKN4R20~I*X(ch$cdXV|T z_+RZc4-musXl;dl;akY5=iq5=`;yf;lLX_PoJ*~?_2-JY)p#`$bZ;M@qc#gg`tI4( z>rOzDC9z1sK;IzY?cXn{FI`6T1%)0iDgYOrrQ4E#FeH#k1(6~6BM>W!433OUI1Zc* zFY6K^Zn(L(#hJ*j15g`rzI=Y6D3Bf=r)H?NT`->tBW$|DGM=6`*Krr3Ha>(lAV>6O z)MS>9ID;X5m_|{zs2d*5&Yxlw_7f|dezms4F+y%jsCXW zjK@oe!CJUkh3q1&CuX8@wGG{-yE|vIm%(|b20|(J1FkJlg z^mjz-o#i;wDlubwUMZ6$%wY0l{}v3frP|PeIPu!VK+Q9RGfd>nlT=w4`1>LvFG&kj z9`mZS4Gr!UMjc^rOxDmPwB9Jn9n>NRnz32Y7zq*VvjVoH^c4ZaZ^;~Y4EtGBYSj#FqGbbDy2u8Pu9L`)bE<1U%Rk3Uz}$9yRWm3Z`iH&KmHUw z%03c2hptoG9-!Uh+z2xOWewPOK%H-28wE5c-AY_&D4J)YJ_yWZ^;r=>f|`thp>e^Q zRru{Nnh*iAt8@Mm7WvoHUT05zc_Gd^w__&hQV(Czr0nYx9ZE+&RPCDfli1ZojMWUr z4%v;>Q6NZBc+-CT=p?WWO8`(b7}C|AEP!B0h?p`VkiodRoCz`4vhFeU z%mGx0Xfywx{_p{i=I!Ohh#qIFWi#a(Nyl|}`~jIMcT|5`UC~~zEL7cLY9Cf)JA>ks zVtTn|kNPj@kzQ*M?i!^sNuzHq==89u((P1~^qI(r#6Edx z>o0g-0@4G}mK)}4N}8PH+qbH!B+$Huumg-r+lnLiMT#PkXSQXT^Bz&FG1X=f+3;Fp z|2En-M|HU+fZ?d+1JH8>F5;usJBGH014}UXx@g@;s6w}ui78CV zzz_i{CFMqspd(|@ii1{o9)$b$4K@U7t-@!eTuxpu_d7{YU-pspN)S&b5iwphYHg(2{yaMZQDPTpFa4oL}c6a*^HDF_lJ+noUWR~Dw zR3F>XP9LNAi?Vflzz1T9iJATW?PuL!cUYf|&QUKNYA=*e{~L520l9knq+D}tSsEL# zgTcj_(sB4Tiiy=FBMYf0FN0Wx5tx@WgWt4(2Rm0o{WBthFtZ{8N`gkHGpxf4GzyCb~L`exXz`hit||C9-o5Ia)`1{o*g*Sbh)=hyns5s^?#ipv7i0CX6#y znxdYACX$e{w|%qiD6gE~XBGjx&ML3nxNfhmsD>+@X^#=$F!HiZ$kLMHquhC44@p09>fywLC zjzz9Na?5kgL0q0>>E9zGYw5}6i28(LE!&N2iEo01T)XrqR?8XNg&4bRJ-s-TL&HS> zg1k@dS`~7O&q*9zbqsmlW>7IIb)r&uCa_9ms$A z3yfaPB4Rhb{c5|}Zrfn9dNV6I-PK9BRslR!lg8!9d|$Z+h4WsT0GT#14-a0p6z_er zJ7!OmsXT~4n{Si_MImDHFAuu-l&OmtH%@P^qP1#5r4iz7r`pdVo%jE33@xgR)9+|Z zheKBDj+Zry4r{iZyJ1#cNSo)o8=L8_|VD+(QWxyl5i^4nUI%1%<{$kE46%^%4#|0>qD_q-p&30#r0pQrBFk ze(4}MK1gxguU)tlmX>Zhw%rk8hraY0N@1@uo}e&e!v}KrB)q&21)*r&yL~3%+BKi3 zsF{!Vw6;-kaMl~P9RRumxMzM7&f1j{4Nb{$Jt=cv)CSLrSF$@bx)@)j_DPa43cv-d z?Y)nRhvv1NKST;Hc=uZIQ=|pRHemQ}fA;v}Oj}*fUF=*?dS=dB{5UP{V0qs9`WKoZ z_%!v`X-z5>_Hg}|99(?{-<8jI?BHF51Et2YXLgzP!pS2ga_@H1yXn;7%iW>c8a^XO z{aveWYU3FOjJlQd{ziMH{YzMEaX%z{Gq7qsy1{m{raf`#s_{p2UX(j}YKmw_7GFNf zy5s3_A(2e4=eP>8vABd8%D6<5*`1HFvi)(|2zSzSf1jRW$*?g%Tb!kdb)`~XMHP}2 zekVedj#8o}4!UfNU0El~VB)^(mduxe zoGz`ZG*9vOcxWD5Dx8Cr|I~hV)S+Cw<^wlMX85#)8|sVp#ogKZ017Ncdy>W{RLk(- z!^FQ2O~gc_J)2T_?O01wWHi}Q-^HShe#Q^kx@kX z*rZn@Xh5N$Bxp|mm0*%??EAz9>s-O<^n1`3Nhw@Xo;2Fla4_9NRs}$tLaNoZ9`K-W zyIOL5cDDk?2?GNIU|_Tf78+{Djte;L0Vap0I1uR-k5IPLwy29ZYO7nj_=C&bDJdrx zl$eNmap3~Kx2&0Ba&kYWl$w52PpbBn_~v%*l(rn^)eiky+q0lKbsgJ&b-^bt4VvX?>TS8Y-ZA#(9DW4{7FJvlaLJkG{^?{|y0 zWo1UGxz4!=UDAkrvzFA54Blz<4-))dohdHqes~bZT~^zJ{Wtm9O-(^h|FhcIo}41! z_y*I&1Toe66KLDW_vMHp5!#ex4aoNi{nFf;x**|>S zqBa|besBv`D8T9ZxComk2Wj)}q^NyA?SqnYB;=WB^Vo^c8(7NW=qsWhm; zWJRHsR$0w&1o|zmuFmVhZwMk_KauS(8m~WG>Gl6QV{x{5c;rMOVG9QP4jqek(N&(9sCtfhjo=_)H7#D&@pMsw3UVZ?ruK{f=|&oeiaLWM2Zn_K?RK`jXrR4n zgksIXG?uHyHER8?d8*#O-4^Y>k{gv`hg1Fz;H;jm2r8n_RpJIh5g?f2fu#WS)mw}RzrxeWnhTld>u#Nl z$6n^$-3=^G9<%xDUwjsYgH)BB8A_q&xllld@f`prx18IP_CKYZ*Uy1@1+#(zE)cC3 zS5>XBcldMCu^v}pfxl=6XZH(6cr7K%zPbMLMPs+VmGjf?xx}E(S0#R3`r&CjpX2SoZv|e5cZO-3~uzi zN7zYQeAy&hg#0Y(k#*oN2rnMb;q-99aeH}TGt6neV|D!Lr=Z>A~Riq31H__*@4Jj;2 zf=44Gqjrlry*ks-!xhgb_hG&}GZ(7o8 zV-gk?Fax2OC}E;dj4>yvl;?;q^f4S&Kv=P6p*51MNQ{Z#>jx9Z!@HHX`Z|%9WUuTx zTEEiYoANC(i+B+Ked0a_)`7by&Ui35XE<}RlkIB7@#b!1hATv)rUwYWCdLGah2Ybw zXv9dDmIJ5IQ1;)H>K=tNa_7? zFGjj@*t6uhwDKGvR*S9nS^8sLRvkXL6q+Fs!(Uhy|eDthS>Fy$z#H4}~voV%FI z#&vv`Q_MBIbC93B%%y?{Z%($98iWB`V#Vvh*)VJZ3R-I=oGKSdUG+;6r5kalr#x9y z_%2$6wS@~={Qm*ZOGya=K!-m2d%J{~7;1KBi-s)k2r(ds}VZg+msDn0V`U?-xMK#l*xV2NTEq z%@+pEdFe&g>kvlmONCaiE<7odN!ch(CqRp3*>i#wF-=$~NUk~`{1 zJ?*L>8o+rFH0NY`0%93t%Z5dr_MEnwy!iVe6I78QlGbct(5H#N{3}G zy}!c=93dcv&8W-w19BtqGp$LK=yTjx*fz~6DEnqbF4*?1`2{%8OBD{q4*U)f_4~58 zEgWfy62MGFqsatsuU!BS#aAkF;%guN=^6qt!J`ZbJK<}de>K=oILF7G`5IavBnC{b zoS!?v#Ka>(Xk-vnw6sEsim6h@O|+~<@bBNd(9j~~UYq?*%U{hNtDfod$KltZ; zFr$N8-&tn3y3NrPm8TnWx*LAu_6I?Ul(2uq#-P}Xj#rg*T8AXu3!pXht?t4qA~a;6 z&Xw(Wu*k9Sc+yIAr7&!SNFuDKV^->gXoc_*$C8mk!`ZOhj~`I#Zq|~4MzBWja78P6 zR}o$nT)barnwxj|{9Gz=2rDY$C33STv9E*y%NvslRcfutG<{`MmR;8^N_TflcS*NMigb5(OG$SN2qKMicXy|>beD8X z_t`w}cgEl^cU^n0m}{;%4Ok1I-Xf@~dKekKo3~MXUMiXDy6u|a$JKknvui_A!bByA z?`~S@|5uT4apyJQ^pC-9l7fw<`G3#+7X3RMR3L&`&F_)qI+{m5s&5HLwuNLYLWqgm znSPR%RE%p7-pwL*`L3muz0xUMpIeCeVDsko9aC)G#r(zid}$X?^>bi@d4Dx{#>e07npg@)T*7VyEONvHZCXldS&Q|Z)ZxJ~p(`;o z>Ugkr;0c;mm;w%2R@yK4*-yn4bC?Kpm#3$O2h;bnOXtN*T3rpIf(Ej_5Hf_twVb;P7vPN-o1VUcVT@Ja2ezkjd!>ww!g6yVVbO6Se*+C& z4%6TM;?yU8iNu_qlXQId1v|vgM*d`v_EdP64*i+4c)`#=%lr`bkr%$X8%zg!q484N13#{>0r_uCDu-@l`5 z*`tlWA4qlL{!>0oc-_whUpQkRXKRQi-u-eCD+I|A@V=>#@HZ_F4eJP61iQbCAMflJ zAnvcO$dhGOx|SszFO3HEV8EasOWN2Z$qTQH<;0u-V04*}A350Y#2W1|s769mi3kF* zfhlkG)J$iLtlIdGmN{cV<@`J=A2DESyz{)S?QSX(Mcs`FtpzUb9SU>q^I~S#X;Nu@ zeUD7~)h*?e_y4=G78v1R1gN$%_Iancr26Y#mdb1y|GC^3dWB^L(buOP=Tt?I+D%Hr z!g#Ou;O-zV73Jed@93eRI^T@F>O&}l!uMl#|B^>m%{cA7{M+i14cQN>P_5 z^q6r_9XSiov}rBcaOKP$rh1QByf@-XRm`Obv;ZI!Fjg2OcKgBZur4oubX3fgFEk;g zCW|0_-Pl7~*#_sDV1bM5=@$McOx)A8AO9PGF3~~T|S<&H&W|wyt7MMQc zLJ5*8Kr9Ir$BswqSu|9Fz>XL1u6J z7`5hmNBMHIlKQvb)B!ZAe{0X*k=JPUS*e0awfoL^Oy8E}FQ%2cGf6+Kj{hwiP5x_t zS?$+Vl=e5>5#||Gs9S$qv(;obA@@aQgo8$H`rh2N*6wamsSe_^j z7{<=`^|e1dzJ2(7*5@`MNC*H-KkhyAjoG|gu{S=v>pIESc5fhIJ(75;{Qo&o0Oo+x z;WQKB>?iHNjcss3xA&E!g7Ho~C5KY<0-OR*PyA5bU21qgUe6d5FtFNwewYI8Rw@`6 z-H#`3rbxsGLK|}z&`(FDO#Q@XAWXxSbmiI>mWM*?i&f|xH%iS3?ZSQ>$SFR%+XWy} zkGeixP>PiUgWrNdw-xIY-X)sAE#8t*z=%mD>XiXwwDG(>=qa+gGF$o$^nh`uM z&z}AoH>jU>5udU1l+hqaHWs$n5JSCX^NDnl~ z`tIcZEbR^$;g6TrwLy-&fetA)rSzi(DyM;w1)Y_vXZ_|{5&CAQ|2?~puwdU03~L$O zAJ5-~ARqF~B&{vq;x~9dlwrf6QenIT+`jc(87 zGjwfYS>Q?@Yh??LD^7Osp7XkMzz|d_*FGE!s*VNQ{WlUv z?cLvqY75nfZbcfmdUf1MJn+EU2GHw^D@~Yg16ggIRr+c9V8s1J0|l0SJn<`9t0Qa1 z%f$);iTP!hUDRQ?*V6h3?RzD?iKOd!?y24KCQl8O`%w0NA}9XJfsQ}%RpU?oZ}y3n zovy4}W^4?qt^O#>UL(s;x?qZVHPykj#CECVmXw10l`hOFJ97}XMjnc->$1GX(RN0P zva`Df15xugFX}pmS&OdSy$t_H-hRi|?0o*^u*_8UmtLse8XMoRxH5p#fFnZ?Kv7t} zed7ZFO)xB}tYx~);|C&9&~yO2YJE~tS^MV3!Ps9-gn=A~Il1{|IMTH|x3nta*Huc? ziivICoAgDG>r2PGZPn>n0(TJj9-q~uHb0ZV2=e#jzrFqU(8J{>Ke&-mrLL%<{@a>R zs2}rjf72h_wIDPa3M{2p)XMi6bD+@?dD-g=FNH*7m6p66b8feCPksdPrOc6R^;0IN z3=4~2FCHF0+L4nEgO-{Zb#88FvkTwjGo(H@cue1LmfzR|^<3&4oaaJYzs3Gp(n$d>3(nHL&R-cvyBz7 z%9K)uUC7Foi$My55KYj9G_jG=@9SnaF(@9k2_4Qs)R zGxMP^a$vc)?oQ~63RU#YA9ap73HBXz94288G^iO*8xX1) zd;qyx!Qdl)_Tv<`h$qf@u*4+zK-6uZ&;;Tz0l_6`1Ngq|=EtTJXMWignZD)~sNs(B zAv97J_rHcN!9QvJ@ZkMq1pT=GweiLZ-tYAke+YB6ys^WS7fk3a)r85HEwaDaKvh+> zgmZUySQvif_GL?EqkA+y_CX=gpte&1Rghs12Qcr1UMxFepc0F$Em($z+ zf5%uVr-n8K{w967^?wZHNZHuXS3OGnrl)}+?qn*5^$xCi*NS}CVp*jTMby!pP0gr< zp+`g2D|DuoXk#cP!J?H#6aM;T}%GZ^e>`k)HXBU zSAy*cY1*F|o&&FJw;_e6Pg{A4d8sFS55vNzkJd-}QGE_B)vfcVu7V;YCs5eTbUC0c z7rDAq{4Al8lMyxvK@EwXLo#FGXM$^`#aOHdi^9NTdy9=|mWVzg!J4WtLS30eKKsUz zxeV>+q(}|+WEX3r;KX{c1nPVD%zE^^e3W9s%w`nuM(2%+TsGo2D-u}x5PgIqlZRy7 zkbmMk%_jAP>FSHDrHFEA(1(WKrQwP7T0*u(Q&jY;`E1r0XAwPp6|Pd`{YxRPIKhCS z#j95Q3V3RQ;142>M3h6rYBVmRf1FGb8;KLgjXnL%w8EkN`Uo=x>wzf(KQLRofzWbg z!c$=-nAw|U;z(V;kK6$BSy=t9SiQxy8fuAje~y-@^_TVs)RIrWnPYPzrG5B)Z(bp^ zP3O(41NW1rk0-4hfvCdEU=@U^Wp9P}vdU;&!pUfA=-co_dt({esxDMA9a!>P=Sn7->V$s%7T#}l$>AGer@5Q7R>yoxj^TySgx0U%oPIU-W6 z$}tBzlmg(g!n)G=tEc^h|Gt~Vh`CvCmPoMJFhb}K{VGF!Y!+>;gZ#R_4ew}HRD&yNoGoDaeoP|NJ`@P0i`Xgjrt!7L#$$3mLVQlEB6*q z_weE2k2!R_k_^He#5uS55gpWjDC?_+QxzJy!d7Cb87%39H8sK*i!-TkZ_bDpRtF3~ z2|?aoEqWWnOb=+mQS!kL@WS=+)jsgRZs747CVmTBk?pk-qMUHl_>r~WL7sU%5t@1Q z@-Zg65kkGDA;%pOkHKnk#&be_+HhHW!MUVck(8{zfzb2W4hfw#vXO3LXpuCogL3vAs*-DP=Wk~%oKaeYrMR>7NJe!6v4-{wq#@pfX3zN z%aFjNV;S-h9Iq9}gFxJ{swLs&#qgwERunp}?l%BC$Hj7~wpCUzc}m`sz$ltQivU%7 zFvstflFU;@ey=OSoQ&{tL(QmNz!Y+n(Bd1PO$*wd3E@0K!r%2ZZ62s%e>^4J1YXMk z9;WG;{ja;}8Ye9*-!3o7HXMd4rWSOyMQ9$Y|R7Zs>Z2 zFlhp&@PS~(_;ZD3l$p^8O2onNStu&s*xY_?H!2FD%51B)TpvPD3KJ?ZEOGEg9=qw~PTjmT!D zETcL6-B8umyeD!Cxn6ClPzg*gAW7Uc4`Kcke46h6zd7LfeB)&I&Zt`c=aL-xU)Smh zO_k+8aA#Y`!Emh)^Kz1(E)mgF&HzOBu@Pc9IUR{mEiA0?&K}f)%1v!V)aS3bmhdFb zKG;zta4>bnpZv+7QpWTdsVh_JQuFp#O_n=&%Bhl&shg>sjVw2`UgtmC_`ZLSS`|Zo z#s4RHP81mMmgAT2iAg5}OO6Dm5m$+=U@j?cxQH}%=}_p^QrO?qOvh1~=|A+<0`y}L zNn#TginOxt6>xG2xFoac6B95BJ{TfRYjxTNNKm{_$y_W}G7b*gd?O&j3t^SH-}BF# zU--;h(O*HT>r{DyP(_v+J6%rv>AQXU@9*4&!vCPK$=de0pp3kzl~&NUAeG^4L>*vM z(tI55$a6^UPnojDOFYBBii;;AxmZ>*>l*5&L?4GE2=#PTykI`4qCOymdf%;AknVa4 zCFvEIf0Q6CCv|1Rz2Utmj1gW5?m+-;j?a0d73hDnuAa-7*WeBttcl4&u2)}7K^8fm znZi4Z+mJm_*!@cUZM}^v|`NOu>4o77-J*Q*({lvU0D&Pa%m=Uv%CRg*C!A|93JSUq5{$6%ZQw_Q0=Pi`yRi3wPG5)0knE3~*IaL-aqy^b&yxFJ0MJ zTjB5_N3!JS^!lWb-Q|ZiLK%kCVp`}JW(+i=HNjEa@GEpl>+l0~dTsDk50Ij_w!HUXYH7`?SKczfIX zw1AX%KpO%lkWOZe@%0B!EA|o!-X1>2!b$=oVsVgMT-98w? zbB2&n4I$|Eqfk{@yZyMu3vLSTalJ{iqt^oEqJ#>Z;yfs5!qiPYJ%wuoqTHk!d9INY< z8a-F=LPn<24@(NxR^Z18w_urR@1yg)Wv~3S&-Ogs!h6)yqi?GG^-V?TOIQnzVAl_3 zim--e6wfFgGB&neFhZG}FO0N0FEv}%)2N1tklCpJ)Md8NF+_@@uvJDAAQM6HCcT_E z{WRSOFjS2D8v*O+WBYA)UvD_Fi3wE9b1$YTdw10NBGJNTg2T1No>wM9eUFW?ft4Fz zVQbU7ZK8NMCfQ69#{5?$YJw^;0^9W!J0<2H0hx05q~#NUZ}X`R>E2YI$4nPMJJb2qI^3uBT=d*=*qA0&CG}i#j5q{RxDH}zDkpf zO(M1CUu}nx1BlYmF+su~r@>$V2o8WfA0DfvJ&z7T`w7Wv!S=fk86s%^+(a$0qlhzg zX|Xo(jdr-|te0YNSPiQGv#@99<@KaVJVLDPrvH9VH0+TLbpQ5SzyGLuX8kP7L zhNVNT%`GFV|AS$IEGUW*xU_@Hb-lr)cy6|bcLdLVlk5L;0gB_igqH6)!|Qo6_;%$& za&N3iXY@-B4aD9Y(FF=_YbE|JYso6FqH9H;?I!F(bAMV#w2;1ZfTF@Ml;FwszL*m; z$sw^ZW129mBWi5mf@V1&$Qnbw`leM$i8j6XMO*fBx=6~&C^aj7?U(IRl_b6o+6wXC zou`?}aRS5XntCkZ8t;sD-LPg7(BWXgBF}4cv$b<`INvlStC#UhF^2#Y)FAlw+(80) zm9sx@=i6c58RBvH#h5#9`1hOUn!9bUB|eh$Vb{Fi4d>6r6K)%R3;CpW|lC$vYtAxHP@>Mn1rjUGBh&Qu7c~l7Cbxl*oy;QBKP6*1lpOx zaT(3nX0K&+7LgX2TrFOkp6R*>>Q+DJ*@8K<*?2j%pdenGZ#N&bhjR#B&&CCIC6_*8 z^nNYz0XFdho8{krv&wpB2Gv!*|66xMEX4$U+>ouKd8<1cFg4}R(KQ7Vlj!+W-~_3Km9)vOV7W9PRS3-bQWT=MlSwsld} z8A#o$Bb>4eNpU9k|JJpM(_ar^UVey1{SoY?$5mmU$> z0#A5Hnc)x}8CQLUf4Z%Pn_rkQMB>`pp5yF5PI<)c$eI}6xpJu=fk}Giwr z{3E7NSp5*Ybc6f(y}Ea=lTJ_-(_%pb^yi1R9UTR8xwp&H8I-qI>oFnM58SiF@Ryi3 zMJw7gw^_wn!-rQ(hU)M?)U9;|mh}pY=IB4#GffMjhSu2uuC1Co&uSiYNBmZ845kq| zjVhw=08d?P=;&K62L9hV%MOwxcl@OSXCiF4BQ_uHRce8tkwv7zbpH9rcW8>D-z*H{ z{#niIzU7ZZT?PYnBlsB?0H=8ULtcJilqGswQ_z*0W$<|ZNhBgW*5Vsg7lD|eF8;HE zgMOmJ|B~5`b4U|lsl4K%K|yK1;XCDJXrYo)*5fVZ8U_?+VKwuTj)4KJBXM5LBc*Cd60Y`vq)$Z8mKk3q!QX__atKU?<9t=iHN3LqT#t}yuE1PL_BzhAwn5MsR z1nuQR#;#N{Ms z7#%ZyKJlzS+MhJO87QR8<}H*h5~+!Pe?=q0l>J^$CU*m|Y*;QI^q&04(*Er05!Czu2 z`9Lm3F4s)gY`3|1uysjZfq5C>I?D6<0D%btsN*QJ4H_gXmzF%|Bh0ZatF21}msqHz+HjhDbbTRida*|1!;^ z)vD^XY48>a+2iZBo{cBya?c|9qaLpt_8%X_aK#FMdl?STJ*FsPJksHpzqTZ#UTp+= zj}QQ0viE)i$d=wM-K6CKU;6!Kyn2g`0XgAZ4cC+4_gUzY!}ly6v#i(;V76qFoDN`j zrygW%kkN`t-=A$pp3A08i~JH2lFk3gECXw2bZ$Lgguvb#!EIy%<4f)b_@lr%Y(x#G(bwy1iWs`qGXpw zx|}wxQG=EExBQry2-mi2^v5-Aty}j=H;1P_t%RlA#wXP$ZDl(h7%;o}yv?uWy+#}i z%EYE!jG^BMXmGWg zBLh6su#+{rbQGAYpvk9=wu<%Qi_~D@KWX8YvIislskn*?ZK2O}D-)z!cXj_|Xnim< ze_ion(q?QumkUd@vbHeK}(O^wU2JY-m**$JA`@w%g%vz(I*A%oVx} z&o@GtSDF^gCa@4q@)_YF8?XoTRl9Ty@>+kMjb=2u<@fzn+Y&9yAM?>7ZxpJIjBhNny_}#5XV~) zS(yB2R)g%hJ6Ae_*dXh+rqrgXm@xy#I`a|WeIJwVE{uzc*jT+ih`sOKwap8P5rXq7 z_dM}t(I+l z?LSE^z@~wa^>`(MNxM*cQ9&!=1j1ly8y{5bD97HHA5)ay7K&9%piC%XS2b|VN zALtrhk6i_N`illenDu}Y%!wv%E%Tbs{IzdoEyER;8o+wx`^Puy@0T2tN`JJJz!z;m zeqOcx3>Y`d3TslA@(|#ze~bsQQUx&hrt)2=xVT0JNbMhnq<>Ws05~s97>jHOC$zfa zLNXAR%Vvt&%ws!1jQKhobE=~w@#}>vkdI2go$H7@d%y<2WK?Z!e1%mBErRYQd-C*G zTK!|a(am&*d_096a{Z@xLgFsl&B-Ztn1!Wt`_EL7 zG8RssXi+7=_3G+N;gKoadn<^p=6>M`C4Et|cU|b~8QLsHgq4m+b zEu$}z7@Sh}H7{ct28K>?+!?j195jZ9r3qQzph^cv8^Dbt%A5I>y3;1o!DLqbc4R!RWjsP zr(>_zu5A0n>PUiN4z(qzra78V0lDVe_6`i#mk|8BeYa$Pwq*d%=5UkXaDsQcOSsrw zuqFV-t@}1n)^;X9ugMV~&&A_ki7Pr^V|NimEwt0PK)jTVO&H)?v)0ZsI+8(snzJ%2 z1=7yxN~oSvJ?&$p^*oFo`;U_ZU_^3MO%E37B9f9EF6X@QFIf#~TU#^^`<+LjwYW#A z(~YNw9H^_>Z3z7p&{`CC0$-;h=UZHMwUy3A@j*dkU~nk`vPyrn?Z=9k6J8a-D`s)? zj*+%E@mR&1ZzSIFg>P%=T*#?2Qu)MMSzxlpK?7=Rd3cPUZ7GGUu|o zFobEF9pb>6MaThRZ7=pOOJi6u806>WNsO2!G&cS!XWd7bClpQeuLVGc9EdCl@x-x&>+tU?AL;1{lB3R4#u7{tlWlI{N1pe_L(qm#~ z!|{3fR9GB*(-F|o4sr8Bz#bR<*!^G0`JpxwaOYmBrR3zjm-| zFL?p!ai~trjCe0!T@muG#Xy@JE1@TY9Y`Y{cpRrywJRcefrbawD)K1`rZTB^>qxpM z(;UV57)p~aHW^C#e7&}ApErLLr`zOhgLYQ^tccmp5bPAHF;`b99cwLj>)D&uYP1s% zCBy+8*Rkgtdu}c1T1(>30A1TlObHE0^KIY`4we8E4&Yjc2#^&{Ts@89+jHbmzOwv0 z=q51k%9ktKZM!kjY@Fybj-jeC`rPq*c`Ys{c48A?hFg^#Vgm3XaWA$5I9p>}qn*M4-!+c-TmuQ?*@6ik9`?B$RDeKh0&E@- zw-H|-AQ{7S#@lxj{sM+3skwX@Qk8wxc}_H4QvCa5R3N&AxzYhAoqwNbKvwa&NOc0b z(d@-5LMYb@*Yw&>q8~!cj6SH;jlMxu0szyd1uy79O=-A@Yi90Q; zw^$cw-R96Dh?L;yXW^Oof2fGCQob?>_B#JNi(nf9J)9PaXpi^6zn*3km@yyIF7g#LUKcO`f{=2lRJwf9Dmc62y2)#@|+U+I}`ac)Et987ICT1-uz z^~6|s>u`tx{u7;o{lV!5Uwv{3$Q4wCyp#nXFV#h3w|vT6%~7TKEf@U5y-dj>O&QT? zo^f&1YBGS-43ly|>_#p&rBL;~m3c(uH-S47K5T3WJ$FM~K3y!=Y~{=^Fw2*SgHj=| zdI1l=pySbfgs>-?@$-2w9Fj`GSnYfC+Odk2RoFsJ2^*fu7;iyzZteuSuUy1iL66(U zr)woJSKOVF*S&p0I6q(PxC680h_^#S$Gi4^;2A|rt8VDO$YfXl8SKMNoN8&PC<}!W z&vO{ox%J|WB1F2;fe!Sj2F`Ku(%scGkOOajFK!q3ze=Q0M?ZM3hEM3^v72UCj7lreIM~xIq{FGj#b|Y?FPFo zKuc5f!Q(RQ&ze&WyqTQe%`@yvO2t!~)LggW(6u|j)qcEJQQER4TOc7#XZtUU_b6lS zfwcy(l>*$*Y-_rCCRMhq*H@S#Ezeq-Y^P24xUf1)NJU@lSY3WNKcSV$RfN(h7lTuR zVbwf+%Kn>^*&TG&Nt=BSxhSbqj$VR`28CRY!7BuDGpF2PS;*J zTwlO=KW;6}O&mJw%-smUl$L!==0;Vs_1{E*gQ`QQ>bS#4+JmtSUxYpg6eE!c#5tLF zid&ou#yYS(?9~8Se5dyn{=jY@q*q}j9K5ef# zAEfZyU(@IFf1PSL0_52Jv`wRQmbK%_mKR2hFcg#CYW+TRV+#!J(9b%rCMZH>d<9ub z@BH}mDaPeq0O2Y$OL_6-+z8YUSBGUsi>BRRJ#kW;v#h>yKWL$h)g^b<|1`tAR(zH7 zYO(H2NH?ebAtRiZkxr+lzWBq~APL^plMCf;hPI?wUk4<`)at79;(q0(X-cQ@<%ZtLSOs1T_` zA5u8b)3YnfnqyDGCsCtbi~ek5u*(OG1`Gz##$#{>EG_Bj^-s0>4&s=Q-4?AeYp&La1EBUpTsE^6hM7`5H70&YmcvYM6uGV zDG=bzz~NhDJmWZ%{!2Wxc4B3d5v+Mo9Peq@OV&s`?CSH|OTNa##L9clq!-rZufb|e zt|r3AL~Pt*{Q9zClig%ok+Y-Ofl$IC+9qFCzt%nA{*_Gcfl2%vNXRm|IJtI-dQ2ka z(!2HE8gLzKcOwzxG5KASk~s=EfUffI$Ga+8gn66qTgCTfv|#^FN){<=%73k*(l`|O zb?ZJp?xx=zFi2vp`Ger4tVx>-RQsi|u#hOkGA}oFsRGdNjQ&q^TZiVpS1mQ z=FYoN^=rzV8MeN_IO^Rv62H5BbM~^(a@tu~TpP2s#^08Iqqhfaz-j3t$igBJ0(28q zd;e)IsD8v9)~akVf_4@^$|U#)9hqKuqe%Q z>@K~)dX5k9T7E?!AOm;t-iEc1t*Z>kH@amoeD6b(mDeNMWjH%JK8L31iVA~PPxh^o z-%0{(pilXia7r-Do@sq~_QAkxqw(opP|||`;_IJ_hxca-br_MPlxgE(8T%uC58Pa; z*c{geYYlJb54zw+9gI&uHHwN6HoZ#a5Z$7c%0I6q!@@?qiH(&)jvOfEsIIfIKO19# z3m}8*=4D`!ALd>Qicc))u|SHA+Z3-r9piCLsQEeI;}fXek^Vc#KEtRt4K|7A(>f^fN7x!?ej;yq8m1cZ{3j)_Sl$_r!AzO06`gv?>_8SL8u5*yCIzEYbs z@@`V_PP?^VjGeW4XtsB)>F6d6xgO-LaEJI}BDLIz75iD85ANlvrl2F|M6CpBhY*}1 zgAu>WK*v)juzR^<-`#oGHBk{4T#QhUzo+L+$fv_d!W!G%5TRzD#_mDZEjjV@G+>wci`hc*3iXnneNvqw90cDL(8S4#Vx1V59EC53LezuHbvLrE`p}dfnp~9MV z(Cc=?=d~kS)`7&N$*=Zlga3Ym4nCQjs%;rUgSNO)c4EOVW}ErPvMFR`5D$FRb}-w& z0&_2sxOwHTu?yNb3VQ0JKb{+ilYMz$_paE%4#((p5wwb0F;J;>#$l@d*Kx>AKqako zfA!*xB7q#R-O;o5EA(>{RL$1pJL*6`BC-Z{7K>e;IjFZX8lQ5$heut8nwbCX5xT|k z653mN0}AU}>7Vd}Z%|Zl*`7;$tNDaO$rl9oVB`T-bQZhCg(YTx zcTvxeB9gss9~!(`_dVO!>f#6*(wF%4M<@2UWEurW-rndyo==KeN0Oz5jnh!Vx$Fm-p_G94^42oc~2l7VcY!91Vw$7cam|@d-x5V=69Y z)t_03u%9&&Ah}@QO9x-}u5)QL8Wha{5bUnj{?uTU0FlGIKkfXl=C4|m+DLnuqMW$! zi-Iq^Zc~j`VPRnjGpd~ zkx2EvNlaBTv_V$O>Me+_-rqu>_*OJQ)Q7;p@LF~dqhd~s zNan~9`$Ctg)&r|dM)d}#G^FBZEOCZxYNL(S3X0HLGcD9NwC6B(O=E+9e^qA7>wo|( zCt&2SDi>cnzT-|D4nFQPo>Dx@J%Zl6N*bCV+N~T+7x^ zlJqmmN%^CBssyCHAi`Efkjv5r>1pTnlPKYf9d;_b)KLjNmcQ8#`3wHjUNF9ZIh=#F z_g^M;YF>Y`|ABy-154W8GNRab#DwT>c}0VCdxpZ5c(U2=n#hs&a!jew+uao6Jj$tx zg=-C1z(kLNzexxRY-G=7Fy>t#{A$mjMzkoje_uo0{eAtd9X5(elob^+skqh0e=@-! zAlA_w#U&0Pcr7nn7i`kF3)Bj1$Dde=*r0)P6Yb84+5ztX`@kH@nP=I zUkXe8KY4azKLz|j5#`YY>CFJu7NK>!Ck` zP{Wg$-W%s7$|HDwE=1x{_%|0E#^yp7{sRWzX^-whIEu2B=*0E2epB8>xIF|N#ETAiL7-_K{m`IAm{al zG|yDLH1z^LXH`pVfF1cDlCM+D*ieD{LkqU;mczsGcI%4|QY4OM)2R@$qhtH}ulLj# z8SR)SUjdW!jY|OzlJ#tiy&Lmxnadaasp~&qtjv!t{26<$k6~VQ_f3aOk?@szN-9Wt zZG;{oDX8G{W$CiZGy_8&)Z@^oL3+woA#}dwW;^Yxs-HNVKj`up+<9|*)`*0b-78;%bENsiW^8p7O zmim7;9f|3;@a9w5b(I}(&Gi8p#}H>QUad8TB;ys2aCI``L0!Mo(ET-2;iiDKi+;gzir#}Q28(I z#1Zo&c|E!C2tQ#-$VGoYutIiQ)BRm*8SKk@!t=%K{i`)X+s#j>0pjhCk}p?Db>lST z((G28jXLxoqAO_@iRQ&=w$97=w4>y(iJY#wQh%lwFL*eFl2ZI0(y$s~dVNHTfKdAy zRVvzC(coC>*LYt>?^J5VqNF+rmAD`or7X3gp=jBi#bM8hQBTf$^%q1p zK}6-#5Om0{OnySr?EgY;fP?>HgZw}gewB`gB~u{Gf*el~2IH4{Mg!$@=J#@_$)DV& zc58^L+ssrNkVI1i)E0{F-p*tPN4A{MQ@!hsStIQ}8_pBlD1LLc;*``8*UpWSEv}@jz6Z_@uq8FT2h0 z#mn@sN#O2I%WNc!ig|1x2p+q)H;AnEUeW~r`fpFkm&`^Yl5_}feiA*et;=T3_+LH# zDes;qUrtxGGV;pa$R=0VPJ`^J`@12D*0>=$AF1z<^779#d+WcZ}P8Fy^5Aa?>c?Xel zn!Oz@n`FYrn%^p|u+;uP7eKLO*I$qOJNozDyahqF!>BCl)U$#=e*^$;K*}ti|NRz> zn?9sIOE9Tg_k>Wdv!!S)TL520ytgX!`h&zIJFZ0vpHU zs(K1IEa_GBb_W}_Ua2w0QDS0lQ80}Hfz6P-Pi3+hIst1e-+xt52`tNh4Eojmfr;N0 zZ*aspK6yW@UTw5o*Mps7C5k|G$onP%hUu1km_0S(OLCp*8>@r}x+i;nU{zSzq0sbP zJJ%I?BYJU}Su2hv7u>f=!#ozaRF>VS@hP6#u9`wQoK-`k@kZV5SYUIoOF}RxIpH&& z3`3T1`V*F|hsF(|G#e&UB6MT4e{kJ=`FByI;&=Gl9?OTDN`h zlKXu`Y9p=9+Z5k+Sov1?I+Vt9c2joQ*Kh;=QbKRZ03HJVjc2b#7iNn#71 zXns~RL0C~PFOb^#X{;EMFM*sJx&!F5Yy%n0R2uzoD-TLo>_ z^GeO3Y_=@h8K9A|=t5r+!o!>p(t|IHM)%}^zRAs_y!MVsP%k!GnjRWYHbgJxt)dU5i1yCq|;>3zN6|J zhD7~g@E*oumeGAfrC_cvqu5LD&IN^+s->~u(843PR`8lE6jLZ2wZzFlLl}?$J*_Qz z(A4+z<996MAdz4^?SoMhb> zci-{O`@3pOLB{u33U2#<_o2~2MZLuRW<>);3nU`LQ**B~L2fCETH>NNcGG zIqI`Bp2lmVTnFpG+M=rPC>82adirVbf6|{WU|tUMltc@DI$VjkZy{>5MjzU@hHbWE zKU!~xK6;Karby&XzUO0VJVv`cs*&=zbcoG3$xS76f6BW{%)PoBB7lMEI=EC|} zt=yg?=;!Xn+s(fwsE4zCuMS1z!>l$M$ONA$Q2h!i_a=xknlbHC5$s2UgDe{DM>IeG zs*kacnA$bdp9v;@24!-Mg(9AAGtb_15p(TafN*J096}N+k`cw5!3rkRud5Q5R>X7l z?NDu6gw5A*1-bQVpAEBq=2D)rMe>jHeIo#^E;jgq zgD%q6Dx51+=>ek5p2GPBC~ePBQj=&Kx<9x=Vp5xAP7Rrux7_U)ur|B8ppl$N#)%Zf z;|sMCl&S529l#_ZLH{H?QgwaZZ*nxsidkkS%Thx3v?-&h-c^{P=0g|^hK4@Z$5U(;vEP0&=@zP>;p_msrKZL4aMDW0 zb#>_sTlh#%8lV}1s&_i8wcMC|C_SZuR$tUKL$Et~j((8|A&@k}N9{iEyzRcD;9nBA zD-X|pw@tvnDd2B6WIM0Y8rigjd(mJwN5aeVyI2K+4s9c*f9&{z-T2tNwesFr<|v`` z_juM7|1SW;SkAyEYuZlVl81cn>h7wj&0h zIfMQcN?h^#&lCdA&#BFdMREd3N7tT3g(Y3Z+(whBv2Wkp+BGS`cqlZW)oP$cC#06_ z0-HmyC8Ss=^GxP%i4pCihZB|3nO^^dZjIxJ*_Bu+Qh8`R6?b=~ z{)^qU)ga=uOxjxgzcPyKu?kfvEWc1{IF=l23t+T{$6;!wcO(zjKP0nP;8=ge5^!WF zK4g9q_}nYs?uUhA1$4wsK-mi_1+?j*vYvO0thqEJ`p~~dXq;{#NKOQ!mm>t!NS1q> zyKUb+qMIz$;{&Ox_k6CUTahf+Bq(o#;|3_spC8z~E*0OOpTE+^-~Y9Jy`TgQA`n1u zG7Use4p$rKr-!8&%~njM7L-n7dy!mh>Tmu(lLvxemwj0DZM1{L&2uHKw6mjj=kodD zptc6oLI3>nq|g5HXpXV5;RAzGo2A6*d?+VU7EoTcktfZ%DVp?*o=ep^C~AI;b-b0j z@vmt?Usp;5B{PoTfoA)tq(r&Ot0~y~!Fk!~6Yu_h#zcB+u97Cvu5-_^I%&J7z3Lkf zL-*rn{YwW;6m=`V(=$w+Rrpe!4YR1}d0&yWc`gOIu}cRWso)7Ck+|dUFjF5c=3A%| z)c=S$3w`~y)95ur%CwOMUc3Y-B-Ot3VRP16?`CUqaKrSR&)I2e+QA@Ip5GtJ^u>U( z85k^)Gif!V>g(-av5SSyf@<4+Gu)*8jyix`%u2JWyEj*w?(gsiifEKpVv42m?&&Th%a85f< z9JA;48f&FlNcK6NZ`-YW!j+mFe92pR;I+)5>uduYib3je7bx!8K&{I)vX~MYS#0%l z)bQuu5Ii3t7h$~I?jo1r11Lga|ZX> zPBY8AB5>Xv8`Ra6U~BJ5(74)(ZP4bsH240}kZ`g+*;jFK(qGY7b4a^6sz`1hPo@+0 z5eN-Mh;6+7AT*ql>*rsK9A+`f8;oWN44zPE8P#164(0`Jk#T}v6qR$##z_SAy|G1a zPF#@i4ER$CW1g~Tjqz@-8>80{8rZ$JC6Pwq0KG;CXdXcPVAQHNEF2#I!Ff(_d zdH-L<1hw&~qE2&uR0H4Je-DJ^*ey&aT^BsZ91o%tjj0E?qti;2iQo<)i?POq&&X0$(3LoUWBDjr6%RvL zzN~b&nKGE8wTT9hW*+?oCI<^kL~-bqLHSZ#YN-;N`ov>_2#9EA?$N4o1lK7qTgAlxCHd-v{WpXU@Um z2{ht>lB2`tT3F`@_kGD114$C31BB!uh}*Y5u0MCH3g~}zxDbB6{E9Qk_v_=wTWOhp zm5w>zkqM&!hgzfpb@L`huf(eY=?Ll9Sb_AZN^M+9S@ysG-2e>DkUHznU>BE~-;F>@ z>TI&&S9%!S%dczbE01Jcy}^O)xZ5jrju-)@j}3Ow!U8AFhsA?~XR!&})a-xcZAue$ zTP`n;t#`X%KkY5e`TX{VY10Ev?>0J4;m5T?W~obEr+rP%GB(lD<{yjo!)?CsYxu0Y zU8`cRCqhC+e~ov15b#Rl_$8e-69PhQo6g|&GUQzpN;FB``ml4HM3^Ty!%@l#_r2* zIE8TWYsR*c9CoA+e=b+sE)K~Nee|DVA;o8a=J|CEB=o(5&)z2Cq6%U@S;OKT-X_b7 zwQHJOo}l+vP|Kme`@3SQ!cJdCjDGoMZcXPDR*j!& zxcCCco-Ya4CY7*4QG!8NX*GJBdg4v}xu2?JAH4CFV}^9NPtNxunu2zSe7fv5uTOfA zo&DbbmgatPC=ESV+Zp$Gxv1jBvPZwF(4O_6$JJ^-Zd3yLayUTb=MF@=lH;n3fw^_p zWAV}!JxBPp#&bcE!m%HdFgsrV>#!T^B9ff{s{x-T#NrD}6@Z=8Y}ZP~dF3EygNK0P z-N~!PSKh}RZw^J~BL5ELRO!Qj^jxsbNRZA&7p+~92`sP#Xf?i6%8tqqEF$1N0ZU2v z0{AJeB2wClPe!;1^i|1;Sa@X1yoR}e0k8J1PQLMG!=~ds2z__FiY62Pb8{3SoSQkOjg4^tlezfB?k(0)-s89 z=1y@?w;(9xs}p~(pm@)V0CZ--)9SB}Td_v~+ysartm{}Pn}yE=N$85{aiVxNM2GC- zMWLACxijN$M%=Lv(F_>)+z_CJ;O?>s>m9Sa21@mMrt}^ zPGJV}HT{#EwAgJj%xQMzb^7UXq*-;gTV|`Rh(CXoh6CfJi0)dAuq-9T&6d$1ZKi3v)?MQVgIfaL`lN{b2!6%u!q8MIrRPZ`^hn)JAcnA$v@OO^bS=M%Zk5sFG|7sp9 zotR`I6u}*b&G&@jA6^%_QF$KNp?N z;ILp|^wzNt3iAmOI!9&wt4h8z|LE^j4(||8-L*MH1Eff%peL>Dcr&v0Y#iO^ z8pllj@_GmF)r{CyEoq^WSj(0<!`!h;_IZ;G&- zWm(}<#l?izsfY?Ljx_`0^mKk0)5T*`7RaU1220v+4$&s`lKyC&+I8VA_VLiLP*T)6 zU@7Y@H7Enr0<`Nm8GOX@@~5y~isCd~G$Ma@)+U3hBc}wTbXwr%HMHI?-O!2)SO3@3 zi2W(&IG<551=dNg(M2>B)u)GazG|1;^!$xj+A%fppnwuk?I73No>b%H+>@Hu4%}Sr zi64?B^Z57aLyp0-*uVqB^908wI?3Z*4YS5>x#^#6xY4z?XkM2E&6b1Z%SSiniKW4( zZX0pN$(xsCmJ|iR}k%LC} zD1aNP>c+2m^N3|x`|M0!Canm6?p0xK)d#YFJv5F!qr!x|K^`IgS&jdrP3x9r!d821BhduDae zBh#mxK;!~HFCma<+xrnpVWHFWaBpz*BJ=k;PW*&qSXsD~8~66uJ>)%7-QY)0v$rbN z{Ay}}AkQiKh2F|Y>HOPOPgl>?oj(18TX@k+7{#;F(xD44<-lYDckGT4+xTn$+ng)* zdpg|*V&PLf^J4nzdK+jPBn)CCQ_HHfPFrVGHs54^Wwfog z*PCxe#J7SYDo<+>&L!HY(wUz{14zK#O$cfS2%@E)X=}+UEF?#O=^k~KHrdkO=u=_8 z%uw#Qh!bvEhY4gGFVeB~Lp6(7tz`sbm+2zy?w)|pWF}LSV^HLxs{=7?+is7*(Kj7? zXfltd&WUWDv;YpkK^X>?v60Q8qStdD^EqiqR1KlP@T_f-%u6o4AbJ45L;O|x{t~J{ zWmzBz3)f6f4?2EUZqgFQ!$Z+&{%&r({}pQb%UbU2Qm0Lv3tQgf;ngW7bJ$W`iH zk*HZ0H?lq;QZ`iS(0RN7|M$8FT&-ZT7_~ct@^6kURLj>t@Fsw6^B~+HT-=a4_h2+r z$EX+3**~opQ_bxR|1DByrU1D4c(;%yCYA~ETGrQN?51{ug@1m*LD{I3((lLuj<9-( z&@D{p|LfnKyAmxdI2yH?o-L%&KK>HKoe)WV>)n*|@<|15H$%vRd;`rboo*9U+_pDf z-+Zwky#2v0`>_-9Y9Ma_P2~8b`m!sQ$~0awUXASH%YIJKX7vXX$yT0jwmr2gSKLxC{SyWd9D`#aEtQ|9 z@I#dS;B(Z(5#NA&sG`wKwaj!hZMbLS70UgiumKrvrbZx)qP7wwtEy6me!- zlrR3n4hFgV8Hj#lu8+{RC(xe z0ojhX=Pb6$U1anQvvo~Ug1c9W1Stq`u~6rAur!ERmf`=LBjY~)W4DM9uD((J-%H<$ zjrdk8IXn`Pj8+5YaQ^tJ^Fixm7g{@P!N(#un~;>vHmxBugqtY6tn%mjUvZYczQxJd z4)ooUgXtD~m^&rEe+koZ;8RUBvKCq?2!TsRh9+w0V{K9H+jREUt3?HMjR}ACEBoE4 zp011C+s$pzyjlw%V!gC0{cIh&;Er_#Q(1}yk{xuPfRjVl8?a~g5490h?B_Sbw`eC% z{grxw@2NnS&hfJc_w~#lcvovd=@ba~#Q;}C57=_WOkEk!0tKunhf|A>FgINbdS7^W zTkvwLL>xIJ+rBCmrzx=}UJC^S@(`Xr(28@HqI_t#0TqTU07uEQLFhtjYq-pGS7s7y zUD8>ILZ93O*fXqzsM(PVF~Y@+6D)cn6&D2s39%Rm>eUZRSQLE=4aM*myWD-nXQ*&c zmoD5kI5H0L%iHSwo1^m|9*1f%>I;8OEBppYFFc=;RLJvR^V1#UV#DKptX^s9Z%wU| z-TCUc5!N!1l5Q$`12O}mM z%&%R!qmI4bs8lZBIZFjH2;bs8JP>~-MaHhw`m=y2LA7-*KblP%rT_;6KOcu2WKKC! zRj~f!M79a;GrTi@-Y{)@V+b`l0)1U_?Ruw-r`8*4z*(+svToGSwl%fv^VCJk)6p=$ z$+~+$N;b-z&H7!%{|C?BLT?owp0t#g3Q^^*)uB6V)ascuWxbXb zB1oIs8Vr$X;~ZM3sITdHYm8~Xgd%j+(=I_@7Jhi2n=g}oSo`M*qt3K5y_+O; z>hiI-w;#WXfFmEiWkp6R6l4~?OjgYD(L?e+L0fW;LjKBsvoX0(gA#M|2O$| zHW!fc0%8mwK3^LnB$y76*5p|u)HXasiWgWdN?&7qh_?P1&MPb*JXKJp+d4lC8hb3V z;|~Y((bz|L%efc&O@(v^qai^P!6nb1^fZ#kVw6J^66MfUdh@x!En2W>(L&x%X3vWY z*!92er63#8^&6j8*wH3uRR;#%Bl619+x_w$H|W)m@fAgWkv!6gM0jMsc#*8AY5IB| zuT!xQ2X!kbe!)-LKpHTA2R@@b1}#Nx?~^o9a~HqJi9*B8YfAtzLk;>=Abjp7^KALn zD}~+@KKn``tkLJ3QeOG$ef?cj{52-_hGZf+!J^F zrD8{u2@%KqN6oT2`~3dLY7?_1^`X0C1F)?vG>zYt46!e457Xf~M#><~=_i-!1oMPX zE(nE@qUDoKC7PTzHgCY>K-DK$M=9=G}6Fwnc4N2o2?f3!cw| zao}>>H`~-$qhti#l*WWMEjR#5U2d1%74660r7Gs@jou3A5IG=Q*|+2=>Yee%KcB&a z85h&HOKBF~B<#>!3Wzuff)TR=$LK z&35Cj5anTz#mVt&|CQ#fgbNK$QfHU?yf&1Fvc)_8SR(FkcLw#YIr<)(ugS?ZOk}b5 zBA`!hyYN+6k*VdIwMyddS`>U{?2@CYPt}Gil*=*)Y{L;_un3S~lX!Kvoh_wf6qb(24$JfD;NM<0cvbasbn2i{O*a(rMU{to3y z*ZL%I*3dS(_jCQ88Qsa9B-*&ZDeWq=C%+*1se-vDjuhV3_BZg{LOhapYC_HS#She% z)ZME1>>!q;MAPhF>qhw1ZW&QHYNm6B|s%hAbLaoZ6}-Q z{UmwD;1xRCk^v2m?uAR~~x zkun~^cLj6++n^xHfEq3|Q;hGtU$NVIrB9;tt%-oWGjRFDwgAggoAK8}Hp*J%M|{!n z;$zXn)Y?5Ib6HvqaKL)ie8fY=w#Q=LZ^&?E2?~IO0Lr=m-bUh-avk27y&3Tm8RLol z>zX2W^y=@3i9PEQ^YjqKAG6M9xT!9yLz ztaj=$z1NtSqWSsBu@=xZsM4G~tU?9~*Q)QC`i@-IU*GJddJkp}vu_S+pP9&t-KhBnH>JA}5I-;^I>4`j=N%`j|(hjVAFnE~za~bhSK~ehQtv= z5?x@P+kEfQoay=R)9G(2>Aw!dLU%_|M-N=r>5zk+hXLWqPh~gv&HL%rThQxgf!mHC zU~f4Ce4$&sh|>hz$oQ63J-Xq}K`M65FI(;(Rhyf6t2^OKvWziZaCw;g7a|9)^2{cV zc{Un+goJb^3)}7`G`MZ*i(GxTye(yCK#me*e56F+*{}3}T7bm8GKYt*38jn!s^gJ} zXVr%AA3xL*ml59meOv8npb7jj6fVD<*=}i9K!1hE^4?x%o#Fa>%BxT%=mu+jor*gJqwjU}fKZTJTz@agsLJ+ApO zZ!oKTg>ID}PZ^qHJ{S+5)(cC{&f5N|y*3zD*k&Q{s=><*xcDq6RfX-l!`elp*RI09cFY7b`8(3JnQ}nfVU`!UPz?aUG{X570u#L)WSDx994{pGV=PC}@)x4W?Ya9GK4PwtTd+`-KIX(AiE ztnu%OMo9vU6ukS)d<`xoC2B9@k>7tx(*^4hYXy46DjNiEjw!8E&_ovBaHSkwG%pyp z$B%rwqLmI68)wk3;LO=Pl>=rdhYA;o%_cIT^n5X_J;AZ&DRjV>R=`Dw!w2^2#E znp}cwVY_3(JSWO#N(sVEC%9nL&1-{+WG?%i+kFNW(n_UWjcjH994Io95@uQr3yu{u z&<}hgQ!r1v5va@P-9iaCol8nI+Uu{sUQVI4{}kv3%Mm2eoig z(zhYLqVkDyNbytx%yBS0(l`sl^6~sVG4FOy$P_+OiR%08Pwy#a-0%1Y{`e7|s6bz# z2~A_1bEa)j94eW~y4Bsi4`UGUzOWxni`T*nF7;k+E1`!h#(i@`-~tfH7E&q6J2x=H z4q0XGw(@`Hk!jD=oSr^nMV`X#!O(DC)+@zlYLr36$TRqP)04Z>b59GCs$(Z14W}W} zL>8zqO-%jPQ5X1C8m;Z-PlNrxa>PYFQe_#Nu9Wc^DDfn?%pAMcPhTdo{~UA8wGZj%Gm!I0x9f z#4`zM%b1`4Ym5zQ6yj^A8Coi0-n79%XD;X53R5Dr4-t*+s=S$mZY5Z+1Qgz)ebK0i z+0hA5G*-f7GvbVL4yiX?TpT1o?GK#6$xJMTg_+(xKjG)9;S}33-}u8h z`Vrx^LlMdsKX6)Be6pOfVV-aMh9#?oLA2OZZsOFxtI6T*{5k|-F1#ITzkwkyD{^1YIn2rYL5^`Em*< z{yjVxEfkcYvsgbaknkVzyc|idPam<8#JG9=E)qi)^?7oF-VA}|Kk!dNjyu+3Wnh*X zi5D7GR3w7&GnB@_pPYB2AOQ{@4!Bw>C`6~0XrMfwwZ1%(NKCDVRwovnpoYxtPwi58 zMq$!c=9@okyUS~8%q0>hOS$V}ofJIHIc<{#VRMq*3@cznZ{UsZG@GxyH!!VJ{!CV2 zg?^=#|B?Xda@5h#{w|&p&n#;Te)0OSrFj#N-^XcbkyOcIp2eYITWkHa>bB2CUE8` zX!~XL(!(8=P`T~4X+@tlJwKriLMf0Wnkv~Qc-3s{1QW{FoUF028cF0anfW)$K z!v9cK=!~jS#dfMmIZ(a`S{cD;IJbOq=oDN6+mbA5& z+1~z_LTWaz6|Me{P`m*6f<7T$k`^_@q_MkLtTU+*vUbh%p}e^B$JAHS^ysk-fLE^O zlItg6U=S8TysfZiDLjEb8tmUJpW(D?X`@bC!EFebgjVg1f(zP^Ur07b7HHJnkB|NW z3O${Js-YcA^CT#BdDaT`oa{VNY*)l0Ho{6#TR3X{d`?p z=T(ir{tjZBQ6=+$Q01EqMQ>q+0_4mME=qa^Cp>WV_}0xL z^6J5uv^~2bbhoHN@iqR1>QMt_p|ZB53iVj=DhnP}9mz2PL_&z~fE()RGX;hT_d`gs{nD0Xf{}xX_6A)dK8` za>#OQxeEo&n%jA13-m&eRF6VWvUjyVxV1?~O)tAhe%i0H@$ZOC__Se}1QK=u?I|j; z_871Xc#|D!bFjV<@Nk|J_M#GBkC78}cLurdQG*qrdSwSJ`)wfYCOx@7~#G<|1-l=LeuE+Mm$r1^WxBcQ_!QdK%-djtzH@!mq-0H zB8~N9`Kn#U{A;lqJx~`Z%b@#^DoM#rIZ?lec8W-{oFQ?HrsaqGpD*vDkjx5*WyoIz zc7)1M&E$pDni5s-lQZ9GmE3UTp1Yt|vMt7GIpxd$J{9Yc*r1a?`B%`#Y)CNfwI=Pn zmCSQ-?1X;jGt0;$!qy&~Q~6AKzEl<&X;&C7`&bcX3C;o%%u$ zd{hcZs@kZX$R8Y92-ju;Dz3cmGSaR!d`+_oU?dxrl z=Zyytd$6|EL6y4lQi5soZqj_P7J?fXZYSX2G4Y0Cgx1PkXoqsCYkwCpye;^t+@~TI zrlwayA+YdHs(0uRb{plUM9}+Vmk;M&60G&yMH2i89EBzzquT>Wfy@W$`N@lf%Sxu! zJSt4U?P{ttnTdXf+a|UydaQTbv#R44M(PBWry?4UJam?}kC3Li@F^QD5)2d#`MNWs zX}s-HLZ@tnWOK)O5v=rZX>OfD^O(phCO&bWde?dkM>S|N_^dObDSK6Diu9pLN+Slo zZwasrE*O?j9v`wRUM7;T6q@TBZD4arsZ9Il*KBSh)8jD+c1%WEPfF@Hx!kY@?@YR=NY0D8MPy}Va_nXGEqKs8kx-!K8&DHl zuPiRGn|8#v>y(P2?iXLYdn(2Rv%&2jl$F0C!GZsR8HlE>g!Up_v)mpfIBG6VQY$Fs zARr?D?N$S@MY`YL?V!&4wYU4sO+WS-lI!K-@_n%eNf!}{ z=5@%Fl11pC)YR3*Q7d5G8HhD#_MP<|&hb3IVsWrptP#=SJ@)F-^aWM-?9BaOpVj`BrtKhH%IQ7rmM&e`g9L{GKhbURxasMcM)< zx7fj82eQThFZmG|0$N@CV}yn}0sBEQ^*~o#SSS^;K+*}CS|?-JwE+BafZaG<&Fg=_ zQzCZz}A`v z0d3ExZSPZ-!19kjg!$$N)Q z_qCK7)>z5IU5jR}Bj^7ze`A?}1*grJVY1@xjf6BVy2KQg75Brvw-qTHc!`T`(iF%Af?XBoMOVikAB$3FxM?6gSPp^{>M;|iK%{DbRQ@Ik_@ zZVzRHNEt&y{DB*(SScm1Tv3DU$+=(-;onq`a$tMPYTF^5k?8WqxoV3SSpeEAoraIJ zW~N^zy$MmFfF2OkK~snX2wsObGgEeSzI3{O=VnKdZ# zD&|k{Y$2?8es|IrxhA;vg5>kCjAVAXwA;aZ?b$P>_R6L3FldR18LMbEZggGN zs3-TwGTGjgQHM*fmwoL72nl0v)-F~LO{WRc&Kj`T2Ni?MzoKJ+zwd1G)wq0ots5v8 zrg%zbeLMoz&*jVYEgMUBa$ zt01~;gx1>p{=v9Cu2o8a1{TLoAUxvFD|uRW)>Ac983RV6cf(}64{m5Fr4_=$zDPpD z=S`IZmuYpysyt658|U)&%hsDSDh0ZY>f``?~Uwshr@m$ysYip;OGP=(r;sY&@5soistmju=RuN4{9)MO5-jGZE(l};%)S2q50b45ap~ra6Uix197q* zzf-45>`3^^M&Y3GI7*r5i$bQk)F;UC$eG3{QQydUUuL{?tOc_0Le5*KAXf^%5?N%7 zfxtmXa1q~v<(G9ciI~QIU5DmdbvoPIO6Rq z(P!br;%o(Kma(2-xR$8svzee??Lgf#p^|WW8O1*uH3dXvJa2)(1C$*gacwYv zrB(d#_iAZ`H4WKEus$UYiA4@6X5-$7si|aT>t&_ZD&fWkOF3hNW;WF)`8lWUJTAUe z;rYZ3c<4_1$sx8~uNETGlfM_A3l3n3+(%|=DL0xTvpfFfDUE|U0v(LZD<%E~ZCajO zBt2<}TI2XQ9y@v(x)5{x{MOKt)6MEAgTn1tU?-sC`1*^-exW?8Ogt+UW&U>Gi9nw~ z-GZ@loh=aWQsnI}IKKOa2Opx4!K+nRbo--R6A>L93$=SZOU7UHHL2k5pY^|1tZDj* z!~>-{lAqklYWF_D_<|cYPCBNWo^397uB`C;-Obg~p;b_0ZipkL@&Fl`&ZoC;BPF55 zIYJP_JIOvORLc2RElcHSLUnbO@nN=)X>MIn9DX3Bi)KHG>8B z?1=8qUZIzI#9e$*RKZLM=rxsdL~-X2yNLLV`B@I|2>9fvy8>4vMxL;%|0&rsEQc)Z zB*3K;Q($bl=|(9_6GpAU;Rt<0H80#|E9HT%m)Wpy4>W zQC-@2YdOLA^O!RwMjzcKk@5?v&}Yzw5Zzx9f;VBh%@6MMG?3Scm&;u4R&AX)M+MSy zZ14Z%!(UXS5A=Cyke(3&ftt_pqKircamn-c1KAO11kS#cucaZAf=OMuuDeC7hODIV zB6tHVjfH1pd`t3*Np8|nQm$9)=UqoDGK&oro9*|m|K_LMlA0vdI?dHFqn@~|+@4so z?|jh2%zsj0Apb?V8>)1k63Jtkh|g9oXQ>%#UYI2=MP}mbY-8&|-+!;F;|(F36qd*9 zcsK6L$jA+Vx*A{^`N6e4cDs`bl`C$l>&s?*bNPXH^SBrP;zJ}VOq=m<^5i7R-l^Ao z)DcMVrl;%dmJ@L_LQ9?HdI+U4@iTNZShLrO^LTr|*ejpz|7wENy;7}%HR1U@c< ze21M?KkS=3J0Y)?WZ8~D+=y)r0Bk|j%VbduLUAqB_N9kh#y`u#(7tL`FQF&Z6`r{i zxpC>j8%fv2v@u4v?SsDKH3N|Zs4^b+Vba^i!?kg^jxy_MtgxE`Uh@+yd6D;=VeDF! zG)`-dX7g2eb@sbk%{w*LYwcIC%u z)~)At$-#;pH6!EORMs~&H5Xv_7ad7VQwv9sw`3-~+mvFUTJGJ)JdxhTgi?uQm8Q@G z(N_p(dAYF2WsUjj^v+RB>zvNXQFA21Xv5XVOwrC*%~fK{!kB{fUt&mK4rKzjE6@{7 zRhlpX);EnVoBv~j7rFl(OZf^spNhHfli5`hnzQ)G6L^R9f?P5sBby^{#L(a= z=wwyY)k$$Q{<%+5!07XZBojw9nNc&Cy4W)Rs!!^nSxo8^3tG!OrNX+HaDthL2d?JH(bs02u}Nd~uI)0qO~ zPVM+Zbq%t&Q#HTKvdaR85RDV-a;$Ly%}P2ooW7NSVAk+_brCATUtm}jXG9~ zHZc`+bwTb5Gc~U^&byLQ=LJ=q>NgjoTpYle#~jQFrKJTWD5iYc^|;u2B2rE3!~e|` z=NlVl+c#ineBZ3~sg1f`joDnZ)6lE4rW4dlrc96!OsYR`L4A^A&3p&aK}hz^a*6UBBAIlRq7BL4?Km^ONWN zkAa&1O&)gYyOE%$+MLskFcdQv3&OJ6##}WVU+M;`ZbunN{QBz{>8-1!a}bT)<1trs z)`t&aHrmUTjYkIg3=!w!Ojd{bOkZh>^5~r>M4EwiyNh9NjaQp;48s4J*L6kuCPe*# zBH=f!>o*nwsyhA4&-h6?Uf>wQ}>QbD*V)ijESxC{);69NmzJO8&%&%#3a?+V)u5$WSX97 zrp9&a*kgk_fdD3?rAr9K)Q^@lf9BTrnyq|nm9~$Jr*~uOWXZ`=zwru-kkFd5$EKKT zu*!66Gy}h@)khf~&HZcUf!)8Vm)h(auBjEJoG|vy2PBiUK82APleON$ZQ^u`%t#BiCz>r6lt| z8Rf~gd^oBR2;virO>ws}6G5OWK|$k%($oT97YkLw+q)`on?D-*QLxA0IVOdO+?tRkE3KCIr+@-qqi-) za_41>ar+{bBL-C#SR`;tXQGwvca~@;ZN$OFiwu$pYB*US5OL-d)vTY*Wu*%8S^_8y zELOw$3uzZJM|)TJM+X4{@^SNmLPr82rP1);Dg&Ww*D#NQpMRk}d4}Nx%6-F;`4HJF zC1zY19t=$?niJebzI}^UkSr=sI-k@LBSNzv@qkH2({CXlJ;~c<8sb!Vuu`^jHZn6b zGV}Gz-wjZ+LD$qR8AsZDWEMEAuaerN4bV!y^MQDy49w$wi(aiIQ)N3*pWm^xx@s;R zn@W6sr_WCERErl}nT`Rl0mV)eTN_H&!2`jkaEFUpq%5!k{NK^SN(aV*1pjtbyHa&p zvVY*xRn_BLl7imNN|wvxICv^e<>LErr6e)fxBI9w4qZKDS%e zpzu@C^bLqyZ?c<5Rt2n9b&X1*_i=eU3jilmMfZ!TsG`Fyi%bv2J6pB479iY}9SRy%_5ZX0(J>wm_iF+d2YOTd zEi*iL+(gdvy(w5;50Cy(^XW)2+L1^2b`9OPjXjt6U6&hDJ65&TtKBJ}^8}~N3=9In zt!H|1unVafF}(CUiB`DT!`E#jog2eH`~AsD6(AMda1&<7F2p`rnddtx7RfaR!N*sIG* zY~`l?U(0JqrBI2a)l%OqQinDA%+*0AJ0&22!e)si3O=<8lPX)CsD6?w5HAjkiRk|3 zaPmayy)NQ?gU9|y(SDWUyMWQgQdN;N=0xRPWS)(P4Q9gU8UHIhzY1dqQ(%~hP4|o7 z<)VS1_vpc2lWayfYCmgA-ZDV;ESULc{f4!VObKb~ls9FiB^KBx<0T|q(u)$!qObbA zT3O3}ziHLtUDfi*!nACD>BwJ@mYdazOe-u5rKjm?(ef2F%`HfiS4w47)hYtsww&qd z@VpM31*OO=2HLKWup$5l1TNmt4Ra91GJ-2!ajhK}3^oAKI$cxL=ot2WamDidQ?I>q4eGbw^{AfxLn z!0&GnWaB^2ebg*%Sg!-_kfp4SWqpv)U@(7AM5mTPeB_+Rvk@jDMmLds(nv zqH#WDcM13+_YH$6)_Q)^9e!|VYU9+Jogfq?Z0voWoxffC@-23HQFEv!u9Ck;ZR~P4 z{O4aTScvrh+!;X^0zB5f0&HaHERN)`q)j>;6#5$jbS(>pRT&w-l*nlgV0mse-(b@t~eY5uLSp#||x|~RhFmL0z7DAJ_C=o42 zT|5S4!afhD{P3?Ct+q!qXB3WfnpZCF1klaQ)DS!>9?5AEeW@9SCO#83|6m-=Iqo%A z_gRl(USA)#pIWkI$2LXl(b5VZFbP8*m_nX=!UClM&h`Q~X z&1WO!Fo#@7;njy`74=;x*iRH4hR>Ri?67OwMV4rsgE>P#v6B?1ttJB|X4lt_6U|Bb z$)5u5_E08|ip5BL1!_2dwjAjQkn@uJum_63)>@4PFGyA=(%Sm+)l7p@baeuNscQT5 z5b%5eBsr4|4tPNVnE{)d|3G-MH*o6#iXu>LS>lOavo?o{hZ&n zb%xWP1kX#SFxRX>VW~k`6G_>rE*gzUvC|B>v^W09UukjOrle`=#SnfV0YDf|3NS_Z zmGCwzg_eaKrET|x*pVKXOrVSSX_IhzKOgd;faeK5_3mt0u*-&m z_3E;pf`C^9)eS=RpiQ2(kTVI6p5|?*22BG9+Mzd5LpoBRul!hp>@vp65;2VoVLfKV zhHL1v_{)e;nK~{*m6c^VZ$+L|QdHjk(PS124+_4Pl0?`Z&pH`-Wij#|!mF0+c_N7j zA2v8@#1Kk_E8AOTCsw}3n(gK%)#@43WE{E_MnFwLgjE_wnP9r^@)b%^X6jIcLqAdq zRF6U;0NMx093Ix5`>H+4qDB=Zv!cbI^T=}^pIDxko?rsL3c1Kmj5Ot11aU_jx`|LR zwpF>%G3%l^1yKBSNJR}XVErUYT1c)sZC*|qY z>97v0dvU(8<$U@PwByrM@AUq_LXxc-jMY1Y8K}- z+x7;GZN%vo$vgtt<12A#+~~5;?ak74yGDK27VxeOnr0Qu-yenUCtEcR<8*YPrHjm# zQ6%^sct2hJ{S`^M{MJ9vI^`9}`{>P^Y_AC8+a7OWNWC#>w&;QZKiI68I?{ zmJ}~`H$)$=Z+r#DP=b@{VmlYwKCsBpC2*q>5*mM3nJ6k(92rj5K0CXxVt!)ZMdepQ z3(g~#&Q_PmBVQCeI;#rm0IAK0bex=>lIW!GHwVSg%n@EQf^}JRV1ilQdSk|of)|QS zc3d2AuK@nP0*`&hZ#?Im=5hjV+fwWwWGI1^{|gsEM)PWDV(xVM-P8+~_4GUWGBN;C zo8?rlT>y5Gl7hWC4k`eS4GEwt<6EIl-mRChr(WiN1MmI`J*9KG$a#&a>dLF>QQbO~ z6<_v0e$3`=`)&Vtyx5}6QbXc9whF7ccm+0QW2lbf56|^G93~6zN*aT00xBhn6GmQN z_6;UjTs5$LDH+pr-bP!#@WDd*X8AF$I+B&9nJ zW)$#?jK6l^hYyrgrvk0G2D{AKM!W z!DU|d7!~)|uiR)A~10?V!B}zQSQEZ-7yZtm5bA3qu^qQs>nZ%_!E+ z>^;X$;|>hhn}@%Zo=f~UwR6w1F0#_e-ti&hB+08i`SGq3rq$AV^@vhhUAE8>xCh!4 zO^A&#`(8~-%U+r>{3O~{1VckS=i7eO2lEaT(}kQ*>#p#qm(g>ANm&Y72CA<)TZ zwh;NK7Qyd(6|KYN^T9G@yT<>x(wayAh}0YAQA4QUw-3`Ktzt6z zpGVg1N`;Iy?997LM5W=8l#K7KsK%gAKR`MS~i_ zkGbcvapjeQk#l7y+ZhSKY@3%921^`@W%Jbw{H$1sIBrLw9C+fSp;*7qY-uu zIMR{D=$k!rWq*gRA@^&cHx8O6a#8qbK9`Dx0we{0Is+M=zR1}o*E;cNOk2~_PpYZq zQPA{xEyk|FRQfB*Ra$r*Yx*v31xFX!OqM3620d{_vOUeutqT@l?mRGrc zv7br@*c&Iq&Y8u&usZcNOcNzm_X|d~t3hKnweVeFFXAQSkT) zc}hQ5Rp}o+*m1?U{C#k$@;}8kl5KeJb0v86aE3(d^`^(es9ynU5VL88$Z}k9^L(P` z^d9%6i}~5nUezygT^oDjE%tby{56L#-#G%o3|YEbE!jj9YpDW*45|MEKAghKhjhuM z|B|v@@GceEa&)jFhz?4p83WI1yNjw(Lg4_(Yi&cYGj3hcm$sq6$lX^2ZlTU*tvzv} z_S)@wWeC`D3j4MVr*XuNTIi|0UnU1o=;@qw)ECA0m#n*w7!q$tn87a-35(8m@u3aN zw_Dhw3r(RvPaUjDXUoSWD_JzP_}?ztQ<$0U`Jj1!iEa72#PcNqHKc{CQDD+>E)bN* zp*Y=g_yxU=lBq@~V3FILCL$Ck`zC7Vu<`njld()?$SUdN=(p}TDVV8a7TM>Z;N zJSRGW-_lLG{nE(d;-uT`pkV|=Rp+rz(}g;|si`;?)`R>0w&`M>aDN=jZO92s@0{iQ zBqxPBJ@cnl1&UuMn&Qd$i~;L^_Oaniwc2~G+uD1SNpO?bt3#mCP3r$qVc>+Be9EQg zM1iNk5PX;y&x>f(C&5zhvohyJMnEez!pV>hlib&gbdA1OgGl@}DvtqCLR6T6G=L}80Q@!OrR-g zz&nBj<2~9ODGJ_Z9514?1u$<YlQY1iU(;lz_ z#@)OkzTWIaDgjV5f`Xm6I!$u&r$7xV+qZhgfJs6R=arOjW)kO!&@)3!IzKR@bFItm!5o9 zF1_>RtTd2qD%kF&^VJDhcv^NpSWH&%pdNWndwj3-s)W}3)!*3fm=s%N3-eWeYnaK% zyN&3mnJ$5l3k$eqbJ`@L#1ug-)5JwAP!ml*)V*ncf-^RFHB%{&r!gvip-<{t5ofyF zMzCayk>hAEe%E?vm3;GI1P{A$Ik7toKLsq47(XJYsv(W&#IO!uuOSW%;M*QD4^tL~ z|38|pGAygEYf3jrOLuomcXv0^(%m54or03mNS8E7cS%ckNw?IuectOkKm38f#eL2` zd#^P!YsLz54%wW{ETz|2C;nG-#IvdA+ zdrvcS8qg?bOc?!YupQ0Ci(_-H@kdO*>G;;A7W=*X&EH<(L||j&OG3;i^%RFpV7|P8 zhTK3>$tbv-ATaT}D#B6z7BjEfay_{!s^h{IvPy5L_TA}}cHrE&%xM808nsKhNE;qQ zKyz!~xW0S;gC6vl6fLJ>v&}LWb3=5cuOb9wpyvnbVZc3e)PMX}*<6%P_XhG3O1%qliK3yWS(Wo}^wIJ^^ZBQ|2vrT7?Wtv%lArIo>m( zF%G(vRN2PJ_H3g2pUF!+MFYG%nEjfxVm~$Fv;E+~f1%w&Z9-C&k;uqEa~})5dW`h$ z#lx^h?aiB$-$#oo{G7CfHf+6lVMR-a9v~DIRYLRf{`@w=yt(||+nD?lzgy)lJXLb| z?#86B(Q>dr-*Dk@xaCkA-HZR*(E9KB|g!(Uv9S zw0*~5w`ja~(nJB|A;I|~5)z3GoGc-5=`&pcFzDzgvs{(61v6q-=3bY~2P=p#w}lyn z70alTionX^KN@3}12D`0{jhHp>J32khg3Wn@{9!_k2J>c9=&gUyCIt>OLZh zq3WAaK9ep`J^X#shxDsN(S`Ba3a*@c#&QXjxb4IvpV361bBm~Rts`2gmTB5{mmM?m zHDRe9ZR3LWeRlWXSN|M@D)yu|_x_a!LX9lilxp&;dEp{OK0W=LQR&|?%DziLdU4M6 zYiK1IPthix1sm#aaUpJzNTN>$H3uAA9OW`u%EaIrK1khQ59`IWkO`rKP1O1lltCk- zTmaUo)e~>rGWQ$t`o3{>M%MP$A%~XGO1URLn}O8|U zZp8B^N5$Q6*l6f(7JF^VWywQCKH=KN0q=0P zX{oWwdz<@mSE-|K0g)Oe(H}PFkKDc%%ShfC!((A%8V6JCDN0NE^<~MGge}TMBJ+!3 zIYQVr>h#;-NE&Nhq3buw^dAOB+CW51J6*3FO)&*1WIUU6QTXrkNvQs`L^7#=0Ps&H zfNB}_uqMWNN-n$M+KwB3;=gA!co09)YdEO!+oipCM-sRY^1JAuC4afr_p(F0w(>Rb zq==IE<)(r)eGS~1Jk8k48f-K*_dh&)>v!&5U^`+uCTx8p3$XCIGP26tdXUoW=bBZA zahNn&pl_01`Rtun3XLe2_mk=rHyz=w*d<}HdW8bo@7vVo9dcQOqc|Cv6X85k6+Vo( zZ*-&Vi8J4pJf-40!2UZ3-+HZB)+C-P^pwuk(*@w}Qx%!QZaz5|gM@FFV9_v;k;bUA zVZQOxMftG3Wt)0YADCw1sHb@XIlwjzyV2wA=pD~OoFMOEN ziB&7kEdxHwz_-$OC$tldC8DWR|N5I3m;V|Z%r9x_SvY{b8X4gP8z@_*vOPLW;rCRW zJ@k5WK^s;Xr%M=GIn1m+8A=hOoE$K;CRP%1?Z%>QsOhJNv~DstLDI4-=}!Ivgf3U( zGXKy5KQFv);}g^)qIgmudzeh6dpP)BE#T}7;o`zgXyN{envf88@(X4+|Ct2%Uf$_x ze_&5Y$u^y^MA+kirm9tJF_8to=EHyplG;^CvDEI57~lY-=Dm{yW#DbW_AT*kbXGip zY|3C>1OYQpD4ASBiIwH3zo{=4$&D9FWBy-zqoksF4^TMp$yz#WN;hD}%pBQyvu?<}V)x@2aRVBSu{7Ozy!Y&Jih7j zC*x9=uscfBV6`b(08y>oeLTlWEL|UKp5acgazWyCgK71Jyj5@hOlB~|AfK|@7$8787KX1T>C}hndS=ebTPFT6i>@aA+>q4_B<*60=jL4ZkTRnU?V}ReO?u zgdwkwsY=kduK#Ip8(Xq0hhEi5PlXY&QH-7zpA3>$=b(`G-Vfivg0De}X-|fUx(%mt z6?%H}?KX6TVk94-RwQynDJ$8|ds>kxZO>c9NF3Ml6ob33_&D;B;LjL6n8v$4-WS@{ z3(=D-hp2@3>mI&Fw3!~4zq#aTYqDa<>PxRc=p*(m6DZ4k>1d}e=CnNk;L&e~I$b1B z#5KnoEEj;iv>Uc^b#nz6&CA(`fRApY{_g%O9Mo7CW}?-~k=!1Z2sF)qAcyFJpG=)Q zDoe2z)}rOkHIM}T<{(FeV_4EC5M#N%7Mzi+NLRyz6zOG^RePL8W9pA$9W07Pb}NR% zK1Wg}4~VeBXYyp~)DMhAqFYGwR`f5CN7YIt>VA#sN`b1E3Zl=|DM1qs@|DE=xXew# z(nT1jRN}Iq?cLX(z4FDuVji|ffm=_qh}buRp2e>j>*cx5Njty+e}!`sOw?Jr{$oHb zXNvdQ?~JevTQ%5y-0<{HWCwmlL&9b+f~?kfOm`#9gvG&q+^y6s$fUug6qFCokmXH3 z+pELMO>G1WIN_P`sPSP*-0&+P{>Qy^RM}~0U|A1RCe0%5&&vfD&QIBBg82(dM#ji- z51ZjU!+zbTr`eR)mCp1Pt!cM5FEt`b01XKo9vT5_(;{oD-Xznx7J^kNV&Oxf{H^zdZF_;ObTj1IPTF#{oa|fTuT=W+l(E}X#sJf z5DA!ZGdtgK0X$gB(9oNO4e&P4z z0eH@WEoP615yT!YjtZV-@zdqiJJK+cIM@W~ULckPWKLO`kXx%BbKb#>D*PLN1Gp|b z%1T>4Og*&CU9PL8#HQ>Y)7Dm8G}aNb5=*UfeY0i5plo1hoj=L)9Ts_hC8S*FoD09bHbq{mUCMB!y{Dgo4NOekX zb%|o;cUXqsyW=bp7biPNlA9B-5%Rd3#Iv_u$HyG%Hey73R{KZyS;K?{G+=8k6@+8!?`=Ydb za4mIgj*HkGPb6hI9!)_b{f~!hu-Dgo4cftpKC{i_oYq~k^8tdPFeLUFy<5vBYzz->*QHNO#^_$-Oq?4?k!jjapP!KDUGsqz#jL ztQqM4zZT%@(7S6>zpA-FSr&uu4M}rx7T;lrUhq3eeHnUv!IerN&cR2}REid5`D#tLq_RE15X%3wg?)ZQzu1Yk_CzA^ zNakjP0Qi^lwJAoUX7n6Vo^8%BlUaP)i&ke}!NoWi1E!=|SQiaSUM5pBsIiPB-;t^h zY5puR+AL)5!}vYz8!!8DI*ON}%+|lb8tYl>@FDgh{YSJE*lMF~ZkBu|MB@1E^sds5 zX~lJ5f<#jjkvc^ul9_J0&Z9Ey^@-*)z-2*7^w0B6i;veYaY0`=Tn`tjgP$L7Qd18W znjW4`6O>nhUCdud8IY+{=x z=Lsg+$83@qD&W-@LsnLZ*#G@wX_eB)*nVg;xM;|>CR~g)PguaVU7m(ZRt)|AIfU~Z z$r&+s$~FlZ9qk6pivj%p6^LrYOid>sHwQZjRVg2~1ZbT^&rn(G&|**F##7#B+Ym?w zEjzMoEISf`1R_eHSxZWE!Vd`1tIRO#lM<`GW%Z7Yblz54tP$5qIvYjz*g?`3$sh(?{a3N;P{L2F{UCSPdR%`0V+Y5crY59dmxTs6Ug}ps1sSVquCa3w)6Cl zF;82mKQdSt@rZwQ@2yBDx|)OmUf6!OUoz0*iS&I&ylZ}M{H@yda@-~t`u)U(+e9Qc zxHw~_^^G>4_U4_T9ok+$zsCje7uH?0BSTiZcLs?^1OU{z{ClkWXZd5P!-|&sCF+2? ztj2qVZ0IuQ^ZRA;eQf0J%Jf+sW7;Gcd>*j4&N>N(2TAx3XUme~iH_GUC?*a23WVE- z9|>@0n5na;nZVF#g8Y;OyEE<23Vb}1;z!RVW&LY-+!T57^9 zRQP%Xwn)_gowuf(k&o0+?~u9h3*;%2ImAoUYxP2`8tH-1z*yy>S1)1JxZkotMP(DC z@uMtT&&9W&R4ZJQZ2uB)PDItz`~+@wxJBYZ|Jb_z*hIMpF*6juePWBXyX-TJ zfK23&ID+vN4}Azg4gIj^xH#{<0OKnrmpkOeilgES&{fFbKbSja-4FJGcv4pv7GTQn zl)6vqfxZ*)Be5;66ho5>|F|~sh|fF*xP1e$Gh`T*c*A0c&qp+-=vE^ZtQ94Helq-P z4rG}C^}K!3R8ac;m(!93^VYU)OY^Ha;n1MKE5Bd#$OOaV^t8_@_Fo=LaApJj2B1#6 z8y9eh=H|+@nyuanT*CU*BkqboRFbP7zRT>s?C4Tc+2q^rBk}L*=?OyxW>mmA2Jy6$ zzuFn?llXTTf%f-kd!Hx}?LQi!nZZWaw%_h_KZZcaeIH5qG7C&jWB;kBYI`Og&!k!1 zZC==7zR7hs+@|g1eWxGq!F0;7qYWJV(9gW!?-x`sX>UV7&~ON;X)h^ev*6E3;E8^* zEVQ*B5O*<}1}$|Gi^RzdCzfhWdGq&T(&d zf-`G1z3)`~`jeo51^c_ajtkRQAVr+V;%6c^3Q)s<+!kzDUR5dH8Q`=0E-m;o0j+SR}H))(-={PT`xOwO1!#D6l zq~Ph$z>Ac`vi%J&%=sNd*mlI6fvxjkA9VA}UokAnR1*t}Lj-87U%&hsJz@)33BKtQ z)TXscf|uDpWVfrwH)bNX5@ z1I`~1Pi3motO2wl^FPKZnU=+(r6XLny=q9-G4#l-<$(I_UmvGizqQo9qyTQH`Vp-8 ze5TVodm!+7z-DGAx2bAI4Kv=AV*m*&{hsSfWu;TUN)q03flZ3f^A-fuA*6pWT5*zH z;~TI+nQnE*uGG){>QwByFGuXhnhDfWlY+R4qM{h!yT-tvLQ0lF1k`>#b~&EZO~@>? z*CvJ6N3uV>q=X_>Byil`6F}((AYg^_M{J>|sbNsQ4^WMkBiBE~TA4V8 zozsn&|C><)6E80Ug8$ze*Ltwskoeb3ceKI96zw6+bCC-ogu6vl`v*xf$h3KIW}E8Q zk-G{KTzO2fv+o}CpHh#3!gOyU4v=&i+)UNCt6Dag0dG2=5CEO{)Q&KK63S04+VsQp zq7&ARd2u|Ze9t*gAh)c8nvJq@kR*o(U-RYWOkrS6r=Opp?r@4HHt87^S3hj_t+0jt z#?88rnf|7chGr4Km$lvA$y%pnO7d&fbXcvk5wRq=|4`QpuUQ(EiA8ZbbPPj&Hf9^Z zF4y5*9F`{H@`@*W5kC5)5$ZUtrFd0pGuQtl_Uo?ie3H2x683E|*qXx@%D2b#nfhgJN0j(MAn zC!svmjqjji4!f3U&I{-rpaSJO z@E^eX(72b*nB`yy3H#OK3+cjk*@qay^*sP|rg;zYAQ58NxrgYdNt#0&#;|T+KSqx! zf~r9U1(w=-7s+LZ8eIvEL5n1x9kn&Ep+8sD{SH>QTAWBd_YswzgaTuDJ|yy9UC^2n|1irCCDlE@PaGT7eei=+OIIzYQ)6xt-z? zEuaO;CuBXrrCk^K^k0Az`<5_Kyl^L3upL6OPY;O9F-#6NriR8qP0=X_SEQp!Bw%1Rq7A1xx4=Rp=RY^n=tiQzuu_XD6ZGmt1Cg zD1C+eu8&9c01h*GaN%DMaNKV_Mg&HDtE^%5T;2N-lU)&yAJDVgi$6#n>>*Svd{)tI zKACcmZq+N5rVM-f_GbOea5UI{y{^)U9 zV7p5Hyn`?Gi(UvH=Kjy!Sw@>R9Sk<})`@EA_mKf6e%;Qy1@U-t=O47mgly8!h$C#& zI?=?z)|RM+0~e|+Y5AJW%m&H5RA>7Iqw%Jvq2{wk3v`5L!NpGxgJ#NG@mx)hSDm6< zeQU{tT11Nqg-hM_1;tz=TdKpg2w}!omYBe`wmba;9|&b82eFW(?=*B;XO+N_3siXU zXz4^bREi;-=qiH7?|T5op09322Ye zs>HvqpSLmgV)5GH&bSOXzx1>EqGlFB2WW+6cv#7qF&LyCFwv3)ytNa>)H8Q;^#N$CdSqhr~gzg zQo!VN%o00YUjAHJ{)ab7*|NY4*H)GT{%(l3}nV96A&W zXm89cA@E452dcO>+bpqQb>A@ZMyOx`Nvph1>s{in+ty>X>0?cY_S!^;Ri&KfsD}5f zhjCmu0UBC1UfXdpV6TGcA_4zqE;~*Rnj#SC+3~#7$S=q&UY5286H+Y?dt#t)0|p!+ zr>p(13x97cr4k%OffJC546g>Q1!s6Okej{SR2wK1zy0#Xr>-v6?N}>lX+Q-X)nZrA1<43MA*_`|u`GqnZ(D-9%E@ZF9yfR_Wa&uxYAxv}T7n-eeO&2pm^ z_nC=qv|P1w`cVF!l-&LVF`xV8`R#Jjzm&V{13ub4!bOzdMZIUfnNnR^&I`Y#~ z_Zu)}^9Z*(#Faf52wDB~7a`Y9Ur9;=!%Po#rw8Ym?I_-4NfpX1=Rv7yolOZdfc}oqZ%?g4J<+~;h0O!I1_Me(& z4MbUhX@n#d{xB#_0$@y@V6X)XT&r+z59aC*tH{nsRBN|fP53c)wP&248}~-ya=4nj z@NB&pYR@*S&aNfff$=RoblLZ@^L)rEE{xy=2ii|%hpHSw-`Ld8-1)E{tfN?ux!*l{ zdfmGptZ8wQ@gtyH!lgG7Ot8RlySz44vom%qut}DnbQ^k7)tW^_easoomrj5^3atLV zb;ZaWQkIf;HB96Qggj(}hC@{L5d|}x`CaI;*)tVi66BekYc1o_B1qza?!+@B@}o58 znPSsDcYCuB@vH6w^PS%n;aOZjn6zio{grGk+5n1dFCu$5vp zg*I)jS5{eH1U65<&5RgyO1R*dH4=Ngz{9@Y8*(4VF2?mFk*ymlloy6fkd*BCIdfwo zc8{`1*ZMXEEjut6A52}Uk2K+U8SJ#iM6&V@Mal?0^-VB(Syl~o3%EADZ<=STt%Y!C zEeo`sNq(3N*g9Ab(0F!#p-5w#TpL@dS?rbFX<|WQcZ<1 z9F@eOHcYpDL5qcT5E+YXTpwoRF-=Q1_;4g)rpJ-x9^qXE60Yq~0Xs5(ANuRTh zqPx~i^JBk&*g%;s__%85m%p= zaXFBNDF#m*#m}I+AOVilwdGwLD6p8!cI7x+_n=*76pJ(iFp40F+p!1yA!Ft-XDYEh zc@8H}S11H(&!K(@y+vy9Rf*-URmYWtjW#1I=A4{|Z1cE4igP?PV})`z2s z+OuHHz%P6k+Z38riI98EV2!05u zNQ5Qp3xt;ghQK4+*bC2WbnDKyCZ2=t!Z?n_#M%gpLGJm;>jcG2WQ9x|g?dZu(1=I6 zY-uc$O+KAgRrW{kLw^;6r-A)jpZAFY$pXG?*;`+Sw-N}DMFTS(nSuN58~-P^NXJfu zy~7fg>SE0_T45ECi&jZZ#s552>yomc~L4kkrj zARzjjOK#2r&pk45bUVMaE_QZ{(QX3qD69|D61nHlnJk)IFD=~VBaD#*WJ9s*#0h%G zVm5XumK^fYch|6mV@cr4395*V!;kFF#&8MvacXh2(O4R(H4OW#N(nLH-x{M3;Q61g zF1-Z7SMyZA*IFr-2%lZH4l|B!Tbc0b6@|BwIYZlwm!{E6sP-}VsM4n5;y!1_oiD2B zv|w8@MNH65{cuKEg-=XM;w3R+iOd&qsS6oSnfZQake{xt^+E!JO|`PxOycMfkYVMT z5db|v%%Y(oW=ZUK!|+t2V{^%Ukf%s7Ja%z=nwPu`XJKB2i_cTF@q9OffaIE+VnqfI zDe8m7mli%&=SO$351b1sbj>XLqu+p+7x-fDVH2F3jPi#M9)AOimLpgwLLI}OP&Nb( zPF#6CLks~j7B6KI%wE?!=H|2uV4IlipUy<)qZL=$q?zN?o)R?s3NRWV6|4s*k_wEKX4;BU3U4mBUtx6eNrH@vMg?=2mZ|Y1fsi4?3?6TO_Up zYZbNFVcV%Cha?Cq^*U%LrtTz$k<5vJ75V3PBU+lAK=uJyw2DrtL=nccl|;KyP$)D_ zhi`hFV{Uw{nVHva8tqr^$~<>l{_O#a$NqGJ6|HJ-0gBy!QfAF}bK1QwsaUde3A7*Kcs4PQV3AeeL&@pMb!w<5hR!bXqAK ze7BB9!#O(+)r-iQ`KjjRFbncS7c#|%2)cT*A;<(Y817PXQ%t-1V3M|>#g+7O=))%RDP$#Ts}J5w zN>?IDEE7`V!fZBxEGxqo6I;4fDcigM$^5`W4QCu@El zOzP1HM#edcpdN}!;vu!HPY1n{Gzb%2@5EmyOcyPk9%+uJ5XE}9`APrx`Fw{rftM@g z%BSO6(Pon7Ifsgx6iBHeP{R0W2`*8;b(2#?_3~=XhQq6~9tp$Xlx0up}}T|Lf2?ZzH;VFo26~7!_%rw##w1LEpK?ogM;1bKxZz zieIU4@bI4Cm&fLL^MO`5RsAg!O+8~m)Tf+$cQK5-fvEy$h zTO*}@=yCoSWiKEQ0NEG8GoQ{kAz#A4@X8;Y2A5L{?RnC7vm@DS* zjbL50^zSBc!eC;*4VNn8drZIIhci8)#X>_CdAJQg56}-O@fR@t*)}rh+`_-W-wfM)+DfOk5jVerTn}};SWQG|{ z*B=`B1*BYGbQssX;%&Fn$=IIaRL=sG)?Ibm45F9guK zPn*(UZ32@jtn#_>Qq_ftu*y7<{_YSyn+1=zgnmimeyX9p*5@YzeNi*K7zNug@eZw2 zu;0{&k>I}&5QrxB;jy$Qig)=J{ToNS+K0m+KDAtFwhIoK)ZBtSgrdA@JlWbxSTVpJ zjJLL4s#^(wSs{Q96QehO!WP}Aum!{cplt8MAECLu|?qvL;;ODH(hd!HVHfP8}c z&C-%hU7ZFcHJ`20w+4EI`ks1E@%q-}@*!pU%{%+^A)=|Sf}Qiy_D7j$9eI^ z6^nE(BG!T?KZvR&fSgV%XCRlYLWAu`>2mA~FH$Z|aRmhwoRHz6r?9h5 zB=9ia0pU!Fw$bqI^P6@fI-=X32+b{+oTZ!aEfXGZMtIba;6svHqqwxga^coO*@VY9LK=T__ z`nUwT8YGBIXA zJ-EN7V-(W&SMXfj_uL&~Eo2c#RkGP4f24BG@)_uQhWc3?EBMsxNtfmTrt#SDm zcPm?~uwk%Zemc=o#J$C^VbMUOLPD!H zn_XF$rso35!o_Dsp`w*VzfN|7UOW0jm>l}^=E>eXU{e7ra9(Mo8C@?gqW&}sw64*iBD9ES=dj$tDG)&VPmT;nPI-DDrFPq(i3D3mFw6|3%w(l`d-ctCEy3h7L0~w zvyn=jwClj#S7!d32tHvQ%^ht_dZb;~Q!Jm2eX3fGpQdR}3d%fj%B?E=>iSEokG z+mf7^h$P{Io7VlEiPc@`=?Cn`m{!IETa)sKcjAiOokTUU3Mf)<^JG&HfjTt=cbeyQoK~+a{Tu7LM|Ong`ujevc&y37Pz|6PERLis>PXK8F@L^nUApDI(S{9N)+Uz z`7YG(-@y}Yf1PIjQL7xDoMkY)Si2NUM9|xICIxzK5MBNh!~I(uZ&j~{0Ihpbc_W2{ zjGC~uu~Z9=qex8DMTQB7P*+;&aF@z+*Az|?7$85-i;3*-{N`K z_+h>`V7>gzzz((a**!6vH=>lpAclI={kwA_dwR?aU1Cnv=JOqejEoZyB`3Z9LVT4o zkDRqSKkz-z7hO zOn&cvSP89ceJi=>|JL6CSxPXr1CH~nJnZsdI);7t z`n&3#n96!kQ*k0x_fAQ53^9*>H2mxE??_9ajXF$2q$2Y{8mBmR^$j6r5D$&!PH!lJD8UE_T9MnctqW%41SDqMPE5HFyrRWUAso+ z{>VGYl-;*gaQv{|J(s}=yTz2Wvi{`o!-B~8HVFI4--Tea*qCpC%gn1l2wCYgd}iCU z|AJ|3u|86h=0`I4wStO|>IT+kH^Y^&A8ufbE}kr5AR%FK1+ZZzE166OwLe@LeGD4u zTG5k`07dSTEUZh<*dh)wiGN{imR4R5U_&*rvzx_gRXqqi|r$kXQ7p;_OZW4C0VMY+%qA0f% z0DB-8ex~AZgLU_xm9qU1GOP>WXDa``S;9T?=Qu~Y_tMc6>m?L`Hy4dHLQWG z1+V#a7UnkOh+(tH9R7aPKdn{g+P!h8l~E~Zhr|_PQ)(oFDrhl1o<${8p`qE?IsKlT z-+6o61c$7aYLGwP9b3&;wEyN|Hm^c0y3`ok`eNHjDx#5!86n=ipBqtU85hN7b_vul z@M%ZC-@+Q9yKikAwiU(|li+k$SkxS|R;(Zwz>1B+`s=~Ph#)q~j+us0r7fgx^-we( zM}6-EsVMDip_9Wl>pHfj1be8EJ;g(p?WA){Og^u4hJxQgB_$-ZZm-^xhflzz6Y z_Y8ELFTVBifi}&H$_BND$DkutYWlfxjQ%I;F;&_;$91*#HDtil1P!P3mKiR~o~;!L z@d`t=iuf?MU!nNjV)li}+a}wH(b3AH${PPYl{8NUz|+^@89LU0&M;uU2Q({0hOLWM z>n}$r9J4kmI@p@AOn^m1uQ-~F{S1?_5nQAAg4ZoTY+ZGsz_Ht zkOW0<>)x3O#H2(fEPGu0oeuibe16eI^Lp z#Km;aSSK@9lpc&yC*H+O-_+UUEY|_w-)Z-g0T_BX1Pb+2(0(KXbs4@#TX1zJq9s5$fgO_NA02BF8@kwJ7jztY+VuhZnwYE)j09M@GTy z#^2}yqX2k#x!X5#mRwyg_(QhU7UG|r752#pNIp4>$HN1dOKCU zzK(c}N@FMZMwl^_ilFFScd`4%NyIm4TLY;e3g2G{zu?|lUVmy&i&apR{uUUH!Vtu9 zd

-&6X)>x9(s(j?Zz-O|^mNAQsC&!_<`A>?C+|q;ShbH3Y&-T-(evjVjqN)QS!sxDvgf6KeHqyBKJd!KSQ z??3o;_GD$@4-Vg8$vtQHe(IZ@aUKpYK)e+zAQXv)Aex%`8Hbuqb!UIt+>oXFRHJL? zb)>|qtvpksrlKND36WW!#i&oroPgA*X2`Uk+#)bCiaqufdngnk$=ve0_hFIU-`h&Q z3)TGz?qUVm-QDzp4BnZMuUyploTbJ?iR7@zw4Fi=*X#?F4-ayd6Afyr-!_0V?sJMn zjyCitx0p5W$~;ss6pMGH_H`Y{J}c(Jr^zE>qIO@(A7buA#W994r5eeL6buY0pi?$o zX|_TonZNuA1tTGGzjQuU8bQ`!e5ZPEjqvo5IhKI#(+eaZ2PnR-^bIH5b*}Jbe)0W` z;TYBT9qoLn#>_Me_zdHRg^kQesS5QU22&kx4pL2V!JHn@jh8UHXAJiDP#kBtI&pon zX)2O5hsrG}9-0-tQ3+i*y1*G>d9WIi%@In3|U|XeTjr<`A>wC0+qv zaC)ysSdwDv5DGg$cfmbgx#j50uuKKxW75}WH+m)%F-+xvO3#xYKXb`Zlj`S_KdWHg zh}#&7tvS29qK4&(h~(KPfBAh!JtbqdJI+(!_3S=0s(x`fDt81knCog#K^3es8b*MN z9lUjYwuJ>~1ytwp11Dan^6k($ygovi{dfxcgPHy7bh&H~9Ae#3Q0lH2@yP8Ksiy#H z?K`n*sALS}{b30yK%Coev|w+Jc>P>X0imP1SHqDn+r^NHl$I(B%RkD~{rUOV@3Jw} zABZ*D!K!dKTi-0|Qa8|X$++zF$A1|p7D0S;0(+l(OKHxj-Rgjfc1B=`V(4|ebdXG za|egr>c%oOj2x!GC8{>`(SZ=`!gO3-zPo>=3(&3C+OzDJV+ncl3w-ZvB6V>kb?S)* zKEd*%$!8-5leQ4kVSQ{JgV{`Fin^}VgZZWv2_G(knQ{FVFZvx;Bqp|AftpL;ICElt zZWBo$VniV{3R18(Nobp6@Hwdpy>r^GYXfaaPE;jAdOry}`~L3PC!X<4?WsapD(3XS z@nU0;j?QAYP+Oq3VP!<@yy+Yo-r90pMZR)MzT$9*pg}J?&XCDtpnq^&D3r6^A6)^puu`yED)kMdDhia3Vpjdx~C7BGoE9tpI+NhK^wsPc!k&pt{ zUO1TR>AyY{HMc0k4`?Xl81GoBYw0X&lnO->Y6GaoScL zs98R?v-ce=;|HlHh-4M(>&lw5cYfDUZq^Xlnc6YO-$>y@GlLO+=@0$DR?*R=J_~zD z8j%C0FJbH^Vw5(GL;Ppvz*#sfV_fs@&X(Q#@K;eR3=-v|m-(Bx=GUU-c*SDX{zWXS*r{ zNdQHWFt5Bn*deb1kC632^t2Ml4vK$$;Ryw-_q+E~5hyUY zZs+&b@;{^0zuIN48sW_YL3#b9rW|6uj=<0*qtb*|BF z#LUJ`H7V_zQxZz5V#9%~vYPxWyP@F=7yCf~kYJz%FUO&Ers3 zwk+r{DuCU!I1P^@_+YL)6rBQ*h3_LK^rixNAGQmx*b@>Lvb-tUs{sjg=v7W@YnV~+ z8xs=;F#3`U$`3rwQtrV7+lRLBfsa;PPU>(OZHPk82*jO+KDAKa!bKq6spD}!ZryrK zjqEbv;dO0Xz`rMilq(t{a5PU&-62T7qJXis8(x8fU-`VU{R^&Hu;waJgW~lBZHOr~ zw3(PiB0}s=>(`oXjCq;2Ry9nK8vCUt{lvB3a2%+G*aJi>aoE1J)25Nb!0i8k)pv(D z(9}cSEs@KOgbxZSQ~6U+=s-ddeLhG+y*JVLtI7}-9ewxb+!wA&zS_9_5%wHMFP6m- z5U81gyzuCGZEG{q`H9c}fhsXI74h$#a6K+Xw9`T2=O6a=?+Fo6iD!Wx^xEED{w*mT zPI0@8cT*Dbil$t5M7@bx?~JPz*qzG7aRTm>woIuk>v0p{*xA2#-*g|R88i@kqp`bu z(-fB}gTq!D8cPW!DDo(Elj%W8*pIykpMkMna$=Wn#f&8Pl5BTCUx6epid3VL8*wfY z!-xTV;mPV|C&XLdAABs8oN!<@8Fz${3Uj_28ZwBX#mZBO1eFKu|Iu`nQCW6fQ@Xpm zyIZ=uJEa~%knV1zMH-|_x+El}5v04jyF>CjzH5E=@}Dl1>%PuDd(X_C2~At;7=BnZ zvp83QQTYIi9ziaL!kwr&<<5xO9E=WKrYGQJ$|2~vb=f7bC6wiQ8_M}bBvyeEdr z47lqbaxq9Bz4C2DNGBRPPYdKt|H;(-A6(A|jT;00YQ?Bnx5;|zvOuE@aRazlYgE*Z z=+HPQH7TYj?udfqRl^#B8=nL)1OC0}bpnK5k>&7Jd9DhNLdY0{2G{DJ(XZ&?;#J#w ztt1&upG1hb?*8@m1Do>Ne&*|2w>>$+8cSQcCfRub{_D*!#=H)E%m#2|erOzK7h_av zOqfCXzG)mb+sOYA1iRlLKO^>PnLSR1%_PttvPPGje(*QUXC0J{oLBY$L?9?&eiMZ+ z&ACA(imt}6of=T7iV!GDgoMhH zjnYwc^TqXWrhygIsR~^JB3|M=4|_U;Dlda~Ti1#z``GftKi#O9SKs+BL805$VwNIp z0BFp?5rr%EYeGw~8mP+c^^qd}e*jV|k`Zr}yvG@Ei|t`SW-iy81AR2IAD9<8Q`mUS z-hOSO*KYjSuESF7v$6)|(-_=(>GHt{TsY+j@E1T%x3inQOh{acCRQ?~w%4GkVbhCA zK=~mpx_W#EEnap5(8f`bPLn075V$d+6&QhF1Y1aLB#WQ#wI5pD>_Pwp-=ljFY1OmO zs7QcO@3N!p)kf%F>nPEw>Dif@^~gavym;YM#o<(sx06YDNa_Lhzb&{zLLLMdqSe7N zt{bnxKL~1LM?}T`o$K|0dI0`n^!4)tO=Cg1zl(Yp)uF~@XCExvDq8#+#2k{8W=ug5 zsb@=3|K|>gXp9lI)a2+pg+V6sOEg3e`{{`)O%8hjEd`7a`MQb9oMcRwV4}tD5G?!| zfdZ(W9T^HR@`$B#z!&FHS5YsoOD2?AZEYDT$eg;mily7sMoGzOsmKOc^ z3sdw#MdVBrKhod6{WnwU_wR-S!F34<`PGj_Fdeu)O{oP{o#`l{ZIW{27~f5OXdCvH zvpeh9&hf$MS~K+Wu0*rz5Su-t9hhSBk_ar6)3w~@l0#jy1&?++Bc72{e8ZJeaE*p}W_v(kb%2 zua7CNGDzX_c43Uc)n8~D?RvPJ^m}oqhl0bsKB->}3-dykc4`Z^#V8pZq{se8+X68Y z29SD`G)7#Q+s~px6MTFu0q$6H$ zl~@rd9vp2sJksFkNX0uRYh!|EuIE_ReRi$ybpGk$B~ycO5N3jr$E|EOBzf@BuhW-8 zlJK^`*vYREg^f#d)H*l(A66+-2;8@0`~pSk>$;oAO;1&t8;OKm+IAcQ2_ho_ESm15 ziB7VeS*ZTU_a~?I#K->;iy$BMA7VC^ZSQvSu|oZ&G9$xQCRVP`;_7OU3W&0Fp%P;( zSmm|{ri_4nxeFUFe)~-I=|xq-Hysp7-)=I&jkkc{9DDIH@*TG;*;MA&uL+k>q-aIO zHsBwiq%?wtYx8$mbJ3+)KTH4J9{TAZbt3U+o2bhx+!E7Q8C1!6+_ik-s?tynnhTRq`)WD-8?o}17mkK{C*I0_|DQcKe{rCd9>tf^4wp%}U69&hM`oQ)wO4DXPCQ@=;6q_?a@UY+ zI9Es??gDEa(i+NyALo#eM8z0`Dw6Z&gT?81=6L0jjhGyc;5~2pJjT^>#>mF+qsF(r z-H~I-P~y>&uwxS_@U+>#r|lHzenQ~VtGIhgPH5?d=Q04;J3yr#eCatwHfAi{*F{Kx zW5ei3h7Kd6Ly+N52?(e*1leEK$Otl6E*J4kn{rQbZ#4D=6F_H_Lz^EscAN55~BY!hos(pWWVv4}XB)K506VwRuy^5hQk0<4d9pr%XU zE?@3-vQ!{KyMZ^yUyw;lwD~(cGTzhW?F9x@uPnz-;cjs00JiL(s|#j zQ-GXcAN$C{;uYZVLA?}tYGMis;cptdRyAQ+5(g_r<-$fG{jzh{Q_lkt`~W!ze!_u4@(Lcn>3XOWu>lljXfdb_gS^3^aN>q zS6|d7P_;hZFiYV#usO9Z$y15tHb&p&DlGS2vv6xK8 zPxJatPEivJd#6l5_8y9E(eWsxZGV4OjOQXMqO2B&gBajCkARlYh`mWC+KQn4cj#PM>OsfE@!uA35D5EM zR5Bk@zQIi6ZXncs_15IN`f^4~!A@B53h8{y$%88%6!^jvvHiPorfj=3CkYy#W;<#( zbEEf=y_6`rmK=a3)9;0%Zf)A=nb{~F2$!&&+BPd{B)r~U;6YoJ=W0!)^9hH@Qwv7_ zFS`e)-4fO5TP!j8i%3vIBC*KQ1r$&|2ol|jmz2|9j%$-gL(-|*>eW#Of#E^&3o4r8EGRfP3+oC5loaD90s`BAyFNkh*uZAs zZvX~9j1+6_JzAX`lOW;2g6L-g05d$$efXY-|H_58MYXy2C9lovo0z&Z!};r_39t1@ zp}!qqn&+cFo2B8#4$d%tsjWR?J>~FaaRm$iEoO{aZncb01cj5sz}^x>j1V9ope8FkfOcJ{n)`Y) z;t&XK?uVN}Sprj|@&lmBm~q(*>`}0uhO_X*gTA5zASI3KKN|YixC_w zVgMx-CZ{s485qi6v6+DZeWV0^$g=PO$71;^3Kjl#R1aWW^Z;PGTgCtuZQpgOAah3r znO0R^i5>?Lfalbg5z{czmQ$ZAjvj63JlZG(4V3{e2LYu}y`;%o!JG?dZ+4rT zh8Ty~t75V)CW+2FHKuY~IDZ_yDpGF3glI$<-ps8VzlSae67ncfa2o>6`VYH|4DcGK zeOLB3Ige(C+1BZ49ZOijT7&)m4EdJBcsff>H}g(ciXh`t%<;ahKZ^NJ#qv|{YsjHL z8rOqV-r7wqGy!*5A-xDMf)dlMZx4T?qmx0*$!7W}DF{W`3HdXDl%Ss)uTxARXVTd3 z1{7;??1ebR67sh4O`Q>x+mZ&2jQf+a*Z+2jjQx3{0fc{ZYN*irIRzSercx%AQMNeD zrx6U)4u{YY8fNRx3(n|wq@m%TKvG$|u^MCX9z-bW4C91tmwCv6noYi1XDW7DCN@=+ zMDh>c=veSk8trz_y*R2!*x4-uch2K@!e8ulwy+fm;`^ITwJ=22*5LFYwHEKcgi`2v z9|Q$Ymvvpalq0@R(7=3W3vt}ZhF0zjOq8ok%2G-~M`521*uV9xne( z#$g&6$tD6JQQ|_EVev|+*pMr}NYAYb3a{yn$fU$Z#U*MCT7A%A7)3vwirC{gW%;{5 zf0BK6t0IT51<;veC(3v6P=ygIG;whUKu(mX=3?GFep_y~=Jv6fEO@RQ4-ap_=VQ$* z(+tgc&q16$HawUBquY)K%BQX!FHGl)mDyIGQ%~D%$>Pbh*9^tLwB-=C-8bm)c<*e@Bp zHdr2fP{Uxm2Mvo}`mVoX>gTdvGCW&98NJr~qizetm0wYe0=>t&h_L7S2QdKcuRqT3 z;3h^0RhyV*GRt8%%XYarW_09sC(Vh~n{bDxfR#6NYqT8HU}O;Un38Vd0u@U}(n3+}sG{KBMYXL;!8S)$;>AIP8~wSl$gb z+f?F{9ellkdvcBC5wL}v1d-g~fQ@>u^;H4zpX;%bGJCKC+rcb`v0yS_=dy;KY;h%s z7y0J7^fAA6hOO;y=1Lj%_ zD=^phjU?ubZHR1+x@`RWKLDFS_(?##5W{;v8+mGqo0|GPzsJc@&c0f={M{ZYD3zL& zUqHAP4>|_4=WP{62uvekr4AozM97rJuKpI9co5jOP@@OZK;Y=91LTW&fME6MaGW;< zS8RKMT+RU1tOe-c=3KnCKRp~APTvAFEn`?RNBI$>?SmLLFj4JKq=9fdG=KWN6%Q0m zl`pipbk@L17*QI3u1%o;B8`o&-n}BhVO8O9y5uH0ew=w&vSMa%2!P6OU*$C68N(B) z!fhf8yqZ3Rjkw259$12*@y3S@tn~MSmf`tE6CJeHmt%q%@Q_8{%YoD#yj(nHz(k5Z z1)YeZ!`+s(1vPo0ONX^1WuXYAp@4IcEpd&FK0K7pbXG^NN!~>al|5vUo<(n)ih=_X zvw&iAJg_%(Ck!2sjsO|F*pAoHsY3jBgMi(xbr=Z-{B3+x-MZQnRw& zDBPizfOR@;l*>|qar~9>CkTRuXZ&S$H$#r zOtSBk4leOwZ~qbzzQ{|3fh{qlh2}{>VPSwdOT+(=JCKh4-I@=+k1*miu2{T|nqZTH zDu!)?1`~UtBurWId%GVGg@kI1n~T=2|B&K>!VdtZQz(uc+Ud8w&C{Bz?OawwCq6M7 zN%z~@&Iao@{jy}?(^ZB9D1=&%z8^W~*$)pj)cH6j#a&#A1NYKtEZLn~Ehe0GMJG%I zqHJ%Y?6I{|FD)`Rx#J%8_jEX43pMEk$Ayx50YwjtHZlAjZOYH5ez8i$SfpRz$9m(5 zq{Gq*BcH;wx|(DPq@=cG-t5mqRirmu%F6JN$%QdA|M{GlQ@t08Mj09F=DeRBuE#9G z{Rl(>@}hEOWa7B#H_SJ7uKjULEq4-4R;P4gpYr}g!6F`>u_N`NkIxN6wE(Os60RP| zZyK})Nz^)*m%lf`FfsyKfAD5XR&%P2Me2-ACt!iMAPa8!@-W#ZAtb?HD& zsF?(swF@&6&;T6Ge1~_T5*kc(nhV>-9-eOLSdj(dI@cJlIu_+A3#QNXmiei zu_i-^KgD6yPPb7#Q9V^LlHx0QXx1|YXsJta@S}9fXqR=w)Gf=HOIw2hFbDQurG`^? zpD#jF{$8_`&RW|#W6?@+0w#un!U2H$dw0t*9~Ul83Ie=aLV$p|Z$JRtuV&oFg=hJM zjnq@{Xo(`Y{alX5>IT?ZkMpMqGh2pt-Je%$&CpKx5phtX2Y+YXdFYu6xC;Rr5}~0X9ANiC>+C%H)nf7o#LAMkg2sat>z{d2N>+Br3Xve; z7Flp7Gbvb(;spZw7XR>&@E;B~k%##fT{jj%uYka0G73=)X{8+GbLl0`=89Um^|v@_ zh<d)UU%GLYzKD-if>M)`h0xx*&~DE}iPoj&jl^JI@HzP-|%EaY2* ztNGuGkE*D0$A;qcsdN2RpH9ID1$6|i(UiULxN%?V$jiWkgi-5#wj$7 zcRfnt4RJPp(pz<_Ewc30^n#ApjzD{D$aSx&ryc?y`K}<6zC-r7^fPx<>2O_v+ZQ}b zHNN*b_=@ip#GRMk_3t_Zp$$76k_N(@Ay8H$7E7qywxg?*bcMh`0OkC4S&56k@r3Yb zZ2#9Bs24%;2--A1uK;h3ZYTpIaE2MLLStI&mp!6E(gMdoP>$Fix z>$Osa5qqKor~MjV=n13!fdT)Py>{4}B;8PkW}2&xN7Hj`zoM%13J6lm?dUNu9KcF^ zW+LXUC~rg?rHWOzCKgS}qfaAs#Hh+>jV)^ft2-S|wL=;|KnWoa@+rc(YWVt3$uwN4Oi7N?+mmt8vrLY`!IdujIMS=D86bN8Cr|)w9~JY6 zr%Y7miD7q|VIWXUeHdtHj}u$XMVU@f!M|;_NYrG)T=OM2V%!VN^-xL zz4%ahd$)}(x{9VeCpfYt&UKsV(6dBvik7(RV1NSoPwen=zdv1-iISoq)&A#)WKKt< zGJ!8>SSE_3A{_qmmi;`q%;%9ADbb4dyI*w%uq2uh!GokGATS}1 z5q*|>y5lus4ekz&`FE!QQ@*>i+39v~{^g&?f49-F5D-)V8mL$00465FxJaF2X|TB9 zQ@j@k>csPTAg;$bFM4UCYs40wn$5=8ubrJT{U+w11wA_DOr1QfXble4cVID&h1qDTzg^cY)^D>wZ-Z85Rxf zr-1wv0`8A$@&KHAeM!3Tfq{ft1+zvE*Z9svgH5q2-HrBG84*#}Ump=>+94EgFO$Rn z(vYTH%-)<2PrDEfPt_QAa1atx5MN>SO)OQbBN zUNm+34%*Fjlz@)#f6YrSAh41d@`(kCKw>n~!P@FLN)HY1gL`p9_tO+TV>>G^avOUB>E8#_e(aQCE#pX zcU_sjv2rW__CZUhObU4CWYQ=?0$qgN&_{<#?t(qkxmWt%<+<4|AV4H`$znQ@LtrY9--J1|LQETVHUCF+?=YNNwRWtqY`ypNA2lBP z!h(T((>}lT*cT7aJ!2bP&9j$|b43*;fj7NNLU&`l=yG=M7Bse8SF(=nw%04PedN4f z##rFZdoq+X-}*R`qdIBn8B;+*gk=`Y*NI?c!C{27H{sMMR%vM|3frpvq2m6f#S4c1cvJ)?mw$ZW{%&9) zO)>J3Vr7PZmDb%&g~q4f@<*i;m0C*%LU8iv=YX}Z4Xr2(k}!ih6Oh|3b;lclTl7PP&Kg+Pup ztY(Dpm!`G`{toAp`s$NnejNhuNth*3L*!Z*J^mcrcjSmoe{umxN)n)7G?$UqF1_bf z-?kxNIwGIidVgjPe!@ld#@x53JAS|JcW)U1Yy=5I6lZl`z-Mgo)D#qvrwAa?;P*B`eVn9ISUIiMf%;KGQ&i z=fAM&@1cW^_Iz@TuTcdnu3J7mq!=xI(kQ_TXu!mvxE|pO=jMr$jmtx0_^`Dxr?`2^ zw^?ubZE)GaKIwyDoRvm))Pk~3llGaV(W4lcZLOyW)U^kPxvpyh`|G^xQ`*kT$whvJ zCjAHq3Bv5dyV*wdVkl)Rtj*6NRE7Eh{Ff?7XpA>*@K_P5y@>0NuF1Vs1PHz>*OC@&bTw5R$Ff?%2xdb@5mmsm`BnD<$_)& z-9=G>_@mquo5t=t`(vMbFV@9H-_cKfgW80%@5b0(NP0TIKA#+Le=feEUBg|a6xlT0 zlB+67@chZL!=`9V-Gezcm>e+kWc2JgEtF&Oh5`J>YaAbm^|j?(Y1uoLJ9Jc-MnFwWbtq`g}buE#2@4<=C4+jS?WQV{<%)+ITIerbuS9IRwn6<3#p zncvHa5m)u#w;%j-bvb7UhYk%6)}KGI@3UQ=`0L3~k}#^Xsu9FUeX#;=120B|oyI@%g42e8; zna6yndPp;U74LxikqMdOg6V&~pV@(-Q*Ohiv0B2SuC9`qB)=|Q9J%wU$OT-()1iut zW>VxZ&8E}ff*oRXL0qRCrtC}z4J|B4uR=s6X1~4~<}h+q=HWGb`W^_KOzyrWgV}31 zpgonekrdc{iw5@doc{Vdz1@D}sNrg#rmj3VaO1rpNI<1VNB>HV6C(|LV`YrJX;M#@ zS-5%Rk?}V+bA10W(6di2&`+*Z;y^PXQq#boL!WjDnS~(5Nas76poPLUJFRuT^D}PV z13O#6X1(A3PUrs7ZyHf?Z%i;%i*e`7n4v;Ffq|iAWQq$5XSg}qrC?T~U}YWb3U<)Y zgepBk$b3~>(F>+l==&^9c^EB3lAZKj*ABP5{K&amK(xnBhd^jybfeqhIUxAR7OJ2W zlcY+yK!6z0@t1dysoF*t1QvKx`G)00& z{%dL}O9USE1C&!9_8oTD7pPkM8s5lGXTA}`@6xDWh~T&3dh>E78j->xvLB+bl(Q%* zIDeEE&|h_j5K2#yW_}t7%CupVi(EmlwQLGM1J{ z(`{^L+h6N9IHH^drHKZ-AoHR93Ihg@XB;-^0xeWO|JBh$DT|_!^;aDQv;2hQy%c-lEz_{i)Zzh)YD2mwq9dfwPDbaYSj?(;wE zVH+Dnq)sXu307ybgi7WmiN>}Zc*XtLPY&)dDb$057fA^i1)ZZqwKe#!mxO*lajN-c zUDFWj^9rs;UmN|}T@jM%KfAiGA73<>;Lt%bdT-oT{bmlMLbFcptRJ-REcB?7A;h(X~R_JMA%^ zj-m%ESgbaG&Cd9K&_n)SNNe0c`7VTfgME4Mi%M~zIci%4s8|g-HE5Lsv(%>SrFtU< zA+hS5?BpB~Opi*ty8hocQN6tXyTVnl>QL^ag6w&V(ChvTAd>a zirl_cyp`po)gL466?P}sw41Cjx`V>~K-TZ2`B|L0JRh>?jNAQMDWe(pbC$bCGTif7 zyq+0siA>La8koJj%#)-Un$%T9-xdqj;*Tf|;upk-s&E;o*0gzMdT#_(;P}F%c5^0sa?#cmcPFVSYwC0^MCU3`nwCs$@xry6HvcJV8GVJKblU&E1@2hf!t^~Op>C#Vg7q53U z?w1i?REV}OBZcmbn9n=#`nTipoF}DkPjlcO&zfLPsu@gO_Sj$9uLz}}l^-rAm}(z< z)48#8TJDRan*Oz#bcz~@w6BBXZocjR`P6{V{V3JV=?9>98l#!og)h+;>Uwa{YfTKrb22QdMavN< zC&kZNkJV=C3qGnhbms+4mYQ?h!mZ^?W}>xt;H37pW`C31^tOihW^g`dSOL5x36GAD z;qLS44HDFuz?tvu$D0R5|9$q7`A;VM#2l>|P%b0;7O7MNtifZt`SJ-PQ0s6DEjxF> zLPK6b;87~7J8!D7B7XhtR|xP1j*HW1LyqC>Zf(mNrpkeAj*#r@q7jk^ND zrhVo^$+9W+njE8mcztJAwGuOJM>m?W(49SPgXD8_!D$+l38n(8Xz3$U;tOycn#wm}RUo zJ#QK&S9g^zx2@i;OL0Ue+1mj(!%(ck;l@}Fel#QquLmQC>7V2Qs(~sA1sO~uA#toZ zW&@OtdTtI+q6seEq%~)K<}s7umF$=na%*M}O?)#M#mtj8rTpfF!B8|>AX%f{{@wPl zdd?`PcpL`FVrpn9^3(qoe=RRw&yc!T!)KaJB$K{k8~!rF11;d7TJN2dIQ1B=bjMAYcKwj@pol|VXTPbroQvaU>ibvez|izs_#cJS55L^t)=wAW zr_C%3YPxTtho6V+p~W|<&2-rrTVDQF zwp^kfE}F4{zh}-e5Mc+$rtAykgzyI}w0Ht|&4@Sp#T}{AkL8=Uqq&;f4jXS{t*_S7 zUjzh1Wxbkv(mB4NQ{iKOwX_c?tlDFK4uDXf*^?&q%F7}VWWG5)w#m#sc2j_c@VUF; zbhTm`7s3J?*8GQaqj&;!`IGOgZ|5}xex8Ic$$&0{cErNW?A4R|@mt_zRx;=v#tR9E zWfH#~m3-1QX+sh%Uv+0*`T04I()CS${?mL&KhDJtF^jgxv#Hk!>W7E?!oulI;+*G8 zNy-rq0G^e%oT*(!4Ez6~0}jeFGx()7X>y9!WR*3->MH?k!$^Env-ryKA6RIS(AG*{ zMg=g+5qEcGemziz1VagnLA814H=q9k*VU>hW*|JIk$)pEZXx|rR^wu&IeVBfd?Gff zVt_vaPtIquPJAqgz&04zyC6^8u1~q$c*ACTCI<;%=-;TdQB(>`?ZPvgj}35l8xwQ8 zl!dzjohvX$*H;SrQ-|t<}?NsJzKFeNj23=K4WKO~TKCNm`9g`Z^st zm`}XJ=uj$!DZOPsN%2V%)ZhYHB>^CQozW9dT8~?u;gx0(uqHJ#Lj)mTF^iQsGs@#< zM^NPOZt*HlL-)yiv+UN#ez?0eW@6@Js)+26E?+HSi1gGOqBwO?s5GAvKE_+Uu4&JB z5gJG#u~IT`-h3H0HyR*sm39{w6Vt(gba|Ic+_nDWVdq^N*jIZf=NqbEAg^gc*VaD3 z$#hr4#!w4+2xVEO7k_qn=QyDX{!eTNj`AaF3EJU#lvF3&t@ z``M~YP2hPK`nl98!Dw0s^e+`nrx=&vCQfl}8J%RZ=gKG^gK(l~pM&eK&=`dlUF3x9 z@-nfBVWXxrd>okw1d@Z1N_&~ljdt|Q;gx^zr4V914v;J0(;yUneBazb9W56UNiEm6 zK-rx4qz5LJ=~YDrckN5>HN;m?2f(2%Al*)Ii%=#ZA<6!lM-OZ+QWop6GC;yjrT(mx zlv}N@cM?&m{fv3G^?DJ?HwZ(QbBx0^vvb#qrAZdqH1p{>j54Y3dv`A92ue@^c&} z4-hWC$}lSaLjH}VJ=~D6D~ofkk4*am6>Fh?u^@fPy-)r{gf4^}zHf;#;~P&%-}fA9 zYCX9~VGpy0Q432wg@|(D=Zz9^Jh*Q>t1(++OCt9y*0)gM&i|2)9MY2?fz~5nD2Tt+1VMf{@Rpi=y=-m z?`e`8Qwn#4O8d)%(!!1^1nY_fqy73^^<*k#qTJ41z~-h{Y~sfoi0_SZ&+7B-t=Rzrf%qbZ@4{$nQbM~1QpXUrU3jw$-;rFDaAU!3vp`e>|OJ|l-#R@&&9|p zW1E!?5Wj!1!o%k0>p#7fyV^v>W#0GP`KuYgSk9^$7xFjK{uWmueBP5dSVn0rmblk) zS_o9{(Rcn2#`S;SDb!%J-^b4y+GTg3DRRQ<)qHfZKWpiHcC0SEh63OL2vwslDCPX5 zgJNbz7pSTOZqTtTz%?`IQBy7&9r`ew3cwe*qoW+rEV<@|iyz?)@q=L(7l!xc$VAKBoP8ZkS z%u^XcGRc>NoCEIY!^O$dQu-hpb$@-zMGqy3LEz&+|K@+-t#8+asqUMf+tHf zHRS-nUkg`N85tw9-7aqNA6_75XJJFcH%+gGhMe+#C4+%uwVTw9~~`eETxUWC0Y_*N3hF|4PPMBUt$ zLgXrvuw{vr1Ng#Gc5h-|Z1$zH$5ho&DWfnY;Iyk75K&(Of-Np!n%Fz=V=>au@T7@CUIS zh(0t|yTJ`30zc^TKCFw&#hhZjINWF=rc0O?xe%!zRH>j0o9tEXRI!+lGDE9t-{#3l zs^eHli>q4_`i+7X<+5aQ{<5bv-s|oO4W2JNzbR4xTia%FZ=$tw5ZZ!;W!p(gyw9B7 zj5nQKQAQ~dqkc4upYPk22m={$^u^>%je1tX$YSn*j>Q|*=0 zsi|;7?>?r+!rj}XDy1V=NuW_Bl2af;7LZdSQYMm{qN7Mf@JH24oAKfkWX&WA)F7#0 zpc}5Ox5nMk!$U$YT|+`zg(9>KMbk%G{4Sa#zF@CZBzwIXt@r!!387cx@gV%yzX6A$ zpju@Mq>n$m`VuA4@tN1Tg-~Am(_HK-*l)PF1=glt0L-y!LD4~immoo&WK}Yo*SrTB zkL{P9n3Yvz_GN2d@9ch8st_$RGp%#wh@T~nG|F!FSawJALLW#8om^q&w9%kav4)GO zLoF$Q4S2)$yFs}*M-6P#SKPPxdjW2NPNMxy_GSLgCw$^PO;2<~Y;9Onx9c@ubs+lv z@7YVY?Y%OD!P4&{vx^x)c2AC-qEFI!bW!w?N`u5bqoJ&Ohdk%Cm8MWAYqWdkANu)W z3Y)EWX0v%wO1Kg-4!2Wu5dkbXS(RB+KUzgn^rIz}e;F5@2)El_lC{vYj^iX|uZkbK z5P9}SkFt}?a#euMv}~ystuJ1@nrG8&9aiMbU{Ag#Y(1G!i!G27Ik*(CJ{|8 z=1?6`Kkl$GM7Iqbz26)AlwB09<_0DXI#r=xq^Oz(ats9XKMUL&>0mqT{B5djT z*v*bZ0dbmGQBlE3gt9tX;ktaIy^Qz=x|CQ=_4sG4n3w|lFOF_*=$$55ppOMy6MZx- z;$MD5BxSG_g&dMMRgv~nS?WPl78H>n;-bfoLu6Iyu@hXHSeiLp23)NRy2yWN)U=Uy z8^7w7j(+m>Tk@PIx7jz5hptDk(^1CXf)A~S?dj09DL@BY8T^OmNpUb;{-}(z_!*UH z(ShVa@-FZlEwaepmqv>I>bV`X)loIs5*Bor;FU1Dxl}v4&T1*Vzy_>k#`{eKFM{Nm z>*jF6AC%X7sciCy@s=8U6J+*$j`td`&!J={-oo^|gBI2M@H&+^bbyJF}j9uN9SZZyDTEV;-UO~~}|&No3SiUr4e zLFr8*b5d7b+n#cQ4bB-(C|2cke5ShBJ787z`MT{VyZivvT1h#h@uF%2Pe{bTniQb> zI+?wrU>&jU<66I5x8_QREq@TnY}Sm7+TzpLjWBWkr5igV2=F{ne!6+YoW*qp|h$o1<|nQq_997hYgfKZ9QE)ea}Lj@_S;=Ox|#H zEemR@!fd0iD%|&;4ZQjn&k^4gJ&2UI^iZrENL(0nZv~0;)fd!SLuGY;b$`kfE$N;g z0R#yh3uT@1l0Y_~;XwK#h>-3)F)xorf&CpTJLRyW|Fgrz+@_LoEg zborGL!r>R^Z4_q*xYbbJ(TBm(8r33|+kfzSWJkolqa|0a`l z8KQAl$~rhYaIoop;rC!{!qz##GoRi}js*;CuQ+0l-z9mXa5?VYE%gmif-ovq*yaHbv zqM`v^i@fwBhx-rY=nz%RQdGP$HwCTtG)=d>^^Ct&w7E@1-hIcUH-W&R^Ax&)_Q&Q< zp4_mvGML|75xL<6Q(Q#c2U}RK1RXf}O^(M)-4bOvWfXQx1*lK+OAp&*N%}u5(54We zHHSI>)e==93{~g4jDVMw=WQ|?I>(+;*FR>Bj7IL-D2k~IKygeD@*P;+5Ry;@kxwAT z1M+BOl}WlsjFY_0R%I*MmWOP_M8al9|= zr&BTXomA&UF*U4!=5P7=@`_cLk6pW;dt4S0(1`B4zMU?4sRUpMy&Bq^2nduQv_2Gu zUie63OLv*8vp4jYeAR`Av7BHdG8feCkx`c{PJK3;j|m5DW^}i_uzsy0Pwt694?uN5 z=Qq08St#g%FUohw%ETF6ZvL^b4@o~EK^wqR@-tHy0bl;?8Kjafh_wqxzasF5WiZQy zENtn1pZaF9{&+p`V>R}1{T57J-Y$PWuw0H*z38CDw23w-H@1Dr?DR_ZZc9rvjo*tJ z^5iJ|{r;WNFRQinUy*`)Z&*Qe^X;Ll*aKlB-OVrGnhUh;@>xXuewZjut3g7CEESgQ z@~BpbQF(nNQjIa~#k$!>dAuOKJ4l0yxF?(lgEfM5EW5ZftTO*RhZi1t3^xxw+TWyW zN2{vR5>xOQ@yzgptBvmz=P^$f%CbcSMQ zKhk!Sj^g;202W2wk#u2A#>n6fmB_r8A$G^skB8$0qWH_x_lX>bPy|UL7kKur z5@Aq$BS978GJcy>m8xUGo@renw@$1Af^?v!^azB@FIeXRs2$1J9|%Ut_mrZ2zqlV=sY?^Sr3`kr{9Y7 z`cYwjMjTx%Q411+9N$Cp+uXNhlMB6P-4Cz0Wh>rCyM$|t#L_H^CvsiS3wCZH}&QV34~Xx4VF~VhE{-*HtU9`B!~&h9m)$N=Itp#|sBp>XD2WsX z;96bZUj7*u;sF_TlzQQ}gSC!O4H5waF!$p_L(QJ~*b1T0Sw=evsOi#OE`6HB#v=kz zO;Gm#3Aj@N>BD%c4FfdQWANXF{bz0IOb!K^YBDDgyr$UP!>m`g!>#>pIK_uvG7Y`< zg-P!|vOIp70jaK=gr$OVH60WD2B~%4~2L8iK1UVi%+GR zDA?d+dE)u~f^04BKFJjLke&KvEDA7n0`M$Z~c8dBj9HQTR)Jy)5v`#OwV(n!Y+J>MrV9y1TnUT0pubWB}>z zmXPj7Qo0*N>29RqA*8#NZjcVi0p9ETeeYWSql-0+GrxQ8KKtymx9OuW^ob*o=f&VJ z&#S`tIgmu?Y6FZt=w|L>=8rN`LA z?Y_mapC(XJWgEGYAz!36{uV|1;-7%AdUvm-)s#XO9|s(R{u{_U5D5iZ4cvDC$XjqMK}Zuu8W2QKp!!A_T)!C-z8b6h%O&3TVS-TnBL2Dh5peKR9U-tTG z&U^je69n7^2Z${I0M>L>VmO6fo++BRoVLQ?2V2g74`S#8X zLF6UTgCY-~EUB2AF8Tgs${66p9`lMd6UE=J5SeaKA^Ii2F*F;*l760KO3GeFnMfV{ z_S&ZWnhqDH52*0bCMaX$~{HL7sA+`9sE$w zqX)%7M+N$Q_;vq}=0Fd}V>Rcg_+G^5ZqIkg`xRviWm_@%qSeu;2d-(|EW12ah`?+H zZ$k8*y(m)L7x}Ylvu-Q+8K!1$#@}j=XaTcwLV78ED_L(_))8^682v%^VoO{s^ z#5?Z92eN&HdZimJ7W4`3le4g)AtC^4i*`}?+f2i)@1BHgcbF`;G<2CT5YZOT{&|td zr^l6s0~^Y0H>QHNYbjje!JGteZ-&zML=m*>Hgm*u`AZ3;dE@^PiS1}}rbN5(A58Tx zaZbznviUor(YZr6z1NXL$klPo-OWvimnwj`r_0|86jvI)8#x?_6wPec(!VX#Y@}v6 zDyy$fZ1=;S0O);-1_q*ldI3?llpyGWo!QR@26UY@03=-vl z!VIwnXCV@=?YHDK{zh}0df(Je8SzW@lg_?8{q(e8YGlLv3ozfiY7bL>6L`k*PtxV& zO00dIIRI1&^gWbt5)zndQz`>9!GHZyn^D`DW5$LoFz3?$wMV0miZsk3gqoTF=*eg{ zzLycaYshCA8ZoVD5}~}vp~X|NK>ai7<@iWTc&h&)w>gnnx9|Sxob`=7qJ^f6DnS~# z&Y;4P_y8x;o!2cc$AMV5^I=GBb|3PPB&>Ww5IKD*{KY7@(ODOV<_qX4(B^b&fy z!sW(zbz8mFc@mvKKmthtW1BWvcT>GZoEQk%(Bm=@ci_5bDN6>1>{t>?vPJ)=H>PPZ z;BPVcFd?r^u^9@}-Z!`%{H1a*Pf`T`tf+Qm_8+~?BNqfQhJBI@lgz}URr+*kDlC3I zo?5kRzj=Ffc;u4ecIV6MFH6@cU#RGi6S7_fwv%v>|I3n(UhMf07%|+pQH%zJn_prN z@ZmyM^V{Bt6mh<+-Z2BxB8ea~xNtJz@BmzJC^9m#_4R%`du^?kBfsNL<768^I|)-b zV0UVv^g)h1Aq3#cC>da#n1&47KQICx0_(abJzZlAu_o&#xazR$e%GBXNV?dv*v zyM+Z&1HE%xG-oxFkdT{$?4XPdfnO8u*8pw(JVBD@YrCqTo!4N1C1YfdQ#Jt~?tVBs zk&A)Bm@J(cD(b^O-k+-MCd=P;rW<|zS zGRMk=86kwK4QG&I8iLpwf4Jq*HpA4#s(@9wFX2xDm+V9C8#0>$^}_>)IdYxTY0)s1 z>BPya7hk(~*;q1%XX)%6AKxNJRRx%>mF+jFi8t5f9Ku=)2vU= z#f4o@8=_)@&Cn)*7w0zvQ)oSTGR~u}YFfCD%vq*7D5gaw9qG_U5!?makOF1dmrMx%;xp`m7@xM z-F)QE$N+}p|MQ0)tTZP>EDxq`cq3Ib!n}RcE}(5#fYVAoN}i>* zGQTV-C@8p+0$UGp1gyt^4tPksqifTIZaM_jTChLWH|k~ci^%9U3=Gr+r1r2kYdD{E z5-?eeJOe=*81H|$J<#CzK!SSptgHYfPJmO}ugZofVS;cG-@0XjPkjHl4lo_&cG{?$ z%+Aad1HqYD;!n((;Ho4MZHsJanTp|kuhUycJl+ywMEW$2)Ez;?K%-YN|FA*!;Z;(u zd`Ud%;7yxXHo)qDgLmGUG7w*q`X@r$bjBK#Fs(04= zX2*=IK&WM@U`Z)z&YkdY-rLM33CkXjl$RU`HIP7|^b`ALjY3>h&4RCK31-Uh8>5{S zOB!8d1r`D=hM?{HT9;|CVE0dha&CB`wYL7uYa1P%N&f}uCq~s#(rZ&|95cCh6?c;Q z&BSA4LnMPSInH+$;_Ju8qt)eb)IsAWlH3rvd@rX!*=Y$`3vTV3T%~fJ&u3B1wb%b4 zuE3o2JT*tLHU12m{j|OH6|XLnE#^2$L06qXQs#e0#&C!|L8`#}&l<-Qu+3nuAMqO5 zKzsvsVwf`47}F#vCX|F-T8A8|Ah(9hNv!)ca7|U6`!`;@;pS;OYiSkl8^^E7pq-La zzNL#QnXs@ckxepj;yjqeNOKGlL^FA2Y1#cJp@Q0$Ykji%ql5FYaJ~neMZbDU<}~p9@ab=n#@qR%?2HdtJayX- zC3xH%T`h6%sbYaH5$SeKALn(9#6T^W6JPXWyI;IB+KR)f$G0thH_C#z z)ZVE?I*a+gwJtnkhUj_h5iN2pk1Q=NLWSh35P4Msv0t5`vW|GoSY7zhJu4Hrm=wQ$ z8BzMxru6r}!ofLV8^VFla2M-nMqblLZr}(S+evt9iH(6SKSr}a+OrVVNn^9EQP?;) z1QZ^xTF!fY$m1ro8=H&FINR+oH!gYqQI~lqx=Qg&ij=utgQ~MS%UOL*_h^IyExTzN zVDTeq*|Dbg@Yn=LAL-3&t_WpMPRsY2Vmxzo6k}sVqR90?sZsX4O(lLt8qgN~a3;U}_aOo`=OoBK->fvI3ZG=6Mc!~4 zvaq~Qu&k(osn`c~>>^~~1kHL;6f4u*Nm-syH|2CpR8XoaTQy-Qzp`7H*6N(zay0x)t1{hC zl1?L)^{Z)gB#MAWrh`V zmOh6i`nUJA7HqDDW%)kAHN0EUNdE$VY(=(Qe)GNDwxosgSPops^A+}fSFs@=oCc(% z$I`oh?Op$dyVFMz4JI`aJBtL{n0LrSFyP@BrIIz8r76R^xPYOh3jwoBwu=kN>egb! z;ohi3onE#o1Hf4?=#nVXW5ad%{_K*C#IW*(|&Ka|DGw>KV5&B7w* zr+D{q=T8+@4Gf;;SUPI#&swnT_KB7kj=W4Hyf}&wDv9*(l}dfHe@U^-kHDsR^Tf1 zz5INf9}~cbw0>!E{xzM|Q~xEc)^v*b`sBkUk_u%bBW3jD1FUgIUmfz3et3N)`78Nmq8Og!HhI97${q8FTtWO(P9lOV+ zBOgCp@J*Zq5c0ST^r*kUzbB44SUj|K3H&n2RBNM7%#kkL9pIqINT8}wx173-${!zx zd3j{KX!6GT9WEFI8}i z=6eusAeBEPTTfjHJ?#&bp;XL5X5j{h!FBdqG%|~ef=?J@8#V%rDmIoc^xplj7I=mz zrp!m`&Lp8Zkh*cjcJ0yK*rcF?aS{-M&Sy%L^T5c=BknHu=5noA6gWaJ1kru~Jx4AR zPnmfled=1LsD;Jdo6JVE`wkJFcyY@3S!O&kG5}IRV&n${FH=!bUmxXr$Py;q?=loo z#J@qFME?bfhanjU7acWy**HC`E>Tn^FyIFR& zEhj(T0!d7$5fp~FepdHs`Qoh@6eW4>iPVpK<<_oBAfMueOM?J-X~o@N<$~;O=8t(4 z59?1ReF&C%mDeNVdVeN9tCczgskWYBl~5n-Mcep>gLSYsQj{= z2{hn&0i-<{TpT{v*6*9SAi=)XGc)2{IxyObVPjKYQrZNzQ24{@s$4k1h%HfTu#R6S z_TnD?@^VaC7Ey3NC!8*4L@3LrCOWXjI~`1`3+6P(Q~iq*Nir30Gv0z#r{q1we(E1D zL%rvlv2RG5A1W**}OR_yT>P zi?UeGT@;_4aMf0d_}&@s+W>H!88`7E!E!4FzWX}`>CiF90Ck{Q{f4 zqBL@T4-W#%;~sqA02)$~4eu^!FD!7C2j8s))Qf0)pcNS&o*p7I!{p%>Kr>syf4QJP z&SpeD0g5C?%eUA;IPPR>QIxJ_RPQi790qD+SgU~5p3viq9aLcy92UI9ngJ% z6>)1Ik{uiG{@}C1U*5wY|IuV zq@r&lhF5RfOS?729_bD9)?piD3bpY!_HO@9Hd& zDEBTdxPA{`*QkIX(u40JqMeW+Rl1$yd1@Mk7Zz4@n|t_+qR;^`3o0z*@Ex6Mm}JUO zj3NykElDcjE&cBRt0ka462vSy_<`+z&`6O#gmXH`%p73kT@(aZ=z5o;+>_-hHbc^h zXwCuWmnX{=7X?kEn;ZN=YMWuhTkuPvqUW%F9q?)Pq1`LUi@7D8C7taI^8ar1W&N%# zAlCc$@dN2QJy@F@K%$aPNWcbIIVj0RqgU$wl&r{G37e6Cw?Z zF3w+)-mdJR@$mUwEaUe#6?hxR?q@sp-fx6JZ|p^wC^#rJ=*NLdK#e?0 zVJEKKPquh3yf9ZCp+a-BIJ-Q9t01nw-=qZcRC?QXch$^!{;)Th2p`$ZkuwgCFd&Cz zhnHybE{(~!8aa9HffcyF7SNqv{X?e%z?R8;)#^f zVK2+hMW^xLmH&f4wy#%-#pXM-3hlw9+>^~X;Sqhkl^AMicE}di;-MmP?v90c^SaT* z2mYqLikeDv@&kHy_E1+ESvWUGB;x?2(FIn`d@}2KQpBb|6FG*X84Y%V$v$x?s{sg` z=sRxZ8RF|BTR)u@b99D>65Vmc^DYsd{5t%(hB*kf`Ltdm7@l^aa!_IV*jpgcAqP8w z8DX5qvw)zqz?!wBZ1IR@MWw>hR?2-&lKlC-zx)pV}{1f%SN%5C%m#47!FGu5HXRkZxtV9Xv4!W^LIQe(`9!c}?% zqsPB4fF#^%B1g*Yh_KE5ZQ1v$!MOU6xi&hTb2<*h-&VoPXh@em+xE_97joI$MFc;8 z3W4PJ9Mir(QnNb}$jn^xON!+c^Ey zUq(<%2g7GHBAU6$D(b<7hhvg;Kiq}GCpyswAb-RxP~9u9D8D}obp6%rh(yMJy0xG` zdf~$$inpgJvh z#&3LBPC+b1BfX_1>E3ulQeMseUN)=sJPY*m-&j679CD7}@0}aL4RQX$*y!ia3kWH~ z6`4XiK5XF!4(4n*l-cb6na2}2ulpB$$U+yV=$sKw%p>U|<8LasoRI_@vN0Lxf&Nk` zc}ansspb_N4%b37^cnVt-NmF?q>U@Hc{nBQKTF` z55I)+@AZbSZaDST2Au!ytG!acJ2rNjHj#^SbenN>_7{9_8(l|Yc9=Nx{czinMmD~h zj&*c&rInA6BgW}HdMfH^9`au$oq8ofCM-CVNRNw5@WlN{ImQ?j(}UGT%u{{`q(nuUYw}jFb0rYz8U(bumEdR6PLSn zAjbrEe!iQlx?qq~H{7Jpne8=IHwCap7VkTpDxJGlJds!|^k z!8SugFj>OQkNz#hrYxL)U9qrGy080LQ^LStr$Pe_sJfYEtt|iv`Nmd*!r0%^^2*Bm zpoH4TQzJ^4?S8YcePZHRvRv@DtMX|3z8p>{2&np0%9vcIb(syM?n!L znqWe2_U?|D^p!@_Nre2~2mCY?->%GPI>Cs~QYAq)UJm06Y6 zs16%UjuHU@fu5fj;Kw$Y8I6=1cW=~x8*mrVkxKMJ8`oUH|Rt~k6T_5`*qFW?0BeiEU19eh_yN=~I- z=!xq?)H)EC0p3q+a5l#1OX6DI}qkzca`_7^a7vW{j za8OJi+VcwSrpjzLal9})`M$eL`|XuPm>hU3Gha@XYZhkstLW}eeLR$@MiXHCH*z^Q zTCp}`z298WwwPcy+81f8s#c^xewiE3f71+6D)F=L9doCqzPR5fOyh|CcNFHz7zWSK z5mON`YLr{=p(Eob2zkno^Yi;2qE|IUEOy`XWg+=`O(cA0nqNQ8vGRvd3Ry5G4;wDO zZg#LwrN&-8)WjR9VrH!Q5!z*w%XNre(o|)gmi1@*W|?)VX>=%sSr?tSHln{DnM0__ z20{BP7At>G6o%7DnCYR?EQc6guKeiUmOst9hr)(SnNIgwf3Bw$x4j+;9;3#4<#e_U zCwH2>6FsHQ!5+H;s(f`bC08tnZt6KwiazzL&(tVtLBrdB-YldzPY2nu%{Qt1Iwx+{ z_FkFZHpqpuJtFJ+oob%01t)}I-SllXn4J*UUS1+vwT9f67lXe_R&apCZRA#S{3W<( zkbx_ITw-lSAU<~&=^$+d(H)0*E^5;Xn9qHRC!%WG0KUgzy1QmlA>DA;EQ z-wkKw6LRzVC_!#`^7Ir61bfalL#&fHLh2_l=J@9DIdJ0fmh9Y1BL+OY4C!-xw@%=Z z3dOUq@@c*KEw5Nije-IbEcxzHceaV0UeC0TV>jn9)S=yGPx_(Q-AZ9tOl-9&Wx0PP zn;J@6qW&`&f$-1K{EE9aNvH4oF1#H6jqP2kkF(9#&s}p7b4?g4-UN-KF?TxPmnhBG zn*JTj^-aK}P{MRmexv)URE+Ds4;Sqx!AO=I8i3L!y`i?(57cF4ALO2q@0eXRa4OD} za=JD<>`y$FeBpf>)wkUAUd75no}F4XG&HQweTvjMYUv@sHuc`CQ=X`L*d{+NR3&Nr{b|HTmvFxn3Y+D~=VL9%w4CB-y&AmVAC4zgj@G~LnPl3NL@Lg&L zVF)gJV|4%oe|DXy;~)JU%f=c@=qGl_)Z8Y-t5>Bs`IQ5dpif+v#|_LH+ICV~8$XHE?{@I0K&vqT1V4$1o6%m6 zt2_fkpWnO)W?WFR=^%KDU^E-TEXHc#iqT0V(fbs+ncRP;(oOEx1hqJr`mL%%bsUkA z+)rDKH_m1Z_P@QdeC1FBU+wwB`MPceg3;)!~i{tosM18NPN@d67z0mI{YdtoKrB-%I62q4!z<;u6$o{~U;A9Eh!ut*}3x zW?l)vipHwmU0#WeIpYrgOtPx-BI`M?ZsqyTT~uII-fXYVfm{+9KAy>&{KH*s`?n6g zLjjF5l{i&*C84=r-sJynnU_KUB#=Y?G8%N>&n(_ch}@ zt?-t%NFD0rsr4Tft#dIKbQm^_Yr=@}EEuJHT>2|Eb^q4oNf)PA)p5RR^cPXZP13-a0;pxDO8PibD}5` z9*wgyT4%aP;>{P%1G?9vmBZ`uYd2NUk2D#LvMu-A#M9!m+t~1u$f=cVRJyv|1_{(_ zO9{};YN<3!`e>3$tJl?^5_82X7hc^0?=Q?X-cz3(G5$IsygH#|Zhm3AL~ar;(-bxM z5(IE;?#P4!tRyOIoe*m}k_L4@3M#R}NH9PO`}?;q zeM>K-TkwozlaioyPO)nE%sdSBkMU;U#skPmQbjJo+=Ip=lF$vOms`m&r32zE~l&@YH943hXFCNO({W7nLDG8~}@a zrCg14qP;K3e4Q))-zTwHz`AP%TF{$Xb`f=A%2LjZiCv#kx;-=$8h-EQtKMMUQnnid@Hir}-3daykWp^Dl5S7n=(_;?}>-p+9T`~EoRAa2Tm`)krz>;-Ipeh(sK3SWQMZu%i)_| zix{zOH1|?!!Aa&Hu+614^DS3Ac=0|=*|p-?Wa^`QmQ8xR|uM&5IoCpr=eROsv zdF5;IyHO=dRH=3mEn{P^{z#qqMc0FyHi6CL@+eAP$?Xo;2?TIylVS z1`-^^NxemIv-vW;_H(5{CKssCy9@dXt-EPar4VRBqM%CZtd38Znn&QUI z>%p>u!McLg(6}`N%AzK}Dhe00ROyBhyAv!JdLa3E#f;{~~k4W8|4I znFo-6=s<@dP)AMFA|oEXhO~wV0h{Hu=t4E-cwQ2k;?1S9X>w%_6!;YX-?<}86daa0 zm_!0(&z(mJN!Xg|H6ril6R49ug*+RY>WC9B5&ZrbvH$ZPA&Gukw3Yp7MyLUL?sI9Y zAQw|N4Hbp-4j!d?J>TPl&xN(7a==z}oL0T$kA#@tb8eE{+owHQ&nM&&$-QF(`LfQa zc0_384T`QQW$BdK{S)rGAD)8b=QJQjU|?WqgHr)ed4AqjO%3XH>gNI+2(aO4gvbpW zTm&?LEmxs36_czv@?ssLM+j$E2*Xi85){VC!wPFFmT-aKxUjZ5M==^%2rm@RyHkF~ zalK3F;X2Y_Fy1FVBU zCT4+#sv%Yo{*;zyZ{p%I^WbDEZ1_HdiY2 zmNc`;&V1@91c<@d27mzHLS z!cpN(jlbf~O|j^f$q~x{oPhd~x1KGTR_GtJ$eB(`egZmQLGU|4F&mgEa`w9jOKq5_ zZ?K+*c?AoDlJK)bM}29_Waj6H%phxCFVt~U1!l#S*TDNL?l)rDPBr0tuv@6oh^G8s zw2{9R5)o+SL)C6i9gKXK^Fl-aV{V?u5Nt*w^v4oE4Xxk|GNO1@dMo4|cmzv$tp5|R zLam+a1pOptS>Cnp=u=Z|GDU^II;EuSPWYLxzxYG~zvqJDX zg|tRd&${_RV!`1*6bQXK0-zLCHm)-It2E@lQ|HUPapU^-tvAV!z%x@e zeZ6K#UjviOqc09_Fj?>q#fbALkxH8nxx({#@MsnJBoxLvw;2D1i-c5&q%3~@8Y7qY zT8Lq~54V6kdrWrs1#$JFrZ`+$AQ$H45?{Lv6cUZhEvm;}9BR2xUUQ|)jw|D7J_d&>B$Qc*)8A9NSqBL4U@ z;rX7g4tgGcEoUFE<-W%e2)#2$2f>&MN^udR92GWSCGVi;_s#O}rt)MZfIhYx^=Rbo zyNR$~Q`YiB9L73v7~$l8vQF)Py&c|K(11utG7A@RzH86?zB;a^*d6s}pe{1$|Kg*H z{T>vSk?}mo-FfX~z)i=X;FU`?Z%VGFxZdrGvrKC+864ARZ<8cUrwX>G{d-F*Q%6Zt zC)(J00_h4{kxVlOi<85k)lEFQqe0U3Ie1TL@PLcpZh4^MJm{0j+Klx5<9n|=M9Xn4 zZ20eC7hd$ItxU-~7F3R%?(pL%>XwLAUx{-+2a$hUFc<#{t@Gx*%WwbvG>H&WYpqJo zsy)E%V8Ht^@8s@@iT8CS>tN}0vPnJ5x=tIWJWHz5hTx$osq;bEJU3t`GsQYH8sAc} zq$+AH9CpWnHVh1>Qw|pcAXBlQc7j8|?bJWDgwNC&A|D z)86x(Eir#}xbt?({dK`=I0YtwLvzwA*xJDE&++1MA8#G#0w48ph>Y%*m+d(|p8k2C zq5!#=uF2b8%Dzs4hpoNB?$`gODL+RMb8N(-MhSiehy@TFC4oMRwI>Sy@J*d%bRs5&NQPn$;|C7e{%608mss45 zfcaAMJevC^hK?p@F$&!JR^JWH#vjFWxzkPcVR(msxjTIX>vW)>);@s?0q=(I2cJ1P z1)jcZOWPMS-=ZX_Gi@%R+E(haBMR{7u?^htl4uhD2G2$pf`0eZVheY79I&+oD^K0T z2A6c{m`rJ=h&_w#L}BU5Dz2?#Jdl>u=>{2#TnY8!Nu~#5I#hB@0vj6~Bexm5RM(3& z3ez>z3<05?VJa5L&!8BNPi((`w)Ikc1Z*(<@PV5ofXeE{DbB0znmapQ`79R&BbuXg zMVvf=lc;Ts&AZBmvL;;6k)uXt;oRZMrkVt57-*}1NUz4j+s~HdJ2ty^g&XX9vEnsbm&da zDieVffClFXp;WhycDdl)okvSuK};mlwq%V(R*C^&-gm!FTlEsU5D6*ezmaP5gmtr9 zE?s{qo2h651a`!v2mAgLJ6cQC8G%mViMuddO1j;bcr4JfT3)%oTknIj3o@;GOtgVuY*UA&DU~DxwOSfySMB8h8N}^Rp&LoufclRuGYn<1OnFFT z+QqhJsfO7p0Jk*1Gsj^rFRy{V*~Y+4m4Z;=3u=p-eMP_14q?wGZIQV(;93=gzm6W~ zD(Ex@Vl3X0hv3IjeG0}ltw*ov{@Sm=S@hmf^kty+BJjm`jP-ufdICPG}>}S+(29jTWLN zM5UOkCr?cclw42Bu-nQJzx+C0FaDXgDpnddf!^7IxJqcsjp@vv;rc?gKc)F2nq1wm8N3R6GE;hThL>NpAlNM$=TBGHD=+eYoIP?n zx{y0wv7zVJ9$c#9mBTG8egHjz52G>%aLeI`KmtDTiCejz>kwfEZT1~0+pTxY7OBN0 z3mLu=2=F_e8y*M#WS0j8B*1(EY(%vJFW0U@fkf!E;y`?j)%Ahi)|OI%*>~|$@-Mhs zDLe76)pyJLh^~`O8o$VI0&+MIn=}?+t$3{}za00p5R<+^1NWvZ%h9d7+itu};l%;b z+Z2$>W~oZBfj3W&qF2%vvdBDN=I9Um^+}?v`eB2fq4YI6z;$%4h?jrDm0KMz&^m-3 zXnYDAu|~T9Ow<$VrXpmkJqK^m?fAfKp>pMmCZipGI$7HDt0Rxz&c)YxOe_TTY**u( zf9G0`TFP!2(8msLA`a-O$(bNi<*D&q{<$ElD*u}V+071C^qS)B&X2M6D|T<*pVuPu zS7=SBb3#)u4^kE+&s^-e{*UP3!IN=2@$*Se9v|LyZD0&!jVO=KSlTw5F;52E432pn ze60>Fe2Dyi4YG82R8-%q>TlP)!SZ%~?MX$ep_3%VdO$l-MN=lOc!!uy7v;hU;7q?sX%*!C zx$(Ud3nT+KFx0hQ)SBM;lo=}2q-S-YA`J3)2G(D`4m{m9n+?RkPKYj2y03G zJ<@k=n_pTUL1w-`ss20|VF!$Z^E${{L%)616M~gy_BOoxv4U;1qi&PutI?B~X0@Kf zsVj-6<=6Q8d4B2|Osf?*smD-%a`3=z=1&KW6aIIWURw2JbBQFO78Be1pk}-3AvYB= zoTHF|-pa>q2R{tfd_B_XSx4I@)h`#bBm zmvwO%&d!^<;&scKpVl2LCMn^(y@j5iZ?_oFMhm$T%s+s|_!N0!R;aR%pMR=i$ah9Gv6%l|mP> z>Sk_>5=26C*=fP%`CAp$t10+(I@2Sx2in z#&S4Gpt`-9`;U<)*WV?@u{~;L=I7aV6BKxpL7JjVJu8<3L?T-7f%(C7XH){h=MFB3 z{tapT$E|@uq`T$ys0_X;;&g?db7h$;Ugms8XJvUL2(T);WyOWkA%l39A9Xg(_pVRjbF1J zY{#1xf0*to(b?E^C1|RnWcIpvnRB=~U=U$xvBbeiTI?O`Dajge0}prU3PN7m=Pxs} z{$ORv;?@DUa*!U^w>FQ7-^=Jo?t{mkH~K-xVV6pP;=PRZf+4@eAt+F@R- z-9Onc%W)#nnEUUE^FM~ba5@>&SxPV09QiX%=k35mP%%qmxDb;1Y1zu``ru|P z*Us+L^r;^V$~$iKxO0VC!Mbeylx7^!zwUj+B*FW<2iHv~Q`-nq+$9#enA!Kpil%G# zy&N)nrbpni{EpJM@=GG!krImqEku4MLW?zTruA1Gg{(tc z881kBo`|DhbZeuglbxe@6y_xj(P8^sDi0MHvAS|S>$IGkE4_cPL%YA9UW9Ipc{BZZ z^Yf=3CizsJQLU{FLyCq(Fu_bdXAeLJ5#k3-qJ00KP?Y{08v1IsB>m0D2^ybkC*T+b zyJ(ax<$O_tl=J5werzcJJF&10%mWYTIC4m?HM!N3?I>&}G3HcHtLLGwi>; z*Cz`;YvThraL?i`;^FclB%9BOkUgrPn6bk$MKdXC0#bFD`up>41iy-!F;3bOKA|lL znTr7bNdS7LtMo^0H3Ra$u{8)eqUp=uaMM>1bZ-rn%*QOIEvBnW%B(%|09Cwkw%4jf0Lce))$V!c-p}eJztTE3YnHp zvjo%e%=!ae#7N+jJ1KOoIeX_5F4tzp9@L; zey(2rIycifpo{~l6;rKw#P|C>krku6;_pX;cR2D9g|etal6(Ybrgp;t18&6SY?Wy5 z=)i-P$yJa5=;xu~3pGOuQG4;r%f=Nqb-u{RfYZ+A6if=~Y5afRjKzio(|(S+vSm@) zuZC^VUAvOCAylp-oF-QT5A>pfG#)lqivbl=G3$Z z{Sn^kuc`h)znGFDaXVTF1F*29EAfMG${(j+HY1C#)ekHCh|ZH4|CeV&#-K+D$Ex|b zP}v6xn<)59bvlJ^3I_qT@G<`Lq*z0}hy7UH*{Ykm9U|6g|9;*w@So&yu@L8JIt}bBewq%EbT;p}06!_H8%=485$~PG+LI zm;adYP<`R$Wm~+r=csn2NIgkO%`T!UVCZtH+4U8H0zDPLLC|t?2R=&z0#TYm)LAa- z1ZgAId#a&xMsnnv;>~dVST@C}Nhg(eoRVwx4;h;w}Yx`2!$0tz9oxTY}7622c= z*UD$Tp!+?p7EqMHv`3+BH~eWHUzD6)vOl9>2R_bocll`e^vQAXT8WkrOX=*-{fA`6 zrca791rgEA>LXLu79hYWOe%u*EmiSsZ|XjCG%UCp^?c>{IU&HT{kCt@y{^f^Sgv_B zCs=Z+eeu6W8xk0PuoCK8pxYQEH;15 zvMfCV81=7V@y|%Se`(eYV>qJ-{S zQf=&BE5R&1O+zM&r3za>TDGD(UQU;-3c=mqzh+Y63@!^D;K>eI@%JRj3-C$EcC3a^ z3I6k0;)*h4v68DmtFOg*UNJ*uwbC31+@V=YNgL0P3e&bBpg-xQDmOU%QAI6G!D456 zyP14?nvoDYcvheSro@3x0Pg&1;R=6#q7Zqoc3#?F5Dnn8L;G=&zFXr`Se&u^XgD0| zQ1Go1_4$f{oFzzjkk$2&eM8R}a4EO+4EKSZR}sUq)WqKwX5XymCcUyso+0>-fbi>h zy$0VTKK|Ccf%n-$Da|tKh~NR{s<6r{C7AC=?Y+43H^jp!|xs=9wr3bl!< zHZ%lpg6ro`QZR()V}4^)Gd;t?L6SP(SW1oQXl!(e#WnYzijd|HO>8^=I}5<_9EbOW`~Qq?BFTz}~@S(&AQ$RlhqF|r!| zXT|w>IWK(BAxt$yg6#LKNT=-J&y$Fa^ENNDUE!7HJ8#?=Eu;23n(6~TBe`23cfziM zg|P%FgLYT|vkb(P$s~RA^(3MYZY!u~VD?~A45aWAYuWNU@bA$7uWN*^quCvXnF}T6 zP@s_niCH=X5RbFPspNL+WDb1hY;fFdT%Nc59i7f%xydfpRCxsTCxK5*VfR;6|Cqvu zYcurl*U-mL!SmkwI@&EETqhB4=qt2cu}Xe{;l{uEQ~ZGuG+v2|MhaW4`>3?8Ujsdq z4;D%GYJ$93HwF~mwcTI2Jn+~((*8)}>-w$n_Ue%VC@Z+lWm&|b*nPX{i*M}pAQ}XU zuJyVp^^{KT1(CjF`_*V?LAYb*w1#Hq0;(S7|(Bk z>UvNLtI6!o9PVjbg@}uAT=Rd)KqJ)xWO?gr8n}`U-MF~#vV(kdOI*D@PLTXOE%4U& z94x$!0<7oR1DOkJRYs!-`mm*{$B_z%$+q3Ia_FZjoKaqDTp;R(S%v2{57;u z`PEH+Op*Z{PewIhhULlsjZKWxz?z0>aCD>R`-iblQLNRaG}sBme3f0^&m2Hs6*|lJ zDI+(6iobRm zdIZcI27>_?kg*sz%YY{IJA2#BtpBiq3xxgtUI_4wQ+I-5D3M+TVL<5iPs`|Qn9*3G zD$!l`+ma;=m;cmeuJ0)z5(rS?L$LAiEOzCKYLhNqn+^UIJ#a_>s~sH8QT{kTn5p=W zT?UL_mPSnJdn_WJk9!4bASU#hLFsMyFY=uc)`E&}zasUXqu!$tAj=KayHJZ*>feS8 zzY-+*e@D~y0s*ctTL$P(fu6Sh_!B4pTB*iiMY-D5f|7*|y*zfKqK9uldYWwiUcBVF#^n+jvzhG5^B4!(Z{F`G>$bd!1LKC)zYFr{;pc`M zZ=*TvO&-P*EJD)7!jX(Zk!nIvh+glb&{#|zv{Y`lF2y*r2{*J=WAhA99O$@+6s$>W`5G0^z*#+6v#9lhUHl+VID^kowfFe7*^ywec_%7G3euCZ zyD2z~Zd4kTtgO;v2LU+oKQw)1KvrGXw9+Bn-QC??BHf^*G?LQYA)QjvA>ANIcQ;74 zbeA-IoBR1*e)#hOud~nEYt77>DN;YX-IDtISJL-kJ?jz{@~C*gR7r{%Ys^Y`@mXYq zAH$gc9o3|X&B+E=DQJYjV$k6IHT9~mNE}#r-fp=RUlUrVq=sC!hiAOk-+#mAf~&1` z^4YB<#N?Wsc9^he=;xTR-TCYp3gN`%j9M{(``=GNKx`a6Vr_+&yUJqLaDL~*Q->a};-S2uvoy4U% zJe4B>ENXc0ySm8O?mCz?ZhtL^7^@}eh#(Pj&QR?k<#r;9iZ|W_Q=_T;!wy$rrCUaI zMu?+jXpWP-b(Hihd#N}eTpjYh0j?AmbaG=ELZg@5%Rb7*AxnI)eHkd#Q7BKlNcy7G+Ho{08zP;N6WY z&=8WCm=IW*@Y$!}vj3!e{hIFW1yhILTg6PzitIrUc4{T3EQ{Vi&vRejob8;ZDyc-0 z6TLr*T%94oeUdqlN(~s;Js$==QO5R9u)u}_?)-9^(UL~5& z`@GrwoQRT1i;)=kckcV zn(@zfPa~G4Tpec{*H@>f>ovnx+Km%kBdLRo+J+kqOY~ij37iQ>oNk8XCIuaJS{tW! z5>iad+}!zZE#ClZ2|50ErpnSh*vBuKNWIMqIxb-+bjRYqNkB!msP%2n1cwepKSn!_ zS+?!&vev>QHU4ZrE#+(o_dj!4_cebV1oZ-C*|CKyHTZjJA>2`cZzS&zBgJcSdrx)E>aR>Z{r_N^wX9#`yk+eD;P z?+9U^7>w4D@vzq%XJeW@@TFu}@>r z?d^BHV-)}?Dg&5<&r4eg;F>)>s6Xs7RwU?pzGlCnw@M_}M`C9xw$Q*YS-GC^Ae?`f zqc@BeWN~vnhy9%?VjBc8fkah|e@_doikZ51$YA>aDp4ud>?W*Nwsuyoak8byG2BDHHYV|hrHgK7KFs3BW3Wr<0m{Rr)ef3kZ1p`Q3x}h2!jj zDnM)-Wn(vKn4r7_8*tDifvI$4gnAZ)6?C7$ML}Ke?~kXK?#T=KUGYS@4+yWemu1@3 zF~Nu^XPXhwps7_-jekkpvI3YdAa-6U_ZSi3o(L9f!ox-?86|Sty`E3&A;3Sroi4TT z#lxUD|07x^wv#LyH?ytC>o~XT*$!42K$**xQiw_eDm%kY2nH>Eol(H;O8G9ElfK~) zQ9&1_)`!}?7IB&DEP=?pdxrdQl=SF*`!cymPM-?jPn1ErR@K=vtF>F@dQT82nL^(-?-7Jonj(QTLt)j7wW!DRm+kR(7viC!_i6zi*39?w zjfUVdrui|y$cjhz39c6Qd$LtRj$@Ry>n+-Pd}{fkoo*CIJk}1pCZhCr_NTM!U%P$V zVa)fisb=ECfhLsBRlT;WL3{lpBpb_TGo zTM>Pc>LsNVKi(NlbnREgx!njw9Sxq}%=Y|5Rk0=7sdU0_;Z#>csdnnDdV)%nA0+Y}KsGna34>k1n*Wa2 zBu%pHY=89ULauRemh#*n|4zenZ28*n+aAKAB|g_+-_INNZG^7?9KL*Ytx}!pu90XW z8WOt%c}<8;()yE-zbH}o?D3+d!L3bkM0<4i&kwkN%D!2u%LHUCef&*QtMvKSNat<= z)+ID(0_&$GGPN3N0v+z8^ARZ6D1xz_TyuYw)n^*-#M57|L3H=}f*DVVUwvElMcTF0 zAz+IF%9lx``?Dqj^}Uxp>x=8JeK6m7p?kEBAn~Z5P02w!of3E2E*ibwQ;Q#wz+5*l z@_1|lLv=?Xst|=AvwO3qE%I#f86cRSe&Ms>etiCsDov4)RcU;pOR&8?sUgqt;rq(7 zHpJWg`OfV`0pFuBjW)AFKQ?w835DtkLs-~SMBEi0R&135@mJb}$f{mmJRl2bxE2;Z zNEIkU!}j(-;c<^B?vB|~!v8y-b{rQ}pb@*GArd3ezue9wU$M=ds8?dgY(rb+z|9vOIE8vD|S9FdWh(;No*i6!s zD6zmen76Fc-8QslU>~N5L9X|=A6SlCL znfS%wbq!HB=*Q9?m`Fs`GZMk&*$F3I5k7a*pX? z5HdB@=FOq&t2Nt2Q7J)MB+{C>VQ7bAz|%vpszcM^-VQBnOE9OaQzdP!>~j+i`E)gswjt zlxzO>P1NXm&Z52pPk`VHj7wz#yUg|esT}G@xL=<@BnUSq&KEq6!VpAeIJ zKKxsfO&JvnLAJRgQhl?z^<-l1Y0s-pC|E>;8kXry?oek16Hf^ue}zC2*tZS!OKulp zsCoo`lVB(79K#!au+2tL5KUik7IE@yPRZ^zZ&pwQgd0nz!fFh*~bfS)7jKz$ZZ3)>$Pl^YHou<44SX zfcFBs#MGgo?>smF0wr0|Zx5%@Y<(pm4m~0Zlc=C&<9pT)>;{IX*?hc^l?3DPQ)RW1 z5DN8COlN^GZ~dJ@FijHWBuzO-n_pJ)ScuxZYj4G zIYe+pwX0*b*;DwC-LF#fZhMy19j1i~a;c3kUz=PLjXTf<5q{x!sf=Ksypy;Mv~Sh`Aqe42pFZRA&x{$oe2nCeoR0Ej_}XOq zYyfPSu@?St7G`=2Nz{1Ix$^6s&4oaCB=mIzn}^zwg5xwgV1=}PDLXTlC76?lX$eWntrsyR zfLW4Z$EmBHO7S}AoCii%#=sQT&c~ytnrrmz#b9YEEFD#XxDiIdh^zkRx#U1uLw)+A zmZbS58e#ecyzN3|nE@eP$Q1py!{}A+ua=}U4!=%Pz*GLz>9p>j{2OyL@s1t}EUrO2 z7cdGnM%y7*{&f6|+^V{ihyE7u4xkU60BM@h89jrV1>|HPTCVcOpI$eC`p z;pB39-Dv}-Nf&+1hoHYR5C)*S1+I2lx32sia84s3z=A*Y*k1o7)|z|Lq(DL(+r6F& zb0%q$uXvl0+r1T?r8O}UAQgafkv4XMo`d~M`sJeGYc_orfv4VwmdUS=W7%a;^&(Hq zUcWIt>O!@CcKO+k@~p$fQoi0gOLn_Cs)GYH@$y&%1f;^kE&cZil-e8ZG2K~Nfdz+# z_-A`e6L~~AVNmQ=*G@{7GBtde1)+b~N>+4mm5y%FdzWp$b%_IquhpGmTAJarW0>0` zf^BDy{by<_$tEw`HkSFmrS#qDzVDqc*R2pqn8!3T;&Ri~dFdd9@^dc&hjiXoLBzSM z8L*TkeAm;*w>uBs=-=1|`>(U#Z80FBBtquzHbQZcN&dtoZ1J^@Vd)CLMvDds#;1o)0Fq15FS(t9#^PZg{zJ;qX7bTG}cK6zsYew+7$D}&*JAAWO#S$Y*8utH_zD4XKN z4$~e$%dlqx-D)7lSQ<3yX*f(gKxbm&K{uC}yzW+vxgs~)kKc?HkD**~BBisY&b|p@ zpB_VU(}2%N2_rQ(>=i`)+^D?pTPx$%igJ*|XJMQs-PiEB!jw^<(O)znqnSU3dKr6p zqQDY79q@c446}R6e_?-})hGa5pE(GIwX~!j8j9vjv|cnZI+&pqm!P7Sr_J_#x$tn# zEau^-?5^`9 zxd(Klbg;{@E{F!>_h=26U2MeHiIIpm8s)w{k_m$k^z0M&Yc+F@YmRhIT{@HXxuWlm(xiW=N;20 zj}%V2EO4B5ODh8`C&` zx6HuKbYB(L!GRc9q@Qy!Z);#y(;IWt=O0aj^use9>y5XtE+dcm@`&5dIe2^T> zLqo=zX7KMx%tMxYFbBTA@=mbI-sla9H|CJYORC&joB6JxHjT;OPS~|lX0z#&kezDt zD^6LE1^%P6s}8H>ml1O~#IFVt#lxz?Yu&28f-wC`5dF{_Nvx-P+Fv2^QiqPcW8M?? zIX=E_1_cQTDJmi=7FA^Bw+6dwMFP_&#;YTpZwtD^r{6^dbpH?{n}|u@zk7Rr}U@uwi6+LeDhu| zR0-Q}4rP3$0AYoTlarHK^@k$7l*)9nm+(f4nUfeQTm#f*oOhz9UWt*SSN*N=+*>ZB zKNGi$5tkQNEl)1AzR#8gzAs;;qv-h#ZH@-kl)Tt<4=*~K6} z`I#>XEFRzQjKFstV!{pI<#7yqYy`{K)V!0F%J@L$7!;2l2MHSqLSMdpBL*92LuFBj10}Q_$0A=9 zlT(c(@d}KM^J56wggq7O^Y)d8imfEy@*p3T2gh z=MH2kPQXg6Hf>z&F&X_@VC{0uER)d{1Fko_Sxn@f8ZEbk*&EFCoGBtH1#LP$_82ISkMz=$9U4p?Y-Oe-;BAduv9Q^j0?!`& zD84tz&x)gv1I%I2h&+Y6yT|6HdZucJIkzFoz08T(^@U~18Xr@lIgAoH(WIKs4&@1he^zV~AN(N6xit8@t|6KJ z9YAMp9`XK>E|o`B3AdV#n0j|M4>jAQ>uQ2(WZ(e9fNWDJq0Y`EzR5Xf8pR=Asr6n_ zb49(R1gh<2RaQF0zxiaS-?~EN?fV;Qn?3Y|E|g}iv-Mma3#_z`AeXrbVfwq2{<|ku zV`*LkA3Pu_-Uf4``A;oZZ1v<@@f*9XkpGLA*-2p<%$?8Yq>d*>;B2j zk+Vf@(f1F8jq-XZ$M~tXne{RvPJ3XbXT>(IWn3CEe`bd7tcy`#P-AAkKViHzWop+YHwN2By>Wf102u5qJDFw_G`)5zoSJ2tc!6S_yBPM(&bU$i|5~8ZAaY6sAR`RC(dq!>4_vzeLA3UXkk#%4~C4~F7Xu62S!>D4pQkQPcqLY$D`fEIY zeLJ#-gogIeW!9^g)q~&I@R3v@BkLSS;=zpnp(~X@Ev%}#Txa1xSw6lITfJn8fOzdD z_|u{;ChAQoG{T4Ms=tY?YGh>3#(id$ze^G;+mSc7VkD|Qn*MevFO%iKfWqagNs)?x zxIN|(0IG?-we}x}6%2jE&SBSl0u%5MAaP5D)38JzUrH$CV0*(EW+iUPBSZUV*V_!_ zG)_Ku`eB2G>h6)NeYE`i#wL%=uf#f6)CHLc9{u(GW_2@R^XaKl2nbi;FZBA*pSpRW zQO#zKGyUB+EI`~$hgdINS6arL!HLEV<%*f*?ZaiYDW=gNOSkqx-{yt!HT|9`>qF-W zbf}D8NF!O{yGOFOjh_RGt&IBZI5xQOVk61p2mQv43Q0xB#b_{fNS9b@xR%2D$)@vz zaq`~yYba|&4cX!_eJ^yFR$2%u7w866sh^m?gy)553cxB7$qfkJjWpua`8L=l_O z3&Y-jEi3rR__=Tn4y*VZu%e}!8iMDN+%`+U-AB_qC)Z=|*MN&kG{?FZm{8hpBM~Ux8pCoqo{-oWiNl0u3NXM_Y z-iW6N3k3{)AYy4tS(u>8!1IAOdwGMX)sbz>TJyq2r(~Lm(6)3<;2FVzJ8LD#CZpsA z&ODivl!w{aJJW6$hPyitY6W^ywn@)>noP*Jf2hcU=Ha*8e7r^Zeqhn-3=+@-pNo!z-)d-Oq(irsIlY$K7N({~#z73>s`eyR(gC z98z-Chfhp+V3SfxmPSpCx1vP+5w)uQ_|rG#S~|WPoh{761*=ePr5*2TM>*e|M@0j&UX%+tIG&(^b*s#6EmENXL@>;R4;FhJ$(=!Pbf+k(sUd8r`Nc=Ui)QY6SQ( za{9D)EH`QN^v^x(I`#&wfjn)c&j4l1d>rdmY#meI7w30a*{s9eZ z74o~zBW$j_t@4-7XU4O8bsihidGz;1v$FoBL7!b0st2L)@p0gN+Wpp0%xcAfgnhBj zVXisM<;$wRkHSkr^kn%S)*SZJ#wwMRKbVe74M5E3^C^9m)&4vy06ns{yFd9y5oHkKZf_6q{ul7OflILhX$7i!U(Z+eQ z;+Hn%a=h&vFIbi{)$9sgT&%&HaX>h_+@y%j{LXMB1sw*3x!Wqqp~-0g%ZRs!G<@0g zXoPkrf+b*YezJGH)0C3ZEiCF94HvW=+0n;PFhjuGRoJ67&4MDl|Hfv)njJYbXs$G` z@fNdn*eqdD#F-Z7pJ}EBipzK=me=F?TaeI^Lkog-3+k*if=NYH<3r7}MghG0+2@(h z&#vA1Vki>ThyNC_@8tAr5j&9>>ck;Pl2K3Q*SkLDm&|Y*u~AW;+b>C$@wwvqg(8An zlxiTz*oTT*^sMxx;5Vfzq#pyU!HqbJ4;63rMeI9zR9gefgMGd~)})nPc%2;cM+@-l zMaXi_Sa)tu0jmfK#-rukU9b2Uy9Sn>H3oAPU5znFA={loZY^}fI`UgDWgY0=?J5xr zpS3XCWBrj}EL=HVT>6&1QWGa1F!VS_cbbL7iiRPmCmVH66!KAWbsp8_{7Q|D^uTNl zV?0p4;-{?jH&p50@N%ovl2M5ZqoofD`Oq&<_RW^1uzEpzHElS|4%^|5hpKVWIb^u` z?4c7$Ugw^>6xqh;^8-jE+WIWo+Nk1M=y<<6pOE81Ss$s@K8c^QHuduNCXm1qdnRa! zKT?^ZG4!u1CNrA_Je(0RlV8D*K!SU~{w^Er2k#I={&Y7a;l)q*xbWAsal`J0j9<+IKL1 zdo!dIh76bIZ6YV?TzN~bHlZ;4J|l-X_f}fW4Ra4{C>nN zSS)ZTRir&08W93dprP@(mqZis>J-ZHdl!yK=YUV_VvA-vCX~O0CoWUK*8KNhF%VjV z&}3kX#bR-$yUK_viupRPYil!M6fvwW^h~{705^6XI>ADnsMR(V;Y&m3Y^%`$r3S8V z4w2*mY6kNCb?N%77Dwary=0+MOuoA#ijb#f=9)NE&i(IeZs(f2B&Cg$W14GJwS zKKE!<p*z?R}tKOBtA)(4t9Maol>KSuf;8XKmw!>Ik}?H3u!olmaa<3G#whY3qF}^`c4eUK; z^HDy^Qv2F~c@{JVDyhS?f)o_Atgeqc9~hf+X-n4s?oEF?vln@KNCqY~5r>s5o4t12 z96v9x1VbCx>ZEwct;rgnG#b4QVwO&GhIVsCz`v)R$CsKcLLia>;lNzC2-~hmZlj2b zYnOvYq?E5l`T}tP;ov&je)#}{Tn?fQ8-fZV-_*l`WFa10|IuRDYi~O(t z&@*DE>bKJCRDY%cmfzvI%6asaMH57>=xcjy_}O+cw}uFU{|s(Vcp5K+Z^tFm@R5$cx2|HTUF;QQBBrB5ySv>&1qOyo)gz*+23dNAW7BTy3NUP;KqH20NkC% zYD}Bm?)Pcip18yIrzygs|FK!A%VuQZ0Izzqe}?36JNwVBn+Z=X&;7~r27Kw?s!=8? zni8@}zx^pMwbFHF=JZ*vji-8;Lo-9%jMK-MfKRsFa<{Qus0lAtt1T*-nylVxYVyv& zf|y{2hjG zV_i;Day3l_D_rj^S0VE(l#Q1wp9RX6-aEc#aqZXahJFEEM!S-R#E3f6Y`Ye?%WiLs@%)F^26#3RF4>5wM$M_gQUDOYwu_ zmcPfW?F^#bv!W*D;vD1AEFCGWB>oJ-bR2h};u8OE4+Nkml7ta0m+pJh7VBCPE4 z?JG!Z2`Xz+U(9NWfjKte-!a4F{=px?ol5JGh2C|g)0_c4>Chq*kDi83uX!V#3dN^e zH(}jX_=+QFY^DrlP-Zq|FtMJ`V+5f#db<9gI=;~#lnFj9`m*{*VfOsgCdz!o_1}>p zkc%e9h^#7Em&IgfJCanEm6aLJhpR$~w%Ft^qE@J|06TlNpJvmAQR&5MdGl?0Tr`+c z!Rv-1gRRC@cub7ESCC`sXLo_{H?U~buwX|sl7PctdSEx99(ReU25p^KMJp>^T{~7 zhxQV2xzc?YwP|Nm*{Snl`eV`VhRi^1+r0Mul8C>gL3&L}1lxzwa zhn2Mv3b111U`u~>xVD#wb7Ya2T%WqqBV?$cV){W`ukh;rq!qUy<%|d>%QJjb4nwZg z%z`U9cMy`tO-|b9b(?rE9&qE9M=hpYd0w~zDJ>-ULbfatc$<7mHHJ5s`}AdA!_ALY zW@SvmQlOiTg^LiTN$cL*;z6BP@0X|Zv z^Lh@4$4S;aq!i)AL&e#&&6aeT?V#~(l(;K=1Xw~h*A)o)b(F`)@?{1=%gWC#<(FU;^hC z3nkr~fS56NZ#>XLy=FB5r#hSr2xz-OX>i^8DvhSdFP%K$FZG?J_>lAWOKpa>k zQkbK$GPZE4wRG|C;;P1Vu$=L46d8)uH^F+zpIa$G5WhZ!F6fSbwn(S)$U^0+TT6tn#5ge)DT=HrokXWkNBFqO5VSP5!d^SO#d=f$s z>UX>xoeIHPq@(r6{M4|wGb&2;vD&3PDT<)Hr`H`gsxDtL*s5b{H{oUaC^^fg3*v() zM$rt7%yFDgzSKW+V_Bp{)-2T2Ihln34Y4z_02I31zy;sJ=aJ1XS$`-WGy==EL@|Qs zqhV-NpaJ|g=yY_W<l8MM zA1K0b+j9ofVc*VYZ3EFd4_ZcEz88JIvKsM#1a};x+?r@yY29~?FBY7@8q?=tbZjKm z=;}bDbG>uBKf`mD>-3o~^n(G`Tmx|jq)^{98U5YB&?dXvGo<~Z(TJ!!dQ@lX~ z#dhYdP@iwvg1|*|G2A8+Yl0&K@{G98uqO9cY5BE|FB12pKs@>KXr z9X{&Br6&I)7)E)LZSRSWRA>wT!H5`7Ig^5%1^mvm_fUaf}X#vgf)PvJ6w$6aLLfVOZDIx~<{gQ#qAP1IR-La{UHzfPGh(?zhON zCm3rygI~cJkbo&r-FL(|jU*qzceg^VyzV&O8<|O~=*aoFh$9Q1pI0R|*+` zeS$Au*qxm?9c-;N2&?z_JB%7JyW?v}J6kJ5ZA*6q5D+#LA5ph?9WFCN`W8O3(!L}5 zICNN9dcqwSS8pA}3n@Oj5$Ph_QF3%cXLn8^H@a5ibYj$=cJRW`@BWu?E8EdzbidzZ z1``?jPTty1v6F3AL?#P?4%NiL-XQr9FPXncvognl5f2Z>Y#iBaZ-RZXuGl>JM6o>E zK*sHm!0kogny?u=V-aMCMa1%wACo;cnqxtxJ5wzGx$Rq~lr=p6413y6G6c9r`(CW= zU0WwLrGfB~7*8!UD~Bnz+yeZK=KuUzlOc;_kAEB3)J{iGI&n# zA^lz4P9Rh6qw#m2eYNIzsk4~0IFE-ohF8rs`mi5sX7->o!C(va>j~e%1pE12dMW;P z=UHag$WU&!fx5ExoC>WNUmg73A_Tgqj8%u@af2v)d~?xe7v@#3OVXDoJKmZy{3bv8 ziZmgCAeJ_`ou*xOJOND`TsC|xz+rZXiU?YU}k+qNFBXaw7ihyqV;c=oy3VOW9Xs*#cb<`^in!IMz{2CA(4E zWR{*lE}7rHNfHK$zCeuzhmEZ*t-E%q+_)PCaa@?7H=YW4@t5oQS@#0q2)`cS@Dk~h ze0OI+`@oRO#UA#vw~ve2ts0Cy7^wDtIp!%Ekd&_518v+NXul={XhgcYIg(w8N_Zj0 z;QN^tiz{~irRV(@xB$Og+Aw}1?ABswMsf{A8808aN&^@%akQCgV4BDpA)N-@|5ZVi z6}hMEMB9Vw(>Nex=EPi)(gVy@|)BLnk{8Z=F2Ic{^OgA7+aoLchZ!&?u5NR z7?Nv!q$;5jDdpP2_v>N1DseswXJ)fi2y1YC7ttPqrA! zOQV?3eCr*S)+qBvGch^?1@|9!h1aQPVjnXg;1T!T#R5;ddrNH6Pib`O-dQV7MIni5!4&L@A0pBX3cibZD7t^Das{~=FLgB*DsM_P7X}AdQHhR?r}Dk16&YKq zBtPL_hv$l3?hsQejpfP2giFtLcn}hkc)c*RJQsMBW%`IvN|M~Lf|x?DLnWv*qN@ly zudzS)INV}l=wP$TNnc-1#c<`Lz^R}k^uLnAcdbtx{K}P)nWZRak4J zfIy6`6Zt_IqtI)msWC+kc}FJ|-(m0aHsCrWpbI<`?w$NNJp6uW*mDjO354!VhD9>zq-gc+W#C-|CalEY23 zdQv?-l#2JgJl~MU#kHmF{_ik(z(HK?t91fk=yF!8vmVDcEO&7p6A$9Bp?i;^Bby&Z z1~w=!J626!G-)lc*RUd8L|h{8?cEj%!LPMUQK{eoNR+>T)zJx~ds|9S7r>i+$#l$AuyDzy1^%5)vX!A^sg&_(d>9A-$}p-}8n185OP`W;3oO z(LFlf%9vBs%5mNk&V{5z?L3qbu}s@&_utZ19HsN}e(iVw9)DdTKtevRcYGDaDigf< z;jtoYrOt*Tlqk2

+L-An?yvzdc>TOyrA)^sI*`etmZt4;y=v2t~pJiDP^IfZL<~ zavQzwtcaylsCGhA((&CxELL!|%An+;#QC7GpbrW0U}*oT>6)1KZ328?L3obVE?Ex3 z`;tfff7qt1#@D;JQjlsMYvE)2%F}dT5y}4bw8{gNeU8D9J;S~7m%(@KjHaZuX`Zjn z5&BM%R>6}D8}{!X|D^}sT|xrW`1s4km~2{5W8!kjg^2hYC-xQ37c1!J-9@<&KDNLN z=W;o@%DvY^M@vJ22u%wAAT;drDTeszkFwb@hs4_)CLV;D_y2PcP--^rfM(G1tF1x-=*+dwzU zE|AU`&oOhfKW>r&KJ|1JE9zmn-twKGH_g>CoB>NfmS*Px(?mOl?g}D|i@>43vI@<` z_z4f1HT?Qzxybo_8q4INer-;W1-tSecA_+7&0HWjc zG1t-w!6GoaH!oQka7@^^7^Csp^N(kI9$1zhj&=LZJz25Dc@PQ&2kG28-y*Lj%Tj;p zM_x`%$pe@J^Wk4w<8G$%322h_@h>Q)`e^Q0_pZWZ_&SGu9gz9C5X{lB$>AWVC&P+* zm1p^$?vtiVwV)k$`Q4A}?SZLW#hTa^@?goAzol8-h$P)3{pvh64=6{B%ca$954gkAcsbFZxlC;TWdBRR(L@` zQf2xIhnr_bN&i%9d^i#GxGL(gNPMqQzB|JTR6s~khykDw!6RN?_LFdbb-b38oVn2D zW&7BQtkVoxBDh`!zD_YS*o_85z?RY7{N_9l?UNEyiOZZ)ecglU&zFVPF25F8eIDEi z2BaVus-rjd4l%T_1fPg8le><)b7ayzDy3ehFt!|h0}Zu*q||*f@58d@wOK%;G}Y1s8z^RUzWD}d`b?I%5uYAT zB~c9@T&{oYJwG^t-DU`KiZ3F}bnnrB_xg%@aAz67d_Vh*QExHBl$+gc#cIrz!e_lP z!_Mi?kbaXtp%+j#5cDxnF=ej>VAxER)Y-HM9BT{TB1tO$_8$YeW{!ej%br5p@;^kB zt46#}Uj;FfC8SsBdP#)WjL!R0qvo(1KLCZ9-5!*GX@Uoa8KU@UYzjM7Iy?qCaP*^C zXkXLjKqe$QE_K~1D53WU|D!yW9OuK5tbx6Q%c=}eEt3ToCiCWS(dVSl{kIw*BxyP`SB1eaq5onQt@Lcbvddsaw%ZNj@9 z6n9#~A$wthU6BcPfD$BROAFIEu(Su}Uqgpo}knw84FpR;VBZ;xB}GmX&9U@N=WPO@hc)W>Z>A zJvw(qx?J14P6^g)vkXl{uAk31aI!wWqqaR{4cO_d7OcKvT3tFLI?jv7n<-m@XXygE zA1Sj!e;~N~sX%}OK2TmgF$P=>JJU*m;FdT1&g^W+J?tjP|9tv_u)o}d4g?_li~XZK zIP8X^eB~cCHk>|SV(r7fyV`R4K#KrW#=IEu*fLCygcPdbveyd8&g&uEJFb`2fi*t1OSzCRsTe<)5&id19VxDfSk$vqE4M(E3^ zVphmCU_+nvV6cHF3$XK(OPc3-N4P?7xJ#eVFCN{s z2}6BG)e#H+>hmQcfJ8aU>V-W@)8a$j+B=6h~4I$5+dz54HeOqnA8KVNa#8MXuFim}- zB*fWjG;{8<25Ygc5d{E12jqLB&M#vvpIU9MRyj);S6xrdIWVdLjvLY6|7-p2)-Btl zvRwUb_m;RyA_WXxhT8hmsbT+ft&dQ<0q{B?czG~D{q*Z&Q3*OgECAlC+ZV+^4WtYG z#KWCt36qCd6^-It9)eB-exrqj48Rl$Ef6LtAzn4OTZLzhs^JG=Pd!2L#NC}ic=W%9 z5FY(GUIEFB=(Fj^W@zX;Fd6(iR!hIS<`)8;Y-#6+Uk`KLH;c~Y3^|>Q>h6ebzW>t# z1iu}Gud;|*Oz=j>l*&-7(oW+^QA(`l8(9qMN0ZZAGRc}4q zGMrzSWQ-%gV>RTpio^u?uJlw0ecEp|p&5d#>>8n&@vY@w-}LEck!HV~C93$OE1@M0 zkkg}Zh{#<3#IukL!s-7Wy#=ikKhOY3O&97v`oJM+um}n`m;62T9pBncrf}Oyr3K@E zS5Q~2(i4ByYm*H_aW6jJQ02kV^27v29R&z?S7hClPc|j8kvsAg*5Jdz*>9|Wvd?_H zCK6t{fLuw_m9C;%7km`M$AJX;mYs2wzbmd1AjI)QIyZ9&5(5?E$oPD9@71Zn*v%Sj z4alYjddk0l>F;l}g8z85cC9@Z>K6%QsE$HgYtP3O)@S*;oLx;%28G;%J(>7KOrFk8 zbkIHR&6X0Tm!qB5;@3;7toy@$PT?7s1wE8;%r;OA|D>V7$@IbT(L=$g2zhCiCK};` zM|7za#dLaS`=@-8x9^LtS5KeE`2)1sD1y;U5&HcNOXcMpu3%&2oW8&SP)J0TOzP&H zPc?vCV}mi^XDhktM)AYtco`@slwNuqso3yOnvhR`@qq8!6=ulcbMah`-dr9B$E8wb zzjh|CZJHfaQNYrccGXVxkG{8t8`Ud7}r`$6O zK4TM(_&4_z4U(FR#>_W78Z?)>`#!nq-dsya@^yvPgtGsheG@`+1D%~;@?%9RGz=wD z@Hqdo4e$WF+(|c@KSsA%Y#fi^V1Dz!KGPFphh1u!&9aK<@Dtk+=-yLX?_l5Y#{u{S zzM6krsT?2QIjom_`lk}KkVny2p+{@(KE!`Of3(=oKv3Uq?+;0V0Hv(;wj1xwXj)O! zN8b~_@8^E>&tWb>HKnW>Xx^ODQs~ zHC{NNHxwvjOHI9Alt2EIdiIA$c_YM}x)dq?wXP)N24v4r`ZntJqx^;W1fhayf4A&L z$+FYEqusjX-w(TV6WH%LRCtj`$B60vc#i9HOBM@gbInqDlYEqP1?dXnlc__jA7c~& z(T%(;lasxTE8?Ttj-PXr3l$FS1r6dIPUig^8KP!e$@wrddr=i09aJ`*K7fhw?(YB5 z^o`+lbzRqKY&5oQG`4Lvw(Z8Y+1PC3#Jm_R%;&utvON( zHli?MclbGMg5nk+Z$;y%jYp!pp^3@i@s`B>8U>SC?4g94f1lEY@P#4M(jBc^*)y1~ zd@a^f6#>8d0o@>C0xb$I;*W15AxaEcn4?-4fR==^jrk=~+Rz@-W~msKA6ELWE#et0 z>qS_j6!Hmp7=jBZKz8~^#sRALzOc0E`qGz9aH!X*O-(m2C(h^Ht)6;hKM*4$_)mO{ z!HHG(8B0Jd{X)#^rIG!&C_(_o|Niv1?9Z=a7G=5a8(bc4sAfP>as#lvepFt{0=%vK zC0+5#Y4Gt-=iKpy|4x?X>6v39vOP_xzk4P~NCH_RRuxg&_HrgKchCTn1s+dx;fXTo z{>QgKI}ZV@6&W>mf!8l|x^Sm%-FM4O%{*(K^mkV7-xqa~Hio-Pbf19=jc%Z{o}XZQpKDKt=z0Fw#;&;tcHb%IKN z-<8nfvh;H&)hZNnVF^6RGBNeS_W<<(@&FO|7Z>i3(wxzq9w_J2+o=T$1AvgX--je( zxiH?B&O89H-;N#Cdip+K@7KQ+9bAXEnFhc={p`&!;_Rzud>0@B`8~rPSH+cWe)O(W@ z%ocMMg^>T=?lyG>2sBoJo-qHBIjO<@y*A^BcFNLpyZ?~u>9zjpaUJOu*IfM#WMF`V z&>LAei9!$fv3c7eAQH8uN64RgTv2jdmb~uIx@@nOJTF5VffOiLci9ypYR1YHIw0w? zupK|trrTS>6a)|ezK^hM38efdh^rqQlJZnYBC5gc?a8;(3z4h8_!Wf_B9jbmXn2BxTbbuk&u=T{Ep+V=NN+bd0vB2%HK{%x$C0n$&I|gz182)UfF-?Y zZ!jp(T?z;g&aXplUtj|E&RDZxC7adkWI3Q>N}7%qsLt*mqely1&Ahd&1$pNhIG7ZH zAdn)v&jkP7P8QyG=i2gd1SvqOV%7Vg3uuFUFcB1;HWCN?7l1=AEUn3kai-S;g?o^Q z_EpAzMDKNRZkluIABX{50L?p*PC$CrX> z(0l!Tx0QUnRgU`yl^ByTDOSjTaQeaz*)SP#eE*lv;+;df6W5P5&&k$>HCsrlh3?^j{%(4p6}%~{tu8P?5u%S^8uWH4P@=ggFHfYk9f@we&UY}!$fk?*VR&h%Gli84wS>r{}pI#s7>##oJnTq+JrBjlT zqTda<*$YD~B(NZ_moR)vRSKNVG4Z*}7O@J-a1x7(e?lk1!n|JkZSOtbeh~X+JhX z?nZUgX6uN5ZHf*9J~ppmqc^#?Rd-ctqPBm7AS2&&KA)Pmh@{1*5Zp%bYbhzUDQLw#jdP!kaTlLqXNeeiUAzW{WfmA~SFr;)F@9Fo|S<9m3D~%JcLI7J#zvG=%>QkFD(6Te7)Ab^>q#0ON%*;H7m&Au;Q1 z6KH5hTJ?j2Y8ok^C$80GFflwW61%??(KI{P29v30fHS|k-6_1NNZi+^%B2six+hJb z$De`8^(&cZ?hSPp;hJFalpJssa8AVDs+Iw|9inbI4)lL=f!hNvZ2ora%l0IB@3&=2 z7b@81b#4qsH^AkcS@J8LCXo3kT1^4KE7qb)+aZ`N5mC1+jz)&>94eX7Oy>kxk5uCy zUtZjmvlFZW^eAt7(cM`YZL$AtykYhC%w&#ONs*TAfTD3RKvcGJfK7lU2%_mgcExl5{C}#CdBl@8?Kk6#d@XtTbbOsSFbW z36k$G;UyNgWl+0@Zbm`E1Ce_ za=)2cvOH(d-=4KV+zKJK*$N`N>`sH@p2yaL^86>DZ0BfN4tL+d(Y>BJd_Zy^=t=F* z$FM%o0Io7THy>oSPzU`9^T}V+fXd`cw|8+J1GL3P9KmGLyM}N7J#4@iow5dtZ2)d) zXk9gsR)IzgHpR7C1C+LK9F5qcFIo8QZ67?TgloYQ7R1vg#x|owcFi`>6z|I|V^$Vf z_K}gIK*0*26L5gqXmN!~_{&=zp;oFjJQH~ENvGH!Qzc~+c9Tn^l}kdUBZlpDYXZt{ zlgbVMf(vuFR1trKoa|peh5o&ZI%rUEs7fj5I&W{kQmSyy2}B)!4u;&<@Q6|(!9}#C z^pXc z%%w*)Tuc;T5C^m%Y}Y7gdjk1Sq#M{`PLd?AQT3YE)P;ck_8N&R!-g4`ofiPfm=+^e zs__>(<4L71sm06Jko#LmEJ<1OwmzEdio=nj9JaK-EJxv@+-6A^h2 zFX-Lqpa7t719n>A!Ay&;jqD@7Jt{mj!^1T~Afp!^s-W&W;=A`s|DbLt^O?%}cb1UB z05p=1t=xgIO-3QNPMmVrP^-}wvg*2Y>FUgb9yy%9jsO+tKLE(|Yh=BbxNQ?K9b9pN$1m+xIoZ8CbZhfhVruWdsMUf4_Cf&MTC#(e7M( zfz!8r4Uxi^AaLBAX*Nk93joMX|5)PI3rj#V3|KKxQzZ5NS;Uz8txZl%ZC6m}6Fy`e zc>*t_XpAEfO9v4P&0q1_40!SO=8K5G+|v%(bv=>NGD5grvIE?AW>xh_K!A+_*as~D zS^zvTB~+qZAAMJv(|Pq6P}}vpA_eM4Re&kkALpgM{osj}uy*-2U+FkvR7)kBnJNV! z{lFLmU~0tLcdbWJ2?OX$9ZP~gNJO__IYrNLb#h7skb-eA#u)T;R&Rg?0nCMn*cwop z$E|g00HELVdO%i?uSl4$ITU|l>w+nd_19`uiQk&bKFq+3xkxi#@N28ylnkwTt;Hrz zYkv`Y_*~}@sR0`eK&lLnW8}N6_G9_S{J43uEJ7zRavA&JwLF*l8$?*Hboki{V~008 zO|Cbs`I|)~EVUMxQL&nbvUqz)?VkLcInI-T_2z^CMlS$E*A=PH*}W&vu7Y)i8X#CL zMV}PuS$Q~%Dh*L)V(c(2AK`8W_`={n8=X%58e54~NWB{MRdZ3IKjCEQWW=+MBg1=b zbNKriCoZ(z?TeZ|7Gb?JWcCe!A(RfvIS-rmM4{^fYscjj#j*PqJX=f){VDq=ou0P%1t7zE)&3LeW3}5D zj>s6`UB5MO>k8)0Y8DJ5)>cjN66un(awMeGxS*u#mXsVolqj8aM+L_-Ktv0_D1qee z0lcl5(|#+V_OeJOvH*dPn(OyR`IiU!Qb6+@E;@bx3NgEg+Y zp#AaF%WTruNnZXThCBe71l-is7)7ihysg2tNv-zJ$<#veeWRYX{k)!)_8*3(#y{${ z7vJ3*zNgU;(FE3Ak`a>;pDs83^z`-PrKAJJfsO~c_3fZ=cACuMnmU`hdG{7@CpTlJ zzX!doS2%E6{bYI^V3vgm_1Fq{$p)w6$*+jdCNIt3=kaOxEDUPncrdpeAIZ~SQ1+H> z(B5CkDImcwRZ-MF-5SJw1&B;hVFVSs&ASiYx=^&C`N(l&MYRkXkEd;(IW}x!`*XX} z=^g`GS5K!`i)qA5^*-hi0zba!YB0%Jn*Napn&@EyCsj6`hr*#ezb2}63H1Hwtwyxf z()@4PNEqf%#&EC~QU$K*faz)gNQ8{3X<}mHT@N`lAk)A0TzB6dtvCEgyPBkAX+H0m z+8TJwGplJ(AQ1Q}4xbuJ6xrK6YnXhP%u;;;cd+O;^7Mt&%gdVX2g+Qq>6p&j0mp#% z!_TxRM!VhC)9;ODoLI~xfXxk$yC6PQYn64KW(NaUxunIl_eabdz^tI6A`u=xBd?t|V$=RB zG!~wxNme^=wt?bqQy2Zt^P#haO#`c$Y&0CB%^}Zb?L`{~p9HjpWo@lPeptRplBz1% z<7UU^zQ1)R*yd}B%UC8GEaW|1P+VXywg~0T>$5^lgC{-x3}R&c&4Zk0n-o*obuZi( zNO(zRQ|aa@ULJ_R%?Y2tKlqtX8%lG}wT~8%>-W5WIr@;Mf^v15bLaWPpj1kNf$(Md zH(#(mMa6mk)Cn0Sle!|F>VS$bSHrYSxAM(4+&WGf<2nb9uEyVBISAaD%~jA&eBlD|8&34rCp5>1~*6#EX^G?yvM;@ zl!IZZAq-YgN)*qyAd7uj@%0QC*VI@HZ>@{X+OIr*{E%)(!8IC%UYX<%olOdJE*%Rs z%)sguqb6USZw|2Ne{0oW@>Yc0zZOpKptFI^WWm63m;Gg`d6ejU59zK-+ZXT zuk9@PV{43Co4KQ{R-u+6gRBJ>(6+Vm%4Qi;9MyZVNQB$lA&gAF@&ap%+b)nAYL+&S zN_uum)aWcUrLF107cY9P-FF*#9GA0>U?``$v}FsuNX@fwjOsB;{^%K~%tt%)F$|DI zMpl$LRgJcklr5UrT6wDQ-oR?!GeiE<7LDI zEDz`~pV0Yof6Uqrq zhB*8%$9@!-g^oD8474BghjAh)Glj;{1RbwaamN}#6;$KadI4Cfp|b>msq$2e>z2zU z6u5*w$pZtJO|GX+b0w1%jo(8L5Qi%zwq*4IZ;y%z0B#y@$X+ss;51^s>HivJuPz{j8Xd%90 z9UGj?AyQtvqQVNZQ~C{+MWz`4TdN6aP4ve1P=qFq@AvQ6tQ3QH$3pU41ArJM9%NGsi5Q&uL$?Yu5O zJ*>}%?xq-wX1kT}v^ax5mc^iIwlKnYii<7HCaj1E(m15%f=5TeWzt%;8ixC17$KP8 zE#tIRP!Ih+n*!Q-@pZ$1$Uy&-6Y$MXU)s6Su(B$7Ja)GpjMvdw?6=kTgsgOa$O6X+i57t75!l0Qnn;zZ7?J zj=?`Wdc_lKaaey=)MbDmitD6VEj!F1s~#~#-+Fp+7FJWOxE*u%U|jtv*2rqzh3<8y zV6e_jsiqdtp&x;atS}1iI$=Bg7ZDfN&=&vK8i;;XQqY|QQjkil2-hvRbm(2F$);^+ z$p6*=aYR)gqpy-UaGlgoT@*Dphg}p&AcawG#0MO&MhJksJi{FyGJ+de=y6r9o<5x( zGS=FR{g8PxoT0@k>Dk2W8ZC^{H*}n{0+|h!U-_$q4gu_Ad`!c3&PfMmiTS4^d~9A5 z729ST#4L7+!QUccW8s3WSt4v=169jcE9=1b+0;nOOP^N@(zq%-pwsYOx#cGU7~rWj zIbwcS>#{?M+(NQ6+F-R@oY{tK{H3d>&ZO}Egr}lCi_rx(yWvc!WHB1Mt<%;$4jRS@ z&)(<^T8jVJP|0*^_5k62aXexCcb7kB z8tPb|x*T z^Yn!ceF+y;&62Mj+ARtF^5+jCyKSBG$1@Bp+~dV}S5EMd5Ek*0KlAc(as@*L$w4s# zQR~1=4kk^1qcv;?Ng$(Q2Fo%epqM3KP2rPjoyg0d{No71MORPN3$J^60hmC8MGDS6 zC~UV%v1RA6qKK<}gYDo-y$$>Ce?363<(3IgkhKTg*?|2D#_gfkPp~Kb_l0{RCXOxt!~`9+s#$HkM@7)d|N9jA~_OEkhhM$vGB*DG@ZO#NgGB*Q0A| zyD$m;faPitW886G2{%yq4WEOj;GDh3+Z=<*3{UUM8_p_%N83?v2sBOnG>i`ab%vT% zQ}c>G;^wVDL<+gc={1|umSuU}?CeST<>QqULkh;JEuijDR!=QyLR zU}Td!wbgRy)bh0R@J{&wGCUS)uMmKQ*&}e!y*D$Pk_Yvatw(``*Y~R>uC~sV6csXB zR1Hyf*YMd1Gfp5!g094AJLKG_V)Ee$vpVUoitLR#)7A3xtnL0^{m-|z%9ox0Z=xO747rEC{8HY!kbXEllO3r;O&JuAm-3u{xI~PC- z8I~juo0Md%sFt!;kDgA!*3cb^;Pkx>CgXcPDII=452;f(OHQ&K)uC+as(@8lJK^#V zckiCw|E(Q^o=XmFE|$R(ImA?YXBC|_5#~2X((e6aA-&puJN%P&M2?~4d56m(g_*CX zM7Bpu-)P&1j6SEop6Brq^j58e7pZ1d(Q)q(6TIGhyU2Ov1nof>(iMcURM++&+p-7EIT|@=HXKS^LXGd^RiIi~ZBeFdqyF=Sn zRrO^QDX;d|rqmrdRzsb6D7qy5nfeY&NFREu5HMogZKuoe?~=;oSpCW63^G>|()_SO z->kE0r2b8fbZFmL&I`ZxPUEGt-407DWN8Wfl)Vt1D!+_M?(>5hpw|Fdx&>&Mk3Anf z48i_wgkk%*TZzZv)Do!ks729eZu5=v_lrBz#*=sg_2!4y9hZNAP=-VK+(R!XEIp?1 zmBE-_QvoRF`MQw;@FK)1iLNMNeP`;ti*>0878T+@yFi-OpYP$CT)IW3q)@tjI7VuV z;NM?Mk2m%8^s}>Znl`>mdwM2fvvOl|*1Xn!t4$yE``9I=9Wxn@&xz?uO(|AX3n=Ig zN2%>ReyAtJW+DnHfmx_}58Zu1zu}#IE~K7?mFLNFq8rx-^?Npt8+D$ZcfzF8?CwJn z7(bb>EU&6MC>408R#W3K=l=#D)U@fF8Aj-v?!Y(tfT z?NlKZET*0ZF{{~l_x_97>toK&bvjTevtsrUc-PYJzA;--S#;oHed|#Bm6w8^>wa9o7Rr2jGROa(Q(HOnOKi=&L zY1Nybo~JT@v{_)R_p=qRju*xq08-2e*>vQd!_%N_6ya`M!X7?_oRdckO)@Gel2Qj=&|@;%w>baKB-T87nARX-}`Kx zSxWApZ7K#a<*Y5@!iFb|d-nc67vS-(n>;U5w2)?sFRgE_MGx@WOi7YI;i)3TzebLu z`w?P;r_;U``jVDrxQ9&rRz_8y75Rt?h;;e8UUiu_EPta5#T@$7cs%JRg ziN~ql)NB2#&;MFeP0cgrBuWX7s~%8*vGceFQ(GWQ;qmN(O{WJjMEGZHfK7~i6Se#D zZWhgwJR=r$`WJ{;l#c{SevMg7l3Kav+VkW zwMG0}xuJmJMvx&DfF|90(`=gcgCWQ+Uit?u^-5|fgOZuvg+vmqi+-)YB=)(=`U%I<7!Mm) z?Tr7HDd~9br@Xyi`T-QqYC!XlL(1VkB>h^URtc!rPk}?2LL?M^yYuxzL`|)#?SdN* z5vscDgBywO4p{);*37tOYt@@2WM+<8mS#6*>TkLO8*x7bbD_}E>*!;K`~ypK?Q|#3 zfJB%HC7+5GDa`D0zV3fd5}wV{d7$t6Y;vj_%MX|6wo3-Hhcg`@qarr~wGR#bUP)%0 zug5U$3x#P2OWTnGL$E*xh(d?h2&wCuwMMhyi=;1edrTMo4+s&gx4mY#a_D5Op3yMq z?V3>tO!%EXBtUj6?J!0kljUiK944~hS1OM{3hvXTLKQS*>@-SEEYC^YI~aqwP~~dW z1Q+Z-CE$Jw^oR_dPno!j7#%<+w_a7d6A?q&2=F2b*`xEXJ|PW&gbuVTm!8K19!wq& z>hl&1yXFz$OBmq-!_I;GhhzX{HzS3fkeng8mA<;F7Ty9dq|q@78&}4_fC9vLOs3M| zY5Is)r2^=H4Cc4RiZ3sc^P9s%1oqekWpTWH_eR?~b)@j;nUNJNt=39iEd5L@7|90^ z2GQp{wa;Rq7)e`gbIMv}-fHPExB57XYMCd_E|z^RMu;jws2AVbw86T;+@cA+vT z^tJDW|7}WOMG-K2I;FQ=(3l-7FKX=eJm6(QQpN^A$ZQ2oxzm1tTygQDneWeF*^wqj zYAu)3KTv0K@HFp0h7=oLkQ|p6PV4%Y7g+r)lZKA7vwEbTx=MG+D`7GUo%@!2j7m1%t`(4%X3_YiX0C=M;9?3hkNV#6m+3eT?UIAOXba4ur1R1;28JBAk zusn|LmMPne8gsdYWt$-_{$^-&YF6}KmwNAU#xPnh)9KrDkD#1~7Tt}nG1j@U&gAV8 z2qc`2UHa+wTUSE>Q^ko@d-L1XO^n;LE}OlxdiPwNYW*%YU~6K4ehD({+gV=?Ur!~K zH!qD`XF!y>mgw>Y>WtqL;+(&B9^LKR>86rmO3K(mwNZqJTQ82RJoQh$K&3qG1|jhi zF*3$g0`Z*zU{EaHPY&_|?=A=9Kl{WmbsPHXkObbCNF`$TN;2(0i{^$lKOQ(bA3H9$ zA74EWewwE<8$+h)IKhCNF8tn2kRae9+5w0%XS(s)+KOg3C;IK$DT@IlS&?65#i<_- z3^kA{=KlTZdwUC}@+uUS5_UGcP6765e|G@&&8=x_h=iNo>c#pK9;$#(ki=wHkfjLagIhWM4@s}KLCaFLo99D4 zd48^bzQ@0;E=RH1f>66Hzb%!)S!^@|4g0==1PkK;M$tn-NEkQcb6jh#Llp8Ec>Tvr z`xYU{PAsfK-*rD}Bis4WzOiaF;)V~OW&Rd2k3{coPD`ht(>pVJxsyhNsOoTo!_-^y zH5l}kWpzFq&^Vwtf+SO}X~oz`hhyxd&3Z?VVu-hWS4nmr$0Uk7-Ow1WrX0JR`5`?kIc)pB8DQz0HkK#>udw0~!V3wHDcO3qee(e>o? z^mwtFaC!OWz`AJ_o8OzWQlomq@;L+!(`m!=(DuEnq$G4MTHepM+qO4bV(=1bM!h*UW;s^Wdh*8D-7^?`e4LmVHzz0f$f&t>Yv|&+>6M5? zS>hM;5utIt=rlNr0`Mdh00^tCZ0uM;f}#x6Tfc70ALCZZN$Sw*>};~90~R9WnOjfG zp&i_Yl~tW1Q1fOvic3x(y=9I$c z$8k_zCzXkT1`Et}@-IK!RnS(n_4sAi`|)HH=O_3cHHj)w!koUy0rs4>niSu(Uq=0T zh>~QcL|RNFV8h(P)7Sy3-y!{xF=C^*CJ?VSLgmIj+Ah4=XA> zMV1>jve}&Ae0Ks2a{Vd`SXkJhYmz)I5XT)xTSY~gt^PC<*Lbx{XrCZg?&HayanQJn z7ggA=!eUXwx4YK-jutIBw)E|%&16Dz`{KT7UviTm}h5;XZA6;L=DcGz7B-~jUk9_5@?>s(C zlzFIs5}Dg7u)Mk`rSkKEVaSffVzsH(z;t*i8^;%vX$WdHK(*}aZY2DDtft0fp%@4h zG244deVo}|iqxelSt82bL$u{BEF24Tz?w+<6* zPfb=BNuAy160DqUU2LxG*n{x*v~zzG=|)DDb7<1Uf{QUCu0}VSD1^MaV5REp=0xwLpnfbB*|8{wEc6x z_U^gHgqDlBus~{so8Rt|7G=5&h+RlkQF_V_DT{x)$$CON8Pw#4xHd6CUn(K_)=nxN?3>_=(Do?#6aUW$sA9Nc{H zOFa2}mD3h9nkN07+sL?ZTy+yO=@R-&E%@jm?G{H|Z=h-T97Xq~A1GCNiA|SSBKCC{ zZQCX95Zwb8Vpv3lFk8jN11IK>TcFt*HZw{-DE#(^gqu`Ry}=bbZfNfyGqYto^uTTq z3;HB*0zk`d)&tfVyUHQ<&lS3vP!4lxc12q~`Cr~Ck|@N|Ihlol6C5b}u|j3P(}076 zLLN8t20{?5tegS9RK2I`9I+R6OcyyvieO>l z$f&3YQ4$kVQ``5o!&?;C5Vz-5pgb|&X!j&bk_twq``!>PNhYVO3*Y85h5KON30w(C z@PIQghVNC-i(QMqMGrEUt8FtcL1Vvd(aDcRc5@#Q9{gG+hINU#12hz`292@$Pbo0S zX^|JVAQ32b-{O`R=&;eVSRWAtmunJMJ? z(I)x&ML@@wc~purzw_nGWE_UmO6z>{rB>j_q+foPH}7DA8kv)mA~*WiFC4!!*Ptgt zr&WW^`Wh_L5ur-fV{0I_kf4PHwKJm{**OxzvmKV?MS_ARGVzbNvwVM$l8OhHl}7+& znU1F^T*=Rp#zyzC-|3LwX+lyZjb!?j=8nfdVYn1d%Z|~kIAP^}Q_0z~)X*lR3Ta;l zkAvdHj8Uh?gT^+*CN6LZb2JOgvCNUO8zHq=_65+6iMm##v*QBqVaBzyg2sv}Ji|^* zu2jiYcM<`tHXAHFL%y(huI#u0%?aFl%gJPxjY$8s9@*1(ctYG`ealHWRsk~J)SMU( zQ8o;J{kY$ur7=~=y_HEvUbYQi5g9g}ou{{iIGKORunE&5?LH*+??4A3WFqlj5AEO)XZ{0mfP7LLr@gT%99pK{*x#e100J zqr{FRQGGb!?{pCqUB`6^yL&zSaJ?`=^lgiaTdX!nHmB2D-Keev06*z;R0Y+V<^C^~ zb1>kp*WdZ=v?R4j!l`9R%CX>ZQfmraNh1}pac^$@2!C8H+U6gR+b29dv`i<9KWuBA z*$4ZVt3X_KUG9{ZI+c|#_vQ)JR@0G&i@K%mNq(Q?K-9Bv3dPn^d{goYS_(5u?r{Kh!6$=-t1q6B7jSItMy zC_WL1905@5`X*}}Tvr=*fH+X&Xbjrsqb;zZ{YkU4A%M`ssWLtN)#QB;nccMQgIZ-k zm)pO+Na*A|qyeF7@ak-n|CnzeRW@EtLt!CsY9=R3q%}V#7L_9Y=~yis12vo^IIo^n zPMcGf?q{!|M|ow+6nB(JoWoKGa$qWk(7D|SgmBpsI*(&m40~?c+P6##-8pHJN{?zk z4%-ro*v2H=TU2XTMcj?&CiFS7(;&u?cLU;{-NCOnX$A|I9b@{o^bLQwJa0ynRn?e$ zz2gtepdQyXMpNl=6!`u;)wmol>1Vlpr$?o*@ZhcG!!f?I_LU{ptTSY_q7vlJrocI0 z#@ZJm{is<6a22=25wg(QbHfx_3K(!u9{S7s9}z>lJapz66n0IxVoDAzI%Hp0qAPI+hJet~mZ8gWrpx6zDViR)}EZrL6buM9ZHW=bp99pL9eZmDPmiUIC0&GMzuG%(f*OBQS zU_$eOG(UblkNjYIZJl6Y`7<{mA)$<&9W+vj3V58NLMn&b30ErE{)aHLWi;hv6d6G> z$R22EHpGZzZ-InhkFO-m$qw-3cmo)5##7OfOJ8Ab_X=ny}3IdLRl#PZ4! z$m`#wIcf08XIpjB<|20PNq7lln{fM%MISw;JM`d7Rbb^o`nJ0rxQan~&PAKESNkbK zUATKnq=+N=b{TdWf)<0WT1~_w>EhtO-?l!+EP5d!lT4&Dqm;b zZ3iPx{38a;5kbU}ED-8kg&YB*%4ueN6=-f$!`YHpx%n~#_M4j(_op&jep_+ekQ}_a zY%N)8V6?gB^wKhlbxIf|xg1{ni~Ff37#RTH4FW9w9-Ye!_U_c|>?LUf<5Qxast#?B z_CHA8f0d^bPD%iqW`uH+!t>*H>>s@2+LAvml#Nga zFIySaIENkgkfjDJjw~p%Qp8WAem2s-u#FV;T37F1t^OfQR69OcyGi1*99G1pEBRt6 zneRL+Wec=;@qok<4U;ll93m1FQ}=JPt8N587Dw5{Cnx~>kZ@!^A#9R{PMi?da6&UD zT&pwx5_E~;E2I^_1h6sae224IVy^yQMG>YKNv8{3&l9@jWcaR}s+6_~O!)bndatp} z4WrXNSl?38KfU9gl2K=9$Gjd@(FHkSPucT-t@- z+PN^of;6UIW&0&hEZ^7(XVMLI9mA-&xTGlL;gz(oSATR~MtUm%dn{(b29qo1H(5qd zf5FSbEl+}?W?jFCS6d9Talzi9pAUW^!&kEH>blVQlBZ`eYxM1Jhh3>XPZt10Yh-d#TnX*v@p1~7!TscRr2(N;|79>7Pu%u)UKqTw~hr=gD zrK=Y0z)JDAU4|D+hMQx;#~((00_DKMY%_@l_eGntwj4)K85fZ}mv8zTIL6fF%%|)JTZCK^Cl<{QIx3@h12!8oa4B}(Tthud@U68; zbk%cb3<&*gg6?AjX8!auZk;w-ePuiOZ#QL^tW1i5ix(v%iqZ)jNSRhJYl!NysOrCA zx34YWv9|tzh62SI6EJWVK|+t0qykK;Smh5tep$aN*}e0RE_1LPo%<0p`~*o^uR~gb zQK$**$&`L-Fyt~tXQu&u?Tnjd+g{LyGHmMe`+PL3s6^6nkuWYwaku^)D3~TOgBM6( z4a@OgJ?Jm7LNnc0B5>a7`V{*+#oqhZ7`eWxxS-(7KV`~D;^h&^IKvPY?!4?I_OQSb zR=He0GExT(ld$vr_sb6``BEvve0kSz!~6#ur>jl>=FCT2CDcsO$N~P@bu4l7sQ|tp zD_M#T%w%Sl%b5Xa_UtSNLXo;Ef~sj#!tm4#R$6uWvKcP4IP&V3OMpOs9u0?GX1zq0 zwWCKZ5Ty=;t{e`e@rh17ho5BGFz`6CeJgIWOG>AB@+Q_{hzS5g3j7#NMNIyD!!0g` z@b&ptT#7GdnakJ^GEl{o-~%C&fLMfqu}%)t06IC|VC|xt-_U?B7SJn9DPNi`D*P{t z+rn~Wr`dV-my?&{GXf2b?p|xxO%@g>ylIa`780+>erqw44|o~Wl`n2|cL{w>Ird3r zek06+z3_4~_DP0f#)^Rn`kFWMPV%lpTv^dto3URJa*drXRtIrJ`3XEV?OwQ5W!!~g z@h@4!ygX^*iYLFF2qO%}2cTL6o1fRe zWN0jQ!>=e%OwjMIA$4PC12OQV9W~F*kN#EQutEhJdU$s4<_6dx$7il~XK^k6`o7=0 z8v)Q?(~swP9NRkh^tuMvWl>K~@I*;)00_|C2D`l$nH^@$le(hvy-3-zuHGwk?Ho8g zsUmx80X03YeS1$7W9M*#$tDG z{=@#@@i^ltb36ifV|fsBr^43l%vTyL+pl`z;0gKhbQb~10VXhVJYewCR#W>ci=1eg zVUYpE7nD_GJ)q60GRZk`4*x2|)sO5qL7oloDI-`6@bUKzY0fF&L+LN)8oqz3u?`cd zNvK4n+UQkUTGQ?@}%EnOndRFyB(Vp?xJzNe#F^Cq7zY zSn4!x`{WUxCI~gqWXN4`&q>5q5}~1w<1+~c_oW&Q*;zXW7qmNGOE?Yd)$#PMuW!V6 z4zpdoc3$eqL18uNCs^l7)NdLOhEW=fiQ09`Y-m~qtS|6*36kn3VRvrN2lDbNgc>#E z*TtZzod77(RkDO>2c|cH=m_%rXt!~Nh3*J=F!iIOCU-eR5MUR9*vNER+=>$%1V10BRGPo=tgK@}8XWVxY;qMh^^ zDuy;NfTUPbRus)fO)9s-#?mGtWUBrCUf4RY#%Iqy_I&|WYH--eLoyTKB2KCqPi{jQ zPZqK?3Aml-Sq^G@ladtfC;GsJ9U1on6Dp&oJ{5(1l&Eq%Kkw)y1;oouLf&VK<}KA^ z%nh;US6YWxr2ShnBIz&@2 zIwV-ir>6~u*wCGvT!6DE6q3i()KZ6`XE25V;1#8bZcvtK(Zi2okE4*2>(5PMYC9|3 zKbvP+_F5D6cJYV8kZ!-4=UMr%rVjP)WFANUQ9k|;twcBFsCMt)_P@EgLmcCOwIKk; zjD5oi%paTIgnU1KhB?rPkIG)YWnHxzo-kjHLY4XXqAaYOyJ zYPT}`rS_?DFK;F|ny?H9#9SdXX;5gwfNDhI+RMF#G8maEQkWB++_Y%q5fV|et7#yB zl4q5Shv(228#8f=JG*JrS`7$(BpaJ(0w%H2&fi-(-LTyDTjvBziJ*ncLHojfI}=j zI;O(=ya(C7ana(A_UiP-BF5Eb9{;YP%12QwCK{I`)*47+7I@o6TJt>2R@Km8wO*j3 zp`p=iw819yxkCXw5ugB*h-)3c_j};kITs~Ck>}b+tLl8Q;w3rm^G$j7-o}M z5d~EL&e$yX4NoW&9+UQhI`ieWJ|&CO;6!h1gTGPzvoI@0LQd<;Jj>qyConm~Ws_qv z6b_bQusr;Dh5M&3QByM#Fekh4k@kMhVs`mTiNqa>fRC_tGx^@${NYUTTB^)!!Y03} zp|cnqUj-goOF!KqgO?~RA_LXnGP-qTf%iQ~aTDBCPH~m0UYJgwak1DmaJ4P)Z=2Oh zWZgO6aY%+Gq3J;e#Q-EZ1XCUsjdW3bQGx2@EBa{OJ^#8)r**JDuKn52ZrtI_tdaS6 zI+a~h#A>;W;Y}R{S6shI>DYm~g;mmLSOLqexN{~NybG5^`T;v-#Q7l!s|FhN$}rNf zeBqlvntk$KPyCnZF3CtRCvT^&3f)QE(Z<~pnmm&Y71k;|sG3`GwVw0Tn0B>FoquH8 z-@n-}x&$U$4&9sp%DSo=xf>^Wr;T1;`wQdKLrv1i?HL7}C;Zp#sv5i*9MhITyaJb3lhI?khRL)sBD?MP13i9l73Y5@ryRD5b#uqhdD!kCbs*lY*7o&0xf7Jon&LKbQ5j0m0xqCjGX5(29B26 zDF8j*iT7rPVM+#DM@YoNb$efpq0uBr43eAMQQB$0OL7U`Ad_e}acqTc}O zwb?bB!@Id4RrUWz(^rO7`Fvdq2uLg4h(U^gbRI%dQaYuS?(XjHZlt@rJEc1gAl)Gi z@9_ISFBkC1OYU>e%$~j1UVANywwvJRa_PS>SKRoa?tPYVSrH z$m;zstn*aq(|8=hzKf!c%=xw(M05nuA*Wo8d4O-LSEq>iU*yzNXK;~!<}vY`s~Tsab4s41CQ5Vq~2l_gDNg0(Iv-}@06%q)$2Ob| zdxb^y;K#0^w6jy-2)H+cpV0@!m1XTDE4~@%oHq&`b~Hg`u+?9|BD}zTG0+>dT6W{M zqpkA!AHDtY-Rp=WvdKI|KynV7q<+1gG4=Z3O;T3WUkkwQOdtzO?FgC)z5jKz%AWhg zAdIbWR9~Luk$cd}xSAS*HI5Hx3)8mczcuWzDZhWA;z{$;`$ZbcZ{0M^zVsLO&opDC zsQ77DR_r1YVJ!+f;x4|7EDhWs{Nf587^F2YiQO+Zwo3dIeo#D$Av%jZ8PgUmI%HbA zSSu;zZ{p#!{5@d(VQ}iNk8BEMDn4gtrCFk=XRc0079oPTn((Kp2Kb7KNVH%%^>S5< zn)kxf_pgt#*Cz-v>8OS(Th?@($9ohjBq#z_4}I>r=e0ifN21fhbI2rAEjuSt(>u?S z2;C)C7i1?ROA?&pxT*Utl81y}M9Gu>$|A2xwUtB2;xW4QY%t0-^ESQ9 zL~Eehqw-*TD4X@h{QHKBDD*AUTd(9tTQXWzwv%A{r||U9wvb&x3Yn-_|6HTQbR`dx z*%mBV(1V~ayY*Ndbq!h2!ZI&S9mB~UTOWP8551MaGE2r%kbT1^m*d;!_K5kUe#%Sl zvR#KdLe`(v8@qH0eLoE5#|5h*zu10Gw#Iv6d%z8&!vCsK9;mkUm`J}kb2dQq)YZ<% zNTeHD-;B=tsuX&Er7ycUFRCtm)>!A;mf}te7_wt@?*4sk4&F{Ri3D;|>*15XptW3e zaf_lK7*rSDj2z~VnC8=^Qgs*z&wW&0t_}-Vq~iYPYE)tW#}Ui&;V29d$ET zi~12VD?B1A*8H1bJDxb*=3wB`JT=&hxF6#!@kHcTy;31h?8tzUrb)h68jYruLbK3i zDEliIOP&thAI+mY=jk6z_t=?}m&OW(-=%glpf&ouO)AupGbMNv(2flYcnu5#=P$1} zs*~#v@|m2*2gU%YY5ioq`J59>nZj<3UNXA7;Zmknr!Paq&!Bip?P%^EfQpyxccfs^ z8Ld&z&jT_|`7xSz5%G;remSZZBeAoVk3D0}?ocD-P(JgMnF`AY;i z7G8X@9-fyVu^DEC`kS>+nsP*r<1jxijdx-WqZFAiZq=ykpFwTe^;f|A+BC3 z$Yt1Z#DMDCM>h8N-y&$HS;#0SY?U?<)^8=nnd!fH1~LEp+DX2CKcBB-%5qDS&Fo@~+?VE+2y>y0V+hA4fn``{rQ20g$3PwwVZ6 zXnI*@t1}EihlGn(sc~RTI@|EiN-4RIS1!`KHypjd0W;}*%zXP%1k#x~pUAM5uenm_ z`js7lz6Fu&vsb$MtL&l@Uf5?oR2ly(hvSw{t#`{E0N%i&OegN#W#+hALI<-w6{X9P z6>Q;K21Jn;W-m*n5byVBu6031b(kJSTjbL7SS$W@n)lO5f$_5Y|BG>y#P^?_xQa6O- zWG%L5=rymg9xhBE7~R1D@M%l-;gI0oSvfqDuL?Ng5AaQzTDByB!w>l3x*`Xsb}ARV zL9imE1p2$**=lM=&4M98%?+p}f8_ghzSKc#7oEd1QK zEFknHCAGi)BB~+#`a9famA(&>_SX4Dlt+AcHwVtXi<=oHsBos%*KF0-9 z8J(QmG{(^ek;3Ey%uu9`u}Kk9`}Fe`ws?o$tA`sczxxEUyy?*Q5TcK4FL~K=XH6w7 zKD`o*!>GC$YSj10r2eWcrZW>?r52-;o*Bdwr+d^e#Z#K-yt1N85L)(4FKT%C{ta22 z%V2NP_dQJ6^~9Hf63CLW6~?S4g=mtpC94F;rxH5QQT zo0O$JYeJ<35C6|a(3wF3ZkZXhF&eL}3F2nsV}I_~pIxp-9gl3SLnm)Wa%ib9{0Hzk zjf-l}{zSQ-g^#UhPsl0hD6vck`(+G`slZ8ZE@Y4Wg%oX{?VQCYK8EinEA3Y_CHygE zCp%UbG|cfjMosUi(H(9Ful6@}hm;0_&gNIDKBiQ*q)L zZP7MNMlyn*<63l%QLDIYy1Kw;i0uH?Pqf7fY8usI#J~hNI%Q$6n|hPdUK!tU{6YrC zLbTyMK`xl_(s}%(S^xBqwg5v{%GWkGFZRtv#HGQ_7S?+_-kQ+l8|d>|04Q+CYzNWO z-1N{lo*Xs7gmD%^|0oJg$g`h2IN0*u+mol*V7oYrlwS)4Ry!(_HMu=9sU3K*76BU@7u5TmFvd25qGZ zV#%y{i)vh}tl;Ntzr1fquH+HH)joK3nRB67ENw&M2V*?jczs!h0tAcS@}}GJGNdYk zAPwjW(TPmP?2p$@2pCdpr}+2?V6;TDtU|=K#CBTkrrLyO{^*5n5Q6PevJtHxOfbZo z@`pDg95jVm5rzdk(p?S}2>F@P=`V{E8|v@R#J5H@zJ2;dQhmm;gnezTtkN20@TK(_ z9_Mf81H{w#$m{oy_U7<*v%0NH&I3ih9Fa`hWwSbDO{Ww^i>_rG*Sc?YlQbDB*nXuq zij?7>p2)fW5wYoXU*N;!VYE#;i_VavV|E3nGT>CSzVRI_Y#AUf~1+wF%QTBR2lKa#Ar((rLLS=aW_ z;M&jbk^Os$laY^{bZGTGd|-@%@4~k4Co&S(TBztE0eA11eqn`zzbwDCt{;j7%{7_>I#A z9n62wNLnn{o6PWca?Ladoz88Za<|!9dQDKVm`S(-@}fUn%5Uu3tNl9vTl$w(nx?P( zb8=k#;x*G3k3h1?ozN(W%p4n&arS?OPE*xpp`tL7)8G?gbMAU1`;3W6R^#TusN}-w zfAUpK=L^nbknf*kL6wB>;u}Z%V;d9VnKUjdM^LSY0PNYmsX%Jw5$Jwre`K1&G+aWX zmWRV+jdhyl|2{6mI4%L#MD)dt>rGR1i6#BV>wrcyf#vnhO-`9q^a)nq5J~b4TW!6Y zeuIdak}!hT{0e)rF(p9O#8Af!)_St^t)z8%F15s@4N(=xk~Z^?Rh;r0tLxmG*5yui z;f=%GeHX(UXFA=w)2R>dm~*gfP&VIK!Bd_2R}>H?6|&g>WUzDQNtjD=vv(pClKn&2 zWM~i+RAO0~RpUY{Bfo~iWc?=)b!dMmDvG7K+KF}C278j3diCh{TtYudG)2YoeTbu4 zTveeCmf?F{-}k7-m_~Al5oMf9KUsNoW=*hfJ0%X8(s(mVxgSqy!P!liv4_pOOg4}# zd`X-%7}314CPVdZ?)m6k=^D zI&R#L0*{p!@P+HPOAfTj3$iL}`vF!WcfSJ&3jfMQU%;1>6&U zFScn3+5+6cxpv@>__xDi&BH9UI&3A)`G3(@Z1V9IW1V>_t-5GL#^NVjE$UqV)Xh>X z-oR`trR?OFdh0)-Kw4Ifyxq=!S{%i=+CN~C^lmWL|BWL_vGj`Qr*NNEtmcUTDT(;WlS7l=!Jt1~STZ|hr&>5nZX424xO1ld8ZhYyJi@~PvTH*fr32Nw?^Wckvs*P6kI&DV$!YJQh6neI&eUJ+ zQ{OL4-(>%UhSNm?&TZEd4m7-xs`(_XCT&0$;B{!dy zmTpxda0nU0QIZF9>z5)2-BH{kq_ZJOLJvVSM;aHzM8>tcItr6@UWkcXG9nB85#uF8 z)sf^S`o(WObbPVDJ0-=WQRwcBz@XQhW(YEqh?u9auY6UImlxufV+OxW5AHKqrBsz< zWs;8I43aFQHolr+eIba|`~ERjUhKEL#H8vEGcyE9NnQNh>G@337$;wk$zU@==A88z z&sdKjOsz7cvnI3Sq@6HW8X77oZ1twJ#i^1kP2GKA%A~~)ZG4opS_;8Ns#0=z==;ez zKpZ4+&L!q|bWW(mhW_siBH0Psn*5*%Vy|+|)hW84vkpm+;AQkT1x?FlNhd4J!Z`3k z3Q6(f7n+8xQX7}c6c=nQ?shHl8vEuhdUdO4gK7JA26hPB|8yMqAs`Jp<=|##=CV`h zVyF;+39{`9x_!}1jQk4{YS8T76U4z%>C++q!QtMq>D+~r1KdB4 z%VH3|Wx9y7pHj)G$rPFblJC5-s2mQ>h!;wwywOKS!+SM`!$|DD8+spfs;aXh63rlR z^xWv4IrZ+6R<|<3b@J3dbRV;|{iDxY{>qHgXK1}v$&u9e2*55(F;?cMyYGZgrUjvG z*}ZOD&M$3PyF-<4xZl*CkCM~|K8;APEqYq=rk_-JZGcrQGe=3UZ5*5{7`yHpPNWC}bVqD(4 zmwi1r|8$3ynl@>eLA3?L<-X}8@Zpl#7QG9Z;iH_4Dood%XVz=vUC^WnT{go+KYmIP zdl#LPm5CrJ+uC^Eckr=18+nv{W$y(QXGx~u#)oL+#oBqXJe-4naK~6%P6AX^Q+Ybw zOkyV0kLvOFIQuWGw{H{K#`;wBr@!cl-nVlZ4)l(akwdOAyiY_Z#B8|*;%Ge;>nkA8@(3sxJTC~ z#w=K*DC#J77D16goJ3OAl~jN9$7D`ne`2pcW9^U0fBGJX|9acK3iEeDHMqQ_$VmNB zB**{A*KizUp8fsfzd$T*kfhfta-CtgRbOzjWIYeCjMwi=v~uM8^XpR)f?%(B8{yp< zLg(j%vUY1U{fWAmK{~~JWj#mtr(9n->r~+mnIogzu_}6fo!O3PYR1T=aY9gA+b^q= znKxbGRBQIbwMHuLi-@KCKO!VK*c*NXu`#tG9cSuzL#m2OgTr zna5tK%C`lMWX9UQWtGSL{5K=j9e%WJo8)x=)vxTs_irt!lvm}rNQJc5*`t33N8N9b zaSW#t0eLfa*V_-kH`+5=s*sX+R4eI+Iqduqf0(N*wy%l3McG|ZA#)u46)=sA?+I>^ zNK+rHncbs8=00^u0CmFVb{?n(M!~(_8*biyysDrwoV(C(b#tX!nrq~<RC{cym3OHuJ&=_N==a`0Ilb`Am6+E9$9 zi1i|<5Ycg8|I>4|<+If-Q0O^NWXlwJv*d;&K|@1?L~8~9gNz(-52XM zv5T?Ym0ItES5F$R+#m5Sju4bm(KOCEoxTdZ8aH%kL0E45XxW6OSZWh3O7)UZdbTh~ zJd8{9&#tbT20?)YVbex`vLZ1PVHa6zDdr=4CyVW)=m&Wl*VR1SBmwD230R)C7bDxA zwrU;aqar?C1f}&^m>>?gA4>}f(oyq-uI|3yxeZbQbM<%!geh*s>>rvJ5^ayu*4KlJ z5*RXJy4X+7VYt!pVDjQaGUc$!C}(4*_bmH=RG^nTRK(vMkLk{pvwI`fy}h@@w|!)g zj5gqua-|XOKU~c&EC+$@c2lPD|8oJz(OdZVw(B>tb{adyD5semEQlw4Wb#uf3Tx!JySN=<-=B>xSP=ZOM2RQq5tbDJaB0Y0K5LbQ073 z#4mSi!J710X^}HX5;Npau%EGm?#MENYKKwhYs$LLenmxgV@4rGFrIVZSLQGXZ_vcj0<8DMqvb9Q{(YnA- zPVBu2LP2A5{QZEe;Ce_@dZy}Zh( z>;#dom7XYld89XKBG*ZF{nfPmOB(zsj=wRY!4!l?-vnt!qbA1krF-jd^UaT^#~UZ- z6%il}WKo9K9UL>3IN<-M%cWv)wBo5-Y4pwxGkS}?VC}|V%f(kq*+0{mnsdRdsp?kT zSQW6#s3RN#`vaXd@ss6O>xN>l;#{PG9Iw9f>C8hD`xgqbhN3-z{;tvWVoH;rx ziy3mS4X;&0_mYaPX7cy9#`peq{d4j}AUWc6!uP0&zFu*5+uLK7#}OAl06GWyr#kd~ zWIx6PF-+fMPc)ne7{7C&(lfo_BHki3U7Ibjw%Shh1^R^0oaj9;KP(_Co3zq`b#ahr zv=XV_Jl6#_SFO2ygcNP}22GJtlYxN@@QXABc{WBn@R`ZnM+OizXbxhqun;C80O-Yo zlNpUWtu{G^egPy}z-uPxvxZRuV|LhrYHT>~S(af$y#9mp<0cl{7;iEV8}kL=P7>Gg zr{(M+VYQoe6g;-&DPM3h!0E2Hlm&stt3dAk#eTd=8miOfG>*ER%Ey`-LSPEGHZEd) zGv;0io`?X_>gnY*6D~Omja90wKdgPHSYidd14+VpY7;G#<8RWz>swFIo4pW7b3{vkEPMl2$L4aY?b43qCD<9mqz7fRH&lJiOsin>#IKs{HDB7bbX0P}FE$ zZQPyK2Q4lSy7ql`WUzWM>_*6H;+^Trw`g6d+{#7-lCj>TsF{*)#Q)M9-uX-Oo}Lu_ zIDE@iXDhVII&GHs;k(rFLFvWl(Sq>%gSQ3DOJ@wl^QhYr6^#W8dK0Cu1&E7RTB3o{ z90%)Snl?9-MpT$A-#?5mR{ZKMWmZ{a}4?#^m zGhpHM_xG5by(xlwelMv@N7I*hfVt=DL}u3NNU8KgWBkk%&62NC%G!bLb$Q`SpzP6O zGN+}WtcYz42f-eUh|Xs7X9ZI+d~a*U{^H{00gj1L>vd-j3cb(uHbgKXx5m|Wkh-S% z-vWX>&U5w(#wxzOtJu#8FHE{POzt+Ta~liv=>(-^^Z->p&E}?F{XwO;S$$@RX3IYw z1k3C4Majxa8}JQG!In2F0Kk}EHhcYWjN))m!C-4k2$X23eSLSmlQ0aEz!8dxomZ~z z??WVWP-&bRx@uJ#_!uug4vt8xE7rwv`Whuwm3C#(Pkw@55 zsgq2EQ^+&@srkTTY*Idy*xo~#lb^Zoo7*3KUx>~ADv*j!1&N*iMp*C{N2>?7E;8Fd zC)CLgizIXBFkK!`pQ{O9q}T^xH*pHcD;hPQ2n2x8J()Mll1^5>)z+@Wf=6@mx4h7b ziRDx@IfVZ)$o7Rsom&T;5xh~->p)e=Jj@9R0yJD1%?%uaD&4+!&zB>QDc}=BJr>RB zKVXhuKVH%H4-E8wh*2yongsdDkjG(c_WE)ac{Zf!q{3SAr(+NcdvU==C z^*j8Mz4n}vpBwX&bi+f>o>SF|PDzE>)XRMmo82h0$K_NfBNBM{-7WNYc1>dOpQ%BS zxpAq=m6ls@GN-GSUp%$5$Tk2Hjk9y6%3}wgR|sgOZLKMQO9Eyj?KNG-_nt?{7k5`7 zo>|J2B++8n6zAx0f67qS@~dTKpXKDvR{UE@G(@wkgXbzH zqY!acYGs>={c0&`YcVpQcg$V0yE_mq#X-j>h1j(W`3pFV3pJm&hED;sjh8nGF4X{G zg`>uz7?4LZ{hDI5)QNF>h{C)F8_801-h{ze5v@ue@p}0fnd9z&5E(^{%!fUL+;uH( zXiem*GyK@!9jD!cl#UbTq{Nf*tjeBj{h=hiyw-^Jq3iCI(t(Irptt=B5`)gy5TI&W zf*wJX+W{IkRz3UnQB!i*PF+hpe>wgBUd`VPG{SJvtd-Gs9;bWVo76i|++V}Kx>aLA zAFr@GCP~`H2@tG)uWn~E`fn~JC>1iKnu4K`BF6XgwnM^hb;W6b@$byFtWFgT| zfFfHf2{|mzXB-W#R>`Z&>;cBY<{->PcuZzR2GkrK#}}m6@XzndfQ?CiX3d6h$;tQ) z25*9hN@A$Fdy^l?Bz*)LeO{nPX}1?Dd`@%Y^l!WW7~kBC`Z=EeUFO#E{N@gTX#TOQB-f1bSFnl7AQy^*>jlH0otH^-9SP&)c9oWWjLhO7ieTg0EJnA z-DcaH7r_nNw=JehLu|3o_3=5GJ7TEcgz+|dx;c#>T&@*~2XaQdnbe|Zs z_;kX>jB8ovzNxn?45*pII|8i|DV~}zbJwCca=~?Myu1@9G*m(D@poji8ndCGLfG6^ z!_oUf&_6QrTqS^%2>ctW&t?w}&tV~s9q2dKpBU8YHQbQ*s1Ff9;PUfwMMOIO6hny}fo zU03>@zLV{r{foJpIy;%SQXXc^V5=Cq) zA5#1&l`?Hkf<1*C(nbQS^WOnjFULaOeMWODe`-Es`#?@Fb{pBr-j|;T+9eG=M{_>J z@Kbm5`V2wh5i@kd*+4(w9^rB(N$IU)h;C!hcqUwiAKY5H!^Zx0iwIy<;Q zsz>obfvMbvL+V0W8{b72-^JL)!xFsm|oPq{eu8NXFex;XAJol+B_O% zSJ*`Def9YiPnO>0{jOyy%mJ9i>UAMd;%O=i@pmYZ^-W`gDmTt89Bi47Dze@YHJAsc6Kj zz-4wmb}VLC;0@R(g+(-14w9J=iQYd2V%48_mcNeX)G&3u@bBtAp0(suv#9*WmXWix zcO6Lr>T8S&P+F6g^lqQLwh+C3h8ftGK(Fs*c;8x@^V#zb+Zsl)SanrPZ~I{F-GB=v39>3UV#YQwFmFF3dOGr(3T#%d)yLYHs}&T$eyw)= zzLz6*30kvRxxyP&W9rR!rRiYDg76O?ul`+9F>dr?*A{@m&mh}GmHwUwB6Vx&c=iUM zjZ!~7+T#KU&hbj4DC-&=1;F7asb8iT&lh)dOPZ7_+Stj?_7I@?9T6R^{U_s^oFE>= z@d}7t(?HE^91t3V0W0gzG*v&n`pfZBcJ)`! zXbpGGI@*@0iWKNj<&b7K*lg}%Uw7WQntsYX8>Ch75g-7-(p%d7wK|CI?#p0t-k-7q z`T%M9sV|6QTv%&y)6diZpk}OVt5-b?TDsKD3`A+JD0cFl9CB+5*4h{C-kNRf+yyjX zbe(7QW>oR0r7j`a{768^H}o5Q$sV&O(xi`MatimoMS_0%2y~dqn1GWxY)t=)!%3vl zgUoY2D?pq=z+`lDo^I{9`};NI!BAzNbJ=m3;n&+{?%4$;&c6vfq%-oNrH|aig{gq8 z@ZsL_<+!ac2Jgw)oNhzCIzrp+bXW_`OLvmrkyflzF$@e#(dBGK)>7sr`JN)0UhwJd zDwG{Ulf_45;6$M#B^NRl+!?GamnU#-K{_b8W-%?C2+~&Lk$SpzarS})_nVjd)^}ej zoT^$a@pIcHdOS&jJ70Uni53i5j6e85W^On^9Ya*GiJZtp(1nJ(d~dGJKw%@T=V31I}J{q zGZEHR{wOwEY6uI1#09WOc5X0RyS89F)bKa%GvIA{1Y%_$R-q-tqt&@#lr|APJ`!U4 zLDwgXy%_EoKef?crJd<&YA~gPWmi_K@rAh7C(+ZeTK>z3-g)z>+vFYt3w83X?hX}I zcNY4LFd-GMc*mqQV)}uE>KL=6Ns^yn&BmVtgS+b&pr6dZyn3KA(+e&Hr)?G}QTUf43k2R6I z>Y{57jb`800?B5*cfIK->uq;8w73Ap_FctsD6N755~u5jFNW*8IXI6N9NK?5UjT{Q zR7KUPoA*&h&v}j=hP%lMOc9%)CVB|z)ZWzxbTZ!b(Lb4%5?HvOPO=Lb^uxkWH?qNA z0>}ukpzV`F}e-tGz$cQaH>+`=gph9jE&>kMrT0J{{V1BwCw$#LB7;BTkMd9Ru;mr+%h z!Y+ZjMu}d09^7#0>ET5cfhriz*y=4kYwJu<;s-zN_XIok)jsJkl`0 zn=iQ)g^lNx`!%E=Np(7d_^vG9&L*B574<5IQ?oC3;c)4)L$0}c&%L?rGMXo-E+IE? z-T_IAkY*8)Yh3>NrV@M4s_MqEFe|Ho2K+k67S7iuJP1+Lo@91|+^F{2lLTp0Vc9tC z#xC2=Vlfdo*jFf2Sl<}shpQa#pD}5Fg`9}~u6Z9jS-|A#ga#A~mh9Bt2nkUiq-OAG zz00(i)qv-Ia$yCa>R+X{h0%aFr(0pp|D_oMfN%~{$8wv3cqPpNBiHL}dnJ697rcuv z%0|79hvzn+vc7O93mVN;mW;WES^Y?m~8$j-W?DA2GJFoS8e67_`*SogzbjK>zfj>dP#347 zZ;9#gLAvBV>sLfZ2D+mQjFP?}ZF6qU{euU3em)R%`$m}GIEt}tU76?p zX1)*?bd1MQWpX}n)mpyw6fXuU(rasS?99YuMkR%;7BAVi}}RaQ#zO_v0Ap#%VGOw42k^to6TMnk?H8_;N0~tP4$$J z#gevt!Ua=O!7|@YLLw>=`-qePb&^k^T7z=+e{$SXQT-prLtUkLcOw=0L;KXbsa?Z5 zOrO37yifDFA?ry0;enwfAjyNei{{=8BSor@(-b-5B*I+;Cki(PX+z4J*44M2QnGLn~QE&OjM>d=FF{T%Ag3#uXG2TSQD zv|LG#_^tLInm)mK#})0`HxDNq&Bdil!=rvQ$gUGS6;%tZ%cDyTZrr5aASwC{sB$gN zc{0O!hX?@9fN+@;iYmqhAq2p`;?~4 z%klGvPK~FR1Yd-Il~qtvg(izAHe}^86x%+P-X)n;En0u^8`U~~J-UBMch)k0cp?@Q zwq=)0HR#z%M&p(j4_KbulXEv+ht;(rUpTWx`jjiyQ3S|I;*Fokm;W!DAnGF9MRjQ; z6(7_ZWG~7NV9&bPjovJ-G6Jz~1Bi*GYx7i4;I6@2J@HR2Asm*rR$s?Dt(tm z2?^zae^NNxD(cykT=MQDWy2F5K0-{KirBvctvggJ2+f8qfc$y=iB`>G;rV>seIV-zVwbr-^~ zStpB>(3IpgGW$-$J}5#xVo z22L81;w}cewMosEQXe(s#W3pXAi8-zCr>`t!Zb94C&%vQCQa~Z+~`(STD#jbty6z^ zM=)-P&4h6;^i8L6am_S3=Dnqinl6I`N0~E0+h*B*`}~if;|ENd7N?K+-0V`Ttzyh2 zhp?yP@*$Enzp-z-d|Fge^S*^3nb7#kmHIYPsk5Q9I^RY*c76xkqrlw2Q@6Z2j@J{K z5|bvVUOB~Y#pE*d>V~S#e5JoT1?f>pzKebrDaK-NIcLiySxVWhWr{77ram=#_9Q$` z0{}an3Rm-Q20=!E)_7kU5s#Mnws-}VNc`mDcyz5J5VwT>e?Wvf?|#^X745xj1e~C= zcS(sPjbSD|h@+~K$m@teKnf%E!-95mxV9|4E>%+l-fSexXx91g?kjDW9{y~kk z4*ra8K}_d*4{2eMsYD9?N9+l%zl;hRN&$WLhvj*b$d{Ld01E>>-5xNz{GHnO8A}Af zgf~LZ&HfK-$D;<5T#3Mg*jC*CqQj~L=&yjL$ELYE3fTDf*L{Bvv0m32T8wZgMy$7P zuN4zP!-}9yOmEqy_5v}$Uk+un+W<)w_rnFnui^YVCzLO!1_6SmQ=E~E<{ZrrU z_JH_!{a(gCbw5Fw+sobc@iR)T+b3waR5!Es2q7gXf0S07>G`y^lXSxZfz4kPY4+TR7S0p#S;IfuyiXiq!X0M8=i<~fc#4{%AQ?Y z0ccaDY{6eCguZr?rG}TPL0HvLiV|XDytM`5FkDDh4WHRFF6edDZ*ah?341HqCq+wR z!hOQWd%ktUzF({g7Un%ArFRyerlwyS&tm3;CCbk)$RN9(YnZNaOeqnN--hV*BU4kgx1|uVC}*tqOSn{1mhk>t z4v|^_je^R&XE4?b*t^6791}#%S-aFP|N6|l_s6^~aF@=RLBICe07u;sH-z}byl2_+ zcVnmkJxJhz-9iVrpVxepgzE%I$JuixBL?}H5f%rv2J{)O-Yd5vq}Wj*cXhvE$YGNp z!RSMUYr8TIl_PEd>8Z=HbF8|P;YaXU9j>9=0JH^kC=JJh3OZDR3AZ~vfbY_l>78yv zwymZWaMT^NS?rpqpO+KFrSW$F>4n4CgxV23gPEGgt(3ks{l1fHt?um)xqh<$p9`Rd z0u{mItMl6Or?4Xm%cA;3^APft!gpxP;O~x*bAEpL=}A`uh`su^7o27dKM_F(9Ao}= zPY%tbnC_<@zkB7fr(kUwYc`Rh!a*{rheGmN3bn3#@)1u;wv@4Dm20joCBl7V}CM{q}Vglv}8nJtawyFT889qBkY%{g^z64 zboq@pW90Xml`@?#x_6x1e$ls+XO6iQrxVrlni}YKWQ-0cvV6cqe!5l4XT;A0#K-5} zhy6-JOSbabfAYyp92^%0i>$a7vyh*wq; z(oQB(bYm*!zmM~1q?(!%{8?h_m6bExNcxTM6Vl)5@`~=glkqmL;UrkW+xC-IhUzhG z>rZmTE6iv>Rb@c%6Z~_Q2<>H*R?|*VXr;WLZfY< zovcz`g=>@dMtB*}`mY5%n@p6Z%aec*;4UAc_ zZJFmiTfML|&L|unc6h}Rl(lYKFN+iFz{#&Vwsx>eA`fr<7oqmjk^u-AP|NLIHKq93 zq=aN{R5Vo>+vOM6Hu`V+YFU`?--llJ$|&s2GYxpaAOY1}K*=*kb*J*-QHl9Fm@f^O z0$o!dv*de>2I{smXz0vY9R7gT)$t2`-Rlj8@=PZp%_biRc$R?okz@K6|K@8zMzZaV z(F{z}Oih%~eSMoK>USG!Di&m|8*u5)&VqknpWbYn0Vr$@AXJu3p<7y};iS)mWgpRQ znt=m5B0$6f%^b0}8EmWefX@Qt8)EzraN>vFay7-$&Hq>PcfaX_G9>c0gb4*VbDv9~ z1K0VXRC_b?Ra2<0h(P!|2UA{vo&kiTnH$duN2L#SITVUfHnc~4aPHA|nzvg!3m+t~ zYh*D>4Rta1vkpN!(Sw`%s-^!?eo7S@4us{mPwQtwXC}I2QinO1& zF_cqY(D_CDfF)ZuMtX@_+Ekh%`W5hKUWXPoU+V;Tc`*YrWBBrl*E?}UYEmVKolNz| z+gWwcu64VeOa&eXbW-|@WzY9E0OK0KAc}67p%y@L_GcOva)XyIw>yf?p@$gIlz|az zAwWmP!$|MdIEM7N&kX-mpCzZN#IT#&2i(vx_g1Xrk(?iGo8-%;qxhW3Mu2BL(UTrL z3+1(;H7*H3CoA^gBCX?0b#wl*HR%P|i#<0T^ze%6* zz+#o@i$iAvjPLHT6W_UJH5Wrc_Z7r?9ALZ4uc?VJnd2xR!;sHpYm_52go0q}#gF9r z-&+mX^TGC#*5?Sbu+8{vFo4~br* z?6q>wuGaktGxO%D7rquH1N4K~#72Ji5Q^df+`tda-5oC~U0$CE@P{c_)~fNM?!dG( z3bgCejpeE=3s>IHoKMH$^}f;h0a9^`xxHIp%@YoJWK91mpbcyU^-~qPrV1`iYmeh3 zXr7x#(mXi1}@$Wyro&Yg%)3P2YhXI5gz+#+YI@w`1{I+OuW6%~{ zgGEFF*~ek*sZ9`vB#gQeJ++*WbuE5cB?@#fXXt9PAD5*+HU(28RTuk}qNjO;EOKKs z>)YGo4CMLRrulDc+ZY{jBqyl^7R#TgJ|FDJK3_cRuTEE-VceeXU`ILfl8nnr=C;pG zlF-V!BtNCT{hgOt{{ogbzp!UXGjL=EuF3Uj-v}(@-!pHs_Cm>WQ_2($q@eS~f1!a= z-5EL|MMXr(*Y+I6 zZ-vuK8BDXLGvCM7!V+Ji$!H)>zsX-XtlV`n^^q6X)=*&mSo>B^|JU2apSFktDE#SW ziuP~P5t(sJSj*WS*$-!a%g5jx0vrs%?Yip=h+iIfKTuD>)Ek(B0<_CRy|Ya){}R|E zzv9LvDkbITd`t(O)6Hflo;dx#_2o_;(d!Pt4}v9P<18qde&ws`xYDWZPnH75;rxg)!S~wc6*tg6c16Es}K2ToZ3;x;tDRBDA1znn``TaQVvu)705D)llJ(JSr zVA=n1#MkOZQQ z@2ZBgAlRH(k_nKwIzc{oI_Bz-F+E;ksD|zV93|kotiHRI<}40!i9&D9+<6B#DcQH!6OKTcbZTl2fcY!E+5gLWR{=GW z)Af#Gu6Bf9C9&lais4b=t$i<}T#p&&1|t`Sz$c4cO6-dJv|Jt`!s`?$64w%dbZ@wa zrfz@X=x?9rZyq3-Obl2mWT5;9JY5nVr)uewE(TPy$JH({u+YkK^3ut-v3AHwZJ1eG zA7|-=@_L&~k#hWp2Fz@lvF(@tk`MzyvpQQ$O48M*e-#>&#iL}2AE>h{_>Oj9sK{LW zjL#`dSkdtx4Mcm!(NZI5Ukotc+h;167(2AFI?`uZ@69vy6sxd+D;&_!Um}CH_!q-H zIn2i$hG!+4KXNLHwL!Bpqxw_XcsdC)WT@#~T@BuO7U!1n;~=joVmQbs^hw}zgYjG%S*+DHf#%k6y)b{f;ShnPLj-zvI>`mXN%V7q#w}4!EuqS zGustpw)$_2oJy`=?T3&o@&WdRL3OB<=H^SNmmKsK(&-#r!XT;(;}Pu?`t$K)_-SwB z)eT7Ac;{-p;uS}rN!gTAp%Z=6){?Hj5@E1)5eb)i zKAa-?8qn|u^AMF(h&m7mnsC}UU6+NEVKTI$nVGE8k18&HNQVo`T?bQhpYq7!%KW0N z*xi^fXw9Op-f@;4yXY&C({{-xak&HTY>8&A4@8xG6a8dpqfO-azziUJUj=DAJv;v0 zB0paCI0JBQYoTI$z2ewtIa)N|WaZ#(s^ZQpz2{^@y1epFy6*KgTS2=Fl9lntlENh) z!74dos-2z8|AGh{4miYXp8rjRR}~&VhPRE@*xL!}H(%qd~K|s2sW2=-%cWfGA(<$BEotu2u)^ncc8Q=H*1Me8W zHO2uC;=b2f_nd3ZxaKwQ5pN7vgK}_C5I$Yzo|6}}F*2=TlUI?ZQe-|gq*BWM_O9($ zJTi|R%wj|t0(oioZTLA__YF@7UAU-zo6yY83L{szgT2?xOfM6G@FP^w2bW10Os}~K zkDB}eDGz8d9hH#q%Y4e|td=eCQzMlPCZOkkUUxAd@9g{u{Ms*l?9A-^UV1PFYS%aN zYLLd*nib;!8{MG@)u`C0-`m0hbfQ{VPm=ITXv%OSOyJG zy(jZtWn-?oIKcjWUh32aq|z8CQx)j-^;;`3J2^s>i!Bd#cH6QB)m7lJ)Gkaysd&p) zI$aSy;#w}NNJ9^9VbAFu)`U;^L%U!ym>h7S2Dcx$1f&`cXTaIK+k!T6wX1p}FRfS|rh^ zw-aFz>7{Fs7SkfDmA+Z^E9#bp!MB1Wc~9Nj&{Ab1YoQ8S?^|e@W>LJ+UFz45M{2w{ z2suufb>P8!Mhp}hePkbgKB01%R)6YM8{@GvC26+C?mVtpLXk_l8i{edeXYWltsOjN zp2jONM@UQ@Nmm^b!dQR$0v|y$@(XMUlbk8~`=wXRijb7<*+xAD(IT@rT)Xl8VNGw) zvhR!QWD^$I@4l>FQUIrUqi&|UD*+ZOS*>kn=c8#o*0dCNvIrtff~T|heQ^Td@Lc{E zY1jp|r0>^%({EQAkbvw|f!|JXFBe`N0bA{r`v*W?gadxq`GRanuL63$GRBMQD+)Z} z4NO$rM@!lhb6Zs`}TuIQqkCLA_p?W~|$rPH$3hsXKC^YH3M8$UBZLd1`${T4lH9tM4lEmi{@4|A$GXM z$--waN_`Or?^eRKaRfF=S#$!Ds+AT5=E8Mah<5dD%o#;gF!C?7!-yxRkqm@nHD}h< z!84V5H1;&bP}dV}h^qFxroOaty~pK5ApwDm&XF{u7*nuEqv7O0fD5@Y4Ii!GL&7FZ zARY2MV!t9T>Ly*fhVa-|B^dSf4va;Pj`;7uCl2+tNDI}zx{lO~R(C`tICM>|vJ!yQqXwXVK=S2;M?=|K8~}Xn#{gtRO-W@n>3KlfBb*cV z^QZd_bR7S0Z);GibA;p!Ek;Oa0A>zsl&kJCy*CJV0a{9O%+JTi4=|qrGqCg;(emc! zZjoN0&3bQ?4UE8>*5|^_N*Vruh;FhL*h9XNOv6^rBHb^58UYMRh(&((a^*rIIp=+! z=5H`4F&JyEY-}px=UwvLx6-5oc9Fuf$i4+1211`WljcF2hW3Ew)sG_7&XNWF7e|9@ zq6bS!T3)+Vqpapfqhoh&fvkQf=%1k=lmTGlm;f@`R;c$tDx4rPI(qYqTaKnh)j~6K zo8wuf-i05vig=LZlV=j?Sn!sfJ|FQE?j37B9KC+?_Dh|w z#b?Kga51k&ls>1^fI}yQZl-CrF;bh>q+%ST5iLWcKR>MCSS_D;uY}d;B%hl&{j~9M z%i(Ij^QZ`Uc!b=;wUXjn{38uT0Z;2wY21X0!#Bow{3lZ8ht`m`-(X6t&jo3%M&fTn z9dA@jwNv%S_yzP>&1Ft=hwmYd1u?)mk zpHX}94H8$}^?jRN8cgu`4TH2l0LypFrD*)}I$7efhz$qrJGjl>@Q^T-Mnx8FKwPP? zwVZ}jm=rAM4hN}rk$2v{b9%jpI#TI99x*V0F2?+OtyCynPVi&p#MOxkFX)dgy!P}) zKr-zLIzt7}48MYjzjhjo_L@$Y>7I0+AZ4#g4*@xA&|$d*06@I=qlJ6KDhQJB&rZT4 z;#4~U=7Yyn3A4W5fmAmTB~fUWQ|1dC(DsMqrMn1-b?eH;*Og}UB~Byi$vw;qf2K(*<8zbjGk9G#x^v(Up{ww?H@lh>KI<_gitT}2-^>G_iBc6~1!dj8_YmyV9M zkw&`$fuoevNO=;_=XbA-p{gr+4V0rO7#sVP^q7DBPXFq~ixqK)nWKK?T&u|@WOMk! z?~l^6MJ@(7p~FO;H8+<%6Swz^zEPI{e){N!FUxFwuU{a})0xx=*pWPoG?36pb|no; z5H9B55f12;N5r(4S?Z~b!2zj2qCBeY1a;CU44fO*@$=f>kZEF5_LCWN? zuGn zph#I-fR;p%=~jZm3jrkZ7C1AvZ9x;17(ZOGw{ImMu>|wDJAQs3(Il9{lwIp^V2IK^ z&)DL!RUs>J7aSA3bd$6uyXj)p&uVrS;;C16fd$rcWyR zT)qI`lbO*H)EU#X^a@9ul@!@hgZ2RX{NjGZY!j}9(Ci1I zLJ6j|yt?ZOGY{l+ae-D4hq^aVu4ejmnB@=S&>aq`p)koTe zUxh%tPX&JN%f4jdXfU4ewf5I_xq7r3nF4WLF-94mhprXpd^d+74|qOz+uFg) z;1eVzuaxgcEY=*X0|bZ^f#Chp5iAHAs4t5KXF2Hbi=S-!d_hM&t?gvaHa>)k3~;!s z5))93Zh2ZXKXf`HLJ3*^7Z?oaP}88INs(nj^f!s-QA?V`iy=5>Pco+LaKpp;07crF zZ^2EC84_-bppVX2VFa!e^$gd+wlB~}yY=jQXmZJ;K4w0>aq}TO>oOU$mnWAXnoS?W z{aFehoZEWgsnMWzX&01KqTKxCp1S~Ris%-wdBDNZ|4{GXOTzr{*q~`p`F@UX&-?c} zJ3X+&89v_T867|A%;u=FwJ)J&O?`E{ojkL@ZuQl(*4})z5eU|9$Pw`>1Ag%E4gl`% z@!P!K9Nq#k$S?g)Su$+-^vjZWiEL&)tIZWxJ4)R zJS%mr5^NIkDAoR{44?#U;!T|Q1q9mNR)(OLHbwD`MsYFwhl4_+TTCCHMqONBdYzZs zpU$z}_Cl#lo4C>G?(WF7RieiXWx&rTA~@7U^A`se?HvR9u4C6~tg}b!LT^wnwmNRg z8WcXq16AZP#su{MOcz%KHHu<8g06Z@T{<@hGn@UGKQ1NV^l?3uD54}?w$_kjr9kMF zxlB%;-yHk|s+Zn%XTrcn_Nnm*#SY5OnoNhx3Y}X<{Gs zr=z5~K-D>$0tsbYOi$Z}r-I(1$D8F*+2R9mYivkNGo{QkZ(+y9iPmcMLH0VA>8Z64c!pgN?GP6l-~RoZCF8 zqAxlpapqIO8DfOn4bK{k4v#l%Ia~#$UAR5*AT3AYV!f=8%C&e^vB%oARsDRT&~?Hb z4V&!I#RG8n&FF%f319_BGx34Nu1G`7^}FI#_76zlJ3&mS%dwd36%#(d?H5|7_%;(* zAbauE;Gm7V>cJpv`1PBCI+{r@nXYQbfB5-}jiSSZU7c zoZZgSySVvd^XMq++%QgQvp4O*WY@sB6CTUzgq_0<1MrYQ(-w6+%DZz>vgYkQ(?{4h zudgoEOIjOWkj3=pr~mS~YPbHw!FvtMI)QWMGY)=DblShHTILj; zw=CH9iXlbME%|Ngs(d0Dn&FUak_0ADNc#=k?#9MZ`}SBUs}~GmO*gj?AfX_b1-L$O zfaXuZ4z;Q6h>{&xMTKd$y$HOaLWb$SXr#?eb4zJ%c58B^mg@Vyc+g1?8*$(m{tE0q zTqC(uSXo|S7Cicmo$AG(qaWjlaV%m<)dXX%Pgc&xkHL$;pMwp?}px<$<|Pql1ir_NdX7pIF;GY{Yp_Y zZe$P7YYK#+pXQ090*}RXO`%KdZz&(mCVxZdm#MkEpPo_IfRje^Ydo`_q`i8?u|7`k zqVHvJFRzHG<)f#)Si+Qc7})Gh99Gi5n`U@D>zH_#3~>{i?V|Vk@P2=tLig5j3z@a| z`2>BY0vqF)n1%A+-SxIjR)_{y^GY~$Qqs;22M2oQa)Dq;VTXBN4nR05xnRl)}1TEg^E&@6xoVlsS&MXk+M9vw7#UODx6yV`;TkYxPG4e>1C zvUiA1_OParrkj%Us=Wu}c=7r*b%jXTd9;X(1?w-LpBdn25UQJT&84Z;VW$2_X3}JE z?bECJUU>5@j1z0ZjHEqDki2g&0@Q5sbr zjAe0P>bjsxzJWLx{;60we+1c&hE6_}Wj)-&5U|?0=+CM2xP9ZRPw&52fJ*^gOU)O8 z#CmV%K5Vn2Y_dPYus~TYezv%?ynoVi>FWI8b4xX|)84oRIsl9N0;M0(D!CVYb;j~% zQwNN4hYzvQBR~6rqFTouMiRmg!3v)U#eM5*Z`Fc)=xf%WQxfI`J20NPC+U(Tuh-RwH}nLA6G z)H`mYS9Ip)mNbxO{)9ac+E#qu`U?`E>iTO|28y|&A%V37v(eqb>V-yTh~8RoSvK+x zHd2LWc{EefSQ%YP#eyc2&&OUCPks!ea6I6zT&ESB8`&@Le-}1_uVN%TUeRuWQ+#<4t^mtn(gO1=hg6Jf_p*I zYBg4TPT!h2h@%%JQI=2by(A3c@7jCPaGE$3?T59Az0up~7ms2p^ zLE~bXsawCw9)2J+iJ7cp?i2bedhP2=PSd%3>GS>36&!J?>qEIh~D6^)xocG&t zHR|YdO{}c`u?wBs04KO#qrOF(MN&=?p)JFRr_Y6v#pBna&z&m`$%ia@ZYQ2ILZC~| zVQW0Go=M@s!@1uB%=Qu8HYE7oqgF>fS|YGBTOP7dQDTf*{Xf??N*M=Yd3sF07IOA{ zx|OFbYy+H9J`1fcaR^YvEnHkObo3{TD47n|^04CLF*e*i92}!|kRu78zOy-c3lAeq z_$IpuzV|h`mL0RG_`UPl=`Tj41Jw9$$gCNS64j0uQqWa$ZMh7jK7cUt;tB!|Ht^k) z1_B&=hn6Rh_1 zk1aP;a>kbJ#8KtyvQ|Gns&RWMnk5p2jGMKu$^3pDVln+jFb(Ur{Q&cjKrp2Fv|ph=aU?I^D#vY<|+5_Mqe3f8|Cw*Qy|AedzH^bts7Tly;GPDL~1Yg8wM$K`F%p=HTT#w z6u(^xu`cOsCtd_w=Z*M01MzX8)DY{uzv2XrF+<%5IZ9TI#rYUjZo!LP($+A1XLE9f z1UZ}EW5A>amH)67_P-l_UVPA7urQ>`@6oz7#cGPo^PIMZ!gyr1pZ<`h31{U8T*qS0=CY} zDeO@V9FA@ulj#qNq#%}Q+jIA{|C>_$gwTs%)Uj-Y^5ex$?%JMjCArXC*}Asbx@X_w zzjIyDL)ZTUtK`Rrx6dfL&dEtx{p!RXkozNaJ`Qv0DzLuScD^^ZjmK)L%04EB5<7vC zsf9-u{ViaX+*aelXUCzl_Ff0OYvm#o%G{rTANc+f=L5}|s_og=wCV!2zb6~`id4XB zHr&#{LB)^8%M_kG(LY=z-YG?b*h)YmC6!64x}u%kN;kvbjq+d@5owH3wO&fJcx7r{ z9QBf1kUE7(2~^{6^ePr8d7Q$&@LDZ>_I>kvacGblzrT58PuaP`cC@K0!5h?w?FQ@q zR#K-hf{vRaJFRluT<0JZ5vo0n8O^q8TOQ8(+zA98lh>j(JcPNVr$=LJVRXLd=@67~ zAwS;4j7on)bbITJwrvMgMj}l=^O6Kff3RtyBZc8^oa*gvi`dQ_*mgDUE^h1&cyK!3 zbP727YBY!qs@*~^*ZkiKhxX1fDFU$)YiY3y3QppbANM|;)WGQ{KYX%2F#h-A17Fj< zK%9x2vFjNQ7U;<&2he?y2H{ps=3A##lvHe!j>^PtZgydU-(R4zC}2d^ermZ9%~S?b zBj!QD3!_^pqY2*y>8#;*J+1e5+!A$F8zIzun1mK1cB<~t?RVM;~gz&ipGxp4Pqi()PC1qcQWMz@{TyI$uE|v$$2m@bow+T|7?a# z03>9}9|A5(^enPL-t1d^`iV?HTb^L?!vnYCF=nSCL0-wWgKxLxN!z}`)jFPr6^uli zOxER!^KNO()WP`FqWf>80j#VuVr1C;bL+h;RKVxY7{fW*rde2wrb3lZH?-z4rF^4f4?CD8$G- zMb#aJ9h@++P3ofXM;zh%AfTncp&|l$GM^;n)4?oty0Uw9CEi)ENvnn|eUD_GD;9Ew z&P(eyWI#W(r)%!{J72xgrsC-}mE z$NGqp&lP~AQK4^89-HV(aC`frApVYZYEp-R1tKv zuJ0K@v})wR0&_IBqG)6{Pwyg-?&azYkY+OZXE)92^E9nQ50z*!us;dSePW^xQ&_(- ze?U~bD9Qh+eC~Q?Wl!f!dQ=U-rf#c$>`5pI&UmwCvfb#*piP#$cAtr<{q60fr3u1a zfQSBWEw)n28s{II3fb&ceHKLAP;hdOMesc#-0zRw zhd3@hzRXq%K_(KlclD9WrYs6M7{Pil0Z)$zMB;e)ALfkw}O|_ zO@jXCM4D-g=lncp{DqV-F~PUb%}|xp>#sZ0;M_x0_E@RD32UPie6VO0>L1 z`N`g~t?f!P>K9ri(bPj^R8+WA#Kj$dRrCZhelKlpGOVl-`Q-7!`C;c8^Xy@{1s=Hl zmFOcCBHcu@%c0+RalSo_w}y`~WLe+>Yvb>TBv`Od01!HSuo956(ksinmWr428AM(> zyN62Rfm-?CSW*^{DD2)t2sqge{nfOANCHvLw#9aN6#5*Ld^c}Z*feqqo3ID#&E7KH zJ^Sd59Y))<ovP57BdT_LEL%0JT$`WYxdxs`LSP@=YUAN%#Qlb>weZrRp4YVqTf}SCQksj; zt+T$pb2~Q8kQsR#v7S^sG8kU-`A+nVGFVz<&j8#d1Z0Gt*L%YWbxf)*0WaTA4GS5) zV$Z5zO&hkwQG+DG>x&c@M?ypzrhy)?+Ba1^q~kcwxty*>5x*9&8^2;zc#zG7pD~%< zdZtG(dW8GzUoAA$H72(`?C(YcAxa$&wuYd4?7%=uX!LFNpuWLXLAUIfm~1B{1_Cw! zT%^GY-%1mm7=sjT~#RbAcXcH7}SEj;#|7h8Ol z+uovQ! zQ$d3})MD87-0&-Ul&^bi57Ia6mG4&?L$ANAjniI@P9qIENku?j9J|)NjD|XpQNOgc zA^`FmDN*Mur}_aeu8HnE#Kz^yH0{#Ri=@>5TRK{<`;y9kb`07-ZmxHBCtOkU?w@x0l7AjW9~!V&BvCmXbX1&&_Z0{jD$E0Y7(QaPYE$%A}yK|mPz_71RQGCL7w z7~vo;pGgn@^r1Pph0}H-MJ?o7jp1%^^9svsRmJQSve1<8?U#mYI382DpH9pB!RHbv z$xGqtKJ>o~#H^fJX18%G(Lxt>W~NH2&`V^B{EQWhwRv2w>wAlNAO&)RU3Vg7LeiOj zBwD7Nr7xfBkYvQ~P9O-Z#lu%G`tkA}tSbAIZ;||?s>EYZL!*aP%ZYhkVq0C;v#C)P zHGu5{6pb4L?gJ~3Q@ksAshur+ZM#!~I@ym1 zXHA$JTCzTv>}=lv#0LqWf2IEXFJl6s^fGv-+2Evnu&e1+@F*L|6}z_{XZR3&_o7Jeh_^)_J9A zIggbqSX9mxj#I>sBvHFy@8oH=g`b5Z^oziO2RuAEN(>hWmSWBAk*PR7mW%2$QkvqMd1MnA1i;R`0^BMq>6M4Sfx$s4q5*=9I`vbD-H5c|wfL8-t z2p1zzE2E3kVFgWcl$`{Ib~8BgrksYJx?}VwQnG*!v??ma5-=q8iYn;yurTFxU>54% z?uZ<~4YB0^@#y0<9J?nGZ)6$=H?ArB8lRblKoy2@+1a3HV&isGyLMbgJ~U-u;1Pmu z=J(Xn=6$2g(Mhf5(4ET!3X5g#pM_ByttkOZkb3WSM#+UWC24t#t}9-e)A(AVpBoLv zGSI0h_IOV69%0Hb3Y@BhDF;2&9M1(oxRU!82-GP(YALsJu9?0&Hg+p_*e0xmQsvAr zZXPt|D7oTkntKi3x*%4NyoI`KFM#QxtpKsp?$Sp$(VWtdJ4o7A-4$dQ0f+THI|V>mrsKLd1jrgXSuKfGMsRb~|C0MOu6XHmn>}k_tmW-1Ua=V?9z)C0EhAoSR1mjm2Eu=N-CriT=z(Wo@z6w zefX~B^k3Hi`El=D*<(o|^Pl}I!fOVk9ROxb9TYSVSU2!#6@N;!9*fi_i!G9C=s!!< zIm9MpyTGX}2@)#W=k(@YB*$JlX*Dj&5c!zwLQO3$OmoBS$m?_=dUq2~@aQHvOUMI50#u_rZwQQ-B{Jnu@$a=Sx3K1`OFW68 zN6_4#NqCkyB=69zGJR=^-Myh|n+pFBTtZ;jFv0Sm4%3JDhmAj95(s$}mfyDL{%V4r z%=v&OpJJHM|M=r{%dDeg#}Nvra-oFue0=AYZ<$33fRZqi@{n`Umkuf+KGR;_5)|vw zsE>f8=r)6VdsJlPb&l^^KPi4xQOuY|MAV3)7A9UA#^iZSqq)Z^e+TCiG(@wVZX|V#lH8 zB*Ip0unTBH1kcqXIaicjFPjfFV!w+%>X8k25p?jClhB^0VM76j#?yM&l2CUzl7}n7 zgVMws3{se5#Vw6ZezYK152%a)B1!UP#_Vzuu1p3V5JXBChu`4x`?uk*#3xU&!s||i zARTl~pXXk4^VHY2*PA6;nooB$ts7mq&PIMQA$1xYY9~xU?Q$gNO+QwUZlWe|Kwu-&bUWI|wzJDKe{DULVKK z`R+e&>r@Dka9@1d+jLkTb2mMFEc8V%AfjAD`~k^qi-U^(zB`}ZCB1KPSA%1%Cw{HE zm*}JR)13V6yBA~Sd9DVtav#`Yym|02YS`z+4$PkPX0&4Dgg#hw2CBL4~`g3hQ*|_S;wM=?!ywBjuAP-=e zIx=VtLF?{T2@@+1EHdy#qn>miC+vZKlvb5n$QUYkT{);BogPv7Z z_pq@gZl8fDgyX@x4#G&V(~CKz&w!B{&g?feEp?h!ev5$edk@{;WA?va&#P)`FqJcT zON@ej0jNLa&J|iAB`Lup%C^y{Z*scg!LV@Q1mJRDTVdYa$z0O`UWY!@TcNK)UkDs{aVqM|nugugYOqQ3{EyxdDL&=C75LV@ zNa4xl^veWBZKgb&Lne#;*OfTOzR4kuCSiDVu2Z9VD#dxE-1t8le(^RKmwjwWB(V3q z#3r}$UP6hIA%~I{HDW==ZY_fk?MuvykB3{6k<#V64H#~ohmj{6y9nYX9HoSj;NBe7 zzWB+GaW-tJn2#--V1yiMa>wXDwHA`VJ$ui^I_2!O-<+|FIJp~04p0+&uB-rb;|vcp zBD*F`Vk#}q1flh=lmG~&<{+Hl?o#$a0O}S0&uH`R;Y4K{_jIqz?rAa?%s=jAU2L1i z;RZQ3YuA%!S9=R0?c-C{E!b=KKTpLHSQ(xT>P3_@Mim;9N`A%^K_B8 zyUTYD$1C?rvXIiYkMjrgty4U?E^%o4jghfiHYkB8w!!sd1y(F`%J0u3NoT_=s5m9$ z;u{V)TTQLYiEgI19UF4)_+;6+`EzeJJfZbo=Xnz*McKs0E3IJ`R6cO`)}4?5iZ3%s zzOn&MgE8%dDNS@UgCvTJAP#dMn?R1sSS~_>zzkH^aRQW%v%BXLqrL(CmN`y4xUvZL zi#swuEIz##tab2d`u`VGv2bP@PtNW``m$@S=vejuB=_#EE^unR8U^k zEqboq>c$mp7|uoNAwu1IRU7ZJ^Xqrssg{MAn(9-wZS~?W=r3w3jVBcWgg^_Sor8L# zn`NN+Sp+kzYc5u^+;+~dY(}F(TZI&K3MT@b*J{PTy5qUlw&_5BaL#CF``UyMR+d)I zAb7TWWI15d5j)zXNYkw+a&n?Y@fUh*x34TGRqVoN-bKG8w;VS_=zskFU65b%>_Kg% zU{5$yOVP;45P{y@e;9@%u2`LyJ~ZB<`j18aUrnBR5XlL`j&kMJWe)8R`2p zy65*XpeSU}BuI81c5b&PNH7_cI5rC3YkuiM(0*9q_LA3BPvuegND}v|hZA4<dgaKYvHLyVPjD}Gwn z`{DRh)Syfi1b;at0{n$G3rPvYN}X2fiJFLi;H2p{O4Qx1aL5cyZ5P? z6x0|15Tk8Yx6{-9``$dq%oqEiB2{~}0grZ#c(U~^v${{TS3E4e{>1_S$S*W3Y`yg>E!&rxGAquAgK_>vya6>N1xgUr0 zSJ-^i9v?(O(LRMH` zI3{OVeyD7!r6BY$CU{}n?3 zu)=WMu5!ZkRRO#X{o~_RvY@Y>2w9kDq=Uc0T(dmPVTQT)HJSPPZy^^GaM7U(7X~u& z2`FqF4)`hQyMZ(I<@7+rP!45pjS0vl4E$;#8v#5}___rmHJc$t(fpijYzSq9=eos$6G-W5=ppkbL9A5`Y>m1 zfloii1D3v{Kk2gnIiEkjtf1g#1ekn1RDBV0g|;lFh+ z{^|fhFc$EeRV*e1hCt*U6pM1_*A#zo+Mot(p0@yxtRkc{VptH63f>S+y{nuB615xgQ?YTw`47!9$u;^aBwA4cw8+cOc&=xF3@{S( zYSjWHOD8k1Uf9)_@S*Xkn7~r`x$xR&^yn-CPZh8aSI>qM{#Q6re;&95(MA9YumD}N z^D3vb`_6o~&?CO1Yw;ah23@#K3VTrMT569ybPy2GtU8(Y1f{$7%Lz_$iNCqDrK604 z?m1Dt%((l?3M?0y=ByPk~}5G$o3uuK!wV}uQ@Uq5bQ~3&Q&DvnfX1^y-nrx zKUw5|c4jf4V?hR7i9{a^2O2o#ShWkwa#{*)-|ld+(w6&+KwNz^O(0E!S(9Oi?e*Vo zE4?S20FmH*Ne@)kDL~r-G>INpVgT*3rqy52@ccjt@}`SF-YtjAqagrgY+T}|5Xdis z%ibA#=m$B*-owltMe}9(J8hI|{X3B8vW$47?2afFRR!VfNOTN(ZSI1J?ZxD8%C0t3 zH>R~Ni3NJk{=}Y(L!R$@2?^#M6TnIUwlcwF7!(0Sq>35P@LRu=Ws8&y(T9q&CzUj} z-UA;Wc^RzNFk18s6%}`ROz$CydNEcEmU+In7`{FIC)fG!G{CRZJsJFjg)0hZ-_b#Q zH^0`I<>S+0*=6=ycWsXvS9aZwZf{>N?$nf8l2Rzp0Ux&aVVdHDk?64p2l2-4-?Tyf z2B5y7`V%m?diXMDnmAlD3c>tcKSh-Dbyuw*_Z{D?2cA6 zCJCl6G-NEA=qC7aK{b@;1h9NhieCx;XA0@Ni0StLdg%65^|g!Y|F2-uPi;0}NT8|_ zA3o#)7RKkROB}nCDI~B7b`GnoNLeoJJ1VW_In;I!>i4=HS46KJ+I3G{Ba8|z2@CRF zVZhy1)2@&7x8=#K0?~c|E;_d4K%K9kc|m9Kb?@{gPP_Jq8!gnS_pr;*m^;C+X;FX? z{W%dmDEe5E_6hcRv*E5eytZB)wE0e3CM75N;$y6;6E%E$O}*1@T~}qRJ^!71*2DgH zRf8=?d}UZvC0LmHcOowQpL#1WCBUYJh7^g6oE!TQmn$40a|Pn3Yx?{zb@f5xK*kr|;cVPPrA z;QII^*tMs|cAW=jfydNKQubs)1D>}}Vsf>Mxnb333{~fi1uGLtJG~>cNbgpv=xj!} z1D|_Hx}8cko8$`7m{&`SmrP7gm|YIYY4eTGk9(*^RNBvuYLOQ!E5<#^fs>AdSGj6j z_8QCH%d1x*@?jH53^cU(H^1oe%B@t3k=ce@9g73F8e;hWPR_4#yE+XVA9ELr%!A-U zOi?decTMazoT<|g7NJ_(DOgcW3?BSmlE*;j)(p2Fs)}2Yu6N~3IKoBg=wkchi z?HE*@e=ArSW)Y7-dif>{Pe*!rxbKI9zT(bXwqT8*EJePvTL2b^piPR^$V-rAr)a0U znrpmhq@xyRD;Y@&-J}wa-#as8FFe3OL*w-O4AHQfnqj8dYER;j&vdD9r~G%iw+DuX zx+bRizf{z2{er>Ve=_Kv4ZJt*PVAC~oN1k%Z)AD-n`b00m5`YrH(QwN%P)7QJvVW# z*=EM}3CF|^En~Zd1-!Jy#`ae?MR%cOi@t~)w-KilAzprF)fvGkmJtF&TVpmG=($pU z<@{)S$}@$sZ~b%Bv?7UNTKkd;zVFvX`VV2auOFSot!uWi1}*B<(xw>^34%9kYI zV$|%v-IXE|NeDfC`g4c}f@rD}LjE2SSYn|vSvFC$=@Fp4Jf{}-X6-)if2%UGKjg); z?{acv^nN_#FmF}%y0k7tZl_mb3uEl);A8S24~rMgRKlQ0grAqMSwU)IXFNd&b^Gq= zUKdPUBxS2ic|RWP(L*9=>A>}w-u@~{d(B4@5$M1B)?icUxTXeLia^V)wc|y$v@-G>9^PusHy7o**5cjumt>I@tfF~x2X+3 zttabw7>%4}Sz_vV>7k>Xtc!=L@c8(k_C|-$6c3Nh*=F(xgo6c}qithFE8>NhgR+Ik zQXKyl#9Od=0a5b9M&V}+>02%^t*pS)1vyGOMStn2OX(=+X#B;xQgt%x;RIm4=Q zT{gTrhsH&W|+6u|bF; zSWlR_hwy~R;LvpBbl7(C;1uj3&x#4MA&M2|rNf?DD;R9T{?a9H;woJ@+HJc^B^i;Yb7gQwa*ep_5EGF(;T zzGC4hW{Dx8yIz`MrmHD>XM+CEIvdn8OG*+Hz3p}Rtv7pWPkOp`E~ov}D?kHcb#Cug z6VQ@R12Awydc{Uk>#sI+4d1IU$at7rZLMWro)wYx>g@ZREAp?8dAr(_(@iHqz1=Om ziw|H2iXL<#MGkF^+DODyI6%^m$t9X)=G5}Yo~;-?n@K)&IW}}RQH<@?N#5v%%EtC+ zMdaZ)F9WvT$n_0*To6DG-2lkd}3{1z$ z?I;)@G7XszsK~p+ql0^7tt;u>W{&d2N&bC}J=`fN-4{c;R*EGFc=%-*wJ%iByMcbx zUvz3C`vQ(v*ldKZf_7$ftU9quNSA!ngYBmV1XjvfAn}1`hCtYRc%%sz+neDfPS-t_ zLWK+y1lwID2m)hQPsVVub3@8*sr7EDtCIytN7mK0Y_`hJY?YjZ>Hd_?WvzJgcNbuv zn@U( zMwV&Fv=aFL=&kbS(}fDBmY~I0Xi^u1nIbs>uSb~J_1`%)Pz+2=ytLVI1@{56UD4fP z#>=Z}KF9#1V(0J(6jIAqXeiA)E9$3UW`mReA1WJGboL99R{+xROSf-!Z;QE65D zx;L_a?)UgOPi=`v%v*(XQSk95QK$!BH7%y7GSQT&DE_+*4HjByk(;Cak@d)=kGYy7 zuo#wbla`>!nmK%is?FjBfH9(vQT{E#O9`$dF=Us?^2*N~e}|=*W)sG%Q~B{6D~i?B z{s9W`2nFUnaEksN$xFh*e-s>uRNd840D?4Wk1yDeELx@s{ha?*XHE?1q$^Hr+F z$+iY4m)D^TU37uEtd?$bf~hs!nkW4CqXawOJ!zk;igvp`CtOb15sj+#umBtp(-*q| zUTbUFCdmDM<$X~GhM|jg7;8^jxbq4IonXXC&5A9ULe^ptkP%n2|9)INJ@_#Nb#mA2 ztRZ{7CnNMMt2bjzlsKRUU;@jRE_ZaJ=q`T%yTpkXdTin`IHLY59I#uh68CH^c#=i4_6}xU_m%IP_@o2M$?uY&Ppz62@{O4miHjwb= z7zzv|(eybyMZFUw(k|gK&C-7l4p=9OUQLqoG3_n@V zTjs`O0drwD(O~62TN*zf%SzGv^Bv;PzXoQ;@(J|XHjF06c)82nx@PaCO1@|+e0w}b zieap(gkhrGX}O&lUJQk5l5&U>yT5(X?lI%>qs0Wwdv~1i>fdR9cx-*V+3tDTjAK9h z)T8bw?+Va;4mtp(Qq>Vk&dH}#fI`K*yp9;#=UWy~A`OJ9?Iqukd2j&g`u(5n)y{~j z*$YJ+tU&9SN3?j7ttNyA$HuzKMrh?#RTp0DDCaSWiE(&SfhU{9o`U859Xc34hYZ`J z_D~j6NNCDve;OQ~T3)WAh>d!GQvZEG!2@mWZbzpfO)>B{Xa!HphW_&zs88A*KpBAl z9atp)xpPrJyes$LPXhm|#Q9&j2mkxD@&Equ|83a+3CaH{#{V4#UDwg$aLag1e0du<*{`e z^C$v%oAb_eN}6=|a+EB4`#^@Qa`xMvUG@JM3}72Bj7{V(ioDK`J&~QdJ*i?IplqQO zuv`yTA(xX5Qh~wpB3!rL+pBKZk0ZUl9%5i%kici5VqJSQ%&J|@d*m**F`U=wk55%> zx6nFi-^m7AvS3Ew4i@OH1x1`U+YsW%MV`kcFhGi} z3lrI{WWXV$^=#Y&6L*<*Gl^wYj}qCb;elNpW*r<3Dz4N4$kpko>(3$c>8s<46@VgW zUmwcRw3Ygw$DncasuM%0#oT$5_^moJ;&c+<<)|3-Bnu(iq{XAaB9|hiY26z4dd1Hz zY28=9)$DlfbT;|ng4|EsqP&f}GQag?e1Cuc+nk}AtD}P6{iRMGud_qaWa9sMNJHl! zDgqM*eh&{Hf9c|&S20gTHtO&QIMna&!=1O>8}~eb#R1w|l5*%IGiJYik|5$@P3yVa zD5s!MH@^Z)PVO2VRZHwPrVN#ml9nDcl{2=tXB=8*fr|D>k;o*6i{zzT$R1(l77~h$WwS%G4HBzw<)a*uQwY;s z0AZN*qx3QA^QH5cv|%B%OuQY{8=UVhJI`Zc(hs}=D_Q!fsYUkyD;3Y-pD7bwE|1kJs%&5 zVjQ~O$+9lfkS{?t`Q_*oWWC8w&&%6d9C;Gc5lnk-@3}xV)5a{m7f3Da_(*2JlHURJ z99gP6C&;L+{cQ8Vr0X(|cJ?7(QupQ*ykf}UB50qU0R7}^rq~zqb?J0wTb*`XCWY+bU$DW62bYA@vmw7hpZ$81a}npRPHd+7Sl< zI+yzMDbd}A%c?p5vbEJ!*OqX^*iSZ@ydjC2AMUlO@=5$g+mls5cP;0DvukV4M;R)5 zb-IusSXz z-g~WDyXv0I+O=y1`1wCma(unLdp|zlt5qd0G!kvn$~0ALN!AG*gq|(EidT^`@-B@7 zouZXzZ-!0@+|GURQ_sfd3h90!awcZTZ_30+ZGfOdfe63 z#o{ggzP(*_>~n*u5NI`j^Q?f`*{;l-2QsFG=2_0RIU%#NH~3zz`sd}S%~WA#k3;?Q z!YSIx+AwC@UEZE^+^e2Y3iQ{NTkoVbP{iefPyT~v@MGlf|ADUf(c{*SFaK}uFqvo>)vsCr!WxLrk1;2a z{x^^LzoYzPoQZz;G0r~%!2gG!*S(VFxRR#bIqUpwY(ukfGtbXR#GcIO{MpQ=@y^ zr#auL9%nNBdT1}#a?0bn{(^#{oc1?wJ}mq_>~>@HSlyz7?%eQKQXPi;BX0kQTR;36 z;nII3v~ULOPrgJaCUS2=6|-^mlSd8Fa{UBRl%kv8HM79T%vRp4sUHSj$LM{g8TNe7 z&#DOEf>3(Iqwllk z8+_d#bEg&vBxBmr+ekv?_|DiS{it=V^h_FLD-B& zdU;SaJ}XN&r}KtRUv-dQZEdYmh{))*R$4KcJeEIRwA9TgQ@%7mrJmY41tzDT1v_yQ z0M}1dTAcf0(m+0af8b?Gs%tN|TLja0j+Aun{wAfRG^45jEG)6BSXfw4KHc7`au$El zbDeli{!0c&;}jdWrs)1dJ#m_un=81uxP-e-R@gf_7LVo?78Vi^6G&4KrNE9$E5kF+ zG%l~{+1a@GcrFbMf{4&dWgjcOvvR3WPgO(1&9_QBxrL^<+N1QP7el04kPS&F{nTP# z9~;U0O)madNnG6%Y%O0c7D?N)P`J2!a3398PM2l4FE2P2jNIe!DaXNcA%LAiqN2s4 z=?0~qMnJ$TwjrJQj`0^0jov*su+ES8lW|kgk(Otz!;k@(Oio3t9AnXQGSI&?DI+!4 zVMoCH*>PF~m6~qW7{_Mw>K6i5uidz7T928PIT4rb`fI1Brw!Y)uPqm{k;E*i)XEU+ zqM+r)IV?bieY-Y0+Ae5X9|=aK?2I63V{d)#Wlc@ZY-?Hr}rD!&;_tT&fWx?Rpc{dhtNT-+waJh(+ogVONa#2$XtS88?- z-)`*985|OVL#ImEjyZk47C73L!Bu*9(@J1_W_ETQm5N7mMW69jpp3NV@SXBxl2=z( zr{ui!?T;W!JK`t?70J=e%k~Yj;|mq+9A~`B55%u-S2#alei zOw}#=*Y=W3IWb9SMQ*G@rVm*ekDp4Q9>(lDOUca4yeH$~-rU)_T-5&OzK_1XZX*Q! z+9IiU5tJ2(l(eg5##4PYZMk+P+B!NJn5!f2v$(m!?B5o57{9!|&g|N?8j!OBW^ZGf zhGz(vFDFd;FlRY%L%Ah(uk;X84+0%v5;)+h1QqCblNgZRPopV zw1=?M$M~hu_8e4v`PSN$?J=ocRnI>(<9uWEy??Zi#Nn%DKEgdD)15QUh2!21qnfMh z&r+#Fi?4jMvqc1%2Q+ncby-C$-!10(q6_|DU^MP7anx6^v$Hd<3lD>Ss-2)sph*j| zNXb30frYnv9arc>PAC=JDakrHebmI1%6q?XOvduL9jXfCt80*B5330gHCbMm0kxv# z$-F066uZ|2>fX?bQwa;MbDzx^931?|%{}6fE4r$zp4hzL-rZ`RB_u37vmA2b_&WOh z#GuW(;~ew-LB?-Z)t{yJ>-~vW=Sb6EcRV_s_@4k?$S~ZGLBU4Moq78&hD#*pOJ1?VR%@TiJ|O(FW5Lp}{>nmok(HHI zZMsoax+Mf5xns9}+JGMdR{R~lcWrDc%FBh{+$!;xuCO2M&kx4y2jlaD34k;Bkvac> z(LZQGA}s!(1%Eh$ADkK{g2%0mBjZ20o|^%BO-xKI4qPQqLCTL0kWzepetvNv1L>|e zGUR9~m1z*&Lh62Q!%JLk9d?_l0aSX#_CA%3|96jN1=6m{C|1qHW&+I; zzps~CoVvJ~ymXg&6g7)~_-d<9InMCM~8F^2$%UTe>0 zLKPt(-}qNh*5x`?!^9@Wf8@xKe}HHb!0B%5f=5xO?!Hf56B&i4TOvb-N~G<7P^fz^ z9`g3>+mCnB0CsR!fR!fmEFj2Wo8!epqoXzK^v`!g?P|pns6$ena>>rAIZG=S3iawh zc2HQLvQ1osoGA`OT{pN@S-niA9nEn1QYfbmbS z4B*D4IQmyD`b;m>FQPyb2Z`_Zhr0-1r-SMzM@!xJlQu?!E06)lA$W80Q#Fn}2M@3@ zIwwbT&z?Q3N3Wa)a1We(=Iaa>Pq+Mqm9UXzh9_HHh8#g?a6$xHt zy0f#h^X6b|pa7b{qgU{b0Q0dRm4;hW>p-m7b=~Z5L)RJ*n0X%iT${y*1=P9r3C?ok zyLctYj_8!5SKquN`kx>UpeG`*&d1je1g}R1Dl;sDR6xHJ_V=qSZFAWa92{)>*%Y`xp{-mh)sTyz?#nkGK4M&Aadxz- z(w|$Qr=ebZTW*mMpspawB}!lDftS)mNyv zoq)m1+k`3yW-jjZ`F9FIHd#yFm7Ip`zE{30_z@xSBEE?m_YyZUF)<#hQ&C;YzwzSk7ab%lWFnbj@AEif6x{J2!1KC_!F z=kT2#HM*$bAE@sx&Z6&X^TwAw;?4#Z+$~(bP;Wf7bd`rRWGebJyK7t#uC|070iy4( z&=DLVT0+&>7lsq2KP944l=k4xqwAI=()MKe(fp=7)S_VUztRK`+-4FH1~yq_x2Tm8 z#ooc8_isja6n%I46GToi6nMm)nRbit$iHoC3j&KM-Wac{Dkmo=Jsq`)P~O#n4O*Cb zNcvTtkRS4BrE|iGR>-pGK89C6x?9BZtcC{R2x;>=FoBCHmxBn7J1L`9fdZov2kmne zx}*&AW@=_mPCpb-B0Z#oF9~rE(E{RL1pN!OlOf0=5ZnYWL83n9*>QUfs;&3$vd1{FsZQDsr!#2yAqQKHxUhunK^@1$0<0RdmS-Z2oac$RqlR_ zDcjoW!t$6sP2@enhZ? z2kJSSLFF{LJWiG&yhxtIFiOi!W~+{(p@_vD4z0Rw`o4Q4MSNxGPI}IRu}TrrQc!6T zmcsj@`xeI51njE##H+1>=1tGQvh}@Y(N_Z9%UirOsT3^q4=qTLh7d~iq1Q*tI2b$# zf!pZf;tQLebP$yV7)e6-x|W&k32cb#=CG?(spm#R0~FF!h@ z9v4$sC?#lIU5>$?Oi*>B7BjCSQ8?#lWHOCbhS^Una6s{eN+x%Nw8=NStqmtWz7`*h z@e?qrd`!H7PL7o_1sfA`6Ouqe6}DCN*irR(l^Xo{sBEvxNO61qT;#K{Dc_!mQoTz% zE~VVEm3w;m)#-*y!U=wFvdyZ*gd0ng&NqrM)jWCkYKL&J(ypwoos5c<1ZBnG3eGe^ zWr?(GgO9H~pZV>&!1LDp)%I=YZvT8Z@F%SsHgj`~Q|2K7rE{vU?wukOf zdAxX~2%Q*v>(=V5tgM9GTrKN@3C}pyh?I_w%gs2W8@A&N`zkwnm_&+!V_Yj89}{DW z)0c*ZhR*BjN5GD0gUEgwTZ`!q^RCia+1W$UzS3`@s5=s*bYQe2SAD#2E*wiY@sJXq zlJni$jHLpNbLS$TKYwoHwVvdm7U9k)aOjYHb93|1z`(=SVGSFbv;w`<8zb+cz!`hB zrDkNP69Fz0OAa;RQabbV^VHi)R7U(JGY;wNPBe4PB4Dn|IuE;Xy=*8l2S_% z3(OO9Q`2)-uSOr+>sz!uYMmGpbJ{9L2T@JU);9fsaxka-eQ$3KJ-u-Hd>#2bYIJ@+ zjGQ9Rd4_ua{CQ4!q(IcvRL#?;Z!_0nS5{V1IAvvJ4@pYuAP3)udZSwkc%HM1i+^Y+&x6-bpFii<;@OdvnRyUh8_27B z-r719>eb$hOnKAo{4irAFg*V*6**2 zXuZqs{>;aRSvSvK{s9YLK#g(!2ltH|H>PVRSJu@9a^AUncR0J<%CB)SrgXbUq#QAP z4ILdxntC^7G3reSteoCO19_Hh0@zKhyno6JjsmNle#jCMo0=}*R)>UyE*MX(EGI~^ zG3Q=RnOM(2@~}YuKZM26W(0SP43|97eR%bcJv}o>$Oe(uXs2DdL)caXs@?N!d+#S* zOyt?2*e%9<_tf(8a?f^@c(s~ZTel+q#bFY3VqK(l8yPC;vwEqTNGAMWUwKs4)6m@= zdGgdLqbzNPo_#nW)Q02{iCCC`1*e0;!WtRIHIxcNN?pJDnKPc|=H?f4bhvZckN8!@ z)YqSrr&RS)n$7q4^7m^L0* z`r&7<4I4K$mzUp5(JS0lZXLlp`Mk~2HotRn-nHi!;$55D+Y=$M{z+o9+?g|U#l=fJ z0Y_!`-N@Gs{~}#IW&D>b=85+}b+FxBMpqsifvQed*>kT9K}ChE{BB?EU-q zDMESFldi4>J9sWdVlvl+imM|;`l83SZP~IfzmwOuj3c#mx7bDKx}WTBB9Xk}Q&M;f z;q&ndXh!qxbz9%K(rC0)EUK8pJ`_|`0ytScqdtGWzH!s0s-B58Z}Kju9QRp6`n_Og zdU_zIcsUvKKto%b8WY1Q|F*vVA(l2%o<7}otu0-)x3@P~%;u?{+l+>M^d?=Yy>(C6 zMEUuT6J5L!T}-7OhJ&Nxjq4vB#gss<)IvDg*!Xx0BxGw^$@sG;D1MU?Wt*~ZO`mSWl)3j8$L4*Td{jEefL%`)3! zNA4;#d#7hqXlUs1a7B6f1}rpjZDeBVxL!OkV0yDqFSm27BpZ$c(}~=mzSe`hd&QgK z#28k|)nsMwoH=tQ(|+(gy1IhjYuINGD=T5PFnCLm5aiQIn4b<8OcW?peEa z@v^ZeN*^6`i(Iv~Z{I#NJlu%Ythl74q>`GCc;J36F5ld!5!+ns(*7Il6VY@4(81i= zI#4L@aOq!LxrBg$ZT|X+B+P59KcH8&tIU+9* zq*Pg3+Y+l7*woT;z%0{ah0^J=HzI?#Xl0#{&~<|!l6IR(Z}R0iFB5-jx}EY?$kEAv~n8%d8~=S8soRRj+MALW2C;0k>)d zcbn8Lq|HL~oF^QZ-a$b@dDlPOx^m^pHg@(@U+IOjluz)ivm;t?RtE(H&Lc*_cS|@= zKZ|LwC<+MJ5gQlhGdS=wsl-Vzqy~n69)1B3(;f?mM>qVXSBLg|nsAz)C}UULb!17* zZ6Om&o(nXI2m@#ITsCkY3OgB zht3n)xTcm?kV^Qm1Ynj!M~~Vl`D|FXP7S^uiET9Ug*{Tv7wTkI3c}rH+e%)~hD*8F zV>%;}S%4WB8XRmuDpU?XXrp=YVq9LH1Q9G16cpBP6V&F}fhmc}LPdl@6x<{=eJ+yw zp21ES05(=p!*V?ww1$>ef~xfVX-tq$Vx*E6I=Qy7(qFn62z7&kva)~sXaGDKylT0DhF`JWoMPHs09t1@eayuT#q7Fn8aUa$(gT+;CAg;rFeE1^kcs+@f z^8)rYP)DX`pr+^<<|Mild5c!^MKp0}$UOHlFA??p{rx2z$3g+qqJY80#9L2QM%1Q+y z*FtjnPf&UJ@?=efj6UKGx?;Rw$_FD&b)>mzvb%o%18`8y$k=%D3J+p3ppce+rb!bn*_XT&&CD*H zl%6iIpOe$e@e=9!DNow?obMbb>9RhVOpc75jwk${Vj!=7<6slkob8b+qAzNK1m$E_ z=Ii`JLb%QBjXZ&A%m5k@>tldwlYt7j#l`21@2)15?39kc5jZxjmiqZOk^}hkc}w}5 z5D4+oMDmBXBzUka!-_3;Zr?^6Pe6e+@I?~@5<+%;N`+rOKB%m&X1i-jBJJcpaG)>v z8tmjEED>%B(=iKnjJBILQ#G#YInB(wA}4EIm>F)aua86#j0FgWKZdbm!JEbz+YVUw zOq06mAs!wjcJfjh2(d`mA+oQ3q9_y<+qQ4tj{)f^^RA^>>w3RelCLF}n#*mQg32`2M}Na+rih zh^Tc-7%JqHS>SK1vN4IwkUZzP&ZiS5Q#kIXx_|$E1tlefd6FJ3{%&%v`mtalq6nZv@>55d7CzdhR`dd?cDuOuJx68`u6AX%~un? zuciC)mAU_Wb@Qu(|5dK?@715L5E<+L{aJH# z$_dpB|MU5E=a*%72YY+Cb@ZECR6mic0gxH)^xU##i;&I7SG#>i2L|d(N<4_4L5;F{ zPTZ;ewrRl{79u78_fvADXEcXKuO2_Iu0DfFaq57dJZ`E#aLk8YCS`uAKk@nVbFW{& zUO@V_5_DBkLgE61UO8RPin#dxg-vwQ#bFkSZ@1fg`Ma0O@dB}=Kv`H^boktT0#nx< zq!1+r5;h%~FMn^c8gg}qEbbsL@0jOR0YSkmt4;~zA?22R4a{Ggm$NT?^Vh$7=)3{6 z-!Gq>oUEN=6}EoE28|0BwtaDjU~N6Tv6|W=W;U@%aNUQ*#kIiH`PCRVqP|U6oQ)Y4 zt%&rn$!)GP-Wuh76i#>}R85(~4B?*D5OE0lWA_fn+js9W<~ad`H4aj0q;UgqoJ`exbs%p3f-{~BE|GeJi$^f z**<$D<3Off=HTFnkmLjCYSky}qW<*4i4%XUU%y@mMR9zi8@_fHeX)Vq+v?v>w;&8g z3a}sG=sZvzF*$DEUb8$PCqqFlhU_L849Nh(k>w|8)mdwosaqYs9&G_*KE`CCLCS1JFtty`nv=aCOp z@_Us$dGX>!os_S^&IM>TlYrX^G)YZKX#q1dgPcHCOG|4d*W>F0N&>fpeKT(oT^ZT` z&6_tRTxOFzJw1s#APRD=yE!w*gnNcbVe31_;Qjk+*A^k;G zxONswv{=*_iXg~`hO#AVXDQ%)uu9}#W2|m&PGw^*>#yZP;-)`esrl);n2?y*GyEQb zN8mnJK9qm0(JKjj^kHssxkqZ<*O&FssrXQOSC~w9J))g?77oK1T$_yD2%^&rhH@Bs r#0!|V$TkipHal-M`DVRu+E++NKh8{Q3p+^>H8= literal 0 HcmV?d00001 diff --git a/simulator/simple_planning_simulator/param/simple_planning_simulator_mechanical_sample.param.yaml b/simulator/simple_planning_simulator/param/simple_planning_simulator_mechanical_sample.param.yaml new file mode 100644 index 0000000000000..e844b07ba0693 --- /dev/null +++ b/simulator/simple_planning_simulator/param/simple_planning_simulator_mechanical_sample.param.yaml @@ -0,0 +1,62 @@ +/**: + ros__parameters: + simulated_frame_id: "base_link" + origin_frame_id: "map" + vehicle_model_type: "ACTUATION_CMD_MECHANICAL" + initialize_source: "INITIAL_POSE_TOPIC" + timer_sampling_time_ms: 25 + add_measurement_noise: False + enable_road_slope_simulation: True + vel_lim: 50.0 + vel_rate_lim: 7.0 + steer_lim: 1.0 + steer_rate_lim: 5.0 + acc_time_delay: 0.1 + acc_time_constant: 0.1 + steer_time_delay: 0.0 + steer_time_constant: 0.001 + steer_dead_band: 0.0 + x_stddev: 0.0001 # x standard deviation for dummy covariance in map coordinate + y_stddev: 0.0001 # y standard deviation for dummy covariance in map coordinate + + accel_time_delay: 0.1 + accel_time_constant: 0.1 + brake_time_delay: 0.1 + brake_time_constant: 0.1 + accel_map_path: $(find-pkg-share simple_planning_simulator)/data/actuation_cmd_map/accel_map.csv + brake_map_path: $(find-pkg-share simple_planning_simulator)/data/actuation_cmd_map/brake_map.csv + + convert_accel_cmd: true + convert_brake_cmd: true + + convert_steer_cmd_method: "vgr" + vgr_coef_a: 15.713 + vgr_coef_b: 0.053 + vgr_coef_c: 0.042 + enable_pub_steer: true + + mechanical_params: + kp: 386.9151820510161 + ki: 5.460970982628869 + kd: 0.03550834077602694 + ff_gain: 0.03051963576179274 + angle_limit: 10.0 + rate_limit: 3.0 + dead_zone_threshold: 0.00708241866710033 + poly_a: 0.15251276182076065 + poly_b: -0.17301900674117585 + poly_c: 1.5896528355739639 + poly_d: 0.002300899817071436 + poly_e: -0.0418928856764797 + poly_f: 0.18449047960081838 + poly_g: -0.06320887302605509 + poly_h: 0.18696796150634806 + inertia: 25.17844747941984 + damping: 117.00653795106054 + stiffness: 0.17526182368541224 + friction: 0.6596571248682918 + vgr_coef_a: 2.4181735349544224 + vgr_coef_b: -0.013434076966833082 + vgr_coef_c: -0.033963661615283594 + steering_torque_limit: 30.0 + torque_delay_time: 0.0007641271506616108 diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp index 96cfa1587e646..685708844d32d 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp @@ -21,6 +21,7 @@ #include "autoware_vehicle_info_utils/vehicle_info_utils.hpp" #include "rclcpp_components/register_node_macro.hpp" #include "simple_planning_simulator/vehicle_model/sim_model.hpp" +#include "simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.hpp" #include #include @@ -147,7 +148,7 @@ SimplePlanningSimulator::SimplePlanningSimulator(const rclcpp::NodeOptions & opt // Initial value must be set to current_input_command_ with the correct type. // If not, the vehicle_model will not be updated, and it will die when publishing the state. const auto vehicle_model_type_str = declare_parameter("vehicle_model_type", "IDEAL_STEER_VEL"); - if (vehicle_model_type_str == "ACTUATION_CMD") { + if (vehicle_model_type_str.find("ACTUATION_CMD") != std::string::npos) { current_input_command_ = ActuationCommandStamped(); sub_actuation_cmd_ = create_subscription( "input/actuation_command", QoS{1}, @@ -311,9 +312,7 @@ void SimplePlanningSimulator::initialize_vehicle_model(const std::string & vehic vehicle_model_ptr_ = std::make_shared( timer_sampling_time_ms_ / 1000.0, model_module_paths, model_param_paths, model_class_names); - } else if (vehicle_model_type_str == "ACTUATION_CMD") { - vehicle_model_type_ = VehicleModelType::ACTUATION_CMD; - + } else if (vehicle_model_type_str.find("ACTUATION_CMD") != std::string::npos) { // time delay const double accel_time_delay = declare_parameter("accel_time_delay"); const double accel_time_constant = declare_parameter("accel_time_constant"); @@ -323,37 +322,77 @@ void SimplePlanningSimulator::initialize_vehicle_model(const std::string & vehic // command conversion flag const bool convert_accel_cmd = declare_parameter("convert_accel_cmd"); const bool convert_brake_cmd = declare_parameter("convert_brake_cmd"); - const bool convert_steer_cmd = declare_parameter("convert_steer_cmd"); // actuation conversion map const std::string accel_map_path = declare_parameter("accel_map_path"); const std::string brake_map_path = declare_parameter("brake_map_path"); - // init vehicle model depending on convert_steer_cmd_method - if (convert_steer_cmd) { - const std::string convert_steer_cmd_method = - declare_parameter("convert_steer_cmd_method"); - if (convert_steer_cmd_method == "vgr") { - const double vgr_coef_a = declare_parameter("vgr_coef_a"); - const double vgr_coef_b = declare_parameter("vgr_coef_b"); - const double vgr_coef_c = declare_parameter("vgr_coef_c"); - vehicle_model_ptr_ = std::make_shared( - vel_lim, steer_lim, vel_rate_lim, steer_rate_lim, wheelbase, - timer_sampling_time_ms_ / 1000.0, accel_time_delay, accel_time_constant, brake_time_delay, - brake_time_constant, steer_time_delay, steer_time_constant, steer_bias, convert_accel_cmd, - convert_brake_cmd, convert_steer_cmd, accel_map_path, brake_map_path, vgr_coef_a, - vgr_coef_b, vgr_coef_c); - } else if (convert_steer_cmd_method == "steer_map") { - const std::string steer_map_path = declare_parameter("steer_map_path"); - vehicle_model_ptr_ = std::make_shared( - vel_lim, steer_lim, vel_rate_lim, steer_rate_lim, wheelbase, - timer_sampling_time_ms_ / 1000.0, accel_time_delay, accel_time_constant, brake_time_delay, - brake_time_constant, steer_time_delay, steer_time_constant, steer_bias, convert_accel_cmd, - convert_brake_cmd, convert_steer_cmd, accel_map_path, brake_map_path, steer_map_path); - } else { - throw std::invalid_argument( - "Invalid convert_steer_cmd_method: " + convert_steer_cmd_method); - } + if (vehicle_model_type_str == "ACTUATION_CMD") { + vehicle_model_type_ = VehicleModelType::ACTUATION_CMD; + vehicle_model_ptr_ = std::make_shared( + vel_lim, steer_lim, vel_rate_lim, steer_rate_lim, wheelbase, + timer_sampling_time_ms_ / 1000.0, accel_time_delay, accel_time_constant, brake_time_delay, + brake_time_constant, steer_time_delay, steer_time_constant, steer_bias, convert_accel_cmd, + convert_brake_cmd, accel_map_path, brake_map_path); + } else if (vehicle_model_type_str == "ACTUATION_CMD_VGR") { + vehicle_model_type_ = VehicleModelType::ACTUATION_CMD_VGR; + const double vgr_coef_a = declare_parameter("vgr_coef_a"); + const double vgr_coef_b = declare_parameter("vgr_coef_b"); + const double vgr_coef_c = declare_parameter("vgr_coef_c"); + vehicle_model_ptr_ = std::make_shared( + vel_lim, steer_lim, vel_rate_lim, steer_rate_lim, wheelbase, + timer_sampling_time_ms_ / 1000.0, accel_time_delay, accel_time_constant, brake_time_delay, + brake_time_constant, steer_time_delay, steer_time_constant, steer_bias, convert_accel_cmd, + convert_brake_cmd, accel_map_path, brake_map_path, vgr_coef_a, vgr_coef_b, vgr_coef_c); + } else if (vehicle_model_type_str == "ACTUATION_CMD_MECHANICAL") { + vehicle_model_type_ = VehicleModelType::ACTUATION_CMD_MECHANICAL; + const double vgr_coef_a = declare_parameter("vgr_coef_a"); + const double vgr_coef_b = declare_parameter("vgr_coef_b"); + const double vgr_coef_c = declare_parameter("vgr_coef_c"); + + const MechanicalParams mechanical_params = std::invoke([this]() -> MechanicalParams { + const std::string ns = "mechanical_params."; + MechanicalParams p; + p.kp = declare_parameter(ns + "kp"); + p.ki = declare_parameter(ns + "ki"); + p.kd = declare_parameter(ns + "kd"); + p.ff_gain = declare_parameter(ns + "ff_gain"); + p.angle_limit = declare_parameter(ns + "angle_limit"); + p.rate_limit = declare_parameter(ns + "rate_limit"); + p.dead_zone_threshold = declare_parameter(ns + "dead_zone_threshold"); + p.poly_a = declare_parameter(ns + "poly_a"); + p.poly_b = declare_parameter(ns + "poly_b"); + p.poly_c = declare_parameter(ns + "poly_c"); + p.poly_d = declare_parameter(ns + "poly_d"); + p.poly_e = declare_parameter(ns + "poly_e"); + p.poly_f = declare_parameter(ns + "poly_f"); + p.poly_g = declare_parameter(ns + "poly_g"); + p.poly_h = declare_parameter(ns + "poly_h"); + p.inertia = declare_parameter(ns + "inertia"); + p.damping = declare_parameter(ns + "damping"); + p.stiffness = declare_parameter(ns + "stiffness"); + p.friction = declare_parameter(ns + "friction"); + p.steering_torque_limit = declare_parameter(ns + "steering_torque_limit"); + p.torque_delay_time = declare_parameter(ns + "torque_delay_time"); + return p; + }); + vehicle_model_ptr_ = std::make_shared( + vel_lim, steer_lim, vel_rate_lim, steer_rate_lim, wheelbase, + timer_sampling_time_ms_ / 1000.0, accel_time_delay, accel_time_constant, brake_time_delay, + brake_time_constant, steer_time_delay, steer_time_constant, steer_bias, convert_accel_cmd, + convert_brake_cmd, accel_map_path, brake_map_path, vgr_coef_a, vgr_coef_b, vgr_coef_c, + mechanical_params); + } else if (vehicle_model_type_str == "ACTUATION_CMD_STEER_MAP") { + vehicle_model_type_ = VehicleModelType::ACTUATION_CMD_STEER_MAP; + const std::string steer_map_path = declare_parameter("steer_map_path"); + vehicle_model_ptr_ = std::make_shared( + vel_lim, steer_lim, vel_rate_lim, steer_rate_lim, wheelbase, + timer_sampling_time_ms_ / 1000.0, accel_time_delay, accel_time_constant, brake_time_delay, + brake_time_constant, steer_time_delay, steer_time_constant, steer_bias, convert_accel_cmd, + convert_brake_cmd, accel_map_path, brake_map_path, steer_map_path); + } else { + throw std::invalid_argument( + "Invalid ACTUATION_CMD vehicle_model_type: " + vehicle_model_type_str); } } else { throw std::invalid_argument("Invalid vehicle_model_type: " + vehicle_model_type_str); @@ -710,7 +749,10 @@ void SimplePlanningSimulator::set_initial_state(const Pose & pose, const Twist & vehicle_model_type_ == VehicleModelType::DELAY_STEER_ACC_GEARED || vehicle_model_type_ == VehicleModelType::DELAY_STEER_ACC_GEARED_WO_FALL_GUARD || vehicle_model_type_ == VehicleModelType::DELAY_STEER_MAP_ACC_GEARED || - vehicle_model_type_ == VehicleModelType::ACTUATION_CMD) { + vehicle_model_type_ == VehicleModelType::ACTUATION_CMD || + vehicle_model_type_ == VehicleModelType::ACTUATION_CMD_VGR || + vehicle_model_type_ == VehicleModelType::ACTUATION_CMD_MECHANICAL || + vehicle_model_type_ == VehicleModelType::ACTUATION_CMD_STEER_MAP) { state << x, y, yaw, vx, steer, accx; } vehicle_model_ptr_->setState(state); diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/utils/mechanical_controller.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/utils/mechanical_controller.cpp new file mode 100644 index 0000000000000..0977cd9e25a92 --- /dev/null +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/utils/mechanical_controller.cpp @@ -0,0 +1,352 @@ +// Copyright 2024 The Autoware Foundation. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "simple_planning_simulator/utils/mechanical_controller.hpp" + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace autoware::simple_planning_simulator::utils::mechanical_controller +{ + +using DelayBuffer = std::deque>; +using DelayOutput = std::pair, DelayBuffer>; + +DelayOutput delay( + const double signal, const double delay_time, const DelayBuffer & buffer, + const double elapsed_time) +{ + DelayBuffer new_buffer = buffer; + + new_buffer.push_back(std::make_pair(signal, elapsed_time)); + + if (!buffer.empty() && (elapsed_time - new_buffer.front().second) >= delay_time) { + const double delayed_signal = new_buffer.front().first; + new_buffer.pop_front(); + return {delayed_signal, new_buffer}; + } else { + return {std::nullopt, new_buffer}; + } +} + +double sign(const double x) +{ + return (x >= 0.0) ? 1.0 : -1.0; +} + +double apply_limits( + const double current_angle, const double previous_angle, const double angle_limit, + const double rate_limit, const double dt) +{ + const double angle_diff = std::clamp(current_angle, -angle_limit, angle_limit) - previous_angle; + const double rate_limited_diff = std::clamp(angle_diff, -rate_limit * dt, rate_limit * dt); + return std::clamp(previous_angle + rate_limited_diff, -angle_limit, angle_limit); +} + +double feedforward(const double input_angle, const double ff_gain) +{ + return ff_gain * input_angle; +} + +double polynomial_transform( + const double torque, const double speed, const double a, const double b, const double c, + const double d, const double e, const double f, const double g, const double h) +{ + return a * torque * torque * torque + b * torque * torque + c * torque + + d * speed * speed * speed + e * speed * speed + f * speed + g * torque * speed + h; +} + +PIDController::PIDController(const double kp, const double ki, const double kd) +: kp_(kp), ki_(ki), kd_(kd), state_{0.0, 0.0} +{ +} + +double PIDController::compute( + const double error, const double integral, const double prev_error, const double dt) const +{ + const double p_term = kp_ * error; + const double i_term = ki_ * integral; + const double d_term = dt < 1e-6 ? 0.0 : kd_ * (error - prev_error) / dt; + + return p_term + i_term + d_term; +} + +void PIDController::update_state(const double error, const double dt) +{ + state_.integral += error * dt; + state_.error = error; +}; + +void PIDController::update_state( + const double k1_error, const double k2_error, const double k3_error, const double k4_error, + const double dt) +{ + state_.error = (k1_error + 2 * k2_error + 2 * k3_error + k4_error) / 6.0; + state_.integral += state_.error * dt; +}; + +PIDControllerState PIDController::get_state() const +{ + return state_; +} + +void PIDController::clear_state() +{ + state_ = {0.0, 0.0}; +} + +SteeringDynamics::SteeringDynamics( + const double angular_position, const double angular_velocity, const double inertia, + const double damping, const double stiffness, const double friction, + const double dead_zone_threshold) +: state_{angular_position, angular_velocity, false}, + inertia_(inertia), + damping_(damping), + stiffness_(stiffness), + friction_(friction), + dead_zone_threshold_(dead_zone_threshold) +{ +} + +bool SteeringDynamics::is_in_dead_zone( + const SteeringDynamicsState & state, const double input_torque) const +{ + bool is_in_dead_zone = state.is_in_dead_zone; + const int rotation_direction = sign(state.angular_velocity); + const int input_direction = sign(input_torque); + + if (input_direction != rotation_direction && std::abs(input_torque) < dead_zone_threshold_) { + return true; + } + + if (is_in_dead_zone) { + return !(dead_zone_threshold_ <= std::abs(input_torque)); + } + + return false; +} + +SteeringDynamicsDeltaState SteeringDynamics::calc_model( + const SteeringDynamicsState & state, const double input_torque) const +{ + const double friction_force = friction_ * sign(state.angular_velocity); + const double angular_acceleration = (input_torque - damping_ * state.angular_velocity - + stiffness_ * state.angular_position - friction_force) / + inertia_; + + const double d_angular_velocity = angular_acceleration; + const double d_angular_position = state.angular_velocity; + + return {d_angular_position, d_angular_velocity}; +} + +void SteeringDynamics::set_state(const SteeringDynamicsState & state) +{ + state_ = state; +} + +SteeringDynamicsState SteeringDynamics::get_state() const +{ + return state_; +} + +void SteeringDynamics::set_steer(const double steer) +{ + state_.angular_position = steer; +} + +void SteeringDynamics::clear_state() +{ + state_ = {0.0, 0.0, false}; +} + +MechanicalController::MechanicalController(const MechanicalParams & params) +: pid_(params.kp, params.ki, params.kd), + steering_dynamics_( + 0.0, 0.0, params.inertia, params.damping, params.stiffness, params.friction, + params.dead_zone_threshold), + params_(params) +{ +} + +void MechanicalController::clear_state() +{ + delay_buffer_.clear(); + pid_.clear_state(); + steering_dynamics_.clear_state(); +} + +void MechanicalController::set_steer(const double steer) +{ + steering_dynamics_.set_steer(steer); +} + +[[maybe_unused]] double MechanicalController::update_euler( + const double input_angle, const double speed, const double prev_input_angle, const double dt) +{ + const auto dynamics_state = steering_dynamics_.get_state(); + + const auto d_state = + run_one_step(input_angle, speed, prev_input_angle, dt, delay_buffer_, pid_, steering_dynamics_); + + const double d_angular_position = d_state.dynamics_d_state.d_angular_position; + const double d_angular_velocity = d_state.dynamics_d_state.d_angular_velocity; + + auto dynamics_state_new = dynamics_state; + dynamics_state_new.angular_position = std::clamp( + dynamics_state.angular_position + d_angular_position * dt, -params_.angle_limit, + params_.angle_limit); + dynamics_state_new.angular_velocity = std::clamp( + dynamics_state.angular_velocity + d_angular_velocity * dt, -params_.rate_limit, + params_.rate_limit); + dynamics_state_new.is_in_dead_zone = d_state.is_in_dead_zone; + steering_dynamics_.set_state(dynamics_state_new); + + pid_.update_state(d_state.pid_error, dt); + delay_buffer_ = d_state.delay_buffer; + + return dynamics_state_new.angular_position; +} + +double MechanicalController::update_runge_kutta( + const double input_angle, const double speed, const double prev_input_angle, const double dt) +{ + const auto dynamics_state = steering_dynamics_.get_state(); + + // NOTE: k1, k2, k3, k4 suffix denote the intermediate points of RK4 + const auto k1 = + run_one_step(input_angle, speed, prev_input_angle, dt, delay_buffer_, pid_, steering_dynamics_); + + auto dynamics_for_k2 = steering_dynamics_; + auto dynamics_state_for_k2 = steering_dynamics_.get_state(); + dynamics_state_for_k2.angular_position = + dynamics_state.angular_position + k1.dynamics_d_state.d_angular_position * 0.5 * dt; + dynamics_state_for_k2.angular_velocity = + dynamics_state.angular_velocity + k1.dynamics_d_state.d_angular_velocity * 0.5 * dt; + dynamics_for_k2.set_state(dynamics_state_for_k2); + const auto k2 = + run_one_step(input_angle, speed, prev_input_angle, dt, delay_buffer_, pid_, dynamics_for_k2); + + auto dynamics_for_k3 = steering_dynamics_; + auto dynamics_state_for_k3 = steering_dynamics_.get_state(); + dynamics_state_for_k3.angular_position = + dynamics_state.angular_position + k2.dynamics_d_state.d_angular_position * 0.5 * dt; + dynamics_state_for_k3.angular_velocity = + dynamics_state.angular_velocity + k2.dynamics_d_state.d_angular_velocity * 0.5 * dt; + dynamics_for_k3.set_state(dynamics_state_for_k3); + const auto k3 = + run_one_step(input_angle, speed, prev_input_angle, dt, delay_buffer_, pid_, dynamics_for_k3); + + auto dynamics_for_k4 = steering_dynamics_; + auto dynamics_state_for_k4 = steering_dynamics_.get_state(); + dynamics_state_for_k4.angular_position = + dynamics_state.angular_position + k3.dynamics_d_state.d_angular_position * dt; + dynamics_state_for_k4.angular_velocity = + dynamics_state.angular_velocity + k3.dynamics_d_state.d_angular_velocity * dt; + dynamics_for_k4.set_state(dynamics_state_for_k4); + const auto k4 = + run_one_step(input_angle, speed, prev_input_angle, dt, delay_buffer_, pid_, dynamics_for_k4); + + const double d_angular_position = + (k1.dynamics_d_state.d_angular_position + 2.0 * k2.dynamics_d_state.d_angular_position + + 2.0 * k3.dynamics_d_state.d_angular_position + k4.dynamics_d_state.d_angular_position) / + 6.0; + const double d_angular_velocity = + (k1.dynamics_d_state.d_angular_velocity + 2.0 * k2.dynamics_d_state.d_angular_velocity + + 2.0 * k3.dynamics_d_state.d_angular_velocity + k4.dynamics_d_state.d_angular_velocity) / + 6.0; + + // update steering dynamics/controller internal state + auto dynamics_state_new = dynamics_state; + dynamics_state_new.angular_position = std::clamp( + dynamics_state.angular_position + d_angular_position * dt, -params_.angle_limit, + params_.angle_limit); + dynamics_state_new.angular_velocity = std::clamp( + dynamics_state.angular_velocity + d_angular_velocity * dt, -params_.rate_limit, + params_.rate_limit); + pid_.update_state(k1.pid_error, k2.pid_error, k3.pid_error, k4.pid_error, dt); + if ( + k1.delay_buffer.empty() || k2.delay_buffer.empty() || k3.delay_buffer.empty() || + k4.delay_buffer.empty()) { + // This condition is assumed to never be met because it is always pushed by + // the delay() function. + return dynamics_state.angular_position; + } + const double delayed_signal = + (k1.delay_buffer.back().first + 2.0 * k2.delay_buffer.back().first + + 2.0 * k3.delay_buffer.back().first + k4.delay_buffer.back().first) / + 6.0; + const double elapsed_time = delay_buffer_.empty() ? dt : delay_buffer_.back().second + dt; + delay_buffer_ = + delay(delayed_signal, params_.torque_delay_time, delay_buffer_, elapsed_time).second; + dynamics_state_new.is_in_dead_zone = + steering_dynamics_.is_in_dead_zone(dynamics_state_new, delayed_signal); + steering_dynamics_.set_state(dynamics_state_new); + + return dynamics_state_new.angular_position; +} + +StepResult MechanicalController::run_one_step( + const double input_angle, const double speed, const double prev_input_angle, const double dt, + const DelayBuffer & delay_buffer, const PIDController & pid, + const SteeringDynamics & dynamics) const +{ + const auto dynamics_state = dynamics.get_state(); + const auto pid_state = pid.get_state(); + + const double limited_input_angle = + apply_limits(input_angle, prev_input_angle, params_.angle_limit, params_.rate_limit, dt); + + const double ff_torque = feedforward(limited_input_angle, params_.ff_gain); + + const double pid_error = limited_input_angle - dynamics_state.angular_position; + + const double pid_torque = + pid.compute(pid_error, pid_state.integral + pid_error * dt, pid_state.error, dt); + + const double total_torque = ff_torque + pid_torque; + + // NOTE: do not distinguish between forward and backward driving + const double steering_torque = std::clamp( + polynomial_transform( + total_torque, std::abs(speed), params_.poly_a, params_.poly_b, params_.poly_c, params_.poly_d, + params_.poly_e, params_.poly_f, params_.poly_g, params_.poly_h), + -params_.steering_torque_limit, params_.steering_torque_limit); + + const double elapsed_time = delay_buffer.empty() ? dt : delay_buffer.back().second + dt; + const auto [delayed_torque_opt, delay_buffer_new] = + delay(steering_torque, params_.torque_delay_time, delay_buffer, elapsed_time); + + if (!delayed_torque_opt.has_value()) { + return {delay_buffer_new, pid_error, {0.0, 0.0}, dynamics_state.is_in_dead_zone}; + } + + const bool is_in_dead_zone = dynamics.is_in_dead_zone(dynamics_state, steering_torque); + if (is_in_dead_zone) { + return {delay_buffer_new, pid_error, {0.0, 0.0}, true}; + } + + const auto d_state = dynamics.calc_model(dynamics.get_state(), steering_torque); + + return {delay_buffer_new, pid_error, d_state, false}; +} + +} // namespace autoware::simple_planning_simulator::utils::mechanical_controller diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.cpp index 74ad765687a2e..469c30dc4f0cf 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/vehicle_model/sim_model_actuation_cmd.cpp @@ -108,43 +108,13 @@ double BrakeMap::getBrake(const double acc, double vel) const return autoware::interpolation::lerp(interpolated_acc_vec, brake_indices, acc); } -// steer map sim model +// convert only longitudinal actuation command SimModelActuationCmd::SimModelActuationCmd( double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, double dt, double accel_delay, double accel_time_constant, double brake_delay, double brake_time_constant, double steer_delay, double steer_time_constant, double steer_bias, - bool convert_accel_cmd, bool convert_brake_cmd, bool convert_steer_cmd, - std::string accel_map_path, std::string brake_map_path, std::string steer_map_path) -: SimModelInterface(6 /* dim x */, 5 /* dim u */), - MIN_TIME_CONSTANT(0.03), - vx_lim_(vx_lim), - vx_rate_lim_(vx_rate_lim), - steer_lim_(steer_lim), - steer_rate_lim_(steer_rate_lim), - wheelbase_(wheelbase), - accel_delay_(accel_delay), - accel_time_constant_(std::max(accel_time_constant, MIN_TIME_CONSTANT)), - brake_delay_(brake_delay), - brake_time_constant_(std::max(brake_time_constant, MIN_TIME_CONSTANT)), - steer_delay_(steer_delay), - steer_time_constant_(std::max(steer_time_constant, MIN_TIME_CONSTANT)), - steer_bias_(steer_bias) -{ - initializeInputQueue(dt); - convert_accel_cmd_ = convert_accel_cmd && accel_map_.readActuationMapFromCSV(accel_map_path); - convert_brake_cmd_ = convert_brake_cmd && brake_map_.readActuationMapFromCSV(brake_map_path); - convert_steer_cmd_ = convert_steer_cmd && steer_map_.readActuationMapFromCSV(steer_map_path); - actuation_sim_type_ = ActuationSimType::STEER_MAP; -} - -// VGR sim model -SimModelActuationCmd::SimModelActuationCmd( - double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, - double dt, double accel_delay, double accel_time_constant, double brake_delay, - double brake_time_constant, double steer_delay, double steer_time_constant, double steer_bias, - bool convert_accel_cmd, bool convert_brake_cmd, bool convert_steer_cmd, - std::string accel_map_path, std::string brake_map_path, double vgr_coef_a, double vgr_coef_b, - double vgr_coef_c) + bool convert_accel_cmd, bool convert_brake_cmd, std::string accel_map_path, + std::string brake_map_path) : SimModelInterface(6 /* dim x */, 5 /* dim u */), MIN_TIME_CONSTANT(0.03), vx_lim_(vx_lim), @@ -159,15 +129,12 @@ SimModelActuationCmd::SimModelActuationCmd( steer_delay_(steer_delay), steer_time_constant_(std::max(steer_time_constant, MIN_TIME_CONSTANT)), steer_bias_(steer_bias), - convert_steer_cmd_(convert_steer_cmd), - vgr_coef_a_(vgr_coef_a), - vgr_coef_b_(vgr_coef_b), - vgr_coef_c_(vgr_coef_c) + convert_accel_cmd_(convert_accel_cmd), + convert_brake_cmd_(convert_brake_cmd) { initializeInputQueue(dt); convert_accel_cmd_ = convert_accel_cmd && accel_map_.readActuationMapFromCSV(accel_map_path); convert_brake_cmd_ = convert_brake_cmd && brake_map_.readActuationMapFromCSV(brake_map_path); - actuation_sim_type_ = ActuationSimType::VGR; } double SimModelActuationCmd::getX() @@ -222,6 +189,7 @@ void SimModelActuationCmd::update(const double & dt) delayed_input(IDX_U::SLOPE_ACCX) = input_(IDX_U::SLOPE_ACCX); const auto prev_state = state_; + updateRungeKutta(dt, delayed_input); // take velocity/steer limit explicitly @@ -248,36 +216,32 @@ void SimModelActuationCmd::initializeInputQueue(const double & dt) std::fill(steer_input_queue_.begin(), steer_input_queue_.end(), 0.0); } -Eigen::VectorXd SimModelActuationCmd::calcModel( +Eigen::VectorXd SimModelActuationCmd::calcLongitudinalModel( const Eigen::VectorXd & state, const Eigen::VectorXd & input) { using autoware_vehicle_msgs::msg::GearCommand; const double vel = std::clamp(state(IDX::VX), -vx_lim_, vx_lim_); const double acc = std::clamp(state(IDX::ACCX), -vx_rate_lim_, vx_rate_lim_); - const double yaw = state(IDX::YAW); const double steer = state(IDX::STEER); - + const double yaw = state(IDX::YAW); const double accel = input(IDX_U::ACCEL_DES); const double brake = input(IDX_U::BRAKE_DES); const auto gear = input(IDX_U::GEAR); - // 1) calculate acceleration by accel and brake command + // calculate acceleration by accel and brake command const double acc_des_wo_slope = std::clamp( std::invoke([&]() -> double { - // Select the non-zero value between accel and brake and calculate the acceleration if (convert_accel_cmd_ && accel > 0.0) { - // convert accel command to acceleration return accel_map_.getControlCommand(accel, vel); } else if (convert_brake_cmd_ && brake > 0.0) { - // convert brake command to acceleration return brake_map_.getControlCommand(brake, vel); } else { - // if conversion is disabled, accel command is directly used as acceleration return accel; } }), -vx_rate_lim_, vx_rate_lim_); + // add slope acceleration considering the gear state const double acc_by_slope = input(IDX_U::SLOPE_ACCX); const double acc_des = std::invoke([&]() -> double { @@ -290,36 +254,31 @@ Eigen::VectorXd SimModelActuationCmd::calcModel( }); const double acc_time_constant = accel > 0.0 ? accel_time_constant_ : brake_time_constant_; - // 2) calculate steering rate by steer command - const double steer_rate = std::clamp( - std::invoke([&]() -> double { - // if conversion is enabled, calculate steering rate from steer command - if (convert_steer_cmd_) { - if (actuation_sim_type_ == ActuationSimType::VGR) { - // convert steer wheel command to steer rate - const double steer_des = - calculateSteeringTireCommand(vel, steer, input(IDX_U::STEER_DES)); - return -(getSteer() - steer_des) / steer_time_constant_; - } else if (actuation_sim_type_ == ActuationSimType::STEER_MAP) { - // convert steer command to steer rate - return steer_map_.getControlCommand(input(IDX_U::STEER_DES), vel) / steer_time_constant_; - } - } - // otherwise, steer command is desired steering angle, so calculate steering rate from the - // difference between the desired steering angle and the current steering angle. - const double steer_des = std::clamp(input(IDX_U::STEER_DES), -steer_lim_, steer_lim_); - return -(getSteer() - steer_des) / steer_time_constant_; - }), - -steer_rate_lim_, steer_rate_lim_); + // calculate derivative of longitudinal states except steering + Eigen::VectorXd d_longitudinal_state = Eigen::VectorXd::Zero(dim_x_); + d_longitudinal_state(IDX::X) = vel * cos(yaw); + d_longitudinal_state(IDX::Y) = vel * sin(yaw); + d_longitudinal_state(IDX::YAW) = vel * std::tan(steer) / wheelbase_; + d_longitudinal_state(IDX::VX) = acc; + d_longitudinal_state(IDX::ACCX) = -(acc - acc_des) / acc_time_constant; - Eigen::VectorXd d_state = Eigen::VectorXd::Zero(dim_x_); - d_state(IDX::X) = vel * cos(yaw); - d_state(IDX::Y) = vel * sin(yaw); - d_state(IDX::YAW) = vel * std::tan(steer) / wheelbase_; - d_state(IDX::VX) = acc; - d_state(IDX::STEER) = steer_rate; - d_state(IDX::ACCX) = -(acc - acc_des) / acc_time_constant; + return d_longitudinal_state; +} +double SimModelActuationCmd::calcLateralModel( + [[maybe_unused]] const double steer, const double steer_input, [[maybe_unused]] const double vel) +{ + const double steer_rate = std::clamp( + -(getSteer() - steer_input) / steer_time_constant_, -steer_rate_lim_, steer_rate_lim_); + return steer_rate; +} + +Eigen::VectorXd SimModelActuationCmd::calcModel( + const Eigen::VectorXd & state, const Eigen::VectorXd & input) +{ + Eigen::VectorXd d_state = calcLongitudinalModel(state, input); + d_state(IDX::STEER) = + calcLateralModel(state(IDX::STEER), input(IDX_U::STEER_DES), state(IDX::VX)); return d_state; } @@ -383,20 +342,57 @@ SimModelActuationCmd::getActuationStatus() const actuation_status.status.brake_status = brake_map_.getBrake(acc_state, vel_state); } - if (convert_steer_cmd_) { - if (actuation_sim_type_ == ActuationSimType::VGR) { - actuation_status.status.steer_status = - calculateSteeringWheelState(vel_state, state_(IDX::STEER)); - } - // NOTE: Conversion by steer map is not supported - // else if (actuation_sim_type_ == ActuationSimType::STEER_MAP) {} + return actuation_status; +} + +/* ------ SteerMap model ----- */ +SimModelActuationCmdSteerMap::SimModelActuationCmdSteerMap( + double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, + double dt, double accel_delay, double accel_time_constant, double brake_delay, + double brake_time_constant, double steer_delay, double steer_time_constant, double steer_bias, + bool convert_accel_cmd, bool convert_brake_cmd, std::string accel_map_path, + std::string brake_map_path, std::string steer_map_path) +: SimModelActuationCmd( + vx_lim, steer_lim, vx_rate_lim, steer_rate_lim, wheelbase, dt, accel_delay, accel_time_constant, + brake_delay, brake_time_constant, steer_delay, steer_time_constant, steer_bias, + convert_accel_cmd, convert_brake_cmd, accel_map_path, brake_map_path) +{ + initializeInputQueue(dt); + if (!steer_map_.readActuationMapFromCSV(steer_map_path)) { + throw std::runtime_error("Failed to read steer map from " + steer_map_path); } +} - return actuation_status; +double SimModelActuationCmdSteerMap::calcLateralModel( + [[maybe_unused]] const double steer, const double steer_input, const double vel) +{ + const double steer_rate = std::clamp( + steer_map_.getControlCommand(steer_input, vel) / steer_time_constant_, -steer_rate_lim_, + steer_rate_lim_); + + return steer_rate; } +/* ---------------------------------------- */ -/* ------ Functions for VGR sim model ----- */ -double SimModelActuationCmd::calculateSteeringTireCommand( +/* ------ VGR model ----- */ +SimModelActuationCmdVGR::SimModelActuationCmdVGR( + double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, + double dt, double accel_delay, double accel_time_constant, double brake_delay, + double brake_time_constant, double steer_delay, double steer_time_constant, double steer_bias, + bool convert_accel_cmd, bool convert_brake_cmd, std::string accel_map_path, + std::string brake_map_path, double vgr_coef_a, double vgr_coef_b, double vgr_coef_c) +: SimModelActuationCmd( + vx_lim, steer_lim, vx_rate_lim, steer_rate_lim, wheelbase, dt, accel_delay, accel_time_constant, + brake_delay, brake_time_constant, steer_delay, steer_time_constant, steer_bias, + convert_accel_cmd, convert_brake_cmd, accel_map_path, brake_map_path), + vgr_coef_a_(vgr_coef_a), + vgr_coef_b_(vgr_coef_b), + vgr_coef_c_(vgr_coef_c) +{ + initializeInputQueue(dt); +} + +double SimModelActuationCmdVGR::calculateSteeringTireCommand( const double vel, const double steer, const double steer_wheel_des) const { // steer_tire_state -> steer_wheel_state @@ -408,17 +404,114 @@ double SimModelActuationCmd::calculateSteeringTireCommand( return steer_wheel_des / adaptive_gear_ratio; } -double SimModelActuationCmd::calculateSteeringWheelState( +double SimModelActuationCmdVGR::calculateSteeringWheelState( const double vel, const double steer_state) const { return (vgr_coef_a_ + vgr_coef_b_ * vel * vel) * steer_state / (1.0 + vgr_coef_c_ * std::abs(steer_state)); } -double SimModelActuationCmd::calculateVariableGearRatio( +double SimModelActuationCmdVGR::calculateVariableGearRatio( const double vel, const double steer_wheel) const { return std::max( 1e-5, vgr_coef_a_ + vgr_coef_b_ * vel * vel - vgr_coef_c_ * std::fabs(steer_wheel)); } + +double SimModelActuationCmdVGR::calcLateralModel( + const double steer, const double steer_input, const double vel) +{ + const double steer_des = calculateSteeringTireCommand(vel, steer, steer_input); + const double steer_rate = + std::clamp(-(getSteer() - steer_des) / steer_time_constant_, -steer_rate_lim_, steer_rate_lim_); + return steer_rate; +} +/* ---------------------------------------- */ + +/* ------ MECHANICAL model ----- */ +SimModelActuationCmdMechanical::SimModelActuationCmdMechanical( + double vx_lim, double steer_lim, double vx_rate_lim, double steer_rate_lim, double wheelbase, + double dt, double accel_delay, double accel_time_constant, double brake_delay, + double brake_time_constant, double steer_delay, double steer_time_constant, double steer_bias, + bool convert_accel_cmd, bool convert_brake_cmd, std::string accel_map_path, + std::string brake_map_path, double vgr_coef_a, double vgr_coef_b, double vgr_coef_c, + MechanicalParams mechanical_params) +: SimModelActuationCmdVGR( + vx_lim, steer_lim, vx_rate_lim, steer_rate_lim, wheelbase, dt, accel_delay, accel_time_constant, + brake_delay, brake_time_constant, steer_delay, steer_time_constant, steer_bias, + convert_accel_cmd, convert_brake_cmd, accel_map_path, brake_map_path, vgr_coef_a, vgr_coef_b, + vgr_coef_c), + mechanical_controller_(std::make_unique(mechanical_params)) +{ +} + +void SimModelActuationCmdMechanical::update(const double & dt) +{ + Eigen::VectorXd delayed_input = Eigen::VectorXd::Zero(dim_u_); + + accel_input_queue_.push_back(input_(IDX_U::ACCEL_DES)); + delayed_input(IDX_U::ACCEL_DES) = accel_input_queue_.front(); + accel_input_queue_.pop_front(); + + brake_input_queue_.push_back(input_(IDX_U::BRAKE_DES)); + delayed_input(IDX_U::BRAKE_DES) = brake_input_queue_.front(); + brake_input_queue_.pop_front(); + + steer_input_queue_.push_back(input_(IDX_U::STEER_DES)); + delayed_input(IDX_U::STEER_DES) = steer_input_queue_.front(); + steer_input_queue_.pop_front(); + + delayed_input(IDX_U::GEAR) = input_(IDX_U::GEAR); + delayed_input(IDX_U::SLOPE_ACCX) = input_(IDX_U::SLOPE_ACCX); + + const auto prev_state = state_; + + updateRungeKuttaWithController(dt, delayed_input); + + // take velocity/steer limit explicitly + state_(IDX::VX) = std::clamp(state_(IDX::VX), -vx_lim_, vx_lim_); + state_(IDX::STEER) = std::clamp(state_(IDX::STEER), -steer_lim_, steer_lim_); + + // consider gear + // update position and velocity first, and then acceleration is calculated naturally + updateStateWithGear(state_, prev_state, gear_, dt); +} + +void SimModelActuationCmdMechanical::updateRungeKuttaWithController( + const double dt, const Eigen::VectorXd & input) +{ + // 1) update longitudinal states + const Eigen::VectorXd k1_longitudinal = calcLongitudinalModel(state_, input); + const Eigen::VectorXd k2_longitudinal = + calcLongitudinalModel(state_ + k1_longitudinal * 0.5 * dt, input); + const Eigen::VectorXd k3_longitudinal = + calcLongitudinalModel(state_ + k2_longitudinal * 0.5 * dt, input); + const Eigen::VectorXd k4_longitudinal = + calcLongitudinalModel(state_ + k3_longitudinal * dt, input); + state_ += + dt / 6.0 * (k1_longitudinal + 2.0 * k2_longitudinal + 2.0 * k3_longitudinal + k4_longitudinal); + + // 2) update lateral states + const double steer = state_(IDX::STEER); + const double steer_des = input(IDX_U::STEER_DES); + const double vel = state_(IDX::VX); + + const double steer_tire_des = calculateSteeringTireCommand(vel, steer, steer_des); + + mechanical_controller_->set_steer(state_(IDX::STEER)); + const double new_steer = + mechanical_controller_->update_runge_kutta(steer_tire_des, vel, prev_steer_tire_des_, dt); + state_(IDX::STEER) = new_steer; + prev_steer_tire_des_ = steer_tire_des; +} + +void SimModelActuationCmdMechanical::setState(const Eigen::VectorXd & state) +{ + // NOTE: This function is intended to overwrite the state by setting the initial pose, etc. In + // that case, it is necessary to reset the pid and steering dynamics states of the mechanical + // controller. + mechanical_controller_->clear_state(); + mechanical_controller_->set_steer(state(IDX::STEER)); + state_ = state; +} /* ---------------------------------------- */ diff --git a/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp b/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp index d774617dc77f1..6f2590417e574 100644 --- a/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp +++ b/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp @@ -271,19 +271,11 @@ void declareVehicleInfoParams(rclcpp::NodeOptions & node_options) node_options.append_parameter_override("max_steer_angle", 0.7); } +// NOTE: +// command type and vehicle model type area common params to all vehicle models. +// currently, no vehicle model requires additional parameters. using DefaultParamType = std::tuple; -using ActuationCmdParamType = std::tuple; -using ParamType = std::variant; -std::unordered_map vehicle_model_type_map = { - {"IDEAL_STEER_VEL", typeid(DefaultParamType)}, - {"IDEAL_STEER_ACC", typeid(DefaultParamType)}, - {"IDEAL_STEER_ACC_GEARED", typeid(DefaultParamType)}, - {"DELAY_STEER_VEL", typeid(DefaultParamType)}, - {"DELAY_STEER_ACC", typeid(DefaultParamType)}, - {"DELAY_STEER_ACC_GEARED", typeid(DefaultParamType)}, - {"DELAY_STEER_ACC_GEARED_WO_FALL_GUARD", typeid(DefaultParamType)}, - {"ACTUATION_CMD", typeid(ActuationCmdParamType)}}; - +using ParamType = std::variant; std::pair get_common_params(const ParamType & params) { return std::visit( @@ -304,21 +296,10 @@ TEST_P(TestSimplePlanningSimulator, TestIdealSteerVel) rclcpp::init(0, nullptr); const auto params = GetParam(); - // common parameters const auto common_params = get_common_params(params); const auto command_type = common_params.first; const auto vehicle_model_type = common_params.second; - // optional parameters - std::optional conversion_type{}; // for ActuationCmdParamType - - // Determine the ParamType corresponding to vehicle_model_type and get the specific parameters. - const auto iter = vehicle_model_type_map.find(vehicle_model_type); - if (iter == vehicle_model_type_map.end()) { - throw std::invalid_argument("Unexpected vehicle_model_type."); - } - if (iter->second == typeid(ActuationCmdParamType)) { - conversion_type = std::get<2>(std::get(params)); - } + std::cout << "\n\n vehicle model = " << vehicle_model_type << std::endl << std::endl; rclcpp::NodeOptions node_options; node_options.append_parameter_override("initialize_source", "INITIAL_POSE_TOPIC"); @@ -331,7 +312,6 @@ TEST_P(TestSimplePlanningSimulator, TestIdealSteerVel) node_options.append_parameter_override("brake_time_constant", 0.2); node_options.append_parameter_override("convert_accel_cmd", true); node_options.append_parameter_override("convert_brake_cmd", true); - node_options.append_parameter_override("convert_steer_cmd", true); const auto share_dir = ament_index_cpp::get_package_share_directory("simple_planning_simulator"); const auto accel_map_path = share_dir + "/test/actuation_cmd_map/accel_map.csv"; const auto brake_map_path = share_dir + "/test/actuation_cmd_map/brake_map.csv"; @@ -342,17 +322,31 @@ TEST_P(TestSimplePlanningSimulator, TestIdealSteerVel) node_options.append_parameter_override("vgr_coef_a", 15.713); node_options.append_parameter_override("vgr_coef_b", 0.053); node_options.append_parameter_override("vgr_coef_c", 0.042); - if (conversion_type.has_value()) { - std::cout << "\n\n vehicle model = " << vehicle_model_type - << ", conversion_type = " << conversion_type.value() << std::endl - << std::endl; - node_options.append_parameter_override("convert_steer_cmd_method", conversion_type.value()); - } else { - std::cout << "\n\n vehicle model = " << vehicle_model_type << std::endl << std::endl; - } + // mechanical parameters + node_options.append_parameter_override("mechanical_params.kp", 386.915); + node_options.append_parameter_override("mechanical_params.ki", 5.461); + node_options.append_parameter_override("mechanical_params.kd", 0.036); + node_options.append_parameter_override("mechanical_params.ff_gain", 0.031); + node_options.append_parameter_override("mechanical_params.angle_limit", 10.0); + node_options.append_parameter_override("mechanical_params.rate_limit", 3.0); + node_options.append_parameter_override("mechanical_params.dead_zone_threshold", 0.007); + node_options.append_parameter_override("mechanical_params.poly_a", 0.153); + node_options.append_parameter_override("mechanical_params.poly_b", -0.173); + node_options.append_parameter_override("mechanical_params.poly_c", 1.590); + node_options.append_parameter_override("mechanical_params.poly_d", 0.002); + node_options.append_parameter_override("mechanical_params.poly_e", -0.042); + node_options.append_parameter_override("mechanical_params.poly_f", 0.184); + node_options.append_parameter_override("mechanical_params.poly_g", -0.063); + node_options.append_parameter_override("mechanical_params.poly_h", 0.187); + node_options.append_parameter_override("mechanical_params.inertia", 25.178); + node_options.append_parameter_override("mechanical_params.damping", 117.007); + node_options.append_parameter_override("mechanical_params.stiffness", 0.175); + node_options.append_parameter_override("mechanical_params.friction", 0.660); + node_options.append_parameter_override("mechanical_params.steering_torque_limit", 30.0); + node_options.append_parameter_override("mechanical_params.torque_delay_time", 0.001); declareVehicleInfoParams(node_options); - const auto sim_node = std::make_shared(node_options); + auto sim_node = std::make_shared(node_options); const auto pub_sub_node = std::make_shared(); @@ -364,7 +358,7 @@ TEST_P(TestSimplePlanningSimulator, TestIdealSteerVel) // acceleration or braking, and whether it turns left or right, and generate an actuation // command. So do not change the map. If it is necessary, you need to change this parameters as // well. - const double target_steer_actuation = 10.0f; + const double target_steer_actuation = 20.0f; const double target_accel_actuation = 0.5f; // const double target_brake_actuation = 0.5f; // unused for now. @@ -375,10 +369,15 @@ TEST_P(TestSimplePlanningSimulator, TestIdealSteerVel) const auto t = sim_node->now(); sendCommand(command_type, sim_node, pub_sub_node, t, ackermann_cmd, actuation_cmd); }; + // NOTE: Since the node has a queue, the node needs to be re-created. + auto _restartNode = [&]() { + sim_node.reset(); + sim_node = std::make_shared(node_options); + }; // check pub-sub connections { - size_t expected = 1; + constexpr size_t expected = 1; // actuation or ackermann must be subscribed const auto sub_command_count = (command_type == CommandType::Actuation) @@ -404,6 +403,7 @@ TEST_P(TestSimplePlanningSimulator, TestIdealSteerVel) // go backward // NOTE: positive acceleration with reverse gear drives the vehicle backward. + _restartNode(); _resetInitialpose(); _sendBwdGear(); _sendCommand( @@ -412,6 +412,7 @@ TEST_P(TestSimplePlanningSimulator, TestIdealSteerVel) isOnBackward(*(pub_sub_node->current_odom_), init_state); // go forward left + _restartNode(); _resetInitialpose(); _sendFwdGear(); _sendCommand( @@ -421,6 +422,7 @@ TEST_P(TestSimplePlanningSimulator, TestIdealSteerVel) // go backward right // NOTE: positive acceleration with reverse gear drives the vehicle backward. + _restartNode(); _resetInitialpose(); _sendBwdGear(); _sendCommand( @@ -443,5 +445,9 @@ INSTANTIATE_TEST_SUITE_P( std::make_tuple(CommandType::Ackermann, "DELAY_STEER_ACC_GEARED"), std::make_tuple(CommandType::Ackermann, "DELAY_STEER_ACC_GEARED_WO_FALL_GUARD"), /* Actuation type */ - std::make_tuple(CommandType::Actuation, "ACTUATION_CMD", "steer_map"), - std::make_tuple(CommandType::Actuation, "ACTUATION_CMD", "vgr"))); + // NOTE: Just "ACTUATION_CMD" sim model converts only accel/brake actuation commands. The test + // is performed for models that convert all accel/brake/steer commands, so the test for + // accel/brake alone is skipped. + std::make_tuple(CommandType::Actuation, "ACTUATION_CMD_STEER_MAP"), + std::make_tuple(CommandType::Actuation, "ACTUATION_CMD_VGR"), + std::make_tuple(CommandType::Actuation, "ACTUATION_CMD_MECHANICAL")));